From daf54ad54d6356d35061ea2864d6397dc6184f3f Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Sat, 30 Sep 2017 03:07:27 -0700 Subject: [PATCH] openpilot v0.3.7 release --- .travis.yml | 4 +- Dockerfile.openpilot | 12 +- README.md | 10 +- RELEASES.md | 18 +- cereal/Makefile | 47 +- cereal/build_from_src.mk | 45 - cereal/car.capnp | 187 +- cereal/log.capnp | 187 +- common/basedir.py | 4 + common/crash.py | 2 +- common/fingerprints.py | 3 + common/params.py | 51 +- common/profiler.py | 6 + opendbc | 2 +- panda | 2 +- phonelibs/qpoases/EXAMPLES/example1.cpp | 74 + phonelibs/qpoases/EXAMPLES/example1b.cpp | 69 + phonelibs/qpoases/INCLUDE/Bounds.hpp | 189 + phonelibs/qpoases/INCLUDE/Constants.hpp | 108 + phonelibs/qpoases/INCLUDE/Constraints.hpp | 181 + phonelibs/qpoases/INCLUDE/CyclingManager.hpp | 126 + .../INCLUDE/EXTRAS/SolutionAnalysis.hpp | 107 + phonelibs/qpoases/INCLUDE/Indexlist.hpp | 154 + phonelibs/qpoases/INCLUDE/MessageHandling.hpp | 415 ++ phonelibs/qpoases/INCLUDE/QProblem.hpp | 666 +++ phonelibs/qpoases/INCLUDE/QProblemB.hpp | 628 +++ phonelibs/qpoases/INCLUDE/SubjectTo.hpp | 178 + phonelibs/qpoases/INCLUDE/Types.hpp | 131 + phonelibs/qpoases/INCLUDE/Utils.hpp | 197 + phonelibs/qpoases/LICENSE.txt | 504 +++ phonelibs/qpoases/README.txt | 92 + phonelibs/qpoases/SRC/Bounds.cpp | 252 ++ phonelibs/qpoases/SRC/Bounds.ipp | 144 + phonelibs/qpoases/SRC/Constraints.cpp | 248 ++ phonelibs/qpoases/SRC/Constraints.ipp | 144 + phonelibs/qpoases/SRC/CyclingManager.cpp | 188 + phonelibs/qpoases/SRC/CyclingManager.ipp | 51 + .../qpoases/SRC/EXTRAS/SolutionAnalysis.cpp | 434 ++ phonelibs/qpoases/SRC/Indexlist.cpp | 342 ++ phonelibs/qpoases/SRC/Indexlist.ipp | 85 + phonelibs/qpoases/SRC/MessageHandling.cpp | 529 +++ phonelibs/qpoases/SRC/MessageHandling.ipp | 137 + phonelibs/qpoases/SRC/QProblem.cpp | 3867 +++++++++++++++++ phonelibs/qpoases/SRC/QProblem.ipp | 299 ++ phonelibs/qpoases/SRC/QProblemB.cpp | 2151 +++++++++ phonelibs/qpoases/SRC/QProblemB.ipp | 425 ++ phonelibs/qpoases/SRC/SubjectTo.cpp | 200 + phonelibs/qpoases/SRC/SubjectTo.ipp | 132 + phonelibs/qpoases/SRC/Utils.cpp | 471 ++ phonelibs/qpoases/SRC/Utils.ipp | 51 + phonelibs/qpoases/VERSIONS.txt | 87 + pyextra | 2 +- run_docker_tests.sh | 5 +- selfdrive/boardd/Makefile | 9 +- selfdrive/boardd/boardd.cc | 132 +- selfdrive/boardd/boardd.py | 5 +- selfdrive/can/Makefile | 5 +- selfdrive/can/{parser_common.h => common.h} | 13 +- selfdrive/can/dbc.cc | 26 + selfdrive/can/dbc_template.cc | 2 +- selfdrive/can/libdbc_py.py | 51 + selfdrive/can/packer.cc | 81 + selfdrive/can/packer.py | 37 + selfdrive/can/parser.cc | 32 +- selfdrive/can/parser.py | 40 +- selfdrive/car/__init__.py | 6 + selfdrive/car/honda/carcontroller.py | 86 +- selfdrive/car/honda/carstate.py | 143 +- selfdrive/car/honda/interface.py | 233 +- .../{can_parser.py => old_can_parser.py} | 8 +- selfdrive/common/cereal.mk | 20 +- selfdrive/common/mat.h | 20 + selfdrive/common/{params.c => params.cc} | 25 +- selfdrive/common/params.h | 4 +- selfdrive/common/swaglog.h | 36 + selfdrive/common/timing.h | 15 +- selfdrive/common/util.c | 11 + selfdrive/common/util.h | 14 + selfdrive/common/utilpp.h | 4 + selfdrive/common/version.h | 2 +- selfdrive/common/visionipc.c | 9 +- selfdrive/common/visionipc.h | 16 +- selfdrive/controls/controlsd.py | 826 ++-- selfdrive/controls/lib/adaptivecruise.py | 12 +- selfdrive/controls/lib/alertmanager.py | 394 +- selfdrive/controls/lib/drive_helpers.py | 30 + selfdrive/controls/lib/latcontrol.py | 187 +- selfdrive/controls/lib/latcontrol_helpers.py | 89 + selfdrive/controls/lib/lateral_mpc/Makefile | 75 + .../controls/lib/lateral_mpc/__init__.py | 0 .../controls/lib/lateral_mpc/generator.cpp | 137 + .../controls/lib/lateral_mpc/libmpc_py.py | 30 + selfdrive/controls/lib/lateral_mpc/mpc.c | 100 + .../mpc_export/acado_auxiliary_functions.c | 212 + .../mpc_export/acado_auxiliary_functions.h | 138 + .../lib/lateral_mpc/mpc_export/acado_common.h | 349 ++ .../lateral_mpc/mpc_export/acado_integrator.c | 252 ++ .../mpc_export/acado_qpoases_interface.cpp | 70 + .../mpc_export/acado_qpoases_interface.hpp | 65 + .../lib/lateral_mpc/mpc_export/acado_solver.c | 1981 +++++++++ selfdrive/controls/lib/longcontrol.py | 226 +- selfdrive/controls/lib/pathplanner.py | 102 +- selfdrive/controls/lib/pid.py | 91 + selfdrive/controls/lib/planner.py | 71 +- selfdrive/controls/lib/vehicle_model.py | 49 +- selfdrive/controls/radard.py | 9 +- selfdrive/debug/can_printer.py | 21 +- selfdrive/debug/dump.py | 2 +- selfdrive/debug/getframes/getframes.py | 12 +- selfdrive/debug/test_carcontroller.py | 5 +- selfdrive/debug/test_carstate.py | 4 +- selfdrive/logcatd/Makefile | 1 + selfdrive/loggerd/config.py | 7 +- selfdrive/loggerd/loggerd | Bin 1367088 -> 1364512 bytes selfdrive/manager.py | 170 +- selfdrive/proclogd/Makefile | 1 + selfdrive/radar/nidec/interface.py | 76 +- selfdrive/sensord/sensord | Bin 935360 -> 939496 bytes selfdrive/service_list.yaml | 3 + selfdrive/test/plant/maneuver.py | 2 + selfdrive/test/plant/plant.py | 33 +- selfdrive/test/plant/plant_ui.py | 122 + selfdrive/test/plant/runtest.sh | 14 - selfdrive/test/plant/runtracks.py | 207 - selfdrive/test/test_openpilot.py | 38 +- selfdrive/test/tests/plant/__init__.py | 0 .../test/tests/plant/test_longitudinal.py | 255 ++ selfdrive/ui/Makefile | 3 +- selfdrive/ui/ui.c | 119 +- selfdrive/visiond/visiond | Bin 16407976 -> 13285152 bytes 130 files changed, 20576 insertions(+), 1742 deletions(-) delete mode 100644 cereal/build_from_src.mk create mode 100644 common/basedir.py create mode 100644 phonelibs/qpoases/EXAMPLES/example1.cpp create mode 100644 phonelibs/qpoases/EXAMPLES/example1b.cpp create mode 100644 phonelibs/qpoases/INCLUDE/Bounds.hpp create mode 100644 phonelibs/qpoases/INCLUDE/Constants.hpp create mode 100644 phonelibs/qpoases/INCLUDE/Constraints.hpp create mode 100644 phonelibs/qpoases/INCLUDE/CyclingManager.hpp create mode 100644 phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp create mode 100644 phonelibs/qpoases/INCLUDE/Indexlist.hpp create mode 100644 phonelibs/qpoases/INCLUDE/MessageHandling.hpp create mode 100644 phonelibs/qpoases/INCLUDE/QProblem.hpp create mode 100644 phonelibs/qpoases/INCLUDE/QProblemB.hpp create mode 100644 phonelibs/qpoases/INCLUDE/SubjectTo.hpp create mode 100644 phonelibs/qpoases/INCLUDE/Types.hpp create mode 100644 phonelibs/qpoases/INCLUDE/Utils.hpp create mode 100644 phonelibs/qpoases/LICENSE.txt create mode 100644 phonelibs/qpoases/README.txt create mode 100644 phonelibs/qpoases/SRC/Bounds.cpp create mode 100644 phonelibs/qpoases/SRC/Bounds.ipp create mode 100644 phonelibs/qpoases/SRC/Constraints.cpp create mode 100644 phonelibs/qpoases/SRC/Constraints.ipp create mode 100644 phonelibs/qpoases/SRC/CyclingManager.cpp create mode 100644 phonelibs/qpoases/SRC/CyclingManager.ipp create mode 100644 phonelibs/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp create mode 100644 phonelibs/qpoases/SRC/Indexlist.cpp create mode 100644 phonelibs/qpoases/SRC/Indexlist.ipp create mode 100644 phonelibs/qpoases/SRC/MessageHandling.cpp create mode 100644 phonelibs/qpoases/SRC/MessageHandling.ipp create mode 100644 phonelibs/qpoases/SRC/QProblem.cpp create mode 100644 phonelibs/qpoases/SRC/QProblem.ipp create mode 100644 phonelibs/qpoases/SRC/QProblemB.cpp create mode 100644 phonelibs/qpoases/SRC/QProblemB.ipp create mode 100644 phonelibs/qpoases/SRC/SubjectTo.cpp create mode 100644 phonelibs/qpoases/SRC/SubjectTo.ipp create mode 100644 phonelibs/qpoases/SRC/Utils.cpp create mode 100644 phonelibs/qpoases/SRC/Utils.ipp create mode 100644 phonelibs/qpoases/VERSIONS.txt rename selfdrive/can/{parser_common.h => common.h} (81%) create mode 100644 selfdrive/can/dbc.cc create mode 100644 selfdrive/can/libdbc_py.py create mode 100644 selfdrive/can/packer.cc create mode 100644 selfdrive/can/packer.py rename selfdrive/car/honda/{can_parser.py => old_can_parser.py} (97%) rename selfdrive/common/{params.c => params.cc} (83%) create mode 100644 selfdrive/controls/lib/latcontrol_helpers.py create mode 100644 selfdrive/controls/lib/lateral_mpc/Makefile create mode 100644 selfdrive/controls/lib/lateral_mpc/__init__.py create mode 100644 selfdrive/controls/lib/lateral_mpc/generator.cpp create mode 100644 selfdrive/controls/lib/lateral_mpc/libmpc_py.py create mode 100644 selfdrive/controls/lib/lateral_mpc/mpc.c create mode 100644 selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.c create mode 100644 selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.h create mode 100644 selfdrive/controls/lib/lateral_mpc/mpc_export/acado_common.h create mode 100644 selfdrive/controls/lib/lateral_mpc/mpc_export/acado_integrator.c create mode 100644 selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.cpp create mode 100644 selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.hpp create mode 100644 selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c create mode 100644 selfdrive/controls/lib/pid.py create mode 100755 selfdrive/test/plant/plant_ui.py delete mode 100755 selfdrive/test/plant/runtest.sh delete mode 100755 selfdrive/test/plant/runtracks.py create mode 100644 selfdrive/test/tests/plant/__init__.py create mode 100755 selfdrive/test/tests/plant/test_longitudinal.py diff --git a/.travis.yml b/.travis.yml index 9c668d75d91b78..74411b5de82281 100644 --- a/.travis.yml +++ b/.travis.yml @@ -8,5 +8,5 @@ install: script: - docker run --rm - -v "$(pwd)"/selfdrive/test/plant/out:/tmp/openpilot/selfdrive/test/plant/out - tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/plant && ./runtest.sh' + -v "$(pwd)"/selfdrive/test/tests/plant/out:/tmp/openpilot/selfdrive/test/tests/plant/out + tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/tests/plant && OPTEST=1 ./test_longitudinal.py' diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 3b3638f9cae5c6..4efafd40df1d53 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -1,8 +1,7 @@ FROM ubuntu:16.04 ENV PYTHONUNBUFFERED 1 -RUN apt-get update && apt-get install -y build-essential clang vim screen wget bzip2 git libglib2.0-0 python-pip capnproto libcapnp-dev libzmq5-dev libffi-dev - +RUN apt-get update && apt-get install -y build-essential clang vim screen wget bzip2 git libglib2.0-0 python-pip capnproto libcapnp-dev libzmq5-dev libffi-dev libusb-1.0-0 RUN pip install numpy==1.11.2 scipy==0.18.1 matplotlib COPY requirements_openpilot.txt /tmp/ @@ -10,4 +9,11 @@ RUN pip install -r /tmp/requirements_openpilot.txt ENV PYTHONPATH /tmp/openpilot:$PYTHONPATH -COPY . /tmp/openpilot +COPY ./common /tmp/openpilot/common +COPY ./cereal /tmp/openpilot/cereal +COPY ./opendbc /tmp/openpilot/opendbc +COPY ./selfdrive /tmp/openpilot/selfdrive +COPY ./phonelibs /tmp/openpilot/phonelibs +COPY ./pyextra /tmp/openpilot/pyextra + +RUN mkdir /tmp/openpilot/selfdrive/test/out \ No newline at end of file diff --git a/README.md b/README.md index 32513579c43765..c70574e84a735f 100644 --- a/README.md +++ b/README.md @@ -22,12 +22,20 @@ Supported Cars - Acura ILX 2016 with AcuraWatch Plus - Due to use of the cruise control for gas, it can only be enabled above 25 mph -- Honda Civic 2016 with Honda Sensing +- Honda Civic 2016-2017 with Honda Sensing - Due to limitations in steering firmware, steering is disabled below 12 mph + - Note that the hatchback model is not supported - Honda CR-V Touring 2015-2016 (very alpha!) - Can only be enabled above 25 mph +In Progress Cars +------ + +- Chevy Volt 2016-2018 Premier with Driver Confidence II + +- All 2017 Toyota Prius, Corolla, and RAV4 + Directory structure ------ diff --git a/RELEASES.md b/RELEASES.md index bb2a2b85a4bd29..bf4baad56c0113 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,6 +1,18 @@ -Version 0.3.6.1 (2017-08-15) -============================ - * Mitigate low speed steering oscillations on some vehicles +Version 0.3.7 (2017-09-30) +========================== + * Improved lateral control using model predictive control + * Improved lane centering + * Improved GPS + * Reduced tendency of path deviation near right side exits + * Enable engagement while the accelerator pedal is pressed + * Enable engagement while the brake pedal is pressed, when stationary and with lead vehicle within 5m + * Disable engagement when park brake or brake hold are active + * Fixed sporadic longitudinal pulsing in Civic + * Cleanups to vehicle interface + +Version 0.3.6.1 (2017-08-15) +============================ + * Mitigate low speed steering oscillations on some vehicles * Include board steering check for CR-V Version 0.3.6 (2017-08-08) diff --git a/cereal/Makefile b/cereal/Makefile index ead08bf5be4108..3a580592b12951 100644 --- a/cereal/Makefile +++ b/cereal/Makefile @@ -1,4 +1,45 @@ --include build_from_src.mk +SRCS := log.capnp car.capnp + +GENS := gen/cpp/car.capnp.c++ gen/cpp/log.capnp.c++ + + +UNAME_M ?= $(shell uname -m) + +# only generate C++ for docker tests +ifneq ($(OPTEST),1) + GENS += gen/c/car.capnp.c gen/c/log.capnp.c gen/c/c++.capnp.h gen/c/java.capnp.h + +# Dont build java on the phone... +ifeq ($(UNAME_M),x86_64) + GENS += gen/java/Car.java gen/java/Log.java +endif + +endif + +.PHONY: all +all: $(GENS) + +.PHONY: clean +clean: + rm -rf gen + +gen/c/%.capnp.c: %.capnp + @echo "[ CAPNPC C ] $@" + mkdir -p gen/c/ + capnpc '$<' -o c:gen/c/ + +gen/cpp/%.capnp.c++: %.capnp + @echo "[ CAPNPC C++ ] $@" + mkdir -p gen/cpp/ + capnpc '$<' -o c++:gen/cpp/ + +gen/java/Car.java gen/java/Log.java: $(SRCS) + @echo "[ CAPNPC java ] $@" + mkdir -p gen/java/ + capnpc $^ -o java:gen/java + +# c-capnproto needs some empty headers +gen/c/c++.capnp.h gen/c/java.capnp.h: + mkdir -p gen/c/ + touch '$@' -release: - @echo "cereal: this is a release" diff --git a/cereal/build_from_src.mk b/cereal/build_from_src.mk deleted file mode 100644 index 3a580592b12951..00000000000000 --- a/cereal/build_from_src.mk +++ /dev/null @@ -1,45 +0,0 @@ -SRCS := log.capnp car.capnp - -GENS := gen/cpp/car.capnp.c++ gen/cpp/log.capnp.c++ - - -UNAME_M ?= $(shell uname -m) - -# only generate C++ for docker tests -ifneq ($(OPTEST),1) - GENS += gen/c/car.capnp.c gen/c/log.capnp.c gen/c/c++.capnp.h gen/c/java.capnp.h - -# Dont build java on the phone... -ifeq ($(UNAME_M),x86_64) - GENS += gen/java/Car.java gen/java/Log.java -endif - -endif - -.PHONY: all -all: $(GENS) - -.PHONY: clean -clean: - rm -rf gen - -gen/c/%.capnp.c: %.capnp - @echo "[ CAPNPC C ] $@" - mkdir -p gen/c/ - capnpc '$<' -o c:gen/c/ - -gen/cpp/%.capnp.c++: %.capnp - @echo "[ CAPNPC C++ ] $@" - mkdir -p gen/cpp/ - capnpc '$<' -o c++:gen/cpp/ - -gen/java/Car.java gen/java/Log.java: $(SRCS) - @echo "[ CAPNPC java ] $@" - mkdir -p gen/java/ - capnpc $^ -o java:gen/java - -# c-capnproto needs some empty headers -gen/c/c++.capnp.h gen/c/java.capnp.h: - mkdir -p gen/c/ - touch '$@' - diff --git a/cereal/car.capnp b/cereal/car.capnp index c52a5d12af3e13..6b5a019c7b5b35 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -7,11 +7,59 @@ $Java.outerClassname("Car"); @0x8e2af1e708af8b8d; +# ******* events causing controls state machine transition ******* + +struct CarEvent @0x9b1657f34caf3ad3 { + name @0 :EventName; + enable @1 :Bool; + preEnable @7 :Bool; + noEntry @2 :Bool; + warning @3 :Bool; + userDisable @4 :Bool; + softDisable @5 :Bool; + immediateDisable @6 :Bool; + + enum EventName @0xbaa8c5d505f727de { + # TODO: copy from error list + commIssue @0; + steerUnavailable @1; + brakeUnavailable @2; + gasUnavailable @3; + wrongGear @4; + doorOpen @5; + seatbeltNotLatched @6; + espDisabled @7; + wrongCarMode @8; + steerTempUnavailable @9; + reverseGear @10; + buttonCancel @11; + buttonEnable @12; + pedalPressed @13; + cruiseDisabled @14; + radarCommIssue @15; + dataNeeded @16; + speedTooLow @17; + outOfSpace @18; + overheat @19; + calibrationInProgress @20; + calibrationInvalid @21; + controlsMismatch @22; + pcmEnable @23; + pcmDisable @24; + noTarget @25; + radarFault @26; + modelCommIssue @27; + brakeHold @28; + parkBrake @29; + } +} + # ******* main car state @ 100hz ******* # all speeds in m/s struct CarState { - errors @0: List(Error); + errorsDEPRECATED @0 :List(CarEvent.EventName); + events @13 :List(CarEvent); # car speed vEgo @1 :Float32; # best estimate of speed @@ -33,6 +81,9 @@ struct CarState { # cruise state cruiseState @10 :CruiseState; + # gear + gearShifter @14 :GearShifter; + # button presses buttonEvents @11 :List(ButtonEvent); @@ -48,31 +99,28 @@ struct CarState { } struct CruiseState { - enabled @0: Bool; - speed @1: Float32; - available @2: Bool; + enabled @0 :Bool; + speed @1 :Float32; + available @2 :Bool; + speedOffset @3 :Float32; } - enum Error { - # TODO: copy from error list - commIssue @0; - steerUnavailable @1; - brakeUnavailable @2; - gasUnavailable @3; - wrongGear @4; - doorOpen @5; - seatbeltNotLatched @6; - espDisabled @7; - wrongCarMode @8; - steerTempUnavailable @9; - reverseGear @10; - # ... + enum GearShifter { + unknown @0; + park @1; + drive @2; + neutral @3; + reverse @4; + sport @5; + low @6; + brake @7; } + # send on change struct ButtonEvent { - pressed @0: Bool; - type @1: Type; + pressed @0 :Bool; + type @1 :Type; enum Type { unknown @0; @@ -91,29 +139,30 @@ struct CarState { # ******* radar state @ 20hz ******* struct RadarState { - errors @0: List(Error); - points @1: List(RadarPoint); + errors @0 :List(Error); + points @1 :List(RadarPoint); # which packets this state came from - canMonoTimes @2: List(UInt64); + canMonoTimes @2 :List(UInt64); enum Error { - notValid @0; + commIssue @0; + fault @1; } # similar to LiveTracks # is one timestamp valid for all? I think so struct RadarPoint { - trackId @0: UInt64; # no trackId reuse + trackId @0 :UInt64; # no trackId reuse # these 3 are the minimum required - dRel @1: Float32; # m from the front bumper of the car - yRel @2: Float32; # m - vRel @3: Float32; # m/s + dRel @1 :Float32; # m from the front bumper of the car + yRel @2 :Float32; # m + vRel @3 :Float32; # m/s # these are optional and valid if they are not NaN - aRel @4: Float32; # m/s^2 - yvRel @5: Float32; # m/s + aRel @4 :Float32; # m/s^2 + yvRel @5 :Float32; # m/s } } @@ -121,17 +170,24 @@ struct RadarState { struct CarControl { # must be true for any actuator commands to work - enabled @0: Bool; + enabled @0 :Bool; - # range from 0.0 - 1.0 - gas @1: Float32; - brake @2: Float32; + gasDEPRECATED @1 :Float32; + brakeDEPRECATED @2 :Float32; + steeringTorqueDEPRECATED @3 :Float32; - # range from -1.0 - 1.0 - steeringTorque @3 :Float32; + actuators @6 :Actuators; - cruiseControl @4: CruiseControl; - hudControl @5: HUDControl; + cruiseControl @4 :CruiseControl; + hudControl @5 :HUDControl; + + struct Actuators { + # range from 0.0 - 1.0 + gas @0: Float32; + brake @1: Float32; + # range from -1.0 - 1.0 + steer @2: Float32; + } struct CruiseControl { cancel @0: Bool; @@ -178,31 +234,48 @@ struct CarControl { # ****** car param ****** struct CarParams { - carName @0: Text; - radarName @1: Text; - carFingerprint @2: Text; - - enableSteer @3: Bool; - enableGas @4: Bool; - enableBrake @5: Bool; - enableCruise @6: Bool; + carName @0 :Text; + radarName @1 :Text; + carFingerprint @2 :Text; + + enableSteer @3 :Bool; + enableGas @4 :Bool; + enableBrake @5 :Bool; + enableCruise @6 :Bool; + + minEnableSpeed @18 :Float32; + safetyModel @19 :Int16; + + steerMaxBP @20 :List(Float32); + steerMaxV @21 :List(Float32); + gasMaxBP @22 :List(Float32); + gasMaxV @23 :List(Float32); + brakeMaxBP @24 :List(Float32); + brakeMaxV @25 :List(Float32); + + enum SafetyModels { + # from board + default @0; + honda @1; + toyota @2; + } # things about the car in the manual - m @7: Float32; # [kg] running weight - l @8: Float32; # [m] wheelbase - sR @9: Float32; # [] steering ratio - aF @10: Float32; # [m] GC distance to front axle - aR @11: Float32; # [m] GC distance to rear axle - chi @12: Float32; # [] rear steering ratio wrt front steering (usually 0) + m @7 :Float32; # [kg] running weight + l @8 :Float32; # [m] wheelbase + sR @9 :Float32; # [] steering ratio + aF @10 :Float32; # [m] GC distance to front axle + aR @11 :Float32; # [m] GC distance to rear axle + chi @12 :Float32; # [] rear steering ratio wrt front steering (usually 0) # things we can derive - j @13: Float32; # [kg*m2] body rot inertia - cF @14: Float32; # [N/rad] front tire coeff of stiff - cR @15: Float32; # [N/rad] rear tire coeff of stiff + j @13 :Float32; # [kg*m2] body rotational inertia + cF @14 :Float32; # [N/rad] front tire coeff of stiff + cR @15 :Float32; # [N/rad] rear tire coeff of stiff # Kp and Ki for the lateral control - steerKp @16: Float32; - steerKi @17: Float32; + steerKp @16 :Float32; + steerKi @17 :Float32; # TODO: Kp and Ki for long control, perhaps not needed? } diff --git a/cereal/log.capnp b/cereal/log.capnp index 183ca904d8dee4..1496ff135692ce 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -92,10 +92,10 @@ struct InitData { } struct PandaInfo { - hasPanda @0: Bool; - dongleId @1: Text; - stVersion @2: Text; - espVersion @3: Text; + hasPanda @0 :Bool; + dongleId @1 :Text; + stVersion @2 :Text; + espVersion @3 :Text; } } @@ -110,9 +110,10 @@ struct FrameData { frameType @7 :FrameType; timestampSof @8 :UInt64; + transform @10 :List(Float32); androidCaptureResult @9 :AndroidCaptureResult; - + enum FrameType { unknown @0; neo @1; @@ -196,10 +197,10 @@ struct GpsLocationData { timestamp @7 :Int64; source @8 :SensorSource; - + # Represents NED velocity in m/s. vNED @9 :List(Float32); - + # Represents expected vertical accuracy in meters. (presumably 1 sigma?) verticalAccuracy @10 :Float32; @@ -239,7 +240,9 @@ struct ThermalData { # not thermal freeSpace @7 :Float32; batteryPercent @8 :Int16; - batteryStatus @9: Text; + batteryStatus @9 :Text; + + fanSpeed @10 :UInt16; } struct HealthData { @@ -254,8 +257,8 @@ struct HealthData { struct LiveUI { rearViewCam @0 :Bool; - alertText1 @1 :Text; - alertText2 @2 :Text; + alertText1 @1 :Text; + alertText2 @2 :Text; awarenessStatus @3 :Float32; } @@ -264,6 +267,7 @@ struct Live20Data { mdMonoTime @6 :UInt64; ftMonoTimeDEPRECATED @7 :UInt64; l100MonoTime @11 :UInt64; + radarErrors @12 :List(Car.RadarState.Error); # all deprecated warpMatrixDEPRECATED @0 :List(Float32); @@ -294,6 +298,7 @@ struct Live20Data { struct LiveCalibrationData { warpMatrix @0 :List(Float32); + warpMatrix2 @5 :List(Float32); calStatus @1 :Int8; calCycle @2 :Int32; calPerc @3 :Int8; @@ -340,14 +345,14 @@ struct Live100Data { hudLeadDEPRECATED @14 :Int32; cumLagMs @15 :Float32; - enabled @19: Bool; - steerOverride @20: Bool; + enabled @19 :Bool; + steerOverride @20 :Bool; - vCruise @22: Float32; + vCruise @22 :Float32; rearViewCam @23 :Bool; - alertText1 @24 :Text; - alertText2 @25 :Text; + alertText1 @24 :Text; + alertText2 @25 :Text; awarenessStatus @26 :Float32; angleOffset @27 :Float32; @@ -387,6 +392,7 @@ struct ModelData { bigBoxHeight @3 :UInt16; boxProjection @4 :List(Float32); yuvCorrection @5 :List(Float32); + inputTransform @6 :List(Float32); } } @@ -399,7 +405,7 @@ struct CalibrationFeatures { } struct EncodeIndex { - # picture from camera + # picture from camera frameId @0 :UInt32; type @1 :Type; # index of encoder from start of route @@ -438,69 +444,79 @@ struct LogRotate { struct Plan { mdMonoTime @9 :UInt64; l20MonoTime @10 :UInt64; + events @13 :List(Car.CarEvent); # lateral, 3rd order polynomial - lateralValid @0: Bool; + lateralValid @0 :Bool; dPoly @1 :List(Float32); + laneWidth @11 :Float32; # longitudinal - longitudinalValid @2: Bool; + longitudinalValid @2 :Bool; vTarget @3 :Float32; aTargetMin @4 :Float32; aTargetMax @5 :Float32; jerkFactor @6 :Float32; hasLead @7 :Bool; fcw @8 :Bool; + + # gps trajectory in car frame + gpsTrajectory @12 :GpsTrajectory; + + struct GpsTrajectory { + x @0 :List(Float32); + y @1 :List(Float32); + } } struct LiveLocationData { - status @0: UInt8; + status @0 :UInt8; - # 3D fix - lat @1: Float64; - lon @2: Float64; - alt @3: Float32; # m + # 3D fix + lat @1 :Float64; + lon @2 :Float64; + alt @3 :Float32; # m # speed - speed @4: Float32; # m/s + speed @4 :Float32; # m/s # NED velocity components - vNED @5: List(Float32); + vNED @5 :List(Float32); # roll, pitch, heading (x,y,z) - roll @6: Float32; # WRT to center of earth? - pitch @7: Float32; # WRT to center of earth? - heading @8: Float32; # WRT to north? + roll @6 :Float32; # WRT to center of earth? + pitch @7 :Float32; # WRT to center of earth? + heading @8 :Float32; # WRT to north? # what are these? - wanderAngle @9: Float32; - trackAngle @10: Float32; + wanderAngle @9 :Float32; + trackAngle @10 :Float32; # car frame -- https://upload.wikimedia.org/wikipedia/commons/f/f5/RPY_angles_of_cars.png # gyro, in car frame, deg/s - gyro @11: List(Float32); + gyro @11 :List(Float32); # accel, in car frame, m/s^2 - accel @12: List(Float32); + accel @12 :List(Float32); - accuracy @13: Accuracy; + accuracy @13 :Accuracy; struct Accuracy { - pNEDError @0: List(Float32); - vNEDError @1: List(Float32); - rollError @2: Float32; - pitchError @3: Float32; - headingError @4: Float32; - ellipsoidSemiMajorError @5: Float32; - ellipsoidSemiMinorError @6: Float32; - ellipsoidOrientationError @7: Float32; + pNEDError @0 :List(Float32); + vNEDError @1 :List(Float32); + rollError @2 :Float32; + pitchError @3 :Float32; + headingError @4 :Float32; + ellipsoidSemiMajorError @5 :Float32; + ellipsoidSemiMinorError @6 :Float32; + ellipsoidOrientationError @7 :Float32; } } struct EthernetPacket { pkt @0 :Data; - ts @1: Float32; + ts @1 :Float32; } struct NavUpdate { @@ -602,7 +618,7 @@ struct AndroidGnss { hasLeapSecond @4 :Bool; leapSecond @5 :Int32; - + hasFullBiasNanos @6 :Bool; fullBiasNanos @7 :Int64; @@ -611,10 +627,10 @@ struct AndroidGnss { hasBiasUncertaintyNanos @10 :Bool; biasUncertaintyNanos @11 :Float64; - + hasDriftNanosPerSecond @12 :Bool; driftNanosPerSecond @13 :Float64; - + hasDriftUncertaintyNanosPerSecond @14 :Bool; driftUncertaintyNanosPerSecond @15 :Float64; } @@ -633,7 +649,7 @@ struct AndroidGnss { accumulatedDeltaRangeState @9 :Int32; accumulatedDeltaRangeMeters @10 :Float64; accumulatedDeltaRangeUncertaintyMeters @11 :Float64; - + hasCarrierFrequencyHz @12 :Bool; carrierFrequencyHz @13 :Float32; hasCarrierCycles @14 :Bool; @@ -705,6 +721,8 @@ struct QcomGnss { measurementReport @1 :MeasurementReport; clockReport @2 :ClockReport; drMeasurementReport @3 :DrMeasurementReport; + drSvPoly @4 :DrSvPolyReport; + rawLog @5 :Data; } enum MeasurementSource @0xd71a12b6faada7ee { @@ -742,18 +760,18 @@ struct QcomGnss { measurementNotUsable @12 :Bool; sirCheckIsNeeded @13 :Bool; probationMode @14 :Bool; - + glonassMeanderBitEdgeValid @15 :Bool; glonassTimeMarkValid @16 :Bool; - + gpsRoundRobinRxDiversity @17 :Bool; gpsRxDiversity @18 :Bool; gpsLowBandwidthRxDiversityCombined @19 :Bool; gpsHighBandwidthNu4 @20 :Bool; gpsHighBandwidthNu8 @21 :Bool; gpsHighBandwidthUniform @22 :Bool; - gpsMultipathIndicator @23 :Bool; - + multipathIndicator @23 :Bool; + imdJammingIndicator @24 :Bool; lteB13TxJammingIndicator @25 :Bool; freshMeasurementIndicator @26 :Bool; @@ -953,6 +971,37 @@ struct QcomGnss { goodParity @32 :Bool; } } + + struct DrSvPolyReport { + svId @0 :UInt16; + frequencyIndex @1 :Int8; + + hasPosition @2 :Bool; + hasIono @3 :Bool; + hasTropo @4 :Bool; + hasElevation @5 :Bool; + polyFromXtra @6 :Bool; + hasSbasIono @7 :Bool; + + iode @8 :UInt16; + t0 @9 :Float64; + xyz0 @10 :List(Float64); + xyzN @11 :List(Float64); + other @12 :List(Float32); + + positionUncertainty @13 :Float32; + ionoDelay @14 :Float32; + ionoDot @15 :Float32; + sbasIonoDelay @16 :Float32; + sbasIonoDot @17 :Float32; + tropoDelay @18 :Float32; + elevation @19 :Float32; + elevationDot @20 :Float32; + elevationUncertainty @21 :Float32; + + velocityCoeff @22 :List(Float64); + + } } struct LidarPts { @@ -1037,12 +1086,12 @@ struct UbloxGnss { # num of measurements to follow numMeas @4 :UInt8; measurements @5 :List(Measurement); - + struct ReceiverStatus { - # leap seconds have been determined + # leap seconds have been determined leapSecValid @0 :Bool; # Clock reset applied - clkReset @1 : Bool; + clkReset @1 :Bool; } struct Measurement { @@ -1060,7 +1109,7 @@ struct UbloxGnss { # carrier phase locktime counter in ms locktime @7 :UInt16; # Carrier-to-noise density ratio (signal strength) in dBHz - cno @8 : UInt8; + cno @8 :UInt8; # pseudorange standard deviation in meters pseudorangeStdev @9 :Float32; # carrier phase standard deviation in cycles @@ -1103,31 +1152,47 @@ struct UbloxGnss { ecc @15 :Float64; cus @16 :Float64; a @17 :Float64; # note that this is not the root!! - + toe @18 :Float64; cic @19 :Float64; omega0 @20 :Float64; cis @21 :Float64; - + i0 @22 :Float64; crc @23 :Float64; omega @24 :Float64; omegaDot @25 :Float64; - + iDot @26 :Float64; codesL2 @27 :Float64; gpsWeek @28 :Float64; l2 @29 :Float64; - + svAcc @30 :Float64; svHealth @31 :Float64; tgd @32 :Float64; iodc @33 :Float64; - + transmissionTime @34 :Float64; fitInterval @35 :Float64; } } + +struct Clocks { + bootTimeNanos @0 :UInt64; + monotonicNanos @1 :UInt64; + monotonicRawNanos @2 :UInt64; + wallTimeNanos @3 :UInt64; + modemUptimeMillis @4 :UInt64; +} + +struct LiveMpcData { + x @0 :List(Float32); + y @1 :List(Float32); + psi @2 :List(Float32); + delta @3 :List(Float32); +} + struct Event { # in nanoseconds? logMonoTime @0 :UInt64; @@ -1144,7 +1209,7 @@ struct Event { model @9 :ModelData; features @10 :CalibrationFeatures; sensorEvents @11 :List(SensorEventData); - health @12 : HealthData; + health @12 :HealthData; live20 @13 :Live20Data; liveUIDEPRECATED @14 :LiveUI; encodeIdx @15 :EncodeIndex; @@ -1167,5 +1232,7 @@ struct Event { lidarPts @32 :LidarPts; procLog @33 :ProcLog; ubloxGnss @34 :UbloxGnss; + clocks @35 :Clocks; + liveMpc @36 :LiveMpcData; } } diff --git a/common/basedir.py b/common/basedir.py new file mode 100644 index 00000000000000..991f6aaed92ae4 --- /dev/null +++ b/common/basedir.py @@ -0,0 +1,4 @@ +import os +BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../") + + diff --git a/common/crash.py b/common/crash.py index 06fe9a91325994..bc5be003d73355 100644 --- a/common/crash.py +++ b/common/crash.py @@ -2,7 +2,7 @@ import os import sys -if os.getenv("NOLOG"): +if os.getenv("NOLOG") or os.getenv("NOCRASH"): def capture_exception(*exc_info): pass def bind_user(**kwargs): diff --git a/common/fingerprints.py b/common/fingerprints.py index 298424940b5131..34c84b7449de75 100644 --- a/common/fingerprints.py +++ b/common/fingerprints.py @@ -18,6 +18,9 @@ 57L: 3, 145L: 8, 316L: 8, 340L: 8, 342L: 6, 344L: 8, 380L: 8, 398L: 3, 399L: 6, 401L: 8, 420L: 8, 422L: 8, 426L: 8, 432L: 7, 464L: 8, 474L: 5, 476L: 4, 487L: 4, 490L: 8, 493L: 3, 507L: 1, 542L: 7, 545L: 4, 597L: 8, 660L: 8, 661L: 4, 773L: 7, 777L: 8, 800L: 8, 804L: 8, 808L: 8, 882L: 2, 884L: 7, 888L: 8, 891L: 8, 892L: 8, 923L: 2, 929L: 8, 983L: 8, 985L: 3, 1024L: 5, 1027L: 5, 1029L: 8, 1033L: 5, 1036L: 8, 1039L: 8, 1057L: 5, 1064L: 7, 1108L: 8, 1125L: 8, 1296L: 8, 1365L: 5, 1424L: 5, 1600L: 5, 1601L: 8, # sent messages 0x194: 4, 0x1fa: 8, 0x30c: 8, 0x33d: 5, + }, + "TOYOTA PRIUS 2017": { + 896L: 8, 832L: 8, 898L: 8, 899L: 8, 577L: 8, 528L: 8, 529L: 8, 530L: 8, 531L: 8, 532L: 8, 533L: 8, 534L: 8, 535L: 8, 536L: 8, 537L: 8, 538L: 8, 539L: 8, 540L: 8, 541L: 8, 542L: 8, 543L: 8, 544L: 8, 545L: 8, 546L: 8, 547L: 8, 548L: 8, 549L: 8, 550L: 8, 551L: 8, 296L: 6, 553L: 6, 554L: 6, 555L: 6, 556L: 6, 557L: 6, 558L: 6, 559L: 6, 560L: 7, 561L: 8, 562L: 8, 883L: 8, 837L: 8, 833L: 8, 576L: 8, 321L: 4, 834L: 8, 835L: 8, 580L: 8, 581L: 8, 897L: 8, 584L: 8, 1136L: 4, 976L: 8, 977L: 8, 978L: 8, 291L: 7, 881L: 8, 352L: 8, 353L: 7, 867L: 8, 868L: 8, 869L: 8, 1126L: 3, 304L: 7, 880L: 8, 552L: 6, 882L: 8, 979L: 8, 884L: 8, 885L: 8, 836L: 8 } } diff --git a/common/params.py b/common/params.py index 8e8a11edc207c8..ca3ee99923377f 100755 --- a/common/params.py +++ b/common/params.py @@ -66,6 +66,13 @@ class UnknownKeyName(Exception): # read: radard "CarParams": TxType.CLEAR_ON_CAR_START} +def fsync_dir(path): + fd = os.open(path, os.O_RDONLY) + try: + os.fsync(fd) + finally: + os.close(fd) + class FileLock(object): def __init__(self, path, create): @@ -182,15 +189,32 @@ def __exit__(self, type, value, traceback): self._check_entered() try: + # data_path refers to the externally used path to the params. It is a symlink. + # old_data_path is the path currently pointed to by data_path. + # tempdir_path is a path where the new params will go, which the new data path will point to. + # new_data_path is a temporary symlink that will atomically overwrite data_path. + # + # The current situation is: + # data_path -> old_data_path + # We're going to write params data to tempdir_path + # tempdir_path -> params data + # Then point new_data_path to tempdir_path + # new_data_path -> tempdir_path + # Then atomically overwrite data_path with new_data_path + # data_path -> tempdir_path old_data_path = None new_data_path = None tempdir_path = tempfile.mkdtemp(prefix=".tmp", dir=self._path) + try: # Write back all keys. os.chmod(tempdir_path, 0o777) for k, v in self._vals.items(): with open(os.path.join(tempdir_path, k), "wb") as f: f.write(v) + f.flush() + os.fsync(f.fileno()) + fsync_dir(tempdir_path) data_path = self._data_path() try: @@ -203,16 +227,21 @@ def __exit__(self, type, value, traceback): new_data_path = "{}.link".format(tempdir_path) os.symlink(os.path.basename(tempdir_path), new_data_path) os.rename(new_data_path, data_path) - # TODO(mgraczyk): raise useful error when values are bad. - except: - shutil.rmtree(tempdir_path) - if new_data_path is not None: + fsync_dir(self._path) + finally: + # If the rename worked, we can delete the old data. Otherwise delete the new one. + success = new_data_path is not None and os.path.exists(data_path) and ( + os.readlink(data_path) == os.path.basename(tempdir_path)) + + if success: + if old_data_path is not None: + shutil.rmtree(old_data_path) + else: + shutil.rmtree(tempdir_path) + + # Regardless of what happened above, there should be no link at new_data_path. + if new_data_path is not None and os.path.islink(new_data_path): os.remove(new_data_path) - raise - - # Keep holding the lock while we clean up the old data. - if old_data_path is not None: - shutil.rmtree(old_data_path) finally: os.umask(self._prev_umask) self._prev_umask = None @@ -249,6 +278,10 @@ def manager_start(self): def car_start(self): self._clear_keys_with_type(TxType.CLEAR_ON_CAR_START) + def delete(self, key): + with self.env.begin(write=True) as txn: + txn.delete(key) + def get(self, key, block=False): if key not in keys: raise UnknownKeyName(key) diff --git a/common/profiler.py b/common/profiler.py index b35a52d16fd81f..26fbeb382b57d9 100644 --- a/common/profiler.py +++ b/common/profiler.py @@ -14,6 +14,12 @@ def checkpoint(self, name): self.cp.append((name, tt - self.last_time)) self.last_time = tt + def reset(self, enabled=False): + self.enabled = enabled + self.cp = [] + self.start_time = sec_since_boot() + self.last_time = self.start_time + def display(self): if not self.enabled: return diff --git a/opendbc b/opendbc index 008089045e371a..063032ff2b9b87 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 008089045e371a9eebbe79d978ff22ae3e70bdba +Subproject commit 063032ff2b9b878c2cc10301504bad9db54f655f diff --git a/panda b/panda index 4901d52104e369..92a1c773e76329 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 4901d52104e369f2444b5d56846199fdfc3fd695 +Subproject commit 92a1c773e763297b7478b5bca44e25fb8cd8bdf2 diff --git a/phonelibs/qpoases/EXAMPLES/example1.cpp b/phonelibs/qpoases/EXAMPLES/example1.cpp new file mode 100644 index 00000000000000..92b47fc93798d2 --- /dev/null +++ b/phonelibs/qpoases/EXAMPLES/example1.cpp @@ -0,0 +1,74 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file EXAMPLES/example1.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Very simple example for testing qpOASES (using QProblem class). + */ + + +#include + + +/** Example for qpOASES main function using the QProblem class. */ +int main( ) +{ + /* Setup data of first QP. */ + real_t H[2*2] = { 1.0, 0.0, 0.0, 0.5 }; + real_t A[1*2] = { 1.0, 1.0 }; + real_t g[2] = { 1.5, 1.0 }; + real_t lb[2] = { 0.5, -2.0 }; + real_t ub[2] = { 5.0, 2.0 }; + real_t lbA[1] = { -1.0 }; + real_t ubA[1] = { 2.0 }; + + /* Setup data of second QP. */ + real_t g_new[2] = { 1.0, 1.5 }; + real_t lb_new[2] = { 0.0, -1.0 }; + real_t ub_new[2] = { 5.0, -0.5 }; + real_t lbA_new[1] = { -2.0 }; + real_t ubA_new[1] = { 1.0 }; + + + /* Setting up QProblem object. */ + QProblem example( 2,1 ); + + /* Solve first QP. */ + int nWSR = 10; + example.init( H,g,A,lb,ub,lbA,ubA, nWSR,0 ); + + /* Solve second QP. */ + nWSR = 10; + example.hotstart( g_new,lb_new,ub_new,lbA_new,ubA_new, nWSR,0 ); + + return 0; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/EXAMPLES/example1b.cpp b/phonelibs/qpoases/EXAMPLES/example1b.cpp new file mode 100644 index 00000000000000..331f19d8da0cbc --- /dev/null +++ b/phonelibs/qpoases/EXAMPLES/example1b.cpp @@ -0,0 +1,69 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file EXAMPLES/example1b.cpp + * \author Hans Joachim Ferreau + * \version 1.3 + * \date 2007-2008 + * + * Very simple example for testing qpOASES using the QProblemB class. + */ + + +#include + + +/** Example for qpOASES main function using the QProblemB class. */ +int main( ) +{ + /* Setup data of first QP. */ + real_t H[2*2] = { 1.0, 0.0, 0.0, 0.5 }; + real_t g[2] = { 1.5, 1.0 }; + real_t lb[2] = { 0.5, -2.0 }; + real_t ub[2] = { 5.0, 2.0 }; + + /* Setup data of second QP. */ + real_t g_new[2] = { 1.0, 1.5 }; + real_t lb_new[2] = { 0.0, -1.0 }; + real_t ub_new[2] = { 5.0, -0.5 }; + + + /* Setting up QProblemB object. */ + QProblemB example( 2 ); + + /* Solve first QP. */ + int nWSR = 10; + example.init( H,g,lb,ub, nWSR,0 ); + + /* Solve second QP. */ + nWSR = 10; + example.hotstart( g_new,lb_new,ub_new, nWSR,0 ); + + return 0; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/Bounds.hpp b/phonelibs/qpoases/INCLUDE/Bounds.hpp new file mode 100644 index 00000000000000..1fbd28ab38d342 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Bounds.hpp @@ -0,0 +1,189 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/Bounds.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the Bounds class designed to manage working sets of + * bounds within a QProblem. + */ + + +#ifndef QPOASES_BOUNDS_HPP +#define QPOASES_BOUNDS_HPP + + +#include + + + +/** This class manages working sets of bounds by storing + * index sets and other status information. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class Bounds : public SubjectTo +{ + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + Bounds( ); + + /** Copy constructor (deep copy). */ + Bounds( const Bounds& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~Bounds( ); + + /** Assignment operator (deep copy). */ + Bounds& operator=( const Bounds& rhs /**< Rhs object. */ + ); + + + /** Pseudo-constructor takes the number of bounds. + * \return SUCCESSFUL_RETURN */ + returnValue init( int n /**< Number of bounds. */ + ); + + + /** Initially adds number of a new (i.e. not yet in the list) bound to + * given index set. + * \return SUCCESSFUL_RETURN \n + RET_SETUP_BOUND_FAILED \n + RET_INDEX_OUT_OF_BOUNDS \n + RET_INVALID_ARGUMENTS */ + returnValue setupBound( int _number, /**< Number of new bound. */ + SubjectToStatus _status /**< Status of new bound. */ + ); + + /** Initially adds all numbers of new (i.e. not yet in the list) bounds to + * to the index set of free bounds; the order depends on the SujectToType + * of each index. + * \return SUCCESSFUL_RETURN \n + RET_SETUP_BOUND_FAILED */ + returnValue setupAllFree( ); + + + /** Moves index of a bound from index list of fixed to that of free bounds. + * \return SUCCESSFUL_RETURN \n + RET_MOVING_BOUND_FAILED \n + RET_INDEX_OUT_OF_BOUNDS */ + returnValue moveFixedToFree( int _number /**< Number of bound to be freed. */ + ); + + /** Moves index of a bound from index list of free to that of fixed bounds. + * \return SUCCESSFUL_RETURN \n + RET_MOVING_BOUND_FAILED \n + RET_INDEX_OUT_OF_BOUNDS */ + returnValue moveFreeToFixed( int _number, /**< Number of bound to be fixed. */ + SubjectToStatus _status /**< Status of bound to be fixed. */ + ); + + /** Swaps the indices of two free bounds within the index set. + * \return SUCCESSFUL_RETURN \n + RET_SWAPINDEX_FAILED */ + returnValue swapFree( int number1, /**< Number of first constraint or bound. */ + int number2 /**< Number of second constraint or bound. */ + ); + + + /** Returns number of variables. + * \return Number of variables. */ + inline int getNV( ) const; + + /** Returns number of implicitly fixed variables. + * \return Number of implicitly fixed variables. */ + inline int getNFV( ) const; + + /** Returns number of bounded (but possibly free) variables. + * \return Number of bounded (but possibly free) variables. */ + inline int getNBV( ) const; + + /** Returns number of unbounded variables. + * \return Number of unbounded variables. */ + inline int getNUV( ) const; + + + /** Sets number of implicitly fixed variables. + * \return SUCCESSFUL_RETURN */ + inline returnValue setNFV( int n /**< Number of implicitly fixed variables. */ + ); + + /** Sets number of bounded (but possibly free) variables. + * \return SUCCESSFUL_RETURN */ + inline returnValue setNBV( int n /**< Number of bounded (but possibly free) variables. */ + ); + + /** Sets number of unbounded variables. + * \return SUCCESSFUL_RETURN */ + inline returnValue setNUV( int n /**< Number of unbounded variables */ + ); + + + /** Returns number of free variables. + * \return Number of free variables. */ + inline int getNFR( ); + + /** Returns number of fixed variables. + * \return Number of fixed variables. */ + inline int getNFX( ); + + + /** Returns a pointer to free variables index list. + * \return Pointer to free variables index list. */ + inline Indexlist* getFree( ); + + /** Returns a pointer to fixed variables index list. + * \return Pointer to fixed variables index list. */ + inline Indexlist* getFixed( ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + int nV; /**< Number of variables (nV = nFV + nBV + nUV). */ + int nFV; /**< Number of implicitly fixed variables. */ + int nBV; /**< Number of bounded (but possibly free) variables. */ + int nUV; /**< Number of unbounded variables. */ + + Indexlist free; /**< Index list of free variables. */ + Indexlist fixed; /**< Index list of fixed variables. */ +}; + +#include + +#endif /* QPOASES_BOUNDS_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/Constants.hpp b/phonelibs/qpoases/INCLUDE/Constants.hpp new file mode 100644 index 00000000000000..8293fa514c6a9c --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Constants.hpp @@ -0,0 +1,108 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/Constants.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2008 + * + * Definition of all global constants. + */ + + +#ifndef QPOASES_CONSTANTS_HPP +#define QPOASES_CONSTANTS_HPP + +#ifndef QPOASES_CUSTOM_INTERFACE +#include "acado_qpoases_interface.hpp" +#else + #define XSTR(x) #x + #define STR(x) XSTR(x) + #include STR(QPOASES_CUSTOM_INTERFACE) +#endif + +/** Maximum number of variables within a QP formulation. + Note: this value has to be positive! */ +const int NVMAX = QPOASES_NVMAX; + +/** Maximum number of constraints within a QP formulation. + Note: this value has to be positive! */ +const int NCMAX = QPOASES_NCMAX; + +/** Redefinition of NCMAX used for memory allocation, to avoid zero sized arrays + and compiler errors. */ +const int NCMAX_ALLOC = (NCMAX == 0) ? 1 : NCMAX; + +/**< Maximum number of working set recalculations. + Note: this value has to be positive! */ +const int NWSRMAX = QPOASES_NWSRMAX; + +/** Desired KKT tolerance of QP solution; a warning RET_INACCURATE_SOLUTION is + * issued if this tolerance is not met. + * Note: this value has to be positive! */ +const real_t DESIREDACCURACY = (real_t) 1.0e-3; + +/** Critical KKT tolerance of QP solution; an error is issued if this + * tolerance is not met. + * Note: this value has to be positive! */ +const real_t CRITICALACCURACY = (real_t) 1.0e-2; + + + +/** Numerical value of machine precision (min eps, s.t. 1+eps > 1). + Note: this value has to be positive! */ +const real_t EPS = (real_t) QPOASES_EPS; + +/** Numerical value of zero (for situations in which it would be + * unreasonable to compare with 0.0). + * Note: this value has to be positive! */ +const real_t ZERO = (real_t) 1.0e-50; + +/** Numerical value of infinity (e.g. for non-existing bounds). + * Note: this value has to be positive! */ +const real_t INFTY = (real_t) 1.0e12; + + +/** Lower/upper (constraints') bound tolerance (an inequality constraint + * whose lower and upper bound differ by less than BOUNDTOL is regarded + * to be an equality constraint). + * Note: this value has to be positive! */ +const real_t BOUNDTOL = (real_t) 1.0e-10; + +/** Offset for relaxing (constraints') bounds at beginning of an initial homotopy. + * Note: this value has to be positive! */ +const real_t BOUNDRELAXATION = (real_t) 1.0e3; + + +/** Factor that determines physical lengths of index lists. + * Note: this value has to be greater than 1! */ +const int INDEXLISTFACTOR = 5; + + +#endif /* QPOASES_CONSTANTS_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/Constraints.hpp b/phonelibs/qpoases/INCLUDE/Constraints.hpp new file mode 100644 index 00000000000000..0b78747e29afeb --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Constraints.hpp @@ -0,0 +1,181 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/Constraints.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the Constraints class designed to manage working sets of + * constraints within a QProblem. + */ + + +#ifndef QPOASES_CONSTRAINTS_HPP +#define QPOASES_CONSTRAINTS_HPP + + +#include + + + +/** This class manages working sets of constraints by storing + * index sets and other status information. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class Constraints : public SubjectTo +{ + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + Constraints( ); + + /** Copy constructor (deep copy). */ + Constraints( const Constraints& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~Constraints( ); + + /** Assignment operator (deep copy). */ + Constraints& operator=( const Constraints& rhs /**< Rhs object. */ + ); + + + /** Pseudo-constructor takes the number of constraints. + * \return SUCCESSFUL_RETURN */ + returnValue init( int n /**< Number of constraints. */ + ); + + + /** Initially adds number of a new (i.e. not yet in the list) constraint to + * a given index set. + * \return SUCCESSFUL_RETURN \n + RET_SETUP_CONSTRAINT_FAILED \n + RET_INDEX_OUT_OF_BOUNDS \n + RET_INVALID_ARGUMENTS */ + returnValue setupConstraint( int _number, /**< Number of new constraint. */ + SubjectToStatus _status /**< Status of new constraint. */ + ); + + /** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to + * to the index set of inactive constraints; the order depends on the SujectToType + * of each index. Only disabled constraints are added to index set of disabled constraints! + * \return SUCCESSFUL_RETURN \n + RET_SETUP_CONSTRAINT_FAILED */ + returnValue setupAllInactive( ); + + + /** Moves index of a constraint from index list of active to that of inactive constraints. + * \return SUCCESSFUL_RETURN \n + RET_MOVING_CONSTRAINT_FAILED */ + returnValue moveActiveToInactive( int _number /**< Number of constraint to become inactive. */ + ); + + /** Moves index of a constraint from index list of inactive to that of active constraints. + * \return SUCCESSFUL_RETURN \n + RET_MOVING_CONSTRAINT_FAILED */ + returnValue moveInactiveToActive( int _number, /**< Number of constraint to become active. */ + SubjectToStatus _status /**< Status of constraint to become active. */ + ); + + + /** Returns the number of constraints. + * \return Number of constraints. */ + inline int getNC( ) const; + + /** Returns the number of implicit equality constraints. + * \return Number of implicit equality constraints. */ + inline int getNEC( ) const; + + /** Returns the number of "real" inequality constraints. + * \return Number of "real" inequality constraints. */ + inline int getNIC( ) const; + + /** Returns the number of unbounded constraints (i.e. without any bounds). + * \return Number of unbounded constraints (i.e. without any bounds). */ + inline int getNUC( ) const; + + + /** Sets number of implicit equality constraints. + * \return SUCCESSFUL_RETURN */ + inline returnValue setNEC( int n /**< Number of implicit equality constraints. */ + ); + + /** Sets number of "real" inequality constraints. + * \return SUCCESSFUL_RETURN */ + inline returnValue setNIC( int n /**< Number of "real" inequality constraints. */ + ); + + /** Sets number of unbounded constraints (i.e. without any bounds). + * \return SUCCESSFUL_RETURN */ + inline returnValue setNUC( int n /**< Number of unbounded constraints (i.e. without any bounds). */ + ); + + + /** Returns the number of active constraints. + * \return Number of constraints. */ + inline int getNAC( ); + + /** Returns the number of inactive constraints. + * \return Number of constraints. */ + inline int getNIAC( ); + + + /** Returns a pointer to active constraints index list. + * \return Pointer to active constraints index list. */ + inline Indexlist* getActive( ); + + /** Returns a pointer to inactive constraints index list. + * \return Pointer to inactive constraints index list. */ + inline Indexlist* getInactive( ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + int nC; /**< Number of constraints (nC = nEC + nIC + nUC). */ + int nEC; /**< Number of implicit equality constraints. */ + int nIC; /**< Number of "real" inequality constraints. */ + int nUC; /**< Number of unbounded constraints (i.e. without any bounds). */ + + Indexlist active; /**< Index list of active constraints. */ + Indexlist inactive; /**< Index list of inactive constraints. */ +}; + + +#include + +#endif /* QPOASES_CONSTRAINTS_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/CyclingManager.hpp b/phonelibs/qpoases/INCLUDE/CyclingManager.hpp new file mode 100644 index 00000000000000..9b5c064a0bd7a4 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/CyclingManager.hpp @@ -0,0 +1,126 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/CyclingManager.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the CyclingManager class designed to detect + * and handle possible cycling during QP iterations. + */ + + +#ifndef QPOASES_CYCLINGMANAGER_HPP +#define QPOASES_CYCLINGMANAGER_HPP + + +#include + + + +/** This class is intended to detect and handle possible cycling during QP iterations. + * As cycling seems to occur quite rarely, this class is NOT FULLY IMPLEMENTED YET! + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class CyclingManager +{ + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + CyclingManager( ); + + /** Copy constructor (deep copy). */ + CyclingManager( const CyclingManager& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~CyclingManager( ); + + /** Copy asingment operator (deep copy). */ + CyclingManager& operator=( const CyclingManager& rhs /**< Rhs object. */ + ); + + + /** Pseudo-constructor which takes the number of bounds/constraints. + * \return SUCCESSFUL_RETURN */ + returnValue init( int _nV, /**< Number of bounds to be managed. */ + int _nC /**< Number of constraints to be managed. */ + ); + + + /** Stores index of a bound/constraint that might cause cycling. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + returnValue setCyclingStatus( int number, /**< Number of bound/constraint. */ + BooleanType isBound, /**< Flag that indicates if given number corresponds to a + * bound (BT_TRUE) or a constraint (BT_FALSE). */ + CyclingStatus _status /**< Cycling status of bound/constraint. */ + ); + + /** Returns if bound/constraint might cause cycling. + * \return BT_TRUE: bound/constraint might cause cycling \n + BT_FALSE: otherwise */ + CyclingStatus getCyclingStatus( int number, /**< Number of bound/constraint. */ + BooleanType isBound /**< Flag that indicates if given number corresponds to + * a bound (BT_TRUE) or a constraint (BT_FALSE). */ + ) const; + + + /** Clears all previous cycling information. + * \return SUCCESSFUL_RETURN */ + returnValue clearCyclingData( ); + + + /** Returns if cycling was detected. + * \return BT_TRUE iff cycling was detected. */ + inline BooleanType isCyclingDetected( ) const; + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + int nV; /**< Number of managed bounds. */ + int nC; /**< Number of managed constraints. */ + + CyclingStatus status[NVMAX+NCMAX]; /**< Array to store cycling status of all bounds/constraints. */ + + BooleanType cyclingDetected; /**< Flag if cycling was detected. */ +}; + + +#include + +#endif /* QPOASES_CYCLINGMANAGER_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp b/phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp new file mode 100644 index 00000000000000..056bb26f02d09d --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp @@ -0,0 +1,107 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/EXTRAS/SolutionAnalysis.hpp + * \author Milan Vukov, Boris Houska, Hans Joachim Ferreau + * \version 1.3embedded + * \date 2012 + * + * Solution analysis class, based on a class in the standard version of the qpOASES + */ + + +// + +#ifndef QPOASES_SOLUTIONANALYSIS_HPP +#define QPOASES_SOLUTIONANALYSIS_HPP + +#include + +/** Enables the computation of variance as is in the standard version of qpOASES */ +#define QPOASES_USE_OLD_VERSION 0 + +#if QPOASES_USE_OLD_VERSION +#define KKT_DIM (2 * NVMAX + NCMAX) +#endif + +class SolutionAnalysis +{ +public: + + /** Default constructor. */ + SolutionAnalysis( ); + + /** Copy constructor (deep copy). */ + SolutionAnalysis( const SolutionAnalysis& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~SolutionAnalysis( ); + + /** Copy asingment operator (deep copy). */ + SolutionAnalysis& operator=( const SolutionAnalysis& rhs /**< Rhs object. */ + ); + + /** A routine for computation of inverse of the Hessian matrix. */ + returnValue getHessianInverse( + QProblem* qp, /** QP */ + real_t* hessianInverse /** Inverse of the Hessian matrix*/ + ); + + /** A routine for computation of inverse of the Hessian matrix. */ + returnValue getHessianInverse( QProblemB* qp, /** QP */ + real_t* hessianInverse /** Inverse of the Hessian matrix*/ + ); + +#if QPOASES_USE_OLD_VERSION + returnValue getVarianceCovariance( + QProblem* qp, + real_t* g_b_bA_VAR, + real_t* Primal_Dual_VAR + ); +#endif + +private: + + real_t delta_g_cov[ NVMAX ]; /** A covariance-vector of g */ + real_t delta_lb_cov[ NVMAX ]; /** A covariance-vector of lb */ + real_t delta_ub_cov[ NVMAX ]; /** A covariance-vector of ub */ + real_t delta_lbA_cov[ NCMAX_ALLOC ]; /** A covariance-vector of lbA */ + real_t delta_ubA_cov[ NCMAX_ALLOC ]; /** A covariance-vector of ubA */ + +#if QPOASES_USE_OLD_VERSION + real_t K[KKT_DIM * KKT_DIM]; /** A matrix to store an intermediate result */ +#endif + + int FR_idx[ NVMAX ]; /** Index array for free variables */ + int FX_idx[ NVMAX ]; /** Index array for fixed variables */ + int AC_idx[ NCMAX_ALLOC ]; /** Index array for active constraints */ + + real_t delta_xFR[ NVMAX ]; /** QP reaction, primal, w.r.t. free */ + real_t delta_xFX[ NVMAX ]; /** QP reaction, primal, w.r.t. fixed */ + real_t delta_yAC[ NVMAX ]; /** QP reaction, dual, w.r.t. active */ + real_t delta_yFX[ NVMAX ]; /** QP reaction, dual, w.r.t. fixed*/ +}; + +#endif // QPOASES_SOLUTIONANALYSIS_HPP diff --git a/phonelibs/qpoases/INCLUDE/Indexlist.hpp b/phonelibs/qpoases/INCLUDE/Indexlist.hpp new file mode 100644 index 00000000000000..18e3494e3f656c --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Indexlist.hpp @@ -0,0 +1,154 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/Indexlist.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the Indexlist class designed to manage index lists of + * constraints and bounds within a SubjectTo object. + */ + + +#ifndef QPOASES_INDEXLIST_HPP +#define QPOASES_INDEXLIST_HPP + + +#include + + +/** This class manages index lists. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class Indexlist +{ + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + Indexlist( ); + + /** Copy constructor (deep copy). */ + Indexlist( const Indexlist& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~Indexlist( ); + + /** Assingment operator (deep copy). */ + Indexlist& operator=( const Indexlist& rhs /**< Rhs object. */ + ); + + /** Pseudo-constructor. + * \return SUCCESSFUL_RETURN */ + returnValue init( ); + + + /** Creates an array of all numbers within the index set in correct order. + * \return SUCCESSFUL_RETURN \n + RET_INDEXLIST_CORRUPTED */ + returnValue getNumberArray( int* const numberarray /**< Output: Array of numbers (NULL on error). */ + ) const; + + + /** Determines the index within the index list at with a given number is stored. + * \return >= 0: Index of given number. \n + -1: Number not found. */ + int getIndex( int givennumber /**< Number whose index shall be determined. */ + ) const; + + /** Determines the physical index within the index list at with a given number is stored. + * \return >= 0: Index of given number. \n + -1: Number not found. */ + int getPhysicalIndex( int givennumber /**< Number whose physical index shall be determined. */ + ) const; + + /** Returns the number stored at a given physical index. + * \return >= 0: Number stored at given physical index. \n + -RET_INDEXLIST_OUTOFBOUNDS */ + int getNumber( int physicalindex /**< Physical index of the number to be returned. */ + ) const; + + + /** Returns the current length of the index list. + * \return Current length of the index list. */ + inline int getLength( ); + + /** Returns last number within the index list. + * \return Last number within the index list. */ + inline int getLastNumber( ) const; + + + /** Adds number to index list. + * \return SUCCESSFUL_RETURN \n + RET_INDEXLIST_MUST_BE_REORDERD \n + RET_INDEXLIST_EXCEEDS_MAX_LENGTH */ + returnValue addNumber( int addnumber /**< Number to be added. */ + ); + + /** Removes number from index list. + * \return SUCCESSFUL_RETURN */ + returnValue removeNumber( int removenumber /**< Number to be removed. */ + ); + + /** Swaps two numbers within index list. + * \return SUCCESSFUL_RETURN */ + returnValue swapNumbers( int number1,/**< First number for swapping. */ + int number2 /**< Second number for swapping. */ + ); + + /** Determines if a given number is contained in the index set. + * \return BT_TRUE iff number is contain in the index set */ + inline BooleanType isMember( int _number /**< Number to be tested for membership. */ + ) const; + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + int number[INDEXLISTFACTOR*(NVMAX+NCMAX)]; /**< Array to store numbers of constraints or bounds. */ + int next[INDEXLISTFACTOR*(NVMAX+NCMAX)]; /**< Array to store physical index of successor. */ + int previous[INDEXLISTFACTOR*(NVMAX+NCMAX)]; /**< Array to store physical index of predecossor. */ + int length; /**< Length of index list. */ + int first; /**< Physical index of first element. */ + int last; /**< Physical index of last element. */ + int lastusedindex; /**< Physical index of last entry in index list. */ + int physicallength; /**< Physical length of index list. */ +}; + + +#include + +#endif /* QPOASES_INDEXLIST_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/MessageHandling.hpp b/phonelibs/qpoases/INCLUDE/MessageHandling.hpp new file mode 100644 index 00000000000000..f0b0c79a473b85 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/MessageHandling.hpp @@ -0,0 +1,415 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/MessageHandling.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the MessageHandling class including global return values. + */ + + +#ifndef QPOASES_MESSAGEHANDLING_HPP +#define QPOASES_MESSAGEHANDLING_HPP + +// #define PC_DEBUG + +#ifdef PC_DEBUG + #include + + /** Defines an alias for FILE from stdio.h. */ + #define myFILE FILE + /** Defines an alias for stderr from stdio.h. */ + #define myStderr stderr + /** Defines an alias for stdout from stdio.h. */ + #define myStdout stdout +#else + /** Defines an alias for FILE from stdio.h. */ + #define myFILE int + /** Defines an alias for stderr from stdio.h. */ + #define myStderr 0 + /** Defines an alias for stdout from stdio.h. */ + #define myStdout 0 +#endif + + +#include +#include + + +/** Defines symbols for global return values. \n + * Important: All return values are assumed to be nonnegative! */ +enum returnValue +{ +TERMINAL_LIST_ELEMENT = -1, /**< Terminal list element, internal usage only! */ +/* miscellaneous */ +SUCCESSFUL_RETURN = 0, /**< Successful return. */ +RET_DIV_BY_ZERO, /**< Division by zero. */ +RET_INDEX_OUT_OF_BOUNDS, /**< Index out of bounds. */ +RET_INVALID_ARGUMENTS, /**< At least one of the arguments is invalid. */ +RET_ERROR_UNDEFINED, /**< Error number undefined. */ +RET_WARNING_UNDEFINED, /**< Warning number undefined. */ +RET_INFO_UNDEFINED, /**< Info number undefined. */ +RET_EWI_UNDEFINED, /**< Error/warning/info number undefined. */ +RET_AVAILABLE_WITH_LINUX_ONLY, /**< This function is available under Linux only. */ +RET_UNKNOWN_BUG, /**< The error occured is not yet known. */ +RET_PRINTLEVEL_CHANGED, /**< 10 Print level changed. */ +RET_NOT_YET_IMPLEMENTED, /**< Requested function is not yet implemented in this version of qpOASES. */ +/* Indexlist */ +RET_INDEXLIST_MUST_BE_REORDERD, /**< Index list has to be reordered. */ +RET_INDEXLIST_EXCEEDS_MAX_LENGTH, /**< Index list exceeds its maximal physical length. */ +RET_INDEXLIST_CORRUPTED, /**< Index list corrupted. */ +RET_INDEXLIST_OUTOFBOUNDS, /**< Physical index is out of bounds. */ +RET_INDEXLIST_ADD_FAILED, /**< Adding indices from another index set failed. */ +RET_INDEXLIST_INTERSECT_FAILED, /**< Intersection with another index set failed. */ +/* SubjectTo / Bounds / Constraints */ +RET_INDEX_ALREADY_OF_DESIRED_STATUS, /**< Index is already of desired status. */ +RET_ADDINDEX_FAILED, /**< Cannot swap between different indexsets. */ +RET_SWAPINDEX_FAILED, /**< 20 Adding index to index set failed. */ +RET_NOTHING_TO_DO, /**< Nothing to do. */ +RET_SETUP_BOUND_FAILED, /**< Setting up bound index failed. */ +RET_SETUP_CONSTRAINT_FAILED, /**< Setting up constraint index failed. */ +RET_MOVING_BOUND_FAILED, /**< Moving bound between index sets failed. */ +RET_MOVING_CONSTRAINT_FAILED, /**< Moving constraint between index sets failed. */ +/* QProblem */ +RET_QP_ALREADY_INITIALISED, /**< QProblem has already been initialised. */ +RET_NO_INIT_WITH_STANDARD_SOLVER, /**< Initialisation via extern QP solver is not yet implemented. */ +RET_RESET_FAILED, /**< Reset failed. */ +RET_INIT_FAILED, /**< Initialisation failed. */ +RET_INIT_FAILED_TQ, /**< 30 Initialisation failed due to TQ factorisation. */ +RET_INIT_FAILED_CHOLESKY, /**< Initialisation failed due to Cholesky decomposition. */ +RET_INIT_FAILED_HOTSTART, /**< Initialisation failed! QP could not be solved! */ +RET_INIT_FAILED_INFEASIBILITY, /**< Initial QP could not be solved due to infeasibility! */ +RET_INIT_FAILED_UNBOUNDEDNESS, /**< Initial QP could not be solved due to unboundedness! */ +RET_INIT_SUCCESSFUL, /**< Initialisation done. */ +RET_OBTAINING_WORKINGSET_FAILED, /**< Failed to obtain working set for auxiliary QP. */ +RET_SETUP_WORKINGSET_FAILED, /**< Failed to setup working set for auxiliary QP. */ +RET_SETUP_AUXILIARYQP_FAILED, /**< Failed to setup auxiliary QP for initialised homotopy. */ +RET_NO_EXTERN_SOLVER, /**< No extern QP solver available. */ +RET_QP_UNBOUNDED, /**< 40 QP is unbounded. */ +RET_QP_INFEASIBLE, /**< QP is infeasible. */ +RET_QP_NOT_SOLVED, /**< Problems occured while solving QP with standard solver. */ +RET_QP_SOLVED, /**< QP successfully solved. */ +RET_UNABLE_TO_SOLVE_QP, /**< Problems occured while solving QP. */ +RET_INITIALISATION_STARTED, /**< Starting problem initialisation. */ +RET_HOTSTART_FAILED, /**< Unable to perform homotopy due to internal error. */ +RET_HOTSTART_FAILED_TO_INIT, /**< Unable to initialise problem. */ +RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED, /**< Unable to perform homotopy as previous QP is not solved. */ +RET_ITERATION_STARTED, /**< Iteration... */ +RET_SHIFT_DETERMINATION_FAILED, /**< 50 Determination of shift of the QP data failed. */ +RET_STEPDIRECTION_DETERMINATION_FAILED, /**< Determination of step direction failed. */ +RET_STEPLENGTH_DETERMINATION_FAILED, /**< Determination of step direction failed. */ +RET_OPTIMAL_SOLUTION_FOUND, /**< Optimal solution of neighbouring QP found. */ +RET_HOMOTOPY_STEP_FAILED, /**< Unable to perform homotopy step. */ +RET_HOTSTART_STOPPED_INFEASIBILITY, /**< Premature homotopy termination because QP is infeasible. */ +RET_HOTSTART_STOPPED_UNBOUNDEDNESS, /**< Premature homotopy termination because QP is unbounded. */ +RET_WORKINGSET_UPDATE_FAILED, /**< Unable to update working sets according to initial guesses. */ +RET_MAX_NWSR_REACHED, /**< Maximum number of working set recalculations performed. */ +RET_CONSTRAINTS_NOT_SPECIFIED, /**< Problem does comprise constraints! You also have to specify new constraints' bounds. */ +RET_INVALID_FACTORISATION_FLAG, /**< 60 Invalid factorisation flag. */ +RET_UNABLE_TO_SAVE_QPDATA, /**< Unable to save QP data. */ +RET_STEPDIRECTION_FAILED_TQ, /**< Abnormal termination due to TQ factorisation. */ +RET_STEPDIRECTION_FAILED_CHOLESKY, /**< Abnormal termination due to Cholesky factorisation. */ +RET_CYCLING_DETECTED, /**< Cycling detected. */ +RET_CYCLING_NOT_RESOLVED, /**< Cycling cannot be resolved, QP probably infeasible. */ +RET_CYCLING_RESOLVED, /**< Cycling probably resolved. */ +RET_STEPSIZE, /**< For displaying performed stepsize. */ +RET_STEPSIZE_NONPOSITIVE, /**< For displaying non-positive stepsize. */ +RET_SETUPSUBJECTTOTYPE_FAILED, /**< Setup of SubjectToTypes failed. */ +RET_ADDCONSTRAINT_FAILED, /**< 70 Addition of constraint to working set failed. */ +RET_ADDCONSTRAINT_FAILED_INFEASIBILITY, /**< Addition of constraint to working set failed (due to QP infeasibility). */ +RET_ADDBOUND_FAILED, /**< Addition of bound to working set failed. */ +RET_ADDBOUND_FAILED_INFEASIBILITY, /**< Addition of bound to working set failed (due to QP infeasibility). */ +RET_REMOVECONSTRAINT_FAILED, /**< Removal of constraint from working set failed. */ +RET_REMOVEBOUND_FAILED, /**< Removal of bound from working set failed. */ +RET_REMOVE_FROM_ACTIVESET, /**< Removing from active set... */ +RET_ADD_TO_ACTIVESET, /**< Adding to active set... */ +RET_REMOVE_FROM_ACTIVESET_FAILED, /**< Removing from active set failed. */ +RET_ADD_TO_ACTIVESET_FAILED, /**< Adding to active set failed. */ +RET_CONSTRAINT_ALREADY_ACTIVE, /**< 80 Constraint is already active. */ +RET_ALL_CONSTRAINTS_ACTIVE, /**< All constraints are active, no further constraint can be added. */ +RET_LINEARLY_DEPENDENT, /**< New bound/constraint is linearly dependent. */ +RET_LINEARLY_INDEPENDENT, /**< New bound/constraint is linearly independent. */ +RET_LI_RESOLVED, /**< Linear independence of active contraint matrix successfully resolved. */ +RET_ENSURELI_FAILED, /**< Failed to ensure linear indepence of active contraint matrix. */ +RET_ENSURELI_FAILED_TQ, /**< Abnormal termination due to TQ factorisation. */ +RET_ENSURELI_FAILED_NOINDEX, /**< No index found, QP probably infeasible. */ +RET_ENSURELI_FAILED_CYCLING, /**< Cycling detected, QP probably infeasible. */ +RET_BOUND_ALREADY_ACTIVE, /**< Bound is already active. */ +RET_ALL_BOUNDS_ACTIVE, /**< 90 All bounds are active, no further bound can be added. */ +RET_CONSTRAINT_NOT_ACTIVE, /**< Constraint is not active. */ +RET_BOUND_NOT_ACTIVE, /**< Bound is not active. */ +RET_HESSIAN_NOT_SPD, /**< Projected Hessian matrix not positive definite. */ +RET_MATRIX_SHIFT_FAILED, /**< Unable to update matrices or to transform vectors. */ +RET_MATRIX_FACTORISATION_FAILED, /**< Unable to calculate new matrix factorisations. */ +RET_PRINT_ITERATION_FAILED, /**< Unable to print information on current iteration. */ +RET_NO_GLOBAL_MESSAGE_OUTPUTFILE, /**< No global message output file initialised. */ +/* Utils */ +RET_UNABLE_TO_OPEN_FILE, /**< Unable to open file. */ +RET_UNABLE_TO_WRITE_FILE, /**< Unable to write into file. */ +RET_UNABLE_TO_READ_FILE, /**< 100 Unable to read from file. */ +RET_FILEDATA_INCONSISTENT, /**< File contains inconsistent data. */ +/* SolutionAnalysis */ +RET_NO_SOLUTION, /**< QP solution does not satisfy KKT optimality conditions. */ +RET_INACCURATE_SOLUTION /**< KKT optimality conditions not satisfied to sufficient accuracy. */ +}; + + + +/** This class handles all kinds of messages (errors, warnings, infos) initiated + * by qpOASES modules and stores the correspoding global preferences. + * + * \author Hans Joachim Ferreau (special thanks to Leonard Wirsching) + * \version 1.3embedded + * \date 2007-2008 + */ +class MessageHandling +{ + /* + * INTERNAL DATA STRUCTURES + */ + public: + /** Data structure for entries in global message list. */ + typedef struct { + returnValue key; /**< Global return value. */ + const char* data; /**< Corresponding message. */ + VisibilityStatus globalVisibilityStatus; /**< Determines if message can be printed. + * If this value is set to VS_HIDDEN, no message is printed! */ + } ReturnValueList; + + + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + MessageHandling( ); + + /** Constructor which takes the desired output file. */ + MessageHandling( myFILE* _outputFile /**< Output file. */ + ); + + /** Constructor which takes the desired visibility states. */ + MessageHandling( VisibilityStatus _errorVisibility, /**< Visibility status for error messages. */ + VisibilityStatus _warningVisibility,/**< Visibility status for warning messages. */ + VisibilityStatus _infoVisibility /**< Visibility status for info messages. */ + ); + + /** Constructor which takes the desired output file and desired visibility states. */ + MessageHandling( myFILE* _outputFile, /**< Output file. */ + VisibilityStatus _errorVisibility, /**< Visibility status for error messages. */ + VisibilityStatus _warningVisibility,/**< Visibility status for warning messages. */ + VisibilityStatus _infoVisibility /**< Visibility status for info messages. */ + ); + + /** Copy constructor (deep copy). */ + MessageHandling( const MessageHandling& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~MessageHandling( ); + + /** Assignment operator (deep copy). */ + MessageHandling& operator=( const MessageHandling& rhs /**< Rhs object. */ + ); + + + /** Prints an error message(a simplified macro THROWERROR is also provided). \n + * Errors are definied as abnormal events which cause an immediate termination of the current (sub) function. + * Errors of a sub function should be commented by the calling function by means of a warning message + * (if this error does not cause an error of the calling function, either)! + * \return Error number returned by sub function call + */ + returnValue throwError( + returnValue Enumber, /**< Error number returned by sub function call. */ + const char* additionaltext, /**< Additional error text (0, if none). */ + const char* functionname, /**< Name of function which caused the error. */ + const char* filename, /**< Name of file which caused the error. */ + const unsigned long linenumber, /**< Number of line which caused the error.incompatible binary file */ + VisibilityStatus localVisibilityStatus /**< Determines (locally) if error message can be printed to myStderr. + * If GLOBAL visibility status of the message is set to VS_HIDDEN, + * no message is printed, anyway! */ + ); + + /** Prints a warning message (a simplified macro THROWWARNING is also provided). + * Warnings are definied as abnormal events which does NOT cause an immediate termination of the current (sub) function. + * \return Warning number returned by sub function call + */ + returnValue throwWarning( + returnValue Wnumber, /**< Warning number returned by sub function call. */ + const char* additionaltext, /**< Additional warning text (0, if none). */ + const char* functionname, /**< Name of function which caused the warning. */ + const char* filename, /**< Name of file which caused the warning. */ + const unsigned long linenumber, /**< Number of line which caused the warning. */ + VisibilityStatus localVisibilityStatus /**< Determines (locally) if warning message can be printed to myStderr. + * If GLOBAL visibility status of the message is set to VS_HIDDEN, + * no message is printed, anyway! */ + ); + + /** Prints a info message (a simplified macro THROWINFO is also provided). + * \return Info number returned by sub function call + */ + returnValue throwInfo( + returnValue Inumber, /**< Info number returned by sub function call. */ + const char* additionaltext, /**< Additional warning text (0, if none). */ + const char* functionname, /**< Name of function which submitted the info. */ + const char* filename, /**< Name of file which submitted the info. */ + const unsigned long linenumber, /**< Number of line which submitted the info. */ + VisibilityStatus localVisibilityStatus /**< Determines (locally) if info message can be printed to myStderr. + * If GLOBAL visibility status of the message is set to VS_HIDDEN, + * no message is printed, anyway! */ + ); + + + /** Resets all preferences to default values. + * \return SUCCESSFUL_RETURN */ + returnValue reset( ); + + + /** Prints a complete list of all messages to output file. + * \return SUCCESSFUL_RETURN */ + returnValue listAllMessages( ); + + + /** Returns visibility status for error messages. + * \return Visibility status for error messages. */ + inline VisibilityStatus getErrorVisibilityStatus( ) const; + + /** Returns visibility status for warning messages. + * \return Visibility status for warning messages. */ + inline VisibilityStatus getWarningVisibilityStatus( ) const; + + /** Returns visibility status for info messages. + * \return Visibility status for info messages. */ + inline VisibilityStatus getInfoVisibilityStatus( ) const; + + /** Returns pointer to output file. + * \return Pointer to output file. */ + inline myFILE* getOutputFile( ) const; + + /** Returns error count value. + * \return Error count value. */ + inline int getErrorCount( ) const; + + + /** Changes visibility status for error messages. */ + inline void setErrorVisibilityStatus( VisibilityStatus _errorVisibility /**< New visibility status for error messages. */ + ); + + /** Changes visibility status for warning messages. */ + inline void setWarningVisibilityStatus( VisibilityStatus _warningVisibility /**< New visibility status for warning messages. */ + ); + + /** Changes visibility status for info messages. */ + inline void setInfoVisibilityStatus( VisibilityStatus _infoVisibility /**< New visibility status for info messages. */ + ); + + /** Changes output file for messages. */ + inline void setOutputFile( myFILE* _outputFile /**< New output file for messages. */ + ); + + /** Changes error count. + * \return SUCCESSFUL_RETURN \n + * RET_INVALID_ARGUMENT */ + inline returnValue setErrorCount( int _errorCount /**< New error count value. */ + ); + + /** Return the error code string. */ + static const char* getErrorString(int error); + + /* + * PROTECTED MEMBER FUNCTIONS + */ + protected: + /** Prints a info message to myStderr (auxiliary function). + * \return Error/warning/info number returned by sub function call + */ + returnValue throwMessage( + returnValue RETnumber, /**< Error/warning/info number returned by sub function call. */ + const char* additionaltext, /**< Additional warning text (0, if none). */ + const char* functionname, /**< Name of function which caused the error/warning/info. */ + const char* filename, /**< Name of file which caused the error/warning/info. */ + const unsigned long linenumber, /**< Number of line which caused the error/warning/info. */ + VisibilityStatus localVisibilityStatus, /**< Determines (locally) if info message can be printed to myStderr. + * If GLOBAL visibility status of the message is set to VS_HIDDEN, + * no message is printed, anyway! */ + const char* RETstring /**< Leading string of error/warning/info message. */ + ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + VisibilityStatus errorVisibility; /**< Error messages visible? */ + VisibilityStatus warningVisibility; /**< Warning messages visible? */ + VisibilityStatus infoVisibility; /**< Info messages visible? */ + + myFILE* outputFile; /**< Output file for messages. */ + + int errorCount; /**< Counts number of errors (for nicer output only). */ +}; + + +#ifndef __FUNCTION__ + /** Ensures that __FUNCTION__ macro is defined. */ + #define __FUNCTION__ 0 +#endif + +#ifndef __FILE__ + /** Ensures that __FILE__ macro is defined. */ + #define __FILE__ 0 +#endif + +#ifndef __LINE__ + /** Ensures that __LINE__ macro is defined. */ + #define __LINE__ 0 +#endif + + +/** Short version of throwError with default values, only returnValue is needed */ +#define THROWERROR(retval) ( getGlobalMessageHandler( )->throwError((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) ) + +/** Short version of throwWarning with default values, only returnValue is needed */ +#define THROWWARNING(retval) ( getGlobalMessageHandler( )->throwWarning((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) ) + +/** Short version of throwInfo with default values, only returnValue is needed */ +#define THROWINFO(retval) ( getGlobalMessageHandler( )->throwInfo((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) ) + + +/** Returns a pointer to global message handler. + * \return Pointer to global message handler. + */ +MessageHandling* getGlobalMessageHandler( ); + + +#include + +#endif /* QPOASES_MESSAGEHANDLING_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/QProblem.hpp b/phonelibs/qpoases/INCLUDE/QProblem.hpp new file mode 100644 index 00000000000000..68fc1af9c53a79 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/QProblem.hpp @@ -0,0 +1,666 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/QProblem.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the QProblem class which is able to use the newly + * developed online active set strategy for parametric quadratic programming. + */ + + + +#ifndef QPOASES_QPROBLEM_HPP +#define QPOASES_QPROBLEM_HPP + + +#include +#include +#include + + +/** A class for setting up and solving quadratic programs. The main feature is + * the possibily to use the newly developed online active set strategy for + * parametric quadratic programming. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class QProblem : public QProblemB +{ + /* allow SolutionAnalysis class to access private members */ + friend class SolutionAnalysis; + + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + QProblem( ); + + /** Constructor which takes the QP dimensions only. */ + QProblem( int _nV, /**< Number of variables. */ + int _nC /**< Number of constraints. */ + ); + + /** Copy constructor (deep copy). */ + QProblem( const QProblem& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~QProblem( ); + + /** Assignment operator (deep copy). */ + QProblem& operator=( const QProblem& rhs /**< Rhs object. */ + ); + + + /** Clears all data structures of QProblemB except for QP data. + * \return SUCCESSFUL_RETURN \n + RET_RESET_FAILED */ + returnValue reset( ); + + + /** Initialises a QProblem with given QP data and solves it + * using an initial homotopy with empty working set (at most nWSR iterations). + * \return SUCCESSFUL_RETURN \n + RET_INIT_FAILED \n + RET_INIT_FAILED_CHOLESKY \n + RET_INIT_FAILED_TQ \n + RET_INIT_FAILED_HOTSTART \n + RET_INIT_FAILED_INFEASIBILITY \n + RET_INIT_FAILED_UNBOUNDEDNESS \n + RET_MAX_NWSR_REACHED \n + RET_INVALID_ARGUMENTS \n + RET_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue init( const real_t* const _H, /**< Hessian matrix. */ + const real_t* const _g, /**< Gradient vector. */ + const real_t* const _A, /**< Constraint matrix. */ + const real_t* const _lb, /**< Lower bound vector (on variables). \n + If no lower bounds exist, a NULL pointer can be passed. */ + const real_t* const _ub, /**< Upper bound vector (on variables). \n + If no upper bounds exist, a NULL pointer can be passed. */ + const real_t* const _lbA, /**< Lower constraints' bound vector. \n + If no lower constraints' bounds exist, a NULL pointer can be passed. */ + const real_t* const _ubA, /**< Upper constraints' bound vector. \n + If no lower constraints' bounds exist, a NULL pointer can be passed. */ + int& nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. + Output: Number of performed working set recalculations. */ + const real_t* const yOpt = 0, /**< Initial guess for dual solution vector. */ + real_t* const cputime = 0 /**< Output: CPU time required to initialise QP. */ + ); + + + /** Initialises a QProblem with given QP data and solves it + * using an initial homotopy with empty working set (at most nWSR iterations). + * \return SUCCESSFUL_RETURN \n + RET_INIT_FAILED \n + RET_INIT_FAILED_CHOLESKY \n + RET_INIT_FAILED_TQ \n + RET_INIT_FAILED_HOTSTART \n + RET_INIT_FAILED_INFEASIBILITY \n + RET_INIT_FAILED_UNBOUNDEDNESS \n + RET_MAX_NWSR_REACHED \n + RET_INVALID_ARGUMENTS \n + RET_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue init( const real_t* const _H, /**< Hessian matrix. */ + const real_t* const _R, /**< Cholesky factorization of the Hessian matrix. */ + const real_t* const _g, /**< Gradient vector. */ + const real_t* const _A, /**< Constraint matrix. */ + const real_t* const _lb, /**< Lower bound vector (on variables). \n + If no lower bounds exist, a NULL pointer can be passed. */ + const real_t* const _ub, /**< Upper bound vector (on variables). \n + If no upper bounds exist, a NULL pointer can be passed. */ + const real_t* const _lbA, /**< Lower constraints' bound vector. \n + If no lower constraints' bounds exist, a NULL pointer can be passed. */ + const real_t* const _ubA, /**< Upper constraints' bound vector. \n + If no lower constraints' bounds exist, a NULL pointer can be passed. */ + int& nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. + Output: Number of performed working set recalculations. */ + const real_t* const yOpt = 0, /**< Initial guess for dual solution vector. */ + real_t* const cputime = 0 /**< Output: CPU time required to initialise QP. */ + ); + + + /** Solves QProblem using online active set strategy. + * \return SUCCESSFUL_RETURN \n + RET_MAX_NWSR_REACHED \n + RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n + RET_HOTSTART_FAILED \n + RET_SHIFT_DETERMINATION_FAILED \n + RET_STEPDIRECTION_DETERMINATION_FAILED \n + RET_STEPLENGTH_DETERMINATION_FAILED \n + RET_HOMOTOPY_STEP_FAILED \n + RET_HOTSTART_STOPPED_INFEASIBILITY \n + RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n + RET_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue hotstart( const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ + const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n + If no lower bounds exist, a NULL pointer can be passed. */ + const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n + If no upper bounds exist, a NULL pointer can be passed. */ + const real_t* const lbA_new, /**< Lower constraints' bounds of neighbouring QP to be solved. \n + If no lower constraints' bounds exist, a NULL pointer can be passed. */ + const real_t* const ubA_new, /**< Upper constraints' bounds of neighbouring QP to be solved. \n + If no upper constraints' bounds exist, a NULL pointer can be passed. */ + int& nWSR, /**< Input: Maximum number of working set recalculations; \n + Output: Number of performed working set recalculations. */ + real_t* const cputime /**< Output: CPU time required to solve QP (or to perform nWSR iterations). */ + ); + + + /** Returns constraint matrix of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getA( real_t* const _A /**< Array of appropriate dimension for copying constraint matrix.*/ + ) const; + + /** Returns a single row of constraint matrix of the QP (deep copy). + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue getA( int number, /**< Number of entry to be returned. */ + real_t* const row /**< Array of appropriate dimension for copying (number)th constraint. */ + ) const; + + /** Returns lower constraints' bound vector of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getLBA( real_t* const _lbA /**< Array of appropriate dimension for copying lower constraints' bound vector.*/ + ) const; + + /** Returns single entry of lower constraints' bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue getLBA( int number, /**< Number of entry to be returned. */ + real_t& value /**< Output: lbA[number].*/ + ) const; + + /** Returns upper constraints' bound vector of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getUBA( real_t* const _ubA /**< Array of appropriate dimension for copying upper constraints' bound vector.*/ + ) const; + + /** Returns single entry of upper constraints' bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue getUBA( int number, /**< Number of entry to be returned. */ + real_t& value /**< Output: ubA[number].*/ + ) const; + + + /** Returns current constraints object of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getConstraints( Constraints* const _constraints /** Output: Constraints object. */ + ) const; + + + /** Returns the number of constraints. + * \return Number of constraints. */ + inline int getNC( ) const; + + /** Returns the number of (implicitly defined) equality constraints. + * \return Number of (implicitly defined) equality constraints. */ + inline int getNEC( ) const; + + /** Returns the number of active constraints. + * \return Number of active constraints. */ + inline int getNAC( ); + + /** Returns the number of inactive constraints. + * \return Number of inactive constraints. */ + inline int getNIAC( ); + + /** Returns the dimension of null space. + * \return Dimension of null space. */ + int getNZ( ); + + + /** Returns the dual solution vector (deep copy). + * \return SUCCESSFUL_RETURN \n + RET_QP_NOT_SOLVED */ + returnValue getDualSolution( real_t* const yOpt /**< Output: Dual solution vector (if QP has been solved). */ + ) const; + + + /* + * PROTECTED MEMBER FUNCTIONS + */ + protected: + /** Determines type of constraints and bounds (i.e. implicitly fixed, unbounded etc.). + * \return SUCCESSFUL_RETURN \n + RET_SETUPSUBJECTTOTYPE_FAILED */ + returnValue setupSubjectToType( ); + + /** Computes the Cholesky decomposition R of the projected Hessian (i.e. R^T*R = Z^T*H*Z). + * \return SUCCESSFUL_RETURN \n + * RET_INDEXLIST_CORRUPTED */ + returnValue setupCholeskyDecompositionProjected( ); + + /** Initialises TQ factorisation of A (i.e. A*Q = [0 T]) if NO constraint is active. + * \return SUCCESSFUL_RETURN \n + RET_INDEXLIST_CORRUPTED */ + returnValue setupTQfactorisation( ); + + + /** Solves a QProblem whose QP data is assumed to be stored in the member variables. + * A guess for its primal/dual optimal solution vectors and the corresponding + * working sets of bounds and constraints can be provided. + * \return SUCCESSFUL_RETURN \n + RET_INIT_FAILED \n + RET_INIT_FAILED_CHOLESKY \n + RET_INIT_FAILED_TQ \n + RET_INIT_FAILED_HOTSTART \n + RET_INIT_FAILED_INFEASIBILITY \n + RET_INIT_FAILED_UNBOUNDEDNESS \n + RET_MAX_NWSR_REACHED */ + returnValue solveInitialQP( const real_t* const xOpt, /**< Optimal primal solution vector. + * A NULL pointer can be passed. */ + const real_t* const yOpt, /**< Optimal dual solution vector. + * A NULL pointer can be passed. */ + const Bounds* const guessedBounds, /**< Guessed working set of bounds for solution (xOpt,yOpt). + * A NULL pointer can be passed. */ + const Constraints* const guessedConstraints, /**< Optimal working set of constraints for solution (xOpt,yOpt). + * A NULL pointer can be passed. */ + int& nWSR, /**< Input: Maximum number of working set recalculations; \n + * Output: Number of performed working set recalculations. */ + real_t* const cputime /**< Output: CPU time required to solve QP (or to perform nWSR iterations). */ + ); + + /** Obtains the desired working set for the auxiliary initial QP in + * accordance with the user specifications + * (assumes that member AX has already been initialised!) + * \return SUCCESSFUL_RETURN \n + RET_OBTAINING_WORKINGSET_FAILED \n + RET_INVALID_ARGUMENTS */ + returnValue obtainAuxiliaryWorkingSet( const real_t* const xOpt, /**< Optimal primal solution vector. + * If a NULL pointer is passed, all entries are assumed to be zero. */ + const real_t* const yOpt, /**< Optimal dual solution vector. + * If a NULL pointer is passed, all entries are assumed to be zero. */ + const Bounds* const guessedBounds, /**< Guessed working set of bounds for solution (xOpt,yOpt). */ + const Constraints* const guessedConstraints, /**< Guessed working set for solution (xOpt,yOpt). */ + Bounds* auxiliaryBounds, /**< Input: Allocated bound object. \n + * Ouput: Working set of constraints for auxiliary QP. */ + Constraints* auxiliaryConstraints /**< Input: Allocated bound object. \n + * Ouput: Working set for auxiliary QP. */ + ) const; + + /** Setups bound and constraints data structures according to auxiliaryBounds/Constraints. + * (If the working set shall be setup afresh, make sure that + * bounds and constraints data structure have been resetted + * and the TQ factorisation has been initialised!) + * \return SUCCESSFUL_RETURN \n + RET_SETUP_WORKINGSET_FAILED \n + RET_INVALID_ARGUMENTS \n + RET_UNKNOWN BUG */ + returnValue setupAuxiliaryWorkingSet( const Bounds* const auxiliaryBounds, /**< Working set of bounds for auxiliary QP. */ + const Constraints* const auxiliaryConstraints, /**< Working set of constraints for auxiliary QP. */ + BooleanType setupAfresh /**< Flag indicating if given working set shall be + * setup afresh or by updating the current one. */ + ); + + /** Setups the optimal primal/dual solution of the auxiliary initial QP. + * \return SUCCESSFUL_RETURN */ + returnValue setupAuxiliaryQPsolution( const real_t* const xOpt, /**< Optimal primal solution vector. + * If a NULL pointer is passed, all entries are set to zero. */ + const real_t* const yOpt /**< Optimal dual solution vector. + * If a NULL pointer is passed, all entries are set to zero. */ + ); + + /** Setups gradient of the auxiliary initial QP for given + * optimal primal/dual solution and given initial working set + * (assumes that members X, Y and BOUNDS, CONSTRAINTS have already been initialised!). + * \return SUCCESSFUL_RETURN */ + returnValue setupAuxiliaryQPgradient( ); + + /** Setups (constraints') bounds of the auxiliary initial QP for given + * optimal primal/dual solution and given initial working set + * (assumes that members X, Y and BOUNDS, CONSTRAINTS have already been initialised!). + * \return SUCCESSFUL_RETURN \n + RET_UNKNOWN BUG */ + returnValue setupAuxiliaryQPbounds( const Bounds* const auxiliaryBounds, /**< Working set of bounds for auxiliary QP. */ + const Constraints* const auxiliaryConstraints, /**< Working set of constraints for auxiliary QP. */ + BooleanType useRelaxation /**< Flag indicating if inactive (constraints') bounds shall be relaxed. */ + ); + + + /** Adds a constraint to active set. + * \return SUCCESSFUL_RETURN \n + RET_ADDCONSTRAINT_FAILED \n + RET_ADDCONSTRAINT_FAILED_INFEASIBILITY \n + RET_ENSURELI_FAILED */ + returnValue addConstraint( int number, /**< Number of constraint to be added to active set. */ + SubjectToStatus C_status, /**< Status of new active constraint. */ + BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ + ); + + /** Checks if new active constraint to be added is linearly dependent from + * from row of the active constraints matrix. + * \return RET_LINEARLY_DEPENDENT \n + RET_LINEARLY_INDEPENDENT \n + RET_INDEXLIST_CORRUPTED */ + returnValue addConstraint_checkLI( int number /**< Number of constraint to be added to active set. */ + ); + + /** Ensures linear independence of constraint matrix when a new constraint is added. + * To this end a bound or constraint is removed simultaneously if necessary. + * \return SUCCESSFUL_RETURN \n + RET_LI_RESOLVED \n + RET_ENSURELI_FAILED \n + RET_ENSURELI_FAILED_TQ \n + RET_ENSURELI_FAILED_NOINDEX \n + RET_REMOVE_FROM_ACTIVESET */ + returnValue addConstraint_ensureLI( int number, /**< Number of constraint to be added to active set. */ + SubjectToStatus C_status /**< Status of new active bound. */ + ); + + /** Adds a bound to active set. + * \return SUCCESSFUL_RETURN \n + RET_ADDBOUND_FAILED \n + RET_ADDBOUND_FAILED_INFEASIBILITY \n + RET_ENSURELI_FAILED */ + returnValue addBound( int number, /**< Number of bound to be added to active set. */ + SubjectToStatus B_status, /**< Status of new active bound. */ + BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ + ); + + /** Checks if new active bound to be added is linearly dependent from + * from row of the active constraints matrix. + * \return RET_LINEARLY_DEPENDENT \n + RET_LINEARLY_INDEPENDENT */ + returnValue addBound_checkLI( int number /**< Number of bound to be added to active set. */ + ); + + /** Ensures linear independence of constraint matrix when a new bound is added. + * To this end a bound or constraint is removed simultaneously if necessary. + * \return SUCCESSFUL_RETURN \n + RET_LI_RESOLVED \n + RET_ENSURELI_FAILED \n + RET_ENSURELI_FAILED_TQ \n + RET_ENSURELI_FAILED_NOINDEX \n + RET_REMOVE_FROM_ACTIVESET */ + returnValue addBound_ensureLI( int number, /**< Number of bound to be added to active set. */ + SubjectToStatus B_status /**< Status of new active bound. */ + ); + + /** Removes a constraint from active set. + * \return SUCCESSFUL_RETURN \n + RET_CONSTRAINT_NOT_ACTIVE \n + RET_REMOVECONSTRAINT_FAILED \n + RET_HESSIAN_NOT_SPD */ + returnValue removeConstraint( int number, /**< Number of constraint to be removed from active set. */ + BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ + ); + + /** Removes a bounds from active set. + * \return SUCCESSFUL_RETURN \n + RET_BOUND_NOT_ACTIVE \n + RET_HESSIAN_NOT_SPD \n + RET_REMOVEBOUND_FAILED */ + returnValue removeBound( int number, /**< Number of bound to be removed from active set. */ + BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ + ); + + + /** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. + * \return SUCCESSFUL_RETURN \n + RET_DIV_BY_ZERO */ + returnValue backsolveR( const real_t* const b, /**< Right hand side vector. */ + BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ + real_t* const a /**< Output: Solution vector */ + ); + + /** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n + * Special variant for the case that this function is called from within "removeBound()". + * \return SUCCESSFUL_RETURN \n + RET_DIV_BY_ZERO */ + returnValue backsolveR( const real_t* const b, /**< Right hand side vector. */ + BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ + BooleanType removingBound, /**< Indicates if function is called from "removeBound()". */ + real_t* const a /**< Output: Solution vector */ + ); + + + /** Solves the system Ta = b or T^Ta = b where T is a reverse upper triangular matrix. + * \return SUCCESSFUL_RETURN \n + RET_DIV_BY_ZERO */ + returnValue backsolveT( const real_t* const b, /**< Right hand side vector. */ + BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ + real_t* const a /**< Output: Solution vector */ + ); + + + /** Determines step direction of the shift of the QP data. + * \return SUCCESSFUL_RETURN */ + returnValue hotstart_determineDataShift(const int* const FX_idx, /**< Index array of fixed variables. */ + const int* const AC_idx, /**< Index array of active constraints. */ + const real_t* const g_new, /**< New gradient vector. */ + const real_t* const lbA_new,/**< New lower constraints' bounds. */ + const real_t* const ubA_new,/**< New upper constraints' bounds. */ + const real_t* const lb_new, /**< New lower bounds. */ + const real_t* const ub_new, /**< New upper bounds. */ + real_t* const delta_g, /**< Output: Step direction of gradient vector. */ + real_t* const delta_lbA, /**< Output: Step direction of lower constraints' bounds. */ + real_t* const delta_ubA, /**< Output: Step direction of upper constraints' bounds. */ + real_t* const delta_lb, /**< Output: Step direction of lower bounds. */ + real_t* const delta_ub, /**< Output: Step direction of upper bounds. */ + BooleanType& Delta_bC_isZero,/**< Output: Indicates if active constraints' bounds are to be shifted. */ + BooleanType& Delta_bB_isZero/**< Output: Indicates if active bounds are to be shifted. */ + ); + + /** Determines step direction of the homotopy path. + * \return SUCCESSFUL_RETURN \n + RET_STEPDIRECTION_FAILED_TQ \n + RET_STEPDIRECTION_FAILED_CHOLESKY */ + returnValue hotstart_determineStepDirection(const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + const int* const AC_idx, /**< Index array of active constraints. */ + const real_t* const delta_g, /**< Step direction of gradient vector. */ + const real_t* const delta_lbA, /**< Step direction of lower constraints' bounds. */ + const real_t* const delta_ubA, /**< Step direction of upper constraints' bounds. */ + const real_t* const delta_lb, /**< Step direction of lower bounds. */ + const real_t* const delta_ub, /**< Step direction of upper bounds. */ + BooleanType Delta_bC_isZero, /**< Indicates if active constraints' bounds are to be shifted. */ + BooleanType Delta_bB_isZero, /**< Indicates if active bounds are to be shifted. */ + real_t* const delta_xFX, /**< Output: Primal homotopy step direction of fixed variables. */ + real_t* const delta_xFR, /**< Output: Primal homotopy step direction of free variables. */ + real_t* const delta_yAC, /**< Output: Dual homotopy step direction of active constraints' multiplier. */ + real_t* const delta_yFX /**< Output: Dual homotopy step direction of fixed variables' multiplier. */ + ); + + /** Determines the maximum possible step length along the homotopy path. + * \return SUCCESSFUL_RETURN */ + returnValue hotstart_determineStepLength( const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + const int* const AC_idx, /**< Index array of active constraints. */ + const int* const IAC_idx, /**< Index array of inactive constraints. */ + const real_t* const delta_lbA, /**< Step direction of lower constraints' bounds. */ + const real_t* const delta_ubA, /**< Step direction of upper constraints' bounds. */ + const real_t* const delta_lb, /**< Step direction of lower bounds. */ + const real_t* const delta_ub, /**< Step direction of upper bounds. */ + const real_t* const delta_xFX, /**< Primal homotopy step direction of fixed variables. */ + const real_t* const delta_xFR, /**< Primal homotopy step direction of free variables. */ + const real_t* const delta_yAC, /**< Dual homotopy step direction of active constraints' multiplier. */ + const real_t* const delta_yFX, /**< Dual homotopy step direction of fixed variables' multiplier. */ + real_t* const delta_Ax, /**< Output: Step in vector Ax. */ + int& BC_idx, /**< Output: Index of blocking constraint. */ + SubjectToStatus& BC_status, /**< Output: Status of blocking constraint. */ + BooleanType& BC_isBound /**< Output: Indicates if blocking constraint is a bound. */ + ); + + /** Performs a step along the homotopy path (and updates active set). + * \return SUCCESSFUL_RETURN \n + RET_OPTIMAL_SOLUTION_FOUND \n + RET_REMOVE_FROM_ACTIVESET_FAILED \n + RET_ADD_TO_ACTIVESET_FAILED \n + RET_QP_INFEASIBLE */ + returnValue hotstart_performStep( const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + const int* const AC_idx, /**< Index array of active constraints. */ + const int* const IAC_idx, /**< Index array of inactive constraints. */ + const real_t* const delta_g, /**< Step direction of gradient vector. */ + const real_t* const delta_lbA, /**< Step direction of lower constraints' bounds. */ + const real_t* const delta_ubA, /**< Step direction of upper constraints' bounds. */ + const real_t* const delta_lb, /**< Step direction of lower bounds. */ + const real_t* const delta_ub, /**< Step direction of upper bounds. */ + const real_t* const delta_xFX, /**< Primal homotopy step direction of fixed variables. */ + const real_t* const delta_xFR, /**< Primal homotopy step direction of free variables. */ + const real_t* const delta_yAC, /**< Dual homotopy step direction of active constraints' multiplier. */ + const real_t* const delta_yFX, /**< Dual homotopy step direction of fixed variables' multiplier. */ + const real_t* const delta_Ax, /**< Step in vector Ax. */ + int BC_idx, /**< Index of blocking constraint. */ + SubjectToStatus BC_status, /**< Status of blocking constraint. */ + BooleanType BC_isBound /**< Indicates if blocking constraint is a bound. */ + ); + + + /** Checks if lower/upper (constraints') bounds remain consistent + * (i.e. if lb <= ub and lbA <= ubA ) during the current step. + * \return BT_TRUE iff (constraints") bounds remain consistent + */ + BooleanType areBoundsConsistent( const real_t* const delta_lb, /**< Step direction of lower bounds. */ + const real_t* const delta_ub, /**< Step direction of upper bounds. */ + const real_t* const delta_lbA, /**< Step direction of lower constraints' bounds. */ + const real_t* const delta_ubA /**< Step direction of upper constraints' bounds. */ + ) const; + + + /** Setups internal QP data. + * \return SUCCESSFUL_RETURN \n + RET_INVALID_ARGUMENTS */ + returnValue setupQPdata( const real_t* const _H, /**< Hessian matrix. */ + const real_t* const _R, /**< Cholesky factorization of the Hessian matrix. */ + const real_t* const _g, /**< Gradient vector. */ + const real_t* const _A, /**< Constraint matrix. */ + const real_t* const _lb, /**< Lower bound vector (on variables). \n + If no lower bounds exist, a NULL pointer can be passed. */ + const real_t* const _ub, /**< Upper bound vector (on variables). \n + If no upper bounds exist, a NULL pointer can be passed. */ + const real_t* const _lbA, /**< Lower constraints' bound vector. \n + If no lower constraints' bounds exist, a NULL pointer can be passed. */ + const real_t* const _ubA /**< Upper constraints' bound vector. \n + If no lower constraints' bounds exist, a NULL pointer can be passed. */ + ); + + + #ifdef PC_DEBUG /* Define print functions only for debugging! */ + + /** Prints concise information on the current iteration. + * \return SUCCESSFUL_RETURN \n */ + returnValue printIteration( int iteration, /**< Number of current iteration. */ + int BC_idx, /**< Index of blocking constraint. */ + SubjectToStatus BC_status, /**< Status of blocking constraint. */ + BooleanType BC_isBound /**< Indicates if blocking constraint is a bound. */ + ); + + /** Prints concise information on the current iteration. + * NOTE: ONLY DEFINED FOR SUPPRESSING A COMPILER WARNING!! + * \return SUCCESSFUL_RETURN \n */ + returnValue printIteration( int iteration, /**< Number of current iteration. */ + int BC_idx, /**< Index of blocking bound. */ + SubjectToStatus BC_status /**< Status of blocking bound. */ + ); + + #endif /* PC_DEBUG */ + + + /** Determines the maximum violation of the KKT optimality conditions + * of the current iterate within the QProblem object. + * \return SUCCESSFUL_RETURN \n + * RET_INACCURATE_SOLUTION \n + * RET_NO_SOLUTION */ + returnValue checkKKTconditions( ); + + + /** Sets constraint matrix of the QP. \n + (Remark: Also internal vector Ax is recomputed!) + * \return SUCCESSFUL_RETURN */ + inline returnValue setA( const real_t* const A_new /**< New constraint matrix (with correct dimension!). */ + ); + + /** Changes single row of constraint matrix of the QP. \n + (Remark: Also correponding component of internal vector Ax is recomputed!) + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue setA( int number, /**< Number of row to be changed. */ + const real_t* const value /**< New (number)th constraint (with correct dimension!). */ + ); + + + /** Sets constraints' lower bound vector of the QP. + * \return SUCCESSFUL_RETURN */ + inline returnValue setLBA( const real_t* const lbA_new /**< New constraints' lower bound vector (with correct dimension!). */ + ); + + /** Changes single entry of lower constraints' bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue setLBA( int number, /**< Number of entry to be changed. */ + real_t value /**< New value for entry of lower constraints' bound vector (with correct dimension!). */ + ); + + /** Sets constraints' upper bound vector of the QP. + * \return SUCCESSFUL_RETURN */ + inline returnValue setUBA( const real_t* const ubA_new /**< New constraints' upper bound vector (with correct dimension!). */ + ); + + /** Changes single entry of upper constraints' bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue setUBA( int number, /**< Number of entry to be changed. */ + real_t value /**< New value for entry of upper constraints' bound vector (with correct dimension!). */ + ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + real_t A[NCMAX_ALLOC*NVMAX]; /**< Constraint matrix. */ + real_t lbA[NCMAX_ALLOC]; /**< Lower constraints' bound vector. */ + real_t ubA[NCMAX_ALLOC]; /**< Upper constraints' bound vector. */ + + Constraints constraints; /**< Data structure for problem's constraints. */ + + real_t T[NVMAX*NVMAX]; /**< Reverse triangular matrix, A = [0 T]*Q'. */ + real_t Q[NVMAX*NVMAX]; /**< Orthonormal quadratic matrix, A = [0 T]*Q'. */ + int sizeT; /**< Matrix T is stored in a (sizeT x sizeT) array. */ + + real_t Ax[NCMAX_ALLOC]; /**< Stores the current product A*x (for increased efficiency only). */ + + CyclingManager cyclingManager; /**< Data structure for storing (possible) cycling information (NOT YET IMPLEMENTED!). */ +}; + + +#include + +#endif /* QPOASES_QPROBLEM_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/QProblemB.hpp b/phonelibs/qpoases/INCLUDE/QProblemB.hpp new file mode 100644 index 00000000000000..8b3acb82bddab4 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/QProblemB.hpp @@ -0,0 +1,628 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/QProblemB.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the QProblemB class which is able to use the newly + * developed online active set strategy for parametric quadratic programming + * for problems with (simple) bounds only. + */ + + + +#ifndef QPOASES_QPROBLEMB_HPP +#define QPOASES_QPROBLEMB_HPP + + +#include + + + +class SolutionAnalysis; + +/** Class for setting up and solving quadratic programs with (simple) bounds only. + * The main feature is the possibily to use the newly developed online active set strategy + * for parametric quadratic programming. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class QProblemB +{ + /* allow SolutionAnalysis class to access private members */ + friend class SolutionAnalysis; + + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + QProblemB( ); + + /** Constructor which takes the QP dimension only. */ + QProblemB( int _nV /**< Number of variables. */ + ); + + /** Copy constructor (deep copy). */ + QProblemB( const QProblemB& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~QProblemB( ); + + /** Assignment operator (deep copy). */ + QProblemB& operator=( const QProblemB& rhs /**< Rhs object. */ + ); + + + /** Clears all data structures of QProblemB except for QP data. + * \return SUCCESSFUL_RETURN \n + RET_RESET_FAILED */ + returnValue reset( ); + + + /** Initialises a QProblemB with given QP data and solves it + * using an initial homotopy with empty working set (at most nWSR iterations). + * \return SUCCESSFUL_RETURN \n + RET_INIT_FAILED \n + RET_INIT_FAILED_CHOLESKY \n + RET_INIT_FAILED_HOTSTART \n + RET_INIT_FAILED_INFEASIBILITY \n + RET_INIT_FAILED_UNBOUNDEDNESS \n + RET_MAX_NWSR_REACHED \n + RET_INVALID_ARGUMENTS \n + RET_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue init( const real_t* const _H, /**< Hessian matrix. */ + const real_t* const _g, /**< Gradient vector. */ + const real_t* const _lb, /**< Lower bounds (on variables). \n + If no lower bounds exist, a NULL pointer can be passed. */ + const real_t* const _ub, /**< Upper bounds (on variables). \n + If no upper bounds exist, a NULL pointer can be passed. */ + int& nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n + Output: Number of performed working set recalculations. */ + const real_t* const yOpt = 0, /**< Initial guess for dual solution vector. */ + real_t* const cputime = 0 /**< Output: CPU time required to initialise QP. */ + ); + + + /** Initialises a QProblemB with given QP data and solves it + * using an initial homotopy with empty working set (at most nWSR iterations). + * \return SUCCESSFUL_RETURN \n + RET_INIT_FAILED \n + RET_INIT_FAILED_CHOLESKY \n + RET_INIT_FAILED_HOTSTART \n + RET_INIT_FAILED_INFEASIBILITY \n + RET_INIT_FAILED_UNBOUNDEDNESS \n + RET_MAX_NWSR_REACHED \n + RET_INVALID_ARGUMENTS \n + RET_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue init( const real_t* const _H, /**< Hessian matrix. */ + const real_t* const _R, /**< Cholesky factorization of the Hessian matrix. */ + const real_t* const _g, /**< Gradient vector. */ + const real_t* const _lb, /**< Lower bounds (on variables). \n + If no lower bounds exist, a NULL pointer can be passed. */ + const real_t* const _ub, /**< Upper bounds (on variables). \n + If no upper bounds exist, a NULL pointer can be passed. */ + int& nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n + Output: Number of performed working set recalculations. */ + const real_t* const yOpt = 0, /**< Initial guess for dual solution vector. */ + real_t* const cputime = 0 /**< Output: CPU time required to initialise QP. */ + ); + + + /** Solves an initialised QProblemB using online active set strategy. + * \return SUCCESSFUL_RETURN \n + RET_MAX_NWSR_REACHED \n + RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n + RET_HOTSTART_FAILED \n + RET_SHIFT_DETERMINATION_FAILED \n + RET_STEPDIRECTION_DETERMINATION_FAILED \n + RET_STEPLENGTH_DETERMINATION_FAILED \n + RET_HOMOTOPY_STEP_FAILED \n + RET_HOTSTART_STOPPED_INFEASIBILITY \n + RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n + RET_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue hotstart( const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ + const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n + If no lower bounds exist, a NULL pointer can be passed. */ + const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n + If no upper bounds exist, a NULL pointer can be passed. */ + int& nWSR, /**< Input: Maximum number of working set recalculations; \n + Output: Number of performed working set recalculations. */ + real_t* const cputime /**< Output: CPU time required to solve QP (or to perform nWSR iterations). */ + ); + + + /** Returns Hessian matrix of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getH( real_t* const _H /**< Array of appropriate dimension for copying Hessian matrix.*/ + ) const; + + /** Returns gradient vector of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getG( real_t* const _g /**< Array of appropriate dimension for copying gradient vector.*/ + ) const; + + /** Returns lower bound vector of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getLB( real_t* const _lb /**< Array of appropriate dimension for copying lower bound vector.*/ + ) const; + + /** Returns single entry of lower bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue getLB( int number, /**< Number of entry to be returned. */ + real_t& value /**< Output: lb[number].*/ + ) const; + + /** Returns upper bound vector of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getUB( real_t* const _ub /**< Array of appropriate dimension for copying upper bound vector.*/ + ) const; + + /** Returns single entry of upper bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue getUB( int number, /**< Number of entry to be returned. */ + real_t& value /**< Output: ub[number].*/ + ) const; + + + /** Returns current bounds object of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getBounds( Bounds* const _bounds /** Output: Bounds object. */ + ) const; + + + /** Returns the number of variables. + * \return Number of variables. */ + inline int getNV( ) const; + + /** Returns the number of free variables. + * \return Number of free variables. */ + inline int getNFR( ); + + /** Returns the number of fixed variables. + * \return Number of fixed variables. */ + inline int getNFX( ); + + /** Returns the number of implicitly fixed variables. + * \return Number of implicitly fixed variables. */ + inline int getNFV( ) const; + + /** Returns the dimension of null space. + * \return Dimension of null space. */ + int getNZ( ); + + + /** Returns the optimal objective function value. + * \return finite value: Optimal objective function value (QP was solved) \n + +infinity: QP was not yet solved */ + real_t getObjVal( ) const; + + /** Returns the objective function value at an arbitrary point x. + * \return Objective function value at point x */ + real_t getObjVal( const real_t* const _x /**< Point at which the objective function shall be evaluated. */ + ) const; + + /** Returns the primal solution vector. + * \return SUCCESSFUL_RETURN \n + RET_QP_NOT_SOLVED */ + returnValue getPrimalSolution( real_t* const xOpt /**< Output: Primal solution vector (if QP has been solved). */ + ) const; + + /** Returns the dual solution vector. + * \return SUCCESSFUL_RETURN \n + RET_QP_NOT_SOLVED */ + returnValue getDualSolution( real_t* const yOpt /**< Output: Dual solution vector (if QP has been solved). */ + ) const; + + + /** Returns status of the solution process. + * \return Status of solution process. */ + inline QProblemStatus getStatus( ) const; + + + /** Returns if the QProblem object is initialised. + * \return BT_TRUE: QProblemB initialised \n + BT_FALSE: QProblemB not initialised */ + inline BooleanType isInitialised( ) const; + + /** Returns if the QP has been solved. + * \return BT_TRUE: QProblemB solved \n + BT_FALSE: QProblemB not solved */ + inline BooleanType isSolved( ) const; + + /** Returns if the QP is infeasible. + * \return BT_TRUE: QP infeasible \n + BT_FALSE: QP feasible (or not known to be infeasible!) */ + inline BooleanType isInfeasible( ) const; + + /** Returns if the QP is unbounded. + * \return BT_TRUE: QP unbounded \n + BT_FALSE: QP unbounded (or not known to be unbounded!) */ + inline BooleanType isUnbounded( ) const; + + + /** Returns the print level. + * \return Print level. */ + inline PrintLevel getPrintLevel( ) const; + + /** Changes the print level. + * \return SUCCESSFUL_RETURN */ + returnValue setPrintLevel( PrintLevel _printlevel /**< New print level. */ + ); + + + /** Returns Hessian type flag (type is not determined due to this call!). + * \return Hessian type. */ + inline HessianType getHessianType( ) const; + + /** Changes the print level. + * \return SUCCESSFUL_RETURN */ + inline returnValue setHessianType( HessianType _hessianType /**< New Hessian type. */ + ); + + + /* + * PROTECTED MEMBER FUNCTIONS + */ + protected: + /** Checks if Hessian happens to be the identity matrix, + * and sets corresponding status flag (otherwise the flag remains unaltered!). + * \return SUCCESSFUL_RETURN */ + returnValue checkForIdentityHessian( ); + + /** Determines type of constraints and bounds (i.e. implicitly fixed, unbounded etc.). + * \return SUCCESSFUL_RETURN \n + RET_SETUPSUBJECTTOTYPE_FAILED */ + returnValue setupSubjectToType( ); + + /** Computes the Cholesky decomposition R of the (simply projected) Hessian (i.e. R^T*R = Z^T*H*Z). + * It only works in the case where Z is a simple projection matrix! + * \return SUCCESSFUL_RETURN \n + * RET_INDEXLIST_CORRUPTED */ + returnValue setupCholeskyDecomposition( ); + + + /** Solves a QProblemB whose QP data is assumed to be stored in the member variables. + * A guess for its primal/dual optimal solution vectors and the corresponding + * optimal working set can be provided. + * \return SUCCESSFUL_RETURN \n + RET_INIT_FAILED \n + RET_INIT_FAILED_CHOLESKY \n + RET_INIT_FAILED_HOTSTART \n + RET_INIT_FAILED_INFEASIBILITY \n + RET_INIT_FAILED_UNBOUNDEDNESS \n + RET_MAX_NWSR_REACHED */ + returnValue solveInitialQP( const real_t* const xOpt, /**< Optimal primal solution vector. + * A NULL pointer can be passed. */ + const real_t* const yOpt, /**< Optimal dual solution vector. + * A NULL pointer can be passed. */ + const Bounds* const guessedBounds, /**< Guessed working set for solution (xOpt,yOpt). + * A NULL pointer can be passed. */ + int& nWSR, /**< Input: Maximum number of working set recalculations; \n + * Output: Number of performed working set recalculations. */ + real_t* const cputime /**< Output: CPU time required to solve QP (or to perform nWSR iterations). */ + ); + + + /** Obtains the desired working set for the auxiliary initial QP in + * accordance with the user specifications + * \return SUCCESSFUL_RETURN \n + RET_OBTAINING_WORKINGSET_FAILED \n + RET_INVALID_ARGUMENTS */ + returnValue obtainAuxiliaryWorkingSet( const real_t* const xOpt, /**< Optimal primal solution vector. + * If a NULL pointer is passed, all entries are assumed to be zero. */ + const real_t* const yOpt, /**< Optimal dual solution vector. + * If a NULL pointer is passed, all entries are assumed to be zero. */ + const Bounds* const guessedBounds, /**< Guessed working set for solution (xOpt,yOpt). */ + Bounds* auxiliaryBounds /**< Input: Allocated bound object. \n + * Ouput: Working set for auxiliary QP. */ + ) const; + + /** Setups bound data structure according to auxiliaryBounds. + * (If the working set shall be setup afresh, make sure that + * bounds data structure has been resetted!) + * \return SUCCESSFUL_RETURN \n + RET_SETUP_WORKINGSET_FAILED \n + RET_INVALID_ARGUMENTS \n + RET_UNKNOWN BUG */ + returnValue setupAuxiliaryWorkingSet( const Bounds* const auxiliaryBounds, /**< Working set for auxiliary QP. */ + BooleanType setupAfresh /**< Flag indicating if given working set shall be + * setup afresh or by updating the current one. */ + ); + + /** Setups the optimal primal/dual solution of the auxiliary initial QP. + * \return SUCCESSFUL_RETURN */ + returnValue setupAuxiliaryQPsolution( const real_t* const xOpt, /**< Optimal primal solution vector. + * If a NULL pointer is passed, all entries are set to zero. */ + const real_t* const yOpt /**< Optimal dual solution vector. + * If a NULL pointer is passed, all entries are set to zero. */ + ); + + /** Setups gradient of the auxiliary initial QP for given + * optimal primal/dual solution and given initial working set + * (assumes that members X, Y and BOUNDS have already been initialised!). + * \return SUCCESSFUL_RETURN */ + returnValue setupAuxiliaryQPgradient( ); + + /** Setups bounds of the auxiliary initial QP for given + * optimal primal/dual solution and given initial working set + * (assumes that members X, Y and BOUNDS have already been initialised!). + * \return SUCCESSFUL_RETURN \n + RET_UNKNOWN BUG */ + returnValue setupAuxiliaryQPbounds( BooleanType useRelaxation /**< Flag indicating if inactive bounds shall be relaxed. */ + ); + + + /** Adds a bound to active set (specialised version for the case where no constraints exist). + * \return SUCCESSFUL_RETURN \n + RET_ADDBOUND_FAILED */ + returnValue addBound( int number, /**< Number of bound to be added to active set. */ + SubjectToStatus B_status, /**< Status of new active bound. */ + BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ + ); + + /** Removes a bounds from active set (specialised version for the case where no constraints exist). + * \return SUCCESSFUL_RETURN \n + RET_HESSIAN_NOT_SPD \n + RET_REMOVEBOUND_FAILED */ + returnValue removeBound( int number, /**< Number of bound to be removed from active set. */ + BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ + ); + + + /** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. + * \return SUCCESSFUL_RETURN \n + RET_DIV_BY_ZERO */ + returnValue backsolveR( const real_t* const b, /**< Right hand side vector. */ + BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ + real_t* const a /**< Output: Solution vector */ + ); + + /** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n + * Special variant for the case that this function is called from within "removeBound()". + * \return SUCCESSFUL_RETURN \n + RET_DIV_BY_ZERO */ + returnValue backsolveR( const real_t* const b, /**< Right hand side vector. */ + BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ + BooleanType removingBound, /**< Indicates if function is called from "removeBound()". */ + real_t* const a /**< Output: Solution vector */ + ); + + + /** Determines step direction of the shift of the QP data. + * \return SUCCESSFUL_RETURN */ + returnValue hotstart_determineDataShift(const int* const FX_idx, /**< Index array of fixed variables. */ + const real_t* const g_new, /**< New gradient vector. */ + const real_t* const lb_new, /**< New lower bounds. */ + const real_t* const ub_new, /**< New upper bounds. */ + real_t* const delta_g, /**< Output: Step direction of gradient vector. */ + real_t* const delta_lb, /**< Output: Step direction of lower bounds. */ + real_t* const delta_ub, /**< Output: Step direction of upper bounds. */ + BooleanType& Delta_bB_isZero/**< Output: Indicates if active bounds are to be shifted. */ + ); + + + /** Checks if lower/upper bounds remain consistent + * (i.e. if lb <= ub) during the current step. + * \return BT_TRUE iff bounds remain consistent + */ + BooleanType areBoundsConsistent( const real_t* const delta_lb, /**< Step direction of lower bounds. */ + const real_t* const delta_ub /**< Step direction of upper bounds. */ + ) const; + + + /** Setups internal QP data. + * \return SUCCESSFUL_RETURN \n + RET_INVALID_ARGUMENTS */ + returnValue setupQPdata( const real_t* const _H, /**< Hessian matrix. */ + const real_t* const _R, /**< Cholesky factorization of the Hessian matrix. */ + const real_t* const _g, /**< Gradient vector. */ + const real_t* const _lb, /**< Lower bounds (on variables). \n + If no lower bounds exist, a NULL pointer can be passed. */ + const real_t* const _ub /**< Upper bounds (on variables). \n + If no upper bounds exist, a NULL pointer can be passed. */ + ); + + + /** Sets Hessian matrix of the QP. + * \return SUCCESSFUL_RETURN */ + inline returnValue setH( const real_t* const H_new /**< New Hessian matrix (with correct dimension!). */ + ); + + /** Changes gradient vector of the QP. + * \return SUCCESSFUL_RETURN */ + inline returnValue setG( const real_t* const g_new /**< New gradient vector (with correct dimension!). */ + ); + + /** Changes lower bound vector of the QP. + * \return SUCCESSFUL_RETURN */ + inline returnValue setLB( const real_t* const lb_new /**< New lower bound vector (with correct dimension!). */ + ); + + /** Changes single entry of lower bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue setLB( int number, /**< Number of entry to be changed. */ + real_t value /**< New value for entry of lower bound vector. */ + ); + + /** Changes upper bound vector of the QP. + * \return SUCCESSFUL_RETURN */ + inline returnValue setUB( const real_t* const ub_new /**< New upper bound vector (with correct dimension!). */ + ); + + /** Changes single entry of upper bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue setUB( int number, /**< Number of entry to be changed. */ + real_t value /**< New value for entry of upper bound vector. */ + ); + + + /** Computes parameters for the Givens matrix G for which [x,y]*G = [z,0] + * \return SUCCESSFUL_RETURN */ + inline void computeGivens( real_t xold, /**< Matrix entry to be normalised. */ + real_t yold, /**< Matrix entry to be annihilated. */ + real_t& xnew, /**< Output: Normalised matrix entry. */ + real_t& ynew, /**< Output: Annihilated matrix entry. */ + real_t& c, /**< Output: Cosine entry of Givens matrix. */ + real_t& s /**< Output: Sine entry of Givens matrix. */ + ) const; + + /** Applies Givens matrix determined by c and s (cf. computeGivens). + * \return SUCCESSFUL_RETURN */ + inline void applyGivens( real_t c, /**< Cosine entry of Givens matrix. */ + real_t s, /**< Sine entry of Givens matrix. */ + real_t xold, /**< Matrix entry to be transformed corresponding to + * the normalised entry of the original matrix. */ + real_t yold, /**< Matrix entry to be transformed corresponding to + * the annihilated entry of the original matrix. */ + real_t& xnew, /**< Output: Transformed matrix entry corresponding to + * the normalised entry of the original matrix. */ + real_t& ynew /**< Output: Transformed matrix entry corresponding to + * the annihilated entry of the original matrix. */ + ) const; + + + /* + * PRIVATE MEMBER FUNCTIONS + */ + private: + /** Determines step direction of the homotopy path. + * \return SUCCESSFUL_RETURN \n + RET_STEPDIRECTION_FAILED_CHOLESKY */ + returnValue hotstart_determineStepDirection(const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + const real_t* const delta_g, /**< Step direction of gradient vector. */ + const real_t* const delta_lb, /**< Step direction of lower bounds. */ + const real_t* const delta_ub, /**< Step direction of upper bounds. */ + BooleanType Delta_bB_isZero, /**< Indicates if active bounds are to be shifted. */ + real_t* const delta_xFX, /**< Output: Primal homotopy step direction of fixed variables. */ + real_t* const delta_xFR, /**< Output: Primal homotopy step direction of free variables. */ + real_t* const delta_yFX /**< Output: Dual homotopy step direction of fixed variables' multiplier. */ + ); + + /** Determines the maximum possible step length along the homotopy path. + * \return SUCCESSFUL_RETURN */ + returnValue hotstart_determineStepLength( const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + const real_t* const delta_lb, /**< Step direction of lower bounds. */ + const real_t* const delta_ub, /**< Step direction of upper bounds. */ + const real_t* const delta_xFR, /**< Primal homotopy step direction of free variables. */ + const real_t* const delta_yFX, /**< Dual homotopy step direction of fixed variables' multiplier. */ + int& BC_idx, /**< Output: Index of blocking constraint. */ + SubjectToStatus& BC_status /**< Output: Status of blocking constraint. */ + ); + + /** Performs a step along the homotopy path (and updates active set). + * \return SUCCESSFUL_RETURN \n + RET_OPTIMAL_SOLUTION_FOUND \n + RET_REMOVE_FROM_ACTIVESET_FAILED \n + RET_ADD_TO_ACTIVESET_FAILED \n + RET_QP_INFEASIBLE */ + returnValue hotstart_performStep( const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + const real_t* const delta_g, /**< Step direction of gradient vector. */ + const real_t* const delta_lb, /**< Step direction of lower bounds. */ + const real_t* const delta_ub, /**< Step direction of upper bounds. */ + const real_t* const delta_xFX, /**< Primal homotopy step direction of fixed variables. */ + const real_t* const delta_xFR, /**< Primal homotopy step direction of free variables. */ + const real_t* const delta_yFX, /**< Dual homotopy step direction of fixed variables' multiplier. */ + int BC_idx, /**< Index of blocking constraint. */ + SubjectToStatus BC_status /**< Status of blocking constraint. */ + ); + + + #ifdef PC_DEBUG /* Define print functions only for debugging! */ + + /** Prints concise information on the current iteration. + * \return SUCCESSFUL_RETURN \n */ + returnValue printIteration( int iteration, /**< Number of current iteration. */ + int BC_idx, /**< Index of blocking bound. */ + SubjectToStatus BC_status /**< Status of blocking bound. */ + ); + + #endif /* PC_DEBUG */ + + + /** Determines the maximum violation of the KKT optimality conditions + * of the current iterate within the QProblemB object. + * \return SUCCESSFUL_RETURN \n + * RET_INACCURATE_SOLUTION \n + * RET_NO_SOLUTION */ + returnValue checkKKTconditions( ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + real_t H[NVMAX*NVMAX]; /**< Hessian matrix. */ + BooleanType hasHessian; /**< Flag indicating whether H contains Hessian or corresponding Cholesky factor R; \sa init. */ + + real_t g[NVMAX]; /**< Gradient. */ + real_t lb[NVMAX]; /**< Lower bound vector (on variables). */ + real_t ub[NVMAX]; /**< Upper bound vector (on variables). */ + + Bounds bounds; /**< Data structure for problem's bounds. */ + + real_t R[NVMAX*NVMAX]; /**< Cholesky decomposition of H (i.e. H = R^T*R). */ + BooleanType hasCholesky; /**< Flag indicating whether Cholesky decomposition has already been setup. */ + + real_t x[NVMAX]; /**< Primal solution vector. */ + real_t y[NVMAX+NCMAX]; /**< Dual solution vector. */ + + real_t tau; /**< Last homotopy step length. */ + + QProblemStatus status; /**< Current status of the solution process. */ + + BooleanType infeasible; /**< QP infeasible? */ + BooleanType unbounded; /**< QP unbounded? */ + + HessianType hessianType; /**< Type of Hessian matrix. */ + + PrintLevel printlevel; /**< Print level. */ + + int count; /**< Counts the number of hotstart function calls (internal usage only!). */ +}; + + +#include + +#endif /* QPOASES_QPROBLEMB_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/SubjectTo.hpp b/phonelibs/qpoases/INCLUDE/SubjectTo.hpp new file mode 100644 index 00000000000000..a014843ceabb24 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/SubjectTo.hpp @@ -0,0 +1,178 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/SubjectTo.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the SubjectTo class designed to manage working sets of + * constraints and bounds within a QProblem. + */ + + +#ifndef QPOASES_SUBJECTTO_HPP +#define QPOASES_SUBJECTTO_HPP + + +#include + + + +/** This class manages working sets of constraints and bounds by storing + * index sets and other status information. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class SubjectTo +{ + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + SubjectTo( ); + + /** Copy constructor (deep copy). */ + SubjectTo( const SubjectTo& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~SubjectTo( ); + + /** Assignment operator (deep copy). */ + SubjectTo& operator=( const SubjectTo& rhs /**< Rhs object. */ + ); + + + /** Pseudo-constructor takes the number of constraints or bounds. + * \return SUCCESSFUL_RETURN */ + returnValue init( int n /**< Number of constraints or bounds. */ + ); + + + /** Returns type of (constraints') bound. + * \return Type of (constraints') bound \n + RET_INDEX_OUT_OF_BOUNDS */ + inline SubjectToType getType( int i /**< Number of (constraints') bound. */ + ) const ; + + /** Returns status of (constraints') bound. + * \return Status of (constraints') bound \n + ST_UNDEFINED */ + inline SubjectToStatus getStatus( int i /**< Number of (constraints') bound. */ + ) const; + + + /** Sets type of (constraints') bound. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue setType( int i, /**< Number of (constraints') bound. */ + SubjectToType value /**< Type of (constraints') bound. */ + ); + + /** Sets status of (constraints') bound. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue setStatus( int i, /**< Number of (constraints') bound. */ + SubjectToStatus value /**< Status of (constraints') bound. */ + ); + + + /** Sets status of lower (constraints') bounds. */ + inline void setNoLower( BooleanType _status /**< Status of lower (constraints') bounds. */ + ); + + /** Sets status of upper (constraints') bounds. */ + inline void setNoUpper( BooleanType _status /**< Status of upper (constraints') bounds. */ + ); + + + /** Returns status of lower (constraints') bounds. + * \return BT_TRUE if there is no lower (constraints') bound on any variable. */ + inline BooleanType isNoLower( ) const; + + /** Returns status of upper bounds. + * \return BT_TRUE if there is no upper (constraints') bound on any variable. */ + inline BooleanType isNoUpper( ) const; + + + /* + * PROTECTED MEMBER FUNCTIONS + */ + protected: + /** Adds the index of a new constraint or bound to index set. + * \return SUCCESSFUL_RETURN \n + RET_ADDINDEX_FAILED */ + returnValue addIndex( Indexlist* const indexlist, /**< Index list to which the new index shall be added. */ + int newnumber, /**< Number of new constraint or bound. */ + SubjectToStatus newstatus /**< Status of new constraint or bound. */ + ); + + /** Removes the index of a constraint or bound from index set. + * \return SUCCESSFUL_RETURN \n + RET_UNKNOWN_BUG */ + returnValue removeIndex( Indexlist* const indexlist, /**< Index list from which the new index shall be removed. */ + int removenumber /**< Number of constraint or bound to be removed. */ + ); + + /** Swaps the indices of two constraints or bounds within the index set. + * \return SUCCESSFUL_RETURN \n + RET_SWAPINDEX_FAILED */ + returnValue swapIndex( Indexlist* const indexlist, /**< Index list in which the indices shold be swapped. */ + int number1, /**< Number of first constraint or bound. */ + int number2 /**< Number of second constraint or bound. */ + ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + SubjectToType type[NVMAX+NCMAX]; /**< Type of constraints/bounds. */ + SubjectToStatus status[NVMAX+NCMAX]; /**< Status of constraints/bounds. */ + + BooleanType noLower; /**< This flag indicates if there is no lower bound on any variable. */ + BooleanType noUpper; /**< This flag indicates if there is no upper bound on any variable. */ + + + /* + * PRIVATE MEMBER VARIABLES + */ + private: + int size; +}; + + + +#include + +#endif /* QPOASES_SUBJECTTO_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/Types.hpp b/phonelibs/qpoases/INCLUDE/Types.hpp new file mode 100644 index 00000000000000..330f187c1e3d47 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Types.hpp @@ -0,0 +1,131 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/Types.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2008 + * + * Declaration of all non-built-in types (except for classes). + */ + + +#ifndef QPOASES_TYPES_HPP +#define QPOASES_TYPES_HPP + + + +/** Define real_t for facilitating switching between double and float. */ +// typedef double real_t; + + +/** Summarises all possible logical values. */ +enum BooleanType +{ + BT_FALSE, /**< Logical value for "false". */ + BT_TRUE /**< Logical value for "true". */ +}; + + +/** Summarises all possible print levels. Print levels are used to describe + * the desired amount of output during runtime of qpOASES. */ +enum PrintLevel +{ + PL_NONE, /**< No output. */ + PL_LOW, /**< Print error messages only. */ + PL_MEDIUM, /**< Print error and warning messages as well as concise info messages. */ + PL_HIGH /**< Print all messages with full details. */ +}; + + +/** Defines visibility status of a message. */ +enum VisibilityStatus +{ + VS_VISIBLE, /**< Message visible. */ + VS_HIDDEN /**< Message not visible. */ +}; + + +/** Summarises all possible states of the (S)QProblem(B) object during the +solution process of a QP sequence. */ +enum QProblemStatus +{ + QPS_NOTINITIALISED, /**< QProblem object is freshly instantiated or reset. */ + QPS_PREPARINGAUXILIARYQP, /**< An auxiliary problem is currently setup, either at the very beginning + * via an initial homotopy or after changing the QP matrices. */ + QPS_AUXILIARYQPSOLVED, /**< An auxilary problem was solved, either at the very beginning + * via an initial homotopy or after changing the QP matrices. */ + QPS_PERFORMINGHOMOTOPY, /**< A homotopy according to the main idea of the online active + * set strategy is performed. */ + QPS_HOMOTOPYQPSOLVED, /**< An intermediate QP along the homotopy path was solved. */ + QPS_SOLVED /**< The solution of the actual QP was found. */ +}; + + +/** Summarises all possible types of bounds and constraints. */ +enum SubjectToType +{ + ST_UNBOUNDED, /**< Bound/constraint is unbounded. */ + ST_BOUNDED, /**< Bound/constraint is bounded but not fixed. */ + ST_EQUALITY, /**< Bound/constraint is fixed (implicit equality bound/constraint). */ + ST_UNKNOWN /**< Type of bound/constraint unknown. */ +}; + + +/** Summarises all possible states of bounds and constraints. */ +enum SubjectToStatus +{ + ST_INACTIVE, /**< Bound/constraint is inactive. */ + ST_LOWER, /**< Bound/constraint is at its lower bound. */ + ST_UPPER, /**< Bound/constraint is at its upper bound. */ + ST_UNDEFINED /**< Status of bound/constraint undefined. */ +}; + + +/** Summarises all possible cycling states of bounds and constraints. */ +enum CyclingStatus +{ + CYC_NOT_INVOLVED, /**< Bound/constraint is not involved in current cycling. */ + CYC_PREV_ADDED, /**< Bound/constraint has previously been added during the current cycling. */ + CYC_PREV_REMOVED /**< Bound/constraint has previously been removed during the current cycling. */ +}; + + +/** Summarises all possible types of the QP's Hessian matrix. */ +enum HessianType +{ + HST_SEMIDEF, /**< Hessian is positive semi-definite. */ + HST_POSDEF_NULLSPACE, /**< Hessian is positive definite on null space of active bounds/constraints. */ + HST_POSDEF, /**< Hessian is (strictly) positive definite. */ + HST_IDENTITY /**< Hessian is identity matrix. */ +}; + + + +#endif /* QPOASES_TYPES_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/Utils.hpp b/phonelibs/qpoases/INCLUDE/Utils.hpp new file mode 100644 index 00000000000000..16546a991b1945 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Utils.hpp @@ -0,0 +1,197 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file INCLUDE/Utils.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of global utility functions for working with qpOASES. + */ + + +#ifndef QPOASES_UTILS_HPP +#define QPOASES_UTILS_HPP + + +#include + + +#ifdef PC_DEBUG /* Define print functions only for debugging! */ + +/** Prints a vector. + * \return SUCCESSFUL_RETURN */ +returnValue print( const real_t* const v, /**< Vector to be printed. */ + int n /**< Length of vector. */ + ); + +/** Prints a permuted vector. + * \return SUCCESSFUL_RETURN */ +returnValue print( const real_t* const v, /**< Vector to be printed. */ + int n, /**< Length of vector. */ + const int* const V_idx /**< Pemutation vector. */ + ); + +/** Prints a named vector. + * \return SUCCESSFUL_RETURN */ +returnValue print( const real_t* const v, /**< Vector to be printed. */ + int n, /**< Length of vector. */ + const char* name /** Name of vector. */ + ); + +/** Prints a matrix. + * \return SUCCESSFUL_RETURN */ +returnValue print( const real_t* const M, /**< Matrix to be printed. */ + int nrow, /**< Row number of matrix. */ + int ncol /**< Column number of matrix. */ + ); + +/** Prints a permuted matrix. + * \return SUCCESSFUL_RETURN */ +returnValue print( const real_t* const M, /**< Matrix to be printed. */ + int nrow, /**< Row number of matrix. */ + int ncol , /**< Column number of matrix. */ + const int* const ROW_idx, /**< Row pemutation vector. */ + const int* const COL_idx /**< Column pemutation vector. */ + ); + +/** Prints a named matrix. + * \return SUCCESSFUL_RETURN */ +returnValue print( const real_t* const M, /**< Matrix to be printed. */ + int nrow, /**< Row number of matrix. */ + int ncol, /**< Column number of matrix. */ + const char* name /** Name of matrix. */ + ); + +/** Prints an index array. + * \return SUCCESSFUL_RETURN */ +returnValue print( const int* const index, /**< Index array to be printed. */ + int n /**< Length of index array. */ + ); + +/** Prints a named index array. + * \return SUCCESSFUL_RETURN */ +returnValue print( const int* const index, /**< Index array to be printed. */ + int n, /**< Length of index array. */ + const char* name /**< Name of index array. */ + ); + + +/** Prints a string to desired output target (useful also for MATLAB output!). + * \return SUCCESSFUL_RETURN */ +returnValue myPrintf( const char* s /**< String to be written. */ + ); + + +/** Prints qpOASES copyright notice. + * \return SUCCESSFUL_RETURN */ +returnValue printCopyrightNotice( ); + + +/** Reads a real_t matrix from file. + * \return SUCCESSFUL_RETURN \n + RET_UNABLE_TO_OPEN_FILE \n + RET_UNABLE_TO_READ_FILE */ +returnValue readFromFile( real_t* data, /**< Matrix to be read from file. */ + int nrow, /**< Row number of matrix. */ + int ncol, /**< Column number of matrix. */ + const char* datafilename /**< Data file name. */ + ); + +/** Reads a real_t vector from file. + * \return SUCCESSFUL_RETURN \n + RET_UNABLE_TO_OPEN_FILE \n + RET_UNABLE_TO_READ_FILE */ +returnValue readFromFile( real_t* data, /**< Vector to be read from file. */ + int n, /**< Length of vector. */ + const char* datafilename /**< Data file name. */ + ); + +/** Reads an integer (column) vector from file. + * \return SUCCESSFUL_RETURN \n + RET_UNABLE_TO_OPEN_FILE \n + RET_UNABLE_TO_READ_FILE */ +returnValue readFromFile( int* data, /**< Vector to be read from file. */ + int n, /**< Length of vector. */ + const char* datafilename /**< Data file name. */ + ); + + +/** Writes a real_t matrix into a file. + * \return SUCCESSFUL_RETURN \n + RET_UNABLE_TO_OPEN_FILE */ +returnValue writeIntoFile( const real_t* const data, /**< Matrix to be written into file. */ + int nrow, /**< Row number of matrix. */ + int ncol, /**< Column number of matrix. */ + const char* datafilename, /**< Data file name. */ + BooleanType append /**< Indicates if data shall be appended if the file already exists (otherwise it is overwritten). */ + ); + +/** Writes a real_t vector into a file. + * \return SUCCESSFUL_RETURN \n + RET_UNABLE_TO_OPEN_FILE */ +returnValue writeIntoFile( const real_t* const data, /**< Vector to be written into file. */ + int n, /**< Length of vector. */ + const char* datafilename, /**< Data file name. */ + BooleanType append /**< Indicates if data shall be appended if the file already exists (otherwise it is overwritten). */ + ); + +/** Writes an integer (column) vector into a file. + * \return SUCCESSFUL_RETURN \n + RET_UNABLE_TO_OPEN_FILE */ +returnValue writeIntoFile( const int* const integer, /**< Integer vector to be written into file. */ + int n, /**< Length of vector. */ + const char* datafilename, /**< Data file name. */ + BooleanType append /**< Indicates if integer shall be appended if the file already exists (otherwise it is overwritten). */ + ); + +#endif /* PC_DEBUG */ + + +/** Returns the current system time. + * \return current system time */ +real_t getCPUtime( ); + + +/** Returns the Euclidean norm of a vector. + * \return 0: successful */ +real_t getNorm( const real_t* const v, /**< Vector. */ + int n /**< Vector's dimension. */ + ); + +/** Returns the absolute value of a real_t. + * \return Absolute value of a real_t */ +inline real_t getAbs( real_t x /**< Input argument. */ + ); + + + +#include + +#endif /* QPOASES_UTILS_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/LICENSE.txt b/phonelibs/qpoases/LICENSE.txt new file mode 100644 index 00000000000000..5faba9d48ce750 --- /dev/null +++ b/phonelibs/qpoases/LICENSE.txt @@ -0,0 +1,504 @@ + GNU LESSER GENERAL PUBLIC LICENSE + Version 2.1, February 1999 + + Copyright (C) 1991, 1999 Free Software Foundation, Inc. + 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + +[This is the first released version of the Lesser GPL. It also counts + as the successor of the GNU Library Public License, version 2, hence + the version number 2.1.] + + Preamble + + The licenses for most software are designed to take away your +freedom to share and change it. By contrast, the GNU General Public +Licenses are intended to guarantee your freedom to share and change +free software--to make sure the software is free for all its users. + + This license, the Lesser General Public License, applies to some +specially designated software packages--typically libraries--of the +Free Software Foundation and other authors who decide to use it. You +can use it too, but we suggest you first think carefully about whether +this license or the ordinary General Public License is the better +strategy to use in any particular case, based on the explanations below. + + When we speak of free software, we are referring to freedom of use, +not price. Our General Public Licenses are designed to make sure that +you have the freedom to distribute copies of free software (and charge +for this service if you wish); that you receive source code or can get +it if you want it; that you can change the software and use pieces of +it in new free programs; and that you are informed that you can do +these things. + + To protect your rights, we need to make restrictions that forbid +distributors to deny you these rights or to ask you to surrender these +rights. These restrictions translate to certain responsibilities for +you if you distribute copies of the library or if you modify it. + + For example, if you distribute copies of the library, whether gratis +or for a fee, you must give the recipients all the rights that we gave +you. You must make sure that they, too, receive or can get the source +code. If you link other code with the library, you must provide +complete object files to the recipients, so that they can relink them +with the library after making changes to the library and recompiling +it. And you must show them these terms so they know their rights. + + We protect your rights with a two-step method: (1) we copyright the +library, and (2) we offer you this license, which gives you legal +permission to copy, distribute and/or modify the library. + + To protect each distributor, we want to make it very clear that +there is no warranty for the free library. Also, if the library is +modified by someone else and passed on, the recipients should know +that what they have is not the original version, so that the original +author's reputation will not be affected by problems that might be +introduced by others. + + Finally, software patents pose a constant threat to the existence of +any free program. We wish to make sure that a company cannot +effectively restrict the users of a free program by obtaining a +restrictive license from a patent holder. Therefore, we insist that +any patent license obtained for a version of the library must be +consistent with the full freedom of use specified in this license. + + Most GNU software, including some libraries, is covered by the +ordinary GNU General Public License. This license, the GNU Lesser +General Public License, applies to certain designated libraries, and +is quite different from the ordinary General Public License. We use +this license for certain libraries in order to permit linking those +libraries into non-free programs. + + When a program is linked with a library, whether statically or using +a shared library, the combination of the two is legally speaking a +combined work, a derivative of the original library. The ordinary +General Public License therefore permits such linking only if the +entire combination fits its criteria of freedom. The Lesser General +Public License permits more lax criteria for linking other code with +the library. + + We call this license the "Lesser" General Public License because it +does Less to protect the user's freedom than the ordinary General +Public License. It also provides other free software developers Less +of an advantage over competing non-free programs. These disadvantages +are the reason we use the ordinary General Public License for many +libraries. However, the Lesser license provides advantages in certain +special circumstances. + + For example, on rare occasions, there may be a special need to +encourage the widest possible use of a certain library, so that it becomes +a de-facto standard. To achieve this, non-free programs must be +allowed to use the library. A more frequent case is that a free +library does the same job as widely used non-free libraries. In this +case, there is little to gain by limiting the free library to free +software only, so we use the Lesser General Public License. + + In other cases, permission to use a particular library in non-free +programs enables a greater number of people to use a large body of +free software. For example, permission to use the GNU C Library in +non-free programs enables many more people to use the whole GNU +operating system, as well as its variant, the GNU/Linux operating +system. + + Although the Lesser General Public License is Less protective of the +users' freedom, it does ensure that the user of a program that is +linked with the Library has the freedom and the wherewithal to run +that program using a modified version of the Library. + + The precise terms and conditions for copying, distribution and +modification follow. Pay close attention to the difference between a +"work based on the library" and a "work that uses the library". The +former contains code derived from the library, whereas the latter must +be combined with the library in order to run. + + GNU LESSER GENERAL PUBLIC LICENSE + TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION + + 0. This License Agreement applies to any software library or other +program which contains a notice placed by the copyright holder or +other authorized party saying it may be distributed under the terms of +this Lesser General Public License (also called "this License"). +Each licensee is addressed as "you". + + A "library" means a collection of software functions and/or data +prepared so as to be conveniently linked with application programs +(which use some of those functions and data) to form executables. + + The "Library", below, refers to any such software library or work +which has been distributed under these terms. A "work based on the +Library" means either the Library or any derivative work under +copyright law: that is to say, a work containing the Library or a +portion of it, either verbatim or with modifications and/or translated +straightforwardly into another language. (Hereinafter, translation is +included without limitation in the term "modification".) + + "Source code" for a work means the preferred form of the work for +making modifications to it. For a library, complete source code means +all the source code for all modules it contains, plus any associated +interface definition files, plus the scripts used to control compilation +and installation of the library. + + Activities other than copying, distribution and modification are not +covered by this License; they are outside its scope. The act of +running a program using the Library is not restricted, and output from +such a program is covered only if its contents constitute a work based +on the Library (independent of the use of the Library in a tool for +writing it). Whether that is true depends on what the Library does +and what the program that uses the Library does. + + 1. You may copy and distribute verbatim copies of the Library's +complete source code as you receive it, in any medium, provided that +you conspicuously and appropriately publish on each copy an +appropriate copyright notice and disclaimer of warranty; keep intact +all the notices that refer to this License and to the absence of any +warranty; and distribute a copy of this License along with the +Library. + + You may charge a fee for the physical act of transferring a copy, +and you may at your option offer warranty protection in exchange for a +fee. + + 2. You may modify your copy or copies of the Library or any portion +of it, thus forming a work based on the Library, and copy and +distribute such modifications or work under the terms of Section 1 +above, provided that you also meet all of these conditions: + + a) The modified work must itself be a software library. + + b) You must cause the files modified to carry prominent notices + stating that you changed the files and the date of any change. + + c) You must cause the whole of the work to be licensed at no + charge to all third parties under the terms of this License. + + d) If a facility in the modified Library refers to a function or a + table of data to be supplied by an application program that uses + the facility, other than as an argument passed when the facility + is invoked, then you must make a good faith effort to ensure that, + in the event an application does not supply such function or + table, the facility still operates, and performs whatever part of + its purpose remains meaningful. + + (For example, a function in a library to compute square roots has + a purpose that is entirely well-defined independent of the + application. Therefore, Subsection 2d requires that any + application-supplied function or table used by this function must + be optional: if the application does not supply it, the square + root function must still compute square roots.) + +These requirements apply to the modified work as a whole. If +identifiable sections of that work are not derived from the Library, +and can be reasonably considered independent and separate works in +themselves, then this License, and its terms, do not apply to those +sections when you distribute them as separate works. But when you +distribute the same sections as part of a whole which is a work based +on the Library, the distribution of the whole must be on the terms of +this License, whose permissions for other licensees extend to the +entire whole, and thus to each and every part regardless of who wrote +it. + +Thus, it is not the intent of this section to claim rights or contest +your rights to work written entirely by you; rather, the intent is to +exercise the right to control the distribution of derivative or +collective works based on the Library. + +In addition, mere aggregation of another work not based on the Library +with the Library (or with a work based on the Library) on a volume of +a storage or distribution medium does not bring the other work under +the scope of this License. + + 3. You may opt to apply the terms of the ordinary GNU General Public +License instead of this License to a given copy of the Library. To do +this, you must alter all the notices that refer to this License, so +that they refer to the ordinary GNU General Public License, version 2, +instead of to this License. (If a newer version than version 2 of the +ordinary GNU General Public License has appeared, then you can specify +that version instead if you wish.) Do not make any other change in +these notices. + + Once this change is made in a given copy, it is irreversible for +that copy, so the ordinary GNU General Public License applies to all +subsequent copies and derivative works made from that copy. + + This option is useful when you wish to copy part of the code of +the Library into a program that is not a library. + + 4. You may copy and distribute the Library (or a portion or +derivative of it, under Section 2) in object code or executable form +under the terms of Sections 1 and 2 above provided that you accompany +it with the complete corresponding machine-readable source code, which +must be distributed under the terms of Sections 1 and 2 above on a +medium customarily used for software interchange. + + If distribution of object code is made by offering access to copy +from a designated place, then offering equivalent access to copy the +source code from the same place satisfies the requirement to +distribute the source code, even though third parties are not +compelled to copy the source along with the object code. + + 5. A program that contains no derivative of any portion of the +Library, but is designed to work with the Library by being compiled or +linked with it, is called a "work that uses the Library". Such a +work, in isolation, is not a derivative work of the Library, and +therefore falls outside the scope of this License. + + However, linking a "work that uses the Library" with the Library +creates an executable that is a derivative of the Library (because it +contains portions of the Library), rather than a "work that uses the +library". The executable is therefore covered by this License. +Section 6 states terms for distribution of such executables. + + When a "work that uses the Library" uses material from a header file +that is part of the Library, the object code for the work may be a +derivative work of the Library even though the source code is not. +Whether this is true is especially significant if the work can be +linked without the Library, or if the work is itself a library. The +threshold for this to be true is not precisely defined by law. + + If such an object file uses only numerical parameters, data +structure layouts and accessors, and small macros and small inline +functions (ten lines or less in length), then the use of the object +file is unrestricted, regardless of whether it is legally a derivative +work. (Executables containing this object code plus portions of the +Library will still fall under Section 6.) + + Otherwise, if the work is a derivative of the Library, you may +distribute the object code for the work under the terms of Section 6. +Any executables containing that work also fall under Section 6, +whether or not they are linked directly with the Library itself. + + 6. As an exception to the Sections above, you may also combine or +link a "work that uses the Library" with the Library to produce a +work containing portions of the Library, and distribute that work +under terms of your choice, provided that the terms permit +modification of the work for the customer's own use and reverse +engineering for debugging such modifications. + + You must give prominent notice with each copy of the work that the +Library is used in it and that the Library and its use are covered by +this License. You must supply a copy of this License. If the work +during execution displays copyright notices, you must include the +copyright notice for the Library among them, as well as a reference +directing the user to the copy of this License. Also, you must do one +of these things: + + a) Accompany the work with the complete corresponding + machine-readable source code for the Library including whatever + changes were used in the work (which must be distributed under + Sections 1 and 2 above); and, if the work is an executable linked + with the Library, with the complete machine-readable "work that + uses the Library", as object code and/or source code, so that the + user can modify the Library and then relink to produce a modified + executable containing the modified Library. (It is understood + that the user who changes the contents of definitions files in the + Library will not necessarily be able to recompile the application + to use the modified definitions.) + + b) Use a suitable shared library mechanism for linking with the + Library. A suitable mechanism is one that (1) uses at run time a + copy of the library already present on the user's computer system, + rather than copying library functions into the executable, and (2) + will operate properly with a modified version of the library, if + the user installs one, as long as the modified version is + interface-compatible with the version that the work was made with. + + c) Accompany the work with a written offer, valid for at + least three years, to give the same user the materials + specified in Subsection 6a, above, for a charge no more + than the cost of performing this distribution. + + d) If distribution of the work is made by offering access to copy + from a designated place, offer equivalent access to copy the above + specified materials from the same place. + + e) Verify that the user has already received a copy of these + materials or that you have already sent this user a copy. + + For an executable, the required form of the "work that uses the +Library" must include any data and utility programs needed for +reproducing the executable from it. However, as a special exception, +the materials to be distributed need not include anything that is +normally distributed (in either source or binary form) with the major +components (compiler, kernel, and so on) of the operating system on +which the executable runs, unless that component itself accompanies +the executable. + + It may happen that this requirement contradicts the license +restrictions of other proprietary libraries that do not normally +accompany the operating system. Such a contradiction means you cannot +use both them and the Library together in an executable that you +distribute. + + 7. You may place library facilities that are a work based on the +Library side-by-side in a single library together with other library +facilities not covered by this License, and distribute such a combined +library, provided that the separate distribution of the work based on +the Library and of the other library facilities is otherwise +permitted, and provided that you do these two things: + + a) Accompany the combined library with a copy of the same work + based on the Library, uncombined with any other library + facilities. This must be distributed under the terms of the + Sections above. + + b) Give prominent notice with the combined library of the fact + that part of it is a work based on the Library, and explaining + where to find the accompanying uncombined form of the same work. + + 8. You may not copy, modify, sublicense, link with, or distribute +the Library except as expressly provided under this License. Any +attempt otherwise to copy, modify, sublicense, link with, or +distribute the Library is void, and will automatically terminate your +rights under this License. However, parties who have received copies, +or rights, from you under this License will not have their licenses +terminated so long as such parties remain in full compliance. + + 9. You are not required to accept this License, since you have not +signed it. However, nothing else grants you permission to modify or +distribute the Library or its derivative works. These actions are +prohibited by law if you do not accept this License. Therefore, by +modifying or distributing the Library (or any work based on the +Library), you indicate your acceptance of this License to do so, and +all its terms and conditions for copying, distributing or modifying +the Library or works based on it. + + 10. Each time you redistribute the Library (or any work based on the +Library), the recipient automatically receives a license from the +original licensor to copy, distribute, link with or modify the Library +subject to these terms and conditions. You may not impose any further +restrictions on the recipients' exercise of the rights granted herein. +You are not responsible for enforcing compliance by third parties with +this License. + + 11. If, as a consequence of a court judgment or allegation of patent +infringement or for any other reason (not limited to patent issues), +conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot +distribute so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you +may not distribute the Library at all. For example, if a patent +license would not permit royalty-free redistribution of the Library by +all those who receive copies directly or indirectly through you, then +the only way you could satisfy both it and this License would be to +refrain entirely from distribution of the Library. + +If any portion of this section is held invalid or unenforceable under any +particular circumstance, the balance of the section is intended to apply, +and the section as a whole is intended to apply in other circumstances. + +It is not the purpose of this section to induce you to infringe any +patents or other property right claims or to contest validity of any +such claims; this section has the sole purpose of protecting the +integrity of the free software distribution system which is +implemented by public license practices. Many people have made +generous contributions to the wide range of software distributed +through that system in reliance on consistent application of that +system; it is up to the author/donor to decide if he or she is willing +to distribute software through any other system and a licensee cannot +impose that choice. + +This section is intended to make thoroughly clear what is believed to +be a consequence of the rest of this License. + + 12. If the distribution and/or use of the Library is restricted in +certain countries either by patents or by copyrighted interfaces, the +original copyright holder who places the Library under this License may add +an explicit geographical distribution limitation excluding those countries, +so that distribution is permitted only in or among countries not thus +excluded. In such case, this License incorporates the limitation as if +written in the body of this License. + + 13. The Free Software Foundation may publish revised and/or new +versions of the Lesser General Public License from time to time. +Such new versions will be similar in spirit to the present version, +but may differ in detail to address new problems or concerns. + +Each version is given a distinguishing version number. If the Library +specifies a version number of this License which applies to it and +"any later version", you have the option of following the terms and +conditions either of that version or of any later version published by +the Free Software Foundation. If the Library does not specify a +license version number, you may choose any version ever published by +the Free Software Foundation. + + 14. If you wish to incorporate parts of the Library into other free +programs whose distribution conditions are incompatible with these, +write to the author to ask for permission. For software which is +copyrighted by the Free Software Foundation, write to the Free +Software Foundation; we sometimes make exceptions for this. Our +decision will be guided by the two goals of preserving the free status +of all derivatives of our free software and of promoting the sharing +and reuse of software generally. + + NO WARRANTY + + 15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO +WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW. +EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR +OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY +KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE +LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME +THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN +WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY +AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU +FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR +CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE +LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING +RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A +FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF +SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH +DAMAGES. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Libraries + + If you develop a new library, and you want it to be of the greatest +possible use to the public, we recommend making it free software that +everyone can redistribute and change. You can do so by permitting +redistribution under these terms (or, alternatively, under the terms of the +ordinary General Public License). + + To apply these terms, attach the following notices to the library. It is +safest to attach them to the start of each source file to most effectively +convey the exclusion of warranty; and each file should have at least the +"copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +Also add information on how to contact you by electronic and paper mail. + +You should also get your employer (if you work as a programmer) or your +school, if any, to sign a "copyright disclaimer" for the library, if +necessary. Here is a sample; alter the names: + + Yoyodyne, Inc., hereby disclaims all copyright interest in the + library `Frob' (a library for tweaking knobs) written by James Random Hacker. + + , 1 April 1990 + Ty Coon, President of Vice + +That's all there is to it! + + diff --git a/phonelibs/qpoases/README.txt b/phonelibs/qpoases/README.txt new file mode 100644 index 00000000000000..37175d9192bdbe --- /dev/null +++ b/phonelibs/qpoases/README.txt @@ -0,0 +1,92 @@ +## +## qpOASES -- An Implementation of the Online Active Set Strategy. +## Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. +## +## qpOASES is free software; you can redistribute it and/or +## modify it under the terms of the GNU Lesser General Public +## License as published by the Free Software Foundation; either +## version 2.1 of the License, or (at your option) any later version. +## +## qpOASES is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +## Lesser General Public License for more details. +## +## You should have received a copy of the GNU Lesser General Public +## License along with qpOASES; if not, write to the Free Software +## Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +## + + + +INTRODUCTION +============= + +qpOASES is an open-source C++ implementation of the recently proposed +online active set strategy (see [1], [2]), which was inspired by important +observations from the field of parametric quadratic programming. It has +several theoretical features that make it particularly suited for model +predictive control (MPC) applications. + +The software package qpOASES implements these ideas and has already been +successfully used for closed-loop control of a real-world Diesel engine [3]. + + +References: + +[1] H.J. Ferreau. An Online Active Set Strategy for Fast Solution of +Parametric Quadratic Programs with Applications to Predictive Engine Control. +Diplom thesis, University of Heidelberg, 2006. + +[2] H.J. Ferreau, H.G. Bock, M. Diehl. An online active set strategy to +overcome the limitations of explicit MPC. International Journal of Robust +and Nonlinear Control, 18 (8), pp. 816-830, 2008. + +[3] H.J. Ferreau, P. Ortner, P. Langthaler, L. del Re, M. Diehl. Predictive +Control of a Real-World Diesel Engine using an Extended Online Active Set +Strategy. Annual Reviews in Control, 31 (2), pp. 293-301, 2007. + + + +GETTING STARTED +================ + +1. For installation, usage and additional information on this software package + see the qpOASES User's Manual located at ./DOC/manual.pdf! + + +2. The file ./LICENSE.txt contains a copy of the GNU Lesser General Public + License. Please read it carefully before using qpOASES! + + +3. The whole software package can be downloaded from + + http://homes.esat.kuleuven.be/~optec/software/qpOASES/ + + On this webpage you will also find a list of frequently asked questions. + + + +CONTACT THE AUTHORS +==================== + +If you have got questions, remarks or comments on qpOASES +please contact the main author: + + Hans Joachim Ferreau + Katholieke Universiteit Leuven + Department of Electrical Engineering (ESAT) + Kasteelpark Arenberg 10, bus 2446 + B-3001 Leuven-Heverlee, Belgium + + Phone: +32 16 32 03 63 + E-mail: joachim.ferreau@esat.kuleuven.be + qpOASES@esat.kuleuven.be + +Also bug reports and source code extensions are most welcome! + + + +## +## end of file +## diff --git a/phonelibs/qpoases/SRC/Bounds.cpp b/phonelibs/qpoases/SRC/Bounds.cpp new file mode 100644 index 00000000000000..236ab2f62d284b --- /dev/null +++ b/phonelibs/qpoases/SRC/Bounds.cpp @@ -0,0 +1,252 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/Bounds.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the Bounds class designed to manage working sets of + * bounds within a QProblem. + */ + + +#include + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * B o u n d s + */ +Bounds::Bounds( ) : SubjectTo( ), + nV( 0 ), + nFV( 0 ), + nBV( 0 ), + nUV( 0 ) +{ +} + + +/* + * B o u n d s + */ +Bounds::Bounds( const Bounds& rhs ) : SubjectTo( rhs ), + nV( rhs.nV ), + nFV( rhs.nFV ), + nBV( rhs.nBV ), + nUV( rhs.nUV ) +{ + free = rhs.free; + fixed = rhs.fixed; +} + + +/* + * ~ B o u n d s + */ +Bounds::~Bounds( ) +{ +} + + +/* + * o p e r a t o r = + */ +Bounds& Bounds::operator=( const Bounds& rhs ) +{ + if ( this != &rhs ) + { + SubjectTo::operator=( rhs ); + + nV = rhs.nV; + nFV = rhs.nFV; + nBV = rhs.nBV; + nUV = rhs.nUV; + + free = rhs.free; + fixed = rhs.fixed; + } + + return *this; +} + + +/* + * i n i t + */ +returnValue Bounds::init( int n ) +{ + nV = n; + nFV = 0; + nBV = 0; + nUV = 0; + + free.init( ); + fixed.init( ); + + return SubjectTo::init( n ); +} + + +/* + * s e t u p B o u n d + */ +returnValue Bounds::setupBound( int _number, SubjectToStatus _status + ) +{ + /* consistency check */ + if ( ( _number < 0 ) || ( _number >= getNV( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Add bound index to respective index list. */ + switch ( _status ) + { + case ST_INACTIVE: + if ( this->addIndex( this->getFree( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_BOUND_FAILED ); + break; + + case ST_LOWER: + if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_BOUND_FAILED ); + break; + + case ST_UPPER: + if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_BOUND_FAILED ); + break; + + default: + return THROWERROR( RET_INVALID_ARGUMENTS ); + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p A l l F r e e + */ +returnValue Bounds::setupAllFree( ) +{ + int i; + + /* 1) Place unbounded variables at the beginning of the index list of free variables. */ + for( i=0; i= getNV( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Move index from indexlist of fixed variables to that of free ones. */ + if ( this->removeIndex( this->getFixed( ),_number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + if ( this->addIndex( this->getFree( ),_number,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + return SUCCESSFUL_RETURN; +} + + +/* + * m o v e F r e e T o F i x e d + */ +returnValue Bounds::moveFreeToFixed( int _number, SubjectToStatus _status + ) +{ + /* consistency check */ + if ( ( _number < 0 ) || ( _number >= getNV( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Move index from indexlist of free variables to that of fixed ones. */ + if ( this->removeIndex( this->getFree( ),_number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + return SUCCESSFUL_RETURN; +} + + +/* + * s w a p F r e e + */ +returnValue Bounds::swapFree( int number1, int number2 + ) +{ + /* consistency check */ + if ( ( number1 < 0 ) || ( number1 >= getNV( ) ) || ( number2 < 0 ) || ( number2 >= getNV( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Swap index within indexlist of free variables. */ + return this->swapIndex( this->getFree( ),number1,number2 ); +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/Bounds.ipp b/phonelibs/qpoases/SRC/Bounds.ipp new file mode 100644 index 00000000000000..d0e7dbbf0904f7 --- /dev/null +++ b/phonelibs/qpoases/SRC/Bounds.ipp @@ -0,0 +1,144 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/Bounds.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of inlined member functions of the Bounds class designed + * to manage working sets of bounds within a QProblem. + */ + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + +/* + * g e t N V + */ +inline int Bounds::getNV( ) const +{ + return nV; +} + + +/* + * g e t N F X + */ +inline int Bounds::getNFV( ) const +{ + return nFV; +} + + +/* + * g e t N B V + */ +inline int Bounds::getNBV( ) const +{ + return nBV; +} + + +/* + * g e t N U V + */ +inline int Bounds::getNUV( ) const +{ + return nUV; +} + + + +/* + * s e t N F X + */ +inline returnValue Bounds::setNFV( int n ) +{ + nFV = n; + return SUCCESSFUL_RETURN; +} + + +/* + * s e t N B V + */ +inline returnValue Bounds::setNBV( int n ) +{ + nBV = n; + return SUCCESSFUL_RETURN; +} + + +/* + * s e t N U V + */ +inline returnValue Bounds::setNUV( int n ) +{ + nUV = n; + return SUCCESSFUL_RETURN; +} + + +/* + * g e t N F R + */ +inline int Bounds::getNFR( ) +{ + return free.getLength( ); +} + + +/* + * g e t N F X + */ +inline int Bounds::getNFX( ) +{ + return fixed.getLength( ); +} + + +/* + * g e t F r e e + */ +inline Indexlist* Bounds::getFree( ) +{ + return &free; +} + + +/* + * g e t F i x e d + */ +inline Indexlist* Bounds::getFixed( ) +{ + return &fixed; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/Constraints.cpp b/phonelibs/qpoases/SRC/Constraints.cpp new file mode 100644 index 00000000000000..81fc6ce8679d23 --- /dev/null +++ b/phonelibs/qpoases/SRC/Constraints.cpp @@ -0,0 +1,248 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/Constraints.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the Constraints class designed to manage working sets of + * constraints within a QProblem. + */ + + +#include + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * C o n s t r a i n t s + */ +Constraints::Constraints( ) : SubjectTo( ), + nC( 0 ), + nEC( 0 ), + nIC( 0 ), + nUC( 0 ) +{ +} + + +/* + * C o n s t r a i n t s + */ +Constraints::Constraints( const Constraints& rhs ) : SubjectTo( rhs ), + nC( rhs.nC ), + nEC( rhs.nEC ), + nIC( rhs.nIC ), + nUC( rhs.nUC ) +{ + active = rhs.active; + inactive = rhs.inactive; +} + + +/* + * ~ C o n s t r a i n t s + */ +Constraints::~Constraints( ) +{ +} + + +/* + * o p e r a t o r = + */ +Constraints& Constraints::operator=( const Constraints& rhs ) +{ + if ( this != &rhs ) + { + SubjectTo::operator=( rhs ); + + nC = rhs.nC; + nEC = rhs.nEC; + nIC = rhs.nIC; + nUC = rhs.nUC; + + active = rhs.active; + inactive = rhs.inactive; + } + + return *this; +} + + +/* + * i n i t + */ +returnValue Constraints::init( int n ) +{ + nC = n; + nEC = 0; + nIC = 0; + nUC = 0; + + active.init( ); + inactive.init( ); + + return SubjectTo::init( n ); +} + + +/* + * s e t u p C o n s t r a i n t + */ +returnValue Constraints::setupConstraint( int _number, SubjectToStatus _status + ) +{ + /* consistency check */ + if ( ( _number < 0 ) || ( _number >= getNC( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Add constraint index to respective index list. */ + switch ( _status ) + { + case ST_INACTIVE: + if ( this->addIndex( this->getInactive( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_CONSTRAINT_FAILED ); + break; + + case ST_LOWER: + if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_CONSTRAINT_FAILED ); + break; + + case ST_UPPER: + if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_CONSTRAINT_FAILED ); + break; + + default: + return THROWERROR( RET_INVALID_ARGUMENTS ); + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p A l l I n a c t i v e + */ +returnValue Constraints::setupAllInactive( ) +{ + int i; + + + /* 1) Place unbounded constraints at the beginning of the index list of inactive constraints. */ + for( i=0; i= getNC( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Move index from indexlist of active constraints to that of inactive ones. */ + if ( this->removeIndex( this->getActive( ),_number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + if ( this->addIndex( this->getInactive( ),_number,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + return SUCCESSFUL_RETURN; +} + + +/* + * m o v e I n a c t i v e T o A c t i v e + */ +returnValue Constraints::moveInactiveToActive( int _number, SubjectToStatus _status + ) +{ + /* consistency check */ + if ( ( _number < 0 ) || ( _number >= getNC( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Move index from indexlist of inactive constraints to that of active ones. */ + if ( this->removeIndex( this->getInactive( ),_number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + return SUCCESSFUL_RETURN; +} + + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/Constraints.ipp b/phonelibs/qpoases/SRC/Constraints.ipp new file mode 100644 index 00000000000000..67add20434a1e4 --- /dev/null +++ b/phonelibs/qpoases/SRC/Constraints.ipp @@ -0,0 +1,144 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/Constraints.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of inlined member functions of the Constraints class designed + * to manage working sets of constraints within a QProblem. + */ + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + +/* + * g e t N C + */ +inline int Constraints::getNC( ) const +{ + return nC; +} + + +/* + * g e t N E C + */ +inline int Constraints::getNEC( ) const +{ + return nEC; +} + + +/* + * g e t N I C + */ +inline int Constraints::getNIC( ) const +{ + return nIC; +} + + +/* + * g e t N U C + */ +inline int Constraints::getNUC( ) const +{ + return nUC; +} + + +/* + * s e t N E C + */ +inline returnValue Constraints::setNEC( int n ) +{ + nEC = n; + return SUCCESSFUL_RETURN; +} + + +/* + * s e t N I C + */ +inline returnValue Constraints::setNIC( int n ) +{ + nIC = n; + return SUCCESSFUL_RETURN; +} + + +/* + * s e t N U C + */ +inline returnValue Constraints::setNUC( int n ) +{ + nUC = n; + return SUCCESSFUL_RETURN; +} + + +/* + * g e t N A C + */ +inline int Constraints::getNAC( ) +{ + return active.getLength( ); +} + + +/* + * g e t N I A C + */ +inline int Constraints::getNIAC( ) +{ + return inactive.getLength( ); +} + + +/* + * g e t A c t i v e + */ +inline Indexlist* Constraints::getActive( ) +{ + return &active; +} + + +/* + * g e t I n a c t i v e + */ +inline Indexlist* Constraints::getInactive( ) +{ + return &inactive; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/CyclingManager.cpp b/phonelibs/qpoases/SRC/CyclingManager.cpp new file mode 100644 index 00000000000000..7bbccdac228460 --- /dev/null +++ b/phonelibs/qpoases/SRC/CyclingManager.cpp @@ -0,0 +1,188 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/CyclingManager.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the CyclingManager class designed to detect + * and handle possible cycling during QP iterations. + * + */ + + +#include + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * C y c l i n g M a n a g e r + */ +CyclingManager::CyclingManager( ) : nV( 0 ), + nC( 0 ) +{ + cyclingDetected = BT_FALSE; +} + + +/* + * C y c l i n g M a n a g e r + */ +CyclingManager::CyclingManager( const CyclingManager& rhs ) : nV( rhs.nV ), + nC( rhs.nC ), + cyclingDetected( rhs.cyclingDetected ) +{ + int i; + + for( i=0; i= 0 ) && ( number < nV ) ) + { + status[number] = _status; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } + else + { + /* Set cycling status of a constraint. */ + if ( ( number >= 0 ) && ( number < nC ) ) + { + status[nV+number] = _status; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } +} + + +/* + * g e t C y c l i n g S t a t u s + */ +CyclingStatus CyclingManager::getCyclingStatus( int number, BooleanType isBound ) const +{ + if ( isBound == BT_TRUE ) + { + /* Return cycling status of a bound. */ + if ( ( number >= 0 ) && ( number < nV ) ) + return status[number]; + } + else + { + /* Return cycling status of a constraint. */ + if ( ( number >= 0 ) && ( number < nC ) ) + return status[nV+number]; + } + + return CYC_NOT_INVOLVED; +} + + +/* + * c l e a r C y c l i n g D a t a + */ +returnValue CyclingManager::clearCyclingData( ) +{ + int i; + + /* Reset all status values ... */ + for( i=0; i + +/* + * S o l u t i o n A n a l y s i s + */ +SolutionAnalysis::SolutionAnalysis( ) +{ + +} + +/* + * S o l u t i o n A n a l y s i s + */ +SolutionAnalysis::SolutionAnalysis( const SolutionAnalysis& rhs ) +{ + +} + +/* + * ~ S o l u t i o n A n a l y s i s + */ +SolutionAnalysis::~SolutionAnalysis( ) +{ + +} + +/* + * o p e r a t o r = + */ +SolutionAnalysis& SolutionAnalysis::operator=( const SolutionAnalysis& rhs ) +{ + if ( this != &rhs ) + { + + } + + return *this; +} + +/* + * g e t H e s s i a n I n v e r s e + */ +returnValue SolutionAnalysis::getHessianInverse( QProblem* qp, real_t* hessianInverse ) +{ + returnValue returnvalue; /* the return value */ + BooleanType Delta_bC_isZero = BT_FALSE; /* (just use FALSE here) */ + BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */ + + register int run1, run2, run3; + + register int nFR, nFX; + + /* Ask for the number of free and fixed variables, assumes that active set + * is constant for the covariance evaluation */ + nFR = qp->getNFR( ); + nFX = qp->getNFX( ); + + /* Ask for the corresponding index arrays: */ + if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( qp->constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + /* Initialization: */ + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_g_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_lb_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_ub_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NCMAX; run1++ ) + delta_lbA_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NCMAX; run1++ ) + delta_ubA_cov[ run1 ] = 0.0; + + /* The following loop solves the following: + * + * KKT * x = + * [delta_g_cov', delta_lbA_cov', delta_ubA_cov', delta_lb_cov', delta_ub_cov]' + * + * for the first NVMAX (negative) elementary vectors in order to get + * transposed inverse of the Hessian. Assuming that the Hessian is + * symmetric, the function will return transposed inverse, instead of the + * true inverse. + * + * Note, that we use negative elementary vectors due because internal + * implementation of the function hotstart_determineStepDirection requires + * so. + * + * */ + + for( run3 = 0; run3 < NVMAX; run3++ ) + { + /* Line wise loading of the corresponding (negative) elementary vector: */ + delta_g_cov[ run3 ] = -1.0; + + /* Evaluation of the step: */ + returnvalue = qp->hotstart_determineStepDirection( + FR_idx, FX_idx, AC_idx, + delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov, + Delta_bC_isZero, Delta_bB_isZero, + delta_xFX, delta_xFR, delta_yAC, delta_yFX + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + return returnvalue; + } + + /* Line wise storage of the QP reaction: */ + for( run1 = 0; run1 < nFR; run1++ ) + { + run2 = FR_idx[ run1 ]; + + hessianInverse[run3 * NVMAX + run2] = delta_xFR[ run1 ]; + } + + for( run1 = 0; run1 < nFX; run1++ ) + { + run2 = FX_idx[ run1 ]; + + hessianInverse[run3 * NVMAX + run2] = delta_xFX[ run1 ]; + } + + /* Prepare for the next iteration */ + delta_g_cov[ run3 ] = 0.0; + } + + // TODO: Perform the transpose of the inverse of the Hessian matrix + + return SUCCESSFUL_RETURN; +} + +/* + * g e t H e s s i a n I n v e r s e + */ +returnValue SolutionAnalysis::getHessianInverse( QProblemB* qp, real_t* hessianInverse ) +{ + returnValue returnvalue; /* the return value */ + BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */ + + register int run1, run2, run3; + + register int nFR, nFX; + + /* Ask for the number of free and fixed variables, assumes that active set + * is constant for the covariance evaluation */ + nFR = qp->getNFR( ); + nFX = qp->getNFX( ); + + /* Ask for the corresponding index arrays: */ + if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + /* Initialization: */ + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_g_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_lb_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_ub_cov[ run1 ] = 0.0; + + /* The following loop solves the following: + * + * KKT * x = + * [delta_g_cov', delta_lb_cov', delta_ub_cov']' + * + * for the first NVMAX (negative) elementary vectors in order to get + * transposed inverse of the Hessian. Assuming that the Hessian is + * symmetric, the function will return transposed inverse, instead of the + * true inverse. + * + * Note, that we use negative elementary vectors due because internal + * implementation of the function hotstart_determineStepDirection requires + * so. + * + * */ + + for( run3 = 0; run3 < NVMAX; run3++ ) + { + /* Line wise loading of the corresponding (negative) elementary vector: */ + delta_g_cov[ run3 ] = -1.0; + + /* Evaluation of the step: */ + returnvalue = qp->hotstart_determineStepDirection( + FR_idx, FX_idx, + delta_g_cov, delta_lb_cov, delta_ub_cov, + Delta_bB_isZero, + delta_xFX, delta_xFR, delta_yFX + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + return returnvalue; + } + + /* Line wise storage of the QP reaction: */ + for( run1 = 0; run1 < nFR; run1++ ) + { + run2 = FR_idx[ run1 ]; + + hessianInverse[run3 * NVMAX + run2] = delta_xFR[ run1 ]; + } + + for( run1 = 0; run1 < nFX; run1++ ) + { + run2 = FX_idx[ run1 ]; + + hessianInverse[run3 * NVMAX + run2] = delta_xFX[ run1 ]; + } + + /* Prepare for the next iteration */ + delta_g_cov[ run3 ] = 0.0; + } + + // TODO: Perform the transpose of the inverse of the Hessian matrix + + return SUCCESSFUL_RETURN; +} + +/* + * g e t V a r i a n c e C o v a r i a n c e + */ + +#if QPOASES_USE_OLD_VERSION + +returnValue SolutionAnalysis::getVarianceCovariance( QProblem* qp, real_t* g_b_bA_VAR, real_t* Primal_Dual_VAR ) +{ + int run1, run2, run3; /* simple run variables (for loops). */ + + returnValue returnvalue; /* the return value */ + BooleanType Delta_bC_isZero = BT_FALSE; /* (just use FALSE here) */ + BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */ + + /* ASK FOR THE NUMBER OF FREE AND FIXED VARIABLES: + * (ASSUMES THAT ACTIVE SET IS CONSTANT FOR THE + * VARIANCE-COVARIANCE EVALUATION) + * ----------------------------------------------- */ + int nFR, nFX, nAC; + + nFR = qp->getNFR( ); + nFX = qp->getNFX( ); + nAC = qp->getNAC( ); + + if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( qp->constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + /* SOME INITIALIZATIONS: + * --------------------- */ + for( run1 = 0; run1 < KKT_DIM * KKT_DIM; run1++ ) + { + K [run1] = 0.0; + Primal_Dual_VAR[run1] = 0.0; + } + + /* ================================================================= */ + + /* FIRST MATRIX MULTIPLICATION (OBTAINS THE INTERMEDIATE RESULT + * K := [ ("ACTIVE" KKT-MATRIX OF THE QP)^(-1) * g_b_bA_VAR ]^T ) + * THE EVALUATION OF THE INVERSE OF THE KKT-MATRIX OF THE QP + * WITH RESPECT TO THE CURRENT ACTIVE SET + * USES THE EXISTING CHOLESKY AND TQ-DECOMPOSITIONS. FOR DETAILS + * cf. THE (protected) FUNCTION determineStepDirection. */ + + for( run3 = 0; run3 < KKT_DIM; run3++ ) + { + + for( run1 = 0; run1 < NVMAX; run1++ ) + { + delta_g_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+run1]; + delta_lb_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+NVMAX+run1]; /* LINE-WISE LOADING OF THE INPUT */ + delta_ub_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+NVMAX+run1]; /* VARIANCE-COVARIANCE */ + } + for( run1 = 0; run1 < NCMAX; run1++ ) + { + delta_lbA_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+2*NVMAX+run1]; + delta_ubA_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+2*NVMAX+run1]; + } + + /* EVALUATION OF THE STEP: + * ------------------------------------------------------------------------------ */ + + returnvalue = qp->hotstart_determineStepDirection( + FR_idx, FX_idx, AC_idx, + delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov, + Delta_bC_isZero, Delta_bB_isZero, delta_xFX,delta_xFR, + delta_yAC,delta_yFX ); + + /* ------------------------------------------------------------------------------ */ + + /* STOP THE ALGORITHM IN THE CASE OF NO SUCCESFUL RETURN: + * ------------------------------------------------------ */ + if ( returnvalue != SUCCESSFUL_RETURN ) + { + return returnvalue; + } + + /* LINE WISE */ + /* STORAGE OF THE QP-REACTION */ + /* (uses the index list) */ + + for( run1=0; run1hotstart_determineStepDirection( + FR_idx, FX_idx, AC_idx, + delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov, + Delta_bC_isZero, Delta_bB_isZero, delta_xFX,delta_xFR, + delta_yAC,delta_yFX ); + + /* ------------------------------------------------------------------------------ */ + + /* STOP THE ALGORITHM IN THE CASE OF NO SUCCESFUL RETURN: + * ------------------------------------------------------ */ + if ( returnvalue != SUCCESSFUL_RETURN ) + { + return returnvalue; + } + + /* ROW-WISE STORAGE */ + /* OF THE RESULT. */ + + for( run1=0; run1 + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * I n d e x l i s t + */ +Indexlist::Indexlist( ) : length( 0 ), + first( -1 ), + last( -1 ), + lastusedindex( -1 ), + physicallength( INDEXLISTFACTOR*(NVMAX+NCMAX) ) +{ + int i; + + for( i=0; i= 0 ) && ( number[n] >= 0 ) ) + numberarray[i] = number[n]; + else + return THROWERROR( RET_INDEXLIST_CORRUPTED ); + + n = next[n]; + } + + return SUCCESSFUL_RETURN; +} + + +/* + * g e t I n d e x + */ +int Indexlist::getIndex( int givennumber ) const +{ + int i; + int n = first; + int index = -1; /* return -1 by default */ + + /* Run trough indexlist until number is found, if so return it index. */ + for ( i=0; i length ) ) + return -RET_INDEXLIST_OUTOFBOUNDS; + + return number[physicalindex]; +} + + +/* + * g e t L e n g t h + */ +inline int Indexlist::getLength( ) +{ + return length; +} + + +/* + * g e t L a s t N u m b e r + */ +inline int Indexlist::getLastNumber( ) const +{ + return number[last]; +} + + +/* + * g e t L a s t N u m b e r + */ +inline BooleanType Indexlist::isMember( int _number ) const +{ + if ( getIndex( _number ) >= 0 ) + return BT_TRUE; + else + return BT_FALSE; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/MessageHandling.cpp b/phonelibs/qpoases/SRC/MessageHandling.cpp new file mode 100644 index 00000000000000..6e68cd8552449e --- /dev/null +++ b/phonelibs/qpoases/SRC/MessageHandling.cpp @@ -0,0 +1,529 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/MessageHandling.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the MessageHandling class including global return values. + * + */ + + + +#include +#include + + + + +/** Defines pairs of global return values and messages. */ +MessageHandling::ReturnValueList returnValueList[] = +{ +/* miscellaneous */ +{ SUCCESSFUL_RETURN, "Successful return", VS_VISIBLE }, +{ RET_DIV_BY_ZERO, "Division by zero", VS_VISIBLE }, +{ RET_INDEX_OUT_OF_BOUNDS, "Index out of bounds", VS_VISIBLE }, +{ RET_INVALID_ARGUMENTS, "At least one of the arguments is invalid", VS_VISIBLE }, +{ RET_ERROR_UNDEFINED, "Error number undefined", VS_VISIBLE }, +{ RET_WARNING_UNDEFINED, "Warning number undefined", VS_VISIBLE }, +{ RET_INFO_UNDEFINED, "Info number undefined", VS_VISIBLE }, +{ RET_EWI_UNDEFINED, "Error/warning/info number undefined", VS_VISIBLE }, +{ RET_AVAILABLE_WITH_LINUX_ONLY, "This function is available under Linux only", VS_HIDDEN }, +{ RET_UNKNOWN_BUG, "The error occured is not yet known", VS_VISIBLE }, +{ RET_PRINTLEVEL_CHANGED, "Print level changed", VS_VISIBLE }, +{ RET_NOT_YET_IMPLEMENTED, "Requested function is not yet implemented.", VS_VISIBLE }, +/* Indexlist */ +{ RET_INDEXLIST_MUST_BE_REORDERD, "Index list has to be reordered", VS_VISIBLE }, +{ RET_INDEXLIST_EXCEEDS_MAX_LENGTH, "Index list exceeds its maximal physical length", VS_VISIBLE }, +{ RET_INDEXLIST_CORRUPTED, "Index list corrupted", VS_VISIBLE }, +{ RET_INDEXLIST_OUTOFBOUNDS, "Physical index is out of bounds", VS_VISIBLE }, +{ RET_INDEXLIST_ADD_FAILED, "Adding indices from another index set failed", VS_VISIBLE }, +{ RET_INDEXLIST_INTERSECT_FAILED, "Intersection with another index set failed", VS_VISIBLE }, +/* SubjectTo / Bounds / Constraints */ +{ RET_INDEX_ALREADY_OF_DESIRED_STATUS, "Index is already of desired status", VS_VISIBLE }, +{ RET_SWAPINDEX_FAILED, "Cannot swap between different indexsets", VS_VISIBLE }, +{ RET_ADDINDEX_FAILED, "Adding index to index set failed", VS_VISIBLE }, +{ RET_NOTHING_TO_DO, "Nothing to do", VS_VISIBLE }, +{ RET_SETUP_BOUND_FAILED, "Setting up bound index failed", VS_VISIBLE }, +{ RET_SETUP_CONSTRAINT_FAILED, "Setting up constraint index failed", VS_VISIBLE }, +{ RET_MOVING_BOUND_FAILED, "Moving bound between index sets failed", VS_VISIBLE }, +{ RET_MOVING_CONSTRAINT_FAILED, "Moving constraint between index sets failed", VS_VISIBLE }, +/* QProblem */ +{ RET_QP_ALREADY_INITIALISED, "QProblem has already been initialised", VS_VISIBLE }, +{ RET_NO_INIT_WITH_STANDARD_SOLVER, "Initialisation via extern QP solver is not yet implemented", VS_VISIBLE }, +{ RET_RESET_FAILED, "Reset failed", VS_VISIBLE }, +{ RET_INIT_FAILED, "Initialisation failed", VS_VISIBLE }, +{ RET_INIT_FAILED_TQ, "Initialisation failed due to TQ factorisation", VS_VISIBLE }, +{ RET_INIT_FAILED_CHOLESKY, "Initialisation failed due to Cholesky decomposition", VS_VISIBLE }, +{ RET_INIT_FAILED_HOTSTART, "Initialisation failed! QP could not be solved!", VS_VISIBLE }, +{ RET_INIT_FAILED_INFEASIBILITY, "Initial QP could not be solved due to infeasibility!", VS_VISIBLE }, +{ RET_INIT_FAILED_UNBOUNDEDNESS, "Initial QP could not be solved due to unboundedness!", VS_VISIBLE }, +{ RET_INIT_SUCCESSFUL, "Initialisation done", VS_VISIBLE }, +{ RET_OBTAINING_WORKINGSET_FAILED, "Failed to obtain working set for auxiliary QP", VS_VISIBLE }, +{ RET_SETUP_WORKINGSET_FAILED, "Failed to setup working set for auxiliary QP", VS_VISIBLE }, +{ RET_SETUP_AUXILIARYQP_FAILED, "Failed to setup auxiliary QP for initialised homotopy", VS_VISIBLE }, +{ RET_NO_EXTERN_SOLVER, "No extern QP solver available", VS_VISIBLE }, +{ RET_QP_UNBOUNDED, "QP is unbounded", VS_VISIBLE }, +{ RET_QP_INFEASIBLE, "QP is infeasible", VS_VISIBLE }, +{ RET_QP_NOT_SOLVED, "Problems occured while solving QP with standard solver", VS_VISIBLE }, +{ RET_QP_SOLVED, "QP successfully solved", VS_VISIBLE }, +{ RET_UNABLE_TO_SOLVE_QP, "Problems occured while solving QP", VS_VISIBLE }, +{ RET_INITIALISATION_STARTED, "Starting problem initialisation...", VS_VISIBLE }, +{ RET_HOTSTART_FAILED, "Unable to perform homotopy due to internal error", VS_VISIBLE }, +{ RET_HOTSTART_FAILED_TO_INIT, "Unable to initialise problem", VS_VISIBLE }, +{ RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED, "Unable to perform homotopy as previous QP is not solved", VS_VISIBLE }, +{ RET_ITERATION_STARTED, "Iteration", VS_VISIBLE }, +{ RET_SHIFT_DETERMINATION_FAILED, "Determination of shift of the QP data failed", VS_VISIBLE }, +{ RET_STEPDIRECTION_DETERMINATION_FAILED, "Determination of step direction failed", VS_VISIBLE }, +{ RET_STEPLENGTH_DETERMINATION_FAILED, "Determination of step direction failed", VS_VISIBLE }, +{ RET_OPTIMAL_SOLUTION_FOUND, "Optimal solution of neighbouring QP found", VS_VISIBLE }, +{ RET_HOMOTOPY_STEP_FAILED, "Unable to perform homotopy step", VS_VISIBLE }, +{ RET_HOTSTART_STOPPED_INFEASIBILITY, "Premature homotopy termination because QP is infeasible", VS_VISIBLE }, +{ RET_HOTSTART_STOPPED_UNBOUNDEDNESS, "Premature homotopy termination because QP is unbounded", VS_VISIBLE }, +{ RET_WORKINGSET_UPDATE_FAILED, "Unable to update working sets according to initial guesses", VS_VISIBLE }, +{ RET_MAX_NWSR_REACHED, "Maximum number of working set recalculations performed", VS_VISIBLE }, +{ RET_CONSTRAINTS_NOT_SPECIFIED, "Problem does comprise constraints! You have to specify new constraints' bounds", VS_VISIBLE }, +{ RET_INVALID_FACTORISATION_FLAG, "Invalid factorisation flag", VS_VISIBLE }, +{ RET_UNABLE_TO_SAVE_QPDATA, "Unable to save QP data", VS_VISIBLE }, +{ RET_STEPDIRECTION_FAILED_TQ, "Abnormal termination due to TQ factorisation", VS_VISIBLE }, +{ RET_STEPDIRECTION_FAILED_CHOLESKY, "Abnormal termination due to Cholesky factorisation", VS_VISIBLE }, +{ RET_CYCLING_DETECTED, "Cycling detected", VS_VISIBLE }, +{ RET_CYCLING_NOT_RESOLVED, "Cycling cannot be resolved, QP is probably infeasible", VS_VISIBLE }, +{ RET_CYCLING_RESOLVED, "Cycling probably resolved", VS_VISIBLE }, +{ RET_STEPSIZE, "", VS_VISIBLE }, +{ RET_STEPSIZE_NONPOSITIVE, "", VS_VISIBLE }, +{ RET_SETUPSUBJECTTOTYPE_FAILED, "Setup of SubjectToTypes failed", VS_VISIBLE }, +{ RET_ADDCONSTRAINT_FAILED, "Addition of constraint to working set failed", VS_VISIBLE }, +{ RET_ADDCONSTRAINT_FAILED_INFEASIBILITY, "Addition of constraint to working set failed", VS_VISIBLE }, +{ RET_ADDBOUND_FAILED, "Addition of bound to working set failed", VS_VISIBLE }, +{ RET_ADDBOUND_FAILED_INFEASIBILITY, "Addition of bound to working set failed", VS_VISIBLE }, +{ RET_REMOVECONSTRAINT_FAILED, "Removal of constraint from working set failed", VS_VISIBLE }, +{ RET_REMOVEBOUND_FAILED, "Removal of bound from working set failed", VS_VISIBLE }, +{ RET_REMOVE_FROM_ACTIVESET, "Removing from active set:", VS_VISIBLE }, +{ RET_ADD_TO_ACTIVESET, "Adding to active set:", VS_VISIBLE }, +{ RET_REMOVE_FROM_ACTIVESET_FAILED, "Removing from active set failed", VS_VISIBLE }, +{ RET_ADD_TO_ACTIVESET_FAILED, "Adding to active set failed", VS_VISIBLE }, +{ RET_CONSTRAINT_ALREADY_ACTIVE, "Constraint is already active", VS_VISIBLE }, +{ RET_ALL_CONSTRAINTS_ACTIVE, "All constraints are active, no further constraint can be added", VS_VISIBLE }, +{ RET_LINEARLY_DEPENDENT, "New bound/constraint is linearly dependent", VS_VISIBLE }, +{ RET_LINEARLY_INDEPENDENT, "New bound/constraint is linearly independent", VS_VISIBLE }, +{ RET_LI_RESOLVED, "Linear independence of active contraint matrix successfully resolved", VS_VISIBLE }, +{ RET_ENSURELI_FAILED, "Failed to ensure linear indepence of active contraint matrix", VS_VISIBLE }, +{ RET_ENSURELI_FAILED_TQ, "Abnormal termination due to TQ factorisation", VS_VISIBLE }, +{ RET_ENSURELI_FAILED_NOINDEX, "No index found, QP is probably infeasible", VS_VISIBLE }, +{ RET_ENSURELI_FAILED_CYCLING, "Cycling detected, QP is probably infeasible", VS_VISIBLE }, +{ RET_BOUND_ALREADY_ACTIVE, "Bound is already active", VS_VISIBLE }, +{ RET_ALL_BOUNDS_ACTIVE, "All bounds are active, no further bound can be added", VS_VISIBLE }, +{ RET_CONSTRAINT_NOT_ACTIVE, "Constraint is not active", VS_VISIBLE }, +{ RET_BOUND_NOT_ACTIVE, "Bound is not active", VS_VISIBLE }, +{ RET_HESSIAN_NOT_SPD, "Projected Hessian matrix not positive definite", VS_VISIBLE }, +{ RET_MATRIX_SHIFT_FAILED, "Unable to update matrices or to transform vectors", VS_VISIBLE }, +{ RET_MATRIX_FACTORISATION_FAILED, "Unable to calculate new matrix factorisations", VS_VISIBLE }, +{ RET_PRINT_ITERATION_FAILED, "Unable to print information on current iteration", VS_VISIBLE }, +{ RET_NO_GLOBAL_MESSAGE_OUTPUTFILE, "No global message output file initialised", VS_VISIBLE }, +/* Utils */ +{ RET_UNABLE_TO_OPEN_FILE, "Unable to open file", VS_VISIBLE }, +{ RET_UNABLE_TO_WRITE_FILE, "Unable to write into file", VS_VISIBLE }, +{ RET_UNABLE_TO_READ_FILE, "Unable to read from file", VS_VISIBLE }, +{ RET_FILEDATA_INCONSISTENT, "File contains inconsistent data", VS_VISIBLE }, +/* SolutionAnalysis */ +{ RET_NO_SOLUTION, "QP solution does not satisfy KKT optimality conditions", VS_VISIBLE }, +{ RET_INACCURATE_SOLUTION, "KKT optimality conditions not satisfied to sufficient accuracy", VS_VISIBLE }, +{ TERMINAL_LIST_ELEMENT, "", VS_HIDDEN } /* IMPORTANT: Terminal list element! */ +}; + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * M e s s a g e H a n d l i n g + */ +MessageHandling::MessageHandling( ) : errorVisibility( VS_VISIBLE ), + warningVisibility( VS_VISIBLE ), + infoVisibility( VS_VISIBLE ), + outputFile( myStdout ), + errorCount( 0 ) +{ +} + +/* + * M e s s a g e H a n d l i n g + */ +MessageHandling::MessageHandling( myFILE* _outputFile ) : + errorVisibility( VS_VISIBLE ), + warningVisibility( VS_VISIBLE ), + infoVisibility( VS_VISIBLE ), + outputFile( _outputFile ), + errorCount( 0 ) +{ +} + +/* + * M e s s a g e H a n d l i n g + */ +MessageHandling::MessageHandling( VisibilityStatus _errorVisibility, + VisibilityStatus _warningVisibility, + VisibilityStatus _infoVisibility + ) : + errorVisibility( _errorVisibility ), + warningVisibility( _warningVisibility ), + infoVisibility( _infoVisibility ), + outputFile( myStderr ), + errorCount( 0 ) +{ +} + +/* + * M e s s a g e H a n d l i n g + */ +MessageHandling::MessageHandling( myFILE* _outputFile, + VisibilityStatus _errorVisibility, + VisibilityStatus _warningVisibility, + VisibilityStatus _infoVisibility + ) : + errorVisibility( _errorVisibility ), + warningVisibility( _warningVisibility ), + infoVisibility( _infoVisibility ), + outputFile( _outputFile ), + errorCount( 0 ) +{ +} + + + +/* + * M e s s a g e H a n d l i n g + */ +MessageHandling::MessageHandling( const MessageHandling& rhs ) : + errorVisibility( rhs.errorVisibility ), + warningVisibility( rhs.warningVisibility ), + infoVisibility( rhs.infoVisibility ), + outputFile( rhs.outputFile ), + errorCount( rhs.errorCount ) +{ +} + + +/* + * ~ M e s s a g e H a n d l i n g + */ +MessageHandling::~MessageHandling( ) +{ + #ifdef PC_DEBUG + if ( outputFile != 0 ) + fclose( outputFile ); + #endif +} + + +/* + * o p e r a t o r = + */ +MessageHandling& MessageHandling::operator=( const MessageHandling& rhs ) +{ + if ( this != &rhs ) + { + errorVisibility = rhs.errorVisibility; + warningVisibility = rhs.warningVisibility; + infoVisibility = rhs.infoVisibility; + outputFile = rhs.outputFile; + errorCount = rhs.errorCount; + } + + return *this; +} + + +/* + * t h r o w E r r o r + */ +returnValue MessageHandling::throwError( + returnValue Enumber, + const char* additionaltext, + const char* functionname, + const char* filename, + const unsigned long linenumber, + VisibilityStatus localVisibilityStatus + ) +{ + /* consistency check */ + if ( Enumber <= SUCCESSFUL_RETURN ) + return throwError( RET_ERROR_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + + /* Call to common throwMessage function if error shall be displayed. */ + if ( errorVisibility == VS_VISIBLE ) + return throwMessage( Enumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"ERROR" ); + else + return Enumber; +} + + +/* + * t h r o w W a r n i n g + */ +returnValue MessageHandling::throwWarning( + returnValue Wnumber, + const char* additionaltext, + const char* functionname, + const char* filename, + const unsigned long linenumber, + VisibilityStatus localVisibilityStatus + ) +{ + /* consistency check */ + if ( Wnumber <= SUCCESSFUL_RETURN ) + return throwError( RET_WARNING_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + + /* Call to common throwMessage function if warning shall be displayed. */ + if ( warningVisibility == VS_VISIBLE ) + return throwMessage( Wnumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"WARNING" ); + else + return Wnumber; +} + + +/* + * t h r o w I n f o + */ +returnValue MessageHandling::throwInfo( + returnValue Inumber, + const char* additionaltext, + const char* functionname, + const char* filename, + const unsigned long linenumber, + VisibilityStatus localVisibilityStatus + ) +{ + /* consistency check */ + if ( Inumber < SUCCESSFUL_RETURN ) + return throwError( RET_INFO_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + + /* Call to common throwMessage function if info shall be displayed. */ + if ( infoVisibility == VS_VISIBLE ) + return throwMessage( Inumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"INFO" ); + else + return Inumber; +} + + +/* + * r e s e t + */ +returnValue MessageHandling::reset( ) +{ + setErrorVisibilityStatus( VS_VISIBLE ); + setWarningVisibilityStatus( VS_VISIBLE ); + setInfoVisibilityStatus( VS_VISIBLE ); + + setOutputFile( myStderr ); + setErrorCount( 0 ); + + return SUCCESSFUL_RETURN; +} + + +/* + * l i s t A l l M e s s a g e s + */ +returnValue MessageHandling::listAllMessages( ) +{ + #ifdef PC_DEBUG + int keypos = 0; + char myPrintfString[160]; + + /* Run through whole returnValueList and print each item. */ + while ( returnValueList[keypos].key != TERMINAL_LIST_ELEMENT ) + { + sprintf( myPrintfString," %d - %s \n",keypos,returnValueList[keypos].data ); + myPrintf( myPrintfString ); + + ++keypos; + } + #endif + + return SUCCESSFUL_RETURN; +} + + + +/***************************************************************************** + * P R O T E C T E D * + *****************************************************************************/ + + +#ifdef PC_DEBUG /* Re-define throwMessage function for embedded code! */ + +/* + * t h r o w M e s s a g e + */ +returnValue MessageHandling::throwMessage( + returnValue RETnumber, + const char* additionaltext, + const char* functionname, + const char* filename, + const unsigned long linenumber, + VisibilityStatus localVisibilityStatus, + const char* RETstring + ) +{ + int i; + + int keypos = 0; + char myPrintfString[160]; + + /* 1) Determine number of whitespace for output. */ + char whitespaces[41]; + int numberOfWhitespaces = (errorCount-1)*2; + + if ( numberOfWhitespaces < 0 ) + numberOfWhitespaces = 0; + + if ( numberOfWhitespaces > 40 ) + numberOfWhitespaces = 40; + + for( i=0; i 0 ) + { + sprintf( myPrintfString,"%s->", whitespaces ); + myPrintf( myPrintfString ); + } + + if ( additionaltext == 0 ) + { + sprintf( myPrintfString,"%s (%s, %s:%d): \t%s\n", + RETstring,functionname,filename,(int)linenumber,returnValueList[keypos].data + ); + myPrintf( myPrintfString ); + } + else + { + sprintf( myPrintfString,"%s (%s, %s:%d): \t%s %s\n", + RETstring,functionname,filename,(int)linenumber,returnValueList[keypos].data,additionaltext + ); + myPrintf( myPrintfString ); + } + + /* take care of proper indention for subsequent error messages */ + if ( RETstring[0] == 'E' ) + { + ++errorCount; + } + else + { + if ( errorCount > 0 ) + myPrintf( "\n" ); + errorCount = 0; + } + } + + return RETnumber; +} + +#else /* = PC_DEBUG not defined */ + +/* + * t h r o w M e s s a g e + */ +returnValue MessageHandling::throwMessage( + returnValue RETnumber, + const char* additionaltext, + const char* functionname, + const char* filename, + const unsigned long linenumber, + VisibilityStatus localVisibilityStatus, + const char* RETstring + ) +{ + /* DUMMY CODE FOR PRETENDING USE OF ARGUMENTS + * FOR SUPPRESSING COMPILER WARNINGS! */ + int i = 0; + if ( additionaltext == 0 ) i++; + if ( functionname == 0 ) i++; + if ( filename == 0 ) i++; + if ( linenumber == 0 ) i++; + if ( localVisibilityStatus == VS_VISIBLE ) i++; + if ( RETstring == 0 ) i++; + /* END OF DUMMY CODE */ + + return RETnumber; +} + +#endif /* PC_DEBUG */ + + + +/***************************************************************************** + * G L O B A L M E S S A G E H A N D L E R * + *****************************************************************************/ + + +/** Global message handler for all qpOASES modules.*/ +MessageHandling globalMessageHandler( myStderr,VS_VISIBLE,VS_VISIBLE,VS_VISIBLE ); + + +/* + * g e t G l o b a l M e s s a g e H a n d l e r + */ +MessageHandling* getGlobalMessageHandler( ) +{ + return &globalMessageHandler; +} + +const char* MessageHandling::getErrorString(int error) +{ + return returnValueList[ error ].data; +} + + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/MessageHandling.ipp b/phonelibs/qpoases/SRC/MessageHandling.ipp new file mode 100644 index 00000000000000..ad9624b3d69a62 --- /dev/null +++ b/phonelibs/qpoases/SRC/MessageHandling.ipp @@ -0,0 +1,137 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/MessageHandling.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of inlined member functions of the MessageHandling class. + */ + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + +/* + * g e t E r r o r V i s i b i l i t y S t a t u s + */ +inline VisibilityStatus MessageHandling::getErrorVisibilityStatus( ) const +{ + return errorVisibility; +} + + +/* + * g e t W a r n i n g V i s i b i l i t y S t a t u s + */ +inline VisibilityStatus MessageHandling::getWarningVisibilityStatus( ) const +{ + return warningVisibility; +} + + +/* + * g e t I n f o V i s i b i l i t y S t a t u s + */ +inline VisibilityStatus MessageHandling::getInfoVisibilityStatus( ) const +{ + return infoVisibility; +} + + +/* + * g e t O u t p u t F i l e + */ +inline myFILE* MessageHandling::getOutputFile( ) const +{ + return outputFile; +} + + +/* + * g e t E r r o r C o u n t + */ +inline int MessageHandling::getErrorCount( ) const +{ + return errorCount; +} + + +/* + * s e t E r r o r V i s i b i l i t y S t a t u s + */ +inline void MessageHandling::setErrorVisibilityStatus( VisibilityStatus _errorVisibility ) +{ + errorVisibility = _errorVisibility; +} + + +/* + * s e t W a r n i n g V i s i b i l i t y S t a t u s + */ +inline void MessageHandling::setWarningVisibilityStatus( VisibilityStatus _warningVisibility ) +{ + warningVisibility = _warningVisibility; +} + + +/* + * s e t I n f o V i s i b i l i t y S t a t u s + */ +inline void MessageHandling::setInfoVisibilityStatus( VisibilityStatus _infoVisibility ) +{ + infoVisibility = _infoVisibility; +} + + +/* + * s e t O u t p u t F i l e + */ +inline void MessageHandling::setOutputFile( myFILE* _outputFile ) +{ + outputFile = _outputFile; +} + + +/* + * s e t E r r o r C o u n t + */ +inline returnValue MessageHandling::setErrorCount( int _errorCount ) +{ + if ( _errorCount >= 0 ) + { + errorCount = _errorCount; + return SUCCESSFUL_RETURN; + } + else + return RET_INVALID_ARGUMENTS; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/QProblem.cpp b/phonelibs/qpoases/SRC/QProblem.cpp new file mode 100644 index 00000000000000..68a6a79e534f65 --- /dev/null +++ b/phonelibs/qpoases/SRC/QProblem.cpp @@ -0,0 +1,3867 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/QProblem.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the QProblem class which is able to use the newly + * developed online active set strategy for parametric quadratic programming. + */ + + +#include + +#include + +void printmatrix2(char *name, double *A, int m, int n) { + int i, j; + + printf("%s = [...\n", name); + for (i = 0; i < m; i++) { + for (j = 0; j < n; j++) + printf(" % 9.4f", A[i*n+j]); + printf(",\n"); + } + printf("];\n"); +} + +//#define __PERFORM_KKT_TEST__ + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * Q P r o b l e m + */ +QProblem::QProblem( ) : QProblemB( ) +{ + constraints.init( 0 ); + + sizeT = 0; + + cyclingManager.init( 0,0 ); +} + + +/* + * Q P r o b l e m + */ +QProblem::QProblem( int _nV, int _nC ) : QProblemB( _nV ) +{ + /* consistency checks */ + if ( _nV <= 0 ) + _nV = 1; + + if ( _nC < 0 ) + { + _nC = 0; + THROWERROR( RET_INVALID_ARGUMENTS ); + } + + constraints.init( _nC ); + + + sizeT = _nC; + if ( _nC > _nV ) + sizeT = _nV; + + cyclingManager.init( _nV,_nC ); +} + + +/* + * Q P r o b l e m + */ +QProblem::QProblem( const QProblem& rhs ) : QProblemB( rhs ) +{ + int i, j; + + int _nV = rhs.bounds.getNV( ); + int _nC = rhs.constraints.getNC( ); + + for( i=0; i<_nC; ++i ) + for( j=0; j<_nV; ++j ) + A[i*NVMAX + j] = rhs.A[i*NVMAX + j]; + + for( i=0; i<_nC; ++i ) + lbA[i] = rhs.lbA[i]; + + for( i=0; i<_nC; ++i ) + ubA[i] = rhs.ubA[i]; + + constraints = rhs.constraints; + + for( i=0; i<(_nV+_nC); ++i ) + y[i] = rhs.y[i]; + + + sizeT = rhs.sizeT; + + for( i=0; ithrowInfo( RET_ITERATION_STARTED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + /* 1) Setup index arrays. */ + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( constraints.getInactive( )->getNumberArray( IAC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + /* 2) Detemination of shift direction of the gradient and the (constraints') bounds. */ + returnvalue = hotstart_determineDataShift( FX_idx, AC_idx, + g_new,lbA_new,ubA_new,lb_new,ub_new, + delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub, + Delta_bC_isZero, Delta_bB_isZero ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_SHIFT_DETERMINATION_FAILED ); + return returnvalue; + } + + /* 3) Determination of step direction of X and Y. */ + returnvalue = hotstart_determineStepDirection( FR_idx,FX_idx,AC_idx, + delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub, + Delta_bC_isZero, Delta_bB_isZero, + delta_xFX,delta_xFR,delta_yAC,delta_yFX + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_STEPDIRECTION_DETERMINATION_FAILED ); + return returnvalue; + } + + /* 4) Determination of step length TAU. */ + returnvalue = hotstart_determineStepLength( FR_idx,FX_idx,AC_idx,IAC_idx, + delta_lbA,delta_ubA,delta_lb,delta_ub, + delta_xFX,delta_xFR,delta_yAC,delta_yFX,delta_Ax, + BC_idx,BC_status,BC_isBound + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_STEPLENGTH_DETERMINATION_FAILED ); + return returnvalue; + } + + /* 5) Realisation of the homotopy step. */ + returnvalue = hotstart_performStep( FR_idx,FX_idx,AC_idx,IAC_idx, + delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub, + delta_xFX,delta_xFR,delta_yAC,delta_yFX,delta_Ax, + BC_idx,BC_status,BC_isBound + ); + + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + + /* stop runtime measurement */ + if ( cputime != 0 ) + *cputime = getCPUtime( ) - starttime; + + /* optimal solution found? */ + if ( returnvalue == RET_OPTIMAL_SOLUTION_FOUND ) + { + status = QPS_SOLVED; + + if ( printlevel == PL_HIGH ) + THROWINFO( RET_OPTIMAL_SOLUTION_FOUND ); + + #ifdef PC_DEBUG + if ( printIteration( l,BC_idx,BC_status,BC_isBound ) != SUCCESSFUL_RETURN ) + THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */ + #endif + + /* check KKT optimality conditions */ + return checkKKTconditions( ); + } + else + { + /* checks for infeasibility... */ + if ( isInfeasible( ) == BT_TRUE ) + { + status = QPS_HOMOTOPYQPSOLVED; + return THROWERROR( RET_HOTSTART_STOPPED_INFEASIBILITY ); + } + + /* ...unboundedness... */ + if ( unbounded == BT_TRUE ) /* not necessary since objective function convex! */ + return THROWERROR( RET_HOTSTART_STOPPED_UNBOUNDEDNESS ); + + /* ... and throw unspecific error otherwise */ + THROWERROR( RET_HOMOTOPY_STEP_FAILED ); + return returnvalue; + } + } + + /* 6) Output information of successful QP iteration. */ + status = QPS_HOMOTOPYQPSOLVED; + + #ifdef PC_DEBUG + if ( printIteration( l,BC_idx,BC_status,BC_isBound ) != SUCCESSFUL_RETURN ) + THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */ + #endif + } + + + /* stop runtime measurement */ + if ( cputime != 0 ) + *cputime = getCPUtime( ) - starttime; + + + /* if programm gets to here, output information that QP could not be solved + * within the given maximum numbers of working set changes */ + if ( printlevel == PL_HIGH ) + { + #ifdef PC_DEBUG + sprintf( messageString,"(nWSR = %d)",nWSR ); + return getGlobalMessageHandler( )->throwWarning( RET_MAX_NWSR_REACHED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + /* Finally check KKT optimality conditions. */ + returnValue returnvalueKKTcheck = checkKKTconditions( ); + + if ( returnvalueKKTcheck != SUCCESSFUL_RETURN ) + return returnvalueKKTcheck; + else + return RET_MAX_NWSR_REACHED; +} + + +/* + * g e t N Z + */ +int QProblem::getNZ( ) +{ + /* nZ = nFR - nAC */ + return bounds.getFree( )->getLength( ) - constraints.getActive( )->getLength( ); +} + + +/* + * g e t D u a l S o l u t i o n + */ +returnValue QProblem::getDualSolution( real_t* const yOpt ) const +{ + int i; + + /* return optimal dual solution vector + * only if current QP has been solved */ + if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + for( i=0; i -INFTY ) + { + constraints.setNoLower( BT_FALSE ); + break; + } + } + + /* 2) Check if upper constraints' bounds are present. */ + constraints.setNoUpper( BT_TRUE ); + for( i=0; i INFTY - BOUNDTOL ) ) + { + constraints.setType( i,ST_UNBOUNDED ); + ++nUC; + } + else + { + if ( lbA[i] > ubA[i] - BOUNDTOL ) + { + constraints.setType( i,ST_EQUALITY ); + ++nEC; + } + else + { + constraints.setType( i,ST_BOUNDED ); + } + } + } + + /* 4) Set dimensions of constraints structure. */ + constraints.setNEC( nEC ); + constraints.setNUC( nUC ); + constraints.setNIC( nC - nEC - nUC ); + + return SUCCESSFUL_RETURN; +} + + +/* + * c h o l e s k y D e c o m p o s i t i o n P r o j e c t e d + */ +returnValue QProblem::setupCholeskyDecompositionProjected( ) +{ + int i, j, k, ii, kk; + int nV = getNV( ); + int nFR = getNFR( ); + int nZ = getNZ( ); + + /* 1) Initialises R with all zeros. */ + for( i=0; i 0 ) + { + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INDEXLIST_CORRUPTED ); + +#if 0 + real_t HZ[NVMAX*NVMAX]; + real_t ZHZ[NVMAX*NVMAX]; + + /* calculate H*Z */ + for ( i=0; i=0; --k ) + sum -= R[k*NVMAX + i] * R[k*NVMAX + i]; + + if ( sum > 0.0 ) + { + R[i*NVMAX + i] = sqrt( sum ); + inv = 1.0 / R[i * NVMAX + i]; + } + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + + for( j=(i+1); j=0; --k ) + sum -= R[k*NVMAX + i] * R[k*NVMAX + j]; + + R[i*NVMAX + j] = sum * inv; + } + } +#else + real_t HZ[NVMAX]; + real_t ZHZ[NVMAX]; + + real_t sum, inv; + for (j = 0; j < nZ; ++j) + { + /* Cache one column of Z. */ + for (i = 0; i < NVMAX; ++i) + ZHZ[i] = Q[i * NVMAX + j]; + + /* Create one column of the product H * Z. */ + for (i = 0; i < nFR; ++i) + { + ii = FR_idx[i]; + + sum = 0.0; + for (k = 0; k < nFR; ++k) + { + kk = FR_idx[k]; + sum += H[ii * NVMAX + kk] * ZHZ[kk]; + } + HZ[ii] = sum; + } + + /* Create one column of the product Z^T * H * Z. */ + for (i = j; i < nZ; ++i) + ZHZ[ i ] = 0.0; + + for (k = 0; k < nFR; ++k) + { + kk = FR_idx[k]; + real_t q = HZ[kk]; + for (i = j; i < nZ; ++i) + { + ZHZ[i] += Q[kk * NVMAX + i] * q; + } + } + + /* Use the computed column to update the factorization. */ + /* j == i */ + sum = ZHZ[j]; + + for (k = (j - 1); k >= 0; --k) + sum -= R[k * NVMAX + j] * R[k * NVMAX + j]; + + if (sum > 0.0) + { + R[j * NVMAX + j] = sqrt(sum); + inv = 1.0 / R[j * NVMAX + j]; + } + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + + for (i = (j + 1); i < nZ; ++i) + { + sum = ZHZ[i]; + + for (k = (j - 1); k >= 0; --k) + sum -= R[k * NVMAX + j] * R[k * NVMAX + i]; + + R[j * NVMAX + i] = sum * inv; + } + } +#endif + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p T Q f a c t o r i s a t i o n + */ +returnValue QProblem::setupTQfactorisation( ) +{ + int i, j, ii; + int nV = getNV( ); + int nFR = getNFR( ); + + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INDEXLIST_CORRUPTED ); + + /* 1) Set Q to unity matrix. */ + for( i=0; igetStatus( i ); + + if ( constraints.getType( i ) == ST_EQUALITY ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryConstraints->setupConstraint( i,guessedStatus ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + else /* No initial working set specified. */ + { + /* Obtain initial working set by "clipping". */ + if ( ( xOpt != 0 ) && ( yOpt == 0 ) ) + { + for( i=0; isetupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + if ( Ax[i] >= ubA[i] - BOUNDTOL ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_UPPER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + /* Moreover, add all equality constraints if specified. */ + if ( constraints.getType( i ) == ST_EQUALITY ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + + /* Obtain initial working set in accordance to sign of dual solution vector. */ + if ( ( xOpt == 0 ) && ( yOpt != 0 ) ) + { + for( i=0; i ZERO ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + if ( yOpt[nV+i] < -ZERO ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_UPPER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + /* Moreover, add all equality constraints if specified. */ + if ( constraints.getType( i ) == ST_EQUALITY ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + + /* If xOpt and yOpt are null pointer and no initial working is specified, + * start with empty working set (or implicitly fixed bounds and equality constraints only) + * for auxiliary QP. */ + if ( ( xOpt == 0 ) && ( yOpt == 0 ) ) + { + for( i=0; isetupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + } + + return SUCCESSFUL_RETURN; +} + + + +/* + * s e t u p A u x i l i a r y W o r k i n g S e t + */ +returnValue QProblem::setupAuxiliaryWorkingSet( const Bounds* const auxiliaryBounds, + const Constraints* const auxiliaryConstraints, + BooleanType setupAfresh + ) +{ + int i; + int nV = getNV( ); + int nC = getNC( ); + + /* consistency checks */ + if ( auxiliaryBounds != 0 ) + { + for( i=0; igetStatus( i ) == ST_UNDEFINED ) ) + return THROWERROR( RET_UNKNOWN_BUG ); + } + else + { + return THROWERROR( RET_INVALID_ARGUMENTS ); + } + + if ( auxiliaryConstraints != 0 ) + { + for( i=0; igetStatus( i ) == ST_UNDEFINED ) ) + return THROWERROR( RET_UNKNOWN_BUG ); + } + else + { + return THROWERROR( RET_INVALID_ARGUMENTS ); + } + + + /* I) SETUP CHOLESKY FLAG: + * Cholesky decomposition shall only be updated if working set + * shall be updated (i.e. NOT setup afresh!) */ + BooleanType updateCholesky; + if ( setupAfresh == BT_TRUE ) + updateCholesky = BT_FALSE; + else + updateCholesky = BT_TRUE; + + + /* II) REMOVE FORMERLY ACTIVE (CONSTRAINTS') BOUNDS (IF NECESSARY): */ + if ( setupAfresh == BT_FALSE ) + { + /* 1) Remove all active constraints that shall be inactive AND + * all active constraints that are active at the wrong bound. */ + for( i=0; igetStatus( i ) != ST_LOWER ) ) + if ( removeConstraint( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + + if ( ( constraints.getStatus( i ) == ST_UPPER ) && ( auxiliaryConstraints->getStatus( i ) != ST_UPPER ) ) + if ( removeConstraint( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + + /* 2) Remove all active bounds that shall be inactive AND + * all active bounds that are active at the wrong bound. */ + for( i=0; igetStatus( i ) != ST_LOWER ) ) + if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + + if ( ( bounds.getStatus( i ) == ST_UPPER ) && ( auxiliaryBounds->getStatus( i ) != ST_UPPER ) ) + if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + } + + + /* III) ADD NEWLY ACTIVE (CONSTRAINTS') BOUNDS: */ + /* 1) Add all inactive bounds that shall be active AND + * all formerly active bounds that have been active at the wrong bound. */ + for( i=0; igetStatus( i ) != ST_INACTIVE ) ) + { + /* Add bound only if it is linearly independent from the current working set. */ + if ( addBound_checkLI( i ) == RET_LINEARLY_INDEPENDENT ) + { + if ( addBound( i,auxiliaryBounds->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + } + } + + /* 2) Add all inactive constraints that shall be active AND + * all formerly active constraints that have been active at the wrong bound. */ + for( i=0; igetStatus( i ) == ST_LOWER ) || ( auxiliaryConstraints->getStatus( i ) == ST_UPPER ) ) + { + /* formerly inactive */ + if ( constraints.getStatus( i ) == ST_INACTIVE ) + { + /* Add constraint only if it is linearly independent from the current working set. */ + if ( addConstraint_checkLI( i ) == RET_LINEARLY_INDEPENDENT ) + { + if ( addConstraint( i,auxiliaryConstraints->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + } + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p A u x i l i a r y Q P s o l u t i o n + */ +returnValue QProblem::setupAuxiliaryQPsolution( const real_t* const xOpt, const real_t* const yOpt + ) +{ + int i, j; + int nV = getNV( ); + int nC = getNC( ); + + + /* Setup primal/dual solution vector for auxiliary initial QP: + * if a null pointer is passed, a zero vector is assigned; + * old solution vector is kept if pointer to internal solution vevtor is passed. */ + if ( xOpt != 0 ) + { + if ( xOpt != x ) + for( i=0; igetStatus( i ) == ST_LOWER ) + lb[i] = x[i]; + else + lb[i] = x[i] - BOUNDRELAXATION; + + if ( auxiliaryBounds->getStatus( i ) == ST_UPPER ) + ub[i] = x[i]; + else + ub[i] = x[i] + BOUNDRELAXATION; + } + } + break; + + case ST_LOWER: + lb[i] = x[i]; + if ( bounds.getType( i ) == ST_EQUALITY ) + { + ub[i] = x[i]; + } + else + { + if ( useRelaxation == BT_TRUE ) + ub[i] = x[i] + BOUNDRELAXATION; + } + break; + + case ST_UPPER: + ub[i] = x[i]; + if ( bounds.getType( i ) == ST_EQUALITY ) + { + lb[i] = x[i]; + } + else + { + if ( useRelaxation == BT_TRUE ) + lb[i] = x[i] - BOUNDRELAXATION; + } + break; + + default: + return THROWERROR( RET_UNKNOWN_BUG ); + } + } + + /* 2) Setup constraints vectors. */ + for ( i=0; igetStatus( i ) == ST_LOWER ) + lbA[i] = Ax[i]; + else + lbA[i] = Ax[i] - BOUNDRELAXATION; + + if ( auxiliaryConstraints->getStatus( i ) == ST_UPPER ) + ubA[i] = Ax[i]; + else + ubA[i] = Ax[i] + BOUNDRELAXATION; + } + } + break; + + case ST_LOWER: + lbA[i] = Ax[i]; + if ( constraints.getType( i ) == ST_EQUALITY ) + { + ubA[i] = Ax[i]; + } + else + { + if ( useRelaxation == BT_TRUE ) + ubA[i] = Ax[i] + BOUNDRELAXATION; + } + break; + + case ST_UPPER: + ubA[i] = Ax[i]; + if ( constraints.getType( i ) == ST_EQUALITY ) + { + lbA[i] = Ax[i]; + } + else + { + if ( useRelaxation == BT_TRUE ) + lbA[i] = Ax[i] - BOUNDRELAXATION; + } + break; + + default: + return THROWERROR( RET_UNKNOWN_BUG ); + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * a d d C o n s t r a i n t + */ +returnValue QProblem::addConstraint( int number, SubjectToStatus C_status, + BooleanType updateCholesky + ) +{ + int i, j, ii; + + /* consistency checks */ + if ( constraints.getStatus( number ) != ST_INACTIVE ) + return THROWERROR( RET_CONSTRAINT_ALREADY_ACTIVE ); + + if ( ( constraints.getNC( ) - getNAC( ) ) == constraints.getNUC( ) ) + return THROWERROR( RET_ALL_CONSTRAINTS_ACTIVE ); + + if ( ( getStatus( ) == QPS_NOTINITIALISED ) || + ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + return THROWERROR( RET_UNKNOWN_BUG ); + } + + + /* I) ENSURE LINEAR INDEPENDENCE OF THE WORKING SET, + * i.e. remove a constraint or bound if linear dependence occurs. */ + /* check for LI only if Cholesky decomposition shall be updated! */ + if ( updateCholesky == BT_TRUE ) + { + returnValue ensureLIreturnvalue = addConstraint_ensureLI( number,C_status ); + + switch ( ensureLIreturnvalue ) + { + case SUCCESSFUL_RETURN: + break; + + case RET_LI_RESOLVED: + break; + + case RET_ENSURELI_FAILED_NOINDEX: + return THROWERROR( RET_ADDCONSTRAINT_FAILED_INFEASIBILITY ); + + case RET_ENSURELI_FAILED_CYCLING: + return THROWERROR( RET_ADDCONSTRAINT_FAILED_INFEASIBILITY ); + + default: + return THROWERROR( RET_ENSURELI_FAILED ); + } + } + + /* some definitions */ + int nFR = getNFR( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + int tcol = sizeT - nAC; + + + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ADDCONSTRAINT_FAILED ); + + real_t aFR[NVMAX]; + real_t wZ[NVMAX]; + for( i=0; i 0 ) + { + for( j=0; j 0 ) + { + /* II) RESTORE TRIANGULAR FORM OF T: */ + /* Use column-wise Givens rotations to restore reverse triangular form + * of T, simultanenous change of Q (i.e. Z) and R. */ + for( j=0; jgetNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INDEXLIST_CORRUPTED ); + + /* Check if constraint is linearly independent from the + the active ones (<=> is element of null space of Afr). */ + real_t sum; + + for( i=0; i 10.0*EPS ) + return RET_LINEARLY_INDEPENDENT; + } + + return RET_LINEARLY_DEPENDENT; +} + + +/* + * a d d C o n s t r a i n t _ e n s u r e L I + */ +returnValue QProblem::addConstraint_ensureLI( int number, SubjectToStatus C_status ) +{ + int i, j, ii, jj; + int nV = getNV( ); + int nFR = getNFR( ); + int nFX = getNFX( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + + /* I) Check if new constraint is linearly independent from the active ones. */ + returnValue returnvalueCheckLI = addConstraint_checkLI( number ); + + if ( returnvalueCheckLI == RET_INDEXLIST_CORRUPTED ) + return THROWERROR( RET_ENSURELI_FAILED ); + + if ( returnvalueCheckLI == RET_LINEARLY_INDEPENDENT ) + return SUCCESSFUL_RETURN; + + + /* II) NEW CONSTRAINT IS LINEARLY DEPENDENT: */ + /* 1) Determine coefficients of linear combination, + * cf. M.J. Best. Applied Mathematics and Parallel Computing, chapter: + * An Algorithm for the Solution of the Parametric Quadratic Programming + * Problem, pages 57-76. Physica-Verlag, Heidelberg, 1996. */ + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + int FX_idx[NVMAX]; + if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + real_t xiC[NCMAX_ALLOC]; + real_t xiC_TMP[NCMAX_ALLOC]; + real_t xiB[NVMAX]; + + /* 2) Calculate xiC */ + if ( nAC > 0 ) + { + if ( C_status == ST_LOWER ) + { + for( i=0; igetNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + if ( C_status == ST_LOWER ) + { + for( i=0; i ZERO ) && ( y[nV+ii] >= 0.0 ) ) + { + if ( y[nV+ii]/xiC[i] < y_min ) + { + y_min = y[nV+ii]/xiC[i]; + y_min_number = ii; + } + } + } + else + { + if ( ( xiC[i] < -ZERO ) && ( y[nV+ii] <= 0.0 ) ) + { + if ( y[nV+ii]/xiC[i] < y_min ) + { + y_min = y[nV+ii]/xiC[i]; + y_min_number = ii; + } + } + } + } + + /* 2) Bounds. */ + for( i=0; i ZERO ) && ( y[ii] >= 0.0 ) ) + { + if ( y[ii]/xiB[i] < y_min ) + { + y_min = y[ii]/xiB[i]; + y_min_number = ii; + y_min_isBound = BT_TRUE; + } + } + } + else + { + if ( ( xiB[i] < -ZERO ) && ( y[ii] <= 0.0 ) ) + { + if ( y[ii]/xiB[i] < y_min ) + { + y_min = y[ii]/xiB[i]; + y_min_number = ii; + y_min_isBound = BT_TRUE; + } + } + } + } + + /* setup output preferences */ + #ifdef PC_DEBUG + char messageString[80]; + VisibilityStatus visibilityStatus; + + if ( printlevel == PL_HIGH ) + visibilityStatus = VS_VISIBLE; + else + visibilityStatus = VS_HIDDEN; + #endif + + + /* IV) REMOVE CONSTRAINT/BOUND FOR RESOLVING LINEAR DEPENDENCE: */ + if ( y_min_number >= 0 ) + { + /* 1) Check for cycling due to infeasibility. */ + if ( ( cyclingManager.getCyclingStatus( number,BT_FALSE ) == CYC_PREV_REMOVED ) && + ( cyclingManager.getCyclingStatus( y_min_number,y_min_isBound ) == CYC_PREV_ADDED ) ) + { + infeasible = BT_TRUE; + + return THROWERROR( RET_ENSURELI_FAILED_CYCLING ); + } + else + { + /* set cycling data */ + cyclingManager.clearCyclingData( ); + cyclingManager.setCyclingStatus( number,BT_FALSE, CYC_PREV_ADDED ); + cyclingManager.setCyclingStatus( y_min_number,y_min_isBound, CYC_PREV_REMOVED ); + } + + /* 2) Update Lagrange multiplier... */ + for( i=0; ithrowInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeBound( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[y_min_number] = 0.0; + } + else + { + #ifdef PC_DEBUG + sprintf( messageString,"constraint no. %d.",y_min_number ); + getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeConstraint( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[nV+y_min_number] = 0.0; + } + } + else + { + /* no constraint/bound can be removed => QP is infeasible! */ + infeasible = BT_TRUE; + + return THROWERROR( RET_ENSURELI_FAILED_NOINDEX ); + } + + return getGlobalMessageHandler( )->throwInfo( RET_LI_RESOLVED,0,__FUNCTION__,__FILE__,__LINE__,VS_HIDDEN ); +} + + + +/* + * a d d B o u n d + */ +returnValue QProblem::addBound( int number, SubjectToStatus B_status, + BooleanType updateCholesky + ) +{ + int i, j, ii; + + /* consistency checks */ + if ( bounds.getStatus( number ) != ST_INACTIVE ) + return THROWERROR( RET_BOUND_ALREADY_ACTIVE ); + + if ( getNFR( ) == bounds.getNUV( ) ) + return THROWERROR( RET_ALL_BOUNDS_ACTIVE ); + + if ( ( getStatus( ) == QPS_NOTINITIALISED ) || + ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + return THROWERROR( RET_UNKNOWN_BUG ); + } + + + /* I) ENSURE LINEAR INDEPENDENCE OF THE WORKING SET, + * i.e. remove a constraint or bound if linear dependence occurs. */ + /* check for LI only if Cholesky decomposition shall be updated! */ + if ( updateCholesky == BT_TRUE ) + { + returnValue ensureLIreturnvalue = addBound_ensureLI( number,B_status ); + + switch ( ensureLIreturnvalue ) + { + case SUCCESSFUL_RETURN: + break; + + case RET_LI_RESOLVED: + break; + + case RET_ENSURELI_FAILED_NOINDEX: + return THROWERROR( RET_ADDBOUND_FAILED_INFEASIBILITY ); + + case RET_ENSURELI_FAILED_CYCLING: + return THROWERROR( RET_ADDBOUND_FAILED_INFEASIBILITY ); + + default: + return THROWERROR( RET_ENSURELI_FAILED ); + } + } + + + /* some definitions */ + int nFR = getNFR( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + int tcol = sizeT - nAC; + + + /* I) SWAP INDEXLIST OF FREE VARIABLES: + * move the variable to be fixed to the end of the list of free variables. */ + int lastfreenumber = bounds.getFree( )->getLastNumber( ); + if ( lastfreenumber != number ) + if ( bounds.swapFree( number,lastfreenumber ) != SUCCESSFUL_RETURN ) + THROWERROR( RET_ADDBOUND_FAILED ); + + + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ADDBOUND_FAILED ); + + real_t w[NVMAX]; + + + /* II) ADD NEW ACTIVE BOUND TO TOP OF MATRIX T: */ + /* 1) add row [wZ wY] = [Z Y](number) at the top of T: assign w */ + for( i=0; i 0 ) /* ( nAC == 0 ) <=> ( nZ == nFR ) <=> Y and T are empty => nothing to do */ + { + /* store new column a in a temporary vector instead of shifting T one column to the left */ + real_t tmp[NCMAX_ALLOC]; + for( i=0; i is linearly independent from the + the active ones (<=> is element of null space of Afr). */ + for( i=0; i EPS ) + return RET_LINEARLY_INDEPENDENT; + } + + return RET_LINEARLY_DEPENDENT; +} + + +/* + * a d d B o u n d _ e n s u r e L I + */ +returnValue QProblem::addBound_ensureLI( int number, SubjectToStatus B_status ) +{ + int i, j, ii, jj; + int nV = getNV( ); + int nFX = getNFX( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + + /* I) Check if new constraint is linearly independent from the active ones. */ + returnValue returnvalueCheckLI = addBound_checkLI( number ); + + if ( returnvalueCheckLI == RET_LINEARLY_INDEPENDENT ) + return SUCCESSFUL_RETURN; + + + /* II) NEW BOUND IS LINEARLY DEPENDENT: */ + /* 1) Determine coefficients of linear combination, + * cf. M.J. Best. Applied Mathematics and Parallel Computing, chapter: + * An Algorithm for the Solution of the Parametric Quadratic Programming + * Problem, pages 57-76. Physica-Verlag, Heidelberg, 1996. */ + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + int FX_idx[NVMAX]; + if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + int AC_idx[NCMAX_ALLOC]; + if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + real_t xiC[NCMAX_ALLOC]; + real_t xiC_TMP[NCMAX_ALLOC]; + real_t xiB[NVMAX]; + + /* 2) Calculate xiC. */ + if ( nAC > 0 ) + { + if ( B_status == ST_LOWER ) + { + for( i=0; i ZERO ) && ( y[nV+ii] >= 0.0 ) ) + { + if ( y[nV+ii]/xiC[i] < y_min ) + { + y_min = y[nV+ii]/xiC[i]; + y_min_number = ii; + } + } + } + else + { + if ( ( xiC[i] < -ZERO ) && ( y[nV+ii] <= 0.0 ) ) + { + if ( y[nV+ii]/xiC[i] < y_min ) + { + y_min = y[nV+ii]/xiC[i]; + y_min_number = ii; + } + } + } + } + + /* 2) Bounds. */ + for( i=0; i ZERO ) && ( y[ii] >= 0.0 ) ) + { + if ( y[ii]/xiB[i] < y_min ) + { + y_min = y[ii]/xiB[i]; + y_min_number = ii; + y_min_isBound = BT_TRUE; + } + } + } + else + { + if ( ( xiB[i] < -ZERO ) && ( y[ii] <= 0.0 ) ) + { + if ( y[ii]/xiB[i] < y_min ) + { + y_min = y[ii]/xiB[i]; + y_min_number = ii; + y_min_isBound = BT_TRUE; + } + } + } + } + + /* setup output preferences */ + #ifdef PC_DEBUG + char messageString[80]; + VisibilityStatus visibilityStatus; + + if ( printlevel == PL_HIGH ) + visibilityStatus = VS_VISIBLE; + else + visibilityStatus = VS_HIDDEN; + #endif + + + /* IV) REMOVE CONSTRAINT/BOUND FOR RESOLVING LINEAR DEPENDENCE: */ + if ( y_min_number >= 0 ) + { + /* 1) Check for cycling due to infeasibility. */ + if ( ( cyclingManager.getCyclingStatus( number,BT_TRUE ) == CYC_PREV_REMOVED ) && + ( cyclingManager.getCyclingStatus( y_min_number,y_min_isBound ) == CYC_PREV_ADDED ) ) + { + infeasible = BT_TRUE; + + return THROWERROR( RET_ENSURELI_FAILED_CYCLING ); + } + else + { + /* set cycling data */ + cyclingManager.clearCyclingData( ); + cyclingManager.setCyclingStatus( number,BT_TRUE, CYC_PREV_ADDED ); + cyclingManager.setCyclingStatus( y_min_number,y_min_isBound, CYC_PREV_REMOVED ); + } + + + /* 2) Update Lagrange multiplier... */ + for( i=0; ithrowInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeBound( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[y_min_number] = 0.0; + } + else + { + #ifdef PC_DEBUG + sprintf( messageString,"constraint no. %d.",y_min_number ); + getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeConstraint( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[nV+y_min_number] = 0.0; + } + } + else + { + /* no constraint/bound can be removed => QP is infeasible! */ + infeasible = BT_TRUE; + + return THROWERROR( RET_ENSURELI_FAILED_NOINDEX ); + } + + return getGlobalMessageHandler( )->throwInfo( RET_LI_RESOLVED,0,__FUNCTION__,__FILE__,__LINE__,VS_HIDDEN ); +} + + + +/* + * r e m o v e C o n s t r a i n t + */ +returnValue QProblem::removeConstraint( int number, + BooleanType updateCholesky + ) +{ + int i, j, ii, jj; + + /* consistency check */ + if ( ( getStatus( ) == QPS_NOTINITIALISED ) || + ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + return THROWERROR( RET_UNKNOWN_BUG ); + } + + /* some definitions */ + int nFR = getNFR( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + int tcol = sizeT - nAC; + int number_idx = constraints.getActive( )->getIndex( number ); + + + /* consistency checks */ + if ( constraints.getStatus( number ) == ST_INACTIVE ) + return THROWERROR( RET_CONSTRAINT_NOT_ACTIVE ); + + if ( ( number_idx < 0 ) || ( number_idx >= nAC ) ) + return THROWERROR( RET_CONSTRAINT_NOT_ACTIVE ); + + + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVECONSTRAINT_FAILED ); + + + /* I) REMOVE th ROW FROM T, + * i.e. shift rows number+1 through nAC upwards (instead of the actual + * constraint number its corresponding index within matrix A is used). */ + if ( number_idx < nAC-1 ) + { + for( i=(number_idx+1); i=0; --j ) + { + computeGivens( T[(nAC-2-j)*NVMAX + tcol+1+j],T[(nAC-2-j)*NVMAX + tcol+j], T[(nAC-2-j)*NVMAX + tcol+1+j],T[(nAC-2-j)*NVMAX + tcol+j],c,s ); + + for( i=(nAC-j-1); i<(nAC-1); ++i ) + applyGivens( c,s,T[i*NVMAX + tcol+1+j],T[i*NVMAX + tcol+j], T[i*NVMAX + tcol+1+j],T[i*NVMAX + tcol+j] ); + + for( i=0; i 0 ) + { + real_t ZHz[NVMAX]; + for ( i=0; i 0.0 ) + R[nZ*NVMAX + nZ] = sqrt( rho2 ); + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + } + + /* IV) UPDATE INDICES */ + if ( constraints.moveActiveToInactive( number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVECONSTRAINT_FAILED ); + + + return SUCCESSFUL_RETURN; +} + + +/* + * r e m o v e B o u n d + */ +returnValue QProblem::removeBound( int number, + BooleanType updateCholesky + ) +{ + int i, j, ii, jj; + + /* consistency checks */ + if ( bounds.getStatus( number ) == ST_INACTIVE ) + return THROWERROR( RET_BOUND_NOT_ACTIVE ); + + if ( ( getStatus( ) == QPS_NOTINITIALISED ) || + ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + return THROWERROR( RET_UNKNOWN_BUG ); + } + + /* some definitions */ + int nFR = getNFR( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + int tcol = sizeT - nAC; + + + /* I) UPDATE INDICES */ + if ( bounds.moveFixedToFree( number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVEBOUND_FAILED ); + + + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVEBOUND_FAILED ); + + /* I) APPEND th UNITY VECOTR TO Q. */ + int nnFRp1 = FR_idx[nFR]; + for( i=0; i 0 ) + { + /* store new column a in a temporary vector instead of shifting T one column to the left and appending a */ + int AC_idx[NCMAX_ALLOC]; + if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVEBOUND_FAILED ); + + real_t tmp[NCMAX_ALLOC]; + for( i=0; i=0; --j ) + { + computeGivens( tmp[nAC-1-j],T[(nAC-1-j)*NVMAX + tcol+j],T[(nAC-1-j)*NVMAX + tcol+j],tmp[nAC-1-j],c,s ); + + for( i=(nAC-j); i 0 ) + { + real_t Hz[NVMAX]; + for( i=0; i 0 ) + { + real_t r[NVMAX]; + real_t rhs[NVMAX]; + for( i=0; i 0.0 ) + R[nZ*NVMAX + nZ] = sqrt( rho2 ); + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * b a c k s o l v e R (CODE DUPLICATE OF QProblemB CLASS!!!) + */ +returnValue QProblem::backsolveR( const real_t* const b, BooleanType transposed, + real_t* const a + ) +{ + /* Call standard backsolve procedure (i.e. removingBound == BT_FALSE). */ + return backsolveR( b,transposed,BT_FALSE,a ); +} + + +/* + * b a c k s o l v e R (CODE DUPLICATE OF QProblemB CLASS!!!) + */ +returnValue QProblem::backsolveR( const real_t* const b, BooleanType transposed, + BooleanType removingBound, + real_t* const a + ) +{ + int i, j; + int nR = getNZ( ); + + real_t sum; + + /* if backsolve is called while removing a bound, reduce nZ by one. */ + if ( removingBound == BT_TRUE ) + --nR; + + /* nothing to do */ + if ( nR <= 0 ) + return SUCCESSFUL_RETURN; + + + /* Solve Ra = b, where R might be transposed. */ + if ( transposed == BT_FALSE ) + { + /* solve Ra = b */ + for( i=(nR-1); i>=0; --i ) + { + sum = b[i]; + for( j=(i+1); j ZERO ) + a[i] = sum / R[i*NVMAX + i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + else + { + /* solve R^T*a = b */ + for( i=0; i ZERO ) + a[i] = sum / R[i*NVMAX + i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + + return SUCCESSFUL_RETURN; +} + + + +/* + * b a c k s o l v e T + */ +returnValue QProblem::backsolveT( const real_t* const b, BooleanType transposed, real_t* const a ) +{ + int i, j; + int nT = getNAC( ); + int tcol = sizeT - nT; + + real_t sum; + + /* nothing to do */ + if ( nT <= 0 ) + return SUCCESSFUL_RETURN; + + + /* Solve Ta = b, where T might be transposed. */ + if ( transposed == BT_FALSE ) + { + /* solve Ta = b */ + for( i=0; i ZERO ) + a[nT-1-i] = sum / T[i*NVMAX + sizeT-1-i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + else + { + /* solve T^T*a = b */ + for( i=0; i ZERO ) + a[nT-1-i] = sum / T[(nT-1-i)*NVMAX + tcol+i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + + + return SUCCESSFUL_RETURN; +} + + +/* + * h o t s t a r t _ d e t e r m i n e D a t a S h i f t + */ +returnValue QProblem::hotstart_determineDataShift( const int* const FX_idx, const int* const AC_idx, + const real_t* const g_new, const real_t* const lbA_new, const real_t* const ubA_new, + const real_t* const lb_new, const real_t* const ub_new, + real_t* const delta_g, real_t* const delta_lbA, real_t* const delta_ubA, + real_t* const delta_lb, real_t* const delta_ub, + BooleanType& Delta_bC_isZero, BooleanType& Delta_bB_isZero + ) +{ + int i, ii; + int nC = getNC( ); + int nAC = getNAC( ); + + + /* I) DETERMINE DATA SHIFT FOR BOUNDS */ + QProblemB::hotstart_determineDataShift( FX_idx,g_new,lb_new,ub_new, delta_g,delta_lb,delta_ub, Delta_bB_isZero ); + + + /* II) DETERMINE DATA SHIFT FOR CONSTRAINTS */ + /* 1) Calculate shift directions. */ + for( i=0; i EPS ) || ( getAbs( delta_ubA[ii] ) > EPS ) ) + { + Delta_bC_isZero = BT_FALSE; + break; + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * h o t s t a r t _ d e t e r m i n e S t e p D i r e c t i o n + */ +returnValue QProblem::hotstart_determineStepDirection( const int* const FR_idx, const int* const FX_idx, const int* const AC_idx, + const real_t* const delta_g, const real_t* const delta_lbA, const real_t* const delta_ubA, + const real_t* const delta_lb, const real_t* const delta_ub, + BooleanType Delta_bC_isZero, BooleanType Delta_bB_isZero, + real_t* const delta_xFX, real_t* const delta_xFR, + real_t* const delta_yAC, real_t* const delta_yFX + ) +{ + int i, j, ii, jj; + int nFR = getNFR( ); + int nFX = getNFX( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + /* initialise auxiliary vectors */ + real_t HMX_delta_xFX[NVMAX]; + real_t YFR_delta_xFRy[NVMAX]; + real_t ZFR_delta_xFRz[NVMAX]; + real_t HFR_YFR_delta_xFRy[NVMAX]; + for( i=0; i 0 ) + { + for( i=0; i 0 ) + { + /* 1) Determine delta_xFRy. */ + if ( nAC > 0 ) + { + if ( ( Delta_bC_isZero == BT_TRUE ) && ( Delta_bB_isZero == BT_TRUE ) ) + { + for( i=0; i 0 ) + { + for( i=0; i 0 ) + { + if ( ( Delta_bC_isZero == BT_FALSE ) || ( Delta_bB_isZero == BT_FALSE ) ) + { + for( i=0; i 0 ) + { + /* auxiliary variable */ + real_t delta_xFRz_TMP[NVMAX]; + real_t delta_xFRz_RHS[NVMAX]; + + + if ( ( nAC > 0 ) && ( nFX > 0 ) && ( Delta_bB_isZero == BT_FALSE ) ) + { + for( j=0; j 0 ) /* => Delta_bB_isZero == BT_TRUE, as BT_FALSE would imply nFX>0 */ + { + for( j=0; j 0 ) /* => ( nFR = nZ + nAC > 0 ) */ + { + /* auxiliary variables */ + real_t delta_yAC_TMP[NCMAX_ALLOC]; + for( i=0; i 0 ) + { + for( i=0; i 0 ) + { + if ( Delta_bB_isZero == BT_FALSE ) + { + for( i=0; i 0 ) + { + for( i=0; i 0.0 ) + maxStepLength[nV+ii] = y[nV+ii] / ( -delta_yAC[i] ); + else + maxStepLength[nV+ii] = 0.0; + } + } + else + { + /* active upper constraints' bounds */ + if ( delta_yAC[i] > ZERO ) + { + if ( y[nV+ii] < 0.0 ) + maxStepLength[nV+ii] = y[nV+ii] / ( -delta_yAC[i] ); + else + maxStepLength[nV+ii] = 0.0; + } + } + } + } + + /* 2) Ensure that active dual bounds remain valid + * (ignoring implicitly fixed variables). */ + for( i=0; i 0.0 ) + maxStepLength[ii] = y[ii] / ( -delta_yFX[i] ); + else + maxStepLength[ii] = 0.0; + } + } + else + { + /* active upper bounds */ + if ( delta_yFX[i] > ZERO ) + { + if ( y[ii] < 0.0 ) + maxStepLength[ii] = y[ii] / ( -delta_yFX[i] ); + else + maxStepLength[ii] = 0.0; + } + } + } + } + + + /* II) DETERMINE MAXIMUM PRIMAL STEPLENGTH */ + /* 1) Ensure that inactive constraints' bounds remain valid + * (ignoring unbounded constraints). */ + real_t delta_x[NVMAX]; + for( j=0; j delta_Ax[ii] ) + { + if ( Ax[ii] > lbA[ii] ) + maxStepLength[nV+ii] = ( Ax[ii] - lbA[ii] ) / ( delta_lbA[ii] - delta_Ax[ii] ); + else + maxStepLength[nV+ii] = 0.0; + } + } + + /* inactive upper constraints' bounds */ + if ( constraints.isNoUpper( ) == BT_FALSE ) + { + if ( delta_ubA[ii] < delta_Ax[ii] ) + { + if ( Ax[ii] < ubA[ii] ) + maxStepLength[nV+nC+nV+ii] = ( Ax[ii] - ubA[ii] ) / ( delta_ubA[ii] - delta_Ax[ii] ); + else + maxStepLength[nV+nC+nV+ii] = 0.0; + } + } + } + } + + + /* 2) Ensure that inactive bounds remain valid + * (ignoring unbounded variables). */ + /* inactive lower bounds */ + if ( bounds.isNoLower( ) == BT_FALSE ) + { + for( i=0; i delta_xFR[i] ) + { + if ( x[ii] > lb[ii] ) + maxStepLength[ii] = ( x[ii] - lb[ii] ) / ( delta_lb[ii] - delta_xFR[i] ); + else + maxStepLength[ii] = 0.0; + } + } + } + + /* inactive upper bounds */ + if ( bounds.isNoUpper( ) == BT_FALSE ) + { + for( i=0; i EPS ) + cyclingManager.clearCyclingData( ); + + + /* V) SET MAXIMUM HOMOTOPY STEPLENGTH */ + tau = tau_new; + + #ifdef PC_DEBUG + if ( printlevel == PL_HIGH ) + { + + char messageString[80]; + + if ( BC_status == ST_UNDEFINED ) + sprintf( messageString,"Stepsize is %.6e!",tau ); + else + sprintf( messageString,"Stepsize is %.6e! (BC_idx = %d, BC_isBound = %d, BC_status = %d)",tau,BC_idx,BC_isBound,BC_status ); + + getGlobalMessageHandler( )->throwInfo( RET_STEPSIZE_NONPOSITIVE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + #endif + + return SUCCESSFUL_RETURN; +} + + +/* + * h o t s t a r t _ p e r f o r m S t e p + */ +returnValue QProblem::hotstart_performStep( const int* const FR_idx, const int* const FX_idx, const int* const AC_idx, const int* const IAC_idx, + const real_t* const delta_g, const real_t* const delta_lbA, const real_t* const delta_ubA, + const real_t* const delta_lb, const real_t* const delta_ub, + const real_t* const delta_xFX, const real_t* const delta_xFR, + const real_t* const delta_yAC, const real_t* const delta_yFX, + const real_t* const delta_Ax, int BC_idx, SubjectToStatus BC_status, BooleanType BC_isBound + ) +{ + int i, j, ii; + int nV = getNV( ); + int nC = getNC( ); + int nFR = getNFR( ); + int nFX = getNFX( ); + int nAC = getNAC( ); + int nIAC = getNIAC( ); + + + /* I) CHECK (CONSTRAINTS') BOUNDS' CONSISTENCY */ + if ( areBoundsConsistent( delta_lb,delta_ub,delta_lbA,delta_ubA ) == BT_FALSE ) + { + infeasible = BT_TRUE; + tau = 0.0; + + return THROWERROR( RET_QP_INFEASIBLE ); + } + + + /* II) GO TO ACTIVE SET CHANGE */ + if ( tau > ZERO ) + { + /* 1) Perform step in primal und dual space... */ + for( i=0; ithrowWarning( RET_STEPSIZE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + + /* setup output preferences */ + #ifdef PC_DEBUG + char messageString[80]; + VisibilityStatus visibilityStatus; + + if ( printlevel == PL_HIGH ) + visibilityStatus = VS_VISIBLE; + else + visibilityStatus = VS_HIDDEN; + #endif + + + /* III) UPDATE ACTIVE SET */ + switch ( BC_status ) + { + /* Optimal solution found as no working set change detected. */ + case ST_UNDEFINED: + return RET_OPTIMAL_SOLUTION_FOUND; + + + /* Remove one variable from active set. */ + case ST_INACTIVE: + if ( BC_isBound == BT_TRUE ) + { + #ifdef PC_DEBUG + sprintf( messageString,"bound no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeBound( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[BC_idx] = 0.0; + } + else + { + #ifdef PC_DEBUG + sprintf( messageString,"constraint no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeConstraint( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[nV+BC_idx] = 0.0; + } + break; + + + /* Add one variable to active set. */ + default: + if ( BC_isBound == BT_TRUE ) + { + #ifdef PC_DEBUG + if ( BC_status == ST_LOWER ) + sprintf( messageString,"lower bound no. %d.", BC_idx ); + else + sprintf( messageString,"upper bound no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( addBound( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED ); + } + else + { + #ifdef PC_DEBUG + if ( BC_status == ST_LOWER ) + sprintf( messageString,"lower constraint's bound no. %d.", BC_idx ); + else + sprintf( messageString,"upper constraint's bound no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( addConstraint( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED ); + } + break; + } + + return SUCCESSFUL_RETURN; +} + + +/* + * a r e B o u n d s C o n s i s t e n t + */ +BooleanType QProblem::areBoundsConsistent( const real_t* const delta_lb, const real_t* const delta_ub, + const real_t* const delta_lbA, const real_t* const delta_ubA + ) const +{ + int i; + + /* 1) Check bounds' consistency. */ + if ( QProblemB::areBoundsConsistent( delta_lb,delta_ub ) == BT_FALSE ) + return BT_FALSE; + + /* 2) Check constraints' consistency, i.e. + * check if delta_lb[i] is greater than delta_ub[i] + * for a component i whose bounds are already (numerically) equal. */ + for( i=0; i ubA[i] - BOUNDTOL ) && ( delta_lbA[i] > delta_ubA[i] + EPS ) ) + return BT_FALSE; + + return BT_TRUE; +} + + +/* + * s e t u p Q P d a t a + */ +returnValue QProblem::setupQPdata( const real_t* const _H, const real_t* const _R, const real_t* const _g, const real_t* const _A, + const real_t* const _lb, const real_t* const _ub, + const real_t* const _lbA, const real_t* const _ubA + ) +{ + int i, j; + int nV = getNV( ); + int nC = getNC( ); + + + /* 1) Load Hessian matrix as well as lower and upper bounds vectors. */ + if (QProblemB::setupQPdata(_H, _R, _g, _lb, _ub) != SUCCESSFUL_RETURN) + return THROWERROR( RET_INVALID_ARGUMENTS ); + + /* 2) Load constraint matrix. */ + if ( ( nC > 0 ) && ( _A == 0 ) ) + return THROWERROR( RET_INVALID_ARGUMENTS ); + + if ( nC > 0 ) + { + for( i=0; igetNumberArray( AC_idx ); + + /* 1) check for Hx + g - [yFX yAC]*[Id A]' = 0. */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = getAbs( tmp ); + } + + /* 2) Check for [lb lbA] <= [Id A]*x <= [ub ubA]. */ + /* lbA <= Ax <= ubA */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = lbA[i] - Ax[i]; + + if ( Ax[i] - ubA[i] > maxKKTviolation ) + maxKKTviolation = Ax[i] - ubA[i]; + } + + /* lb <= x <= ub */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = lb[i] - x[i]; + + if ( x[i] - ub[i] > maxKKTviolation ) + maxKKTviolation = x[i] - ub[i]; + } + + /* 3) Check for correct sign of y and for complementary slackness. */ + /* bounds */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = -y[i]; + if ( getAbs( x[i] - lb[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( x[i] - lb[i] ); + break; + + case ST_UPPER: + if ( y[i] > maxKKTviolation ) + maxKKTviolation = y[i]; + if ( getAbs( ub[i] - x[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( ub[i] - x[i] ); + break; + + default: /* inactive */ + if ( getAbs( y[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( y[i] ); + break; + } + } + + /* constraints */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = -y[nV+i]; + if ( getAbs( Ax[i] - lbA[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( Ax[i] - lbA[i] ); + break; + + case ST_UPPER: + if ( y[nV+i] > maxKKTviolation ) + maxKKTviolation = y[nV+i]; + if ( getAbs( ubA[i] - Ax[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( ubA[i] - Ax[i] ); + break; + + default: /* inactive */ + if ( getAbs( y[nV+i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( y[nV+i] ); + break; + } + } + + if ( maxKKTviolation > CRITICALACCURACY ) + return RET_NO_SOLUTION; + + if ( maxKKTviolation > DESIREDACCURACY ) + return RET_INACCURATE_SOLUTION; + + #endif /* __PERFORM_KKT_TEST__ */ + + return SUCCESSFUL_RETURN; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/QProblem.ipp b/phonelibs/qpoases/SRC/QProblem.ipp new file mode 100644 index 00000000000000..cec58e291ddeab --- /dev/null +++ b/phonelibs/qpoases/SRC/QProblem.ipp @@ -0,0 +1,299 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/QProblem.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of inlined member functions of the QProblem class which + * is able to use the newly developed online active set strategy for + * parametric quadratic programming. + */ + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + +/* + * g e t A + */ +inline returnValue QProblem::getA( real_t* const _A ) const +{ + int i; + + for ( i=0; i= 0 ) && ( number < getNC( ) ) ) + { + for ( int i=0; i= 0 ) && ( number < getNC( ) ) ) + { + value = lbA[number]; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * g e t U B A + */ +inline returnValue QProblem::getUBA( real_t* const _ubA ) const +{ + int i; + + for ( i=0; i= 0 ) && ( number < getNC( ) ) ) + { + value = ubA[number]; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * g e t C o n s t r a i n t s + */ +inline returnValue QProblem::getConstraints( Constraints* const _constraints ) const +{ + *_constraints = constraints; + + return SUCCESSFUL_RETURN; +} + + + +/* + * g e t N C + */ +inline int QProblem::getNC( ) const +{ + return constraints.getNC( ); +} + + +/* + * g e t N E C + */ +inline int QProblem::getNEC( ) const +{ + return constraints.getNEC( ); +} + + +/* + * g e t N A C + */ +inline int QProblem::getNAC( ) +{ + return constraints.getNAC( ); +} + + +/* + * g e t N I A C + */ +inline int QProblem::getNIAC( ) +{ + return constraints.getNIAC( ); +} + + + +/***************************************************************************** + * P R O T E C T E D * + *****************************************************************************/ + + +/* + * s e t A + */ +inline returnValue QProblem::setA( const real_t* const A_new ) +{ + int i, j; + int nV = getNV( ); + int nC = getNC( ); + + /* Set constraint matrix AND update member AX. */ + for( j=0; j= 0 ) && ( number < getNC( ) ) ) + { + Ax[number] = 0.0; + + for( i=0; i= 0 ) && ( number < getNC( ) ) ) + { + lbA[number] = value; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * s e t U B A + */ +inline returnValue QProblem::setUBA( const real_t* const ubA_new ) +{ + int i; + int nC = getNC(); + + for( i=0; i= 0 ) && ( number < getNC( ) ) ) + { + ubA[number] = value; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/QProblemB.cpp b/phonelibs/qpoases/SRC/QProblemB.cpp new file mode 100644 index 00000000000000..f84daabc025d3f --- /dev/null +++ b/phonelibs/qpoases/SRC/QProblemB.cpp @@ -0,0 +1,2151 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/QProblemB.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the QProblemB class which is able to use the newly + * developed online active set strategy for parametric quadratic programming. + */ + + +#include + +#include + +void printmatrix(char *name, double *A, int m, int n) { + int i, j; + + printf("%s = [...\n", name); + for (i = 0; i < m; i++) { + for (j = 0; j < n; j++) + printf(" % 9.4f", A[i*n+j]); + printf(",\n"); + } + printf("];\n"); +} + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * Q P r o b l e m B + */ +QProblemB::QProblemB( ) +{ + /* reset global message handler */ + getGlobalMessageHandler( )->reset( ); + + hasHessian = BT_FALSE; + + bounds.init( 0 ); + + hasCholesky = BT_FALSE; + + tau = 0.0; + + hessianType = HST_POSDEF_NULLSPACE; /* Hessian is assumed to be positive definite by default */ + infeasible = BT_FALSE; + unbounded = BT_FALSE; + + status = QPS_NOTINITIALISED; + + #ifdef PC_DEBUG + printlevel = PL_MEDIUM; + setPrintLevel( PL_MEDIUM ); + #else + printlevel = QPOASES_PRINTLEVEL; + #endif + + count = 0; +} + + +/* + * Q P r o b l e m B + */ +QProblemB::QProblemB( int _nV ) +{ + /* consistency check */ + if ( _nV <= 0 ) + { + _nV = 1; + THROWERROR( RET_INVALID_ARGUMENTS ); + } + + hasHessian = BT_FALSE; + + /* reset global message handler */ + getGlobalMessageHandler( )->reset( ); + + bounds.init( _nV ); + + hasCholesky = BT_FALSE; + + tau = 0.0; + + hessianType = HST_POSDEF_NULLSPACE; /* Hessian is assumed to be positive definite by default */ + infeasible = BT_FALSE; + unbounded = BT_FALSE; + + status = QPS_NOTINITIALISED; + + #ifdef PC_DEBUG + printlevel = PL_MEDIUM; + setPrintLevel( PL_MEDIUM ); + #else + printlevel = QPOASES_PRINTLEVEL; + #endif + + count = 0; +} + + +/* + * Q P r o b l e m B + */ +QProblemB::QProblemB( const QProblemB& rhs ) +{ + int i, j; + + int _nV = rhs.bounds.getNV( ); + + for( i=0; i<_nV; ++i ) + for( j=0; j<_nV; ++j ) + H[i*NVMAX + j] = rhs.H[i*NVMAX + j]; + + hasHessian = rhs.hasHessian; + + for( i=0; i<_nV; ++i ) + g[i] = rhs.g[i]; + + for( i=0; i<_nV; ++i ) + lb[i] = rhs.lb[i]; + + for( i=0; i<_nV; ++i ) + ub[i] = rhs.ub[i]; + + + bounds = rhs.bounds; + + for( i=0; i<_nV; ++i ) + for( j=0; j<_nV; ++j ) + R[i*NVMAX + j] = rhs.R[i*NVMAX + j]; + hasCholesky = rhs.hasCholesky; + + for( i=0; i<_nV; ++i ) + x[i] = rhs.x[i]; + + for( i=0; i<_nV; ++i ) + y[i] = rhs.y[i]; + + tau = rhs.tau; + + hessianType = rhs.hessianType; + infeasible = rhs.infeasible; + unbounded = rhs.unbounded; + + status = rhs.status; + + printlevel = rhs.printlevel; + + count = rhs.count; +} + + +/* + * ~ Q P r o b l e m B + */ +QProblemB::~QProblemB( ) +{ +} + + +/* + * o p e r a t o r = + */ +QProblemB& QProblemB::operator=( const QProblemB& rhs ) +{ + int i, j; + + if ( this != &rhs ) + { + int _nV = rhs.bounds.getNV( ); + + for( i=0; i<_nV; ++i ) + for( j=0; j<_nV; ++j ) + H[i*NVMAX + j] = rhs.H[i*NVMAX + j]; + + hasHessian = rhs.hasHessian; + + for( i=0; i<_nV; ++i ) + g[i] = rhs.g[i]; + + for( i=0; i<_nV; ++i ) + lb[i] = rhs.lb[i]; + + for( i=0; i<_nV; ++i ) + ub[i] = rhs.ub[i]; + + bounds = rhs.bounds; + + for( i=0; i<_nV; ++i ) + for( j=0; j<_nV; ++j ) + R[i*NVMAX + j] = rhs.R[i*NVMAX + j]; + hasCholesky = rhs.hasCholesky; + + + for( i=0; i<_nV; ++i ) + x[i] = rhs.x[i]; + + for( i=0; i<_nV; ++i ) + y[i] = rhs.y[i]; + + tau = rhs.tau; + + hessianType = rhs.hessianType; + infeasible = rhs.infeasible; + unbounded = rhs.unbounded; + + status = rhs.status; + + printlevel = rhs.printlevel; + setPrintLevel( rhs.printlevel ); + + count = rhs.count; + } + + return *this; +} + + +/* + * r e s e t + */ +returnValue QProblemB::reset( ) +{ + int i, j; + int nV = getNV( ); + + /** 0) Reset has Hessian flag. */ + hasHessian = BT_FALSE; + + /* 1) Reset bounds. */ + bounds.init( nV ); + + /* 2) Reset Cholesky decomposition. */ + for( i=0; ithrowInfo( RET_ITERATION_STARTED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + /* 1) Setup index arrays. */ + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + /* 2) Initialize shift direction of the gradient and the bounds. */ + returnvalue = hotstart_determineDataShift( FX_idx, + g_new,lb_new,ub_new, + delta_g,delta_lb,delta_ub, + Delta_bB_isZero + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_SHIFT_DETERMINATION_FAILED ); + return returnvalue; + } + + /* 3) Determination of step direction of X and Y. */ + returnvalue = hotstart_determineStepDirection( FR_idx,FX_idx, + delta_g,delta_lb,delta_ub, + Delta_bB_isZero, + delta_xFX,delta_xFR,delta_yFX + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_STEPDIRECTION_DETERMINATION_FAILED ); + return returnvalue; + } + + + /* 4) Determination of step length TAU. */ + returnvalue = hotstart_determineStepLength( FR_idx,FX_idx, + delta_lb,delta_ub, + delta_xFR,delta_yFX, + BC_idx,BC_status ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_STEPLENGTH_DETERMINATION_FAILED ); + return returnvalue; + } + + /* 5) Realization of the homotopy step. */ + returnvalue = hotstart_performStep( FR_idx,FX_idx, + delta_g,delta_lb,delta_ub, + delta_xFX,delta_xFR,delta_yFX, + BC_idx,BC_status + ); + + + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + + /* stop runtime measurement */ + if ( cputime != 0 ) + *cputime = getCPUtime( ) - starttime; + + /* optimal solution found? */ + if ( returnvalue == RET_OPTIMAL_SOLUTION_FOUND ) + { + status = QPS_SOLVED; + + if ( printlevel == PL_HIGH ) + THROWINFO( RET_OPTIMAL_SOLUTION_FOUND ); + + #ifdef PC_DEBUG + if ( printIteration( l,BC_idx,BC_status ) != SUCCESSFUL_RETURN ) + THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */ + #endif + + /* check KKT optimality conditions */ + return checkKKTconditions( ); + } + else + { + /* checks for infeasibility... */ + if ( infeasible == BT_TRUE ) + { + status = QPS_HOMOTOPYQPSOLVED; + return THROWERROR( RET_HOTSTART_STOPPED_INFEASIBILITY ); + } + + /* ...unboundedness... */ + if ( unbounded == BT_TRUE ) /* not necessary since objective function convex! */ + return THROWERROR( RET_HOTSTART_STOPPED_UNBOUNDEDNESS ); + + /* ... and throw unspecific error otherwise */ + THROWERROR( RET_HOMOTOPY_STEP_FAILED ); + return returnvalue; + } + } + + /* 6) Output information of successful QP iteration. */ + status = QPS_HOMOTOPYQPSOLVED; + + #ifdef PC_DEBUG + if ( printIteration( l,BC_idx,BC_status ) != SUCCESSFUL_RETURN ) + THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */ + #endif + } + + + /* stop runtime measurement */ + if ( cputime != 0 ) + *cputime = getCPUtime( ) - starttime; + + + /* if programm gets to here, output information that QP could not be solved + * within the given maximum numbers of working set changes */ + if ( printlevel == PL_HIGH ) + { + #ifdef PC_DEBUG + sprintf( messageString,"(nWSR = %d)",nWSR ); + return getGlobalMessageHandler( )->throwWarning( RET_MAX_NWSR_REACHED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + /* Finally check KKT optimality conditions. */ + returnValue returnvalueKKTcheck = checkKKTconditions( ); + + if ( returnvalueKKTcheck != SUCCESSFUL_RETURN ) + return returnvalueKKTcheck; + else + return RET_MAX_NWSR_REACHED; +} + + +/* + * g e t N Z + */ +int QProblemB::getNZ( ) +{ + /* if no constraints are present: nZ=nFR */ + return bounds.getFree( )->getLength( ); +} + + +/* + * g e t O b j V a l + */ +real_t QProblemB::getObjVal( ) const +{ + real_t objVal; + + /* calculated optimal objective function value + * only if current QP has been solved */ + if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + objVal = getObjVal( x ); + } + else + { + objVal = INFTY; + } + + return objVal; +} + + +/* + * g e t O b j V a l + */ +real_t QProblemB::getObjVal( const real_t* const _x ) const +{ + int i, j; + int nV = getNV( ); + + real_t obj_tmp = 0.0; + + for( i=0; i= PL_MEDIUM ) && ( printlevel != _printlevel ) ) + THROWINFO( RET_PRINTLEVEL_CHANGED ); + #endif + + printlevel = _printlevel; + + /* update message handler preferences */ + switch ( printlevel ) + { + case PL_NONE: + getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_HIDDEN ); + getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_HIDDEN ); + getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_HIDDEN ); + break; + + case PL_LOW: + getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_VISIBLE ); + getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_HIDDEN ); + getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_HIDDEN ); + break; + + default: /* PL_MEDIUM, PL_HIGH */ + getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_VISIBLE ); + getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_VISIBLE ); + getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_VISIBLE ); + break; + } + + return SUCCESSFUL_RETURN; +} + + + +/***************************************************************************** + * P R O T E C T E D * + *****************************************************************************/ + +/* + * c h e c k F o r I d e n t i t y H e s s i a n + */ +returnValue QProblemB::checkForIdentityHessian( ) +{ + int i, j; + int nV = getNV( ); + + /* nothing to do as status flag remains unaltered + * if Hessian differs from identity matrix */ + if ( hessianType == HST_IDENTITY ) + return SUCCESSFUL_RETURN; + + /* 1) If Hessian differs from identity matrix, + * return without changing the internal HessianType. */ + for ( i=0; i EPS ) + return SUCCESSFUL_RETURN; + + for ( i=0; i EPS ) || ( getAbs( H[j*NVMAX + i] ) > EPS ) ) + return SUCCESSFUL_RETURN; + } + + /* 2) If this point is reached, Hessian equals the idetity matrix. */ + hessianType = HST_IDENTITY; + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p S u b j e c t T o T y p e + */ +returnValue QProblemB::setupSubjectToType( ) +{ + int i; + int nV = getNV( ); + + + /* 1) Check if lower bounds are present. */ + bounds.setNoLower( BT_TRUE ); + for( i=0; i -INFTY ) + { + bounds.setNoLower( BT_FALSE ); + break; + } + + /* 2) Check if upper bounds are present. */ + bounds.setNoUpper( BT_TRUE ); + for( i=0; i INFTY - BOUNDTOL ) ) + { + bounds.setType( i,ST_UNBOUNDED ); + ++nUV; + } + else + { + if ( lb[i] > ub[i] - BOUNDTOL ) + { + bounds.setType( i,ST_EQUALITY ); + ++nFV; + } + else + { + bounds.setType( i,ST_BOUNDED ); + } + } + + /* 4) Set dimensions of bounds structure. */ + bounds.setNFV( nFV ); + bounds.setNUV( nUV ); + bounds.setNBV( nV - nFV - nUV ); + + return SUCCESSFUL_RETURN; +} + + +/* + * c h o l e s k y D e c o m p o s i t i o n + */ +returnValue QProblemB::setupCholeskyDecomposition( ) +{ + int i, j, k, ii, jj; + int nV = getNV( ); + int nFR = getNFR( ); + + /* If Hessian flag is false, it means that H & R already contain Cholesky + * factorization -- provided from outside. */ + if (hasHessian == BT_FALSE) + return SUCCESSFUL_RETURN; + + /* 1) Initialises R with all zeros. */ + for( i=0; i 0 ) + { + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INDEXLIST_CORRUPTED ); + + /* R'*R = H */ + real_t sum; + real_t inv; + + for( i=0; i=0; --k ) + sum -= R[k*NVMAX + i] * R[k*NVMAX + i]; + + if ( sum > 0.0 ) + { + R[i*NVMAX + i] = sqrt( sum ); + inv = 1.0 / R[i*NVMAX + i]; + } + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + + /* j > i */ + for( j=(i+1); j=0; --k ) + sum -= R[k*NVMAX + i] * R[k*NVMAX + j]; + + R[i*NVMAX + j] = sum * inv; + } + } + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s o l v e I n i t i a l Q P + */ +returnValue QProblemB::solveInitialQP( const real_t* const xOpt, const real_t* const yOpt, + const Bounds* const guessedBounds, + int& nWSR, real_t* const cputime + ) +{ + int i, nFR; + int nV = getNV( ); + + + /* start runtime measurement */ + real_t starttime = 0.0; + if ( cputime != 0 ) + starttime = getCPUtime( ); + + + status = QPS_NOTINITIALISED; + + /* I) ANALYSE QP DATA: */ + /* 1) Check if Hessian happens to be the identity matrix. */ + if ( checkForIdentityHessian( ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + /* 2) Setup type of bounds (i.e. unbounded, implicitly fixed etc.). */ + if ( setupSubjectToType( ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + status = QPS_PREPARINGAUXILIARYQP; + + + /* II) SETUP AUXILIARY QP WITH GIVEN OPTIMAL SOLUTION: */ + /* 1) Setup bounds data structure. */ + if ( bounds.setupAllFree( ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + /* 2) Setup optimal primal/dual solution for auxiliary QP. */ + if ( setupAuxiliaryQPsolution( xOpt,yOpt ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + /* 3) Obtain linear independent working set for auxiliary QP. */ + + static Bounds auxiliaryBounds; + + auxiliaryBounds.init( nV ); + + if ( obtainAuxiliaryWorkingSet( xOpt,yOpt,guessedBounds, &auxiliaryBounds ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + /* 4) Setup working set of auxiliary QP and setup cholesky decomposition. */ + if ( setupAuxiliaryWorkingSet( &auxiliaryBounds,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + nFR = getNFR(); + /* At the moment we can only provide a Cholesky of the Hessian if + * the solver is cold-started. */ + if (hasCholesky == BT_FALSE || nFR != nV) + if (setupCholeskyDecomposition() != SUCCESSFUL_RETURN) + return THROWERROR( RET_INIT_FAILED_CHOLESKY ); + + /* 5) Store original QP formulation... */ + real_t g_original[NVMAX]; + real_t lb_original[NVMAX]; + real_t ub_original[NVMAX]; + + for( i=0; isetupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryBounds->setupBound( i,guessedBounds->getStatus( i ) ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + else /* No initial working set specified. */ + { + if ( ( xOpt != 0 ) && ( yOpt == 0 ) ) + { + /* Obtain initial working set by "clipping". */ + for( i=0; isetupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + if ( xOpt[i] >= ub[i] - BOUNDTOL ) + { + if ( auxiliaryBounds->setupBound( i,ST_UPPER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + /* Moreover, add all implictly fixed variables if specified. */ + if ( bounds.getType( i ) == ST_EQUALITY ) + { + if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + + if ( ( xOpt == 0 ) && ( yOpt != 0 ) ) + { + /* Obtain initial working set in accordance to sign of dual solution vector. */ + for( i=0; i ZERO ) + { + if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + if ( yOpt[i] < -ZERO ) + { + if ( auxiliaryBounds->setupBound( i,ST_UPPER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + /* Moreover, add all implictly fixed variables if specified. */ + if ( bounds.getType( i ) == ST_EQUALITY ) + { + if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + + /* If xOpt and yOpt are null pointer and no initial working is specified, + * start with empty working set (or implicitly fixed bounds only) + * for auxiliary QP. */ + if ( ( xOpt == 0 ) && ( yOpt == 0 ) ) + { + for( i=0; isetupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p A u x i l i a r y W o r k i n g S e t + */ +returnValue QProblemB::setupAuxiliaryWorkingSet( const Bounds* const auxiliaryBounds, + BooleanType setupAfresh + ) +{ + int i; + int nV = getNV( ); + + /* consistency checks */ + if ( auxiliaryBounds != 0 ) + { + for( i=0; igetStatus( i ) == ST_UNDEFINED ) ) + return THROWERROR( RET_UNKNOWN_BUG ); + } + else + { + return THROWERROR( RET_INVALID_ARGUMENTS ); + } + + + /* I) SETUP CHOLESKY FLAG: + * Cholesky decomposition shall only be updated if working set + * shall be updated (i.e. NOT setup afresh!) */ + BooleanType updateCholesky; + if ( setupAfresh == BT_TRUE ) + updateCholesky = BT_FALSE; + else + updateCholesky = BT_TRUE; + + + /* II) REMOVE FORMERLY ACTIVE BOUNDS (IF NECESSARY): */ + if ( setupAfresh == BT_FALSE ) + { + /* Remove all active bounds that shall be inactive AND + * all active bounds that are active at the wrong bound. */ + for( i=0; igetStatus( i ) != ST_LOWER ) ) + if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + + if ( ( bounds.getStatus( i ) == ST_UPPER ) && ( auxiliaryBounds->getStatus( i ) != ST_UPPER ) ) + if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + } + + + /* III) ADD NEWLY ACTIVE BOUNDS: */ + /* Add all inactive bounds that shall be active AND + * all formerly active bounds that have been active at the wrong bound. */ + for( i=0; igetStatus( i ) != ST_INACTIVE ) ) + { + if ( addBound( i,auxiliaryBounds->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p A u x i l i a r y Q P s o l u t i o n + */ +returnValue QProblemB::setupAuxiliaryQPsolution( const real_t* const xOpt, const real_t* const yOpt + ) +{ + int i; + int nV = getNV( ); + + + /* Setup primal/dual solution vectors for auxiliary initial QP: + * if a null pointer is passed, a zero vector is assigned; + * old solution vector is kept if pointer to internal solution vector is passed. */ + if ( xOpt != 0 ) + { + if ( xOpt != x ) + for( i=0; igetIndex( number ); + + real_t c, s; + + /* 2) Use row-wise Givens rotations to restore upper triangular form of R. */ + for( i=number_idx+1; ith column and ... */ + for( i=0; igetNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVEBOUND_FAILED ); + + /* 1) Calculate new column of cholesky decomposition. */ + real_t rhs[NVMAX]; + real_t r[NVMAX]; + real_t r0 = H[number*NVMAX + number]; + + for( i=0; i 0.0 ) + R[nFR*NVMAX + nFR] = sqrt( r0 ); + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + + + return SUCCESSFUL_RETURN; +} + + +/* + * b a c k s o l v e R (CODE DUPLICATED IN QProblem CLASS!!!) + */ +returnValue QProblemB::backsolveR( const real_t* const b, BooleanType transposed, + real_t* const a + ) +{ + /* Call standard backsolve procedure (i.e. removingBound == BT_FALSE). */ + return backsolveR( b,transposed,BT_FALSE,a ); +} + + +/* + * b a c k s o l v e R (CODE DUPLICATED IN QProblem CLASS!!!) + */ +returnValue QProblemB::backsolveR( const real_t* const b, BooleanType transposed, + BooleanType removingBound, + real_t* const a + ) +{ + int i, j; + int nR = getNZ( ); + + real_t sum; + + /* if backsolve is called while removing a bound, reduce nZ by one. */ + if ( removingBound == BT_TRUE ) + --nR; + + /* nothing to do */ + if ( nR <= 0 ) + return SUCCESSFUL_RETURN; + + + /* Solve Ra = b, where R might be transposed. */ + if ( transposed == BT_FALSE ) + { + /* solve Ra = b */ + for( i=(nR-1); i>=0; --i ) + { + sum = b[i]; + for( j=(i+1); j ZERO ) + a[i] = sum / R[i*NVMAX + i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + else + { + /* solve R^T*a = b */ + for( i=0; i ZERO ) + a[i] = sum / R[i*NVMAX + i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * h o t s t a r t _ d e t e r m i n e D a t a S h i f t + */ +returnValue QProblemB::hotstart_determineDataShift( const int* const FX_idx, + const real_t* const g_new, const real_t* const lb_new, const real_t* const ub_new, + real_t* const delta_g, real_t* const delta_lb, real_t* const delta_ub, + BooleanType& Delta_bB_isZero + ) +{ + int i, ii; + int nV = getNV( ); + int nFX = getNFX( ); + + + /* 1) Calculate shift directions. */ + for( i=0; i EPS ) || ( getAbs( delta_ub[ii] ) > EPS ) ) + { + Delta_bB_isZero = BT_FALSE; + break; + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * a r e B o u n d s C o n s i s t e n t + */ +BooleanType QProblemB::areBoundsConsistent( const real_t* const delta_lb, const real_t* const delta_ub + ) const +{ + int i; + + /* Check if delta_lb[i] is greater than delta_ub[i] + * for a component i whose bounds are already (numerically) equal. */ + for( i=0; i ub[i] - BOUNDTOL ) && ( delta_lb[i] > delta_ub[i] + EPS ) ) + return BT_FALSE; + + return BT_TRUE; +} + + +/* + * s e t u p Q P d a t a + */ +returnValue QProblemB::setupQPdata( const real_t* const _H, const real_t* const _R, const real_t* const _g, + const real_t* const _lb, const real_t* const _ub + ) +{ + int i, j; + int nV = getNV( ); + + /* 1) Setup Hessian matrix and it's Cholesky factorization. */ + if (_H != 0) + { + for( i=0; i 0 ) + { + for( i=0; i 0 ) + { + /* auxiliary variables */ + real_t delta_xFRz_TMP[NVMAX]; + real_t delta_xFRz_RHS[NVMAX]; + + /* Determine delta_xFRz. */ + if ( Delta_bB_isZero == BT_FALSE ) + { + for( i=0; i 0 ) + { + for( i=0; i= 0.0 ) ) + { + tau_tmp = y[ii] / ( -delta_yFX[i] ); + if ( tau_tmp < tau_new ) + { + if ( tau_tmp >= 0.0 ) + { + tau_new = tau_tmp; + BC_idx = ii; + BC_status = ST_INACTIVE; + } + } + } + } + else + { + /* 2) Active upper bounds. */ + if ( ( delta_yFX[i] > ZERO ) && ( y[ii] <= 0.0 ) ) + { + tau_tmp = y[ii] / ( -delta_yFX[i] ); + if ( tau_tmp < tau_new ) + { + if ( tau_tmp >= 0.0 ) + { + tau_new = tau_tmp; + BC_idx = ii; + BC_status = ST_INACTIVE; + } + } + } + } + } + } + + + /* II) DETERMINE MAXIMUM PRIMAL STEPLENGTH, i.e. ensure that + * inactive bounds remain valid (ignoring unbounded variables). */ + /* 1) Inactive lower bounds. */ + if ( bounds.isNoLower( ) == BT_FALSE ) + { + for( i=0; i delta_xFR[i] ) + { + if ( x[ii] > lb[ii] ) + tau_tmp = ( x[ii] - lb[ii] ) / ( delta_lb[ii] - delta_xFR[i] ); + else + tau_tmp = 0.0; + + if ( tau_tmp < tau_new ) + { + if ( tau_tmp >= 0.0 ) + { + tau_new = tau_tmp; + BC_idx = ii; + BC_status = ST_LOWER; + } + } + } + } + } + } + + /* 2) Inactive upper bounds. */ + if ( bounds.isNoUpper( ) == BT_FALSE ) + { + for( i=0; i= 0.0 ) + { + tau_new = tau_tmp; + BC_idx = ii; + BC_status = ST_UPPER; + } + } + } + } + } + } + + + /* III) SET MAXIMUM HOMOTOPY STEPLENGTH */ + tau = tau_new; + + if ( printlevel == PL_HIGH ) + { + #ifdef PC_DEBUG + char messageString[80]; + + if ( BC_status == ST_UNDEFINED ) + sprintf( messageString,"Stepsize is %.6e!",tau ); + else + sprintf( messageString,"Stepsize is %.6e! (BC_idx = %d, BC_status = %d)",tau,BC_idx,BC_status ); + + getGlobalMessageHandler( )->throwInfo( RET_STEPSIZE_NONPOSITIVE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + return SUCCESSFUL_RETURN; +} + + +/* + * h o t s t a r t _ p e r f o r m S t e p + */ +returnValue QProblemB::hotstart_performStep( const int* const FR_idx, const int* const FX_idx, + const real_t* const delta_g, const real_t* const delta_lb, const real_t* const delta_ub, + const real_t* const delta_xFX, const real_t* const delta_xFR, + const real_t* const delta_yFX, + int BC_idx, SubjectToStatus BC_status + ) +{ + int i, ii; + int nV = getNV( ); + int nFR = getNFR( ); + int nFX = getNFX( ); + + + /* I) CHECK BOUNDS' CONSISTENCY */ + if ( areBoundsConsistent( delta_lb,delta_ub ) == BT_FALSE ) + { + infeasible = BT_TRUE; + tau = 0.0; + + return THROWERROR( RET_QP_INFEASIBLE ); + } + + + /* II) GO TO ACTIVE SET CHANGE */ + if ( tau > ZERO ) + { + /* 1) Perform step in primal und dual space. */ + for( i=0; ithrowWarning( RET_STEPSIZE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + + /* setup output preferences */ + #ifdef PC_DEBUG + char messageString[80]; + VisibilityStatus visibilityStatus; + + if ( printlevel == PL_HIGH ) + visibilityStatus = VS_VISIBLE; + else + visibilityStatus = VS_HIDDEN; + #endif + + + /* III) UPDATE ACTIVE SET */ + switch ( BC_status ) + { + /* Optimal solution found as no working set change detected. */ + case ST_UNDEFINED: + return RET_OPTIMAL_SOLUTION_FOUND; + + + /* Remove one variable from active set. */ + case ST_INACTIVE: + #ifdef PC_DEBUG + sprintf( messageString,"bound no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeBound( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[BC_idx] = 0.0; + break; + + + /* Add one variable to active set. */ + default: + #ifdef PC_DEBUG + if ( BC_status == ST_LOWER ) + sprintf( messageString,"lower bound no. %d.", BC_idx ); + else + sprintf( messageString,"upper bound no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( addBound( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED ); + break; + } + + return SUCCESSFUL_RETURN; +} + + +#ifdef PC_DEBUG /* Define print functions only for debugging! */ + +/* + * p r i n t I t e r a t i o n + */ +returnValue QProblemB::printIteration( int iteration, + int BC_idx, SubjectToStatus BC_status + ) +{ + char myPrintfString[160]; + + /* consistency check */ + if ( iteration < 0 ) + return THROWERROR( RET_INVALID_ARGUMENTS ); + + /* nothing to do */ + if ( printlevel != PL_MEDIUM ) + return SUCCESSFUL_RETURN; + + + /* 1) Print header at first iteration. */ + if ( iteration == 0 ) + { + sprintf( myPrintfString,"\n############## qpOASES -- QP NO.%4.1d ###############\n", count ); + myPrintf( myPrintfString ); + + sprintf( myPrintfString," Iter | StepLength | Info | nFX \n" ); + myPrintf( myPrintfString ); + } + + /* 2) Print iteration line. */ + if ( BC_status == ST_UNDEFINED ) + { + sprintf( myPrintfString," %4.1d | %1.5e | QP SOLVED | %4.1d \n", iteration,tau,getNFX( ) ); + myPrintf( myPrintfString ); + } + else + { + char info[8]; + + if ( BC_status == ST_INACTIVE ) + sprintf( info,"REM BND" ); + else + sprintf( info,"ADD BND" ); + + sprintf( myPrintfString," %4.1d | %1.5e | %s%4.1d | %4.1d \n", iteration,tau,info,BC_idx,getNFX( ) ); + myPrintf( myPrintfString ); + } + + return SUCCESSFUL_RETURN; +} + +#endif /* PC_DEBUG */ + + + +/* + * c h e c k K K T c o n d i t i o n s + */ +returnValue QProblemB::checkKKTconditions( ) +{ + #ifdef __PERFORM_KKT_TEST__ + + int i, j; + int nV = getNV( ); + + real_t tmp; + real_t maxKKTviolation = 0.0; + + + /* 1) Check for Hx + g - y*A' = 0 (here: A = Id). */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = getAbs( tmp ); + } + + /* 2) Check for lb <= x <= ub. */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = lb[i] - x[i]; + + if ( x[i] - ub[i] > maxKKTviolation ) + maxKKTviolation = x[i] - ub[i]; + } + + /* 3) Check for correct sign of y and for complementary slackness. */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = -y[i]; + if ( getAbs( ( x[i] - lb[i] ) * y[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( ( x[i] - lb[i] ) * y[i] ); + break; + + case ST_UPPER: + if ( y[i] > maxKKTviolation ) + maxKKTviolation = y[i]; + if ( getAbs( ( ub[i] - x[i] ) * y[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( ( ub[i] - x[i] ) * y[i] ); + break; + + default: /* inactive */ + if ( getAbs( y[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( y[i] ); + break; + } + } + + if ( maxKKTviolation > CRITICALACCURACY ) + return RET_NO_SOLUTION; + + if ( maxKKTviolation > DESIREDACCURACY ) + return RET_INACCURATE_SOLUTION; + + #endif /* __PERFORM_KKT_TEST__ */ + + return SUCCESSFUL_RETURN; +} + + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/QProblemB.ipp b/phonelibs/qpoases/SRC/QProblemB.ipp new file mode 100644 index 00000000000000..0c1c8b231147b5 --- /dev/null +++ b/phonelibs/qpoases/SRC/QProblemB.ipp @@ -0,0 +1,425 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/QProblemB.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of inlined member functions of the QProblemB class which + * is able to use the newly developed online active set strategy for + * parametric quadratic programming. + */ + + + +#include + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + +/* + * g e t H + */ +inline returnValue QProblemB::getH( real_t* const _H ) const +{ + int i; + + for ( i=0; i= 0 ) && ( number < getNV( ) ) ) + { + value = lb[number]; + return SUCCESSFUL_RETURN; + } + else + { + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } +} + + +/* + * g e t U B + */ +inline returnValue QProblemB::getUB( real_t* const _ub ) const +{ + int i; + + for ( i=0; i= 0 ) && ( number < getNV( ) ) ) + { + value = ub[number]; + return SUCCESSFUL_RETURN; + } + else + { + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } +} + + +/* + * g e t B o u n d s + */ +inline returnValue QProblemB::getBounds( Bounds* const _bounds ) const +{ + *_bounds = bounds; + + return SUCCESSFUL_RETURN; +} + + +/* + * g e t N V + */ +inline int QProblemB::getNV( ) const +{ + return bounds.getNV( ); +} + + +/* + * g e t N F R + */ +inline int QProblemB::getNFR( ) +{ + return bounds.getNFR( ); +} + + +/* + * g e t N F X + */ +inline int QProblemB::getNFX( ) +{ + return bounds.getNFX( ); +} + + +/* + * g e t N F V + */ +inline int QProblemB::getNFV( ) const +{ + return bounds.getNFV( ); +} + + +/* + * g e t S t a t u s + */ +inline QProblemStatus QProblemB::getStatus( ) const +{ + return status; +} + + +/* + * i s I n i t i a l i s e d + */ +inline BooleanType QProblemB::isInitialised( ) const +{ + if ( status == QPS_NOTINITIALISED ) + return BT_FALSE; + else + return BT_TRUE; +} + + +/* + * i s S o l v e d + */ +inline BooleanType QProblemB::isSolved( ) const +{ + if ( status == QPS_SOLVED ) + return BT_TRUE; + else + return BT_FALSE; +} + + +/* + * i s I n f e a s i b l e + */ +inline BooleanType QProblemB::isInfeasible( ) const +{ + return infeasible; +} + + +/* + * i s U n b o u n d e d + */ +inline BooleanType QProblemB::isUnbounded( ) const +{ + return unbounded; +} + + +/* + * g e t P r i n t L e v e l + */ +inline PrintLevel QProblemB::getPrintLevel( ) const +{ + return printlevel; +} + + +/* + * g e t H e s s i a n T y p e + */ +inline HessianType QProblemB::getHessianType( ) const +{ + return hessianType; +} + + +/* + * s e t H e s s i a n T y p e + */ +inline returnValue QProblemB::setHessianType( HessianType _hessianType ) +{ + hessianType = _hessianType; + return SUCCESSFUL_RETURN; +} + + + +/***************************************************************************** + * P R O T E C T E D * + *****************************************************************************/ + +/* + * s e t H + */ +inline returnValue QProblemB::setH( const real_t* const H_new ) +{ + int i, j; + + int nV = getNV(); + + for( i=0; i= 0 ) && ( number < getNV( ) ) ) + { + lb[number] = value; + return SUCCESSFUL_RETURN; + } + else + { + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } +} + + +/* + * s e t U B + */ +inline returnValue QProblemB::setUB( const real_t* const ub_new ) +{ + int i; + + int nV = getNV(); + + for( i=0; i= 0 ) && ( number < getNV( ) ) ) + { + ub[number] = value; + + return SUCCESSFUL_RETURN; + } + else + { + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } +} + + +/* + * c o m p u t e G i v e n s + */ +inline void QProblemB::computeGivens( real_t xold, real_t yold, real_t& xnew, real_t& ynew, + real_t& c, real_t& s + ) const +{ + if ( getAbs( yold ) <= ZERO ) + { + c = 1.0; + s = 0.0; + + xnew = xold; + ynew = yold; + } + else + { + real_t t, mu; + + mu = getAbs( xold ); + if ( getAbs( yold ) > mu ) + mu = getAbs( yold ); + + t = mu * sqrt( (xold/mu)*(xold/mu) + (yold/mu)*(yold/mu) ); + + if ( xold < 0.0 ) + t = -t; + + c = xold/t; + s = yold/t; + xnew = t; + ynew = 0.0; + } + + return; +} + + +/* + * a p p l y G i v e n s + */ +inline void QProblemB::applyGivens( real_t c, real_t s, real_t xold, real_t yold, + real_t& xnew, real_t& ynew + ) const +{ + /* Usual Givens plane rotation requiring four multiplications. */ + xnew = c*xold + s*yold; + ynew = -s*xold + c*yold; +// double nu = s/(1.0+c); +// +// xnew = xold*c + yold*s; +// ynew = (xnew+xold)*nu - yold; + + return; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/SubjectTo.cpp b/phonelibs/qpoases/SRC/SubjectTo.cpp new file mode 100644 index 00000000000000..5dbf707c9d1f21 --- /dev/null +++ b/phonelibs/qpoases/SRC/SubjectTo.cpp @@ -0,0 +1,200 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/SubjectTo.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the SubjectTo class designed to manage working sets of + * constraints and bounds within a QProblem. + */ + + +#include + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * S u b j e c t T o + */ +SubjectTo::SubjectTo( ) : noLower( BT_TRUE ), + noUpper( BT_TRUE ), + size( 0 ) +{ + int i; + + for( i=0; iaddNumber( newnumber ) == RET_INDEXLIST_EXCEEDS_MAX_LENGTH ) + return THROWERROR( RET_ADDINDEX_FAILED ); + + return SUCCESSFUL_RETURN; +} + + +/* + * r e m o v e I n d e x + */ +returnValue SubjectTo::removeIndex( Indexlist* const indexlist, + int removenumber + ) +{ + status[removenumber] = ST_UNDEFINED; + + if ( indexlist->removeNumber( removenumber ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_UNKNOWN_BUG ); + + return SUCCESSFUL_RETURN; +} + + +/* + * s w a p I n d e x + */ +returnValue SubjectTo::swapIndex( Indexlist* const indexlist, + int number1, int number2 + ) +{ + /* consistency checks */ + if ( status[number1] != status[number2] ) + return THROWERROR( RET_SWAPINDEX_FAILED ); + + if ( number1 == number2 ) + { + THROWWARNING( RET_NOTHING_TO_DO ); + return SUCCESSFUL_RETURN; + } + + if ( indexlist->swapNumbers( number1,number2 ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SWAPINDEX_FAILED ); + + return SUCCESSFUL_RETURN; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/SubjectTo.ipp b/phonelibs/qpoases/SRC/SubjectTo.ipp new file mode 100644 index 00000000000000..7cd6dc69fe9bd7 --- /dev/null +++ b/phonelibs/qpoases/SRC/SubjectTo.ipp @@ -0,0 +1,132 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/SubjectTo.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the inlined member functions of the SubjectTo class + * designed to manage working sets of constraints and bounds within a QProblem. + */ + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * g e t T y p e + */ +inline SubjectToType SubjectTo::getType( int i ) const +{ + if ( ( i >= 0 ) && ( i < size ) ) + return type[i]; + else + return ST_UNKNOWN; +} + + +/* + * g e t S t a t u s + */ +inline SubjectToStatus SubjectTo::getStatus( int i ) const +{ + if ( ( i >= 0 ) && ( i < size ) ) + return status[i]; + else + return ST_UNDEFINED; +} + + +/* + * s e t T y p e + */ +inline returnValue SubjectTo::setType( int i, SubjectToType value ) +{ + if ( ( i >= 0 ) && ( i < size ) ) + { + type[i] = value; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * s e t S t a t u s + */ +inline returnValue SubjectTo::setStatus( int i, SubjectToStatus value ) +{ + if ( ( i >= 0 ) && ( i < size ) ) + { + status[i] = value; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * s e t N o L o w e r + */ +inline void SubjectTo::setNoLower( BooleanType _status ) +{ + noLower = _status; +} + + +/* + * s e t N o U p p e r + */ +inline void SubjectTo::setNoUpper( BooleanType _status ) +{ + noUpper = _status; +} + + +/* + * i s N o L o w e r + */ +inline BooleanType SubjectTo::isNoLower( ) const +{ + return noLower; +} + + +/* + * i s N o L o w e r + */ +inline BooleanType SubjectTo::isNoUpper( ) const +{ + return noUpper; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/Utils.cpp b/phonelibs/qpoases/SRC/Utils.cpp new file mode 100644 index 00000000000000..7a3d0a5226203b --- /dev/null +++ b/phonelibs/qpoases/SRC/Utils.cpp @@ -0,0 +1,471 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved. + * + * qpOASES is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * qpOASES is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with qpOASES; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + * + */ + + +/** + * \file SRC/Utils.cpp + * \author Hans Joachim Ferreau, Eckhard Arnold + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of some inlined utilities for working with the different QProblem + * classes. + */ + + +#include + +#if defined(__WIN32__) || defined(WIN32) + #include +#elif defined(LINUX) + #include + #include +#endif + +#ifdef __MATLAB__ + #include +#endif + + +#include + + + +#ifdef PC_DEBUG /* Define print functions only for debugging! */ +/* + * p r i n t + */ +returnValue print( const real_t* const v, int n ) +{ + int i; + char myPrintfString[160]; + + /* Print a vector. */ + myPrintf( "[\t" ); + for( i=0; ithrowError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + + /* 2) Read data from file. */ + for( i=0; ithrowError( RET_UNABLE_TO_READ_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + data[i*ncol + j] = ( (real_t) float_data ); + } + } + + /* 3) Close file. */ + fclose( datafile ); + + return SUCCESSFUL_RETURN; +} + + +/* + * r e a d F r o m F i l e + */ +returnValue readFromFile( real_t* data, int n, + const char* datafilename + ) +{ + return readFromFile( data, n, 1, datafilename ); +} + + + +/* + * r e a d F r o m F i l e + */ +returnValue readFromFile( int* data, int n, + const char* datafilename + ) +{ + int i; + myFILE* datafile; + + /* 1) Open file. */ + if ( ( datafile = fopen( datafilename, "r" ) ) == 0 ) + { + char errstr[80]; + sprintf( errstr,"(%s)",datafilename ); + return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + + /* 2) Read data from file. */ + for( i=0; ithrowError( RET_UNABLE_TO_READ_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + } + + /* 3) Close file. */ + fclose( datafile ); + + return SUCCESSFUL_RETURN; +} + + +/* + * w r i t e I n t o F i l e + */ +returnValue writeIntoFile( const real_t* const data, int nrow, int ncol, + const char* datafilename, BooleanType append + ) +{ + int i, j; + myFILE* datafile; + + /* 1) Open file. */ + if ( append == BT_TRUE ) + { + /* append data */ + if ( ( datafile = fopen( datafilename, "a" ) ) == 0 ) + { + char errstr[80]; + sprintf( errstr,"(%s)",datafilename ); + return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + } + else + { + /* do not append data */ + if ( ( datafile = fopen( datafilename, "w" ) ) == 0 ) + { + char errstr[80]; + sprintf( errstr,"(%s)",datafilename ); + return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + } + + /* 2) Write data into file. */ + for( i=0; ithrowError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + } + else + { + /* do not append data */ + if ( ( datafile = fopen( datafilename, "w" ) ) == 0 ) + { + char errstr[80]; + sprintf( errstr,"(%s)",datafilename ); + return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + } + + /* 2) Write data into file. */ + for( i=0; i #include "cereal/gen/cpp/log.capnp.h" +#include "cereal/gen/cpp/car.capnp.h" +#include "common/params.h" #include "common/swaglog.h" #include "common/timing.h" @@ -38,20 +40,55 @@ bool loopback_can = false; #define TIMEOUT 0 #define SAFETY_NOOUTPUT 0x0000 -#define SAFETY_HONDA 0x0001 -#define SAFETY_ALLOUTPUT 0x1337 +pthread_t safety_setter_thread_handle = -1; + +void *safety_setter_thread(void *s) { + char *value; + size_t value_sz = 0; + + LOGW("waiting for params to set safety model"); + while (1) { + const int result = read_db_value(NULL, "CarParams", &value, &value_sz); + if (value_sz > 0) break; + usleep(100*1000); + } + LOGW("got %d bytes CarParams", value_sz); + + // format for board, make copy due to alignment issues, will be freed on out of scope + auto amsg = kj::heapArray((value_sz / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), value, value_sz); + + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::CarParams::Reader car_params = cmsg.getRoot(); + + int safety_model = car_params.getSafetyModel(); + LOGW("setting safety model: %d", safety_model); + + pthread_mutex_lock(&usb_lock); + + // set in the mutex to avoid race + safety_setter_thread_handle = -1; + + libusb_control_transfer(dev_handle, 0x40, 0xdc, safety_model, 0, NULL, 0, TIMEOUT); + + pthread_mutex_unlock(&usb_lock); + + return NULL; +} + +// must be called before threads or with mutex bool usb_connect() { int err; dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); - if (dev_handle == NULL) { return false; } + if (dev_handle == NULL) { goto fail; } err = libusb_set_configuration(dev_handle, 1); - if (err != 0) { return false; } + if (err != 0) { goto fail; } err = libusb_claim_interface(dev_handle, 0); - if (err != 0) { return false; } + if (err != 0) { goto fail; } if (loopback_can) { libusb_control_transfer(dev_handle, 0xc0, 0xe5, 1, 0, NULL, 0, TIMEOUT); @@ -60,30 +97,23 @@ bool usb_connect() { // power off ESP libusb_control_transfer(dev_handle, 0xc0, 0xd9, 0, 0, NULL, 0, TIMEOUT); - // forward CAN1 to CAN3...soon - //libusb_control_transfer(dev_handle, 0xc0, 0xdd, 1, 2, NULL, 0, TIMEOUT); - - // set UART modes for Honda Accord - /*for (int uart = 2; uart <= 3; uart++) { - // 9600 baud - libusb_control_transfer(dev_handle, 0x40, 0xe1, uart, 9600, NULL, 0, TIMEOUT); - // even parity - libusb_control_transfer(dev_handle, 0x40, 0xe2, uart, 1, NULL, 0, TIMEOUT); - // callback 1 - libusb_control_transfer(dev_handle, 0x40, 0xe3, uart, 1, NULL, 0, TIMEOUT); - } + // power on charging (may trigger a reconnection, should be okay) + #ifndef __x86_64__ + libusb_control_transfer(dev_handle, 0xc0, 0xe6, 1, 0, NULL, 0, TIMEOUT); + #else + LOGW("not enabling charging on x86_64"); + #endif - // TODO: Boardd should be able to set the baud rate - int baud = 500000; - libusb_control_transfer(dev_handle, 0x40, 0xde, 0, 0, - (unsigned char *)&baud, sizeof(baud), TIMEOUT); // CAN1 - libusb_control_transfer(dev_handle, 0x40, 0xde, 1, 0, - (unsigned char *)&baud, sizeof(baud), TIMEOUT); // CAN2*/ + // no output is the default + libusb_control_transfer(dev_handle, 0x40, 0xdc, SAFETY_NOOUTPUT, 0, NULL, 0, TIMEOUT); - // TODO: Boardd should be able to be told which safety model to use - libusb_control_transfer(dev_handle, 0x40, 0xdc, SAFETY_HONDA, 0, NULL, 0, TIMEOUT); + if (safety_setter_thread_handle == -1) { + err = pthread_create(&safety_setter_thread_handle, NULL, safety_setter_thread, NULL); + } return true; +fail: + return false; } void usb_retry_connect() { @@ -93,7 +123,7 @@ void usb_retry_connect() { } void handle_usb_issue(int err, const char func[]) { - LOGE("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func); + LOGE_100("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func); if (err == -4) { LOGE("lost connection"); usb_retry_connect(); @@ -113,7 +143,7 @@ void can_recv(void *s) { do { err = libusb_bulk_transfer(dev_handle, 0x81, (uint8_t*)data, RECV_SIZE, &recv, TIMEOUT); if (err != 0) { handle_usb_issue(err, __func__); } - if (err == -8) { LOGE("overflow got 0x%x", recv); }; + if (err == -8) { LOGE_100("overflow got 0x%x", recv); }; // timeout is okay to exit, recv still happened if (err == -7) { break; } @@ -261,6 +291,46 @@ void can_send(void *s) { // **** threads **** +void *thermal_thread(void *crap) { + int err; + LOGD("start thermal thread"); + + // thermal = 8005 + void *context = zmq_ctx_new(); + void *subscriber = zmq_socket(context, ZMQ_SUB); + zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0); + zmq_connect(subscriber, "tcp://127.0.0.1:8005"); + + // run as fast as messages come in + while (!do_exit) { + // recv from thermal + zmq_msg_t msg; + zmq_msg_init(&msg); + err = zmq_msg_recv(&msg, subscriber, 0); + assert(err >= 0); + + // format for board, make copy due to alignment issues, will be freed on out of scope + // copied from send thread... + auto amsg = kj::heapArray((zmq_msg_size(&msg) / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), zmq_msg_data(&msg), zmq_msg_size(&msg)); + + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + + uint16_t target_fan_speed = event.getThermal().getFanSpeed(); + //LOGW("setting fan speed %d", target_fan_speed); + + pthread_mutex_lock(&usb_lock); + libusb_control_transfer(dev_handle, 0xc0, 0xd3, target_fan_speed, 0, NULL, 0, TIMEOUT); + pthread_mutex_unlock(&usb_lock); + } + + // turn the fan off when we exit + libusb_control_transfer(dev_handle, 0xc0, 0xd3, 0, 0, NULL, 0, TIMEOUT); + + return NULL; +} + void *can_send_thread(void *crap) { LOGD("start send thread"); @@ -364,8 +434,16 @@ int main() { can_recv_thread, NULL); assert(err == 0); + pthread_t thermal_thread_handle; + err = pthread_create(&thermal_thread_handle, NULL, + thermal_thread, NULL); + assert(err == 0); + // join threads + err = pthread_join(thermal_thread_handle, NULL); + assert(err == 0); + err = pthread_join(can_recv_thread_handle, NULL); assert(err == 0); diff --git a/selfdrive/boardd/boardd.py b/selfdrive/boardd/boardd.py index 8bda67923f08f2..06abe8b3a586e2 100755 --- a/selfdrive/boardd/boardd.py +++ b/selfdrive/boardd/boardd.py @@ -20,6 +20,8 @@ SAFETY_NOOUTPUT = 0 SAFETY_HONDA = 1 +SAFETY_TOYOTA = 2 +SAFETY_TOYOTA_NOLIMITS = 0x1336 SAFETY_ALLOUTPUT = 0x1337 # *** serialization functions *** @@ -33,7 +35,7 @@ def can_list_to_can_capnp(can_msgs, msgtype='can'): cc = dat.can[i] cc.address = can_msg[0] cc.busTime = can_msg[1] - cc.dat = can_msg[2] + cc.dat = str(can_msg[2]) cc.src = can_msg[3] return dat @@ -111,6 +113,7 @@ def can_init(): def boardd_mock_loop(): context = zmq.Context() can_init() + handle.controlWrite(0x40, 0xdc, SAFETY_ALLOUTPUT, 0, b'') logcan = messaging.sub_sock(context, service_list['can'].port) diff --git a/selfdrive/can/Makefile b/selfdrive/can/Makefile index 9c2ebbd7321b35..5a91e70291750a 100644 --- a/selfdrive/can/Makefile +++ b/selfdrive/can/Makefile @@ -1,6 +1,7 @@ CC = clang CXX = clang++ +BASEDIR = ../.. PHONELIBS := ../../phonelibs UNAME_S := $(shell uname -s) @@ -53,7 +54,7 @@ libdbc.so:: ../../cereal/gen/cpp/log.capnp.h ../../cereal/gen/cpp/log.capnp.h: cd ../../cereal && make -libdbc.so:: parser.cc $(DBC_CCS) +libdbc.so:: dbc.cc parser.cc packer.cc $(DBC_CCS) $(CXX) -fPIC -shared -o '$@' $^ \ -I. \ -I../.. \ @@ -63,7 +64,7 @@ libdbc.so:: parser.cc $(DBC_CCS) $(CEREAL_CXXFLAGS) \ $(CEREAL_LIBS) -dbc_out/%.cc: $(OPENDBC_PATH)/%.dbc +dbc_out/%.cc: $(OPENDBC_PATH)/%.dbc process_dbc.py dbc_template.cc PYTHONPATH=$(PYTHONPATH):$(CWD)/../../pyextra ./process_dbc.py '$<' '$@' .PHONY: clean diff --git a/selfdrive/can/parser_common.h b/selfdrive/can/common.h similarity index 81% rename from selfdrive/can/parser_common.h rename to selfdrive/can/common.h index e3b944f83ec2a0..3790c1358a9bfe 100644 --- a/selfdrive/can/parser_common.h +++ b/selfdrive/can/common.h @@ -1,13 +1,20 @@ -#ifndef PARSER_COMMON_H -#define PARSER_COMMON_H +#ifndef SELFDRIVE_CAN_COMMON_H +#define SELFDRIVE_CAN_COMMON_H #include #include +#include #define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0])) +struct SignalPackValue { + const char* name; + double value; +}; + + struct SignalParseOptions { uint32_t address; const char* name; @@ -54,6 +61,8 @@ struct DBC { const Msg *msgs; }; +const DBC* dbc_lookup(const std::string& dbc_name); + void dbc_register(const DBC* dbc); #define dbc_init(dbc) \ diff --git a/selfdrive/can/dbc.cc b/selfdrive/can/dbc.cc new file mode 100644 index 00000000000000..c8295d1e0c8157 --- /dev/null +++ b/selfdrive/can/dbc.cc @@ -0,0 +1,26 @@ +#include +#include + +#include "common.h" + +namespace { + +std::vector& get_dbcs() { + static std::vector vec; + return vec; +} + +} + +const DBC* dbc_lookup(const std::string& dbc_name) { + for (const auto& dbci : get_dbcs()) { + if (dbc_name == dbci->name) { + return dbci; + } + } + return NULL; +} + +void dbc_register(const DBC* dbc) { + get_dbcs().push_back(dbc); +} diff --git a/selfdrive/can/dbc_template.cc b/selfdrive/can/dbc_template.cc index 3676c823ecd1eb..1d85b1e2f3eb3b 100644 --- a/selfdrive/can/dbc_template.cc +++ b/selfdrive/can/dbc_template.cc @@ -1,6 +1,6 @@ #include -#include "parser_common.h" +#include "common.h" namespace { diff --git a/selfdrive/can/libdbc_py.py b/selfdrive/can/libdbc_py.py new file mode 100644 index 00000000000000..0afeee40ef334b --- /dev/null +++ b/selfdrive/can/libdbc_py.py @@ -0,0 +1,51 @@ +import os +import subprocess + +from cffi import FFI + +can_dir = os.path.dirname(os.path.abspath(__file__)) +libdbc_fn = os.path.join(can_dir, "libdbc.so") +subprocess.check_output(["make"], cwd=can_dir) + +ffi = FFI() +ffi.cdef(""" + +typedef struct SignalParseOptions { + uint32_t address; + const char* name; + double default_value; +} SignalParseOptions; + +typedef struct MessageParseOptions { + uint32_t address; + int check_frequency; +} MessageParseOptions; + +typedef struct SignalValue { + uint32_t address; + uint16_t ts; + const char* name; + double value; +} SignalValue; + +void* can_init(int bus, const char* dbc_name, + size_t num_message_options, const MessageParseOptions* message_options, + size_t num_signal_options, const SignalParseOptions* signal_options); + +void can_update(void* can, uint64_t sec, bool wait); + +size_t can_query(void* can, uint64_t sec, bool *out_can_valid, size_t out_values_size, SignalValue* out_values); + + +typedef struct SignalPackValue { + const char* name; + double value; +} SignalPackValue; + +void* canpack_init(const char* dbc_name); + +uint64_t canpack_pack(void* inst, uint32_t address, size_t num_vals, const SignalPackValue *vals); + +""") + +libdbc = ffi.dlopen(libdbc_fn) diff --git a/selfdrive/can/packer.cc b/selfdrive/can/packer.cc new file mode 100644 index 00000000000000..3eddc6aeef79a3 --- /dev/null +++ b/selfdrive/can/packer.cc @@ -0,0 +1,81 @@ +#include + +#include +#include +#include +#include +#include + +#include "common.h" + +#define WARN printf + +namespace { + +class CANPacker { +public: + CANPacker(const std::string& dbc_name) { + dbc = dbc_lookup(dbc_name); + assert(dbc); + + for (int i=0; inum_msgs; i++) { + const Msg* msg = &dbc->msgs[i]; + for (int j=0; jnum_sigs; j++) { + const Signal* sig = &msg->sigs[j]; + signal_lookup[std::make_pair(msg->address, std::string(sig->name))] = *sig; + } + } + } + + uint64_t pack(uint32_t address, const std::vector &signals) { + uint64_t ret = 0; + for (const auto& sigval : signals) { + std::string name = std::string(sigval.name); + double value = sigval.value; + + auto sig_it = signal_lookup.find(make_pair(address, name)); + if (sig_it == signal_lookup.end()) { + WARN("undefined signal %s", name.c_str()); + continue; + } + auto sig = sig_it->second; + + int64_t ival = (int64_t)((value - sig.offset) / sig.factor); + if (ival < 0) { + WARN("signed pack unsupported right now"); + continue; + } + + uint64_t mask = ((1ULL << sig.b2)-1) << sig.bo; + uint64_t dat = (ival & ((1ULL << sig.b2)-1)) << sig.bo; + ret &= ~mask; + ret |= dat; + } + + return ret; + } + + + +private: + const DBC *dbc = NULL; + std::map, Signal> signal_lookup; +}; + +} + +extern "C" { + +void* canpack_init(const char* dbc_name) { + CANPacker *ret = new CANPacker(std::string(dbc_name)); + return (void*)ret; +} + +uint64_t canpack_pack(void* inst, uint32_t address, size_t num_vals, const SignalPackValue *vals) { + CANPacker *cp = (CANPacker*)inst; + + return cp->pack(address, std::vector(vals, vals+num_vals)); +} + +} + diff --git a/selfdrive/can/packer.py b/selfdrive/can/packer.py new file mode 100644 index 00000000000000..ff52e165e2f5bd --- /dev/null +++ b/selfdrive/can/packer.py @@ -0,0 +1,37 @@ +import struct + +from selfdrive.can.libdbc_py import libdbc, ffi + +class CANPacker(object): + def __init__(self, dbc_name): + self.packer = libdbc.canpack_init(dbc_name) + self.sig_names = {} + + def pack(self, addr, values): + # values: [(signal_name, signal_value)] + + values_thing = [] + for name, value in values: + if name not in self.sig_names: + self.sig_names[name] = ffi.new("char[]", name) + + values_thing.append({ + 'name': self.sig_names[name], + 'value': value + }) + + values_c = ffi.new("SignalPackValue[]", values_thing) + + return libdbc.canpack_pack(self.packer, addr, len(values_thing), values_c) + + def pack_bytes(self, addr, values): + return struct.pack(">Q", self.pack(addr, values)) + + +if __name__ == "__main__": + cp = CANPacker("honda_civic_touring_2016_can") + s = cp.pack_bytes(0x30c, [ + ("PCM_SPEED", 123), + ("PCM_GAS", 10), + ]) + print s.encode("hex") diff --git a/selfdrive/can/parser.cc b/selfdrive/can/parser.cc index 7e7913bf433862..839adf5222939d 100644 --- a/selfdrive/can/parser.cc +++ b/selfdrive/can/parser.cc @@ -18,7 +18,7 @@ #include #include "cereal/gen/cpp/log.capnp.h" -#include "parser_common.h" +#include "common.h" #define DEBUG(...) // #define DEBUG printf @@ -40,8 +40,6 @@ uint64_t read_u64_be(const uint8_t* v) { | (uint64_t)v[7]); } -std::vector g_dbc; - bool honda_checksum(int address, uint64_t d, int l) { int target = (d >> l) & 0xF; @@ -77,9 +75,9 @@ struct MessageState { for (int i=0; i < parse_sigs.size(); i++) { auto& sig = parse_sigs[i]; - int64_t tmp = (dat >> sig.bo) & ((1 << sig.b2)-1); + int64_t tmp = (dat >> sig.bo) & ((1ULL << sig.b2)-1); if (sig.is_signed) { - tmp -= (tmp >> (sig.b2-1)) ? (1<> (sig.b2-1)) ? (1ULL << sig.b2) : 0; //signed } DEBUG("parse %X %s -> %ld\n", address, sig.name, tmp); @@ -123,6 +121,7 @@ struct MessageState { }; + class CANParser { public: CANParser(int abus, const std::string& dbc_name, @@ -135,15 +134,10 @@ class CANParser { zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0); zmq_connect(subscriber, "tcp://127.0.0.1:8006"); - for (auto dbci : g_dbc) { - if (dbci->name == dbc_name) { - dbc = dbci; - break; - } - } + dbc = dbc_lookup(dbc_name); assert(dbc); - for (auto &op : options) { + for (const auto& op : options) { MessageState state = { .address = op.address, // .check_frequency = op.check_frequency, @@ -178,7 +172,7 @@ class CANParser { } // track requested signals for this message - for (auto &sigop : sigoptions) { + for (const auto& sigop : sigoptions) { if (sigop.address != op.address) continue; for (int i=0; inum_sigs; i++) { @@ -230,8 +224,8 @@ class CANParser { void UpdateValid(uint64_t sec) { can_valid = true; - for (auto &kv : message_states) { - auto &state = kv.second; + for (const auto& kv : message_states) { + const auto& state = kv.second; if (state.check_threshold > 0 && (sec - state.seen) > state.check_threshold) { if (state.seen > 0) { INFO("%X TIMEOUT\n", state.address); @@ -279,8 +273,8 @@ class CANParser { std::vector query(uint64_t sec) { std::vector ret; - for (auto &kv : message_states) { - auto &state = kv.second; + for (const auto& kv : message_states) { + const auto& state = kv.second; if (sec != 0 && state.seen != sec) continue; for (int i=0; i 0. + if (brake < brake_hyst_on and not braking) or brake < brake_hyst_off: + brake = 0. + braking = brake > 0. # for small brake oscillations within brake_hyst_gap, don't change the brake command - if final_brake == 0.: + if brake == 0.: brake_steady = 0. - elif final_brake > brake_steady + brake_hyst_gap: - brake_steady = final_brake - brake_hyst_gap - elif final_brake < brake_steady - brake_hyst_gap: - brake_steady = final_brake + brake_hyst_gap - final_brake = brake_steady + elif brake > brake_steady + brake_hyst_gap: + brake_steady = brake - brake_hyst_gap + elif brake < brake_steady - brake_hyst_gap: + brake_steady = brake + brake_hyst_gap + brake = brake_steady if not civic: brake_on_offset_v = [.25, .15] # min brake command on brake activation. below this no decel is perceived @@ -36,10 +36,10 @@ def actuator_hystereses(final_brake, braking, brake_steady, v_ego, civic): # offset the brake command for threshold in the brake system. no brake torque perceived below it brake_on_offset = interp(v_ego, brake_on_offset_bp, brake_on_offset_v) brake_offset = brake_on_offset - brake_hyst_on - if final_brake > 0.0: - final_brake += brake_offset + if brake > 0.0: + brake += brake_offset - return final_brake, braking, brake_steady + return brake, braking, brake_steady class AH: #[alert_idx, value] @@ -78,12 +78,9 @@ class CarController(object): def __init__(self): self.braking = False self.brake_steady = 0. - self.final_brake_last = 0. - - # redundant safety check with the board - self.controls_allowed = False + self.brake_last = 0. - def update(self, sendcan, enabled, CS, frame, final_gas, final_brake, final_steer, \ + def update(self, sendcan, enabled, CS, frame, actuators, \ pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \ hud_v_cruise, hud_show_lanes, hud_show_car, hud_alert, \ snd_beep, snd_chime): @@ -94,20 +91,16 @@ def update(self, sendcan, enabled, CS, frame, final_gas, final_brake, final_stee return # *** apply brake hysteresis *** - final_brake, self.braking, self.brake_steady = actuator_hystereses(final_brake, self.braking, self.brake_steady, CS.v_ego, CS.civic) + brake, self.braking, self.brake_steady = actuator_hystereses(actuators.brake, self.braking, self.brake_steady, CS.v_ego, CS.civic) # *** no output if not enabled *** - if not enabled: - final_gas = 0. - final_brake = 0. - final_steer = 0. + if not enabled and CS.pcm_acc_status: # send pcm acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated - if CS.pcm_acc_status: - pcm_cancel_cmd = True + pcm_cancel_cmd = True # *** rate limit after the enable check *** - final_brake = rate_limit(final_brake, self.final_brake_last, -2., 1./100) - self.final_brake_last = final_brake + brake = rate_limit(brake, self.brake_last, -2., 1./100) + self.brake_last = brake # vehicle hud display, wait for one update from 10Hz 0x304 msg #TODO: use enum!! @@ -143,7 +136,8 @@ def update(self, sendcan, enabled, CS, frame, final_gas, final_brake, final_stee GAS_MAX = 1004 BRAKE_MAX = 1024/4 if CS.civic: - STEER_MAX = 0x1000 + is_fw_modified = os.getenv("DONGLE_ID") in ['b0f5a01cf604185c'] + STEER_MAX = 0x1FFF if is_fw_modified else 0x1000 elif CS.crv: STEER_MAX = 0x300 # CR-V only uses 12-bits and requires a lower value else: @@ -151,50 +145,22 @@ def update(self, sendcan, enabled, CS, frame, final_gas, final_brake, final_stee GAS_OFFSET = 328 # steer torque is converted back to CAN reference (positive when steering right) - apply_gas = int(clip(final_gas*GAS_MAX, 0, GAS_MAX-1)) - apply_brake = int(clip(final_brake*BRAKE_MAX, 0, BRAKE_MAX-1)) - apply_steer = int(clip(-final_steer*STEER_MAX, -STEER_MAX, STEER_MAX)) + apply_gas = int(clip(actuators.gas * GAS_MAX, 0, GAS_MAX - 1)) + apply_brake = int(clip(brake * BRAKE_MAX, 0, BRAKE_MAX - 1)) + apply_steer = int(clip(-actuators.steer * STEER_MAX, -STEER_MAX, STEER_MAX)) # no gas if you are hitting the brake or the user is if apply_gas > 0 and (apply_brake != 0 or CS.brake_pressed): - print "CANCELLING GAS", apply_brake apply_gas = 0 # no computer brake if the gas is being pressed if CS.car_gas > 0 and apply_brake != 0: - print "CANCELLING BRAKE" apply_brake = 0 # any other cp.vl[0x18F]['STEER_STATUS'] is common and can happen during user override. sending 0 torque to avoid EPS sending error 5 if CS.steer_not_allowed: - print "STEER ALERT, TORQUE INHIBITED" apply_steer = 0 - # *** entry into controls state *** - if (CS.prev_cruise_buttons == CruiseButtons.DECEL_SET or CS.prev_cruise_buttons == CruiseButtons.RES_ACCEL) and \ - CS.cruise_buttons == 0 and not self.controls_allowed: - print "CONTROLS ARE LIVE" - self.controls_allowed = True - - # *** exit from controls state on cancel, gas, or brake *** - if (CS.cruise_buttons == CruiseButtons.CANCEL or CS.brake_pressed or - CS.user_gas_pressed or (CS.pedal_gas > 0 and CS.brake_only)) and self.controls_allowed: - print "CONTROLS ARE DEAD" - self.controls_allowed = False - - # *** controls fail on steer error, brake error, or invalid can *** - if CS.steer_error: - print "STEER ERROR" - self.controls_allowed = False - - if CS.brake_error: - print "BRAKE ERROR" - self.controls_allowed = False - - if not CS.can_valid and self.controls_allowed: # 200 ms - print "CAN INVALID" - self.controls_allowed = False - # Send CAN commands. can_sends = [] diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index d2c0f974ae324a..4eb8c6c38697aa 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -1,18 +1,54 @@ import os import time - +from cereal import car import common.numpy_fast as np from common.realtime import sec_since_boot - import selfdrive.messaging as messaging +from selfdrive.can.parser import CANParser +from selfdrive.config import Conversions as CV -from selfdrive.car.honda.can_parser import CANParser -from selfdrive.can.parser import CANParser as CANParserC -NEW_CAN = os.getenv("OLD_CAN") is None +def parse_gear_shifter(can_gear_shifter, is_acura): -def get_can_parser(CP): - # this function generates lists for signal, messages and initial values + if can_gear_shifter == 0x1: + return "park" + elif can_gear_shifter == 0x2: + return "reverse" + + if is_acura: + if can_gear_shifter == 0x3: + return "neutral" + elif can_gear_shifter == 0x4: + return "drive" + elif can_gear_shifter == 0xa: + return "sport" + + else: + if can_gear_shifter == 0x4: + return "neutral" + elif can_gear_shifter == 0x8: + return "drive" + elif can_gear_shifter == 0x10: + return "sport" + elif can_gear_shifter == 0x20: + return "low" + + return "unknown" + +_K0 = -0.3 +_K1 = -0.01879 +_K2 = 0.01013 + +def calc_cruise_offset(offset, speed): + # euristic formula so that speed is controlled to ~ 0.3m/s below pid_speed + # constraints to solve for _K0, _K1, _K2 are: + # - speed = 0m/s, out = -0.3 + # - speed = 34m/s, offset = 20, out = -0.25 + # - speed = 34m/s, offset = -2.5, out = -1.8 + return min(_K0 + _K1 * speed + _K2 * speed * offset, 0.) + +def get_can_signals(CP): +# this function generates lists for signal, messages and initial values if CP.carFingerprint == "HONDA CIVIC 2016 TOURING": dbc_f = 'honda_civic_touring_2016_can.dbc' signals = [ @@ -50,8 +86,9 @@ def get_can_parser(CP): ("CRUISE_SETTING", 0x296, 0), ("LEFT_BLINKER", 0x326, 0), ("RIGHT_BLINKER", 0x326, 0), - ("COUNTER", 0x324, 0), - ("ENGINE_RPM", 0x17C, 0) + ("CRUISE_SPEED_OFFSET", 0x37c, 0), + ("EPB_STATE", 0x1c2, 0), + ("BRAKE_HOLD_ACTIVE", 0x1A4, 0), ] checks = [ # address, frequency @@ -65,6 +102,7 @@ def get_can_parser(CP): (0x1d0, 50), (0x305, 10), (0x324, 10), + (0x37c, 10), (0x405, 3), ] @@ -104,8 +142,7 @@ def get_can_parser(CP): ("CRUISE_SETTING", 0x1a6, 0), ("LEFT_BLINKER", 0x294, 0), ("RIGHT_BLINKER", 0x294, 0), - ("COUNTER", 0x324, 0), - ("ENGINE_RPM", 0x17C, 0) + ("CRUISE_SPEED_OFFSET", 0x37c, 0) ] checks = [ (0x156, 100), @@ -118,6 +155,7 @@ def get_can_parser(CP): (0x1d0, 50), (0x305, 10), (0x324, 10), + (0x37c, 10), (0x405, 3), ] elif CP.carFingerprint == "HONDA ACCORD 2016 TOURING": @@ -157,8 +195,6 @@ def get_can_parser(CP): ("CRUISE_SETTING", 0x1a6, 0), ("LEFT_BLINKER", 0x294, 0), ("RIGHT_BLINKER", 0x294, 0), - ("COUNTER", 0x324, 0), - ("ENGINE_RPM", 0x17C, 0) ] checks = [ (0x156, 100), @@ -209,8 +245,6 @@ def get_can_parser(CP): ("CRUISE_SETTING", 0x1a6, 0), ("LEFT_BLINKER", 0x294, 0), ("RIGHT_BLINKER", 0x294, 0), - ("COUNTER", 0x324, 0), - ("ENGINE_RPM", 0x17C, 0) ] checks = [ (0x156, 100), @@ -230,22 +264,23 @@ def get_can_parser(CP): signals.append(("INTERCEPTOR_GAS", 0x201, 0)) checks.append((0x201, 50)) - if NEW_CAN: - return CANParserC(os.path.splitext(dbc_f)[0], signals, checks, 0) - else: - return CANParser(dbc_f, signals, checks) + return dbc_f, signals, checks + +def get_can_parser(CP): + dbc_f, signals, checks = get_can_signals(CP) + return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 0) class CarState(object): def __init__(self, CP, logcan): + self.acura = False self.civic = False self.accord = False self.crv = False if CP.carFingerprint == "HONDA CIVIC 2016 TOURING": self.civic = True elif CP.carFingerprint == "ACURA ILX 2016 ACURAWATCH PLUS": - self.civic = False + self.acura = True elif CP.carFingerprint == "HONDA ACCORD 2016 TOURING": - # fake civic self.accord = True elif CP.carFingerprint == "HONDA CR-V 2016 TOURING": self.crv = True @@ -274,10 +309,7 @@ def __init__(self, CP, logcan): def update(self, can_pub_main=None): cp = self.cp - if NEW_CAN: - cp.update(int(sec_since_boot() * 1e9), False) - else: - cp.update_can(can_pub_main) + cp.update(int(sec_since_boot() * 1e9), False) # copy can_valid self.can_valid = cp.can_valid @@ -294,8 +326,6 @@ def update(self, can_pub_main=None): self.prev_left_blinker_on = self.left_blinker_on self.prev_right_blinker_on = self.right_blinker_on - self.rpm = cp.vl[0x17C]['ENGINE_RPM'] - # ******************* parse out can ******************* self.door_all_closed = not any([cp.vl[0x405]['DOOR_OPEN_FL'], cp.vl[0x405]['DOOR_OPEN_FR'], cp.vl[0x405]['DOOR_OPEN_RL'], cp.vl[0x405]['DOOR_OPEN_RR']]) @@ -316,9 +346,11 @@ def update(self, can_pub_main=None): self.brake_error = cp.vl[0x1B0]['BRAKE_ERROR_1'] or cp.vl[0x1B0]['BRAKE_ERROR_2'] self.esp_disabled = cp.vl[0x1A4]['ESP_DISABLED'] # calc best v_ego estimate, by averaging two opposite corners - self.v_wheel = ( - cp.vl[0x1D0]['WHEEL_SPEED_FL'] + cp.vl[0x1D0]['WHEEL_SPEED_FR'] + - cp.vl[0x1D0]['WHEEL_SPEED_RL'] + cp.vl[0x1D0]['WHEEL_SPEED_RR']) / 4. + self.v_wheel_fl = cp.vl[0x1D0]['WHEEL_SPEED_FL'] + self.v_wheel_fr = cp.vl[0x1D0]['WHEEL_SPEED_FR'] + self.v_wheel_rl = cp.vl[0x1D0]['WHEEL_SPEED_RL'] + self.v_wheel_rr = cp.vl[0x1D0]['WHEEL_SPEED_RR'] + self.v_wheel = (self.v_wheel_fl + self.v_wheel_fr + self.v_wheel_rl + self.v_wheel_rr) / 4. # blend in transmission speed at low speed, since it has more low speed accuracy self.v_weight = np.interp(self.v_wheel, v_weight_bp, v_weight_v) self.v_ego = (1. - self.v_weight) * cp.vl[0x158]['XMISSION_SPEED'] + self.v_weight * self.v_wheel @@ -328,49 +360,59 @@ def update(self, can_pub_main=None): self.user_gas_pressed = self.user_gas > 0 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change #print self.user_gas, self.user_gas_pressed if self.civic: - self.gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] + can_gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] self.angle_steers = cp.vl[0x14A]['STEER_ANGLE'] self.gear = 0 # TODO: civic has CVT... needs rev engineering self.cruise_setting = cp.vl[0x296]['CRUISE_SETTING'] self.cruise_buttons = cp.vl[0x296]['CRUISE_BUTTONS'] self.main_on = cp.vl[0x326]['MAIN_ON'] - self.gear_shifter_valid = self.gear_shifter in [1,8] # TODO: 1/P allowed for debug self.blinker_on = cp.vl[0x326]['LEFT_BLINKER'] or cp.vl[0x326]['RIGHT_BLINKER'] self.left_blinker_on = cp.vl[0x326]['LEFT_BLINKER'] self.right_blinker_on = cp.vl[0x326]['RIGHT_BLINKER'] + self.cruise_speed_offset = calc_cruise_offset(cp.vl[0x37c]['CRUISE_SPEED_OFFSET'], self.v_ego) + self.park_brake = cp.vl[0x1c2]['EPB_STATE'] != 0 + self.brake_hold = cp.vl[0x1A4]['BRAKE_HOLD_ACTIVE'] elif self.accord: - self.gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] + can_gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] self.gear = 0 # TODO: accord has CVT... needs rev engineering self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] self.main_on = cp.vl[0x1A6]['MAIN_ON'] - self.gear_shifter_valid = self.gear_shifter in [1,8] # TODO: 1/P allowed for debug self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] + self.cruise_speed_offset = -0.3 + self.park_brake = 0 # TODO + self.brake_hold = 0 # TODO elif self.crv: - self.gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] + can_gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] self.gear = cp.vl[0x191]['GEAR'] self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] self.main_on = cp.vl[0x1A6]['MAIN_ON'] - self.gear_shifter_valid = self.gear_shifter in [1,8] # TODO: 1/P allowed for debug self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] - else: - self.gear_shifter = cp.vl[0x1A3]['GEAR_SHIFTER'] + self.cruise_speed_offset = -0.3 + self.park_brake = 0 # TODO + self.brake_hold = 0 # TODO + elif self.acura: + can_gear_shifter = cp.vl[0x1A3]['GEAR_SHIFTER'] self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] self.gear = cp.vl[0x1A3]['GEAR'] self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] self.main_on = cp.vl[0x1A6]['MAIN_ON'] - self.gear_shifter_valid = self.gear_shifter in [1,4] # TODO: 1/P allowed for debug self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] + self.cruise_speed_offset = calc_cruise_offset(cp.vl[0x37c]['CRUISE_SPEED_OFFSET'], self.v_ego) + self.park_brake = 0 # TODO + self.brake_hold = 0 + + self.gear_shifter = parse_gear_shifter(can_gear_shifter, self.acura) if self.accord: # on the accord, this doesn't seem to include cruise control @@ -398,4 +440,25 @@ def update(self, can_pub_main=None): self.pcm_acc_status = cp.vl[0x17C]['ACC_STATUS'] self.pedal_gas = cp.vl[0x17C]['PEDAL_GAS'] self.hud_lead = cp.vl[0x30C]['HUD_LEAD'] - self.counter_pcm = cp.vl[0x324]['COUNTER'] + + +# carstate standalone tester +if __name__ == '__main__': + import zmq + import time + from selfdrive.services import service_list + context = zmq.Context() + logcan = messaging.sub_sock(context, service_list['can'].port) + + class CarParams(object): + def __init__(self): + self.carFingerprint = "HONDA CIVIC 2016 TOURING" + self.enableGas = 0 + self.enableCruise = 0 + CP = CarParams() + CS = CarState(CP, logcan) + + while 1: + CS.update() + time.sleep(0.01) + diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index c020cc5d4c77ff..730f5ea032ec47 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -1,19 +1,65 @@ #!/usr/bin/env python import os import time -import common.numpy_fast as np +import numpy as np +from common.numpy_fast import clip +from common.realtime import sec_since_boot from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET, get_events from .carstate import CarState from .carcontroller import CarController, AH from selfdrive.boardd.boardd import can_capnp_to_can_list - from cereal import car from selfdrive.services import service_list import selfdrive.messaging as messaging -NEW_CAN = os.getenv("OLD_CAN") is None + +def get_compute_gb(): + # generate a function that takes in [desired_accel, current_speed] -> [-1.0, 1.0] + # where -1.0 is max brake and 1.0 is max gas + # see debug/dump_accel_from_fiber.py to see how those parameters were generated + w0 = np.array([[ 1.22056961, -0.39625418, 0.67952657], + [ 1.03691769, 0.78210306, -0.41343188]]) + b0 = np.array([ 0.01536703, -0.14335321, -0.26932889]) + w2 = np.array([[-0.59124422, 0.42899439, 0.38660881], + [ 0.79973811, 0.13178682, 0.08550351], + [-0.15651935, -0.44360259, 0.76910877]]) + b2 = np.array([ 0.15624429, 0.02294923, -0.0341086 ]) + w4 = np.array([[-0.31521443], + [-0.38626176], + [ 0.52667892]]) + b4 = np.array([-0.02922216]) + + def compute_output(dat, w0, b0, w2, b2, w4, b4): + m0 = np.dot(dat, w0) + b0 + m0 = leakyrelu(m0, 0.1) + m2 = np.dot(m0, w2) + b2 + m2 = leakyrelu(m2, 0.1) + m4 = np.dot(m2, w4) + b4 + return m4 + + def leakyrelu(x, alpha): + return np.maximum(x, alpha * x) + + def _compute_gb(accel, speed): + #linearly extrap below v1 using v1 and v2 data + v1 = 5. + v2 = 10. + dat = np.array([accel, speed]) + if speed > 5.: + m4 = compute_output(dat, w0, b0, w2, b2, w4, b4) + else: + dat[1] = v1 + m4v1 = compute_output(dat, w0, b0, w2, b2, w4, b4) + dat[1] = v2 + m4v2 = compute_output(dat, w0, b0, w2, b2, w4, b4) + m4 = (speed - v1) * (m4v2 - m4v1) / (v2 - v1) + m4v1 + return float(m4) + + return _compute_gb + # Car button codes class CruiseButtons: @@ -22,6 +68,7 @@ class CruiseButtons: CANCEL = 2 MAIN = 1 + #car chimes: enumeration from dbc file. Chimes are for alerts and warnings class CM: MUTE = 0 @@ -30,6 +77,7 @@ class CM: REPEATED = 1 CONTINUOUS = 2 + #car beepss: enumeration from dbc file. Beeps are for activ and deactiv class BP: MUTE = 0 @@ -37,12 +85,17 @@ class BP: TRIPLE = 2 REPEATED = 1 + class CarInterface(object): def __init__(self, CP, logcan, sendcan=None): self.logcan = logcan self.CP = CP self.frame = 0 + self.last_enable_pressed = 0 + self.last_enable_sent = 0 + self.gas_pressed_prev = False + self.brake_pressed_prev = False self.can_invalid_count = 0 # *** init the major players *** @@ -54,7 +107,8 @@ def __init__(self, CP, logcan, sendcan=None): self.CC = CarController() if self.CS.accord: - self.accord_msg = [] + # self.accord_msg = [] + raise NotImplementedError @staticmethod def get_params(candidate, fingerprint): @@ -68,6 +122,8 @@ def get_params(candidate, fingerprint): ret.radarName = "nidec" ret.carFingerprint = candidate + ret.safetyModel = car.CarParams.SafetyModels.honda + ret.enableSteer = True ret.enableBrake = True @@ -75,7 +131,7 @@ def get_params(candidate, fingerprint): ret.enableGas = 0x201 in fingerprint ret.enableCruise = not ret.enableGas - # FIXME: hardcoding honda civic 2016 touring wight so it can be used to + # FIXME: hardcoding honda civic 2016 touring params so they can be used to # scale unknown params for other cars m_civic = 2923./2.205 + std_cargo l_civic = 2.70 @@ -86,27 +142,32 @@ def get_params(candidate, fingerprint): cR_civic = 90000 if candidate == "HONDA CIVIC 2016 TOURING": + stop_and_go = True ret.m = m_civic ret.l = l_civic ret.aF = aF_civic ret.sR = 13.0 - ret.steerKp, ret.steerKi = 0.8, 0.24 + # Civic at comma has modified steering FW, so different tuning for the Neo in that car + is_fw_modified = os.getenv("DONGLE_ID") in ['b0f5a01cf604185c'] + ret.steerKp, ret.steerKi = [0.4, 0.12] if is_fw_modified else [0.8, 0.24] elif candidate == "ACURA ILX 2016 ACURAWATCH PLUS": + stop_and_go = False ret.m = 3095./2.205 + std_cargo ret.l = 2.67 ret.aF = ret.l * 0.37 ret.sR = 15.3 # Acura at comma has modified steering FW, so different tuning for the Neo in that car - # FIXME: using dongleId isn't great, better to identify the car than the Neo - is_fw_modified = os.getenv("DONGLE_ID") == 'cb38263377b873ee' + is_fw_modified = os.getenv("DONGLE_ID") in ['cb38263377b873ee'] ret.steerKp, ret.steerKi = [0.4, 0.12] if is_fw_modified else [0.8, 0.24] elif candidate == "HONDA ACCORD 2016 TOURING": + stop_and_go = False ret.m = 3580./2.205 + std_cargo ret.l = 2.74 ret.aF = ret.l * 0.38 ret.sR = 15.3 ret.steerKp, ret.steerKi = 0.8, 0.24 elif candidate == "HONDA CR-V 2016 TOURING": + stop_and_go = False ret.m = 3572./2.205 + std_cargo ret.l = 2.62 ret.aF = ret.l * 0.41 @@ -114,48 +175,54 @@ def get_params(candidate, fingerprint): ret.steerKp, ret.steerKi = 0.8, 0.24 else: raise ValueError("unsupported car %s" % candidate) - + + # min speed to enable ACC. if car can do stop and go, then set enabling speed + # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not + # conflict with PCM acc + ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGas) else 25.5 * CV.MPH_TO_MS + ret.aR = ret.l - ret.aF # TODO: get actual value, for now starting with reasonable value for # civic and scaling by mass and wheelbase ret.j = j_civic * ret.m * ret.l**2 / (m_civic * l_civic**2) # TODO: start from empirically derived lateral slip stiffness for the civic and scale by - # mass and CG position... all cars will have approximately similar dyn behaviors + # mass and CG position, so all cars will have approximately similar dyn behaviors ret.cF = cF_civic * ret.m / m_civic * (ret.aR / ret.l) / (aR_civic / l_civic) ret.cR = cR_civic * ret.m / m_civic * (ret.aF / ret.l) / (aF_civic / l_civic) # no rear steering, at least on the listed cars above ret.chi = 0. + # no max steer limit VS speed + ret.steerMaxBP = [0.] # m/s + ret.steerMaxV = [1.] # max steer allowed + ret.gasMaxBP = [0.] # m/s + ret.gasMaxV = [0.6] if ret.enableGas else [0.] # max gas allowed + ret.brakeMaxBP = [5., 20.] # m/s + ret.brakeMaxV = [1., 0.8] # max brake allowed + return ret + compute_gb = staticmethod(get_compute_gb()) + # returns a car.CarState - def update(self): + def update(self, c): # ******************* do can recv ******************* can_pub_main = [] canMonoTimes = [] - if NEW_CAN: - self.CS.update(can_pub_main) - else: - for a in messaging.drain_sock(self.logcan): - canMonoTimes.append(a.logMonoTime) - can_pub_main.extend(can_capnp_to_can_list(a.can, [0,0x80])) - if self.CS.accord: - self.accord_msg.extend(can_capnp_to_can_list(a.can, [9])) - self.accord_msg = self.accord_msg[-1:] - self.CS.update(can_pub_main) + self.CS.update(can_pub_main) # create message ret = car.CarState.new_message() # speeds ret.vEgo = self.CS.v_ego - ret.wheelSpeeds.fl = self.CS.cp.vl[0x1D0]['WHEEL_SPEED_FL'] - ret.wheelSpeeds.fr = self.CS.cp.vl[0x1D0]['WHEEL_SPEED_FR'] - ret.wheelSpeeds.rl = self.CS.cp.vl[0x1D0]['WHEEL_SPEED_RL'] - ret.wheelSpeeds.rr = self.CS.cp.vl[0x1D0]['WHEEL_SPEED_RR'] + ret.wheelSpeeds.fl = self.CS.v_wheel_fl + ret.wheelSpeeds.fr = self.CS.v_wheel_fr + ret.wheelSpeeds.rl = self.CS.v_wheel_rl + ret.wheelSpeeds.rr = self.CS.v_wheel_rr # gas pedal ret.gas = self.CS.car_gas / 256.0 @@ -172,28 +239,17 @@ def update(self): # TODO: units ret.steeringAngle = self.CS.angle_steers - if self.CS.accord: - # TODO: move this into the CAN parser - ret.steeringTorque = 0 - if len(self.accord_msg) > 0: - aa = map(lambda x: ord(x)&0x7f, self.accord_msg[0][2]) - if len(aa) != 5 or (-(aa[0]+aa[1]+aa[2]+aa[3]))&0x7f != aa[4]: - print "ACCORD MSG BAD LEN OR CHECKSUM!" - # TODO: throw an error here? - else: - st = ((aa[0]&0xF) << 5) + (aa[1]&0x1F) - if st >= 256: - st = -(512-st) - ret.steeringTorque = st - ret.steeringPressed = abs(ret.steeringTorque) > 20 - else: - ret.steeringTorque = self.CS.cp.vl[0x18F]['STEER_TORQUE_SENSOR'] - ret.steeringPressed = self.CS.steer_override + # gear shifter lever + ret.gearShifter = self.CS.gear_shifter + + ret.steeringTorque = self.CS.cp.vl[0x18F]['STEER_TORQUE_SENSOR'] + ret.steeringPressed = self.CS.steer_override # cruise state ret.cruiseState.enabled = self.CS.pcm_acc_status != 0 ret.cruiseState.speed = self.CS.v_cruise_pcm * CV.KPH_TO_MS ret.cruiseState.available = bool(self.CS.main_on) + ret.cruiseState.speedOffset = self.CS.cruise_speed_offset # TODO: button presses buttonEvents = [] @@ -244,38 +300,94 @@ def update(self): buttonEvents.append(be) ret.buttonEvents = buttonEvents - # errors + # events # TODO: I don't like the way capnp does enums # These strings aren't checked at compile time - errors = [] + events = [] if not self.CS.can_valid: self.can_invalid_count += 1 if self.can_invalid_count >= 5: - errors.append('commIssue') + events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) else: self.can_invalid_count = 0 if self.CS.steer_error: - errors.append('steerUnavailable') + events.append(create_event('steerUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) elif self.CS.steer_not_allowed: - errors.append('steerTempUnavailable') + events.append(create_event('steerTempUnavailable', [ET.NO_ENTRY, ET.WARNING])) if self.CS.brake_error: - errors.append('brakeUnavailable') - if not self.CS.gear_shifter_valid: - errors.append('wrongGear') + events.append(create_event('brakeUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if not ret.gearShifter == 'drive': + events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not self.CS.door_all_closed: - errors.append('doorOpen') + events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not self.CS.seatbelt: - errors.append('seatbeltNotLatched') + events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if self.CS.esp_disabled: - errors.append('espDisabled') + events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not self.CS.main_on: - errors.append('wrongCarMode') - if self.CS.gear_shifter == 2: - errors.append('reverseGear') - - ret.errors = errors + events.append(create_event('wrongCarMode', [ET.NO_ENTRY, ET.USER_DISABLE])) + if ret.gearShifter == 'reverse': + events.append(create_event('reverseGear', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if self.CS.brake_hold: + events.append(create_event('brakeHold', [ET.NO_ENTRY, ET.USER_DISABLE])) + if self.CS.park_brake: + events.append(create_event('parkBrake', [ET.NO_ENTRY, ET.USER_DISABLE])) + + if self.CP.enableCruise and ret.vEgo < self.CP.minEnableSpeed: + events.append(create_event('speedTooLow', [ET.NO_ENTRY])) + + # disable on pedals rising edge or when brake is pressed and speed isn't zero + if (ret.gasPressed and not self.gas_pressed_prev) or \ + (ret.brakePressed and (not self.brake_pressed_prev or ret.vEgo > 0.001)): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + + #if (ret.brakePressed and ret.vEgo < 0.001) or ret.gasPressed: + if ret.gasPressed: + events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) + + # it can happen that car cruise disables while comma system is enabled: need to + # keep braking if needed or if the speed is very low + # TODO: for the Acura, cancellation below 25mph is normal. Issue a non loud alert + if self.CP.enableCruise and not ret.cruiseState.enabled and \ + (c.actuators.brake <= 0. or ret.vEgo < 0.3): + events.append(create_event("cruiseDisabled", [ET.IMMEDIATE_DISABLE])) + + cur_time = sec_since_boot() + enable_pressed = False + # handle button presses + for b in ret.buttonEvents: + + # do enable on both accel and decel buttons + if b.type in ["accelCruise", "decelCruise"] and not b.pressed: + print "enabled pressed at", cur_time + self.last_enable_pressed = cur_time + enable_pressed = True + + # do disable on button down + if b.type == "cancel" and b.pressed: + events.append(create_event('buttonCancel', [ET.USER_DISABLE])) + + if self.CP.enableCruise: + # KEEP THIS EVENT LAST! send enable event if button is pressed and there are + # NO_ENTRY events, so controlsd will display alerts. Also not send enable events + # too close in time, so a no_entry will not be followed by another one. + # TODO: button press should be the only thing that triggers enble + if ((cur_time - self.last_enable_pressed) < 0.2 and + (cur_time - self.last_enable_sent) > 0.2 and + ret.cruiseState.enabled) or \ + (enable_pressed and get_events(events, [ET.NO_ENTRY])): + events.append(create_event('buttonEnable', [ET.ENABLE])) + self.last_enable_sent = cur_time + elif enable_pressed: + events.append(create_event('buttonEnable', [ET.ENABLE])) + + ret.events = events ret.canMonoTimes = canMonoTimes + # update previous brake/gas pressed + self.gas_pressed_prev = ret.gasPressed + self.brake_pressed_prev = ret.brakePressed + # cast to reader so it can't be modified #print ret return ret.as_reader() @@ -309,10 +421,10 @@ def apply(self, c): "chimeRepeated": (BP.MUTE, CM.REPEATED), "chimeContinuous": (BP.MUTE, CM.CONTINUOUS)}[str(c.hudControl.audibleAlert)] - pcm_accel = int(np.clip(c.cruiseControl.accelOverride,0,1)*0xc6) + pcm_accel = int(clip(c.cruiseControl.accelOverride,0,1)*0xc6) self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, \ - c.gas, c.brake, c.steeringTorque, \ + c.actuators, \ c.cruiseControl.speedOverride, \ c.cruiseControl.override, \ c.cruiseControl.cancel, \ @@ -324,4 +436,3 @@ def apply(self, c): snd_chime = snd_chime) self.frame += 1 - return not (c.enabled and not self.CC.controls_allowed) diff --git a/selfdrive/car/honda/can_parser.py b/selfdrive/car/honda/old_can_parser.py similarity index 97% rename from selfdrive/car/honda/can_parser.py rename to selfdrive/car/honda/old_can_parser.py index d12a33fe1e4f09..6f7f3dce3d6131 100644 --- a/selfdrive/car/honda/can_parser.py +++ b/selfdrive/car/honda/old_can_parser.py @@ -36,15 +36,16 @@ def __init__(self, dbc_f, signals, checks=[]): for _, addr, _ in signals: self.vl[addr] = {} - self.ts[addr] = 0 + self.ts[addr] = {} self.ct[addr] = sec_since_boot() - self.ok[addr] = False + self.ok[addr] = True self.cn[addr] = 0 self.cn_vl[addr] = 0 self.ck[addr] = False for name, addr, ival in signals: self.vl[addr][name] = ival + self.ts[addr][name] = 0 self._msgs = [s[1] for s in signals] self._sgs = [s[0] for s in signals] @@ -94,7 +95,6 @@ def update_can(self, can_recv): self.ok[msg] = False # update msg time stamps and counter value - self.ts[msg] = ts self.ct[msg] = self.sec_since_boot_cached self.cn[msg] = cn self.cn_vl[msg] = min(max(self.cn_vl[msg], 0), cn_vl_max) @@ -107,12 +107,14 @@ def update_can(self, can_recv): for ii in idxs: sg = self._sgs[ii] self.vl[msg][sg] = out[sg] + self.ts[msg][sg] = ts # for each message, check if it's too long since last time we received it self._check_dead_msgs() # assess overall can validity: if there is one relevant message invalid, then set can validity flag to False self.can_valid = True + if False in self.ok.values(): #print "CAN INVALID!" self.can_valid = False diff --git a/selfdrive/common/cereal.mk b/selfdrive/common/cereal.mk index f4603dc32d5c42..637a1040610628 100644 --- a/selfdrive/common/cereal.mk +++ b/selfdrive/common/cereal.mk @@ -1,14 +1,27 @@ UNAME_M ?= $(shell uname -m) -ifeq ($(UNAME_M),x86_64) +UNAME_S ?= $(shell uname -s) -CEREAL_CFLAGS = -I$(ONE)/external/capnp/include + +ifeq ($(UNAME_S),Darwin) + +CEREAL_CFLAGS = -I$(PHONELIBS)/capnp-c/include +CEREAL_CXXFLAGS = -I$(PHONELIBS)/capnp-cpp/mac/include + +CEREAL_LIBS = $(PHONELIBS)/capnp-cpp/mac/lib/libcapnp.a \ + $(PHONELIBS)/capnp-cpp/mac/lib/libkj.a \ + $(PHONELIBS)/capnp-c/mac/lib/libcapnp_c.a + +else ifeq ($(UNAME_M),x86_64) + +CEREAL_CFLAGS = -I$(BASEDIR)/external/capnp/include CEREAL_CXXFLAGS = $(CEREAL_CFLAGS) ifeq ($(CEREAL_LIBS),) - CEREAL_LIBS = -L$(ONE)/external/capnp/lib \ + CEREAL_LIBS = -L$(BASEDIR)/external/capnp/lib \ -l:libcapnp.a -l:libkj.a -l:libcapnp_c.a endif else + CEREAL_CFLAGS = -I$(PHONELIBS)/capnp-c/include CEREAL_CXXFLAGS = -I$(PHONELIBS)/capnp-cpp/include ifeq ($(CEREAL_LIBS),) @@ -30,4 +43,3 @@ car.capnp.o: ../../cereal/gen/cpp/car.capnp.c++ @echo "[ CXX ] $@" $(CXX) $(CXXFLAGS) $(CEREAL_CXXFLAGS) \ -c -o '$@' '$<' - diff --git a/selfdrive/common/mat.h b/selfdrive/common/mat.h index f429b0c5d37a39..1c20eae17fd034 100644 --- a/selfdrive/common/mat.h +++ b/selfdrive/common/mat.h @@ -65,4 +65,24 @@ static inline vec4 matvecmul(const mat4 a, const vec4 b) { return ret; } +// scales the input and output space of a transformation matrix +// that assumes pixel-center origin. +static inline mat3 transform_scale_buffer(const mat3 in, float s) { + // in_pt = ( transform(out_pt/s + 0.5) - 0.5) * s + + mat3 transform_out = {{ + 1.0f/s, 0.0f, 0.5f, + 0.0f, 1.0f/s, 0.5f, + 0.0f, 0.0f, 1.0f, + }}; + + mat3 transform_in = {{ + s, 0.0f, -0.5f*s, + 0.0f, s, -0.5f*s, + 0.0f, 0.0f, 1.0f, + }}; + + return matmul3(transform_in, matmul3(in, transform_out)); +} + #endif diff --git a/selfdrive/common/params.c b/selfdrive/common/params.cc similarity index 83% rename from selfdrive/common/params.c rename to selfdrive/common/params.cc index 7cefc7b06b4490..5b0d216bdd873c 100644 --- a/selfdrive/common/params.c +++ b/selfdrive/common/params.cc @@ -11,6 +11,18 @@ #include #include +namespace { + +template +T* null_coalesce(T* a, T* b) { + return a != NULL ? a : b; +} + +static const char* default_params_path = null_coalesce( + const_cast(getenv("PARAMS_PATH")), "/data/params"); + +} // namespace + int write_db_value(const char* params_path, const char* key, const char* value, size_t value_size) { int lock_fd = -1; @@ -18,6 +30,11 @@ int write_db_value(const char* params_path, const char* key, const char* value, int result; char tmp_path[1024]; char path[1024]; + ssize_t bytes_written; + + if (params_path == NULL) { + params_path = default_params_path; + } // Write value to temp. result = @@ -27,7 +44,7 @@ int write_db_value(const char* params_path, const char* key, const char* value, } tmp_fd = mkstemp(tmp_path); - const ssize_t bytes_written = write(tmp_fd, value, value_size); + bytes_written = write(tmp_fd, value, value_size); if (bytes_written != value_size) { result = -20; goto cleanup; @@ -79,6 +96,10 @@ int read_db_value(const char* params_path, const char* key, char** value, int result; char path[1024]; + if (params_path == NULL) { + params_path = default_params_path; + } + result = snprintf(path, sizeof(path), "%s/.lock", params_path); if (result < 0) { goto cleanup; @@ -99,7 +120,7 @@ int read_db_value(const char* params_path, const char* key, char** value, // Read value. // TODO(mgraczyk): If there is a lot of contention, we can release the lock // after opening the file, before reading. - *value = read_file(path, value_sz); + *value = static_cast(read_file(path, value_sz)); if (*value == NULL) { result = -22; goto cleanup; diff --git a/selfdrive/common/params.h b/selfdrive/common/params.h index 05ddb1dd791687..bd4d86dcfee97c 100644 --- a/selfdrive/common/params.h +++ b/selfdrive/common/params.h @@ -7,14 +7,12 @@ extern "C" { #endif -#define PARAMS_PATH "/data/params" - int write_db_value(const char* params_path, const char* key, const char* value, size_t value_size); // Reads a value from the params database. // Inputs: -// params_path: The path of the database, eg /sdcard/params. +// params_path: The path of the database, or NULL to use the default. // key: The key to read. // value: A pointer where a newly allocated string containing the db value will // be written. diff --git a/selfdrive/common/swaglog.h b/selfdrive/common/swaglog.h index b972f98d18fe23..33e77f618aef59 100644 --- a/selfdrive/common/swaglog.h +++ b/selfdrive/common/swaglog.h @@ -1,6 +1,8 @@ #ifndef SWAGLOG_H #define SWAGLOG_H +#include "common/timing.h" + #define CLOUDLOG_DEBUG 10 #define CLOUDLOG_INFO 20 #define CLOUDLOG_WARNING 30 @@ -24,9 +26,43 @@ void cloudlog_bind(const char* k, const char* v); __func__, \ fmt, ## __VA_ARGS__) +#define cloudlog_rl(burst, millis, lvl, fmt, ...) \ +{ \ + static uint64_t __begin = 0; \ + static int __printed = 0; \ + static int __missed = 0; \ + \ + int __burst = (burst); \ + int __millis = (millis); \ + uint64_t __ts = nanos_since_boot(); \ + \ + if (!__begin) __begin = __ts; \ + \ + if (__begin + __millis*1000000ULL < __ts) { \ + if (__missed) { \ + cloudlog(CLOUDLOG_WARNING, "cloudlog: %d messages supressed", __missed); \ + } \ + __begin = 0; \ + __printed = 0; \ + __missed = 0; \ + } \ + \ + if (__printed < __burst) { \ + cloudlog(lvl, fmt, ## __VA_ARGS__); \ + __printed++; \ + } else { \ + __missed++; \ + } \ +} + #define LOGD(fmt, ...) cloudlog(CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) #define LOG(fmt, ...) cloudlog(CLOUDLOG_INFO, fmt, ## __VA_ARGS__) #define LOGW(fmt, ...) cloudlog(CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) #define LOGE(fmt, ...) cloudlog(CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) +#define LOGD_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) +#define LOG_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_INFO, fmt, ## __VA_ARGS__) +#define LOGW_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) +#define LOGE_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) + #endif diff --git a/selfdrive/common/timing.h b/selfdrive/common/timing.h index 02e934dcb5f253..1a30ad6e1e4d7b 100644 --- a/selfdrive/common/timing.h +++ b/selfdrive/common/timing.h @@ -5,7 +5,7 @@ #include #ifdef __APPLE__ -#define CLOCK_BOOTTIME CLOCK_REALTIME +#define CLOCK_BOOTTIME CLOCK_MONOTONIC #endif static inline uint64_t nanos_since_boot() { @@ -38,4 +38,17 @@ static inline double seconds_since_epoch() { return (double)t.tv_sec + t.tv_nsec * 1e-9; } +// you probably should use nanos_since_boot instead +static inline uint64_t nanos_monotonic() { + struct timespec t; + clock_gettime(CLOCK_MONOTONIC, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +static inline uint64_t nanos_monotonic_raw() { + struct timespec t; + clock_gettime(CLOCK_MONOTONIC_RAW, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + #endif diff --git a/selfdrive/common/util.c b/selfdrive/common/util.c index e5ab4d0a6c86a1..172345869ec8a4 100644 --- a/selfdrive/common/util.c +++ b/selfdrive/common/util.c @@ -3,6 +3,10 @@ #include #include +#ifdef __linux__ +#include +#endif + void* read_file(const char* path, size_t* out_len) { FILE* f = fopen(path, "r"); if (!f) { @@ -28,3 +32,10 @@ void* read_file(const char* path, size_t* out_len) { return buf; } + +void set_thread_name(const char* name) { +#ifdef __linux__ + // pthread_setname_np is dumb (fails instead of truncates) + prctl(PR_SET_NAME, (unsigned long)name, 0, 0, 0); +#endif +} diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h index 9b5da8e726863b..ce18068bbe7c7d 100644 --- a/selfdrive/common/util.h +++ b/selfdrive/common/util.h @@ -1,6 +1,9 @@ #ifndef COMMON_UTIL_H #define COMMON_UTIL_H + +#ifndef __cplusplus + #define min(a,b) \ ({ __typeof__ (a) _a = (a); \ __typeof__ (b) _b = (b); \ @@ -11,6 +14,8 @@ __typeof__ (b) _b = (b); \ _a > _b ? _a : _b; }) +#endif + #define clamp(a,b,c) \ ({ __typeof__ (a) _a = (a); \ __typeof__ (b) _b = (b); \ @@ -19,11 +24,20 @@ #define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0])) +#ifdef __cplusplus +extern "C" { +#endif + // Reads a file into a newly allocated buffer. // // Returns NULL on failure, otherwise the NULL-terminated file contents. // The result must be freed by the caller. void* read_file(const char* path, size_t* out_len); +void set_thread_name(const char* name); + +#ifdef __cplusplus +} +#endif #endif diff --git a/selfdrive/common/utilpp.h b/selfdrive/common/utilpp.h index 25abac66825883..bc1b2fd267d966 100644 --- a/selfdrive/common/utilpp.h +++ b/selfdrive/common/utilpp.h @@ -9,6 +9,10 @@ #include #include +#ifdef __x86_64 +#include +#endif + namespace util { inline bool starts_with(std::string s, std::string prefix) { diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index 4c2a881ae99340..de335592cdb0e1 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define OPENPILOT_VERSION "0.3.6.1" +#define OPENPILOT_VERSION "0.3.7" diff --git a/selfdrive/common/visionipc.c b/selfdrive/common/visionipc.c index c371754f88fcc6..4299f512f9a04e 100644 --- a/selfdrive/common/visionipc.c +++ b/selfdrive/common/visionipc.c @@ -1,6 +1,7 @@ #include #include #include +#include #include #include #include @@ -126,7 +127,7 @@ int vipc_send(int fd, const VisionPacket *p2) { return sendrecv_with_fds(true, fd, (void*)&p, sizeof(p), (int*)p2->fds, p2->num_fds, NULL); } -void visionbufs_load(VisionBuf *bufs, const VisionStreamBufs *stream_bufs, +void vipc_bufs_load(VIPCBuf *bufs, const VisionStreamBufs *stream_bufs, int num_fds, const int* fds) { for (int i=0; ibufs_info = rp.d.stream_bufs; s->num_bufs = rp.num_fds; - s->bufs = calloc(s->num_bufs, sizeof(VisionBuf)); + s->bufs = calloc(s->num_bufs, sizeof(VIPCBuf)); assert(s->bufs); - visionbufs_load(s->bufs, &rp.d.stream_bufs, s->num_bufs, rp.fds); + vipc_bufs_load(s->bufs, &rp.d.stream_bufs, s->num_bufs, rp.fds); if (out_bufs_info) { *out_bufs_info = s->bufs_info; @@ -192,7 +193,7 @@ int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, Visi return 0; } -VisionBuf* visionstream_get(VisionStream *s, VisionBufExtra *out_extra) { +VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) { int err; VisionPacket rp; diff --git a/selfdrive/common/visionipc.h b/selfdrive/common/visionipc.h index dab392ec54c619..24b882340fea87 100644 --- a/selfdrive/common/visionipc.h +++ b/selfdrive/common/visionipc.h @@ -47,9 +47,9 @@ typedef struct VisionStreamBufs { } buf_info; } VisionStreamBufs; -typedef struct VisionBufExtra { +typedef struct VIPCBufExtra { uint32_t frame_id; // only for yuv -} VisionBufExtra; +} VIPCBufExtra; typedef union VisionPacketData { struct { @@ -60,7 +60,7 @@ typedef union VisionPacketData { struct { VisionStreamType type; int idx; - VisionBufExtra extra; + VIPCBufExtra extra; } stream_acq; struct { VisionStreamType type; @@ -79,12 +79,12 @@ int vipc_connect(void); int vipc_recv(int fd, VisionPacket *out_p); int vipc_send(int fd, const VisionPacket *p); -typedef struct VisionBuf { +typedef struct VIPCBuf { int fd; size_t len; void* addr; -} VisionBuf; -void visionbufs_load(VisionBuf *bufs, const VisionStreamBufs *stream_bufs, +} VIPCBuf; +void vipc_bufs_load(VIPCBuf *bufs, const VisionStreamBufs *stream_bufs, int num_fds, const int* fds); @@ -94,11 +94,11 @@ typedef struct VisionStream { int last_idx; int num_bufs; VisionStreamBufs bufs_info; - VisionBuf *bufs; + VIPCBuf *bufs; } VisionStream; int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info); -VisionBuf* visionstream_get(VisionStream *s, VisionBufExtra *out_extra); +VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra); void visionstream_destroy(VisionStream *s); #ifdef __cplusplus diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index c93ad1433949d1..867062c54b4acf 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -2,24 +2,24 @@ import os import json from copy import copy - import zmq - from cereal import car, log from common.numpy_fast import clip from common.fingerprints import fingerprint from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper from common.profiler import Profiler from common.params import Params - import selfdrive.messaging as messaging from selfdrive.swaglog import cloudlog from selfdrive.config import Conversions as CV from selfdrive.services import service_list from selfdrive.car import get_car from selfdrive.controls.lib.planner import Planner -from selfdrive.controls.lib.drive_helpers import learn_angle_offset -from selfdrive.controls.lib.longcontrol import LongControl +from selfdrive.controls.lib.drive_helpers import learn_angle_offset, \ + get_events, \ + create_event, \ + EventTypes as ET +from selfdrive.controls.lib.longcontrol import LongControl, STARTING_TARGET_SPEED from selfdrive.controls.lib.latcontrol import LatControl from selfdrive.controls.lib.alertmanager import AlertManager from selfdrive.controls.lib.vehicle_model import VehicleModel @@ -34,427 +34,472 @@ AWARENESS_PRE_TIME = 20. # a first alert is issued 20s before start decelerating the car AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distracted -# class Cal + class Calibration: UNCALIBRATED = 0 CALIBRATED = 1 INVALID = 2 -# to be used -class State(): + +class State: DISABLED = 0 ENABLED = 1 - SOFT_DISABLE = 2 - -class Controls(object): - def __init__(self, gctx, rate=100): - self.rate = rate - - # *** log *** - context = zmq.Context() - - # pub - self.live100 = messaging.pub_sock(context, service_list['live100'].port) - self.carstate = messaging.pub_sock(context, service_list['carState'].port) - self.carcontrol = messaging.pub_sock(context, service_list['carControl'].port) - sendcan = messaging.pub_sock(context, service_list['sendcan'].port) - - # sub - self.thermal = messaging.sub_sock(context, service_list['thermal'].port) - self.health = messaging.sub_sock(context, service_list['health'].port) - logcan = messaging.sub_sock(context, service_list['can'].port) - self.cal = messaging.sub_sock(context, service_list['liveCalibration'].port) - - self.CC = car.CarControl.new_message() - self.CI, self.CP = get_car(logcan, sendcan) - self.PL = Planner(self.CP) - self.AM = AlertManager() - self.LoC = LongControl() - self.LaC = LatControl() - self.VM = VehicleModel(self.CP) - - # write CarParams - params = Params() - params.put("CarParams", self.CP.to_bytes()) - - # fake plan - self.plan_ts = 0 - self.plan = log.Plan.new_message() - self.plan.lateralValid = False - self.plan.longitudinalValid = False - - # controls enabled state - self.enabled = False - self.last_enable_request = 0 - - # learned angle offset - self.angle_offset = 0 - calibration_params = params.get("CalibrationParams") - if calibration_params: - try: - calibration_params = json.loads(calibration_params) - self.angle_offset = calibration_params["angle_offset"] - except (ValueError, KeyError): - pass - - # rear view camera state - self.rear_view_toggle = False - self.rear_view_allowed = (params.get("IsRearViewMirror") == "1") - - self.v_cruise_kph = 255 - - # 0.0 - 1.0 - self.awareness_status = 1.0 - - self.soft_disable_timer = None - - self.overtemp = False - self.free_space = 1.0 - self.cal_status = Calibration.UNCALIBRATED - self.cal_perc = 0 - - self.rk = Ratekeeper(self.rate, print_delay_threshold=2./1000) - - def data_sample(self): - self.prof = Profiler() - self.cur_time = sec_since_boot() - # first read can and compute car states - self.CS = self.CI.update() - - self.prof.checkpoint("CarInterface") - - # *** thermal checking logic *** - # thermal data, checked every second - td = messaging.recv_sock(self.thermal) - if td is not None: - # Check temperature. - self.overtemp = any( - t > 950 - for t in (td.thermal.cpu0, td.thermal.cpu1, td.thermal.cpu2, - td.thermal.cpu3, td.thermal.mem, td.thermal.gpu)) - # under 15% of space free - self.free_space = td.thermal.freeSpace - - # read calibration status - cal = messaging.recv_sock(self.cal) - if cal is not None: - self.cal_status = cal.liveCalibration.calStatus - self.cal_perc = cal.liveCalibration.calPerc - - - def state_transition(self): - pass # for now - - def state_control(self): - - # did it request to enable? - enable_request, enable_condition = False, False - - # reset awareness status on steering - if self.CS.steeringPressed or not self.enabled: - self.awareness_status = 1.0 - elif self.enabled: - # gives the user 6 minutes - self.awareness_status -= 1.0/(self.rate * AWARENESS_TIME) - if self.awareness_status <= 0.: - self.AM.add("driverDistracted", self.enabled) - elif self.awareness_status <= AWARENESS_PRE_TIME / AWARENESS_TIME and \ - self.awareness_status >= (AWARENESS_PRE_TIME - 0.1) / AWARENESS_TIME: - self.AM.add("preDriverDistracted", self.enabled) - - # handle button presses - for b in self.CS.buttonEvents: - print b - - # button presses for rear view - if b.type == "leftBlinker" or b.type == "rightBlinker": - if b.pressed and self.rear_view_allowed: - self.rear_view_toggle = True - else: - self.rear_view_toggle = False - - if b.type == "altButton1" and b.pressed: - self.rear_view_toggle = not self.rear_view_toggle - - if not self.CP.enableCruise and self.enabled and not b.pressed: - if b.type == "accelCruise": - self.v_cruise_kph -= (self.v_cruise_kph % V_CRUISE_DELTA) - V_CRUISE_DELTA - elif b.type == "decelCruise": - self.v_cruise_kph -= (self.v_cruise_kph % V_CRUISE_DELTA) + V_CRUISE_DELTA - self.v_cruise_kph = clip(self.v_cruise_kph, V_CRUISE_MIN, V_CRUISE_MAX) - - if not self.enabled and b.type in ["accelCruise", "decelCruise"] and not b.pressed: - enable_request = True - - # do disable on button down - if b.type == "cancel" and b.pressed: - self.AM.add("disable", self.enabled) - - self.prof.checkpoint("Buttons") - - # *** health checking logic *** - hh = messaging.recv_sock(self.health) - if hh is not None: - # if the board isn't allowing controls but somehow we are enabled! - # TODO: this should be in state transition with a function follower logic - if not hh.health.controlsAllowed and self.enabled: - self.AM.add("controlsMismatch", self.enabled) - - # disable if the pedals are pressed while engaged, this is a user disable - if self.enabled: - if self.CS.gasPressed or self.CS.brakePressed or not self.CS.cruiseState.available: - self.AM.add("disable", self.enabled) - - # it can happen that car cruise disables while comma system is enabled: need to - # keep braking if needed or if the speed is very low - # TODO: for the Acura, cancellation below 25mph is normal. Issue a non loud alert - if self.CP.enableCruise and not self.CS.cruiseState.enabled and \ - (self.CC.brake <= 0. or self.CS.vEgo < 0.3): - self.AM.add("cruiseDisabled", self.enabled) - - if enable_request: - # check for pressed pedals - if self.CS.gasPressed or self.CS.brakePressed: - self.AM.add("pedalPressed", self.enabled) - enable_request = False - else: - print "enabled pressed at", self.cur_time - self.last_enable_request = self.cur_time + PRE_ENABLED = 2 + SOFT_DISABLING = 3 - # don't engage with less than 15% free - if self.free_space < 0.15: - self.AM.add("outOfSpace", self.enabled) - enable_request = False - if self.CP.enableCruise: - enable_condition = ((self.cur_time - self.last_enable_request) < 0.2) and self.CS.cruiseState.enabled - else: - enable_condition = enable_request +# True when actuators are controlled +def isActive(state): + return state in [State.ENABLED, State.SOFT_DISABLING] + + +# True if system is engaged +def isEnabled(state): + return (isActive(state) or state == State.PRE_ENABLED) - if self.CP.enableCruise and self.CS.cruiseState.enabled: - self.v_cruise_kph = self.CS.cruiseState.speed * CV.MS_TO_KPH - self.prof.checkpoint("AdaptiveCruise") +def data_sample(CI, CC, thermal, health, cal, cal_status, cal_perc): - # *** what's the plan *** - plan_packet = self.PL.update(self.CS, self.LoC) - self.plan = plan_packet.plan - self.plan_ts = plan_packet.logMonoTime + # *** read can and compute car states *** + CS = CI.update(CC) + events = list(CS.events) - # if user is not responsive to awareness alerts, then start a smooth deceleration - if self.awareness_status < -0.: - self.plan.aTargetMax = min(self.plan.aTargetMax, AWARENESS_DECEL) - self.plan.aTargetMin = min(self.plan.aTargetMin, self.plan.aTargetMax) + # *** thermal checking logic *** + # thermal data, checked every second + td = messaging.recv_sock(thermal) + if td is not None: + # Check temperature + overtemp = any( + t > 950 + for t in (td.thermal.cpu0, td.thermal.cpu1, td.thermal.cpu2, + td.thermal.cpu3, td.thermal.mem, td.thermal.gpu)) + if overtemp: + events.append(create_event('overheat', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - if enable_request or enable_condition or self.enabled: - # add all alerts from car - for alert in self.CS.errors: - self.AM.add(alert, self.enabled) + # under 15% of space free + if td.thermal.freeSpace < 0.15: + events.append(create_event('outOfSpace', [ET.NO_ENTRY])) - if not self.plan.longitudinalValid: - self.AM.add("radarCommIssue", self.enabled) + # *** read calibration status *** + cal = messaging.recv_sock(cal) + if cal is not None: + cal_status = cal.liveCalibration.calStatus + cal_perc = cal.liveCalibration.calPerc - if self.cal_status != Calibration.CALIBRATED: - if self.cal_status == Calibration.UNCALIBRATED: - self.AM.add("calibrationInProgress", self.enabled, str(self.cal_perc) + '%') + if cal_status != Calibration.CALIBRATED: + if cal_status == Calibration.UNCALIBRATED: + events.append(create_event('calibrationInProgress', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + else: + events.append(create_event('calibrationInvalid', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + + # *** health checking logic *** + hh = messaging.recv_sock(health) + if hh is not None: + controls_allowed = hh.health.controlsAllowed + if not controls_allowed: + events.append(create_event('controlsMismatch', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + + return CS, events, cal_status, cal_perc + + +def calc_plan(CS, events, PL, LoC): + # plan runs always, independently of the state + plan_packet = PL.update(CS, LoC) + plan = plan_packet.plan + plan_ts = plan_packet.logMonoTime + + # add events from planner + events += list(plan.events) + + # disable if lead isn't close when system is active and brake is pressed to avoid + # unexpected vehicle accelerations + if CS.brakePressed and plan.vTarget >= STARTING_TARGET_SPEED: + events.append(create_event('noTarget', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + + return plan, plan_ts + + +def state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, cal_perc, AM): + # compute conditional state transitions and execute actions on state transitions + enabled = isEnabled(state) + + # handle button presses. TODO: this should be in state_control, but a decelCruise press + # would have the effect of both enabling and changing speed is checked after the state transition + for b in CS.buttonEvents: + if not CP.enableCruise and enabled and not b.pressed: + if b.type == "accelCruise": + v_cruise_kph -= (v_cruise_kph % V_CRUISE_DELTA) - V_CRUISE_DELTA + elif b.type == "decelCruise": + v_cruise_kph -= (v_cruise_kph % V_CRUISE_DELTA) + V_CRUISE_DELTA + v_cruise_kph = clip(v_cruise_kph, V_CRUISE_MIN, V_CRUISE_MAX) + + # decrease the soft disable timer at every step, as it's reset on + # entrance in SOFT_DISABLING state + soft_disable_timer = max(0, soft_disable_timer - 1) + + # ***** handle state transitions ***** + + # DISABLED + if state == State.DISABLED: + if get_events(events, [ET.ENABLE]): + if get_events(events, [ET.NO_ENTRY, ET.SOFT_DISABLE, ET.IMMEDIATE_DISABLE]): + for e in get_events(events, [ET.SOFT_DISABLE, ET.IMMEDIATE_DISABLE]): + AM.add(e, enabled) + for e in get_events(events, [ET.NO_ENTRY]): + txt = str(cal_perc) + '%' if e == 'calibrationInProgress' else '' + AM.add(str(e) + "NoEntry", enabled, txt) + else: + if get_events(events, [ET.PRE_ENABLE]): + state = State.PRE_ENABLED else: - self.AM.add("calibrationInvalid", self.enabled) - - if not self.plan.lateralValid: - # If the model is not broadcasting, assume that it is because - # the user has uploaded insufficient data for calibration. - # Other cases that would trigger this are rare and unactionable by the user. - self.AM.add("dataNeeded", self.enabled) - - if self.overtemp: - self.AM.add("overheat", self.enabled) - - - # *** angle offset learning *** - if self.rk.frame % 5 == 2 and self.plan.lateralValid: - # *** run this at 20hz again *** - self.angle_offset = learn_angle_offset(self.enabled, self.CS.vEgo, self.angle_offset, - self.PL.PP.c_poly, self.PL.PP.c_prob, self.LaC.y_des, - self.CS.steeringPressed) - - # *** gas/brake PID loop *** - final_gas, final_brake = self.LoC.update(self.enabled, self.CS.vEgo, self.v_cruise_kph, - self.plan.vTarget, - [self.plan.aTargetMin, self.plan.aTargetMax], - self.plan.jerkFactor, self.CP) - - # *** steering PID loop *** - final_steer, sat_flag = self.LaC.update(self.enabled, self.CS.vEgo, self.CS.steeringAngle, - self.CS.steeringPressed, self.plan.dPoly, self.angle_offset, self.VM) - - self.prof.checkpoint("PID") - - # ***** handle alerts **** - # send FCW alert if triggered by planner - if self.plan.fcw: - self.AM.add("fcw", self.enabled) - - # send a "steering required alert" if saturation count has reached the limit - if sat_flag: - self.AM.add("steerSaturated", self.enabled) - - if self.enabled and self.AM.alertShouldDisable(): - print "DISABLING IMMEDIATELY ON ALERT" - self.enabled = False - - if self.enabled and self.AM.alertShouldSoftDisable(): - if self.soft_disable_timer is None: - self.soft_disable_timer = 3 * self.rate - elif self.soft_disable_timer == 0: - print "SOFT DISABLING ON ALERT" - self.enabled = False + state = State.ENABLED + AM.add("enable", enabled) + # on activation, let's always set v_cruise from where we are, even if PCM ACC is active + v_cruise_kph = int(round(max(CS.vEgo * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN))) + + # ENABLED + elif state == State.ENABLED: + if get_events(events, [ET.USER_DISABLE]): + state = State.DISABLED + AM.add("disable", enabled) + + elif get_events(events, [ET.IMMEDIATE_DISABLE]): + state = State.DISABLED + for e in get_events(events, [ET.IMMEDIATE_DISABLE]): + AM.add(e, enabled) + + elif get_events(events, [ET.SOFT_DISABLE]): + state = State.SOFT_DISABLING + soft_disable_timer = 300 # 3s TODO: use rate + for e in get_events(events, [ET.SOFT_DISABLE]): + AM.add(e, enabled) + + # SOFT DISABLING + elif state == State.SOFT_DISABLING: + if get_events(events, [ET.USER_DISABLE]): + state = State.DISABLED + AM.add("disable", enabled) + + elif get_events(events, [ET.IMMEDIATE_DISABLE]): + state = State.DISABLED + for e in get_events(events, [ET.IMMEDIATE_DISABLE]): + AM.add(e, enabled) + + elif not get_events(events, [ET.SOFT_DISABLE]): + # no more soft disabling condition, so go back to ENABLED + state = State.ENABLED + + elif soft_disable_timer <= 0: + state = State.DISABLED + + # TODO: PRE ENABLING + elif state == State.PRE_ENABLED: + if get_events(events, [ET.USER_DISABLE]): + state = State.DISABLED + AM.add("disable", enabled) + + elif get_events(events, [ET.IMMEDIATE_DISABLE, ET.SOFT_DISABLE]): + state = State.DISABLED + for e in get_events(events, [ET.IMMEDIATE_DISABLE, ET.SOFT_DISABLE]): + AM.add(e, enabled) + + elif not get_events(events, [ET.PRE_ENABLE]): + state = State.ENABLED + + return state, soft_disable_timer, v_cruise_kph + + +def state_control(plan, CS, CP, state, events, v_cruise_kph, AM, rk, awareness_status, + PL, LaC, LoC, VM, angle_offset, rear_view_allowed, rear_view_toggle): + # Given the state, this function returns the actuators + + # reset actuators to zero + actuators = car.CarControl.Actuators.new_message() + + enabled = isEnabled(state) + active = isActive(state) + + for b in CS.buttonEvents: + # any button event resets awarenesss_status + awareness_status = 1. + + # button presses for rear view + if b.type == "leftBlinker" or b.type == "rightBlinker": + if b.pressed and rear_view_allowed: + rear_view_toggle = True else: - self.soft_disable_timer -= 1 - else: - self.soft_disable_timer = None - - if enable_condition and not self.enabled and not self.AM.alertPresent(): - print "*** enabling controls" - - # beep for enabling - self.AM.add("enable", self.enabled) - - # enable both lateral and longitudinal controls - self.enabled = True - - # on activation, let's always set v_cruise from where we are, even if PCM ACC is active - self.v_cruise_kph = int(round(max(self.CS.vEgo * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN))) - - # 6 minutes driver you're on - self.awareness_status = 1.0 - - # reset the PID loops - self.LaC.reset() - # start long control at actual speed - self.LoC.reset(v_pid = self.CS.vEgo) - - # *** push the alerts to current *** - # TODO: remove output, store them inside AM class instead - self.alert_text_1, self.alert_text_2, self.visual_alert, self.audible_alert = self.AM.process_alerts(self.cur_time) - - # ***** control the car ***** - self.CC.enabled = self.enabled - - self.CC.gas = float(final_gas) - self.CC.brake = float(final_brake) - self.CC.steeringTorque = float(final_steer) - - self.CC.cruiseControl.override = True - # always cancel if we have an interceptor - self.CC.cruiseControl.cancel = bool(not self.CP.enableCruise or - (not self.enabled and self.CS.cruiseState.enabled)) - - # brake discount removes a sharp nonlinearity - brake_discount = (1.0 - clip(final_brake*3., 0.0, 1.0)) - self.CC.cruiseControl.speedOverride = float(max(0.0, ((self.LoC.v_pid - .5) * brake_discount)) if self.CP.enableCruise else 0.0) - - #CC.cruiseControl.accelOverride = float(AC.a_pcm) - # TODO: parametrize 0.714 in interface? - # accelOverride is more or less the max throttle allowed to pcm: usually set to a constant - # unless aTargetMax is very high and then we scale with it; this helpw in quicker restart - self.CC.cruiseControl.accelOverride = float(max(0.714, self.plan.aTargetMax/A_ACC_MAX)) - - self.CC.hudControl.setSpeed = float(self.v_cruise_kph * CV.KPH_TO_MS) - self.CC.hudControl.speedVisible = self.enabled - self.CC.hudControl.lanesVisible = self.enabled - self.CC.hudControl.leadVisible = self.plan.hasLead - self.CC.hudControl.visualAlert = self.visual_alert - self.CC.hudControl.audibleAlert = self.audible_alert - - # TODO: remove it from here and put it in state_transition - # this alert will apply next controls cycle - if not self.CI.apply(self.CC): - self.AM.add("controlsFailed", self.enabled) - - def data_send(self): - - # broadcast carControl first - cc_send = messaging.new_message() - cc_send.init('carControl') - cc_send.carControl = copy(self.CC) - self.carcontrol.send(cc_send.to_bytes()) - - self.prof.checkpoint("CarControl") - - # broadcast carState - cs_send = messaging.new_message() - cs_send.init('carState') - cs_send.carState = copy(self.CS) - self.carstate.send(cs_send.to_bytes()) - - # ***** publish state to logger ***** - - # publish controls state at 100Hz - dat = messaging.new_message() - dat.init('live100') + rear_view_toggle = False - # show rear view camera on phone if in reverse gear or when button is pressed - dat.live100.rearViewCam = ('reverseGear' in self.CS.errors and self.rear_view_allowed) or self.rear_view_toggle - dat.live100.alertText1 = self.alert_text_1 - dat.live100.alertText2 = self.alert_text_2 - dat.live100.awarenessStatus = max(self.awareness_status, 0.0) if self.enabled else 0.0 + if b.type == "altButton1" and b.pressed: + rear_view_toggle = not rear_view_toggle - # what packets were used to process - dat.live100.canMonoTimes = list(self.CS.canMonoTimes) - dat.live100.planMonoTime = self.plan_ts - # if controls is enabled - dat.live100.enabled = self.enabled + # send FCW alert if triggered by planner + if plan.fcw: + AM.add("fcw", enabled) - # car state - dat.live100.vEgo = self.CS.vEgo - dat.live100.angleSteers = self.CS.steeringAngle - dat.live100.steerOverride = self.CS.steeringPressed + # ***** state specific actions ***** - # longitudinal control state - dat.live100.vPid = float(self.LoC.v_pid) - dat.live100.vCruise = float(self.v_cruise_kph) - dat.live100.upAccelCmd = float(self.LoC.Up_accel_cmd) - dat.live100.uiAccelCmd = float(self.LoC.Ui_accel_cmd) + # DISABLED + if state in [State.PRE_ENABLED, State.DISABLED]: + awareness_status = 1. + LaC.reset() + LoC.reset(v_pid=CS.vEgo) - # lateral control state - dat.live100.yDes = float(self.LaC.y_des) - dat.live100.angleSteersDes = float(self.LaC.angle_steers_des) - dat.live100.upSteer = float(self.LaC.Up_steer) - dat.live100.uiSteer = float(self.LaC.Ui_steer) + # ENABLED or SOFT_DISABLING + elif state in [State.ENABLED, State.SOFT_DISABLING]: - # processed radar state, should add a_pcm? - dat.live100.vTargetLead = float(self.plan.vTarget) - dat.live100.aTargetMin = float(self.plan.aTargetMin) - dat.live100.aTargetMax = float(self.plan.aTargetMax) - dat.live100.jerkFactor = float(self.plan.jerkFactor) + if CS.steeringPressed: + # reset awareness status on steering + awareness_status = 1.0 - # log learned angle offset - dat.live100.angleOffset = float(self.angle_offset) + # 6 minutes driver you're on + awareness_status -= 0.01/(AWARENESS_TIME) + if awareness_status <= 0.: + AM.add("driverDistracted", enabled) + elif awareness_status <= AWARENESS_PRE_TIME / AWARENESS_TIME and \ + awareness_status >= (AWARENESS_PRE_TIME - 0.1) / AWARENESS_TIME: + AM.add("preDriverDistracted", enabled) - # lag - dat.live100.cumLagMs = -self.rk.remaining*1000. + # parse warnings from car specific interface + for e in get_events(events, [ET.WARNING]): + AM.add(e, enabled) - self.live100.send(dat.to_bytes()) + # if user is not responsive to awareness alerts, then start a smooth deceleration + if awareness_status < -0.: + plan.aTargetMax = min(plan.aTargetMax, AWARENESS_DECEL) + plan.aTargetMin = min(plan.aTargetMin, plan.aTargetMax) - self.prof.checkpoint("Live100") + # *** angle offset learning *** - def wait(self): - # *** run loop at fixed rate *** - if self.rk.keep_time(): - self.prof.display() + if rk.frame % 5 == 2 and plan.lateralValid: + # *** run this at 20hz again *** + angle_offset = learn_angle_offset(active, CS.vEgo, angle_offset, + PL.PP.c_poly, PL.PP.c_prob, LaC.y_des, + CS.steeringPressed) + + # *** gas/brake PID loop *** + actuators.gas, actuators.brake = LoC.update(active, CS.vEgo, CS.brakePressed, + v_cruise_kph, plan.vTarget, + [plan.aTargetMin, plan.aTargetMax], + plan.jerkFactor, CP) + + # *** steering PID loop *** + actuators.steer = LaC.update(active, CS.vEgo, CS.steeringAngle, + CS.steeringPressed, plan.dPoly, angle_offset, VM, PL) + + # send a "steering required alert" if saturation count has reached the limit + if LaC.sat_flag: + AM.add("steerSaturated", enabled) + + if CP.enableCruise and CS.cruiseState.enabled: + v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH + + # *** process alerts *** + + AM.process_alerts(sec_since_boot()) + + return actuators, v_cruise_kph, awareness_status, angle_offset, rear_view_toggle + + +def data_send(plan, plan_ts, CS, CI, CP, state, events, actuators, v_cruise_kph, rk, carstate, + carcontrol, live100, livempc, AM, rear_view_allowed, rear_view_toggle, awareness_status, + LaC, LoC, angle_offset): + + # ***** control the car ***** + + CC = car.CarControl.new_message() + + CC.enabled = isEnabled(state) + + CC.actuators = actuators + + CC.cruiseControl.override = True + # always cancel if we have an interceptor + CC.cruiseControl.cancel = not CP.enableCruise or (not isEnabled(state) and CS.cruiseState.enabled) + + # brake discount removes a sharp nonlinearity + brake_discount = (1.0 - clip(actuators.brake*3., 0.0, 1.0)) + CC.cruiseControl.speedOverride = float(max(0.0, (LoC.v_pid + CS.cruiseState.speedOffset) * brake_discount) if CP.enableCruise else 0.0) + + # TODO: parametrize 0.714 in interface? + # accelOverride is more or less the max throttle allowed to pcm: usually set to a constant + # unless aTargetMax is very high and then we scale with it; this helpw in quicker restart + CC.cruiseControl.accelOverride = float(max(0.714, plan.aTargetMax/A_ACC_MAX)) + + CC.hudControl.setSpeed = float(v_cruise_kph * CV.KPH_TO_MS) + CC.hudControl.speedVisible = isEnabled(state) + CC.hudControl.lanesVisible = isEnabled(state) + CC.hudControl.leadVisible = plan.hasLead + CC.hudControl.visualAlert = AM.visual_alert + CC.hudControl.audibleAlert = AM.audible_alert + + # send car controls over can + CI.apply(CC) + + # ***** publish state to logger ***** + # publish controls state at 100Hz + dat = messaging.new_message() + dat.init('live100') + + # show rear view camera on phone if in reverse gear or when button is pressed + dat.live100.rearViewCam = ('reverseGear' in [e.name for e in events] and rear_view_allowed) or rear_view_toggle + dat.live100.alertText1 = AM.alert_text_1 + dat.live100.alertText2 = AM.alert_text_2 + dat.live100.awarenessStatus = max(awareness_status, 0.0) if isEnabled(state) else 0.0 + + # what packets were used to process + dat.live100.canMonoTimes = list(CS.canMonoTimes) + dat.live100.planMonoTime = plan_ts + + # if controls is enabled + dat.live100.enabled = isEnabled(state) + + # car state + dat.live100.vEgo = CS.vEgo + dat.live100.angleSteers = CS.steeringAngle + dat.live100.steerOverride = CS.steeringPressed + + # longitudinal control state + dat.live100.vPid = float(LoC.v_pid) + dat.live100.vCruise = float(v_cruise_kph) + dat.live100.upAccelCmd = float(LoC.pid.p) + dat.live100.uiAccelCmd = float(LoC.pid.i) + + # lateral control state + dat.live100.yDes = float(LaC.y_des) + dat.live100.angleSteersDes = float(LaC.angle_steers_des) + dat.live100.upSteer = float(LaC.pid.p) + dat.live100.uiSteer = float(LaC.pid.i) + + # processed radar state, should add a_pcm? + dat.live100.vTargetLead = float(plan.vTarget) + dat.live100.aTargetMin = float(plan.aTargetMin) + dat.live100.aTargetMax = float(plan.aTargetMax) + dat.live100.jerkFactor = float(plan.jerkFactor) + + # log learned angle offset + dat.live100.angleOffset = float(angle_offset) + + # lag + dat.live100.cumLagMs = -rk.remaining*1000. + + live100.send(dat.to_bytes()) + + # broadcast carState + cs_send = messaging.new_message() + cs_send.init('carState') + # TODO: override CS.events with all the cumulated events + cs_send.carState = copy(CS) + carstate.send(cs_send.to_bytes()) + + # broadcast carControl + cc_send = messaging.new_message() + cc_send.init('carControl') + cc_send.carControl = copy(CC) + carcontrol.send(cc_send.to_bytes()) + #print [i.name for i in events] + + # publish mpc state at 20Hz + if hasattr(LaC, 'mpc_updated') and LaC.mpc_updated: + dat = messaging.new_message() + dat.init('liveMpc') + dat.liveMpc.x = list(LaC.mpc_solution[0].x) + dat.liveMpc.y = list(LaC.mpc_solution[0].y) + dat.liveMpc.psi = list(LaC.mpc_solution[0].psi) + dat.liveMpc.delta = list(LaC.mpc_solution[0].delta) + livempc.send(dat.to_bytes()) + + return CC def controlsd_thread(gctx, rate=100): # start the loop set_realtime_priority(2) - CTRLS = Controls(gctx, rate) + + context = zmq.Context() + + # pub + live100 = messaging.pub_sock(context, service_list['live100'].port) + carstate = messaging.pub_sock(context, service_list['carState'].port) + carcontrol = messaging.pub_sock(context, service_list['carControl'].port) + sendcan = messaging.pub_sock(context, service_list['sendcan'].port) + livempc = messaging.pub_sock(context, service_list['liveMpc'].port) + + # sub + thermal = messaging.sub_sock(context, service_list['thermal'].port) + health = messaging.sub_sock(context, service_list['health'].port) + cal = messaging.sub_sock(context, service_list['liveCalibration'].port) + logcan = messaging.sub_sock(context, service_list['can'].port) + + CC = car.CarControl.new_message() + CI, CP = get_car(logcan, sendcan) + PL = Planner(CP) + LoC = LongControl(CI.compute_gb) + VM = VehicleModel(CP) + LaC = LatControl(VM) + AM = AlertManager() + + # write CarParams + params = Params() + params.put("CarParams", CP.to_bytes()) + + state = State.DISABLED + soft_disable_timer = 0 + v_cruise_kph = 255 + cal_perc = 0 + cal_status = Calibration.UNCALIBRATED + rear_view_toggle = False + rear_view_allowed = params.get("IsRearViewMirror") == "1" + + # 0.0 - 1.0 + awareness_status = 0. + + rk = Ratekeeper(rate, print_delay_threshold=2./1000) + + # learned angle offset + angle_offset = 0. + calibration_params = params.get("CalibrationParams") + if calibration_params: + try: + calibration_params = json.loads(calibration_params) + angle_offset = calibration_params["angle_offset"] + except (ValueError, KeyError): + pass + + prof = Profiler() + while 1: - CTRLS.data_sample() - CTRLS.state_transition() - CTRLS.state_control() - CTRLS.data_send() - CTRLS.wait() + + prof.reset() # avoid memory leak + + # sample data and compute car events + CS, events, cal_status, cal_perc = data_sample(CI, CC, thermal, health, cal, cal_status, cal_perc) + prof.checkpoint("Sample") + + # define plan + plan, plan_ts = calc_plan(CS, events, PL, LoC) + prof.checkpoint("Plan") + + # update control state + state, soft_disable_timer, v_cruise_kph = state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, cal_perc, AM) + prof.checkpoint("State transition") + + # compute actuators + actuators, v_cruise_kph, awareness_status, angle_offset, rear_view_toggle = state_control(plan, CS, CP, state, events, v_cruise_kph, + AM, rk, awareness_status, PL, LaC, LoC, VM, angle_offset, + rear_view_allowed, rear_view_toggle) + prof.checkpoint("State Control") + + # publish data + CC = data_send(plan, plan_ts, CS, CI, CP, state, events, actuators, v_cruise_kph, + rk, carstate, carcontrol, live100, livempc, AM, rear_view_allowed, + rear_view_toggle, awareness_status, LaC, LoC, angle_offset) + prof.checkpoint("Sent") + + # *** run loop at fixed rate *** + if rk.keep_time(): + prof.display() def main(gctx=None): @@ -462,4 +507,3 @@ def main(gctx=None): if __name__ == "__main__": main() - diff --git a/selfdrive/controls/lib/adaptivecruise.py b/selfdrive/controls/lib/adaptivecruise.py index 1fcf6cad68d4b6..8d3ceec67420d9 100644 --- a/selfdrive/controls/lib/adaptivecruise.py +++ b/selfdrive/controls/lib/adaptivecruise.py @@ -109,7 +109,7 @@ def calc_critical_decel(d_lead, v_rel, d_offset, v_offset): # maximum acceleration adjustment _A_CORR_BY_SPEED_V = [0.4, 0.4, 0] # speeds -_A_CORR_BY_SPEED_BP = [0., 5., 20.] +_A_CORR_BY_SPEED_BP = [0., 2., 10.] # max acceleration allowed in acc, which happens in restart A_ACC_MAX = max(_A_CORR_BY_SPEED_V) + max(_A_CRUISE_MAX_V) @@ -283,20 +283,12 @@ def compute_speed_with_leads(v_ego, angle_steers, v_pid, l1, l2, CP): class AdaptiveCruise(object): def __init__(self): - self.last_cal = 0. self.l1, self.l2 = None, None - self.dead = True - def update(self, cur_time, v_ego, angle_steers, v_pid, CP, l20): + def update(self, v_ego, angle_steers, v_pid, CP, l20): if l20 is not None: self.l1 = l20.live20.leadOne self.l2 = l20.live20.leadTwo - # TODO: no longer has anything to do with calibration - self.last_cal = cur_time - self.dead = False - elif cur_time - self.last_cal > 0.5: - self.dead = True - self.v_target_lead, self.a_target, self.a_pcm, self.jerk_factor = \ compute_speed_with_leads(v_ego, angle_steers, v_pid, self.l1, self.l2, CP) self.has_lead = self.v_target_lead != MAX_SPEED_POSSIBLE diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index 162a1977ed2168..a87667322812b3 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -2,22 +2,31 @@ from selfdrive.swaglog import cloudlog import copy -class ET: - ENABLE = 0 - NO_ENTRY = 1 - WARNING = 2 - USER_DISABLE = 3 - SOFT_DISABLE = 4 - IMMEDIATE_DISABLE = 5 - -class alert(object): - def __init__(self, alert_text_1, alert_text_2, alert_type, visual_alert, audible_alert, duration_sound, duration_hud_alert, duration_text): + +# Priority +class PT: + HIGH = 3 + MID = 2 + LOW = 1 + + +class Alert(object): + def __init__(self, + alert_text_1, + alert_text_2, + alert_priority, + visual_alert, + audible_alert, + duration_sound, + duration_hud_alert, + duration_text): + self.alert_text_1 = alert_text_1 self.alert_text_2 = alert_text_2 - self.alert_type = alert_type + self.alert_priority = alert_priority self.visual_alert = visual_alert if visual_alert is not None else "none" self.audible_alert = audible_alert if audible_alert is not None else "none" - + self.duration_sound = duration_sound self.duration_hud_alert = duration_hud_alert self.duration_text = duration_text @@ -28,45 +37,297 @@ def __init__(self, alert_text_1, alert_text_2, alert_type, visual_alert, audible tst.hudControl.audibleAlert = self.audible_alert def __str__(self): - return self.alert_text_1 + "/" + self.alert_text_2 + " " + str(self.alert_type) + " " + str(self.visual_alert) + " " + str(self.audible_alert) + return self.alert_text_1 + "/" + self.alert_text_2 + " " + str(self.alert_priority) + " " + str( + self.visual_alert) + " " + str(self.audible_alert) def __gt__(self, alert2): - return self.alert_type > alert2.alert_type + return self.alert_priority > alert2.alert_priority + class AlertManager(object): alerts = { - "enable": alert("", "", ET.ENABLE, None, "beepSingle", .2, 0., 0.), - "disable": alert("", "", ET.USER_DISABLE, None, "beepSingle", .2, 0., 0.), - "pedalPressed": alert("Comma Unavailable", "Pedal Pressed", ET.NO_ENTRY, "brakePressed", "chimeDouble", .4, 2., 3.), - "preDriverDistracted": alert("Take Control ", "User Distracted", ET.WARNING, "steerRequired", "chimeDouble", .4, 2., 3.), - "driverDistracted": alert("Take Control to Regain Speed", "User Distracted", ET.WARNING, "steerRequired", "chimeRepeated", .5, .5, .5), - "steerSaturated": alert("Take Control", "Turn Exceeds Limit", ET.WARNING, "steerRequired", "chimeSingle", 1., 2., 3.), - "overheat": alert("Take Control Immediately", "System Overheated", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "controlsMismatch": alert("Take Control Immediately", "Controls Mismatch", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "radarCommIssue": alert("Take Control Immediately", "Radar Error: Restart the Car",ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "calibrationInvalid": alert("Take Control Immediately", "Calibration Invalid: Reposition Neo and Recalibrate", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "calibrationInProgress": alert("Take Control Immediately", "Calibration in Progress: ", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "modelCommIssue": alert("Take Control Immediately", "Model Error: Restart the Car",ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "controlsFailed": alert("Take Control Immediately", "Controls Failed", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "fcw": alert("", "", ET.WARNING, None, None, .1, .1, .1), - # car errors - "commIssue": alert("Take Control Immediately","CAN Error: Restart the Car", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "steerUnavailable": alert("Take Control Immediately","Steer Error: Restart the Car", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "steerTempUnavailable": alert("Take Control", "Steer Temporarily Unavailable", ET.WARNING, "steerRequired", "chimeDouble", .4, 2., 3.), - "brakeUnavailable": alert("Take Control Immediately","Brake Error: Restart the Car", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "gasUnavailable": alert("Take Control Immediately","Gas Error: Restart the Car", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "wrongGear": alert("Take Control Immediately","Gear not D", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "reverseGear": alert("Take Control Immediately","Car in Reverse", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "doorOpen": alert("Take Control Immediately","Door Open", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "seatbeltNotLatched": alert("Take Control Immediately","Seatbelt Unlatched", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "espDisabled": alert("Take Control Immediately","ESP Off", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "cruiseDisabled": alert("Take Control Immediately","Cruise Is Off", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "wrongCarMode": alert("Comma Unavailable","Main Switch Off", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.), - "outOfSpace": alert("Comma Unavailable","Out of Space", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.), - "dataNeeded": alert("Comma Unavailable","Data needed for calibration. Upload drive, try again", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.), - "ethicalDilemma": alert("Take Control Immediately","Ethical Dilemma Detected", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), - "startup": alert("Always Keep Hands on Wheel","Be Ready to Take Over Any Time", ET.NO_ENTRY, None, None, 0., 0., 15.), + + # Miscellaneous alerts + "enable": Alert( + "", + "", + PT.MID, None, "beepSingle", .2, 0., 0.), + + "disable": Alert( + "", + "", + PT.MID, None, "beepSingle", .2, 0., 0.), + + "fcw": Alert( + "", + "", + PT.LOW, None, None, .1, .1, .1), + + "steerSaturated": Alert( + "Take Control", + "Turn Exceeds Limit", + PT.LOW, "steerRequired", "chimeSingle", 1., 2., 3.), + + "steerTempUnavailable": Alert( + "Take Control", + "Steer Temporarily Unavailable", + PT.LOW, "steerRequired", "chimeDouble", .4, 2., 3.), + + "preDriverDistracted": Alert( + "Take Control ", + "User Distracted", + PT.LOW, "steerRequired", "chimeDouble", .4, 2., 3.), + + "driverDistracted": Alert( + "Take Control to Regain Speed", + "User Distracted", + PT.LOW, "steerRequired", "chimeRepeated", .5, .5, .5), + + "startup": Alert( + "Always Keep Hands on Wheel", + "Be Ready to Take Over Any Time", + PT.LOW, None, None, 0., 0., 15.), + + "ethicalDilemma": Alert( + "Take Control Immediately", + "Ethical Dilemma Detected", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "steerTempUnavailableNoEntry": Alert( + "Comma Unavailable", + "Steer Temporary Unavailable", + PT.LOW, None, "chimeDouble", .4, 0., 3.), + + # Non-entry only alerts + "wrongCarModeNoEntry": Alert( + "Comma Unavailable", + "Main Switch Off", + PT.LOW, None, "chimeDouble", .4, 0., 3.), + + "dataNeededNoEntry": Alert( + "Comma Unavailable", + "Data needed for calibration. Upload drive, try again", + PT.LOW, None, "chimeDouble", .4, 0., 3.), + + "outOfSpaceNoEntry": Alert( + "Comma Unavailable", + "Out of Space", + PT.LOW, None, "chimeDouble", .4, 0., 3.), + + "pedalPressedNoEntry": Alert( + "Comma Unavailable", + "Pedal Pressed", + PT.LOW, "brakePressed", "chimeDouble", .4, 2., 3.), + + "speedTooLowNoEntry": Alert( + "Comma Unavailable", + "Speed Too Low", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "brakeHoldNoEntry": Alert( + "Comma Unavailable", + "Brake Hold Active", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "parkBrakeNoEntry": Alert( + "Comma Unavailable", + "Park Brake Engaged", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + # Cancellation alerts causing disabling + "overheat": Alert( + "Take Control Immediately", + "System Overheated", + PT.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "wrongGear": Alert( + "Take Control Immediately", + "Gear not D", + PT.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "calibrationInvalid": Alert( + "Take Control Immediately", + "Calibration Invalid: Reposition Neo and Recalibrate", + PT.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "calibrationInProgress": Alert( + "Take Control Immediately", + "Calibration in Progress", + PT.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "doorOpen": Alert( + "Take Control Immediately", + "Door Open", + PT.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "seatbeltNotLatched": Alert( + "Take Control Immediately", + "Seatbelt Unlatched", + PT.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "espDisabled": Alert( + "Take Control Immediately", + "ESP Off", + PT.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "radarCommIssue": Alert( + "Take Control Immediately", + "Radar Error: Restart the Car", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "radarFault": Alert( + "Take Control Immediately", + "Radar Error: Restart the Car", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "modelCommIssue": Alert( + "Take Control Immediately", + "Model Error: Restart the Car", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "controlsFailed": Alert( + "Take Control Immediately", + "Controls Failed", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "controlsMismatch": Alert( + "Take Control Immediately", + "Controls Mismatch", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "commIssue": Alert( + "Take Control Immediately", + "CAN Error: Restart the Car", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "steerUnavailable": Alert( + "Take Control Immediately", + "Steer Error: Restart the Car", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "brakeUnavailable": Alert( + "Take Control Immediately", + "Brake Error: Restart the Car", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "gasUnavailable": Alert( + "Take Control Immediately", + "Gas Error: Restart the Car", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "reverseGear": Alert( + "Take Control Immediately", + "Reverse Gear", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + "cruiseDisabled": Alert( + "Take Control Immediately", + "Cruise Is Off", + PT.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), + + # not loud cancellations (user is in control) + "noTarget": Alert( + "Comma Canceled", + "No Close Lead", + PT.HIGH, None, "chimeDouble", .4, 2., 3.), + + # Cancellation alerts causing non-entry + "overheatNoEntry": Alert( + "Comma Unavailable", + "System Overheated", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "wrongGearNoEntry": Alert( + "Comma Unavailable", + "Gear not D", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "calibrationInvalidNoEntry": Alert( + "Comma Unavailable", + "Calibration Invalid: Reposition Neo and Recalibrate", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "calibrationInProgressNoEntry": Alert( + "Comma Unavailable", + "Calibration in Progress: ", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "doorOpenNoEntry": Alert( + "Comma Unavailable", + "Door Open", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "seatbeltNotLatchedNoEntry": Alert( + "Comma Unavailable", + "Seatbelt Unlatched", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "espDisabledNoEntry": Alert( + "Comma Unavailable", + "ESP Off", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "radarCommIssueNoEntry": Alert( + "Comma Unavailable", + "Radar Error: Restart the Car", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "radarFaultNoEntry": Alert( + "Comma Unavailable", + "Radar Error: Restart the Car", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "modelCommIssueNoEntry": Alert( + "Comma Unavailable", + "Model Error: Restart the Car", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "controlsFailedNoEntry": Alert( + "Comma Unavailable", + "Controls Failed", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "controlsMismatchNoEntry": Alert( + "Comma Unavailable", + "Controls Mismatch", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "commIssueNoEntry": Alert( + "Comma Unavailable", + "CAN Error: Restart the Car", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "steerUnavailableNoEntry": Alert( + "Comma Unavailable", + "Steer Error: Restart the Car", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "brakeUnavailableNoEntry": Alert( + "Comma Unavailable", + "Brake Error: Restart the Car", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "gasUnavailableNoEntry": Alert( + "Comma Unavailable", + "Gas Error: Restart the Car", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "reverseGearNoEntry": Alert( + "Comma Unavailable", + "Reverse Gear", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "cruiseDisabledNoEntry": Alert( + "Comma Unavailable", + "Cruise is Off", + PT.LOW, None, "chimeDouble", .4, 2., 3.), + + "noTargetNoEntry": Alert( + "Comma Unavailable", + "No Close Lead", + PT.LOW, None, "chimeDouble", .4, 2., 3.), } + def __init__(self): self.activealerts = [] self.current_alert = None @@ -75,31 +336,16 @@ def __init__(self): def alertPresent(self): return len(self.activealerts) > 0 - def alertShouldSoftDisable(self): - return len(self.activealerts) > 0 and any(a.alert_type == ET.SOFT_DISABLE for a in self.activealerts) - - def alertShouldDisable(self): - return len(self.activealerts) > 0 and any(a.alert_type in [ET.IMMEDIATE_DISABLE, ET.USER_DISABLE] for a in self.activealerts) - def add(self, alert_type, enabled=True, extra_text=''): alert_type = str(alert_type) this_alert = copy.copy(self.alerts[alert_type]) this_alert.alert_text_2 += extra_text - # downgrade the alert if we aren't enabled, except if it's FCW, which remains the same - # TODO: remove this 'if' by adding more alerts - if not enabled and this_alert.alert_type in [ET.WARNING, ET.SOFT_DISABLE, ET.IMMEDIATE_DISABLE] \ - and this_alert != self.alerts['fcw']: - this_alert = alert("Comma Unavailable" if this_alert.alert_text_1 != "" else "", this_alert.alert_text_2, ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.) - - # ignore no entries if we are enabled - if enabled and this_alert.alert_type in [ET.ENABLE, ET.NO_ENTRY]: - return # if new alert is higher priority, log it if self.current_alert is None or this_alert > self.current_alert: cloudlog.event('alert_add', - alert_type=alert_type, - enabled=enabled) + alert_type=alert_type, + enabled=enabled) self.activealerts.append(this_alert) self.activealerts.sort() @@ -109,29 +355,29 @@ def process_alerts(self, cur_time): self.alert_start_time = cur_time self.current_alert = self.activealerts[0] print self.current_alert - alert_text_1 = "" - alert_text_2 = "" - visual_alert = "none" - audible_alert = "none" + + # start with assuming no alerts + self.alert_text_1 = "" + self.alert_text_2 = "" + self.visual_alert = "none" + self.audible_alert = "none" if self.current_alert is not None: # ewwwww if self.alert_start_time + self.current_alert.duration_sound > cur_time: - audible_alert = self.current_alert.audible_alert + self.audible_alert = self.current_alert.audible_alert if self.alert_start_time + self.current_alert.duration_hud_alert > cur_time: - visual_alert = self.current_alert.visual_alert + self.visual_alert = self.current_alert.visual_alert if self.alert_start_time + self.current_alert.duration_text > cur_time: - alert_text_1 = self.current_alert.alert_text_1 - alert_text_2 = self.current_alert.alert_text_2 + self.alert_text_1 = self.current_alert.alert_text_1 + self.alert_text_2 = self.current_alert.alert_text_2 # disable current alert - if self.alert_start_time + max(self.current_alert.duration_sound, self.current_alert.duration_hud_alert, self.current_alert.duration_text) < cur_time: + if self.alert_start_time + max(self.current_alert.duration_sound, self.current_alert.duration_hud_alert, + self.current_alert.duration_text) < cur_time: self.current_alert = None # reset self.activealerts = [] - - return alert_text_1, alert_text_2, visual_alert, audible_alert - diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 2d01b40ca0a55c..699893134e5ba0 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -1,8 +1,38 @@ from common.numpy_fast import clip +from cereal import car + + +class EventTypes: + ENABLE = 'enable' + PRE_ENABLE = 'preEnable' + NO_ENTRY = 'noEntry' + WARNING = 'warning' + USER_DISABLE = 'userDisable' + SOFT_DISABLE = 'softDisable' + IMMEDIATE_DISABLE = 'immediateDisable' + + +def create_event(name, types): + event = car.CarEvent.new_message() + event.name = name + for t in types: + setattr(event, t, True) + return event + + +def get_events(events, types): + out = [] + for e in events: + for t in types: + if getattr(e, t): + out.append(e.name) + return out + def rate_limit(new_value, last_value, dw_step, up_step): return clip(new_value, last_value + dw_step, last_value + up_step) + def learn_angle_offset(lateral_control, v_ego, angle_offset, c_poly, c_prob, y_des, steer_override): # simple integral controller that learns how much steering offset to put to have the car going straight # while being in the middle of the lane diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py index 720d7947f8e3de..ab81435fc7996b 100644 --- a/selfdrive/controls/lib/latcontrol.py +++ b/selfdrive/controls/lib/latcontrol.py @@ -1,133 +1,80 @@ import math -import numpy as np +from selfdrive.controls.lib.pid import PIController +from selfdrive.controls.lib.lateral_mpc import libmpc_py from common.numpy_fast import clip, interp -from selfdrive.config import Conversions as CV - -_K_CURV_V = [1., 0.6] -_K_CURV_BP = [0., 0.002] - -def calc_d_lookahead(v_ego, d_poly): - #*** this function computes how far too look for lateral control - # howfar we look ahead is function of speed and how much curvy is the path - offset_lookahead = 1. - k_lookahead = 7. - # integrate abs value of second derivative of poly to get a measure of path curvature - pts_len = 50. # m - if len(d_poly)>0: - pts = np.polyval([6*d_poly[0], 2*d_poly[1]], np.arange(0, pts_len)) - else: - pts = 0. - curv = np.sum(np.abs(pts))/pts_len - - k_curv = interp(curv, _K_CURV_BP, _K_CURV_V) - - # sqrt on speed is needed to keep, for a given curvature, the y_des - # proportional to speed. Indeed, y_des is prop to d_lookahead^2 - # 36m at 25m/s - d_lookahead = offset_lookahead + math.sqrt(max(v_ego, 0)) * k_lookahead * k_curv - return d_lookahead - -def calc_lookahead_offset(v_ego, angle_steers, d_lookahead, VM, angle_offset): - #*** this function returns the lateral offset given the steering angle, speed and the lookahead distance - sa = (angle_steers - angle_offset) * CV.DEG_TO_RAD - curvature = VM.calc_curvature(sa, v_ego) - # clip is to avoid arcsin NaNs due to too sharp turns - y_actual = d_lookahead * np.tan(np.arcsin(np.clip(d_lookahead * curvature, -0.999, 0.999))/2.) - return y_actual, curvature - -def calc_desired_steer_angle(v_ego, y_des, d_lookahead, VM, angle_offset): - # inverse of the above function - curvature = np.sin(np.arctan(y_des / d_lookahead) * 2.) / d_lookahead - steer_des = VM.get_steer_from_curvature(curvature, v_ego) * CV.RAD_TO_DEG + angle_offset - return steer_des, curvature - -def pid_lateral_control(v_ego, sa_actual, sa_des, Ui_steer, steer_max, - steer_override, sat_count, enabled, Kp, Ki, rate): - - sat_count_rate = 1./rate - sat_count_limit = 0.8 # after 0.8s of continuous saturation, an alert will be sent - - error_steer = sa_des - sa_actual - Ui_unwind_speed = 0.3/rate #.3 per second - - Up_steer = error_steer*Kp - Ui_steer_new = Ui_steer + error_steer*Ki * 1./rate - output_steer_new = Ui_steer_new + Up_steer - - # Anti-wind up for integrator: do not integrate if we are against the steer limits - if ( - (error_steer >= 0. and (output_steer_new < steer_max or Ui_steer < 0)) or - (error_steer <= 0. and - (output_steer_new > -steer_max or Ui_steer > 0))) and not steer_override: - #update integrator - Ui_steer = Ui_steer_new - # unwind integrator if driver is maneuvering the steering wheel - elif steer_override: - Ui_steer -= Ui_unwind_speed * np.sign(Ui_steer) - - # still, intergral term should not be bigger then limits - Ui_steer = clip(Ui_steer, -steer_max, steer_max) - - output_steer = Up_steer + Ui_steer - - # don't run steer control if at very low speed - if v_ego < 0.3 or not enabled: - output_steer = 0. - Ui_steer = 0. - - # useful to know if control is against the limit - lateral_control_sat = False - if abs(output_steer) > steer_max: - lateral_control_sat = True - - output_steer = clip(output_steer, -steer_max, steer_max) - - # if lateral control is saturated for a certain period of time, send an alert for taking control of the car - # wind - if lateral_control_sat and not steer_override and v_ego > 10 and abs(error_steer) > 0.1: - sat_count += sat_count_rate - # unwind - else: - sat_count -= sat_count_rate - - sat_flag = False - if sat_count >= sat_count_limit: - sat_flag = True - - sat_count = clip(sat_count, 0, 1) - - return output_steer, Up_steer, Ui_steer, lateral_control_sat, sat_count, sat_flag + + +# 100ms is a rule of thumb estimation of lag from image processing to actuator command +ACTUATORS_DELAY = 0.1 + + +def calc_states_after_delay(states, v_ego, steer_angle, curvature_factor, steer_ratio): + states[0].x = v_ego * ACTUATORS_DELAY + states[0].psi = v_ego * curvature_factor * math.radians(steer_angle) / steer_ratio * ACTUATORS_DELAY + return states + + +def get_steer_max(CP, v_ego): + return interp(v_ego, CP.steerMaxBP, CP.steerMaxV) + class LatControl(object): - def __init__(self): - self.Up_steer = 0. - self.sat_count = 0 - self.y_des = 0.0 - self.lateral_control_sat = False - self.Ui_steer = 0. - self.reset() + def __init__(self, VM): + self.pid = PIController(VM.CP.steerKp, VM.CP.steerKi, pos_limit=1.0) + self.setup_mpc() + + self.y_des = -1 # Legacy + + def setup_mpc(self): + self.libmpc = libmpc_py.libmpc + self.libmpc.init() + + self.mpc_solution = libmpc_py.ffi.new("log_t *") + self.cur_state = libmpc_py.ffi.new("state_t *") + self.mpc_updated = False + self.cur_state[0].x = 0.0 + self.cur_state[0].y = 0.0 + self.cur_state[0].psi = 0.0 + self.cur_state[0].delta = 0.0 + + self.last_mpc_ts = 0.0 + self.angle_steers_des = 0 def reset(self): - self.Ui_steer = 0. + self.pid.reset() + + def update(self, active, v_ego, angle_steers, steer_override, d_poly, angle_offset, VM, PL): + self.mpc_updated = False + if self.last_mpc_ts + 0.001 < PL.last_md_ts: + self.last_mpc_ts = PL.last_md_ts + + curvature_factor = VM.curvature_factor(v_ego) - def update(self, enabled, v_ego, angle_steers, steer_override, d_poly, angle_offset, VM): - rate = 100 + l_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.l_poly)) + r_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.r_poly)) + p_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.p_poly)) - steer_max = 1.0 + # account for actuation delay + self.cur_state = calc_states_after_delay(self.cur_state, v_ego, angle_steers, curvature_factor, VM.CP.sR) - # how far we look ahead is function of speed and desired path - d_lookahead = calc_d_lookahead(v_ego, d_poly) + self.libmpc.run_mpc(self.cur_state, self.mpc_solution, + l_poly, r_poly, p_poly, + PL.PP.l_prob, PL.PP.r_prob, PL.PP.p_prob, curvature_factor, v_ego, PL.PP.lane_width) - # desired lookahead offset - self.y_des = np.polyval(d_poly, d_lookahead) + delta_desired = self.mpc_solution[0].delta[1] + self.cur_state[0].delta = delta_desired - # calculate actual offset at the lookahead point - self.angle_steers_des, _ = calc_desired_steer_angle(v_ego, self.y_des, - d_lookahead, VM, angle_offset) + self.angle_steers_des = math.degrees(delta_desired * VM.CP.sR) + angle_offset + self.mpc_updated = True - output_steer, self.Up_steer, self.Ui_steer, self.lateral_control_sat, self.sat_count, sat_flag = pid_lateral_control( - v_ego, angle_steers, self.angle_steers_des, self.Ui_steer, steer_max, - steer_override, self.sat_count, enabled, VM.CP.steerKp, VM.CP.steerKi, rate) + if v_ego < 0.3 or not active: + output_steer = 0.0 + self.pid.reset() + else: + steer_max = get_steer_max(VM.CP, v_ego) + self.pid.pos_limit = steer_max + self.pid.neg_limit = -steer_max + output_steer = self.pid.update(self.angle_steers_des, angle_steers, check_saturation=(v_ego > 10), override=steer_override) - final_steer = clip(output_steer, -steer_max, steer_max) - return final_steer, sat_flag + self.sat_flag = self.pid.saturated + return output_steer diff --git a/selfdrive/controls/lib/latcontrol_helpers.py b/selfdrive/controls/lib/latcontrol_helpers.py new file mode 100644 index 00000000000000..982152d65c733a --- /dev/null +++ b/selfdrive/controls/lib/latcontrol_helpers.py @@ -0,0 +1,89 @@ +import numpy as np +import math +from common.numpy_fast import interp + +_K_CURV_V = [1., 0.6] +_K_CURV_BP = [0., 0.002] + +# lane width http://safety.fhwa.dot.gov/geometric/pubs/mitigationstrategies/chapter3/3_lanewidth.cfm +_LANE_WIDTH_V = [3., 3.8] + +# break points of speed +_LANE_WIDTH_BP = [0., 31.] + + +def calc_d_lookahead(v_ego, d_poly): + # this function computes how far too look for lateral control + # howfar we look ahead is function of speed and how much curvy is the path + offset_lookahead = 1. + k_lookahead = 7. + # integrate abs value of second derivative of poly to get a measure of path curvature + pts_len = 50. # m + if len(d_poly) > 0: + pts = np.polyval([6 * d_poly[0], 2 * d_poly[1]], np.arange(0, pts_len)) + else: + pts = 0. + curv = np.sum(np.abs(pts)) / pts_len + + k_curv = interp(curv, _K_CURV_BP, _K_CURV_V) + + # sqrt on speed is needed to keep, for a given curvature, the y_des + # proportional to speed. Indeed, y_des is prop to d_lookahead^2 + # 36m at 25m/s + d_lookahead = offset_lookahead + math.sqrt(max(v_ego, 0)) * k_lookahead * k_curv + return d_lookahead + + +def calc_lookahead_offset(v_ego, angle_steers, d_lookahead, VM, angle_offset): + # this function returns the lateral offset given the steering angle, speed and the lookahead distance + sa = math.radians(angle_steers - angle_offset) + curvature = VM.calc_curvature(sa, v_ego) + # clip is to avoid arcsin NaNs due to too sharp turns + y_actual = d_lookahead * np.tan(np.arcsin(np.clip(d_lookahead * curvature, -0.999, 0.999)) / 2.) + return y_actual, curvature + + +def calc_desired_steer_angle(v_ego, y_des, d_lookahead, VM, angle_offset): + # inverse of the above function + curvature = np.sin(np.arctan(y_des / d_lookahead) * 2.) / d_lookahead + steer_des = math.degrees(VM.get_steer_from_curvature(curvature, v_ego)) + angle_offset + return steer_des, curvature + + +def compute_path_pinv(): + deg = 3 + x = np.arange(50.0) + X = np.vstack(tuple(x**n for n in range(deg, -1, -1))).T + pinv = np.linalg.pinv(X) + return pinv + + +def model_polyfit(points, path_pinv): + return np.dot(path_pinv, map(float, points)) + + +def calc_desired_path(l_poly, + r_poly, + p_poly, + l_prob, + r_prob, + p_prob, + speed, + lane_width=None): + # this function computes the poly for the center of the lane, averaging left and right polys + if lane_width is None: + lane_width = interp(speed, _LANE_WIDTH_BP, _LANE_WIDTH_V) + + # lanes in US are ~3.6m wide + half_lane_poly = np.array([0., 0., 0., lane_width / 2.]) + if l_prob + r_prob > 0.01: + c_poly = ((l_poly - half_lane_poly) * l_prob + + (r_poly + half_lane_poly) * r_prob) / (l_prob + r_prob) + c_prob = l_prob + r_prob - l_prob * r_prob + else: + c_poly = np.zeros(4) + c_prob = 0. + + p_weight = 1. # predicted path weight relatively to the center of the lane + d_poly = list((c_poly * c_prob + p_poly * p_prob * p_weight) / (c_prob + p_prob * p_weight)) + return d_poly, c_poly, c_prob diff --git a/selfdrive/controls/lib/lateral_mpc/Makefile b/selfdrive/controls/lib/lateral_mpc/Makefile new file mode 100644 index 00000000000000..b0802f9a440e58 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/Makefile @@ -0,0 +1,75 @@ +CC = clang +CXX = clang++ + +PHONELIBS = ../../../../phonelibs + +UNAME_M := $(shell uname -m) + +CFLAGS = -O3 -fPIC -I. +CXXFLAGS = -O3 -fPIC -I. + +QPOASES_FLAGS = -I$(PHONELIBS)/qpoases -I$(PHONELIBS)/qpoases/INCLUDE -I$(PHONELIBS)/qpoases/SRC + +ACADO_FLAGS = -I$(PHONELIBS)/acado/include -I$(PHONELIBS)/acado/include/acado + +ifeq ($(UNAME_M),aarch64) +ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a +else +ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a +endif + +OBJS = \ + $(PHONELIBS)/qpoases/SRC/Bounds.o \ + $(PHONELIBS)/qpoases/SRC/Constraints.o \ + $(PHONELIBS)/qpoases/SRC/CyclingManager.o \ + $(PHONELIBS)/qpoases/SRC/Indexlist.o \ + $(PHONELIBS)/qpoases/SRC/MessageHandling.o \ + $(PHONELIBS)/qpoases/SRC/QProblem.o \ + $(PHONELIBS)/qpoases/SRC/QProblemB.o \ + $(PHONELIBS)/qpoases/SRC/SubjectTo.o \ + $(PHONELIBS)/qpoases/SRC/Utils.o \ + $(PHONELIBS)/qpoases/SRC/EXTRAS/SolutionAnalysis.o \ + mpc_export/acado_qpoases_interface.o \ + mpc_export/acado_integrator.o \ + mpc_export/acado_solver.o \ + mpc_export/acado_auxiliary_functions.o \ + mpc.o + +DEPS := $(OBJS:.o=.d) + +.PHONY: all +all: libcommampc.so + +libcommampc.so: $(OBJS) + $(CXX) -shared -o '$@' $^ -lm + +%.o: %.cpp + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) -MMD \ + -I mpc_export/ \ + $(QPOASES_FLAGS) \ + -c -o '$@' '$<' + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -I mpc_export/ \ + $(QPOASES_FLAGS) \ + -c -o '$@' '$<' + +generator: generator.cpp + $(CXX) -Wall -std=c++11 \ + generator.cpp \ + -o generator \ + $(ACADO_FLAGS) \ + $(ACADO_LIBS) + +.PHONY: generate +generate: generator + ./generator + +.PHONY: clean +clean: + rm -f libcommampc.so generator $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/controls/lib/lateral_mpc/__init__.py b/selfdrive/controls/lib/lateral_mpc/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/controls/lib/lateral_mpc/generator.cpp b/selfdrive/controls/lib/lateral_mpc/generator.cpp new file mode 100644 index 00000000000000..2e5c3a2ff4732f --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/generator.cpp @@ -0,0 +1,137 @@ +#include + +#define PI 3.1415926536 +#define deg2rad(d) (d/180.0*PI) + +const int controlHorizon = 50; +const double samplingTime = 0.05; // 20 Hz + +using namespace std; + +int main( ) +{ + USING_NAMESPACE_ACADO + + + DifferentialEquation f; + + DifferentialState xx; // x position + DifferentialState yy; // y position + DifferentialState psi; // vehicle heading + DifferentialState delta; + + OnlineData curvature_factor; + OnlineData v_ref; // m/s + OnlineData l_poly_r0, l_poly_r1, l_poly_r2, l_poly_r3; + OnlineData r_poly_r0, r_poly_r1, r_poly_r2, r_poly_r3; + OnlineData p_poly_r0, p_poly_r1, p_poly_r2, p_poly_r3; + OnlineData l_prob, r_prob, p_prob; + OnlineData lane_width; + + Control t; + + // Equations of motion + f << dot(xx) == v_ref * cos(psi); + f << dot(yy) == v_ref * sin(psi); + f << dot(psi) == v_ref * delta * curvature_factor; + f << dot(delta) == t; + + auto lr_prob = l_prob + r_prob - l_prob * r_prob; + + auto poly_l = l_poly_r0*(xx*xx*xx) + l_poly_r1*(xx*xx) + l_poly_r2*xx + l_poly_r3; + auto poly_r = r_poly_r0*(xx*xx*xx) + r_poly_r1*(xx*xx) + r_poly_r2*xx + r_poly_r3; + auto poly_p = p_poly_r0*(xx*xx*xx) + p_poly_r1*(xx*xx) + p_poly_r2*xx + p_poly_r3; + + auto angle_l = atan(3*l_poly_r0*xx*xx + 2*l_poly_r1*xx + l_poly_r2); + auto angle_r = atan(3*r_poly_r0*xx*xx + 2*r_poly_r1*xx + r_poly_r2); + auto angle_p = atan(3*p_poly_r0*xx*xx + 2*p_poly_r1*xx + p_poly_r2); + + auto c_left_lane = exp(-(poly_l - yy)); + auto c_right_lane = exp(poly_r - yy); + + auto r_phantom = poly_l - lane_width/2.0; + auto l_phantom = poly_r + lane_width/2.0; + + auto path = lr_prob * (l_prob * r_phantom + r_prob * l_phantom) / (l_prob + r_prob + 0.0001) + + (1-lr_prob) * poly_p; + + auto angle = lr_prob * (l_prob * angle_l + r_prob * angle_r) / (l_prob + r_prob + 0.0001) + + (1-lr_prob) * angle_p; + + // Running cost + Function h; + + // Distance errors + h << path - yy; + h << l_prob * c_left_lane; + h << r_prob * c_right_lane; + + // Heading error + h << (v_ref + 1.0 ) * (angle - psi); + + // Angular rate error + h << (v_ref + 1.0 ) * t; + + DMatrix Q(5,5); + Q(0,0) = 1.0; + Q(1,1) = 1.0; + Q(2,2) = 1.0; + + Q(3,3) = 1.0; + + Q(4,4) = 1.0; + + // Terminal cost + Function hN; + + // Distance errors + hN << path - yy; + hN << l_prob * c_left_lane; + hN << r_prob * c_right_lane; + + // Heading errors + hN << (2.0 * v_ref + 1.0 ) * (angle - psi); + + DMatrix QN(4,4); + QN(0,0) = 1.0; + QN(1,1) = 1.0; + QN(2,2) = 1.0; + + QN(3,3) = 1.0; + + // Setup Optimal Control Problem + const double tStart = 0.0; + const double tEnd = samplingTime * controlHorizon; + + OCP ocp( tStart, tEnd, controlHorizon ); + ocp.subjectTo(f); + + ocp.minimizeLSQ(Q, h); + ocp.minimizeLSQEndTerm(QN, hN); + + ocp.subjectTo( deg2rad(-90) <= psi <= deg2rad(90)); + ocp.subjectTo( deg2rad(-25) <= delta <= deg2rad(25)); + ocp.subjectTo( -0.1 <= t <= 0.1); + ocp.setNOD(18); + + OCPexport mpc(ocp); + mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON ); + mpc.set( DISCRETIZATION_TYPE, MULTIPLE_SHOOTING ); + mpc.set( INTEGRATOR_TYPE, INT_RK4 ); + mpc.set( NUM_INTEGRATOR_STEPS, 250 ); + + mpc.set( SPARSE_QP_SOLUTION, CONDENSING ); + mpc.set( QP_SOLVER, QP_QPOASES ); + mpc.set( HOTSTART_QP, YES ); + mpc.set( GENERATE_TEST_FILE, NO); + mpc.set( GENERATE_MAKE_FILE, NO ); + mpc.set( GENERATE_MATLAB_INTERFACE, NO ); + mpc.set( GENERATE_SIMULINK_INTERFACE, NO ); + + if (mpc.exportCode( "mpc_export" ) != SUCCESSFUL_RETURN) + exit( EXIT_FAILURE ); + + mpc.printDimensionsQP( ); + + return EXIT_SUCCESS; +} diff --git a/selfdrive/controls/lib/lateral_mpc/libmpc_py.py b/selfdrive/controls/lib/lateral_mpc/libmpc_py.py new file mode 100644 index 00000000000000..032567be59a9b9 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/libmpc_py.py @@ -0,0 +1,30 @@ +import os +import subprocess + +from cffi import FFI + +mpc_dir = os.path.dirname(os.path.abspath(__file__)) + +libmpc_fn = os.path.join(mpc_dir, "libcommampc.so") +subprocess.check_output(["make", "-j4"], cwd=mpc_dir) + +ffi = FFI() +ffi.cdef(""" +typedef struct { + double x, y, psi, delta, t; +} state_t; + +typedef struct { + double x[50]; + double y[50]; + double psi[50]; + double delta[50]; +} log_t; + +void init(); +void run_mpc(state_t * x0, log_t * solution, + double l_poly[4], double r_poly[4], double p_poly[4], + double l_prob, double r_prob, double p_prob, double curvature_factor, double v_ref, double lane_width); +""") + +libmpc = ffi.dlopen(libmpc_fn) diff --git a/selfdrive/controls/lib/lateral_mpc/mpc.c b/selfdrive/controls/lib/lateral_mpc/mpc.c new file mode 100644 index 00000000000000..6823c554c2f644 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/mpc.c @@ -0,0 +1,100 @@ +#include "acado_common.h" +#include "acado_auxiliary_functions.h" + +#include + +#define NX ACADO_NX /* Number of differential state variables. */ +#define NXA ACADO_NXA /* Number of algebraic variables. */ +#define NU ACADO_NU /* Number of control inputs. */ +#define NOD ACADO_NOD /* Number of online data values. */ + +#define NY ACADO_NY /* Number of measurements/references on nodes 0..N - 1. */ +#define NYN ACADO_NYN /* Number of measurements/references on node N. */ + +#define N ACADO_N /* Number of intervals in the horizon. */ + +ACADOvariables acadoVariables; +ACADOworkspace acadoWorkspace; + +typedef struct { + double x, y, psi, delta, t; +} state_t; + + +typedef struct { + double x[N]; + double y[N]; + double psi[N]; + double delta[N]; +} log_t; + +void init(){ + acado_initializeSolver(); + int i; + + /* Initialize the states and controls. */ + for (i = 0; i < NX * (N + 1); ++i) acadoVariables.x[ i ] = 0.0; + for (i = 0; i < NU * N; ++i) acadoVariables.u[ i ] = 0.1; + + /* Initialize the measurements/reference. */ + for (i = 0; i < NY * N; ++i) acadoVariables.y[ i ] = 0.0; + for (i = 0; i < NYN; ++i) acadoVariables.yN[ i ] = 0.0; + + /* MPC: initialize the current state feedback. */ + for (i = 0; i < NX; ++i) acadoVariables.x0[ i ] = 0.0; +} + +void run_mpc(state_t * x0, log_t * solution, + double l_poly[4], double r_poly[4], double p_poly[4], + double l_prob, double r_prob, double p_prob, double curvature_factor, double v_ref, double lane_width){ + + int i; + + for (i = 0; i <= NOD * N; i+= NOD){ + acadoVariables.od[i] = curvature_factor; + acadoVariables.od[i+1] = v_ref; + + acadoVariables.od[i+2] = l_poly[0]; + acadoVariables.od[i+3] = l_poly[1]; + acadoVariables.od[i+4] = l_poly[2]; + acadoVariables.od[i+5] = l_poly[3]; + + acadoVariables.od[i+6] = r_poly[0]; + acadoVariables.od[i+7] = r_poly[1]; + acadoVariables.od[i+8] = r_poly[2]; + acadoVariables.od[i+9] = r_poly[3]; + + acadoVariables.od[i+10] = p_poly[0]; + acadoVariables.od[i+11] = p_poly[1]; + acadoVariables.od[i+12] = p_poly[2]; + acadoVariables.od[i+13] = p_poly[3]; + + + acadoVariables.od[i+14] = l_prob; + acadoVariables.od[i+15] = r_prob; + acadoVariables.od[i+16] = p_prob; + acadoVariables.od[i+17] = lane_width; + + } + + acadoVariables.x0[0] = x0->x; + acadoVariables.x0[1] = x0->y; + acadoVariables.x0[2] = x0->psi; + acadoVariables.x0[3] = x0->delta; + + + acado_preparationStep(); + acado_feedbackStep( ); + + acado_shiftStates(2, 0, 0); + acado_shiftControls( 0 ); + + for (i = 0; i <= N; i++){ + solution->x[i] = acadoVariables.x[i*NX]; + solution->y[i] = acadoVariables.x[i*NX+1]; + solution->psi[i] = acadoVariables.x[i*NX+2]; + solution->delta[i] = acadoVariables.x[i*NX+3]; + } + + return; +} diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.c b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.c new file mode 100644 index 00000000000000..6f0bb705c8a897 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.c @@ -0,0 +1,212 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * + */ + + +#include "acado_auxiliary_functions.h" + +#include + +real_t* acado_getVariablesX( ) +{ + return acadoVariables.x; +} + +real_t* acado_getVariablesU( ) +{ + return acadoVariables.u; +} + +#if ACADO_NY > 0 +real_t* acado_getVariablesY( ) +{ + return acadoVariables.y; +} +#endif + +#if ACADO_NYN > 0 +real_t* acado_getVariablesYN( ) +{ + return acadoVariables.yN; +} +#endif + +real_t* acado_getVariablesX0( ) +{ +#if ACADO_INITIAL_VALUE_FIXED + return acadoVariables.x0; +#else + return 0; +#endif +} + +/** Print differential variables. */ +void acado_printDifferentialVariables( ) +{ + int i, j; + printf("\nDifferential variables:\n[\n"); + for (i = 0; i < ACADO_N + 1; ++i) + { + for (j = 0; j < ACADO_NX; ++j) + printf("\t%e", acadoVariables.x[i * ACADO_NX + j]); + printf("\n"); + } + printf("]\n\n"); +} + +/** Print control variables. */ +void acado_printControlVariables( ) +{ + int i, j; + printf("\nControl variables:\n[\n"); + for (i = 0; i < ACADO_N; ++i) + { + for (j = 0; j < ACADO_NU; ++j) + printf("\t%e", acadoVariables.u[i * ACADO_NU + j]); + printf("\n"); + } + printf("]\n\n"); +} + +/** Print ACADO code generation notice. */ +void acado_printHeader( ) +{ + printf( + "\nACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.\n" + "Copyright (C) 2008-2015 by Boris Houska, Hans Joachim Ferreau,\n" + "Milan Vukov and Rien Quirynen, KU Leuven.\n" + ); + + printf( + "Developed within the Optimization in Engineering Center (OPTEC) under\n" + "supervision of Moritz Diehl. All rights reserved.\n\n" + "ACADO Toolkit is distributed under the terms of the GNU Lesser\n" + "General Public License 3 in the hope that it will be useful,\n" + "but WITHOUT ANY WARRANTY; without even the implied warranty of\n" + "MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the\n" + "GNU Lesser General Public License for more details.\n\n" + ); +} + +#if !(defined _DSPACE) +#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__) + +void acado_tic( acado_timer* t ) +{ + QueryPerformanceFrequency(&t->freq); + QueryPerformanceCounter(&t->tic); +} + +real_t acado_toc( acado_timer* t ) +{ + QueryPerformanceCounter(&t->toc); + return ((t->toc.QuadPart - t->tic.QuadPart) / (real_t)t->freq.QuadPart); +} + + +#elif (defined __APPLE__) + +void acado_tic( acado_timer* t ) +{ + /* read current clock cycles */ + t->tic = mach_absolute_time(); +} + +real_t acado_toc( acado_timer* t ) +{ + + uint64_t duration; /* elapsed time in clock cycles*/ + + t->toc = mach_absolute_time(); + duration = t->toc - t->tic; + + /*conversion from clock cycles to nanoseconds*/ + mach_timebase_info(&(t->tinfo)); + duration *= t->tinfo.numer; + duration /= t->tinfo.denom; + + return (real_t)duration / 1e9; +} + +#else + +#if __STDC_VERSION__ >= 199901L +/* C99 mode */ + +/* read current time */ +void acado_tic( acado_timer* t ) +{ + gettimeofday(&t->tic, 0); +} + +/* return time passed since last call to tic on this timer */ +real_t acado_toc( acado_timer* t ) +{ + struct timeval temp; + + gettimeofday(&t->toc, 0); + + if ((t->toc.tv_usec - t->tic.tv_usec) < 0) + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec - 1; + temp.tv_usec = 1000000 + t->toc.tv_usec - t->tic.tv_usec; + } + else + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec; + temp.tv_usec = t->toc.tv_usec - t->tic.tv_usec; + } + + return (real_t)temp.tv_sec + (real_t)temp.tv_usec / 1e6; +} + +#else +/* ANSI */ + +/* read current time */ +void acado_tic( acado_timer* t ) +{ + clock_gettime(CLOCK_MONOTONIC, &t->tic); +} + + +/* return time passed since last call to tic on this timer */ +real_t acado_toc( acado_timer* t ) +{ + struct timespec temp; + + clock_gettime(CLOCK_MONOTONIC, &t->toc); + + if ((t->toc.tv_nsec - t->tic.tv_nsec) < 0) + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec - 1; + temp.tv_nsec = 1000000000+t->toc.tv_nsec - t->tic.tv_nsec; + } + else + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec; + temp.tv_nsec = t->toc.tv_nsec - t->tic.tv_nsec; + } + + return (real_t)temp.tv_sec + (real_t)temp.tv_nsec / 1e9; +} + +#endif /* __STDC_VERSION__ >= 199901L */ + +#endif /* (defined _WIN32 || _WIN64) */ + +#endif diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.h b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.h new file mode 100644 index 00000000000000..b1be0a661c0125 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.h @@ -0,0 +1,138 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * + */ + + +#ifndef ACADO_AUXILIARY_FUNCTIONS_H +#define ACADO_AUXILIARY_FUNCTIONS_H + +#include "acado_common.h" + +#ifndef __MATLAB__ +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +/** Get pointer to the matrix with differential variables. */ +real_t* acado_getVariablesX( ); + +/** Get pointer to the matrix with control variables. */ +real_t* acado_getVariablesU( ); + +#if ACADO_NY > 0 +/** Get pointer to the matrix with references/measurements. */ +real_t* acado_getVariablesY( ); +#endif + +#if ACADO_NYN > 0 +/** Get pointer to the vector with references/measurement on the last node. */ +real_t* acado_getVariablesYN( ); +#endif + +/** Get pointer to the current state feedback vector. Only applicable for NMPC. */ +real_t* acado_getVariablesX0( ); + +/** Print differential variables. */ +void acado_printDifferentialVariables( ); + +/** Print control variables. */ +void acado_printControlVariables( ); + +/** Print ACADO code generation notice. */ +void acado_printHeader( ); + +/* + * A huge thanks goes to Alexander Domahidi from ETHZ, Switzerland, for + * providing us with the following timing routines. + */ + +#if !(defined _DSPACE) +#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__) + +/* Use Windows QueryPerformanceCounter for timing. */ +#include + +/** A structure for keeping internal timer data. */ +typedef struct acado_timer_ +{ + LARGE_INTEGER tic; + LARGE_INTEGER toc; + LARGE_INTEGER freq; +} acado_timer; + + +#elif (defined __APPLE__) + +#include "unistd.h" +#include + +/** A structure for keeping internal timer data. */ +typedef struct acado_timer_ +{ + uint64_t tic; + uint64_t toc; + mach_timebase_info_data_t tinfo; +} acado_timer; + +#else + +/* Use POSIX clock_gettime() for timing on non-Windows machines. */ +#include + +#if __STDC_VERSION__ >= 199901L +/* C99 mode of operation. */ + +#include +#include + +typedef struct acado_timer_ +{ + struct timeval tic; + struct timeval toc; +} acado_timer; + +#else +/* ANSI C */ + +/** A structure for keeping internal timer data. */ +typedef struct acado_timer_ +{ + struct timespec tic; + struct timespec toc; +} acado_timer; + +#endif /* __STDC_VERSION__ >= 199901L */ + +#endif /* (defined _WIN32 || defined _WIN64) */ + +/** A function for measurement of the current time. */ +void acado_tic( acado_timer* t ); + +/** A function which returns the elapsed time. */ +real_t acado_toc( acado_timer* t ); + +#endif + +#ifndef __MATLAB__ +#ifdef __cplusplus +} /* extern "C" */ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +#endif /* ACADO_AUXILIARY_FUNCTIONS_H */ diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_common.h b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_common.h new file mode 100644 index 00000000000000..a183304f0181b4 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_common.h @@ -0,0 +1,349 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * + */ + + +#ifndef ACADO_COMMON_H +#define ACADO_COMMON_H + +#include +#include + +#ifndef __MATLAB__ +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +/** \defgroup ACADO ACADO CGT generated module. */ +/** @{ */ + +/** qpOASES QP solver indicator. */ +#define ACADO_QPOASES 0 +#define ACADO_QPOASES3 1 +/** FORCES QP solver indicator.*/ +#define ACADO_FORCES 2 +/** qpDUNES QP solver indicator.*/ +#define ACADO_QPDUNES 3 +/** HPMPC QP solver indicator. */ +#define ACADO_HPMPC 4 +#define ACADO_GENERIC 5 + +/** Indicator for determining the QP solver used by the ACADO solver code. */ +#define ACADO_QP_SOLVER ACADO_QPOASES + +#include "acado_qpoases_interface.hpp" + + +/* + * Common definitions + */ +/** User defined block based condensing. */ +#define ACADO_BLOCK_CONDENSING 0 +/** Compute covariance matrix of the last state estimate. */ +#define ACADO_COMPUTE_COVARIANCE_MATRIX 0 +/** Flag indicating whether constraint values are hard-coded or not. */ +#define ACADO_HARDCODED_CONSTRAINT_VALUES 1 +/** Indicator for fixed initial state. */ +#define ACADO_INITIAL_STATE_FIXED 1 +/** Number of control/estimation intervals. */ +#define ACADO_N 50 +/** Number of online data values. */ +#define ACADO_NOD 18 +/** Number of path constraints. */ +#define ACADO_NPAC 0 +/** Number of control variables. */ +#define ACADO_NU 1 +/** Number of differential variables. */ +#define ACADO_NX 4 +/** Number of algebraic variables. */ +#define ACADO_NXA 0 +/** Number of differential derivative variables. */ +#define ACADO_NXD 0 +/** Number of references/measurements per node on the first N nodes. */ +#define ACADO_NY 5 +/** Number of references/measurements on the last (N + 1)st node. */ +#define ACADO_NYN 4 +/** Total number of QP optimization variables. */ +#define ACADO_QP_NV 54 +/** Number of integration steps per shooting interval. */ +#define ACADO_RK_NIS 5 +/** Number of Runge-Kutta stages per integration step. */ +#define ACADO_RK_NSTAGES 4 +/** Providing interface for arrival cost. */ +#define ACADO_USE_ARRIVAL_COST 0 +/** Indicator for usage of non-hard-coded linear terms in the objective. */ +#define ACADO_USE_LINEAR_TERMS 0 +/** Indicator for type of fixed weighting matrices. */ +#define ACADO_WEIGHTING_MATRICES_TYPE 0 + + +/* + * Globally used structure definitions + */ + +/** The structure containing the user data. + * + * Via this structure the user "communicates" with the solver code. + */ +typedef struct ACADOvariables_ +{ +int dummy; +/** Matrix of size: 51 x 4 (row major format) + * + * Matrix containing 51 differential variable vectors. + */ +real_t x[ 204 ]; + +/** Column vector of size: 50 + * + * Matrix containing 50 control variable vectors. + */ +real_t u[ 50 ]; + +/** Matrix of size: 51 x 18 (row major format) + * + * Matrix containing 51 online data vectors. + */ +real_t od[ 918 ]; + +/** Column vector of size: 250 + * + * Matrix containing 50 reference/measurement vectors of size 5 for first 50 nodes. + */ +real_t y[ 250 ]; + +/** Column vector of size: 4 + * + * Reference/measurement vector for the 51. node. + */ +real_t yN[ 4 ]; + +/** Column vector of size: 4 + * + * Current state feedback vector. + */ +real_t x0[ 4 ]; + + +} ACADOvariables; + +/** Private workspace used by the auto-generated code. + * + * Data members of this structure are private to the solver. + * In other words, the user code should not modify values of this + * structure. + */ +typedef struct ACADOworkspace_ +{ +/** Column vector of size: 14 */ +real_t rhs_aux[ 14 ]; + +real_t rk_ttt; + +/** Row vector of size: 43 */ +real_t rk_xxx[ 43 ]; + +/** Matrix of size: 4 x 24 (row major format) */ +real_t rk_kkk[ 96 ]; + +/** Row vector of size: 43 */ +real_t state[ 43 ]; + +/** Column vector of size: 200 */ +real_t d[ 200 ]; + +/** Column vector of size: 250 */ +real_t Dy[ 250 ]; + +/** Column vector of size: 4 */ +real_t DyN[ 4 ]; + +/** Matrix of size: 200 x 4 (row major format) */ +real_t evGx[ 800 ]; + +/** Column vector of size: 200 */ +real_t evGu[ 200 ]; + +/** Column vector of size: 19 */ +real_t objAuxVar[ 19 ]; + +/** Row vector of size: 23 */ +real_t objValueIn[ 23 ]; + +/** Row vector of size: 30 */ +real_t objValueOut[ 30 ]; + +/** Matrix of size: 200 x 4 (row major format) */ +real_t Q1[ 800 ]; + +/** Matrix of size: 200 x 5 (row major format) */ +real_t Q2[ 1000 ]; + +/** Column vector of size: 50 */ +real_t R1[ 50 ]; + +/** Matrix of size: 50 x 5 (row major format) */ +real_t R2[ 250 ]; + +/** Matrix of size: 4 x 4 (row major format) */ +real_t QN1[ 16 ]; + +/** Matrix of size: 4 x 4 (row major format) */ +real_t QN2[ 16 ]; + +/** Column vector of size: 4 */ +real_t Dx0[ 4 ]; + +/** Matrix of size: 4 x 4 (row major format) */ +real_t T[ 16 ]; + +/** Column vector of size: 5100 */ +real_t E[ 5100 ]; + +/** Column vector of size: 5100 */ +real_t QE[ 5100 ]; + +/** Matrix of size: 200 x 4 (row major format) */ +real_t QGx[ 800 ]; + +/** Column vector of size: 200 */ +real_t Qd[ 200 ]; + +/** Column vector of size: 204 */ +real_t QDy[ 204 ]; + +/** Matrix of size: 50 x 4 (row major format) */ +real_t H10[ 200 ]; + +/** Matrix of size: 54 x 54 (row major format) */ +real_t H[ 2916 ]; + +/** Matrix of size: 100 x 54 (row major format) */ +real_t A[ 5400 ]; + +/** Column vector of size: 54 */ +real_t g[ 54 ]; + +/** Column vector of size: 54 */ +real_t lb[ 54 ]; + +/** Column vector of size: 54 */ +real_t ub[ 54 ]; + +/** Column vector of size: 100 */ +real_t lbA[ 100 ]; + +/** Column vector of size: 100 */ +real_t ubA[ 100 ]; + +/** Column vector of size: 54 */ +real_t x[ 54 ]; + +/** Column vector of size: 154 */ +real_t y[ 154 ]; + + +} ACADOworkspace; + +/* + * Forward function declarations. + */ + + +/** Performs the integration and sensitivity propagation for one shooting interval. + * + * \param rk_eta Working array to pass the input values and return the results. + * \param resetIntegrator The internal memory of the integrator can be reset. + * + * \return Status code of the integrator. + */ +int acado_integrate( real_t* const rk_eta, int resetIntegrator ); + +/** Export of an ACADO symbolic function. + * + * \param in Input to the exported function. + * \param out Output of the exported function. + */ +void acado_rhs_forw(const real_t* in, real_t* out); + +/** Preparation step of the RTI scheme. + * + * \return Status of the integration module. =0: OK, otherwise the error code. + */ +int acado_preparationStep( ); + +/** Feedback/estimation step of the RTI scheme. + * + * \return Status code of the qpOASES QP solver. + */ +int acado_feedbackStep( ); + +/** Solver initialization. Must be called once before any other function call. + * + * \return =0: OK, otherwise an error code of a QP solver. + */ +int acado_initializeSolver( ); + +/** Initialize shooting nodes by a forward simulation starting from the first node. + */ +void acado_initializeNodesByForwardSimulation( ); + +/** Shift differential variables vector by one interval. + * + * \param strategy Shifting strategy: 1. Initialize node 51 with xEnd. 2. Initialize node 51 by forward simulation. + * \param xEnd Value for the x vector on the last node. If =0 the old value is used. + * \param uEnd Value for the u vector on the second to last node. If =0 the old value is used. + */ +void acado_shiftStates( int strategy, real_t* const xEnd, real_t* const uEnd ); + +/** Shift controls vector by one interval. + * + * \param uEnd Value for the u vector on the second to last node. If =0 the old value is used. + */ +void acado_shiftControls( real_t* const uEnd ); + +/** Get the KKT tolerance of the current iterate. + * + * \return The KKT tolerance value. + */ +real_t acado_getKKT( ); + +/** Calculate the objective value. + * + * \return Value of the objective function. + */ +real_t acado_getObjective( ); + + +/* + * Extern declarations. + */ + +extern ACADOworkspace acadoWorkspace; +extern ACADOvariables acadoVariables; + +/** @} */ + +#ifndef __MATLAB__ +#ifdef __cplusplus +} /* extern "C" */ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +#endif /* ACADO_COMMON_H */ diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_integrator.c b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_integrator.c new file mode 100644 index 00000000000000..f243d0ffa28169 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_integrator.c @@ -0,0 +1,252 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * + */ + + +#include "acado_common.h" + + +void acado_rhs_forw(const real_t* in, real_t* out) +{ +const real_t* xd = in; +const real_t* u = in + 24; +const real_t* od = in + 25; +/* Vector of auxiliary variables; number of elements: 14. */ +real_t* a = acadoWorkspace.rhs_aux; + +/* Compute intermediate quantities: */ +a[0] = (cos(xd[2])); +a[1] = (sin(xd[2])); +a[2] = ((real_t)(-1.0000000000000000e+00)*(sin(xd[2]))); +a[3] = (xd[12]*a[2]); +a[4] = (xd[13]*a[2]); +a[5] = (xd[14]*a[2]); +a[6] = (xd[15]*a[2]); +a[7] = (cos(xd[2])); +a[8] = (xd[12]*a[7]); +a[9] = (xd[13]*a[7]); +a[10] = (xd[14]*a[7]); +a[11] = (xd[15]*a[7]); +a[12] = (xd[22]*a[2]); +a[13] = (xd[22]*a[7]); + +/* Compute outputs: */ +out[0] = (od[1]*a[0]); +out[1] = (od[1]*a[1]); +out[2] = ((od[1]*xd[3])*od[0]); +out[3] = u[0]; +out[4] = (od[1]*a[3]); +out[5] = (od[1]*a[4]); +out[6] = (od[1]*a[5]); +out[7] = (od[1]*a[6]); +out[8] = (od[1]*a[8]); +out[9] = (od[1]*a[9]); +out[10] = (od[1]*a[10]); +out[11] = (od[1]*a[11]); +out[12] = ((od[1]*xd[16])*od[0]); +out[13] = ((od[1]*xd[17])*od[0]); +out[14] = ((od[1]*xd[18])*od[0]); +out[15] = ((od[1]*xd[19])*od[0]); +out[16] = (real_t)(0.0000000000000000e+00); +out[17] = (real_t)(0.0000000000000000e+00); +out[18] = (real_t)(0.0000000000000000e+00); +out[19] = (real_t)(0.0000000000000000e+00); +out[20] = (od[1]*a[12]); +out[21] = (od[1]*a[13]); +out[22] = ((od[1]*xd[23])*od[0]); +out[23] = (real_t)(1.0000000000000000e+00); +} + +/* Fixed step size:0.01 */ +int acado_integrate( real_t* const rk_eta, int resetIntegrator ) +{ +int error; + +int run1; +acadoWorkspace.rk_ttt = 0.0000000000000000e+00; +rk_eta[4] = 1.0000000000000000e+00; +rk_eta[5] = 0.0000000000000000e+00; +rk_eta[6] = 0.0000000000000000e+00; +rk_eta[7] = 0.0000000000000000e+00; +rk_eta[8] = 0.0000000000000000e+00; +rk_eta[9] = 1.0000000000000000e+00; +rk_eta[10] = 0.0000000000000000e+00; +rk_eta[11] = 0.0000000000000000e+00; +rk_eta[12] = 0.0000000000000000e+00; +rk_eta[13] = 0.0000000000000000e+00; +rk_eta[14] = 1.0000000000000000e+00; +rk_eta[15] = 0.0000000000000000e+00; +rk_eta[16] = 0.0000000000000000e+00; +rk_eta[17] = 0.0000000000000000e+00; +rk_eta[18] = 0.0000000000000000e+00; +rk_eta[19] = 1.0000000000000000e+00; +rk_eta[20] = 0.0000000000000000e+00; +rk_eta[21] = 0.0000000000000000e+00; +rk_eta[22] = 0.0000000000000000e+00; +rk_eta[23] = 0.0000000000000000e+00; +acadoWorkspace.rk_xxx[24] = rk_eta[24]; +acadoWorkspace.rk_xxx[25] = rk_eta[25]; +acadoWorkspace.rk_xxx[26] = rk_eta[26]; +acadoWorkspace.rk_xxx[27] = rk_eta[27]; +acadoWorkspace.rk_xxx[28] = rk_eta[28]; +acadoWorkspace.rk_xxx[29] = rk_eta[29]; +acadoWorkspace.rk_xxx[30] = rk_eta[30]; +acadoWorkspace.rk_xxx[31] = rk_eta[31]; +acadoWorkspace.rk_xxx[32] = rk_eta[32]; +acadoWorkspace.rk_xxx[33] = rk_eta[33]; +acadoWorkspace.rk_xxx[34] = rk_eta[34]; +acadoWorkspace.rk_xxx[35] = rk_eta[35]; +acadoWorkspace.rk_xxx[36] = rk_eta[36]; +acadoWorkspace.rk_xxx[37] = rk_eta[37]; +acadoWorkspace.rk_xxx[38] = rk_eta[38]; +acadoWorkspace.rk_xxx[39] = rk_eta[39]; +acadoWorkspace.rk_xxx[40] = rk_eta[40]; +acadoWorkspace.rk_xxx[41] = rk_eta[41]; +acadoWorkspace.rk_xxx[42] = rk_eta[42]; + +for (run1 = 0; run1 < 5; ++run1) +{ +acadoWorkspace.rk_xxx[0] = + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + rk_eta[23]; +acado_rhs_forw( acadoWorkspace.rk_xxx, acadoWorkspace.rk_kkk ); +acadoWorkspace.rk_xxx[0] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[0] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[1] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[2] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[3] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[4] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[5] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[6] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[7] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[8] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[9] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[10] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[11] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[12] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[13] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[14] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[15] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[16] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[17] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[18] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[19] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[20] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[21] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[22] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[23] + rk_eta[23]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 24 ]) ); +acadoWorkspace.rk_xxx[0] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[24] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[25] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[26] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[27] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[28] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[29] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[30] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[31] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[32] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[33] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[34] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[35] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[36] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[37] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[38] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[39] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[40] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[41] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[42] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[43] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[44] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[45] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[46] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[47] + rk_eta[23]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 48 ]) ); +acadoWorkspace.rk_xxx[0] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[48] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[49] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[50] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[51] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[52] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[53] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[54] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[55] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[56] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[57] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[58] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[59] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[60] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[61] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[62] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[63] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[64] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[65] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[66] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[67] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[68] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[69] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[70] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[71] + rk_eta[23]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 72 ]) ); +rk_eta[0] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[0] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[24] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[48] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[72]; +rk_eta[1] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[1] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[25] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[49] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[73]; +rk_eta[2] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[2] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[26] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[50] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[74]; +rk_eta[3] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[3] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[27] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[51] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[75]; +rk_eta[4] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[4] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[28] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[52] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[76]; +rk_eta[5] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[5] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[29] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[53] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[77]; +rk_eta[6] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[6] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[30] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[54] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[78]; +rk_eta[7] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[7] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[31] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[55] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[79]; +rk_eta[8] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[8] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[32] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[56] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[80]; +rk_eta[9] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[9] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[33] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[57] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[81]; +rk_eta[10] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[10] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[34] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[58] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[82]; +rk_eta[11] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[11] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[35] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[59] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[83]; +rk_eta[12] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[12] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[36] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[60] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[84]; +rk_eta[13] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[13] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[37] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[61] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[85]; +rk_eta[14] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[14] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[38] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[62] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[86]; +rk_eta[15] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[15] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[39] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[63] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[87]; +rk_eta[16] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[16] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[40] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[64] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[88]; +rk_eta[17] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[17] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[41] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[65] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[89]; +rk_eta[18] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[18] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[42] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[66] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[90]; +rk_eta[19] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[19] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[43] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[67] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[91]; +rk_eta[20] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[20] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[44] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[68] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[92]; +rk_eta[21] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[21] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[45] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[69] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[93]; +rk_eta[22] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[22] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[46] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[70] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[94]; +rk_eta[23] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[23] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[47] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[71] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[95]; +acadoWorkspace.rk_ttt += 2.0000000000000001e-01; +} +error = 0; +return error; +} + diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.cpp b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.cpp new file mode 100644 index 00000000000000..09c7da96cad333 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.cpp @@ -0,0 +1,70 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * + */ + + +extern "C" +{ +#include "acado_common.h" +} + +#include "INCLUDE/QProblem.hpp" + +#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1 +#include "INCLUDE/EXTRAS/SolutionAnalysis.hpp" +#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */ + +static int acado_nWSR; + + + +#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1 +static SolutionAnalysis acado_sa; +#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */ + +int acado_solve( void ) +{ + acado_nWSR = QPOASES_NWSRMAX; + + QProblem qp(54, 100); + + returnValue retVal = qp.init(acadoWorkspace.H, acadoWorkspace.g, acadoWorkspace.A, acadoWorkspace.lb, acadoWorkspace.ub, acadoWorkspace.lbA, acadoWorkspace.ubA, acado_nWSR, acadoWorkspace.y); + + qp.getPrimalSolution( acadoWorkspace.x ); + qp.getDualSolution( acadoWorkspace.y ); + +#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1 + + if (retVal != SUCCESSFUL_RETURN) + return (int)retVal; + + retVal = acado_sa.getHessianInverse( &qp,var ); + +#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */ + + return (int)retVal; +} + +int acado_getNWSR( void ) +{ + return acado_nWSR; +} + +const char* acado_getErrorString( int error ) +{ + return MessageHandling::getErrorString( error ); +} diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.hpp b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.hpp new file mode 100644 index 00000000000000..d14523d05a1a0d --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.hpp @@ -0,0 +1,65 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * + */ + + +#ifndef QPOASES_HEADER +#define QPOASES_HEADER + +#ifdef PC_DEBUG +#include +#endif /* PC_DEBUG */ + +#include + +#ifdef __cplusplus +#define EXTERNC extern "C" +#else +#define EXTERNC +#endif + +/* + * A set of options for qpOASES + */ + +/** Maximum number of optimization variables. */ +#define QPOASES_NVMAX 54 +/** Maximum number of constraints. */ +#define QPOASES_NCMAX 100 +/** Maximum number of working set recalculations. */ +#define QPOASES_NWSRMAX 462 +/** Print level for qpOASES. */ +#define QPOASES_PRINTLEVEL PL_NONE +/** The value of EPS */ +#define QPOASES_EPS 2.221e-16 +/** Internally used floating point type */ +typedef double real_t; + +/* + * Forward function declarations + */ + +/** A function that calls the QP solver */ +EXTERNC int acado_solve( void ); + +/** Get the number of active set changes */ +EXTERNC int acado_getNWSR( void ); + +/** Get the error string. */ +const char* acado_getErrorString( int error ); + +#endif /* QPOASES_HEADER */ diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c new file mode 100644 index 00000000000000..963a36430a9bb7 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c @@ -0,0 +1,1981 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * + */ + + +#include "acado_common.h" + + + + +/******************************************************************************/ +/* */ +/* ACADO code generation */ +/* */ +/******************************************************************************/ + + +int acado_modelSimulation( ) +{ +int ret; + +int lRun1; +ret = 0; +for (lRun1 = 0; lRun1 < 50; ++lRun1) +{ +acadoWorkspace.state[0] = acadoVariables.x[lRun1 * 4]; +acadoWorkspace.state[1] = acadoVariables.x[lRun1 * 4 + 1]; +acadoWorkspace.state[2] = acadoVariables.x[lRun1 * 4 + 2]; +acadoWorkspace.state[3] = acadoVariables.x[lRun1 * 4 + 3]; + +acadoWorkspace.state[24] = acadoVariables.u[lRun1]; +acadoWorkspace.state[25] = acadoVariables.od[lRun1 * 18]; +acadoWorkspace.state[26] = acadoVariables.od[lRun1 * 18 + 1]; +acadoWorkspace.state[27] = acadoVariables.od[lRun1 * 18 + 2]; +acadoWorkspace.state[28] = acadoVariables.od[lRun1 * 18 + 3]; +acadoWorkspace.state[29] = acadoVariables.od[lRun1 * 18 + 4]; +acadoWorkspace.state[30] = acadoVariables.od[lRun1 * 18 + 5]; +acadoWorkspace.state[31] = acadoVariables.od[lRun1 * 18 + 6]; +acadoWorkspace.state[32] = acadoVariables.od[lRun1 * 18 + 7]; +acadoWorkspace.state[33] = acadoVariables.od[lRun1 * 18 + 8]; +acadoWorkspace.state[34] = acadoVariables.od[lRun1 * 18 + 9]; +acadoWorkspace.state[35] = acadoVariables.od[lRun1 * 18 + 10]; +acadoWorkspace.state[36] = acadoVariables.od[lRun1 * 18 + 11]; +acadoWorkspace.state[37] = acadoVariables.od[lRun1 * 18 + 12]; +acadoWorkspace.state[38] = acadoVariables.od[lRun1 * 18 + 13]; +acadoWorkspace.state[39] = acadoVariables.od[lRun1 * 18 + 14]; +acadoWorkspace.state[40] = acadoVariables.od[lRun1 * 18 + 15]; +acadoWorkspace.state[41] = acadoVariables.od[lRun1 * 18 + 16]; +acadoWorkspace.state[42] = acadoVariables.od[lRun1 * 18 + 17]; + +ret = acado_integrate(acadoWorkspace.state, 1); + +acadoWorkspace.d[lRun1 * 4] = acadoWorkspace.state[0] - acadoVariables.x[lRun1 * 4 + 4]; +acadoWorkspace.d[lRun1 * 4 + 1] = acadoWorkspace.state[1] - acadoVariables.x[lRun1 * 4 + 5]; +acadoWorkspace.d[lRun1 * 4 + 2] = acadoWorkspace.state[2] - acadoVariables.x[lRun1 * 4 + 6]; +acadoWorkspace.d[lRun1 * 4 + 3] = acadoWorkspace.state[3] - acadoVariables.x[lRun1 * 4 + 7]; + +acadoWorkspace.evGx[lRun1 * 16] = acadoWorkspace.state[4]; +acadoWorkspace.evGx[lRun1 * 16 + 1] = acadoWorkspace.state[5]; +acadoWorkspace.evGx[lRun1 * 16 + 2] = acadoWorkspace.state[6]; +acadoWorkspace.evGx[lRun1 * 16 + 3] = acadoWorkspace.state[7]; +acadoWorkspace.evGx[lRun1 * 16 + 4] = acadoWorkspace.state[8]; +acadoWorkspace.evGx[lRun1 * 16 + 5] = acadoWorkspace.state[9]; +acadoWorkspace.evGx[lRun1 * 16 + 6] = acadoWorkspace.state[10]; +acadoWorkspace.evGx[lRun1 * 16 + 7] = acadoWorkspace.state[11]; +acadoWorkspace.evGx[lRun1 * 16 + 8] = acadoWorkspace.state[12]; +acadoWorkspace.evGx[lRun1 * 16 + 9] = acadoWorkspace.state[13]; +acadoWorkspace.evGx[lRun1 * 16 + 10] = acadoWorkspace.state[14]; +acadoWorkspace.evGx[lRun1 * 16 + 11] = acadoWorkspace.state[15]; +acadoWorkspace.evGx[lRun1 * 16 + 12] = acadoWorkspace.state[16]; +acadoWorkspace.evGx[lRun1 * 16 + 13] = acadoWorkspace.state[17]; +acadoWorkspace.evGx[lRun1 * 16 + 14] = acadoWorkspace.state[18]; +acadoWorkspace.evGx[lRun1 * 16 + 15] = acadoWorkspace.state[19]; + +acadoWorkspace.evGu[lRun1 * 4] = acadoWorkspace.state[20]; +acadoWorkspace.evGu[lRun1 * 4 + 1] = acadoWorkspace.state[21]; +acadoWorkspace.evGu[lRun1 * 4 + 2] = acadoWorkspace.state[22]; +acadoWorkspace.evGu[lRun1 * 4 + 3] = acadoWorkspace.state[23]; +} +return ret; +} + +void acado_evaluateLSQ(const real_t* in, real_t* out) +{ +const real_t* xd = in; +const real_t* u = in + 4; +const real_t* od = in + 5; +/* Vector of auxiliary variables; number of elements: 19. */ +real_t* a = acadoWorkspace.objAuxVar; + +/* Compute intermediate quantities: */ +a[0] = (exp(((real_t)(0.0000000000000000e+00)-(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-xd[1])))); +a[1] = (exp((((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])-xd[1]))); +a[2] = (atan(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]))); +a[3] = (atan(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]))); +a[4] = (atan(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]))); +a[5] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[6] = (exp(((real_t)(0.0000000000000000e+00)-(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-xd[1])))); +a[7] = (((real_t)(0.0000000000000000e+00)-(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))*a[6]); +a[8] = (((real_t)(0.0000000000000000e+00)-((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)))*a[6]); +a[9] = (exp((((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])-xd[1]))); +a[10] = ((((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8])*a[9]); +a[11] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[9]); +a[12] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]),2)))); +a[13] = ((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[2])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[3]))*a[12]); +a[14] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]),2)))); +a[15] = ((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[6])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[7]))*a[14]); +a[16] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[17] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]),2)))); +a[18] = ((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[10])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[11]))*a[17]); + +/* Compute outputs: */ +out[0] = ((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-xd[1]); +out[1] = (od[14]*a[0]); +out[2] = (od[15]*a[1]); +out[3] = ((od[1]+(real_t)(1.0000000000000000e+00))*((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[2])+(od[15]*a[3])))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[4]))-xd[2])); +out[4] = ((od[1]+(real_t)(1.0000000000000000e+00))*u[0]); +out[5] = (((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[5])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12]))); +out[6] = ((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)); +out[7] = (real_t)(0.0000000000000000e+00); +out[8] = (real_t)(0.0000000000000000e+00); +out[9] = (od[14]*a[7]); +out[10] = (od[14]*a[8]); +out[11] = (real_t)(0.0000000000000000e+00); +out[12] = (real_t)(0.0000000000000000e+00); +out[13] = (od[15]*a[10]); +out[14] = (od[15]*a[11]); +out[15] = (real_t)(0.0000000000000000e+00); +out[16] = (real_t)(0.0000000000000000e+00); +out[17] = ((od[1]+(real_t)(1.0000000000000000e+00))*(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[13])+(od[15]*a[15])))*a[16])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[18]))); +out[18] = (real_t)(0.0000000000000000e+00); +out[19] = ((od[1]+(real_t)(1.0000000000000000e+00))*((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))); +out[20] = (real_t)(0.0000000000000000e+00); +out[21] = (real_t)(0.0000000000000000e+00); +out[22] = (real_t)(0.0000000000000000e+00); +out[23] = (real_t)(0.0000000000000000e+00); +out[24] = (real_t)(0.0000000000000000e+00); +out[25] = (real_t)(0.0000000000000000e+00); +out[26] = (real_t)(0.0000000000000000e+00); +out[27] = (real_t)(0.0000000000000000e+00); +out[28] = (real_t)(0.0000000000000000e+00); +out[29] = (od[1]+(real_t)(1.0000000000000000e+00)); +} + +void acado_evaluateLSQEndTerm(const real_t* in, real_t* out) +{ +const real_t* xd = in; +const real_t* od = in + 4; +/* Vector of auxiliary variables; number of elements: 19. */ +real_t* a = acadoWorkspace.objAuxVar; + +/* Compute intermediate quantities: */ +a[0] = (exp(((real_t)(0.0000000000000000e+00)-(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-xd[1])))); +a[1] = (exp((((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])-xd[1]))); +a[2] = (atan(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]))); +a[3] = (atan(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]))); +a[4] = (atan(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]))); +a[5] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[6] = (exp(((real_t)(0.0000000000000000e+00)-(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-xd[1])))); +a[7] = (((real_t)(0.0000000000000000e+00)-(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))*a[6]); +a[8] = (((real_t)(0.0000000000000000e+00)-((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)))*a[6]); +a[9] = (exp((((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])-xd[1]))); +a[10] = ((((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8])*a[9]); +a[11] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[9]); +a[12] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]),2)))); +a[13] = ((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[2])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[3]))*a[12]); +a[14] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]),2)))); +a[15] = ((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[6])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[7]))*a[14]); +a[16] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[17] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]),2)))); +a[18] = ((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[10])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[11]))*a[17]); + +/* Compute outputs: */ +out[0] = ((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-xd[1]); +out[1] = (od[14]*a[0]); +out[2] = (od[15]*a[1]); +out[3] = ((((real_t)(2.0000000000000000e+00)*od[1])+(real_t)(1.0000000000000000e+00))*((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[2])+(od[15]*a[3])))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[4]))-xd[2])); +out[4] = (((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[5])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12]))); +out[5] = ((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)); +out[6] = (real_t)(0.0000000000000000e+00); +out[7] = (real_t)(0.0000000000000000e+00); +out[8] = (od[14]*a[7]); +out[9] = (od[14]*a[8]); +out[10] = (real_t)(0.0000000000000000e+00); +out[11] = (real_t)(0.0000000000000000e+00); +out[12] = (od[15]*a[10]); +out[13] = (od[15]*a[11]); +out[14] = (real_t)(0.0000000000000000e+00); +out[15] = (real_t)(0.0000000000000000e+00); +out[16] = ((((real_t)(2.0000000000000000e+00)*od[1])+(real_t)(1.0000000000000000e+00))*(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[13])+(od[15]*a[15])))*a[16])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[18]))); +out[17] = (real_t)(0.0000000000000000e+00); +out[18] = ((((real_t)(2.0000000000000000e+00)*od[1])+(real_t)(1.0000000000000000e+00))*((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))); +out[19] = (real_t)(0.0000000000000000e+00); +} + +void acado_setObjQ1Q2( real_t* const tmpFx, real_t* const tmpQ1, real_t* const tmpQ2 ) +{ +tmpQ2[0] = + tmpFx[0]; +tmpQ2[1] = + tmpFx[4]; +tmpQ2[2] = + tmpFx[8]; +tmpQ2[3] = + tmpFx[12]; +tmpQ2[4] = + tmpFx[16]; +tmpQ2[5] = + tmpFx[1]; +tmpQ2[6] = + tmpFx[5]; +tmpQ2[7] = + tmpFx[9]; +tmpQ2[8] = + tmpFx[13]; +tmpQ2[9] = + tmpFx[17]; +tmpQ2[10] = + tmpFx[2]; +tmpQ2[11] = + tmpFx[6]; +tmpQ2[12] = + tmpFx[10]; +tmpQ2[13] = + tmpFx[14]; +tmpQ2[14] = + tmpFx[18]; +tmpQ2[15] = + tmpFx[3]; +tmpQ2[16] = + tmpFx[7]; +tmpQ2[17] = + tmpFx[11]; +tmpQ2[18] = + tmpFx[15]; +tmpQ2[19] = + tmpFx[19]; +tmpQ1[0] = + tmpQ2[0]*tmpFx[0] + tmpQ2[1]*tmpFx[4] + tmpQ2[2]*tmpFx[8] + tmpQ2[3]*tmpFx[12] + tmpQ2[4]*tmpFx[16]; +tmpQ1[1] = + tmpQ2[0]*tmpFx[1] + tmpQ2[1]*tmpFx[5] + tmpQ2[2]*tmpFx[9] + tmpQ2[3]*tmpFx[13] + tmpQ2[4]*tmpFx[17]; +tmpQ1[2] = + tmpQ2[0]*tmpFx[2] + tmpQ2[1]*tmpFx[6] + tmpQ2[2]*tmpFx[10] + tmpQ2[3]*tmpFx[14] + tmpQ2[4]*tmpFx[18]; +tmpQ1[3] = + tmpQ2[0]*tmpFx[3] + tmpQ2[1]*tmpFx[7] + tmpQ2[2]*tmpFx[11] + tmpQ2[3]*tmpFx[15] + tmpQ2[4]*tmpFx[19]; +tmpQ1[4] = + tmpQ2[5]*tmpFx[0] + tmpQ2[6]*tmpFx[4] + tmpQ2[7]*tmpFx[8] + tmpQ2[8]*tmpFx[12] + tmpQ2[9]*tmpFx[16]; +tmpQ1[5] = + tmpQ2[5]*tmpFx[1] + tmpQ2[6]*tmpFx[5] + tmpQ2[7]*tmpFx[9] + tmpQ2[8]*tmpFx[13] + tmpQ2[9]*tmpFx[17]; +tmpQ1[6] = + tmpQ2[5]*tmpFx[2] + tmpQ2[6]*tmpFx[6] + tmpQ2[7]*tmpFx[10] + tmpQ2[8]*tmpFx[14] + tmpQ2[9]*tmpFx[18]; +tmpQ1[7] = + tmpQ2[5]*tmpFx[3] + tmpQ2[6]*tmpFx[7] + tmpQ2[7]*tmpFx[11] + tmpQ2[8]*tmpFx[15] + tmpQ2[9]*tmpFx[19]; +tmpQ1[8] = + tmpQ2[10]*tmpFx[0] + tmpQ2[11]*tmpFx[4] + tmpQ2[12]*tmpFx[8] + tmpQ2[13]*tmpFx[12] + tmpQ2[14]*tmpFx[16]; +tmpQ1[9] = + tmpQ2[10]*tmpFx[1] + tmpQ2[11]*tmpFx[5] + tmpQ2[12]*tmpFx[9] + tmpQ2[13]*tmpFx[13] + tmpQ2[14]*tmpFx[17]; +tmpQ1[10] = + tmpQ2[10]*tmpFx[2] + tmpQ2[11]*tmpFx[6] + tmpQ2[12]*tmpFx[10] + tmpQ2[13]*tmpFx[14] + tmpQ2[14]*tmpFx[18]; +tmpQ1[11] = + tmpQ2[10]*tmpFx[3] + tmpQ2[11]*tmpFx[7] + tmpQ2[12]*tmpFx[11] + tmpQ2[13]*tmpFx[15] + tmpQ2[14]*tmpFx[19]; +tmpQ1[12] = + tmpQ2[15]*tmpFx[0] + tmpQ2[16]*tmpFx[4] + tmpQ2[17]*tmpFx[8] + tmpQ2[18]*tmpFx[12] + tmpQ2[19]*tmpFx[16]; +tmpQ1[13] = + tmpQ2[15]*tmpFx[1] + tmpQ2[16]*tmpFx[5] + tmpQ2[17]*tmpFx[9] + tmpQ2[18]*tmpFx[13] + tmpQ2[19]*tmpFx[17]; +tmpQ1[14] = + tmpQ2[15]*tmpFx[2] + tmpQ2[16]*tmpFx[6] + tmpQ2[17]*tmpFx[10] + tmpQ2[18]*tmpFx[14] + tmpQ2[19]*tmpFx[18]; +tmpQ1[15] = + tmpQ2[15]*tmpFx[3] + tmpQ2[16]*tmpFx[7] + tmpQ2[17]*tmpFx[11] + tmpQ2[18]*tmpFx[15] + tmpQ2[19]*tmpFx[19]; +} + +void acado_setObjR1R2( real_t* const tmpFu, real_t* const tmpR1, real_t* const tmpR2 ) +{ +tmpR2[0] = + tmpFu[0]; +tmpR2[1] = + tmpFu[1]; +tmpR2[2] = + tmpFu[2]; +tmpR2[3] = + tmpFu[3]; +tmpR2[4] = + tmpFu[4]; +tmpR1[0] = + tmpR2[0]*tmpFu[0] + tmpR2[1]*tmpFu[1] + tmpR2[2]*tmpFu[2] + tmpR2[3]*tmpFu[3] + tmpR2[4]*tmpFu[4]; +} + +void acado_setObjQN1QN2( real_t* const tmpFx, real_t* const tmpQN1, real_t* const tmpQN2 ) +{ +tmpQN2[0] = + tmpFx[0]; +tmpQN2[1] = + tmpFx[4]; +tmpQN2[2] = + tmpFx[8]; +tmpQN2[3] = + tmpFx[12]; +tmpQN2[4] = + tmpFx[1]; +tmpQN2[5] = + tmpFx[5]; +tmpQN2[6] = + tmpFx[9]; +tmpQN2[7] = + tmpFx[13]; +tmpQN2[8] = + tmpFx[2]; +tmpQN2[9] = + tmpFx[6]; +tmpQN2[10] = + tmpFx[10]; +tmpQN2[11] = + tmpFx[14]; +tmpQN2[12] = + tmpFx[3]; +tmpQN2[13] = + tmpFx[7]; +tmpQN2[14] = + tmpFx[11]; +tmpQN2[15] = + tmpFx[15]; +tmpQN1[0] = + tmpQN2[0]*tmpFx[0] + tmpQN2[1]*tmpFx[4] + tmpQN2[2]*tmpFx[8] + tmpQN2[3]*tmpFx[12]; +tmpQN1[1] = + tmpQN2[0]*tmpFx[1] + tmpQN2[1]*tmpFx[5] + tmpQN2[2]*tmpFx[9] + tmpQN2[3]*tmpFx[13]; +tmpQN1[2] = + tmpQN2[0]*tmpFx[2] + tmpQN2[1]*tmpFx[6] + tmpQN2[2]*tmpFx[10] + tmpQN2[3]*tmpFx[14]; +tmpQN1[3] = + tmpQN2[0]*tmpFx[3] + tmpQN2[1]*tmpFx[7] + tmpQN2[2]*tmpFx[11] + tmpQN2[3]*tmpFx[15]; +tmpQN1[4] = + tmpQN2[4]*tmpFx[0] + tmpQN2[5]*tmpFx[4] + tmpQN2[6]*tmpFx[8] + tmpQN2[7]*tmpFx[12]; +tmpQN1[5] = + tmpQN2[4]*tmpFx[1] + tmpQN2[5]*tmpFx[5] + tmpQN2[6]*tmpFx[9] + tmpQN2[7]*tmpFx[13]; +tmpQN1[6] = + tmpQN2[4]*tmpFx[2] + tmpQN2[5]*tmpFx[6] + tmpQN2[6]*tmpFx[10] + tmpQN2[7]*tmpFx[14]; +tmpQN1[7] = + tmpQN2[4]*tmpFx[3] + tmpQN2[5]*tmpFx[7] + tmpQN2[6]*tmpFx[11] + tmpQN2[7]*tmpFx[15]; +tmpQN1[8] = + tmpQN2[8]*tmpFx[0] + tmpQN2[9]*tmpFx[4] + tmpQN2[10]*tmpFx[8] + tmpQN2[11]*tmpFx[12]; +tmpQN1[9] = + tmpQN2[8]*tmpFx[1] + tmpQN2[9]*tmpFx[5] + tmpQN2[10]*tmpFx[9] + tmpQN2[11]*tmpFx[13]; +tmpQN1[10] = + tmpQN2[8]*tmpFx[2] + tmpQN2[9]*tmpFx[6] + tmpQN2[10]*tmpFx[10] + tmpQN2[11]*tmpFx[14]; +tmpQN1[11] = + tmpQN2[8]*tmpFx[3] + tmpQN2[9]*tmpFx[7] + tmpQN2[10]*tmpFx[11] + tmpQN2[11]*tmpFx[15]; +tmpQN1[12] = + tmpQN2[12]*tmpFx[0] + tmpQN2[13]*tmpFx[4] + tmpQN2[14]*tmpFx[8] + tmpQN2[15]*tmpFx[12]; +tmpQN1[13] = + tmpQN2[12]*tmpFx[1] + tmpQN2[13]*tmpFx[5] + tmpQN2[14]*tmpFx[9] + tmpQN2[15]*tmpFx[13]; +tmpQN1[14] = + tmpQN2[12]*tmpFx[2] + tmpQN2[13]*tmpFx[6] + tmpQN2[14]*tmpFx[10] + tmpQN2[15]*tmpFx[14]; +tmpQN1[15] = + tmpQN2[12]*tmpFx[3] + tmpQN2[13]*tmpFx[7] + tmpQN2[14]*tmpFx[11] + tmpQN2[15]*tmpFx[15]; +} + +void acado_evaluateObjective( ) +{ +int runObj; +for (runObj = 0; runObj < 50; ++runObj) +{ +acadoWorkspace.objValueIn[0] = acadoVariables.x[runObj * 4]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[runObj * 4 + 1]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[runObj * 4 + 2]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[runObj * 4 + 3]; +acadoWorkspace.objValueIn[4] = acadoVariables.u[runObj]; +acadoWorkspace.objValueIn[5] = acadoVariables.od[runObj * 18]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[runObj * 18 + 1]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[runObj * 18 + 2]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[runObj * 18 + 3]; +acadoWorkspace.objValueIn[9] = acadoVariables.od[runObj * 18 + 4]; +acadoWorkspace.objValueIn[10] = acadoVariables.od[runObj * 18 + 5]; +acadoWorkspace.objValueIn[11] = acadoVariables.od[runObj * 18 + 6]; +acadoWorkspace.objValueIn[12] = acadoVariables.od[runObj * 18 + 7]; +acadoWorkspace.objValueIn[13] = acadoVariables.od[runObj * 18 + 8]; +acadoWorkspace.objValueIn[14] = acadoVariables.od[runObj * 18 + 9]; +acadoWorkspace.objValueIn[15] = acadoVariables.od[runObj * 18 + 10]; +acadoWorkspace.objValueIn[16] = acadoVariables.od[runObj * 18 + 11]; +acadoWorkspace.objValueIn[17] = acadoVariables.od[runObj * 18 + 12]; +acadoWorkspace.objValueIn[18] = acadoVariables.od[runObj * 18 + 13]; +acadoWorkspace.objValueIn[19] = acadoVariables.od[runObj * 18 + 14]; +acadoWorkspace.objValueIn[20] = acadoVariables.od[runObj * 18 + 15]; +acadoWorkspace.objValueIn[21] = acadoVariables.od[runObj * 18 + 16]; +acadoWorkspace.objValueIn[22] = acadoVariables.od[runObj * 18 + 17]; + +acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); +acadoWorkspace.Dy[runObj * 5] = acadoWorkspace.objValueOut[0]; +acadoWorkspace.Dy[runObj * 5 + 1] = acadoWorkspace.objValueOut[1]; +acadoWorkspace.Dy[runObj * 5 + 2] = acadoWorkspace.objValueOut[2]; +acadoWorkspace.Dy[runObj * 5 + 3] = acadoWorkspace.objValueOut[3]; +acadoWorkspace.Dy[runObj * 5 + 4] = acadoWorkspace.objValueOut[4]; + +acado_setObjQ1Q2( &(acadoWorkspace.objValueOut[ 5 ]), &(acadoWorkspace.Q1[ runObj * 16 ]), &(acadoWorkspace.Q2[ runObj * 20 ]) ); + +acado_setObjR1R2( &(acadoWorkspace.objValueOut[ 25 ]), &(acadoWorkspace.R1[ runObj ]), &(acadoWorkspace.R2[ runObj * 5 ]) ); + +} +acadoWorkspace.objValueIn[0] = acadoVariables.x[200]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[201]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[202]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[203]; +acadoWorkspace.objValueIn[4] = acadoVariables.od[900]; +acadoWorkspace.objValueIn[5] = acadoVariables.od[901]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[902]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[903]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[904]; +acadoWorkspace.objValueIn[9] = acadoVariables.od[905]; +acadoWorkspace.objValueIn[10] = acadoVariables.od[906]; +acadoWorkspace.objValueIn[11] = acadoVariables.od[907]; +acadoWorkspace.objValueIn[12] = acadoVariables.od[908]; +acadoWorkspace.objValueIn[13] = acadoVariables.od[909]; +acadoWorkspace.objValueIn[14] = acadoVariables.od[910]; +acadoWorkspace.objValueIn[15] = acadoVariables.od[911]; +acadoWorkspace.objValueIn[16] = acadoVariables.od[912]; +acadoWorkspace.objValueIn[17] = acadoVariables.od[913]; +acadoWorkspace.objValueIn[18] = acadoVariables.od[914]; +acadoWorkspace.objValueIn[19] = acadoVariables.od[915]; +acadoWorkspace.objValueIn[20] = acadoVariables.od[916]; +acadoWorkspace.objValueIn[21] = acadoVariables.od[917]; +acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); + +acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0]; +acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1]; +acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2]; +acadoWorkspace.DyN[3] = acadoWorkspace.objValueOut[3]; + +acado_setObjQN1QN2( &(acadoWorkspace.objValueOut[ 4 ]), acadoWorkspace.QN1, acadoWorkspace.QN2 ); + +} + +void acado_multGxd( real_t* const dOld, real_t* const Gx1, real_t* const dNew ) +{ +dNew[0] += + Gx1[0]*dOld[0] + Gx1[1]*dOld[1] + Gx1[2]*dOld[2] + Gx1[3]*dOld[3]; +dNew[1] += + Gx1[4]*dOld[0] + Gx1[5]*dOld[1] + Gx1[6]*dOld[2] + Gx1[7]*dOld[3]; +dNew[2] += + Gx1[8]*dOld[0] + Gx1[9]*dOld[1] + Gx1[10]*dOld[2] + Gx1[11]*dOld[3]; +dNew[3] += + Gx1[12]*dOld[0] + Gx1[13]*dOld[1] + Gx1[14]*dOld[2] + Gx1[15]*dOld[3]; +} + +void acado_moveGxT( real_t* const Gx1, real_t* const Gx2 ) +{ +Gx2[0] = Gx1[0]; +Gx2[1] = Gx1[1]; +Gx2[2] = Gx1[2]; +Gx2[3] = Gx1[3]; +Gx2[4] = Gx1[4]; +Gx2[5] = Gx1[5]; +Gx2[6] = Gx1[6]; +Gx2[7] = Gx1[7]; +Gx2[8] = Gx1[8]; +Gx2[9] = Gx1[9]; +Gx2[10] = Gx1[10]; +Gx2[11] = Gx1[11]; +Gx2[12] = Gx1[12]; +Gx2[13] = Gx1[13]; +Gx2[14] = Gx1[14]; +Gx2[15] = Gx1[15]; +} + +void acado_multGxGx( real_t* const Gx1, real_t* const Gx2, real_t* const Gx3 ) +{ +Gx3[0] = + Gx1[0]*Gx2[0] + Gx1[1]*Gx2[4] + Gx1[2]*Gx2[8] + Gx1[3]*Gx2[12]; +Gx3[1] = + Gx1[0]*Gx2[1] + Gx1[1]*Gx2[5] + Gx1[2]*Gx2[9] + Gx1[3]*Gx2[13]; +Gx3[2] = + Gx1[0]*Gx2[2] + Gx1[1]*Gx2[6] + Gx1[2]*Gx2[10] + Gx1[3]*Gx2[14]; +Gx3[3] = + Gx1[0]*Gx2[3] + Gx1[1]*Gx2[7] + Gx1[2]*Gx2[11] + Gx1[3]*Gx2[15]; +Gx3[4] = + Gx1[4]*Gx2[0] + Gx1[5]*Gx2[4] + Gx1[6]*Gx2[8] + Gx1[7]*Gx2[12]; +Gx3[5] = + Gx1[4]*Gx2[1] + Gx1[5]*Gx2[5] + Gx1[6]*Gx2[9] + Gx1[7]*Gx2[13]; +Gx3[6] = + Gx1[4]*Gx2[2] + Gx1[5]*Gx2[6] + Gx1[6]*Gx2[10] + Gx1[7]*Gx2[14]; +Gx3[7] = + Gx1[4]*Gx2[3] + Gx1[5]*Gx2[7] + Gx1[6]*Gx2[11] + Gx1[7]*Gx2[15]; +Gx3[8] = + Gx1[8]*Gx2[0] + Gx1[9]*Gx2[4] + Gx1[10]*Gx2[8] + Gx1[11]*Gx2[12]; +Gx3[9] = + Gx1[8]*Gx2[1] + Gx1[9]*Gx2[5] + Gx1[10]*Gx2[9] + Gx1[11]*Gx2[13]; +Gx3[10] = + Gx1[8]*Gx2[2] + Gx1[9]*Gx2[6] + Gx1[10]*Gx2[10] + Gx1[11]*Gx2[14]; +Gx3[11] = + Gx1[8]*Gx2[3] + Gx1[9]*Gx2[7] + Gx1[10]*Gx2[11] + Gx1[11]*Gx2[15]; +Gx3[12] = + Gx1[12]*Gx2[0] + Gx1[13]*Gx2[4] + Gx1[14]*Gx2[8] + Gx1[15]*Gx2[12]; +Gx3[13] = + Gx1[12]*Gx2[1] + Gx1[13]*Gx2[5] + Gx1[14]*Gx2[9] + Gx1[15]*Gx2[13]; +Gx3[14] = + Gx1[12]*Gx2[2] + Gx1[13]*Gx2[6] + Gx1[14]*Gx2[10] + Gx1[15]*Gx2[14]; +Gx3[15] = + Gx1[12]*Gx2[3] + Gx1[13]*Gx2[7] + Gx1[14]*Gx2[11] + Gx1[15]*Gx2[15]; +} + +void acado_multGxGu( real_t* const Gx1, real_t* const Gu1, real_t* const Gu2 ) +{ +Gu2[0] = + Gx1[0]*Gu1[0] + Gx1[1]*Gu1[1] + Gx1[2]*Gu1[2] + Gx1[3]*Gu1[3]; +Gu2[1] = + Gx1[4]*Gu1[0] + Gx1[5]*Gu1[1] + Gx1[6]*Gu1[2] + Gx1[7]*Gu1[3]; +Gu2[2] = + Gx1[8]*Gu1[0] + Gx1[9]*Gu1[1] + Gx1[10]*Gu1[2] + Gx1[11]*Gu1[3]; +Gu2[3] = + Gx1[12]*Gu1[0] + Gx1[13]*Gu1[1] + Gx1[14]*Gu1[2] + Gx1[15]*Gu1[3]; +} + +void acado_moveGuE( real_t* const Gu1, real_t* const Gu2 ) +{ +Gu2[0] = Gu1[0]; +Gu2[1] = Gu1[1]; +Gu2[2] = Gu1[2]; +Gu2[3] = Gu1[3]; +} + +void acado_setBlockH11( int iRow, int iCol, real_t* const Gu1, real_t* const Gu2 ) +{ +acadoWorkspace.H[(iRow * 54 + 216) + (iCol + 4)] += + Gu1[0]*Gu2[0] + Gu1[1]*Gu2[1] + Gu1[2]*Gu2[2] + Gu1[3]*Gu2[3]; +} + +void acado_setBlockH11_R1( int iRow, int iCol, real_t* const R11 ) +{ +acadoWorkspace.H[(iRow * 54 + 216) + (iCol + 4)] = R11[0]; +} + +void acado_zeroBlockH11( int iRow, int iCol ) +{ +acadoWorkspace.H[(iRow * 54 + 216) + (iCol + 4)] = 0.0000000000000000e+00; +} + +void acado_copyHTH( int iRow, int iCol ) +{ +acadoWorkspace.H[(iRow * 54 + 216) + (iCol + 4)] = acadoWorkspace.H[(iCol * 54 + 216) + (iRow + 4)]; +} + +void acado_multQ1d( real_t* const Gx1, real_t* const dOld, real_t* const dNew ) +{ +dNew[0] = + Gx1[0]*dOld[0] + Gx1[1]*dOld[1] + Gx1[2]*dOld[2] + Gx1[3]*dOld[3]; +dNew[1] = + Gx1[4]*dOld[0] + Gx1[5]*dOld[1] + Gx1[6]*dOld[2] + Gx1[7]*dOld[3]; +dNew[2] = + Gx1[8]*dOld[0] + Gx1[9]*dOld[1] + Gx1[10]*dOld[2] + Gx1[11]*dOld[3]; +dNew[3] = + Gx1[12]*dOld[0] + Gx1[13]*dOld[1] + Gx1[14]*dOld[2] + Gx1[15]*dOld[3]; +} + +void acado_multQN1d( real_t* const QN1, real_t* const dOld, real_t* const dNew ) +{ +dNew[0] = + acadoWorkspace.QN1[0]*dOld[0] + acadoWorkspace.QN1[1]*dOld[1] + acadoWorkspace.QN1[2]*dOld[2] + acadoWorkspace.QN1[3]*dOld[3]; +dNew[1] = + acadoWorkspace.QN1[4]*dOld[0] + acadoWorkspace.QN1[5]*dOld[1] + acadoWorkspace.QN1[6]*dOld[2] + acadoWorkspace.QN1[7]*dOld[3]; +dNew[2] = + acadoWorkspace.QN1[8]*dOld[0] + acadoWorkspace.QN1[9]*dOld[1] + acadoWorkspace.QN1[10]*dOld[2] + acadoWorkspace.QN1[11]*dOld[3]; +dNew[3] = + acadoWorkspace.QN1[12]*dOld[0] + acadoWorkspace.QN1[13]*dOld[1] + acadoWorkspace.QN1[14]*dOld[2] + acadoWorkspace.QN1[15]*dOld[3]; +} + +void acado_multRDy( real_t* const R2, real_t* const Dy1, real_t* const RDy1 ) +{ +RDy1[0] = + R2[0]*Dy1[0] + R2[1]*Dy1[1] + R2[2]*Dy1[2] + R2[3]*Dy1[3] + R2[4]*Dy1[4]; +} + +void acado_multQDy( real_t* const Q2, real_t* const Dy1, real_t* const QDy1 ) +{ +QDy1[0] = + Q2[0]*Dy1[0] + Q2[1]*Dy1[1] + Q2[2]*Dy1[2] + Q2[3]*Dy1[3] + Q2[4]*Dy1[4]; +QDy1[1] = + Q2[5]*Dy1[0] + Q2[6]*Dy1[1] + Q2[7]*Dy1[2] + Q2[8]*Dy1[3] + Q2[9]*Dy1[4]; +QDy1[2] = + Q2[10]*Dy1[0] + Q2[11]*Dy1[1] + Q2[12]*Dy1[2] + Q2[13]*Dy1[3] + Q2[14]*Dy1[4]; +QDy1[3] = + Q2[15]*Dy1[0] + Q2[16]*Dy1[1] + Q2[17]*Dy1[2] + Q2[18]*Dy1[3] + Q2[19]*Dy1[4]; +} + +void acado_multEQDy( real_t* const E1, real_t* const QDy1, real_t* const U1 ) +{ +U1[0] += + E1[0]*QDy1[0] + E1[1]*QDy1[1] + E1[2]*QDy1[2] + E1[3]*QDy1[3]; +} + +void acado_multQETGx( real_t* const E1, real_t* const Gx1, real_t* const H101 ) +{ +H101[0] += + E1[0]*Gx1[0] + E1[1]*Gx1[4] + E1[2]*Gx1[8] + E1[3]*Gx1[12]; +H101[1] += + E1[0]*Gx1[1] + E1[1]*Gx1[5] + E1[2]*Gx1[9] + E1[3]*Gx1[13]; +H101[2] += + E1[0]*Gx1[2] + E1[1]*Gx1[6] + E1[2]*Gx1[10] + E1[3]*Gx1[14]; +H101[3] += + E1[0]*Gx1[3] + E1[1]*Gx1[7] + E1[2]*Gx1[11] + E1[3]*Gx1[15]; +} + +void acado_zeroBlockH10( real_t* const H101 ) +{ +{ int lCopy; for (lCopy = 0; lCopy < 4; lCopy++) H101[ lCopy ] = 0; } +} + +void acado_multEDu( real_t* const E1, real_t* const U1, real_t* const dNew ) +{ +dNew[0] += + E1[0]*U1[0]; +dNew[1] += + E1[1]*U1[0]; +dNew[2] += + E1[2]*U1[0]; +dNew[3] += + E1[3]*U1[0]; +} + +void acado_zeroBlockH00( ) +{ +acadoWorkspace.H[0] = 0.0000000000000000e+00; +acadoWorkspace.H[1] = 0.0000000000000000e+00; +acadoWorkspace.H[2] = 0.0000000000000000e+00; +acadoWorkspace.H[3] = 0.0000000000000000e+00; +acadoWorkspace.H[54] = 0.0000000000000000e+00; +acadoWorkspace.H[55] = 0.0000000000000000e+00; +acadoWorkspace.H[56] = 0.0000000000000000e+00; +acadoWorkspace.H[57] = 0.0000000000000000e+00; +acadoWorkspace.H[108] = 0.0000000000000000e+00; +acadoWorkspace.H[109] = 0.0000000000000000e+00; +acadoWorkspace.H[110] = 0.0000000000000000e+00; +acadoWorkspace.H[111] = 0.0000000000000000e+00; +acadoWorkspace.H[162] = 0.0000000000000000e+00; +acadoWorkspace.H[163] = 0.0000000000000000e+00; +acadoWorkspace.H[164] = 0.0000000000000000e+00; +acadoWorkspace.H[165] = 0.0000000000000000e+00; +} + +void acado_multCTQC( real_t* const Gx1, real_t* const Gx2 ) +{ +acadoWorkspace.H[0] += + Gx1[0]*Gx2[0] + Gx1[4]*Gx2[4] + Gx1[8]*Gx2[8] + Gx1[12]*Gx2[12]; +acadoWorkspace.H[1] += + Gx1[0]*Gx2[1] + Gx1[4]*Gx2[5] + Gx1[8]*Gx2[9] + Gx1[12]*Gx2[13]; +acadoWorkspace.H[2] += + Gx1[0]*Gx2[2] + Gx1[4]*Gx2[6] + Gx1[8]*Gx2[10] + Gx1[12]*Gx2[14]; +acadoWorkspace.H[3] += + Gx1[0]*Gx2[3] + Gx1[4]*Gx2[7] + Gx1[8]*Gx2[11] + Gx1[12]*Gx2[15]; +acadoWorkspace.H[54] += + Gx1[1]*Gx2[0] + Gx1[5]*Gx2[4] + Gx1[9]*Gx2[8] + Gx1[13]*Gx2[12]; +acadoWorkspace.H[55] += + Gx1[1]*Gx2[1] + Gx1[5]*Gx2[5] + Gx1[9]*Gx2[9] + Gx1[13]*Gx2[13]; +acadoWorkspace.H[56] += + Gx1[1]*Gx2[2] + Gx1[5]*Gx2[6] + Gx1[9]*Gx2[10] + Gx1[13]*Gx2[14]; +acadoWorkspace.H[57] += + Gx1[1]*Gx2[3] + Gx1[5]*Gx2[7] + Gx1[9]*Gx2[11] + Gx1[13]*Gx2[15]; +acadoWorkspace.H[108] += + Gx1[2]*Gx2[0] + Gx1[6]*Gx2[4] + Gx1[10]*Gx2[8] + Gx1[14]*Gx2[12]; +acadoWorkspace.H[109] += + Gx1[2]*Gx2[1] + Gx1[6]*Gx2[5] + Gx1[10]*Gx2[9] + Gx1[14]*Gx2[13]; +acadoWorkspace.H[110] += + Gx1[2]*Gx2[2] + Gx1[6]*Gx2[6] + Gx1[10]*Gx2[10] + Gx1[14]*Gx2[14]; +acadoWorkspace.H[111] += + Gx1[2]*Gx2[3] + Gx1[6]*Gx2[7] + Gx1[10]*Gx2[11] + Gx1[14]*Gx2[15]; +acadoWorkspace.H[162] += + Gx1[3]*Gx2[0] + Gx1[7]*Gx2[4] + Gx1[11]*Gx2[8] + Gx1[15]*Gx2[12]; +acadoWorkspace.H[163] += + Gx1[3]*Gx2[1] + Gx1[7]*Gx2[5] + Gx1[11]*Gx2[9] + Gx1[15]*Gx2[13]; +acadoWorkspace.H[164] += + Gx1[3]*Gx2[2] + Gx1[7]*Gx2[6] + Gx1[11]*Gx2[10] + Gx1[15]*Gx2[14]; +acadoWorkspace.H[165] += + Gx1[3]*Gx2[3] + Gx1[7]*Gx2[7] + Gx1[11]*Gx2[11] + Gx1[15]*Gx2[15]; +} + +void acado_macCTSlx( real_t* const C0, real_t* const g0 ) +{ +g0[0] += 0.0; +; +g0[1] += 0.0; +; +g0[2] += 0.0; +; +g0[3] += 0.0; +; +} + +void acado_macETSlu( real_t* const E0, real_t* const g1 ) +{ +g1[0] += 0.0; +; +} + +void acado_condensePrep( ) +{ +int lRun1; +int lRun2; +int lRun3; +int lRun4; +int lRun5; +/** Row vector of size: 100 */ +static const int xBoundIndices[ 100 ] = +{ 6, 7, 10, 11, 14, 15, 18, 19, 22, 23, 26, 27, 30, 31, 34, 35, 38, 39, 42, 43, 46, 47, 50, 51, 54, 55, 58, 59, 62, 63, 66, 67, 70, 71, 74, 75, 78, 79, 82, 83, 86, 87, 90, 91, 94, 95, 98, 99, 102, 103, 106, 107, 110, 111, 114, 115, 118, 119, 122, 123, 126, 127, 130, 131, 134, 135, 138, 139, 142, 143, 146, 147, 150, 151, 154, 155, 158, 159, 162, 163, 166, 167, 170, 171, 174, 175, 178, 179, 182, 183, 186, 187, 190, 191, 194, 195, 198, 199, 202, 203 }; +acado_moveGuE( acadoWorkspace.evGu, acadoWorkspace.E ); +for (lRun1 = 1; lRun1 < 50; ++lRun1) +{ +acado_moveGxT( &(acadoWorkspace.evGx[ lRun1 * 16 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ lRun1 * 4-4 ]), &(acadoWorkspace.evGx[ lRun1 * 16 ]), &(acadoWorkspace.d[ lRun1 * 4 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ lRun1 * 16-16 ]), &(acadoWorkspace.evGx[ lRun1 * 16 ]) ); +for (lRun2 = 0; lRun2 < lRun1; ++lRun2) +{ +lRun4 = (((lRun1) * (lRun1-1)) / (2)) + (lRun2); +lRun3 = (((lRun1 + 1) * (lRun1)) / (2)) + (lRun2); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ lRun4 * 4 ]), &(acadoWorkspace.E[ lRun3 * 4 ]) ); +} +lRun3 = (((lRun1 + 1) * (lRun1)) / (2)) + (lRun2); +acado_moveGuE( &(acadoWorkspace.evGu[ lRun1 * 4 ]), &(acadoWorkspace.E[ lRun3 * 4 ]) ); +} + +acado_multGxGx( &(acadoWorkspace.Q1[ 16 ]), acadoWorkspace.evGx, acadoWorkspace.QGx ); +acado_multGxGx( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.QGx[ 16 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.QGx[ 32 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.QGx[ 48 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.QGx[ 64 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.QGx[ 80 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.QGx[ 96 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.QGx[ 112 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.QGx[ 128 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.QGx[ 144 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.QGx[ 160 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.QGx[ 176 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.QGx[ 192 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.QGx[ 208 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.QGx[ 224 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.QGx[ 240 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.QGx[ 256 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.QGx[ 272 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.QGx[ 288 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 320 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.QGx[ 304 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 336 ]), &(acadoWorkspace.evGx[ 320 ]), &(acadoWorkspace.QGx[ 320 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 352 ]), &(acadoWorkspace.evGx[ 336 ]), &(acadoWorkspace.QGx[ 336 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 368 ]), &(acadoWorkspace.evGx[ 352 ]), &(acadoWorkspace.QGx[ 352 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 384 ]), &(acadoWorkspace.evGx[ 368 ]), &(acadoWorkspace.QGx[ 368 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 400 ]), &(acadoWorkspace.evGx[ 384 ]), &(acadoWorkspace.QGx[ 384 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 416 ]), &(acadoWorkspace.evGx[ 400 ]), &(acadoWorkspace.QGx[ 400 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.evGx[ 416 ]), &(acadoWorkspace.QGx[ 416 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 448 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.QGx[ 432 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 464 ]), &(acadoWorkspace.evGx[ 448 ]), &(acadoWorkspace.QGx[ 448 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 480 ]), &(acadoWorkspace.evGx[ 464 ]), &(acadoWorkspace.QGx[ 464 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 496 ]), &(acadoWorkspace.evGx[ 480 ]), &(acadoWorkspace.QGx[ 480 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 512 ]), &(acadoWorkspace.evGx[ 496 ]), &(acadoWorkspace.QGx[ 496 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 528 ]), &(acadoWorkspace.evGx[ 512 ]), &(acadoWorkspace.QGx[ 512 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 544 ]), &(acadoWorkspace.evGx[ 528 ]), &(acadoWorkspace.QGx[ 528 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 560 ]), &(acadoWorkspace.evGx[ 544 ]), &(acadoWorkspace.QGx[ 544 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.evGx[ 560 ]), &(acadoWorkspace.QGx[ 560 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 592 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.QGx[ 576 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 608 ]), &(acadoWorkspace.evGx[ 592 ]), &(acadoWorkspace.QGx[ 592 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 624 ]), &(acadoWorkspace.evGx[ 608 ]), &(acadoWorkspace.QGx[ 608 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 640 ]), &(acadoWorkspace.evGx[ 624 ]), &(acadoWorkspace.QGx[ 624 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 656 ]), &(acadoWorkspace.evGx[ 640 ]), &(acadoWorkspace.QGx[ 640 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 672 ]), &(acadoWorkspace.evGx[ 656 ]), &(acadoWorkspace.QGx[ 656 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 688 ]), &(acadoWorkspace.evGx[ 672 ]), &(acadoWorkspace.QGx[ 672 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 704 ]), &(acadoWorkspace.evGx[ 688 ]), &(acadoWorkspace.QGx[ 688 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 720 ]), &(acadoWorkspace.evGx[ 704 ]), &(acadoWorkspace.QGx[ 704 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 736 ]), &(acadoWorkspace.evGx[ 720 ]), &(acadoWorkspace.QGx[ 720 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 752 ]), &(acadoWorkspace.evGx[ 736 ]), &(acadoWorkspace.QGx[ 736 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 768 ]), &(acadoWorkspace.evGx[ 752 ]), &(acadoWorkspace.QGx[ 752 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 784 ]), &(acadoWorkspace.evGx[ 768 ]), &(acadoWorkspace.QGx[ 768 ]) ); +acado_multGxGx( acadoWorkspace.QN1, &(acadoWorkspace.evGx[ 784 ]), &(acadoWorkspace.QGx[ 784 ]) ); + +for (lRun1 = 0; lRun1 < 49; ++lRun1) +{ +for (lRun2 = 0; lRun2 < lRun1 + 1; ++lRun2) +{ +lRun3 = (((lRun1 + 1) * (lRun1)) / (2)) + (lRun2); +acado_multGxGu( &(acadoWorkspace.Q1[ lRun1 * 16 + 16 ]), &(acadoWorkspace.E[ lRun3 * 4 ]), &(acadoWorkspace.QE[ lRun3 * 4 ]) ); +} +} + +for (lRun2 = 0; lRun2 < lRun1 + 1; ++lRun2) +{ +lRun3 = (((lRun1 + 1) * (lRun1)) / (2)) + (lRun2); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ lRun3 * 4 ]), &(acadoWorkspace.QE[ lRun3 * 4 ]) ); +} + +acado_zeroBlockH00( ); +acado_multCTQC( acadoWorkspace.evGx, acadoWorkspace.QGx ); +acado_multCTQC( &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.QGx[ 16 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.QGx[ 32 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.QGx[ 48 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.QGx[ 64 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.QGx[ 80 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.QGx[ 96 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.QGx[ 112 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.QGx[ 128 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.QGx[ 144 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.QGx[ 160 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.QGx[ 176 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.QGx[ 192 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.QGx[ 208 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.QGx[ 224 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.QGx[ 240 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.QGx[ 256 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.QGx[ 272 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.QGx[ 288 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.QGx[ 304 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 320 ]), &(acadoWorkspace.QGx[ 320 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 336 ]), &(acadoWorkspace.QGx[ 336 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 352 ]), &(acadoWorkspace.QGx[ 352 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 368 ]), &(acadoWorkspace.QGx[ 368 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 384 ]), &(acadoWorkspace.QGx[ 384 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 400 ]), &(acadoWorkspace.QGx[ 400 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 416 ]), &(acadoWorkspace.QGx[ 416 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.QGx[ 432 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 448 ]), &(acadoWorkspace.QGx[ 448 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 464 ]), &(acadoWorkspace.QGx[ 464 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 480 ]), &(acadoWorkspace.QGx[ 480 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 496 ]), &(acadoWorkspace.QGx[ 496 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 512 ]), &(acadoWorkspace.QGx[ 512 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 528 ]), &(acadoWorkspace.QGx[ 528 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 544 ]), &(acadoWorkspace.QGx[ 544 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 560 ]), &(acadoWorkspace.QGx[ 560 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.QGx[ 576 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 592 ]), &(acadoWorkspace.QGx[ 592 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 608 ]), &(acadoWorkspace.QGx[ 608 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 624 ]), &(acadoWorkspace.QGx[ 624 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 640 ]), &(acadoWorkspace.QGx[ 640 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 656 ]), &(acadoWorkspace.QGx[ 656 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 672 ]), &(acadoWorkspace.QGx[ 672 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 688 ]), &(acadoWorkspace.QGx[ 688 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 704 ]), &(acadoWorkspace.QGx[ 704 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 720 ]), &(acadoWorkspace.QGx[ 720 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 736 ]), &(acadoWorkspace.QGx[ 736 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 752 ]), &(acadoWorkspace.QGx[ 752 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 768 ]), &(acadoWorkspace.QGx[ 768 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 784 ]), &(acadoWorkspace.QGx[ 784 ]) ); + +for (lRun1 = 0; lRun1 < 50; ++lRun1) +{ +acado_zeroBlockH10( &(acadoWorkspace.H10[ lRun1 * 4 ]) ); +for (lRun2 = lRun1; lRun2 < 50; ++lRun2) +{ +lRun3 = (((lRun2 + 1) * (lRun2)) / (2)) + (lRun1); +acado_multQETGx( &(acadoWorkspace.QE[ lRun3 * 4 ]), &(acadoWorkspace.evGx[ lRun2 * 16 ]), &(acadoWorkspace.H10[ lRun1 * 4 ]) ); +} +} + +for (lRun1 = 0;lRun1 < 4; ++lRun1) +for (lRun2 = 0;lRun2 < 50; ++lRun2) +acadoWorkspace.H[(lRun1 * 54) + (lRun2 + 4)] = acadoWorkspace.H10[(lRun2 * 4) + (lRun1)]; + +for (lRun1 = 0; lRun1 < 50; ++lRun1) +{ +acado_setBlockH11_R1( lRun1, lRun1, &(acadoWorkspace.R1[ lRun1 ]) ); +lRun2 = lRun1; +for (lRun3 = lRun1; lRun3 < 50; ++lRun3) +{ +lRun4 = (((lRun3 + 1) * (lRun3)) / (2)) + (lRun1); +lRun5 = (((lRun3 + 1) * (lRun3)) / (2)) + (lRun2); +acado_setBlockH11( lRun1, lRun2, &(acadoWorkspace.E[ lRun4 * 4 ]), &(acadoWorkspace.QE[ lRun5 * 4 ]) ); +} +for (lRun2 = lRun1 + 1; lRun2 < 50; ++lRun2) +{ +acado_zeroBlockH11( lRun1, lRun2 ); +for (lRun3 = lRun2; lRun3 < 50; ++lRun3) +{ +lRun4 = (((lRun3 + 1) * (lRun3)) / (2)) + (lRun1); +lRun5 = (((lRun3 + 1) * (lRun3)) / (2)) + (lRun2); +acado_setBlockH11( lRun1, lRun2, &(acadoWorkspace.E[ lRun4 * 4 ]), &(acadoWorkspace.QE[ lRun5 * 4 ]) ); +} +} +} + +for (lRun1 = 0; lRun1 < 50; ++lRun1) +{ +for (lRun2 = 0; lRun2 < lRun1; ++lRun2) +{ +acado_copyHTH( lRun1, lRun2 ); +} +} + +for (lRun1 = 0;lRun1 < 50; ++lRun1) +for (lRun2 = 0;lRun2 < 4; ++lRun2) +acadoWorkspace.H[(lRun1 * 54 + 216) + (lRun2)] = acadoWorkspace.H10[(lRun1 * 4) + (lRun2)]; + +acado_multQ1d( &(acadoWorkspace.Q1[ 16 ]), acadoWorkspace.d, acadoWorkspace.Qd ); +acado_multQ1d( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.d[ 4 ]), &(acadoWorkspace.Qd[ 4 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.d[ 8 ]), &(acadoWorkspace.Qd[ 8 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.d[ 12 ]), &(acadoWorkspace.Qd[ 12 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.d[ 16 ]), &(acadoWorkspace.Qd[ 16 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.d[ 20 ]), &(acadoWorkspace.Qd[ 20 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.d[ 24 ]), &(acadoWorkspace.Qd[ 24 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.d[ 28 ]), &(acadoWorkspace.Qd[ 28 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.d[ 32 ]), &(acadoWorkspace.Qd[ 32 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.d[ 36 ]), &(acadoWorkspace.Qd[ 36 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.d[ 40 ]), &(acadoWorkspace.Qd[ 40 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.d[ 44 ]), &(acadoWorkspace.Qd[ 44 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.d[ 48 ]), &(acadoWorkspace.Qd[ 48 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.d[ 52 ]), &(acadoWorkspace.Qd[ 52 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.d[ 56 ]), &(acadoWorkspace.Qd[ 56 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.d[ 60 ]), &(acadoWorkspace.Qd[ 60 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.d[ 64 ]), &(acadoWorkspace.Qd[ 64 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.d[ 68 ]), &(acadoWorkspace.Qd[ 68 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.d[ 72 ]), &(acadoWorkspace.Qd[ 72 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 320 ]), &(acadoWorkspace.d[ 76 ]), &(acadoWorkspace.Qd[ 76 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 336 ]), &(acadoWorkspace.d[ 80 ]), &(acadoWorkspace.Qd[ 80 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 352 ]), &(acadoWorkspace.d[ 84 ]), &(acadoWorkspace.Qd[ 84 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 368 ]), &(acadoWorkspace.d[ 88 ]), &(acadoWorkspace.Qd[ 88 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 384 ]), &(acadoWorkspace.d[ 92 ]), &(acadoWorkspace.Qd[ 92 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 400 ]), &(acadoWorkspace.d[ 96 ]), &(acadoWorkspace.Qd[ 96 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 416 ]), &(acadoWorkspace.d[ 100 ]), &(acadoWorkspace.Qd[ 100 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.d[ 104 ]), &(acadoWorkspace.Qd[ 104 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 448 ]), &(acadoWorkspace.d[ 108 ]), &(acadoWorkspace.Qd[ 108 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 464 ]), &(acadoWorkspace.d[ 112 ]), &(acadoWorkspace.Qd[ 112 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 480 ]), &(acadoWorkspace.d[ 116 ]), &(acadoWorkspace.Qd[ 116 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 496 ]), &(acadoWorkspace.d[ 120 ]), &(acadoWorkspace.Qd[ 120 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 512 ]), &(acadoWorkspace.d[ 124 ]), &(acadoWorkspace.Qd[ 124 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 528 ]), &(acadoWorkspace.d[ 128 ]), &(acadoWorkspace.Qd[ 128 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 544 ]), &(acadoWorkspace.d[ 132 ]), &(acadoWorkspace.Qd[ 132 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 560 ]), &(acadoWorkspace.d[ 136 ]), &(acadoWorkspace.Qd[ 136 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.d[ 140 ]), &(acadoWorkspace.Qd[ 140 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 592 ]), &(acadoWorkspace.d[ 144 ]), &(acadoWorkspace.Qd[ 144 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 608 ]), &(acadoWorkspace.d[ 148 ]), &(acadoWorkspace.Qd[ 148 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 624 ]), &(acadoWorkspace.d[ 152 ]), &(acadoWorkspace.Qd[ 152 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 640 ]), &(acadoWorkspace.d[ 156 ]), &(acadoWorkspace.Qd[ 156 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 656 ]), &(acadoWorkspace.d[ 160 ]), &(acadoWorkspace.Qd[ 160 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 672 ]), &(acadoWorkspace.d[ 164 ]), &(acadoWorkspace.Qd[ 164 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 688 ]), &(acadoWorkspace.d[ 168 ]), &(acadoWorkspace.Qd[ 168 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 704 ]), &(acadoWorkspace.d[ 172 ]), &(acadoWorkspace.Qd[ 172 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 720 ]), &(acadoWorkspace.d[ 176 ]), &(acadoWorkspace.Qd[ 176 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 736 ]), &(acadoWorkspace.d[ 180 ]), &(acadoWorkspace.Qd[ 180 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 752 ]), &(acadoWorkspace.d[ 184 ]), &(acadoWorkspace.Qd[ 184 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 768 ]), &(acadoWorkspace.d[ 188 ]), &(acadoWorkspace.Qd[ 188 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 784 ]), &(acadoWorkspace.d[ 192 ]), &(acadoWorkspace.Qd[ 192 ]) ); +acado_multQN1d( acadoWorkspace.QN1, &(acadoWorkspace.d[ 196 ]), &(acadoWorkspace.Qd[ 196 ]) ); + +acado_macCTSlx( acadoWorkspace.evGx, acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 16 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 32 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 48 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 64 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 80 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 96 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 112 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 128 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 160 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 176 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 192 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 208 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 224 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 240 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 256 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 272 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 304 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 320 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 336 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 352 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 368 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 384 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 400 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 416 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 432 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 448 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 464 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 480 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 496 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 512 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 528 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 544 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 560 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 576 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 592 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 608 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 624 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 640 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 656 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 672 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 688 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 704 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 720 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 736 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 752 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 768 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 784 ]), acadoWorkspace.g ); +for (lRun1 = 0; lRun1 < 50; ++lRun1) +{ +for (lRun2 = lRun1; lRun2 < 50; ++lRun2) +{ +lRun3 = (((lRun2 + 1) * (lRun2)) / (2)) + (lRun1); +acado_macETSlu( &(acadoWorkspace.QE[ lRun3 * 4 ]), &(acadoWorkspace.g[ lRun1 + 4 ]) ); +} +} +acadoWorkspace.lb[4] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[0]; +acadoWorkspace.lb[5] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[1]; +acadoWorkspace.lb[6] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[2]; +acadoWorkspace.lb[7] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[3]; +acadoWorkspace.lb[8] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[4]; +acadoWorkspace.lb[9] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[5]; +acadoWorkspace.lb[10] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[6]; +acadoWorkspace.lb[11] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[7]; +acadoWorkspace.lb[12] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[8]; +acadoWorkspace.lb[13] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[9]; +acadoWorkspace.lb[14] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[10]; +acadoWorkspace.lb[15] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[11]; +acadoWorkspace.lb[16] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[12]; +acadoWorkspace.lb[17] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[13]; +acadoWorkspace.lb[18] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[14]; +acadoWorkspace.lb[19] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[15]; +acadoWorkspace.lb[20] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[16]; +acadoWorkspace.lb[21] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[17]; +acadoWorkspace.lb[22] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[18]; +acadoWorkspace.lb[23] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[19]; +acadoWorkspace.lb[24] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[20]; +acadoWorkspace.lb[25] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[21]; +acadoWorkspace.lb[26] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[22]; +acadoWorkspace.lb[27] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[23]; +acadoWorkspace.lb[28] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[24]; +acadoWorkspace.lb[29] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[25]; +acadoWorkspace.lb[30] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[26]; +acadoWorkspace.lb[31] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[27]; +acadoWorkspace.lb[32] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[28]; +acadoWorkspace.lb[33] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[29]; +acadoWorkspace.lb[34] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[30]; +acadoWorkspace.lb[35] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[31]; +acadoWorkspace.lb[36] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[32]; +acadoWorkspace.lb[37] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[33]; +acadoWorkspace.lb[38] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[34]; +acadoWorkspace.lb[39] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[35]; +acadoWorkspace.lb[40] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[36]; +acadoWorkspace.lb[41] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[37]; +acadoWorkspace.lb[42] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[38]; +acadoWorkspace.lb[43] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[39]; +acadoWorkspace.lb[44] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[40]; +acadoWorkspace.lb[45] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[41]; +acadoWorkspace.lb[46] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[42]; +acadoWorkspace.lb[47] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[43]; +acadoWorkspace.lb[48] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[44]; +acadoWorkspace.lb[49] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[45]; +acadoWorkspace.lb[50] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[46]; +acadoWorkspace.lb[51] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[47]; +acadoWorkspace.lb[52] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[48]; +acadoWorkspace.lb[53] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[49]; +acadoWorkspace.ub[4] = (real_t)1.0000000000000001e-01 - acadoVariables.u[0]; +acadoWorkspace.ub[5] = (real_t)1.0000000000000001e-01 - acadoVariables.u[1]; +acadoWorkspace.ub[6] = (real_t)1.0000000000000001e-01 - acadoVariables.u[2]; +acadoWorkspace.ub[7] = (real_t)1.0000000000000001e-01 - acadoVariables.u[3]; +acadoWorkspace.ub[8] = (real_t)1.0000000000000001e-01 - acadoVariables.u[4]; +acadoWorkspace.ub[9] = (real_t)1.0000000000000001e-01 - acadoVariables.u[5]; +acadoWorkspace.ub[10] = (real_t)1.0000000000000001e-01 - acadoVariables.u[6]; +acadoWorkspace.ub[11] = (real_t)1.0000000000000001e-01 - acadoVariables.u[7]; +acadoWorkspace.ub[12] = (real_t)1.0000000000000001e-01 - acadoVariables.u[8]; +acadoWorkspace.ub[13] = (real_t)1.0000000000000001e-01 - acadoVariables.u[9]; +acadoWorkspace.ub[14] = (real_t)1.0000000000000001e-01 - acadoVariables.u[10]; +acadoWorkspace.ub[15] = (real_t)1.0000000000000001e-01 - acadoVariables.u[11]; +acadoWorkspace.ub[16] = (real_t)1.0000000000000001e-01 - acadoVariables.u[12]; +acadoWorkspace.ub[17] = (real_t)1.0000000000000001e-01 - acadoVariables.u[13]; +acadoWorkspace.ub[18] = (real_t)1.0000000000000001e-01 - acadoVariables.u[14]; +acadoWorkspace.ub[19] = (real_t)1.0000000000000001e-01 - acadoVariables.u[15]; +acadoWorkspace.ub[20] = (real_t)1.0000000000000001e-01 - acadoVariables.u[16]; +acadoWorkspace.ub[21] = (real_t)1.0000000000000001e-01 - acadoVariables.u[17]; +acadoWorkspace.ub[22] = (real_t)1.0000000000000001e-01 - acadoVariables.u[18]; +acadoWorkspace.ub[23] = (real_t)1.0000000000000001e-01 - acadoVariables.u[19]; +acadoWorkspace.ub[24] = (real_t)1.0000000000000001e-01 - acadoVariables.u[20]; +acadoWorkspace.ub[25] = (real_t)1.0000000000000001e-01 - acadoVariables.u[21]; +acadoWorkspace.ub[26] = (real_t)1.0000000000000001e-01 - acadoVariables.u[22]; +acadoWorkspace.ub[27] = (real_t)1.0000000000000001e-01 - acadoVariables.u[23]; +acadoWorkspace.ub[28] = (real_t)1.0000000000000001e-01 - acadoVariables.u[24]; +acadoWorkspace.ub[29] = (real_t)1.0000000000000001e-01 - acadoVariables.u[25]; +acadoWorkspace.ub[30] = (real_t)1.0000000000000001e-01 - acadoVariables.u[26]; +acadoWorkspace.ub[31] = (real_t)1.0000000000000001e-01 - acadoVariables.u[27]; +acadoWorkspace.ub[32] = (real_t)1.0000000000000001e-01 - acadoVariables.u[28]; +acadoWorkspace.ub[33] = (real_t)1.0000000000000001e-01 - acadoVariables.u[29]; +acadoWorkspace.ub[34] = (real_t)1.0000000000000001e-01 - acadoVariables.u[30]; +acadoWorkspace.ub[35] = (real_t)1.0000000000000001e-01 - acadoVariables.u[31]; +acadoWorkspace.ub[36] = (real_t)1.0000000000000001e-01 - acadoVariables.u[32]; +acadoWorkspace.ub[37] = (real_t)1.0000000000000001e-01 - acadoVariables.u[33]; +acadoWorkspace.ub[38] = (real_t)1.0000000000000001e-01 - acadoVariables.u[34]; +acadoWorkspace.ub[39] = (real_t)1.0000000000000001e-01 - acadoVariables.u[35]; +acadoWorkspace.ub[40] = (real_t)1.0000000000000001e-01 - acadoVariables.u[36]; +acadoWorkspace.ub[41] = (real_t)1.0000000000000001e-01 - acadoVariables.u[37]; +acadoWorkspace.ub[42] = (real_t)1.0000000000000001e-01 - acadoVariables.u[38]; +acadoWorkspace.ub[43] = (real_t)1.0000000000000001e-01 - acadoVariables.u[39]; +acadoWorkspace.ub[44] = (real_t)1.0000000000000001e-01 - acadoVariables.u[40]; +acadoWorkspace.ub[45] = (real_t)1.0000000000000001e-01 - acadoVariables.u[41]; +acadoWorkspace.ub[46] = (real_t)1.0000000000000001e-01 - acadoVariables.u[42]; +acadoWorkspace.ub[47] = (real_t)1.0000000000000001e-01 - acadoVariables.u[43]; +acadoWorkspace.ub[48] = (real_t)1.0000000000000001e-01 - acadoVariables.u[44]; +acadoWorkspace.ub[49] = (real_t)1.0000000000000001e-01 - acadoVariables.u[45]; +acadoWorkspace.ub[50] = (real_t)1.0000000000000001e-01 - acadoVariables.u[46]; +acadoWorkspace.ub[51] = (real_t)1.0000000000000001e-01 - acadoVariables.u[47]; +acadoWorkspace.ub[52] = (real_t)1.0000000000000001e-01 - acadoVariables.u[48]; +acadoWorkspace.ub[53] = (real_t)1.0000000000000001e-01 - acadoVariables.u[49]; + +for (lRun1 = 0; lRun1 < 100; ++lRun1) +{ +lRun3 = xBoundIndices[ lRun1 ] - 4; +lRun4 = ((lRun3) / (4)) + (1); +acadoWorkspace.A[lRun1 * 54] = acadoWorkspace.evGx[lRun3 * 4]; +acadoWorkspace.A[lRun1 * 54 + 1] = acadoWorkspace.evGx[lRun3 * 4 + 1]; +acadoWorkspace.A[lRun1 * 54 + 2] = acadoWorkspace.evGx[lRun3 * 4 + 2]; +acadoWorkspace.A[lRun1 * 54 + 3] = acadoWorkspace.evGx[lRun3 * 4 + 3]; +for (lRun2 = 0; lRun2 < lRun4; ++lRun2) +{ +lRun5 = (((((lRun4) * (lRun4-1)) / (2)) + (lRun2)) * (4)) + ((lRun3) % (4)); +acadoWorkspace.A[(lRun1 * 54) + (lRun2 + 4)] = acadoWorkspace.E[lRun5]; +} +} + +} + +void acado_condenseFdb( ) +{ +int lRun1; +int lRun2; +int lRun3; +real_t tmp; + +acadoWorkspace.Dx0[0] = acadoVariables.x0[0] - acadoVariables.x[0]; +acadoWorkspace.Dx0[1] = acadoVariables.x0[1] - acadoVariables.x[1]; +acadoWorkspace.Dx0[2] = acadoVariables.x0[2] - acadoVariables.x[2]; +acadoWorkspace.Dx0[3] = acadoVariables.x0[3] - acadoVariables.x[3]; + +for (lRun2 = 0; lRun2 < 250; ++lRun2) +acadoWorkspace.Dy[lRun2] -= acadoVariables.y[lRun2]; + +acadoWorkspace.DyN[0] -= acadoVariables.yN[0]; +acadoWorkspace.DyN[1] -= acadoVariables.yN[1]; +acadoWorkspace.DyN[2] -= acadoVariables.yN[2]; +acadoWorkspace.DyN[3] -= acadoVariables.yN[3]; + +acado_multRDy( acadoWorkspace.R2, acadoWorkspace.Dy, &(acadoWorkspace.g[ 4 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 5 ]), &(acadoWorkspace.Dy[ 5 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 10 ]), &(acadoWorkspace.Dy[ 10 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 15 ]), &(acadoWorkspace.Dy[ 15 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 20 ]), &(acadoWorkspace.Dy[ 20 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 25 ]), &(acadoWorkspace.Dy[ 25 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 30 ]), &(acadoWorkspace.Dy[ 30 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 35 ]), &(acadoWorkspace.Dy[ 35 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 40 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 45 ]), &(acadoWorkspace.Dy[ 45 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 50 ]), &(acadoWorkspace.Dy[ 50 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 55 ]), &(acadoWorkspace.Dy[ 55 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 60 ]), &(acadoWorkspace.Dy[ 60 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 65 ]), &(acadoWorkspace.Dy[ 65 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 70 ]), &(acadoWorkspace.Dy[ 70 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 75 ]), &(acadoWorkspace.Dy[ 75 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 80 ]), &(acadoWorkspace.Dy[ 80 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 85 ]), &(acadoWorkspace.Dy[ 85 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 90 ]), &(acadoWorkspace.Dy[ 90 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 95 ]), &(acadoWorkspace.Dy[ 95 ]), &(acadoWorkspace.g[ 23 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 100 ]), &(acadoWorkspace.Dy[ 100 ]), &(acadoWorkspace.g[ 24 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 105 ]), &(acadoWorkspace.Dy[ 105 ]), &(acadoWorkspace.g[ 25 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 110 ]), &(acadoWorkspace.Dy[ 110 ]), &(acadoWorkspace.g[ 26 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 115 ]), &(acadoWorkspace.Dy[ 115 ]), &(acadoWorkspace.g[ 27 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 120 ]), &(acadoWorkspace.Dy[ 120 ]), &(acadoWorkspace.g[ 28 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 125 ]), &(acadoWorkspace.Dy[ 125 ]), &(acadoWorkspace.g[ 29 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 130 ]), &(acadoWorkspace.Dy[ 130 ]), &(acadoWorkspace.g[ 30 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 135 ]), &(acadoWorkspace.Dy[ 135 ]), &(acadoWorkspace.g[ 31 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 140 ]), &(acadoWorkspace.Dy[ 140 ]), &(acadoWorkspace.g[ 32 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 145 ]), &(acadoWorkspace.Dy[ 145 ]), &(acadoWorkspace.g[ 33 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 150 ]), &(acadoWorkspace.Dy[ 150 ]), &(acadoWorkspace.g[ 34 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 155 ]), &(acadoWorkspace.Dy[ 155 ]), &(acadoWorkspace.g[ 35 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 160 ]), &(acadoWorkspace.Dy[ 160 ]), &(acadoWorkspace.g[ 36 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 165 ]), &(acadoWorkspace.Dy[ 165 ]), &(acadoWorkspace.g[ 37 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 170 ]), &(acadoWorkspace.Dy[ 170 ]), &(acadoWorkspace.g[ 38 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 175 ]), &(acadoWorkspace.Dy[ 175 ]), &(acadoWorkspace.g[ 39 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 180 ]), &(acadoWorkspace.Dy[ 180 ]), &(acadoWorkspace.g[ 40 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 185 ]), &(acadoWorkspace.Dy[ 185 ]), &(acadoWorkspace.g[ 41 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 190 ]), &(acadoWorkspace.Dy[ 190 ]), &(acadoWorkspace.g[ 42 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 195 ]), &(acadoWorkspace.Dy[ 195 ]), &(acadoWorkspace.g[ 43 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 200 ]), &(acadoWorkspace.Dy[ 200 ]), &(acadoWorkspace.g[ 44 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 205 ]), &(acadoWorkspace.Dy[ 205 ]), &(acadoWorkspace.g[ 45 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 210 ]), &(acadoWorkspace.Dy[ 210 ]), &(acadoWorkspace.g[ 46 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 215 ]), &(acadoWorkspace.Dy[ 215 ]), &(acadoWorkspace.g[ 47 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 220 ]), &(acadoWorkspace.Dy[ 220 ]), &(acadoWorkspace.g[ 48 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 225 ]), &(acadoWorkspace.Dy[ 225 ]), &(acadoWorkspace.g[ 49 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 230 ]), &(acadoWorkspace.Dy[ 230 ]), &(acadoWorkspace.g[ 50 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 235 ]), &(acadoWorkspace.Dy[ 235 ]), &(acadoWorkspace.g[ 51 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 240 ]), &(acadoWorkspace.Dy[ 240 ]), &(acadoWorkspace.g[ 52 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 245 ]), &(acadoWorkspace.Dy[ 245 ]), &(acadoWorkspace.g[ 53 ]) ); + +acado_multQDy( acadoWorkspace.Q2, acadoWorkspace.Dy, acadoWorkspace.QDy ); +acado_multQDy( &(acadoWorkspace.Q2[ 20 ]), &(acadoWorkspace.Dy[ 5 ]), &(acadoWorkspace.QDy[ 4 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 40 ]), &(acadoWorkspace.Dy[ 10 ]), &(acadoWorkspace.QDy[ 8 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 60 ]), &(acadoWorkspace.Dy[ 15 ]), &(acadoWorkspace.QDy[ 12 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 80 ]), &(acadoWorkspace.Dy[ 20 ]), &(acadoWorkspace.QDy[ 16 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 100 ]), &(acadoWorkspace.Dy[ 25 ]), &(acadoWorkspace.QDy[ 20 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 120 ]), &(acadoWorkspace.Dy[ 30 ]), &(acadoWorkspace.QDy[ 24 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 140 ]), &(acadoWorkspace.Dy[ 35 ]), &(acadoWorkspace.QDy[ 28 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 160 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.QDy[ 32 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 180 ]), &(acadoWorkspace.Dy[ 45 ]), &(acadoWorkspace.QDy[ 36 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 200 ]), &(acadoWorkspace.Dy[ 50 ]), &(acadoWorkspace.QDy[ 40 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 220 ]), &(acadoWorkspace.Dy[ 55 ]), &(acadoWorkspace.QDy[ 44 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 240 ]), &(acadoWorkspace.Dy[ 60 ]), &(acadoWorkspace.QDy[ 48 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 260 ]), &(acadoWorkspace.Dy[ 65 ]), &(acadoWorkspace.QDy[ 52 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 280 ]), &(acadoWorkspace.Dy[ 70 ]), &(acadoWorkspace.QDy[ 56 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 300 ]), &(acadoWorkspace.Dy[ 75 ]), &(acadoWorkspace.QDy[ 60 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 320 ]), &(acadoWorkspace.Dy[ 80 ]), &(acadoWorkspace.QDy[ 64 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 340 ]), &(acadoWorkspace.Dy[ 85 ]), &(acadoWorkspace.QDy[ 68 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 360 ]), &(acadoWorkspace.Dy[ 90 ]), &(acadoWorkspace.QDy[ 72 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 380 ]), &(acadoWorkspace.Dy[ 95 ]), &(acadoWorkspace.QDy[ 76 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 400 ]), &(acadoWorkspace.Dy[ 100 ]), &(acadoWorkspace.QDy[ 80 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 420 ]), &(acadoWorkspace.Dy[ 105 ]), &(acadoWorkspace.QDy[ 84 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 440 ]), &(acadoWorkspace.Dy[ 110 ]), &(acadoWorkspace.QDy[ 88 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 460 ]), &(acadoWorkspace.Dy[ 115 ]), &(acadoWorkspace.QDy[ 92 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 480 ]), &(acadoWorkspace.Dy[ 120 ]), &(acadoWorkspace.QDy[ 96 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 500 ]), &(acadoWorkspace.Dy[ 125 ]), &(acadoWorkspace.QDy[ 100 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 520 ]), &(acadoWorkspace.Dy[ 130 ]), &(acadoWorkspace.QDy[ 104 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 540 ]), &(acadoWorkspace.Dy[ 135 ]), &(acadoWorkspace.QDy[ 108 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 560 ]), &(acadoWorkspace.Dy[ 140 ]), &(acadoWorkspace.QDy[ 112 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 580 ]), &(acadoWorkspace.Dy[ 145 ]), &(acadoWorkspace.QDy[ 116 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 600 ]), &(acadoWorkspace.Dy[ 150 ]), &(acadoWorkspace.QDy[ 120 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 620 ]), &(acadoWorkspace.Dy[ 155 ]), &(acadoWorkspace.QDy[ 124 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 640 ]), &(acadoWorkspace.Dy[ 160 ]), &(acadoWorkspace.QDy[ 128 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 660 ]), &(acadoWorkspace.Dy[ 165 ]), &(acadoWorkspace.QDy[ 132 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 680 ]), &(acadoWorkspace.Dy[ 170 ]), &(acadoWorkspace.QDy[ 136 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 700 ]), &(acadoWorkspace.Dy[ 175 ]), &(acadoWorkspace.QDy[ 140 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 720 ]), &(acadoWorkspace.Dy[ 180 ]), &(acadoWorkspace.QDy[ 144 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 740 ]), &(acadoWorkspace.Dy[ 185 ]), &(acadoWorkspace.QDy[ 148 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 760 ]), &(acadoWorkspace.Dy[ 190 ]), &(acadoWorkspace.QDy[ 152 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 780 ]), &(acadoWorkspace.Dy[ 195 ]), &(acadoWorkspace.QDy[ 156 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 800 ]), &(acadoWorkspace.Dy[ 200 ]), &(acadoWorkspace.QDy[ 160 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 820 ]), &(acadoWorkspace.Dy[ 205 ]), &(acadoWorkspace.QDy[ 164 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 840 ]), &(acadoWorkspace.Dy[ 210 ]), &(acadoWorkspace.QDy[ 168 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 860 ]), &(acadoWorkspace.Dy[ 215 ]), &(acadoWorkspace.QDy[ 172 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 880 ]), &(acadoWorkspace.Dy[ 220 ]), &(acadoWorkspace.QDy[ 176 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 900 ]), &(acadoWorkspace.Dy[ 225 ]), &(acadoWorkspace.QDy[ 180 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 920 ]), &(acadoWorkspace.Dy[ 230 ]), &(acadoWorkspace.QDy[ 184 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 940 ]), &(acadoWorkspace.Dy[ 235 ]), &(acadoWorkspace.QDy[ 188 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 960 ]), &(acadoWorkspace.Dy[ 240 ]), &(acadoWorkspace.QDy[ 192 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 980 ]), &(acadoWorkspace.Dy[ 245 ]), &(acadoWorkspace.QDy[ 196 ]) ); + +acadoWorkspace.QDy[200] = + acadoWorkspace.QN2[0]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[1]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[2]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[3]*acadoWorkspace.DyN[3]; +acadoWorkspace.QDy[201] = + acadoWorkspace.QN2[4]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[5]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[6]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[7]*acadoWorkspace.DyN[3]; +acadoWorkspace.QDy[202] = + acadoWorkspace.QN2[8]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[9]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[10]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[11]*acadoWorkspace.DyN[3]; +acadoWorkspace.QDy[203] = + acadoWorkspace.QN2[12]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[13]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[14]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[15]*acadoWorkspace.DyN[3]; + +for (lRun2 = 0; lRun2 < 200; ++lRun2) +acadoWorkspace.QDy[lRun2 + 4] += acadoWorkspace.Qd[lRun2]; + + +acadoWorkspace.g[0] = + acadoWorkspace.evGx[0]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[4]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[8]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[12]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[16]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[20]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[24]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[28]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[32]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[36]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[40]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[44]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[48]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[52]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[56]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[60]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[64]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[68]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[72]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[76]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[80]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[84]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[88]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[92]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[96]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[100]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[104]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[108]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[112]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[116]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[120]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[124]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[128]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[132]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[136]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[140]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[144]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[148]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[152]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[156]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[160]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[164]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[168]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[172]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[176]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[180]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[184]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[188]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[192]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[196]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[200]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[204]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[208]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[212]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[216]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[220]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[224]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[228]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[232]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[236]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[240]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[244]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[248]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[252]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[256]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[260]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[264]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[268]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[272]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[276]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[280]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[284]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[288]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[292]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[296]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[300]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[304]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[308]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[312]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[316]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[320]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[324]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[328]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[332]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[336]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[340]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[344]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[348]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[352]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[356]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[360]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[364]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[368]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[372]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[376]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[380]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[384]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[388]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[392]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[396]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[400]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[404]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[408]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[412]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[416]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[420]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[424]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[428]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[432]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[436]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[440]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[444]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[448]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[452]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[456]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[460]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[464]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[468]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[472]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[476]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[480]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[484]*acadoWorkspace.QDy[125] + acadoWorkspace.evGx[488]*acadoWorkspace.QDy[126] + acadoWorkspace.evGx[492]*acadoWorkspace.QDy[127] + acadoWorkspace.evGx[496]*acadoWorkspace.QDy[128] + acadoWorkspace.evGx[500]*acadoWorkspace.QDy[129] + acadoWorkspace.evGx[504]*acadoWorkspace.QDy[130] + acadoWorkspace.evGx[508]*acadoWorkspace.QDy[131] + acadoWorkspace.evGx[512]*acadoWorkspace.QDy[132] + acadoWorkspace.evGx[516]*acadoWorkspace.QDy[133] + acadoWorkspace.evGx[520]*acadoWorkspace.QDy[134] + acadoWorkspace.evGx[524]*acadoWorkspace.QDy[135] + acadoWorkspace.evGx[528]*acadoWorkspace.QDy[136] + acadoWorkspace.evGx[532]*acadoWorkspace.QDy[137] + acadoWorkspace.evGx[536]*acadoWorkspace.QDy[138] + acadoWorkspace.evGx[540]*acadoWorkspace.QDy[139] + acadoWorkspace.evGx[544]*acadoWorkspace.QDy[140] + acadoWorkspace.evGx[548]*acadoWorkspace.QDy[141] + acadoWorkspace.evGx[552]*acadoWorkspace.QDy[142] + acadoWorkspace.evGx[556]*acadoWorkspace.QDy[143] + acadoWorkspace.evGx[560]*acadoWorkspace.QDy[144] + acadoWorkspace.evGx[564]*acadoWorkspace.QDy[145] + acadoWorkspace.evGx[568]*acadoWorkspace.QDy[146] + acadoWorkspace.evGx[572]*acadoWorkspace.QDy[147] + acadoWorkspace.evGx[576]*acadoWorkspace.QDy[148] + acadoWorkspace.evGx[580]*acadoWorkspace.QDy[149] + acadoWorkspace.evGx[584]*acadoWorkspace.QDy[150] + acadoWorkspace.evGx[588]*acadoWorkspace.QDy[151] + acadoWorkspace.evGx[592]*acadoWorkspace.QDy[152] + acadoWorkspace.evGx[596]*acadoWorkspace.QDy[153] + acadoWorkspace.evGx[600]*acadoWorkspace.QDy[154] + acadoWorkspace.evGx[604]*acadoWorkspace.QDy[155] + acadoWorkspace.evGx[608]*acadoWorkspace.QDy[156] + acadoWorkspace.evGx[612]*acadoWorkspace.QDy[157] + acadoWorkspace.evGx[616]*acadoWorkspace.QDy[158] + acadoWorkspace.evGx[620]*acadoWorkspace.QDy[159] + acadoWorkspace.evGx[624]*acadoWorkspace.QDy[160] + acadoWorkspace.evGx[628]*acadoWorkspace.QDy[161] + acadoWorkspace.evGx[632]*acadoWorkspace.QDy[162] + acadoWorkspace.evGx[636]*acadoWorkspace.QDy[163] + acadoWorkspace.evGx[640]*acadoWorkspace.QDy[164] + acadoWorkspace.evGx[644]*acadoWorkspace.QDy[165] + acadoWorkspace.evGx[648]*acadoWorkspace.QDy[166] + acadoWorkspace.evGx[652]*acadoWorkspace.QDy[167] + acadoWorkspace.evGx[656]*acadoWorkspace.QDy[168] + acadoWorkspace.evGx[660]*acadoWorkspace.QDy[169] + acadoWorkspace.evGx[664]*acadoWorkspace.QDy[170] + acadoWorkspace.evGx[668]*acadoWorkspace.QDy[171] + acadoWorkspace.evGx[672]*acadoWorkspace.QDy[172] + acadoWorkspace.evGx[676]*acadoWorkspace.QDy[173] + acadoWorkspace.evGx[680]*acadoWorkspace.QDy[174] + acadoWorkspace.evGx[684]*acadoWorkspace.QDy[175] + acadoWorkspace.evGx[688]*acadoWorkspace.QDy[176] + acadoWorkspace.evGx[692]*acadoWorkspace.QDy[177] + acadoWorkspace.evGx[696]*acadoWorkspace.QDy[178] + acadoWorkspace.evGx[700]*acadoWorkspace.QDy[179] + acadoWorkspace.evGx[704]*acadoWorkspace.QDy[180] + acadoWorkspace.evGx[708]*acadoWorkspace.QDy[181] + acadoWorkspace.evGx[712]*acadoWorkspace.QDy[182] + acadoWorkspace.evGx[716]*acadoWorkspace.QDy[183] + acadoWorkspace.evGx[720]*acadoWorkspace.QDy[184] + acadoWorkspace.evGx[724]*acadoWorkspace.QDy[185] + acadoWorkspace.evGx[728]*acadoWorkspace.QDy[186] + acadoWorkspace.evGx[732]*acadoWorkspace.QDy[187] + acadoWorkspace.evGx[736]*acadoWorkspace.QDy[188] + acadoWorkspace.evGx[740]*acadoWorkspace.QDy[189] + acadoWorkspace.evGx[744]*acadoWorkspace.QDy[190] + acadoWorkspace.evGx[748]*acadoWorkspace.QDy[191] + acadoWorkspace.evGx[752]*acadoWorkspace.QDy[192] + acadoWorkspace.evGx[756]*acadoWorkspace.QDy[193] + acadoWorkspace.evGx[760]*acadoWorkspace.QDy[194] + acadoWorkspace.evGx[764]*acadoWorkspace.QDy[195] + acadoWorkspace.evGx[768]*acadoWorkspace.QDy[196] + acadoWorkspace.evGx[772]*acadoWorkspace.QDy[197] + acadoWorkspace.evGx[776]*acadoWorkspace.QDy[198] + acadoWorkspace.evGx[780]*acadoWorkspace.QDy[199] + acadoWorkspace.evGx[784]*acadoWorkspace.QDy[200] + acadoWorkspace.evGx[788]*acadoWorkspace.QDy[201] + acadoWorkspace.evGx[792]*acadoWorkspace.QDy[202] + acadoWorkspace.evGx[796]*acadoWorkspace.QDy[203]; +acadoWorkspace.g[1] = + acadoWorkspace.evGx[1]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[5]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[9]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[13]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[17]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[21]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[25]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[29]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[33]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[37]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[41]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[45]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[49]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[53]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[57]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[61]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[65]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[69]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[73]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[77]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[81]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[85]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[89]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[93]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[97]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[101]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[105]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[109]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[113]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[117]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[121]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[125]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[129]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[133]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[137]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[141]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[145]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[149]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[153]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[157]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[161]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[165]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[169]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[173]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[177]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[181]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[185]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[189]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[193]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[197]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[201]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[205]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[209]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[213]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[217]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[221]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[225]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[229]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[233]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[237]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[241]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[245]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[249]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[253]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[257]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[261]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[265]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[269]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[273]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[277]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[281]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[285]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[289]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[293]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[297]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[301]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[305]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[309]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[313]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[317]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[321]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[325]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[329]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[333]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[337]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[341]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[345]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[349]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[353]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[357]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[361]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[365]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[369]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[373]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[377]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[381]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[385]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[389]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[393]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[397]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[401]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[405]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[409]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[413]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[417]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[421]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[425]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[429]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[433]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[437]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[441]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[445]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[449]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[453]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[457]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[461]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[465]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[469]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[473]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[477]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[481]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[485]*acadoWorkspace.QDy[125] + acadoWorkspace.evGx[489]*acadoWorkspace.QDy[126] + acadoWorkspace.evGx[493]*acadoWorkspace.QDy[127] + acadoWorkspace.evGx[497]*acadoWorkspace.QDy[128] + acadoWorkspace.evGx[501]*acadoWorkspace.QDy[129] + acadoWorkspace.evGx[505]*acadoWorkspace.QDy[130] + acadoWorkspace.evGx[509]*acadoWorkspace.QDy[131] + acadoWorkspace.evGx[513]*acadoWorkspace.QDy[132] + acadoWorkspace.evGx[517]*acadoWorkspace.QDy[133] + acadoWorkspace.evGx[521]*acadoWorkspace.QDy[134] + acadoWorkspace.evGx[525]*acadoWorkspace.QDy[135] + acadoWorkspace.evGx[529]*acadoWorkspace.QDy[136] + acadoWorkspace.evGx[533]*acadoWorkspace.QDy[137] + acadoWorkspace.evGx[537]*acadoWorkspace.QDy[138] + acadoWorkspace.evGx[541]*acadoWorkspace.QDy[139] + acadoWorkspace.evGx[545]*acadoWorkspace.QDy[140] + acadoWorkspace.evGx[549]*acadoWorkspace.QDy[141] + acadoWorkspace.evGx[553]*acadoWorkspace.QDy[142] + acadoWorkspace.evGx[557]*acadoWorkspace.QDy[143] + acadoWorkspace.evGx[561]*acadoWorkspace.QDy[144] + acadoWorkspace.evGx[565]*acadoWorkspace.QDy[145] + acadoWorkspace.evGx[569]*acadoWorkspace.QDy[146] + acadoWorkspace.evGx[573]*acadoWorkspace.QDy[147] + acadoWorkspace.evGx[577]*acadoWorkspace.QDy[148] + acadoWorkspace.evGx[581]*acadoWorkspace.QDy[149] + acadoWorkspace.evGx[585]*acadoWorkspace.QDy[150] + acadoWorkspace.evGx[589]*acadoWorkspace.QDy[151] + acadoWorkspace.evGx[593]*acadoWorkspace.QDy[152] + acadoWorkspace.evGx[597]*acadoWorkspace.QDy[153] + acadoWorkspace.evGx[601]*acadoWorkspace.QDy[154] + acadoWorkspace.evGx[605]*acadoWorkspace.QDy[155] + acadoWorkspace.evGx[609]*acadoWorkspace.QDy[156] + acadoWorkspace.evGx[613]*acadoWorkspace.QDy[157] + acadoWorkspace.evGx[617]*acadoWorkspace.QDy[158] + acadoWorkspace.evGx[621]*acadoWorkspace.QDy[159] + acadoWorkspace.evGx[625]*acadoWorkspace.QDy[160] + acadoWorkspace.evGx[629]*acadoWorkspace.QDy[161] + acadoWorkspace.evGx[633]*acadoWorkspace.QDy[162] + acadoWorkspace.evGx[637]*acadoWorkspace.QDy[163] + acadoWorkspace.evGx[641]*acadoWorkspace.QDy[164] + acadoWorkspace.evGx[645]*acadoWorkspace.QDy[165] + acadoWorkspace.evGx[649]*acadoWorkspace.QDy[166] + acadoWorkspace.evGx[653]*acadoWorkspace.QDy[167] + acadoWorkspace.evGx[657]*acadoWorkspace.QDy[168] + acadoWorkspace.evGx[661]*acadoWorkspace.QDy[169] + acadoWorkspace.evGx[665]*acadoWorkspace.QDy[170] + acadoWorkspace.evGx[669]*acadoWorkspace.QDy[171] + acadoWorkspace.evGx[673]*acadoWorkspace.QDy[172] + acadoWorkspace.evGx[677]*acadoWorkspace.QDy[173] + acadoWorkspace.evGx[681]*acadoWorkspace.QDy[174] + acadoWorkspace.evGx[685]*acadoWorkspace.QDy[175] + acadoWorkspace.evGx[689]*acadoWorkspace.QDy[176] + acadoWorkspace.evGx[693]*acadoWorkspace.QDy[177] + acadoWorkspace.evGx[697]*acadoWorkspace.QDy[178] + acadoWorkspace.evGx[701]*acadoWorkspace.QDy[179] + acadoWorkspace.evGx[705]*acadoWorkspace.QDy[180] + acadoWorkspace.evGx[709]*acadoWorkspace.QDy[181] + acadoWorkspace.evGx[713]*acadoWorkspace.QDy[182] + acadoWorkspace.evGx[717]*acadoWorkspace.QDy[183] + acadoWorkspace.evGx[721]*acadoWorkspace.QDy[184] + acadoWorkspace.evGx[725]*acadoWorkspace.QDy[185] + acadoWorkspace.evGx[729]*acadoWorkspace.QDy[186] + acadoWorkspace.evGx[733]*acadoWorkspace.QDy[187] + acadoWorkspace.evGx[737]*acadoWorkspace.QDy[188] + acadoWorkspace.evGx[741]*acadoWorkspace.QDy[189] + acadoWorkspace.evGx[745]*acadoWorkspace.QDy[190] + acadoWorkspace.evGx[749]*acadoWorkspace.QDy[191] + acadoWorkspace.evGx[753]*acadoWorkspace.QDy[192] + acadoWorkspace.evGx[757]*acadoWorkspace.QDy[193] + acadoWorkspace.evGx[761]*acadoWorkspace.QDy[194] + acadoWorkspace.evGx[765]*acadoWorkspace.QDy[195] + acadoWorkspace.evGx[769]*acadoWorkspace.QDy[196] + acadoWorkspace.evGx[773]*acadoWorkspace.QDy[197] + acadoWorkspace.evGx[777]*acadoWorkspace.QDy[198] + acadoWorkspace.evGx[781]*acadoWorkspace.QDy[199] + acadoWorkspace.evGx[785]*acadoWorkspace.QDy[200] + acadoWorkspace.evGx[789]*acadoWorkspace.QDy[201] + acadoWorkspace.evGx[793]*acadoWorkspace.QDy[202] + acadoWorkspace.evGx[797]*acadoWorkspace.QDy[203]; +acadoWorkspace.g[2] = + acadoWorkspace.evGx[2]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[6]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[10]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[14]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[18]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[22]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[26]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[30]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[34]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[38]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[42]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[46]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[50]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[54]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[58]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[62]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[66]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[70]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[74]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[78]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[82]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[86]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[90]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[94]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[98]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[102]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[106]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[110]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[114]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[118]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[122]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[126]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[130]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[134]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[138]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[142]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[146]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[150]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[154]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[158]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[162]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[166]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[170]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[174]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[178]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[182]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[186]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[190]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[194]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[198]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[202]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[206]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[210]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[214]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[218]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[222]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[226]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[230]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[234]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[238]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[242]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[246]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[250]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[254]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[258]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[262]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[266]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[270]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[274]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[278]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[282]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[286]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[290]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[294]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[298]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[302]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[306]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[310]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[314]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[318]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[322]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[326]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[330]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[334]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[338]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[342]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[346]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[350]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[354]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[358]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[362]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[366]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[370]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[374]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[378]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[382]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[386]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[390]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[394]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[398]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[402]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[406]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[410]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[414]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[418]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[422]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[426]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[430]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[434]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[438]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[442]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[446]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[450]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[454]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[458]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[462]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[466]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[470]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[474]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[478]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[482]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[486]*acadoWorkspace.QDy[125] + acadoWorkspace.evGx[490]*acadoWorkspace.QDy[126] + acadoWorkspace.evGx[494]*acadoWorkspace.QDy[127] + acadoWorkspace.evGx[498]*acadoWorkspace.QDy[128] + acadoWorkspace.evGx[502]*acadoWorkspace.QDy[129] + acadoWorkspace.evGx[506]*acadoWorkspace.QDy[130] + acadoWorkspace.evGx[510]*acadoWorkspace.QDy[131] + acadoWorkspace.evGx[514]*acadoWorkspace.QDy[132] + acadoWorkspace.evGx[518]*acadoWorkspace.QDy[133] + acadoWorkspace.evGx[522]*acadoWorkspace.QDy[134] + acadoWorkspace.evGx[526]*acadoWorkspace.QDy[135] + acadoWorkspace.evGx[530]*acadoWorkspace.QDy[136] + acadoWorkspace.evGx[534]*acadoWorkspace.QDy[137] + acadoWorkspace.evGx[538]*acadoWorkspace.QDy[138] + acadoWorkspace.evGx[542]*acadoWorkspace.QDy[139] + acadoWorkspace.evGx[546]*acadoWorkspace.QDy[140] + acadoWorkspace.evGx[550]*acadoWorkspace.QDy[141] + acadoWorkspace.evGx[554]*acadoWorkspace.QDy[142] + acadoWorkspace.evGx[558]*acadoWorkspace.QDy[143] + acadoWorkspace.evGx[562]*acadoWorkspace.QDy[144] + acadoWorkspace.evGx[566]*acadoWorkspace.QDy[145] + acadoWorkspace.evGx[570]*acadoWorkspace.QDy[146] + acadoWorkspace.evGx[574]*acadoWorkspace.QDy[147] + acadoWorkspace.evGx[578]*acadoWorkspace.QDy[148] + acadoWorkspace.evGx[582]*acadoWorkspace.QDy[149] + acadoWorkspace.evGx[586]*acadoWorkspace.QDy[150] + acadoWorkspace.evGx[590]*acadoWorkspace.QDy[151] + acadoWorkspace.evGx[594]*acadoWorkspace.QDy[152] + acadoWorkspace.evGx[598]*acadoWorkspace.QDy[153] + acadoWorkspace.evGx[602]*acadoWorkspace.QDy[154] + acadoWorkspace.evGx[606]*acadoWorkspace.QDy[155] + acadoWorkspace.evGx[610]*acadoWorkspace.QDy[156] + acadoWorkspace.evGx[614]*acadoWorkspace.QDy[157] + acadoWorkspace.evGx[618]*acadoWorkspace.QDy[158] + acadoWorkspace.evGx[622]*acadoWorkspace.QDy[159] + acadoWorkspace.evGx[626]*acadoWorkspace.QDy[160] + acadoWorkspace.evGx[630]*acadoWorkspace.QDy[161] + acadoWorkspace.evGx[634]*acadoWorkspace.QDy[162] + acadoWorkspace.evGx[638]*acadoWorkspace.QDy[163] + acadoWorkspace.evGx[642]*acadoWorkspace.QDy[164] + acadoWorkspace.evGx[646]*acadoWorkspace.QDy[165] + acadoWorkspace.evGx[650]*acadoWorkspace.QDy[166] + acadoWorkspace.evGx[654]*acadoWorkspace.QDy[167] + acadoWorkspace.evGx[658]*acadoWorkspace.QDy[168] + acadoWorkspace.evGx[662]*acadoWorkspace.QDy[169] + acadoWorkspace.evGx[666]*acadoWorkspace.QDy[170] + acadoWorkspace.evGx[670]*acadoWorkspace.QDy[171] + acadoWorkspace.evGx[674]*acadoWorkspace.QDy[172] + acadoWorkspace.evGx[678]*acadoWorkspace.QDy[173] + acadoWorkspace.evGx[682]*acadoWorkspace.QDy[174] + acadoWorkspace.evGx[686]*acadoWorkspace.QDy[175] + acadoWorkspace.evGx[690]*acadoWorkspace.QDy[176] + acadoWorkspace.evGx[694]*acadoWorkspace.QDy[177] + acadoWorkspace.evGx[698]*acadoWorkspace.QDy[178] + acadoWorkspace.evGx[702]*acadoWorkspace.QDy[179] + acadoWorkspace.evGx[706]*acadoWorkspace.QDy[180] + acadoWorkspace.evGx[710]*acadoWorkspace.QDy[181] + acadoWorkspace.evGx[714]*acadoWorkspace.QDy[182] + acadoWorkspace.evGx[718]*acadoWorkspace.QDy[183] + acadoWorkspace.evGx[722]*acadoWorkspace.QDy[184] + acadoWorkspace.evGx[726]*acadoWorkspace.QDy[185] + acadoWorkspace.evGx[730]*acadoWorkspace.QDy[186] + acadoWorkspace.evGx[734]*acadoWorkspace.QDy[187] + acadoWorkspace.evGx[738]*acadoWorkspace.QDy[188] + acadoWorkspace.evGx[742]*acadoWorkspace.QDy[189] + acadoWorkspace.evGx[746]*acadoWorkspace.QDy[190] + acadoWorkspace.evGx[750]*acadoWorkspace.QDy[191] + acadoWorkspace.evGx[754]*acadoWorkspace.QDy[192] + acadoWorkspace.evGx[758]*acadoWorkspace.QDy[193] + acadoWorkspace.evGx[762]*acadoWorkspace.QDy[194] + acadoWorkspace.evGx[766]*acadoWorkspace.QDy[195] + acadoWorkspace.evGx[770]*acadoWorkspace.QDy[196] + acadoWorkspace.evGx[774]*acadoWorkspace.QDy[197] + acadoWorkspace.evGx[778]*acadoWorkspace.QDy[198] + acadoWorkspace.evGx[782]*acadoWorkspace.QDy[199] + acadoWorkspace.evGx[786]*acadoWorkspace.QDy[200] + acadoWorkspace.evGx[790]*acadoWorkspace.QDy[201] + acadoWorkspace.evGx[794]*acadoWorkspace.QDy[202] + acadoWorkspace.evGx[798]*acadoWorkspace.QDy[203]; +acadoWorkspace.g[3] = + acadoWorkspace.evGx[3]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[7]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[11]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[15]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[19]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[23]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[27]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[31]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[35]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[39]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[43]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[47]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[51]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[55]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[59]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[63]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[67]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[71]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[75]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[79]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[83]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[87]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[91]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[95]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[99]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[103]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[107]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[111]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[115]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[119]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[123]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[127]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[131]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[135]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[139]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[143]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[147]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[151]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[155]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[159]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[163]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[167]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[171]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[175]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[179]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[183]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[187]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[191]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[195]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[199]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[203]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[207]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[211]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[215]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[219]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[223]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[227]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[231]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[235]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[239]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[243]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[247]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[251]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[255]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[259]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[263]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[267]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[271]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[275]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[279]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[283]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[287]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[291]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[295]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[299]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[303]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[307]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[311]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[315]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[319]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[323]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[327]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[331]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[335]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[339]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[343]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[347]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[351]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[355]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[359]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[363]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[367]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[371]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[375]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[379]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[383]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[387]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[391]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[395]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[399]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[403]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[407]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[411]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[415]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[419]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[423]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[427]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[431]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[435]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[439]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[443]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[447]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[451]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[455]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[459]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[463]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[467]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[471]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[475]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[479]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[483]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[487]*acadoWorkspace.QDy[125] + acadoWorkspace.evGx[491]*acadoWorkspace.QDy[126] + acadoWorkspace.evGx[495]*acadoWorkspace.QDy[127] + acadoWorkspace.evGx[499]*acadoWorkspace.QDy[128] + acadoWorkspace.evGx[503]*acadoWorkspace.QDy[129] + acadoWorkspace.evGx[507]*acadoWorkspace.QDy[130] + acadoWorkspace.evGx[511]*acadoWorkspace.QDy[131] + acadoWorkspace.evGx[515]*acadoWorkspace.QDy[132] + acadoWorkspace.evGx[519]*acadoWorkspace.QDy[133] + acadoWorkspace.evGx[523]*acadoWorkspace.QDy[134] + acadoWorkspace.evGx[527]*acadoWorkspace.QDy[135] + acadoWorkspace.evGx[531]*acadoWorkspace.QDy[136] + acadoWorkspace.evGx[535]*acadoWorkspace.QDy[137] + acadoWorkspace.evGx[539]*acadoWorkspace.QDy[138] + acadoWorkspace.evGx[543]*acadoWorkspace.QDy[139] + acadoWorkspace.evGx[547]*acadoWorkspace.QDy[140] + acadoWorkspace.evGx[551]*acadoWorkspace.QDy[141] + acadoWorkspace.evGx[555]*acadoWorkspace.QDy[142] + acadoWorkspace.evGx[559]*acadoWorkspace.QDy[143] + acadoWorkspace.evGx[563]*acadoWorkspace.QDy[144] + acadoWorkspace.evGx[567]*acadoWorkspace.QDy[145] + acadoWorkspace.evGx[571]*acadoWorkspace.QDy[146] + acadoWorkspace.evGx[575]*acadoWorkspace.QDy[147] + acadoWorkspace.evGx[579]*acadoWorkspace.QDy[148] + acadoWorkspace.evGx[583]*acadoWorkspace.QDy[149] + acadoWorkspace.evGx[587]*acadoWorkspace.QDy[150] + acadoWorkspace.evGx[591]*acadoWorkspace.QDy[151] + acadoWorkspace.evGx[595]*acadoWorkspace.QDy[152] + acadoWorkspace.evGx[599]*acadoWorkspace.QDy[153] + acadoWorkspace.evGx[603]*acadoWorkspace.QDy[154] + acadoWorkspace.evGx[607]*acadoWorkspace.QDy[155] + acadoWorkspace.evGx[611]*acadoWorkspace.QDy[156] + acadoWorkspace.evGx[615]*acadoWorkspace.QDy[157] + acadoWorkspace.evGx[619]*acadoWorkspace.QDy[158] + acadoWorkspace.evGx[623]*acadoWorkspace.QDy[159] + acadoWorkspace.evGx[627]*acadoWorkspace.QDy[160] + acadoWorkspace.evGx[631]*acadoWorkspace.QDy[161] + acadoWorkspace.evGx[635]*acadoWorkspace.QDy[162] + acadoWorkspace.evGx[639]*acadoWorkspace.QDy[163] + acadoWorkspace.evGx[643]*acadoWorkspace.QDy[164] + acadoWorkspace.evGx[647]*acadoWorkspace.QDy[165] + acadoWorkspace.evGx[651]*acadoWorkspace.QDy[166] + acadoWorkspace.evGx[655]*acadoWorkspace.QDy[167] + acadoWorkspace.evGx[659]*acadoWorkspace.QDy[168] + acadoWorkspace.evGx[663]*acadoWorkspace.QDy[169] + acadoWorkspace.evGx[667]*acadoWorkspace.QDy[170] + acadoWorkspace.evGx[671]*acadoWorkspace.QDy[171] + acadoWorkspace.evGx[675]*acadoWorkspace.QDy[172] + acadoWorkspace.evGx[679]*acadoWorkspace.QDy[173] + acadoWorkspace.evGx[683]*acadoWorkspace.QDy[174] + acadoWorkspace.evGx[687]*acadoWorkspace.QDy[175] + acadoWorkspace.evGx[691]*acadoWorkspace.QDy[176] + acadoWorkspace.evGx[695]*acadoWorkspace.QDy[177] + acadoWorkspace.evGx[699]*acadoWorkspace.QDy[178] + acadoWorkspace.evGx[703]*acadoWorkspace.QDy[179] + acadoWorkspace.evGx[707]*acadoWorkspace.QDy[180] + acadoWorkspace.evGx[711]*acadoWorkspace.QDy[181] + acadoWorkspace.evGx[715]*acadoWorkspace.QDy[182] + acadoWorkspace.evGx[719]*acadoWorkspace.QDy[183] + acadoWorkspace.evGx[723]*acadoWorkspace.QDy[184] + acadoWorkspace.evGx[727]*acadoWorkspace.QDy[185] + acadoWorkspace.evGx[731]*acadoWorkspace.QDy[186] + acadoWorkspace.evGx[735]*acadoWorkspace.QDy[187] + acadoWorkspace.evGx[739]*acadoWorkspace.QDy[188] + acadoWorkspace.evGx[743]*acadoWorkspace.QDy[189] + acadoWorkspace.evGx[747]*acadoWorkspace.QDy[190] + acadoWorkspace.evGx[751]*acadoWorkspace.QDy[191] + acadoWorkspace.evGx[755]*acadoWorkspace.QDy[192] + acadoWorkspace.evGx[759]*acadoWorkspace.QDy[193] + acadoWorkspace.evGx[763]*acadoWorkspace.QDy[194] + acadoWorkspace.evGx[767]*acadoWorkspace.QDy[195] + acadoWorkspace.evGx[771]*acadoWorkspace.QDy[196] + acadoWorkspace.evGx[775]*acadoWorkspace.QDy[197] + acadoWorkspace.evGx[779]*acadoWorkspace.QDy[198] + acadoWorkspace.evGx[783]*acadoWorkspace.QDy[199] + acadoWorkspace.evGx[787]*acadoWorkspace.QDy[200] + acadoWorkspace.evGx[791]*acadoWorkspace.QDy[201] + acadoWorkspace.evGx[795]*acadoWorkspace.QDy[202] + acadoWorkspace.evGx[799]*acadoWorkspace.QDy[203]; + + +for (lRun1 = 0; lRun1 < 50; ++lRun1) +{ +for (lRun2 = lRun1; lRun2 < 50; ++lRun2) +{ +lRun3 = (((lRun2 + 1) * (lRun2)) / (2)) + (lRun1); +acado_multEQDy( &(acadoWorkspace.E[ lRun3 * 4 ]), &(acadoWorkspace.QDy[ lRun2 * 4 + 4 ]), &(acadoWorkspace.g[ lRun1 + 4 ]) ); +} +} + +acadoWorkspace.lb[0] = acadoWorkspace.Dx0[0]; +acadoWorkspace.lb[1] = acadoWorkspace.Dx0[1]; +acadoWorkspace.lb[2] = acadoWorkspace.Dx0[2]; +acadoWorkspace.lb[3] = acadoWorkspace.Dx0[3]; +acadoWorkspace.ub[0] = acadoWorkspace.Dx0[0]; +acadoWorkspace.ub[1] = acadoWorkspace.Dx0[1]; +acadoWorkspace.ub[2] = acadoWorkspace.Dx0[2]; +acadoWorkspace.ub[3] = acadoWorkspace.Dx0[3]; +tmp = acadoVariables.x[6] + acadoWorkspace.d[2]; +acadoWorkspace.lbA[0] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[0] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[7] + acadoWorkspace.d[3]; +acadoWorkspace.lbA[1] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[1] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[10] + acadoWorkspace.d[6]; +acadoWorkspace.lbA[2] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[2] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[11] + acadoWorkspace.d[7]; +acadoWorkspace.lbA[3] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[3] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[14] + acadoWorkspace.d[10]; +acadoWorkspace.lbA[4] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[4] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[15] + acadoWorkspace.d[11]; +acadoWorkspace.lbA[5] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[5] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[18] + acadoWorkspace.d[14]; +acadoWorkspace.lbA[6] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[6] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[19] + acadoWorkspace.d[15]; +acadoWorkspace.lbA[7] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[7] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[22] + acadoWorkspace.d[18]; +acadoWorkspace.lbA[8] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[8] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[23] + acadoWorkspace.d[19]; +acadoWorkspace.lbA[9] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[9] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[26] + acadoWorkspace.d[22]; +acadoWorkspace.lbA[10] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[10] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[27] + acadoWorkspace.d[23]; +acadoWorkspace.lbA[11] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[11] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[30] + acadoWorkspace.d[26]; +acadoWorkspace.lbA[12] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[12] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[31] + acadoWorkspace.d[27]; +acadoWorkspace.lbA[13] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[13] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[34] + acadoWorkspace.d[30]; +acadoWorkspace.lbA[14] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[14] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[35] + acadoWorkspace.d[31]; +acadoWorkspace.lbA[15] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[15] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[38] + acadoWorkspace.d[34]; +acadoWorkspace.lbA[16] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[16] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[39] + acadoWorkspace.d[35]; +acadoWorkspace.lbA[17] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[17] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[42] + acadoWorkspace.d[38]; +acadoWorkspace.lbA[18] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[18] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[43] + acadoWorkspace.d[39]; +acadoWorkspace.lbA[19] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[19] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[46] + acadoWorkspace.d[42]; +acadoWorkspace.lbA[20] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[20] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[47] + acadoWorkspace.d[43]; +acadoWorkspace.lbA[21] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[21] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[50] + acadoWorkspace.d[46]; +acadoWorkspace.lbA[22] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[22] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[51] + acadoWorkspace.d[47]; +acadoWorkspace.lbA[23] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[23] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[54] + acadoWorkspace.d[50]; +acadoWorkspace.lbA[24] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[24] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[55] + acadoWorkspace.d[51]; +acadoWorkspace.lbA[25] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[25] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[58] + acadoWorkspace.d[54]; +acadoWorkspace.lbA[26] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[26] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[59] + acadoWorkspace.d[55]; +acadoWorkspace.lbA[27] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[27] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[62] + acadoWorkspace.d[58]; +acadoWorkspace.lbA[28] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[28] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[63] + acadoWorkspace.d[59]; +acadoWorkspace.lbA[29] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[29] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[66] + acadoWorkspace.d[62]; +acadoWorkspace.lbA[30] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[30] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[67] + acadoWorkspace.d[63]; +acadoWorkspace.lbA[31] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[31] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[70] + acadoWorkspace.d[66]; +acadoWorkspace.lbA[32] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[32] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[71] + acadoWorkspace.d[67]; +acadoWorkspace.lbA[33] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[33] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[74] + acadoWorkspace.d[70]; +acadoWorkspace.lbA[34] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[34] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[75] + acadoWorkspace.d[71]; +acadoWorkspace.lbA[35] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[35] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[78] + acadoWorkspace.d[74]; +acadoWorkspace.lbA[36] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[36] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[79] + acadoWorkspace.d[75]; +acadoWorkspace.lbA[37] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[37] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[82] + acadoWorkspace.d[78]; +acadoWorkspace.lbA[38] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[38] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[83] + acadoWorkspace.d[79]; +acadoWorkspace.lbA[39] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[39] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[86] + acadoWorkspace.d[82]; +acadoWorkspace.lbA[40] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[40] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[87] + acadoWorkspace.d[83]; +acadoWorkspace.lbA[41] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[41] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[90] + acadoWorkspace.d[86]; +acadoWorkspace.lbA[42] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[42] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[91] + acadoWorkspace.d[87]; +acadoWorkspace.lbA[43] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[43] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[94] + acadoWorkspace.d[90]; +acadoWorkspace.lbA[44] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[44] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[95] + acadoWorkspace.d[91]; +acadoWorkspace.lbA[45] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[45] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[98] + acadoWorkspace.d[94]; +acadoWorkspace.lbA[46] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[46] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[99] + acadoWorkspace.d[95]; +acadoWorkspace.lbA[47] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[47] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[102] + acadoWorkspace.d[98]; +acadoWorkspace.lbA[48] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[48] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[103] + acadoWorkspace.d[99]; +acadoWorkspace.lbA[49] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[49] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[106] + acadoWorkspace.d[102]; +acadoWorkspace.lbA[50] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[50] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[107] + acadoWorkspace.d[103]; +acadoWorkspace.lbA[51] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[51] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[110] + acadoWorkspace.d[106]; +acadoWorkspace.lbA[52] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[52] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[111] + acadoWorkspace.d[107]; +acadoWorkspace.lbA[53] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[53] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[114] + acadoWorkspace.d[110]; +acadoWorkspace.lbA[54] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[54] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[115] + acadoWorkspace.d[111]; +acadoWorkspace.lbA[55] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[55] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[118] + acadoWorkspace.d[114]; +acadoWorkspace.lbA[56] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[56] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[119] + acadoWorkspace.d[115]; +acadoWorkspace.lbA[57] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[57] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[122] + acadoWorkspace.d[118]; +acadoWorkspace.lbA[58] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[58] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[123] + acadoWorkspace.d[119]; +acadoWorkspace.lbA[59] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[59] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[126] + acadoWorkspace.d[122]; +acadoWorkspace.lbA[60] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[60] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[127] + acadoWorkspace.d[123]; +acadoWorkspace.lbA[61] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[61] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[130] + acadoWorkspace.d[126]; +acadoWorkspace.lbA[62] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[62] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[131] + acadoWorkspace.d[127]; +acadoWorkspace.lbA[63] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[63] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[134] + acadoWorkspace.d[130]; +acadoWorkspace.lbA[64] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[64] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[135] + acadoWorkspace.d[131]; +acadoWorkspace.lbA[65] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[65] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[138] + acadoWorkspace.d[134]; +acadoWorkspace.lbA[66] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[66] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[139] + acadoWorkspace.d[135]; +acadoWorkspace.lbA[67] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[67] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[142] + acadoWorkspace.d[138]; +acadoWorkspace.lbA[68] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[68] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[143] + acadoWorkspace.d[139]; +acadoWorkspace.lbA[69] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[69] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[146] + acadoWorkspace.d[142]; +acadoWorkspace.lbA[70] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[70] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[147] + acadoWorkspace.d[143]; +acadoWorkspace.lbA[71] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[71] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[150] + acadoWorkspace.d[146]; +acadoWorkspace.lbA[72] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[72] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[151] + acadoWorkspace.d[147]; +acadoWorkspace.lbA[73] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[73] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[154] + acadoWorkspace.d[150]; +acadoWorkspace.lbA[74] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[74] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[155] + acadoWorkspace.d[151]; +acadoWorkspace.lbA[75] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[75] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[158] + acadoWorkspace.d[154]; +acadoWorkspace.lbA[76] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[76] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[159] + acadoWorkspace.d[155]; +acadoWorkspace.lbA[77] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[77] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[162] + acadoWorkspace.d[158]; +acadoWorkspace.lbA[78] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[78] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[163] + acadoWorkspace.d[159]; +acadoWorkspace.lbA[79] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[79] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[166] + acadoWorkspace.d[162]; +acadoWorkspace.lbA[80] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[80] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[167] + acadoWorkspace.d[163]; +acadoWorkspace.lbA[81] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[81] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[170] + acadoWorkspace.d[166]; +acadoWorkspace.lbA[82] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[82] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[171] + acadoWorkspace.d[167]; +acadoWorkspace.lbA[83] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[83] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[174] + acadoWorkspace.d[170]; +acadoWorkspace.lbA[84] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[84] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[175] + acadoWorkspace.d[171]; +acadoWorkspace.lbA[85] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[85] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[178] + acadoWorkspace.d[174]; +acadoWorkspace.lbA[86] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[86] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[179] + acadoWorkspace.d[175]; +acadoWorkspace.lbA[87] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[87] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[182] + acadoWorkspace.d[178]; +acadoWorkspace.lbA[88] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[88] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[183] + acadoWorkspace.d[179]; +acadoWorkspace.lbA[89] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[89] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[186] + acadoWorkspace.d[182]; +acadoWorkspace.lbA[90] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[90] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[187] + acadoWorkspace.d[183]; +acadoWorkspace.lbA[91] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[91] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[190] + acadoWorkspace.d[186]; +acadoWorkspace.lbA[92] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[92] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[191] + acadoWorkspace.d[187]; +acadoWorkspace.lbA[93] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[93] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[194] + acadoWorkspace.d[190]; +acadoWorkspace.lbA[94] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[94] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[195] + acadoWorkspace.d[191]; +acadoWorkspace.lbA[95] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[95] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[198] + acadoWorkspace.d[194]; +acadoWorkspace.lbA[96] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[96] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[199] + acadoWorkspace.d[195]; +acadoWorkspace.lbA[97] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[97] = (real_t)4.3633231300000003e-01 - tmp; +tmp = acadoVariables.x[202] + acadoWorkspace.d[198]; +acadoWorkspace.lbA[98] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[98] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[203] + acadoWorkspace.d[199]; +acadoWorkspace.lbA[99] = (real_t)-4.3633231300000003e-01 - tmp; +acadoWorkspace.ubA[99] = (real_t)4.3633231300000003e-01 - tmp; + +} + +void acado_expand( ) +{ +int lRun1; +int lRun2; +int lRun3; +acadoVariables.x[0] += acadoWorkspace.x[0]; +acadoVariables.x[1] += acadoWorkspace.x[1]; +acadoVariables.x[2] += acadoWorkspace.x[2]; +acadoVariables.x[3] += acadoWorkspace.x[3]; + +acadoVariables.u[0] += acadoWorkspace.x[4]; +acadoVariables.u[1] += acadoWorkspace.x[5]; +acadoVariables.u[2] += acadoWorkspace.x[6]; +acadoVariables.u[3] += acadoWorkspace.x[7]; +acadoVariables.u[4] += acadoWorkspace.x[8]; +acadoVariables.u[5] += acadoWorkspace.x[9]; +acadoVariables.u[6] += acadoWorkspace.x[10]; +acadoVariables.u[7] += acadoWorkspace.x[11]; +acadoVariables.u[8] += acadoWorkspace.x[12]; +acadoVariables.u[9] += acadoWorkspace.x[13]; +acadoVariables.u[10] += acadoWorkspace.x[14]; +acadoVariables.u[11] += acadoWorkspace.x[15]; +acadoVariables.u[12] += acadoWorkspace.x[16]; +acadoVariables.u[13] += acadoWorkspace.x[17]; +acadoVariables.u[14] += acadoWorkspace.x[18]; +acadoVariables.u[15] += acadoWorkspace.x[19]; +acadoVariables.u[16] += acadoWorkspace.x[20]; +acadoVariables.u[17] += acadoWorkspace.x[21]; +acadoVariables.u[18] += acadoWorkspace.x[22]; +acadoVariables.u[19] += acadoWorkspace.x[23]; +acadoVariables.u[20] += acadoWorkspace.x[24]; +acadoVariables.u[21] += acadoWorkspace.x[25]; +acadoVariables.u[22] += acadoWorkspace.x[26]; +acadoVariables.u[23] += acadoWorkspace.x[27]; +acadoVariables.u[24] += acadoWorkspace.x[28]; +acadoVariables.u[25] += acadoWorkspace.x[29]; +acadoVariables.u[26] += acadoWorkspace.x[30]; +acadoVariables.u[27] += acadoWorkspace.x[31]; +acadoVariables.u[28] += acadoWorkspace.x[32]; +acadoVariables.u[29] += acadoWorkspace.x[33]; +acadoVariables.u[30] += acadoWorkspace.x[34]; +acadoVariables.u[31] += acadoWorkspace.x[35]; +acadoVariables.u[32] += acadoWorkspace.x[36]; +acadoVariables.u[33] += acadoWorkspace.x[37]; +acadoVariables.u[34] += acadoWorkspace.x[38]; +acadoVariables.u[35] += acadoWorkspace.x[39]; +acadoVariables.u[36] += acadoWorkspace.x[40]; +acadoVariables.u[37] += acadoWorkspace.x[41]; +acadoVariables.u[38] += acadoWorkspace.x[42]; +acadoVariables.u[39] += acadoWorkspace.x[43]; +acadoVariables.u[40] += acadoWorkspace.x[44]; +acadoVariables.u[41] += acadoWorkspace.x[45]; +acadoVariables.u[42] += acadoWorkspace.x[46]; +acadoVariables.u[43] += acadoWorkspace.x[47]; +acadoVariables.u[44] += acadoWorkspace.x[48]; +acadoVariables.u[45] += acadoWorkspace.x[49]; +acadoVariables.u[46] += acadoWorkspace.x[50]; +acadoVariables.u[47] += acadoWorkspace.x[51]; +acadoVariables.u[48] += acadoWorkspace.x[52]; +acadoVariables.u[49] += acadoWorkspace.x[53]; + +acadoVariables.x[4] += + acadoWorkspace.evGx[0]*acadoWorkspace.x[0] + acadoWorkspace.evGx[1]*acadoWorkspace.x[1] + acadoWorkspace.evGx[2]*acadoWorkspace.x[2] + acadoWorkspace.evGx[3]*acadoWorkspace.x[3] + acadoWorkspace.d[0]; +acadoVariables.x[5] += + acadoWorkspace.evGx[4]*acadoWorkspace.x[0] + acadoWorkspace.evGx[5]*acadoWorkspace.x[1] + acadoWorkspace.evGx[6]*acadoWorkspace.x[2] + acadoWorkspace.evGx[7]*acadoWorkspace.x[3] + acadoWorkspace.d[1]; +acadoVariables.x[6] += + acadoWorkspace.evGx[8]*acadoWorkspace.x[0] + acadoWorkspace.evGx[9]*acadoWorkspace.x[1] + acadoWorkspace.evGx[10]*acadoWorkspace.x[2] + acadoWorkspace.evGx[11]*acadoWorkspace.x[3] + acadoWorkspace.d[2]; +acadoVariables.x[7] += + acadoWorkspace.evGx[12]*acadoWorkspace.x[0] + acadoWorkspace.evGx[13]*acadoWorkspace.x[1] + acadoWorkspace.evGx[14]*acadoWorkspace.x[2] + acadoWorkspace.evGx[15]*acadoWorkspace.x[3] + acadoWorkspace.d[3]; +acadoVariables.x[8] += + acadoWorkspace.evGx[16]*acadoWorkspace.x[0] + acadoWorkspace.evGx[17]*acadoWorkspace.x[1] + acadoWorkspace.evGx[18]*acadoWorkspace.x[2] + acadoWorkspace.evGx[19]*acadoWorkspace.x[3] + acadoWorkspace.d[4]; +acadoVariables.x[9] += + acadoWorkspace.evGx[20]*acadoWorkspace.x[0] + acadoWorkspace.evGx[21]*acadoWorkspace.x[1] + acadoWorkspace.evGx[22]*acadoWorkspace.x[2] + acadoWorkspace.evGx[23]*acadoWorkspace.x[3] + acadoWorkspace.d[5]; +acadoVariables.x[10] += + acadoWorkspace.evGx[24]*acadoWorkspace.x[0] + acadoWorkspace.evGx[25]*acadoWorkspace.x[1] + acadoWorkspace.evGx[26]*acadoWorkspace.x[2] + acadoWorkspace.evGx[27]*acadoWorkspace.x[3] + acadoWorkspace.d[6]; +acadoVariables.x[11] += + acadoWorkspace.evGx[28]*acadoWorkspace.x[0] + acadoWorkspace.evGx[29]*acadoWorkspace.x[1] + acadoWorkspace.evGx[30]*acadoWorkspace.x[2] + acadoWorkspace.evGx[31]*acadoWorkspace.x[3] + acadoWorkspace.d[7]; +acadoVariables.x[12] += + acadoWorkspace.evGx[32]*acadoWorkspace.x[0] + acadoWorkspace.evGx[33]*acadoWorkspace.x[1] + acadoWorkspace.evGx[34]*acadoWorkspace.x[2] + acadoWorkspace.evGx[35]*acadoWorkspace.x[3] + acadoWorkspace.d[8]; +acadoVariables.x[13] += + acadoWorkspace.evGx[36]*acadoWorkspace.x[0] + acadoWorkspace.evGx[37]*acadoWorkspace.x[1] + acadoWorkspace.evGx[38]*acadoWorkspace.x[2] + acadoWorkspace.evGx[39]*acadoWorkspace.x[3] + acadoWorkspace.d[9]; +acadoVariables.x[14] += + acadoWorkspace.evGx[40]*acadoWorkspace.x[0] + acadoWorkspace.evGx[41]*acadoWorkspace.x[1] + acadoWorkspace.evGx[42]*acadoWorkspace.x[2] + acadoWorkspace.evGx[43]*acadoWorkspace.x[3] + acadoWorkspace.d[10]; +acadoVariables.x[15] += + acadoWorkspace.evGx[44]*acadoWorkspace.x[0] + acadoWorkspace.evGx[45]*acadoWorkspace.x[1] + acadoWorkspace.evGx[46]*acadoWorkspace.x[2] + acadoWorkspace.evGx[47]*acadoWorkspace.x[3] + acadoWorkspace.d[11]; +acadoVariables.x[16] += + acadoWorkspace.evGx[48]*acadoWorkspace.x[0] + acadoWorkspace.evGx[49]*acadoWorkspace.x[1] + acadoWorkspace.evGx[50]*acadoWorkspace.x[2] + acadoWorkspace.evGx[51]*acadoWorkspace.x[3] + acadoWorkspace.d[12]; +acadoVariables.x[17] += + acadoWorkspace.evGx[52]*acadoWorkspace.x[0] + acadoWorkspace.evGx[53]*acadoWorkspace.x[1] + acadoWorkspace.evGx[54]*acadoWorkspace.x[2] + acadoWorkspace.evGx[55]*acadoWorkspace.x[3] + acadoWorkspace.d[13]; +acadoVariables.x[18] += + acadoWorkspace.evGx[56]*acadoWorkspace.x[0] + acadoWorkspace.evGx[57]*acadoWorkspace.x[1] + acadoWorkspace.evGx[58]*acadoWorkspace.x[2] + acadoWorkspace.evGx[59]*acadoWorkspace.x[3] + acadoWorkspace.d[14]; +acadoVariables.x[19] += + acadoWorkspace.evGx[60]*acadoWorkspace.x[0] + acadoWorkspace.evGx[61]*acadoWorkspace.x[1] + acadoWorkspace.evGx[62]*acadoWorkspace.x[2] + acadoWorkspace.evGx[63]*acadoWorkspace.x[3] + acadoWorkspace.d[15]; +acadoVariables.x[20] += + acadoWorkspace.evGx[64]*acadoWorkspace.x[0] + acadoWorkspace.evGx[65]*acadoWorkspace.x[1] + acadoWorkspace.evGx[66]*acadoWorkspace.x[2] + acadoWorkspace.evGx[67]*acadoWorkspace.x[3] + acadoWorkspace.d[16]; +acadoVariables.x[21] += + acadoWorkspace.evGx[68]*acadoWorkspace.x[0] + acadoWorkspace.evGx[69]*acadoWorkspace.x[1] + acadoWorkspace.evGx[70]*acadoWorkspace.x[2] + acadoWorkspace.evGx[71]*acadoWorkspace.x[3] + acadoWorkspace.d[17]; +acadoVariables.x[22] += + acadoWorkspace.evGx[72]*acadoWorkspace.x[0] + acadoWorkspace.evGx[73]*acadoWorkspace.x[1] + acadoWorkspace.evGx[74]*acadoWorkspace.x[2] + acadoWorkspace.evGx[75]*acadoWorkspace.x[3] + acadoWorkspace.d[18]; +acadoVariables.x[23] += + acadoWorkspace.evGx[76]*acadoWorkspace.x[0] + acadoWorkspace.evGx[77]*acadoWorkspace.x[1] + acadoWorkspace.evGx[78]*acadoWorkspace.x[2] + acadoWorkspace.evGx[79]*acadoWorkspace.x[3] + acadoWorkspace.d[19]; +acadoVariables.x[24] += + acadoWorkspace.evGx[80]*acadoWorkspace.x[0] + acadoWorkspace.evGx[81]*acadoWorkspace.x[1] + acadoWorkspace.evGx[82]*acadoWorkspace.x[2] + acadoWorkspace.evGx[83]*acadoWorkspace.x[3] + acadoWorkspace.d[20]; +acadoVariables.x[25] += + acadoWorkspace.evGx[84]*acadoWorkspace.x[0] + acadoWorkspace.evGx[85]*acadoWorkspace.x[1] + acadoWorkspace.evGx[86]*acadoWorkspace.x[2] + acadoWorkspace.evGx[87]*acadoWorkspace.x[3] + acadoWorkspace.d[21]; +acadoVariables.x[26] += + acadoWorkspace.evGx[88]*acadoWorkspace.x[0] + acadoWorkspace.evGx[89]*acadoWorkspace.x[1] + acadoWorkspace.evGx[90]*acadoWorkspace.x[2] + acadoWorkspace.evGx[91]*acadoWorkspace.x[3] + acadoWorkspace.d[22]; +acadoVariables.x[27] += + acadoWorkspace.evGx[92]*acadoWorkspace.x[0] + acadoWorkspace.evGx[93]*acadoWorkspace.x[1] + acadoWorkspace.evGx[94]*acadoWorkspace.x[2] + acadoWorkspace.evGx[95]*acadoWorkspace.x[3] + acadoWorkspace.d[23]; +acadoVariables.x[28] += + acadoWorkspace.evGx[96]*acadoWorkspace.x[0] + acadoWorkspace.evGx[97]*acadoWorkspace.x[1] + acadoWorkspace.evGx[98]*acadoWorkspace.x[2] + acadoWorkspace.evGx[99]*acadoWorkspace.x[3] + acadoWorkspace.d[24]; +acadoVariables.x[29] += + acadoWorkspace.evGx[100]*acadoWorkspace.x[0] + acadoWorkspace.evGx[101]*acadoWorkspace.x[1] + acadoWorkspace.evGx[102]*acadoWorkspace.x[2] + acadoWorkspace.evGx[103]*acadoWorkspace.x[3] + acadoWorkspace.d[25]; +acadoVariables.x[30] += + acadoWorkspace.evGx[104]*acadoWorkspace.x[0] + acadoWorkspace.evGx[105]*acadoWorkspace.x[1] + acadoWorkspace.evGx[106]*acadoWorkspace.x[2] + acadoWorkspace.evGx[107]*acadoWorkspace.x[3] + acadoWorkspace.d[26]; +acadoVariables.x[31] += + acadoWorkspace.evGx[108]*acadoWorkspace.x[0] + acadoWorkspace.evGx[109]*acadoWorkspace.x[1] + acadoWorkspace.evGx[110]*acadoWorkspace.x[2] + acadoWorkspace.evGx[111]*acadoWorkspace.x[3] + acadoWorkspace.d[27]; +acadoVariables.x[32] += + acadoWorkspace.evGx[112]*acadoWorkspace.x[0] + acadoWorkspace.evGx[113]*acadoWorkspace.x[1] + acadoWorkspace.evGx[114]*acadoWorkspace.x[2] + acadoWorkspace.evGx[115]*acadoWorkspace.x[3] + acadoWorkspace.d[28]; +acadoVariables.x[33] += + acadoWorkspace.evGx[116]*acadoWorkspace.x[0] + acadoWorkspace.evGx[117]*acadoWorkspace.x[1] + acadoWorkspace.evGx[118]*acadoWorkspace.x[2] + acadoWorkspace.evGx[119]*acadoWorkspace.x[3] + acadoWorkspace.d[29]; +acadoVariables.x[34] += + acadoWorkspace.evGx[120]*acadoWorkspace.x[0] + acadoWorkspace.evGx[121]*acadoWorkspace.x[1] + acadoWorkspace.evGx[122]*acadoWorkspace.x[2] + acadoWorkspace.evGx[123]*acadoWorkspace.x[3] + acadoWorkspace.d[30]; +acadoVariables.x[35] += + acadoWorkspace.evGx[124]*acadoWorkspace.x[0] + acadoWorkspace.evGx[125]*acadoWorkspace.x[1] + acadoWorkspace.evGx[126]*acadoWorkspace.x[2] + acadoWorkspace.evGx[127]*acadoWorkspace.x[3] + acadoWorkspace.d[31]; +acadoVariables.x[36] += + acadoWorkspace.evGx[128]*acadoWorkspace.x[0] + acadoWorkspace.evGx[129]*acadoWorkspace.x[1] + acadoWorkspace.evGx[130]*acadoWorkspace.x[2] + acadoWorkspace.evGx[131]*acadoWorkspace.x[3] + acadoWorkspace.d[32]; +acadoVariables.x[37] += + acadoWorkspace.evGx[132]*acadoWorkspace.x[0] + acadoWorkspace.evGx[133]*acadoWorkspace.x[1] + acadoWorkspace.evGx[134]*acadoWorkspace.x[2] + acadoWorkspace.evGx[135]*acadoWorkspace.x[3] + acadoWorkspace.d[33]; +acadoVariables.x[38] += + acadoWorkspace.evGx[136]*acadoWorkspace.x[0] + acadoWorkspace.evGx[137]*acadoWorkspace.x[1] + acadoWorkspace.evGx[138]*acadoWorkspace.x[2] + acadoWorkspace.evGx[139]*acadoWorkspace.x[3] + acadoWorkspace.d[34]; +acadoVariables.x[39] += + acadoWorkspace.evGx[140]*acadoWorkspace.x[0] + acadoWorkspace.evGx[141]*acadoWorkspace.x[1] + acadoWorkspace.evGx[142]*acadoWorkspace.x[2] + acadoWorkspace.evGx[143]*acadoWorkspace.x[3] + acadoWorkspace.d[35]; +acadoVariables.x[40] += + acadoWorkspace.evGx[144]*acadoWorkspace.x[0] + acadoWorkspace.evGx[145]*acadoWorkspace.x[1] + acadoWorkspace.evGx[146]*acadoWorkspace.x[2] + acadoWorkspace.evGx[147]*acadoWorkspace.x[3] + acadoWorkspace.d[36]; +acadoVariables.x[41] += + acadoWorkspace.evGx[148]*acadoWorkspace.x[0] + acadoWorkspace.evGx[149]*acadoWorkspace.x[1] + acadoWorkspace.evGx[150]*acadoWorkspace.x[2] + acadoWorkspace.evGx[151]*acadoWorkspace.x[3] + acadoWorkspace.d[37]; +acadoVariables.x[42] += + acadoWorkspace.evGx[152]*acadoWorkspace.x[0] + acadoWorkspace.evGx[153]*acadoWorkspace.x[1] + acadoWorkspace.evGx[154]*acadoWorkspace.x[2] + acadoWorkspace.evGx[155]*acadoWorkspace.x[3] + acadoWorkspace.d[38]; +acadoVariables.x[43] += + acadoWorkspace.evGx[156]*acadoWorkspace.x[0] + acadoWorkspace.evGx[157]*acadoWorkspace.x[1] + acadoWorkspace.evGx[158]*acadoWorkspace.x[2] + acadoWorkspace.evGx[159]*acadoWorkspace.x[3] + acadoWorkspace.d[39]; +acadoVariables.x[44] += + acadoWorkspace.evGx[160]*acadoWorkspace.x[0] + acadoWorkspace.evGx[161]*acadoWorkspace.x[1] + acadoWorkspace.evGx[162]*acadoWorkspace.x[2] + acadoWorkspace.evGx[163]*acadoWorkspace.x[3] + acadoWorkspace.d[40]; +acadoVariables.x[45] += + acadoWorkspace.evGx[164]*acadoWorkspace.x[0] + acadoWorkspace.evGx[165]*acadoWorkspace.x[1] + acadoWorkspace.evGx[166]*acadoWorkspace.x[2] + acadoWorkspace.evGx[167]*acadoWorkspace.x[3] + acadoWorkspace.d[41]; +acadoVariables.x[46] += + acadoWorkspace.evGx[168]*acadoWorkspace.x[0] + acadoWorkspace.evGx[169]*acadoWorkspace.x[1] + acadoWorkspace.evGx[170]*acadoWorkspace.x[2] + acadoWorkspace.evGx[171]*acadoWorkspace.x[3] + acadoWorkspace.d[42]; +acadoVariables.x[47] += + acadoWorkspace.evGx[172]*acadoWorkspace.x[0] + acadoWorkspace.evGx[173]*acadoWorkspace.x[1] + acadoWorkspace.evGx[174]*acadoWorkspace.x[2] + acadoWorkspace.evGx[175]*acadoWorkspace.x[3] + acadoWorkspace.d[43]; +acadoVariables.x[48] += + acadoWorkspace.evGx[176]*acadoWorkspace.x[0] + acadoWorkspace.evGx[177]*acadoWorkspace.x[1] + acadoWorkspace.evGx[178]*acadoWorkspace.x[2] + acadoWorkspace.evGx[179]*acadoWorkspace.x[3] + acadoWorkspace.d[44]; +acadoVariables.x[49] += + acadoWorkspace.evGx[180]*acadoWorkspace.x[0] + acadoWorkspace.evGx[181]*acadoWorkspace.x[1] + acadoWorkspace.evGx[182]*acadoWorkspace.x[2] + acadoWorkspace.evGx[183]*acadoWorkspace.x[3] + acadoWorkspace.d[45]; +acadoVariables.x[50] += + acadoWorkspace.evGx[184]*acadoWorkspace.x[0] + acadoWorkspace.evGx[185]*acadoWorkspace.x[1] + acadoWorkspace.evGx[186]*acadoWorkspace.x[2] + acadoWorkspace.evGx[187]*acadoWorkspace.x[3] + acadoWorkspace.d[46]; +acadoVariables.x[51] += + acadoWorkspace.evGx[188]*acadoWorkspace.x[0] + acadoWorkspace.evGx[189]*acadoWorkspace.x[1] + acadoWorkspace.evGx[190]*acadoWorkspace.x[2] + acadoWorkspace.evGx[191]*acadoWorkspace.x[3] + acadoWorkspace.d[47]; +acadoVariables.x[52] += + acadoWorkspace.evGx[192]*acadoWorkspace.x[0] + acadoWorkspace.evGx[193]*acadoWorkspace.x[1] + acadoWorkspace.evGx[194]*acadoWorkspace.x[2] + acadoWorkspace.evGx[195]*acadoWorkspace.x[3] + acadoWorkspace.d[48]; +acadoVariables.x[53] += + acadoWorkspace.evGx[196]*acadoWorkspace.x[0] + acadoWorkspace.evGx[197]*acadoWorkspace.x[1] + acadoWorkspace.evGx[198]*acadoWorkspace.x[2] + acadoWorkspace.evGx[199]*acadoWorkspace.x[3] + acadoWorkspace.d[49]; +acadoVariables.x[54] += + acadoWorkspace.evGx[200]*acadoWorkspace.x[0] + acadoWorkspace.evGx[201]*acadoWorkspace.x[1] + acadoWorkspace.evGx[202]*acadoWorkspace.x[2] + acadoWorkspace.evGx[203]*acadoWorkspace.x[3] + acadoWorkspace.d[50]; +acadoVariables.x[55] += + acadoWorkspace.evGx[204]*acadoWorkspace.x[0] + acadoWorkspace.evGx[205]*acadoWorkspace.x[1] + acadoWorkspace.evGx[206]*acadoWorkspace.x[2] + acadoWorkspace.evGx[207]*acadoWorkspace.x[3] + acadoWorkspace.d[51]; +acadoVariables.x[56] += + acadoWorkspace.evGx[208]*acadoWorkspace.x[0] + acadoWorkspace.evGx[209]*acadoWorkspace.x[1] + acadoWorkspace.evGx[210]*acadoWorkspace.x[2] + acadoWorkspace.evGx[211]*acadoWorkspace.x[3] + acadoWorkspace.d[52]; +acadoVariables.x[57] += + acadoWorkspace.evGx[212]*acadoWorkspace.x[0] + acadoWorkspace.evGx[213]*acadoWorkspace.x[1] + acadoWorkspace.evGx[214]*acadoWorkspace.x[2] + acadoWorkspace.evGx[215]*acadoWorkspace.x[3] + acadoWorkspace.d[53]; +acadoVariables.x[58] += + acadoWorkspace.evGx[216]*acadoWorkspace.x[0] + acadoWorkspace.evGx[217]*acadoWorkspace.x[1] + acadoWorkspace.evGx[218]*acadoWorkspace.x[2] + acadoWorkspace.evGx[219]*acadoWorkspace.x[3] + acadoWorkspace.d[54]; +acadoVariables.x[59] += + acadoWorkspace.evGx[220]*acadoWorkspace.x[0] + acadoWorkspace.evGx[221]*acadoWorkspace.x[1] + acadoWorkspace.evGx[222]*acadoWorkspace.x[2] + acadoWorkspace.evGx[223]*acadoWorkspace.x[3] + acadoWorkspace.d[55]; +acadoVariables.x[60] += + acadoWorkspace.evGx[224]*acadoWorkspace.x[0] + acadoWorkspace.evGx[225]*acadoWorkspace.x[1] + acadoWorkspace.evGx[226]*acadoWorkspace.x[2] + acadoWorkspace.evGx[227]*acadoWorkspace.x[3] + acadoWorkspace.d[56]; +acadoVariables.x[61] += + acadoWorkspace.evGx[228]*acadoWorkspace.x[0] + acadoWorkspace.evGx[229]*acadoWorkspace.x[1] + acadoWorkspace.evGx[230]*acadoWorkspace.x[2] + acadoWorkspace.evGx[231]*acadoWorkspace.x[3] + acadoWorkspace.d[57]; +acadoVariables.x[62] += + acadoWorkspace.evGx[232]*acadoWorkspace.x[0] + acadoWorkspace.evGx[233]*acadoWorkspace.x[1] + acadoWorkspace.evGx[234]*acadoWorkspace.x[2] + acadoWorkspace.evGx[235]*acadoWorkspace.x[3] + acadoWorkspace.d[58]; +acadoVariables.x[63] += + acadoWorkspace.evGx[236]*acadoWorkspace.x[0] + acadoWorkspace.evGx[237]*acadoWorkspace.x[1] + acadoWorkspace.evGx[238]*acadoWorkspace.x[2] + acadoWorkspace.evGx[239]*acadoWorkspace.x[3] + acadoWorkspace.d[59]; +acadoVariables.x[64] += + acadoWorkspace.evGx[240]*acadoWorkspace.x[0] + acadoWorkspace.evGx[241]*acadoWorkspace.x[1] + acadoWorkspace.evGx[242]*acadoWorkspace.x[2] + acadoWorkspace.evGx[243]*acadoWorkspace.x[3] + acadoWorkspace.d[60]; +acadoVariables.x[65] += + acadoWorkspace.evGx[244]*acadoWorkspace.x[0] + acadoWorkspace.evGx[245]*acadoWorkspace.x[1] + acadoWorkspace.evGx[246]*acadoWorkspace.x[2] + acadoWorkspace.evGx[247]*acadoWorkspace.x[3] + acadoWorkspace.d[61]; +acadoVariables.x[66] += + acadoWorkspace.evGx[248]*acadoWorkspace.x[0] + acadoWorkspace.evGx[249]*acadoWorkspace.x[1] + acadoWorkspace.evGx[250]*acadoWorkspace.x[2] + acadoWorkspace.evGx[251]*acadoWorkspace.x[3] + acadoWorkspace.d[62]; +acadoVariables.x[67] += + acadoWorkspace.evGx[252]*acadoWorkspace.x[0] + acadoWorkspace.evGx[253]*acadoWorkspace.x[1] + acadoWorkspace.evGx[254]*acadoWorkspace.x[2] + acadoWorkspace.evGx[255]*acadoWorkspace.x[3] + acadoWorkspace.d[63]; +acadoVariables.x[68] += + acadoWorkspace.evGx[256]*acadoWorkspace.x[0] + acadoWorkspace.evGx[257]*acadoWorkspace.x[1] + acadoWorkspace.evGx[258]*acadoWorkspace.x[2] + acadoWorkspace.evGx[259]*acadoWorkspace.x[3] + acadoWorkspace.d[64]; +acadoVariables.x[69] += + acadoWorkspace.evGx[260]*acadoWorkspace.x[0] + acadoWorkspace.evGx[261]*acadoWorkspace.x[1] + acadoWorkspace.evGx[262]*acadoWorkspace.x[2] + acadoWorkspace.evGx[263]*acadoWorkspace.x[3] + acadoWorkspace.d[65]; +acadoVariables.x[70] += + acadoWorkspace.evGx[264]*acadoWorkspace.x[0] + acadoWorkspace.evGx[265]*acadoWorkspace.x[1] + acadoWorkspace.evGx[266]*acadoWorkspace.x[2] + acadoWorkspace.evGx[267]*acadoWorkspace.x[3] + acadoWorkspace.d[66]; +acadoVariables.x[71] += + acadoWorkspace.evGx[268]*acadoWorkspace.x[0] + acadoWorkspace.evGx[269]*acadoWorkspace.x[1] + acadoWorkspace.evGx[270]*acadoWorkspace.x[2] + acadoWorkspace.evGx[271]*acadoWorkspace.x[3] + acadoWorkspace.d[67]; +acadoVariables.x[72] += + acadoWorkspace.evGx[272]*acadoWorkspace.x[0] + acadoWorkspace.evGx[273]*acadoWorkspace.x[1] + acadoWorkspace.evGx[274]*acadoWorkspace.x[2] + acadoWorkspace.evGx[275]*acadoWorkspace.x[3] + acadoWorkspace.d[68]; +acadoVariables.x[73] += + acadoWorkspace.evGx[276]*acadoWorkspace.x[0] + acadoWorkspace.evGx[277]*acadoWorkspace.x[1] + acadoWorkspace.evGx[278]*acadoWorkspace.x[2] + acadoWorkspace.evGx[279]*acadoWorkspace.x[3] + acadoWorkspace.d[69]; +acadoVariables.x[74] += + acadoWorkspace.evGx[280]*acadoWorkspace.x[0] + acadoWorkspace.evGx[281]*acadoWorkspace.x[1] + acadoWorkspace.evGx[282]*acadoWorkspace.x[2] + acadoWorkspace.evGx[283]*acadoWorkspace.x[3] + acadoWorkspace.d[70]; +acadoVariables.x[75] += + acadoWorkspace.evGx[284]*acadoWorkspace.x[0] + acadoWorkspace.evGx[285]*acadoWorkspace.x[1] + acadoWorkspace.evGx[286]*acadoWorkspace.x[2] + acadoWorkspace.evGx[287]*acadoWorkspace.x[3] + acadoWorkspace.d[71]; +acadoVariables.x[76] += + acadoWorkspace.evGx[288]*acadoWorkspace.x[0] + acadoWorkspace.evGx[289]*acadoWorkspace.x[1] + acadoWorkspace.evGx[290]*acadoWorkspace.x[2] + acadoWorkspace.evGx[291]*acadoWorkspace.x[3] + acadoWorkspace.d[72]; +acadoVariables.x[77] += + acadoWorkspace.evGx[292]*acadoWorkspace.x[0] + acadoWorkspace.evGx[293]*acadoWorkspace.x[1] + acadoWorkspace.evGx[294]*acadoWorkspace.x[2] + acadoWorkspace.evGx[295]*acadoWorkspace.x[3] + acadoWorkspace.d[73]; +acadoVariables.x[78] += + acadoWorkspace.evGx[296]*acadoWorkspace.x[0] + acadoWorkspace.evGx[297]*acadoWorkspace.x[1] + acadoWorkspace.evGx[298]*acadoWorkspace.x[2] + acadoWorkspace.evGx[299]*acadoWorkspace.x[3] + acadoWorkspace.d[74]; +acadoVariables.x[79] += + acadoWorkspace.evGx[300]*acadoWorkspace.x[0] + acadoWorkspace.evGx[301]*acadoWorkspace.x[1] + acadoWorkspace.evGx[302]*acadoWorkspace.x[2] + acadoWorkspace.evGx[303]*acadoWorkspace.x[3] + acadoWorkspace.d[75]; +acadoVariables.x[80] += + acadoWorkspace.evGx[304]*acadoWorkspace.x[0] + acadoWorkspace.evGx[305]*acadoWorkspace.x[1] + acadoWorkspace.evGx[306]*acadoWorkspace.x[2] + acadoWorkspace.evGx[307]*acadoWorkspace.x[3] + acadoWorkspace.d[76]; +acadoVariables.x[81] += + acadoWorkspace.evGx[308]*acadoWorkspace.x[0] + acadoWorkspace.evGx[309]*acadoWorkspace.x[1] + acadoWorkspace.evGx[310]*acadoWorkspace.x[2] + acadoWorkspace.evGx[311]*acadoWorkspace.x[3] + acadoWorkspace.d[77]; +acadoVariables.x[82] += + acadoWorkspace.evGx[312]*acadoWorkspace.x[0] + acadoWorkspace.evGx[313]*acadoWorkspace.x[1] + acadoWorkspace.evGx[314]*acadoWorkspace.x[2] + acadoWorkspace.evGx[315]*acadoWorkspace.x[3] + acadoWorkspace.d[78]; +acadoVariables.x[83] += + acadoWorkspace.evGx[316]*acadoWorkspace.x[0] + acadoWorkspace.evGx[317]*acadoWorkspace.x[1] + acadoWorkspace.evGx[318]*acadoWorkspace.x[2] + acadoWorkspace.evGx[319]*acadoWorkspace.x[3] + acadoWorkspace.d[79]; +acadoVariables.x[84] += + acadoWorkspace.evGx[320]*acadoWorkspace.x[0] + acadoWorkspace.evGx[321]*acadoWorkspace.x[1] + acadoWorkspace.evGx[322]*acadoWorkspace.x[2] + acadoWorkspace.evGx[323]*acadoWorkspace.x[3] + acadoWorkspace.d[80]; +acadoVariables.x[85] += + acadoWorkspace.evGx[324]*acadoWorkspace.x[0] + acadoWorkspace.evGx[325]*acadoWorkspace.x[1] + acadoWorkspace.evGx[326]*acadoWorkspace.x[2] + acadoWorkspace.evGx[327]*acadoWorkspace.x[3] + acadoWorkspace.d[81]; +acadoVariables.x[86] += + acadoWorkspace.evGx[328]*acadoWorkspace.x[0] + acadoWorkspace.evGx[329]*acadoWorkspace.x[1] + acadoWorkspace.evGx[330]*acadoWorkspace.x[2] + acadoWorkspace.evGx[331]*acadoWorkspace.x[3] + acadoWorkspace.d[82]; +acadoVariables.x[87] += + acadoWorkspace.evGx[332]*acadoWorkspace.x[0] + acadoWorkspace.evGx[333]*acadoWorkspace.x[1] + acadoWorkspace.evGx[334]*acadoWorkspace.x[2] + acadoWorkspace.evGx[335]*acadoWorkspace.x[3] + acadoWorkspace.d[83]; +acadoVariables.x[88] += + acadoWorkspace.evGx[336]*acadoWorkspace.x[0] + acadoWorkspace.evGx[337]*acadoWorkspace.x[1] + acadoWorkspace.evGx[338]*acadoWorkspace.x[2] + acadoWorkspace.evGx[339]*acadoWorkspace.x[3] + acadoWorkspace.d[84]; +acadoVariables.x[89] += + acadoWorkspace.evGx[340]*acadoWorkspace.x[0] + acadoWorkspace.evGx[341]*acadoWorkspace.x[1] + acadoWorkspace.evGx[342]*acadoWorkspace.x[2] + acadoWorkspace.evGx[343]*acadoWorkspace.x[3] + acadoWorkspace.d[85]; +acadoVariables.x[90] += + acadoWorkspace.evGx[344]*acadoWorkspace.x[0] + acadoWorkspace.evGx[345]*acadoWorkspace.x[1] + acadoWorkspace.evGx[346]*acadoWorkspace.x[2] + acadoWorkspace.evGx[347]*acadoWorkspace.x[3] + acadoWorkspace.d[86]; +acadoVariables.x[91] += + acadoWorkspace.evGx[348]*acadoWorkspace.x[0] + acadoWorkspace.evGx[349]*acadoWorkspace.x[1] + acadoWorkspace.evGx[350]*acadoWorkspace.x[2] + acadoWorkspace.evGx[351]*acadoWorkspace.x[3] + acadoWorkspace.d[87]; +acadoVariables.x[92] += + acadoWorkspace.evGx[352]*acadoWorkspace.x[0] + acadoWorkspace.evGx[353]*acadoWorkspace.x[1] + acadoWorkspace.evGx[354]*acadoWorkspace.x[2] + acadoWorkspace.evGx[355]*acadoWorkspace.x[3] + acadoWorkspace.d[88]; +acadoVariables.x[93] += + acadoWorkspace.evGx[356]*acadoWorkspace.x[0] + acadoWorkspace.evGx[357]*acadoWorkspace.x[1] + acadoWorkspace.evGx[358]*acadoWorkspace.x[2] + acadoWorkspace.evGx[359]*acadoWorkspace.x[3] + acadoWorkspace.d[89]; +acadoVariables.x[94] += + acadoWorkspace.evGx[360]*acadoWorkspace.x[0] + acadoWorkspace.evGx[361]*acadoWorkspace.x[1] + acadoWorkspace.evGx[362]*acadoWorkspace.x[2] + acadoWorkspace.evGx[363]*acadoWorkspace.x[3] + acadoWorkspace.d[90]; +acadoVariables.x[95] += + acadoWorkspace.evGx[364]*acadoWorkspace.x[0] + acadoWorkspace.evGx[365]*acadoWorkspace.x[1] + acadoWorkspace.evGx[366]*acadoWorkspace.x[2] + acadoWorkspace.evGx[367]*acadoWorkspace.x[3] + acadoWorkspace.d[91]; +acadoVariables.x[96] += + acadoWorkspace.evGx[368]*acadoWorkspace.x[0] + acadoWorkspace.evGx[369]*acadoWorkspace.x[1] + acadoWorkspace.evGx[370]*acadoWorkspace.x[2] + acadoWorkspace.evGx[371]*acadoWorkspace.x[3] + acadoWorkspace.d[92]; +acadoVariables.x[97] += + acadoWorkspace.evGx[372]*acadoWorkspace.x[0] + acadoWorkspace.evGx[373]*acadoWorkspace.x[1] + acadoWorkspace.evGx[374]*acadoWorkspace.x[2] + acadoWorkspace.evGx[375]*acadoWorkspace.x[3] + acadoWorkspace.d[93]; +acadoVariables.x[98] += + acadoWorkspace.evGx[376]*acadoWorkspace.x[0] + acadoWorkspace.evGx[377]*acadoWorkspace.x[1] + acadoWorkspace.evGx[378]*acadoWorkspace.x[2] + acadoWorkspace.evGx[379]*acadoWorkspace.x[3] + acadoWorkspace.d[94]; +acadoVariables.x[99] += + acadoWorkspace.evGx[380]*acadoWorkspace.x[0] + acadoWorkspace.evGx[381]*acadoWorkspace.x[1] + acadoWorkspace.evGx[382]*acadoWorkspace.x[2] + acadoWorkspace.evGx[383]*acadoWorkspace.x[3] + acadoWorkspace.d[95]; +acadoVariables.x[100] += + acadoWorkspace.evGx[384]*acadoWorkspace.x[0] + acadoWorkspace.evGx[385]*acadoWorkspace.x[1] + acadoWorkspace.evGx[386]*acadoWorkspace.x[2] + acadoWorkspace.evGx[387]*acadoWorkspace.x[3] + acadoWorkspace.d[96]; +acadoVariables.x[101] += + acadoWorkspace.evGx[388]*acadoWorkspace.x[0] + acadoWorkspace.evGx[389]*acadoWorkspace.x[1] + acadoWorkspace.evGx[390]*acadoWorkspace.x[2] + acadoWorkspace.evGx[391]*acadoWorkspace.x[3] + acadoWorkspace.d[97]; +acadoVariables.x[102] += + acadoWorkspace.evGx[392]*acadoWorkspace.x[0] + acadoWorkspace.evGx[393]*acadoWorkspace.x[1] + acadoWorkspace.evGx[394]*acadoWorkspace.x[2] + acadoWorkspace.evGx[395]*acadoWorkspace.x[3] + acadoWorkspace.d[98]; +acadoVariables.x[103] += + acadoWorkspace.evGx[396]*acadoWorkspace.x[0] + acadoWorkspace.evGx[397]*acadoWorkspace.x[1] + acadoWorkspace.evGx[398]*acadoWorkspace.x[2] + acadoWorkspace.evGx[399]*acadoWorkspace.x[3] + acadoWorkspace.d[99]; +acadoVariables.x[104] += + acadoWorkspace.evGx[400]*acadoWorkspace.x[0] + acadoWorkspace.evGx[401]*acadoWorkspace.x[1] + acadoWorkspace.evGx[402]*acadoWorkspace.x[2] + acadoWorkspace.evGx[403]*acadoWorkspace.x[3] + acadoWorkspace.d[100]; +acadoVariables.x[105] += + acadoWorkspace.evGx[404]*acadoWorkspace.x[0] + acadoWorkspace.evGx[405]*acadoWorkspace.x[1] + acadoWorkspace.evGx[406]*acadoWorkspace.x[2] + acadoWorkspace.evGx[407]*acadoWorkspace.x[3] + acadoWorkspace.d[101]; +acadoVariables.x[106] += + acadoWorkspace.evGx[408]*acadoWorkspace.x[0] + acadoWorkspace.evGx[409]*acadoWorkspace.x[1] + acadoWorkspace.evGx[410]*acadoWorkspace.x[2] + acadoWorkspace.evGx[411]*acadoWorkspace.x[3] + acadoWorkspace.d[102]; +acadoVariables.x[107] += + acadoWorkspace.evGx[412]*acadoWorkspace.x[0] + acadoWorkspace.evGx[413]*acadoWorkspace.x[1] + acadoWorkspace.evGx[414]*acadoWorkspace.x[2] + acadoWorkspace.evGx[415]*acadoWorkspace.x[3] + acadoWorkspace.d[103]; +acadoVariables.x[108] += + acadoWorkspace.evGx[416]*acadoWorkspace.x[0] + acadoWorkspace.evGx[417]*acadoWorkspace.x[1] + acadoWorkspace.evGx[418]*acadoWorkspace.x[2] + acadoWorkspace.evGx[419]*acadoWorkspace.x[3] + acadoWorkspace.d[104]; +acadoVariables.x[109] += + acadoWorkspace.evGx[420]*acadoWorkspace.x[0] + acadoWorkspace.evGx[421]*acadoWorkspace.x[1] + acadoWorkspace.evGx[422]*acadoWorkspace.x[2] + acadoWorkspace.evGx[423]*acadoWorkspace.x[3] + acadoWorkspace.d[105]; +acadoVariables.x[110] += + acadoWorkspace.evGx[424]*acadoWorkspace.x[0] + acadoWorkspace.evGx[425]*acadoWorkspace.x[1] + acadoWorkspace.evGx[426]*acadoWorkspace.x[2] + acadoWorkspace.evGx[427]*acadoWorkspace.x[3] + acadoWorkspace.d[106]; +acadoVariables.x[111] += + acadoWorkspace.evGx[428]*acadoWorkspace.x[0] + acadoWorkspace.evGx[429]*acadoWorkspace.x[1] + acadoWorkspace.evGx[430]*acadoWorkspace.x[2] + acadoWorkspace.evGx[431]*acadoWorkspace.x[3] + acadoWorkspace.d[107]; +acadoVariables.x[112] += + acadoWorkspace.evGx[432]*acadoWorkspace.x[0] + acadoWorkspace.evGx[433]*acadoWorkspace.x[1] + acadoWorkspace.evGx[434]*acadoWorkspace.x[2] + acadoWorkspace.evGx[435]*acadoWorkspace.x[3] + acadoWorkspace.d[108]; +acadoVariables.x[113] += + acadoWorkspace.evGx[436]*acadoWorkspace.x[0] + acadoWorkspace.evGx[437]*acadoWorkspace.x[1] + acadoWorkspace.evGx[438]*acadoWorkspace.x[2] + acadoWorkspace.evGx[439]*acadoWorkspace.x[3] + acadoWorkspace.d[109]; +acadoVariables.x[114] += + acadoWorkspace.evGx[440]*acadoWorkspace.x[0] + acadoWorkspace.evGx[441]*acadoWorkspace.x[1] + acadoWorkspace.evGx[442]*acadoWorkspace.x[2] + acadoWorkspace.evGx[443]*acadoWorkspace.x[3] + acadoWorkspace.d[110]; +acadoVariables.x[115] += + acadoWorkspace.evGx[444]*acadoWorkspace.x[0] + acadoWorkspace.evGx[445]*acadoWorkspace.x[1] + acadoWorkspace.evGx[446]*acadoWorkspace.x[2] + acadoWorkspace.evGx[447]*acadoWorkspace.x[3] + acadoWorkspace.d[111]; +acadoVariables.x[116] += + acadoWorkspace.evGx[448]*acadoWorkspace.x[0] + acadoWorkspace.evGx[449]*acadoWorkspace.x[1] + acadoWorkspace.evGx[450]*acadoWorkspace.x[2] + acadoWorkspace.evGx[451]*acadoWorkspace.x[3] + acadoWorkspace.d[112]; +acadoVariables.x[117] += + acadoWorkspace.evGx[452]*acadoWorkspace.x[0] + acadoWorkspace.evGx[453]*acadoWorkspace.x[1] + acadoWorkspace.evGx[454]*acadoWorkspace.x[2] + acadoWorkspace.evGx[455]*acadoWorkspace.x[3] + acadoWorkspace.d[113]; +acadoVariables.x[118] += + acadoWorkspace.evGx[456]*acadoWorkspace.x[0] + acadoWorkspace.evGx[457]*acadoWorkspace.x[1] + acadoWorkspace.evGx[458]*acadoWorkspace.x[2] + acadoWorkspace.evGx[459]*acadoWorkspace.x[3] + acadoWorkspace.d[114]; +acadoVariables.x[119] += + acadoWorkspace.evGx[460]*acadoWorkspace.x[0] + acadoWorkspace.evGx[461]*acadoWorkspace.x[1] + acadoWorkspace.evGx[462]*acadoWorkspace.x[2] + acadoWorkspace.evGx[463]*acadoWorkspace.x[3] + acadoWorkspace.d[115]; +acadoVariables.x[120] += + acadoWorkspace.evGx[464]*acadoWorkspace.x[0] + acadoWorkspace.evGx[465]*acadoWorkspace.x[1] + acadoWorkspace.evGx[466]*acadoWorkspace.x[2] + acadoWorkspace.evGx[467]*acadoWorkspace.x[3] + acadoWorkspace.d[116]; +acadoVariables.x[121] += + acadoWorkspace.evGx[468]*acadoWorkspace.x[0] + acadoWorkspace.evGx[469]*acadoWorkspace.x[1] + acadoWorkspace.evGx[470]*acadoWorkspace.x[2] + acadoWorkspace.evGx[471]*acadoWorkspace.x[3] + acadoWorkspace.d[117]; +acadoVariables.x[122] += + acadoWorkspace.evGx[472]*acadoWorkspace.x[0] + acadoWorkspace.evGx[473]*acadoWorkspace.x[1] + acadoWorkspace.evGx[474]*acadoWorkspace.x[2] + acadoWorkspace.evGx[475]*acadoWorkspace.x[3] + acadoWorkspace.d[118]; +acadoVariables.x[123] += + acadoWorkspace.evGx[476]*acadoWorkspace.x[0] + acadoWorkspace.evGx[477]*acadoWorkspace.x[1] + acadoWorkspace.evGx[478]*acadoWorkspace.x[2] + acadoWorkspace.evGx[479]*acadoWorkspace.x[3] + acadoWorkspace.d[119]; +acadoVariables.x[124] += + acadoWorkspace.evGx[480]*acadoWorkspace.x[0] + acadoWorkspace.evGx[481]*acadoWorkspace.x[1] + acadoWorkspace.evGx[482]*acadoWorkspace.x[2] + acadoWorkspace.evGx[483]*acadoWorkspace.x[3] + acadoWorkspace.d[120]; +acadoVariables.x[125] += + acadoWorkspace.evGx[484]*acadoWorkspace.x[0] + acadoWorkspace.evGx[485]*acadoWorkspace.x[1] + acadoWorkspace.evGx[486]*acadoWorkspace.x[2] + acadoWorkspace.evGx[487]*acadoWorkspace.x[3] + acadoWorkspace.d[121]; +acadoVariables.x[126] += + acadoWorkspace.evGx[488]*acadoWorkspace.x[0] + acadoWorkspace.evGx[489]*acadoWorkspace.x[1] + acadoWorkspace.evGx[490]*acadoWorkspace.x[2] + acadoWorkspace.evGx[491]*acadoWorkspace.x[3] + acadoWorkspace.d[122]; +acadoVariables.x[127] += + acadoWorkspace.evGx[492]*acadoWorkspace.x[0] + acadoWorkspace.evGx[493]*acadoWorkspace.x[1] + acadoWorkspace.evGx[494]*acadoWorkspace.x[2] + acadoWorkspace.evGx[495]*acadoWorkspace.x[3] + acadoWorkspace.d[123]; +acadoVariables.x[128] += + acadoWorkspace.evGx[496]*acadoWorkspace.x[0] + acadoWorkspace.evGx[497]*acadoWorkspace.x[1] + acadoWorkspace.evGx[498]*acadoWorkspace.x[2] + acadoWorkspace.evGx[499]*acadoWorkspace.x[3] + acadoWorkspace.d[124]; +acadoVariables.x[129] += + acadoWorkspace.evGx[500]*acadoWorkspace.x[0] + acadoWorkspace.evGx[501]*acadoWorkspace.x[1] + acadoWorkspace.evGx[502]*acadoWorkspace.x[2] + acadoWorkspace.evGx[503]*acadoWorkspace.x[3] + acadoWorkspace.d[125]; +acadoVariables.x[130] += + acadoWorkspace.evGx[504]*acadoWorkspace.x[0] + acadoWorkspace.evGx[505]*acadoWorkspace.x[1] + acadoWorkspace.evGx[506]*acadoWorkspace.x[2] + acadoWorkspace.evGx[507]*acadoWorkspace.x[3] + acadoWorkspace.d[126]; +acadoVariables.x[131] += + acadoWorkspace.evGx[508]*acadoWorkspace.x[0] + acadoWorkspace.evGx[509]*acadoWorkspace.x[1] + acadoWorkspace.evGx[510]*acadoWorkspace.x[2] + acadoWorkspace.evGx[511]*acadoWorkspace.x[3] + acadoWorkspace.d[127]; +acadoVariables.x[132] += + acadoWorkspace.evGx[512]*acadoWorkspace.x[0] + acadoWorkspace.evGx[513]*acadoWorkspace.x[1] + acadoWorkspace.evGx[514]*acadoWorkspace.x[2] + acadoWorkspace.evGx[515]*acadoWorkspace.x[3] + acadoWorkspace.d[128]; +acadoVariables.x[133] += + acadoWorkspace.evGx[516]*acadoWorkspace.x[0] + acadoWorkspace.evGx[517]*acadoWorkspace.x[1] + acadoWorkspace.evGx[518]*acadoWorkspace.x[2] + acadoWorkspace.evGx[519]*acadoWorkspace.x[3] + acadoWorkspace.d[129]; +acadoVariables.x[134] += + acadoWorkspace.evGx[520]*acadoWorkspace.x[0] + acadoWorkspace.evGx[521]*acadoWorkspace.x[1] + acadoWorkspace.evGx[522]*acadoWorkspace.x[2] + acadoWorkspace.evGx[523]*acadoWorkspace.x[3] + acadoWorkspace.d[130]; +acadoVariables.x[135] += + acadoWorkspace.evGx[524]*acadoWorkspace.x[0] + acadoWorkspace.evGx[525]*acadoWorkspace.x[1] + acadoWorkspace.evGx[526]*acadoWorkspace.x[2] + acadoWorkspace.evGx[527]*acadoWorkspace.x[3] + acadoWorkspace.d[131]; +acadoVariables.x[136] += + acadoWorkspace.evGx[528]*acadoWorkspace.x[0] + acadoWorkspace.evGx[529]*acadoWorkspace.x[1] + acadoWorkspace.evGx[530]*acadoWorkspace.x[2] + acadoWorkspace.evGx[531]*acadoWorkspace.x[3] + acadoWorkspace.d[132]; +acadoVariables.x[137] += + acadoWorkspace.evGx[532]*acadoWorkspace.x[0] + acadoWorkspace.evGx[533]*acadoWorkspace.x[1] + acadoWorkspace.evGx[534]*acadoWorkspace.x[2] + acadoWorkspace.evGx[535]*acadoWorkspace.x[3] + acadoWorkspace.d[133]; +acadoVariables.x[138] += + acadoWorkspace.evGx[536]*acadoWorkspace.x[0] + acadoWorkspace.evGx[537]*acadoWorkspace.x[1] + acadoWorkspace.evGx[538]*acadoWorkspace.x[2] + acadoWorkspace.evGx[539]*acadoWorkspace.x[3] + acadoWorkspace.d[134]; +acadoVariables.x[139] += + acadoWorkspace.evGx[540]*acadoWorkspace.x[0] + acadoWorkspace.evGx[541]*acadoWorkspace.x[1] + acadoWorkspace.evGx[542]*acadoWorkspace.x[2] + acadoWorkspace.evGx[543]*acadoWorkspace.x[3] + acadoWorkspace.d[135]; +acadoVariables.x[140] += + acadoWorkspace.evGx[544]*acadoWorkspace.x[0] + acadoWorkspace.evGx[545]*acadoWorkspace.x[1] + acadoWorkspace.evGx[546]*acadoWorkspace.x[2] + acadoWorkspace.evGx[547]*acadoWorkspace.x[3] + acadoWorkspace.d[136]; +acadoVariables.x[141] += + acadoWorkspace.evGx[548]*acadoWorkspace.x[0] + acadoWorkspace.evGx[549]*acadoWorkspace.x[1] + acadoWorkspace.evGx[550]*acadoWorkspace.x[2] + acadoWorkspace.evGx[551]*acadoWorkspace.x[3] + acadoWorkspace.d[137]; +acadoVariables.x[142] += + acadoWorkspace.evGx[552]*acadoWorkspace.x[0] + acadoWorkspace.evGx[553]*acadoWorkspace.x[1] + acadoWorkspace.evGx[554]*acadoWorkspace.x[2] + acadoWorkspace.evGx[555]*acadoWorkspace.x[3] + acadoWorkspace.d[138]; +acadoVariables.x[143] += + acadoWorkspace.evGx[556]*acadoWorkspace.x[0] + acadoWorkspace.evGx[557]*acadoWorkspace.x[1] + acadoWorkspace.evGx[558]*acadoWorkspace.x[2] + acadoWorkspace.evGx[559]*acadoWorkspace.x[3] + acadoWorkspace.d[139]; +acadoVariables.x[144] += + acadoWorkspace.evGx[560]*acadoWorkspace.x[0] + acadoWorkspace.evGx[561]*acadoWorkspace.x[1] + acadoWorkspace.evGx[562]*acadoWorkspace.x[2] + acadoWorkspace.evGx[563]*acadoWorkspace.x[3] + acadoWorkspace.d[140]; +acadoVariables.x[145] += + acadoWorkspace.evGx[564]*acadoWorkspace.x[0] + acadoWorkspace.evGx[565]*acadoWorkspace.x[1] + acadoWorkspace.evGx[566]*acadoWorkspace.x[2] + acadoWorkspace.evGx[567]*acadoWorkspace.x[3] + acadoWorkspace.d[141]; +acadoVariables.x[146] += + acadoWorkspace.evGx[568]*acadoWorkspace.x[0] + acadoWorkspace.evGx[569]*acadoWorkspace.x[1] + acadoWorkspace.evGx[570]*acadoWorkspace.x[2] + acadoWorkspace.evGx[571]*acadoWorkspace.x[3] + acadoWorkspace.d[142]; +acadoVariables.x[147] += + acadoWorkspace.evGx[572]*acadoWorkspace.x[0] + acadoWorkspace.evGx[573]*acadoWorkspace.x[1] + acadoWorkspace.evGx[574]*acadoWorkspace.x[2] + acadoWorkspace.evGx[575]*acadoWorkspace.x[3] + acadoWorkspace.d[143]; +acadoVariables.x[148] += + acadoWorkspace.evGx[576]*acadoWorkspace.x[0] + acadoWorkspace.evGx[577]*acadoWorkspace.x[1] + acadoWorkspace.evGx[578]*acadoWorkspace.x[2] + acadoWorkspace.evGx[579]*acadoWorkspace.x[3] + acadoWorkspace.d[144]; +acadoVariables.x[149] += + acadoWorkspace.evGx[580]*acadoWorkspace.x[0] + acadoWorkspace.evGx[581]*acadoWorkspace.x[1] + acadoWorkspace.evGx[582]*acadoWorkspace.x[2] + acadoWorkspace.evGx[583]*acadoWorkspace.x[3] + acadoWorkspace.d[145]; +acadoVariables.x[150] += + acadoWorkspace.evGx[584]*acadoWorkspace.x[0] + acadoWorkspace.evGx[585]*acadoWorkspace.x[1] + acadoWorkspace.evGx[586]*acadoWorkspace.x[2] + acadoWorkspace.evGx[587]*acadoWorkspace.x[3] + acadoWorkspace.d[146]; +acadoVariables.x[151] += + acadoWorkspace.evGx[588]*acadoWorkspace.x[0] + acadoWorkspace.evGx[589]*acadoWorkspace.x[1] + acadoWorkspace.evGx[590]*acadoWorkspace.x[2] + acadoWorkspace.evGx[591]*acadoWorkspace.x[3] + acadoWorkspace.d[147]; +acadoVariables.x[152] += + acadoWorkspace.evGx[592]*acadoWorkspace.x[0] + acadoWorkspace.evGx[593]*acadoWorkspace.x[1] + acadoWorkspace.evGx[594]*acadoWorkspace.x[2] + acadoWorkspace.evGx[595]*acadoWorkspace.x[3] + acadoWorkspace.d[148]; +acadoVariables.x[153] += + acadoWorkspace.evGx[596]*acadoWorkspace.x[0] + acadoWorkspace.evGx[597]*acadoWorkspace.x[1] + acadoWorkspace.evGx[598]*acadoWorkspace.x[2] + acadoWorkspace.evGx[599]*acadoWorkspace.x[3] + acadoWorkspace.d[149]; +acadoVariables.x[154] += + acadoWorkspace.evGx[600]*acadoWorkspace.x[0] + acadoWorkspace.evGx[601]*acadoWorkspace.x[1] + acadoWorkspace.evGx[602]*acadoWorkspace.x[2] + acadoWorkspace.evGx[603]*acadoWorkspace.x[3] + acadoWorkspace.d[150]; +acadoVariables.x[155] += + acadoWorkspace.evGx[604]*acadoWorkspace.x[0] + acadoWorkspace.evGx[605]*acadoWorkspace.x[1] + acadoWorkspace.evGx[606]*acadoWorkspace.x[2] + acadoWorkspace.evGx[607]*acadoWorkspace.x[3] + acadoWorkspace.d[151]; +acadoVariables.x[156] += + acadoWorkspace.evGx[608]*acadoWorkspace.x[0] + acadoWorkspace.evGx[609]*acadoWorkspace.x[1] + acadoWorkspace.evGx[610]*acadoWorkspace.x[2] + acadoWorkspace.evGx[611]*acadoWorkspace.x[3] + acadoWorkspace.d[152]; +acadoVariables.x[157] += + acadoWorkspace.evGx[612]*acadoWorkspace.x[0] + acadoWorkspace.evGx[613]*acadoWorkspace.x[1] + acadoWorkspace.evGx[614]*acadoWorkspace.x[2] + acadoWorkspace.evGx[615]*acadoWorkspace.x[3] + acadoWorkspace.d[153]; +acadoVariables.x[158] += + acadoWorkspace.evGx[616]*acadoWorkspace.x[0] + acadoWorkspace.evGx[617]*acadoWorkspace.x[1] + acadoWorkspace.evGx[618]*acadoWorkspace.x[2] + acadoWorkspace.evGx[619]*acadoWorkspace.x[3] + acadoWorkspace.d[154]; +acadoVariables.x[159] += + acadoWorkspace.evGx[620]*acadoWorkspace.x[0] + acadoWorkspace.evGx[621]*acadoWorkspace.x[1] + acadoWorkspace.evGx[622]*acadoWorkspace.x[2] + acadoWorkspace.evGx[623]*acadoWorkspace.x[3] + acadoWorkspace.d[155]; +acadoVariables.x[160] += + acadoWorkspace.evGx[624]*acadoWorkspace.x[0] + acadoWorkspace.evGx[625]*acadoWorkspace.x[1] + acadoWorkspace.evGx[626]*acadoWorkspace.x[2] + acadoWorkspace.evGx[627]*acadoWorkspace.x[3] + acadoWorkspace.d[156]; +acadoVariables.x[161] += + acadoWorkspace.evGx[628]*acadoWorkspace.x[0] + acadoWorkspace.evGx[629]*acadoWorkspace.x[1] + acadoWorkspace.evGx[630]*acadoWorkspace.x[2] + acadoWorkspace.evGx[631]*acadoWorkspace.x[3] + acadoWorkspace.d[157]; +acadoVariables.x[162] += + acadoWorkspace.evGx[632]*acadoWorkspace.x[0] + acadoWorkspace.evGx[633]*acadoWorkspace.x[1] + acadoWorkspace.evGx[634]*acadoWorkspace.x[2] + acadoWorkspace.evGx[635]*acadoWorkspace.x[3] + acadoWorkspace.d[158]; +acadoVariables.x[163] += + acadoWorkspace.evGx[636]*acadoWorkspace.x[0] + acadoWorkspace.evGx[637]*acadoWorkspace.x[1] + acadoWorkspace.evGx[638]*acadoWorkspace.x[2] + acadoWorkspace.evGx[639]*acadoWorkspace.x[3] + acadoWorkspace.d[159]; +acadoVariables.x[164] += + acadoWorkspace.evGx[640]*acadoWorkspace.x[0] + acadoWorkspace.evGx[641]*acadoWorkspace.x[1] + acadoWorkspace.evGx[642]*acadoWorkspace.x[2] + acadoWorkspace.evGx[643]*acadoWorkspace.x[3] + acadoWorkspace.d[160]; +acadoVariables.x[165] += + acadoWorkspace.evGx[644]*acadoWorkspace.x[0] + acadoWorkspace.evGx[645]*acadoWorkspace.x[1] + acadoWorkspace.evGx[646]*acadoWorkspace.x[2] + acadoWorkspace.evGx[647]*acadoWorkspace.x[3] + acadoWorkspace.d[161]; +acadoVariables.x[166] += + acadoWorkspace.evGx[648]*acadoWorkspace.x[0] + acadoWorkspace.evGx[649]*acadoWorkspace.x[1] + acadoWorkspace.evGx[650]*acadoWorkspace.x[2] + acadoWorkspace.evGx[651]*acadoWorkspace.x[3] + acadoWorkspace.d[162]; +acadoVariables.x[167] += + acadoWorkspace.evGx[652]*acadoWorkspace.x[0] + acadoWorkspace.evGx[653]*acadoWorkspace.x[1] + acadoWorkspace.evGx[654]*acadoWorkspace.x[2] + acadoWorkspace.evGx[655]*acadoWorkspace.x[3] + acadoWorkspace.d[163]; +acadoVariables.x[168] += + acadoWorkspace.evGx[656]*acadoWorkspace.x[0] + acadoWorkspace.evGx[657]*acadoWorkspace.x[1] + acadoWorkspace.evGx[658]*acadoWorkspace.x[2] + acadoWorkspace.evGx[659]*acadoWorkspace.x[3] + acadoWorkspace.d[164]; +acadoVariables.x[169] += + acadoWorkspace.evGx[660]*acadoWorkspace.x[0] + acadoWorkspace.evGx[661]*acadoWorkspace.x[1] + acadoWorkspace.evGx[662]*acadoWorkspace.x[2] + acadoWorkspace.evGx[663]*acadoWorkspace.x[3] + acadoWorkspace.d[165]; +acadoVariables.x[170] += + acadoWorkspace.evGx[664]*acadoWorkspace.x[0] + acadoWorkspace.evGx[665]*acadoWorkspace.x[1] + acadoWorkspace.evGx[666]*acadoWorkspace.x[2] + acadoWorkspace.evGx[667]*acadoWorkspace.x[3] + acadoWorkspace.d[166]; +acadoVariables.x[171] += + acadoWorkspace.evGx[668]*acadoWorkspace.x[0] + acadoWorkspace.evGx[669]*acadoWorkspace.x[1] + acadoWorkspace.evGx[670]*acadoWorkspace.x[2] + acadoWorkspace.evGx[671]*acadoWorkspace.x[3] + acadoWorkspace.d[167]; +acadoVariables.x[172] += + acadoWorkspace.evGx[672]*acadoWorkspace.x[0] + acadoWorkspace.evGx[673]*acadoWorkspace.x[1] + acadoWorkspace.evGx[674]*acadoWorkspace.x[2] + acadoWorkspace.evGx[675]*acadoWorkspace.x[3] + acadoWorkspace.d[168]; +acadoVariables.x[173] += + acadoWorkspace.evGx[676]*acadoWorkspace.x[0] + acadoWorkspace.evGx[677]*acadoWorkspace.x[1] + acadoWorkspace.evGx[678]*acadoWorkspace.x[2] + acadoWorkspace.evGx[679]*acadoWorkspace.x[3] + acadoWorkspace.d[169]; +acadoVariables.x[174] += + acadoWorkspace.evGx[680]*acadoWorkspace.x[0] + acadoWorkspace.evGx[681]*acadoWorkspace.x[1] + acadoWorkspace.evGx[682]*acadoWorkspace.x[2] + acadoWorkspace.evGx[683]*acadoWorkspace.x[3] + acadoWorkspace.d[170]; +acadoVariables.x[175] += + acadoWorkspace.evGx[684]*acadoWorkspace.x[0] + acadoWorkspace.evGx[685]*acadoWorkspace.x[1] + acadoWorkspace.evGx[686]*acadoWorkspace.x[2] + acadoWorkspace.evGx[687]*acadoWorkspace.x[3] + acadoWorkspace.d[171]; +acadoVariables.x[176] += + acadoWorkspace.evGx[688]*acadoWorkspace.x[0] + acadoWorkspace.evGx[689]*acadoWorkspace.x[1] + acadoWorkspace.evGx[690]*acadoWorkspace.x[2] + acadoWorkspace.evGx[691]*acadoWorkspace.x[3] + acadoWorkspace.d[172]; +acadoVariables.x[177] += + acadoWorkspace.evGx[692]*acadoWorkspace.x[0] + acadoWorkspace.evGx[693]*acadoWorkspace.x[1] + acadoWorkspace.evGx[694]*acadoWorkspace.x[2] + acadoWorkspace.evGx[695]*acadoWorkspace.x[3] + acadoWorkspace.d[173]; +acadoVariables.x[178] += + acadoWorkspace.evGx[696]*acadoWorkspace.x[0] + acadoWorkspace.evGx[697]*acadoWorkspace.x[1] + acadoWorkspace.evGx[698]*acadoWorkspace.x[2] + acadoWorkspace.evGx[699]*acadoWorkspace.x[3] + acadoWorkspace.d[174]; +acadoVariables.x[179] += + acadoWorkspace.evGx[700]*acadoWorkspace.x[0] + acadoWorkspace.evGx[701]*acadoWorkspace.x[1] + acadoWorkspace.evGx[702]*acadoWorkspace.x[2] + acadoWorkspace.evGx[703]*acadoWorkspace.x[3] + acadoWorkspace.d[175]; +acadoVariables.x[180] += + acadoWorkspace.evGx[704]*acadoWorkspace.x[0] + acadoWorkspace.evGx[705]*acadoWorkspace.x[1] + acadoWorkspace.evGx[706]*acadoWorkspace.x[2] + acadoWorkspace.evGx[707]*acadoWorkspace.x[3] + acadoWorkspace.d[176]; +acadoVariables.x[181] += + acadoWorkspace.evGx[708]*acadoWorkspace.x[0] + acadoWorkspace.evGx[709]*acadoWorkspace.x[1] + acadoWorkspace.evGx[710]*acadoWorkspace.x[2] + acadoWorkspace.evGx[711]*acadoWorkspace.x[3] + acadoWorkspace.d[177]; +acadoVariables.x[182] += + acadoWorkspace.evGx[712]*acadoWorkspace.x[0] + acadoWorkspace.evGx[713]*acadoWorkspace.x[1] + acadoWorkspace.evGx[714]*acadoWorkspace.x[2] + acadoWorkspace.evGx[715]*acadoWorkspace.x[3] + acadoWorkspace.d[178]; +acadoVariables.x[183] += + acadoWorkspace.evGx[716]*acadoWorkspace.x[0] + acadoWorkspace.evGx[717]*acadoWorkspace.x[1] + acadoWorkspace.evGx[718]*acadoWorkspace.x[2] + acadoWorkspace.evGx[719]*acadoWorkspace.x[3] + acadoWorkspace.d[179]; +acadoVariables.x[184] += + acadoWorkspace.evGx[720]*acadoWorkspace.x[0] + acadoWorkspace.evGx[721]*acadoWorkspace.x[1] + acadoWorkspace.evGx[722]*acadoWorkspace.x[2] + acadoWorkspace.evGx[723]*acadoWorkspace.x[3] + acadoWorkspace.d[180]; +acadoVariables.x[185] += + acadoWorkspace.evGx[724]*acadoWorkspace.x[0] + acadoWorkspace.evGx[725]*acadoWorkspace.x[1] + acadoWorkspace.evGx[726]*acadoWorkspace.x[2] + acadoWorkspace.evGx[727]*acadoWorkspace.x[3] + acadoWorkspace.d[181]; +acadoVariables.x[186] += + acadoWorkspace.evGx[728]*acadoWorkspace.x[0] + acadoWorkspace.evGx[729]*acadoWorkspace.x[1] + acadoWorkspace.evGx[730]*acadoWorkspace.x[2] + acadoWorkspace.evGx[731]*acadoWorkspace.x[3] + acadoWorkspace.d[182]; +acadoVariables.x[187] += + acadoWorkspace.evGx[732]*acadoWorkspace.x[0] + acadoWorkspace.evGx[733]*acadoWorkspace.x[1] + acadoWorkspace.evGx[734]*acadoWorkspace.x[2] + acadoWorkspace.evGx[735]*acadoWorkspace.x[3] + acadoWorkspace.d[183]; +acadoVariables.x[188] += + acadoWorkspace.evGx[736]*acadoWorkspace.x[0] + acadoWorkspace.evGx[737]*acadoWorkspace.x[1] + acadoWorkspace.evGx[738]*acadoWorkspace.x[2] + acadoWorkspace.evGx[739]*acadoWorkspace.x[3] + acadoWorkspace.d[184]; +acadoVariables.x[189] += + acadoWorkspace.evGx[740]*acadoWorkspace.x[0] + acadoWorkspace.evGx[741]*acadoWorkspace.x[1] + acadoWorkspace.evGx[742]*acadoWorkspace.x[2] + acadoWorkspace.evGx[743]*acadoWorkspace.x[3] + acadoWorkspace.d[185]; +acadoVariables.x[190] += + acadoWorkspace.evGx[744]*acadoWorkspace.x[0] + acadoWorkspace.evGx[745]*acadoWorkspace.x[1] + acadoWorkspace.evGx[746]*acadoWorkspace.x[2] + acadoWorkspace.evGx[747]*acadoWorkspace.x[3] + acadoWorkspace.d[186]; +acadoVariables.x[191] += + acadoWorkspace.evGx[748]*acadoWorkspace.x[0] + acadoWorkspace.evGx[749]*acadoWorkspace.x[1] + acadoWorkspace.evGx[750]*acadoWorkspace.x[2] + acadoWorkspace.evGx[751]*acadoWorkspace.x[3] + acadoWorkspace.d[187]; +acadoVariables.x[192] += + acadoWorkspace.evGx[752]*acadoWorkspace.x[0] + acadoWorkspace.evGx[753]*acadoWorkspace.x[1] + acadoWorkspace.evGx[754]*acadoWorkspace.x[2] + acadoWorkspace.evGx[755]*acadoWorkspace.x[3] + acadoWorkspace.d[188]; +acadoVariables.x[193] += + acadoWorkspace.evGx[756]*acadoWorkspace.x[0] + acadoWorkspace.evGx[757]*acadoWorkspace.x[1] + acadoWorkspace.evGx[758]*acadoWorkspace.x[2] + acadoWorkspace.evGx[759]*acadoWorkspace.x[3] + acadoWorkspace.d[189]; +acadoVariables.x[194] += + acadoWorkspace.evGx[760]*acadoWorkspace.x[0] + acadoWorkspace.evGx[761]*acadoWorkspace.x[1] + acadoWorkspace.evGx[762]*acadoWorkspace.x[2] + acadoWorkspace.evGx[763]*acadoWorkspace.x[3] + acadoWorkspace.d[190]; +acadoVariables.x[195] += + acadoWorkspace.evGx[764]*acadoWorkspace.x[0] + acadoWorkspace.evGx[765]*acadoWorkspace.x[1] + acadoWorkspace.evGx[766]*acadoWorkspace.x[2] + acadoWorkspace.evGx[767]*acadoWorkspace.x[3] + acadoWorkspace.d[191]; +acadoVariables.x[196] += + acadoWorkspace.evGx[768]*acadoWorkspace.x[0] + acadoWorkspace.evGx[769]*acadoWorkspace.x[1] + acadoWorkspace.evGx[770]*acadoWorkspace.x[2] + acadoWorkspace.evGx[771]*acadoWorkspace.x[3] + acadoWorkspace.d[192]; +acadoVariables.x[197] += + acadoWorkspace.evGx[772]*acadoWorkspace.x[0] + acadoWorkspace.evGx[773]*acadoWorkspace.x[1] + acadoWorkspace.evGx[774]*acadoWorkspace.x[2] + acadoWorkspace.evGx[775]*acadoWorkspace.x[3] + acadoWorkspace.d[193]; +acadoVariables.x[198] += + acadoWorkspace.evGx[776]*acadoWorkspace.x[0] + acadoWorkspace.evGx[777]*acadoWorkspace.x[1] + acadoWorkspace.evGx[778]*acadoWorkspace.x[2] + acadoWorkspace.evGx[779]*acadoWorkspace.x[3] + acadoWorkspace.d[194]; +acadoVariables.x[199] += + acadoWorkspace.evGx[780]*acadoWorkspace.x[0] + acadoWorkspace.evGx[781]*acadoWorkspace.x[1] + acadoWorkspace.evGx[782]*acadoWorkspace.x[2] + acadoWorkspace.evGx[783]*acadoWorkspace.x[3] + acadoWorkspace.d[195]; +acadoVariables.x[200] += + acadoWorkspace.evGx[784]*acadoWorkspace.x[0] + acadoWorkspace.evGx[785]*acadoWorkspace.x[1] + acadoWorkspace.evGx[786]*acadoWorkspace.x[2] + acadoWorkspace.evGx[787]*acadoWorkspace.x[3] + acadoWorkspace.d[196]; +acadoVariables.x[201] += + acadoWorkspace.evGx[788]*acadoWorkspace.x[0] + acadoWorkspace.evGx[789]*acadoWorkspace.x[1] + acadoWorkspace.evGx[790]*acadoWorkspace.x[2] + acadoWorkspace.evGx[791]*acadoWorkspace.x[3] + acadoWorkspace.d[197]; +acadoVariables.x[202] += + acadoWorkspace.evGx[792]*acadoWorkspace.x[0] + acadoWorkspace.evGx[793]*acadoWorkspace.x[1] + acadoWorkspace.evGx[794]*acadoWorkspace.x[2] + acadoWorkspace.evGx[795]*acadoWorkspace.x[3] + acadoWorkspace.d[198]; +acadoVariables.x[203] += + acadoWorkspace.evGx[796]*acadoWorkspace.x[0] + acadoWorkspace.evGx[797]*acadoWorkspace.x[1] + acadoWorkspace.evGx[798]*acadoWorkspace.x[2] + acadoWorkspace.evGx[799]*acadoWorkspace.x[3] + acadoWorkspace.d[199]; + +for (lRun1 = 0; lRun1 < 50; ++lRun1) +{ +for (lRun2 = 0; lRun2 < lRun1 + 1; ++lRun2) +{ +lRun3 = (((lRun1 + 1) * (lRun1)) / (2)) + (lRun2); +acado_multEDu( &(acadoWorkspace.E[ lRun3 * 4 ]), &(acadoWorkspace.x[ lRun2 + 4 ]), &(acadoVariables.x[ lRun1 * 4 + 4 ]) ); +} +} +} + +int acado_preparationStep( ) +{ +int ret; + +ret = acado_modelSimulation(); +acado_evaluateObjective( ); +acado_condensePrep( ); +return ret; +} + +int acado_feedbackStep( ) +{ +int tmp; + +acado_condenseFdb( ); + +tmp = acado_solve( ); + +acado_expand( ); +return tmp; +} + +int acado_initializeSolver( ) +{ +int ret; + +/* This is a function which must be called once before any other function call! */ + + +ret = 0; + +memset(&acadoWorkspace, 0, sizeof( acadoWorkspace )); +return ret; +} + +void acado_initializeNodesByForwardSimulation( ) +{ +int index; +for (index = 0; index < 50; ++index) +{ +acadoWorkspace.state[0] = acadoVariables.x[index * 4]; +acadoWorkspace.state[1] = acadoVariables.x[index * 4 + 1]; +acadoWorkspace.state[2] = acadoVariables.x[index * 4 + 2]; +acadoWorkspace.state[3] = acadoVariables.x[index * 4 + 3]; +acadoWorkspace.state[24] = acadoVariables.u[index]; +acadoWorkspace.state[25] = acadoVariables.od[index * 18]; +acadoWorkspace.state[26] = acadoVariables.od[index * 18 + 1]; +acadoWorkspace.state[27] = acadoVariables.od[index * 18 + 2]; +acadoWorkspace.state[28] = acadoVariables.od[index * 18 + 3]; +acadoWorkspace.state[29] = acadoVariables.od[index * 18 + 4]; +acadoWorkspace.state[30] = acadoVariables.od[index * 18 + 5]; +acadoWorkspace.state[31] = acadoVariables.od[index * 18 + 6]; +acadoWorkspace.state[32] = acadoVariables.od[index * 18 + 7]; +acadoWorkspace.state[33] = acadoVariables.od[index * 18 + 8]; +acadoWorkspace.state[34] = acadoVariables.od[index * 18 + 9]; +acadoWorkspace.state[35] = acadoVariables.od[index * 18 + 10]; +acadoWorkspace.state[36] = acadoVariables.od[index * 18 + 11]; +acadoWorkspace.state[37] = acadoVariables.od[index * 18 + 12]; +acadoWorkspace.state[38] = acadoVariables.od[index * 18 + 13]; +acadoWorkspace.state[39] = acadoVariables.od[index * 18 + 14]; +acadoWorkspace.state[40] = acadoVariables.od[index * 18 + 15]; +acadoWorkspace.state[41] = acadoVariables.od[index * 18 + 16]; +acadoWorkspace.state[42] = acadoVariables.od[index * 18 + 17]; + +acado_integrate(acadoWorkspace.state, index == 0); + +acadoVariables.x[index * 4 + 4] = acadoWorkspace.state[0]; +acadoVariables.x[index * 4 + 5] = acadoWorkspace.state[1]; +acadoVariables.x[index * 4 + 6] = acadoWorkspace.state[2]; +acadoVariables.x[index * 4 + 7] = acadoWorkspace.state[3]; +} +} + +void acado_shiftStates( int strategy, real_t* const xEnd, real_t* const uEnd ) +{ +int index; +for (index = 0; index < 50; ++index) +{ +acadoVariables.x[index * 4] = acadoVariables.x[index * 4 + 4]; +acadoVariables.x[index * 4 + 1] = acadoVariables.x[index * 4 + 5]; +acadoVariables.x[index * 4 + 2] = acadoVariables.x[index * 4 + 6]; +acadoVariables.x[index * 4 + 3] = acadoVariables.x[index * 4 + 7]; +} + +if (strategy == 1 && xEnd != 0) +{ +acadoVariables.x[200] = xEnd[0]; +acadoVariables.x[201] = xEnd[1]; +acadoVariables.x[202] = xEnd[2]; +acadoVariables.x[203] = xEnd[3]; +} +else if (strategy == 2) +{ +acadoWorkspace.state[0] = acadoVariables.x[200]; +acadoWorkspace.state[1] = acadoVariables.x[201]; +acadoWorkspace.state[2] = acadoVariables.x[202]; +acadoWorkspace.state[3] = acadoVariables.x[203]; +if (uEnd != 0) +{ +acadoWorkspace.state[24] = uEnd[0]; +} +else +{ +acadoWorkspace.state[24] = acadoVariables.u[49]; +} +acadoWorkspace.state[25] = acadoVariables.od[900]; +acadoWorkspace.state[26] = acadoVariables.od[901]; +acadoWorkspace.state[27] = acadoVariables.od[902]; +acadoWorkspace.state[28] = acadoVariables.od[903]; +acadoWorkspace.state[29] = acadoVariables.od[904]; +acadoWorkspace.state[30] = acadoVariables.od[905]; +acadoWorkspace.state[31] = acadoVariables.od[906]; +acadoWorkspace.state[32] = acadoVariables.od[907]; +acadoWorkspace.state[33] = acadoVariables.od[908]; +acadoWorkspace.state[34] = acadoVariables.od[909]; +acadoWorkspace.state[35] = acadoVariables.od[910]; +acadoWorkspace.state[36] = acadoVariables.od[911]; +acadoWorkspace.state[37] = acadoVariables.od[912]; +acadoWorkspace.state[38] = acadoVariables.od[913]; +acadoWorkspace.state[39] = acadoVariables.od[914]; +acadoWorkspace.state[40] = acadoVariables.od[915]; +acadoWorkspace.state[41] = acadoVariables.od[916]; +acadoWorkspace.state[42] = acadoVariables.od[917]; + +acado_integrate(acadoWorkspace.state, 1); + +acadoVariables.x[200] = acadoWorkspace.state[0]; +acadoVariables.x[201] = acadoWorkspace.state[1]; +acadoVariables.x[202] = acadoWorkspace.state[2]; +acadoVariables.x[203] = acadoWorkspace.state[3]; +} +} + +void acado_shiftControls( real_t* const uEnd ) +{ +int index; +for (index = 0; index < 49; ++index) +{ +acadoVariables.u[index] = acadoVariables.u[index + 1]; +} + +if (uEnd != 0) +{ +acadoVariables.u[49] = uEnd[0]; +} +} + +real_t acado_getKKT( ) +{ +real_t kkt; + +int index; +real_t prd; + +kkt = + acadoWorkspace.g[0]*acadoWorkspace.x[0] + acadoWorkspace.g[1]*acadoWorkspace.x[1] + acadoWorkspace.g[2]*acadoWorkspace.x[2] + acadoWorkspace.g[3]*acadoWorkspace.x[3] + acadoWorkspace.g[4]*acadoWorkspace.x[4] + acadoWorkspace.g[5]*acadoWorkspace.x[5] + acadoWorkspace.g[6]*acadoWorkspace.x[6] + acadoWorkspace.g[7]*acadoWorkspace.x[7] + acadoWorkspace.g[8]*acadoWorkspace.x[8] + acadoWorkspace.g[9]*acadoWorkspace.x[9] + acadoWorkspace.g[10]*acadoWorkspace.x[10] + acadoWorkspace.g[11]*acadoWorkspace.x[11] + acadoWorkspace.g[12]*acadoWorkspace.x[12] + acadoWorkspace.g[13]*acadoWorkspace.x[13] + acadoWorkspace.g[14]*acadoWorkspace.x[14] + acadoWorkspace.g[15]*acadoWorkspace.x[15] + acadoWorkspace.g[16]*acadoWorkspace.x[16] + acadoWorkspace.g[17]*acadoWorkspace.x[17] + acadoWorkspace.g[18]*acadoWorkspace.x[18] + acadoWorkspace.g[19]*acadoWorkspace.x[19] + acadoWorkspace.g[20]*acadoWorkspace.x[20] + acadoWorkspace.g[21]*acadoWorkspace.x[21] + acadoWorkspace.g[22]*acadoWorkspace.x[22] + acadoWorkspace.g[23]*acadoWorkspace.x[23] + acadoWorkspace.g[24]*acadoWorkspace.x[24] + acadoWorkspace.g[25]*acadoWorkspace.x[25] + acadoWorkspace.g[26]*acadoWorkspace.x[26] + acadoWorkspace.g[27]*acadoWorkspace.x[27] + acadoWorkspace.g[28]*acadoWorkspace.x[28] + acadoWorkspace.g[29]*acadoWorkspace.x[29] + acadoWorkspace.g[30]*acadoWorkspace.x[30] + acadoWorkspace.g[31]*acadoWorkspace.x[31] + acadoWorkspace.g[32]*acadoWorkspace.x[32] + acadoWorkspace.g[33]*acadoWorkspace.x[33] + acadoWorkspace.g[34]*acadoWorkspace.x[34] + acadoWorkspace.g[35]*acadoWorkspace.x[35] + acadoWorkspace.g[36]*acadoWorkspace.x[36] + acadoWorkspace.g[37]*acadoWorkspace.x[37] + acadoWorkspace.g[38]*acadoWorkspace.x[38] + acadoWorkspace.g[39]*acadoWorkspace.x[39] + acadoWorkspace.g[40]*acadoWorkspace.x[40] + acadoWorkspace.g[41]*acadoWorkspace.x[41] + acadoWorkspace.g[42]*acadoWorkspace.x[42] + acadoWorkspace.g[43]*acadoWorkspace.x[43] + acadoWorkspace.g[44]*acadoWorkspace.x[44] + acadoWorkspace.g[45]*acadoWorkspace.x[45] + acadoWorkspace.g[46]*acadoWorkspace.x[46] + acadoWorkspace.g[47]*acadoWorkspace.x[47] + acadoWorkspace.g[48]*acadoWorkspace.x[48] + acadoWorkspace.g[49]*acadoWorkspace.x[49] + acadoWorkspace.g[50]*acadoWorkspace.x[50] + acadoWorkspace.g[51]*acadoWorkspace.x[51] + acadoWorkspace.g[52]*acadoWorkspace.x[52] + acadoWorkspace.g[53]*acadoWorkspace.x[53]; +kkt = fabs( kkt ); +for (index = 0; index < 54; ++index) +{ +prd = acadoWorkspace.y[index]; +if (prd > 1e-12) +kkt += fabs(acadoWorkspace.lb[index] * prd); +else if (prd < -1e-12) +kkt += fabs(acadoWorkspace.ub[index] * prd); +} +for (index = 0; index < 100; ++index) +{ +prd = acadoWorkspace.y[index + 54]; +if (prd > 1e-12) +kkt += fabs(acadoWorkspace.lbA[index] * prd); +else if (prd < -1e-12) +kkt += fabs(acadoWorkspace.ubA[index] * prd); +} +return kkt; +} + +real_t acado_getObjective( ) +{ +real_t objVal; + +int lRun1; +/** Row vector of size: 5 */ +real_t tmpDy[ 5 ]; + +/** Row vector of size: 4 */ +real_t tmpDyN[ 4 ]; + +for (lRun1 = 0; lRun1 < 50; ++lRun1) +{ +acadoWorkspace.objValueIn[0] = acadoVariables.x[lRun1 * 4]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[lRun1 * 4 + 1]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[lRun1 * 4 + 2]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[lRun1 * 4 + 3]; +acadoWorkspace.objValueIn[4] = acadoVariables.u[lRun1]; +acadoWorkspace.objValueIn[5] = acadoVariables.od[lRun1 * 18]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[lRun1 * 18 + 1]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[lRun1 * 18 + 2]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[lRun1 * 18 + 3]; +acadoWorkspace.objValueIn[9] = acadoVariables.od[lRun1 * 18 + 4]; +acadoWorkspace.objValueIn[10] = acadoVariables.od[lRun1 * 18 + 5]; +acadoWorkspace.objValueIn[11] = acadoVariables.od[lRun1 * 18 + 6]; +acadoWorkspace.objValueIn[12] = acadoVariables.od[lRun1 * 18 + 7]; +acadoWorkspace.objValueIn[13] = acadoVariables.od[lRun1 * 18 + 8]; +acadoWorkspace.objValueIn[14] = acadoVariables.od[lRun1 * 18 + 9]; +acadoWorkspace.objValueIn[15] = acadoVariables.od[lRun1 * 18 + 10]; +acadoWorkspace.objValueIn[16] = acadoVariables.od[lRun1 * 18 + 11]; +acadoWorkspace.objValueIn[17] = acadoVariables.od[lRun1 * 18 + 12]; +acadoWorkspace.objValueIn[18] = acadoVariables.od[lRun1 * 18 + 13]; +acadoWorkspace.objValueIn[19] = acadoVariables.od[lRun1 * 18 + 14]; +acadoWorkspace.objValueIn[20] = acadoVariables.od[lRun1 * 18 + 15]; +acadoWorkspace.objValueIn[21] = acadoVariables.od[lRun1 * 18 + 16]; +acadoWorkspace.objValueIn[22] = acadoVariables.od[lRun1 * 18 + 17]; + +acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); +acadoWorkspace.Dy[lRun1 * 5] = acadoWorkspace.objValueOut[0] - acadoVariables.y[lRun1 * 5]; +acadoWorkspace.Dy[lRun1 * 5 + 1] = acadoWorkspace.objValueOut[1] - acadoVariables.y[lRun1 * 5 + 1]; +acadoWorkspace.Dy[lRun1 * 5 + 2] = acadoWorkspace.objValueOut[2] - acadoVariables.y[lRun1 * 5 + 2]; +acadoWorkspace.Dy[lRun1 * 5 + 3] = acadoWorkspace.objValueOut[3] - acadoVariables.y[lRun1 * 5 + 3]; +acadoWorkspace.Dy[lRun1 * 5 + 4] = acadoWorkspace.objValueOut[4] - acadoVariables.y[lRun1 * 5 + 4]; +} +acadoWorkspace.objValueIn[0] = acadoVariables.x[200]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[201]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[202]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[203]; +acadoWorkspace.objValueIn[4] = acadoVariables.od[900]; +acadoWorkspace.objValueIn[5] = acadoVariables.od[901]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[902]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[903]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[904]; +acadoWorkspace.objValueIn[9] = acadoVariables.od[905]; +acadoWorkspace.objValueIn[10] = acadoVariables.od[906]; +acadoWorkspace.objValueIn[11] = acadoVariables.od[907]; +acadoWorkspace.objValueIn[12] = acadoVariables.od[908]; +acadoWorkspace.objValueIn[13] = acadoVariables.od[909]; +acadoWorkspace.objValueIn[14] = acadoVariables.od[910]; +acadoWorkspace.objValueIn[15] = acadoVariables.od[911]; +acadoWorkspace.objValueIn[16] = acadoVariables.od[912]; +acadoWorkspace.objValueIn[17] = acadoVariables.od[913]; +acadoWorkspace.objValueIn[18] = acadoVariables.od[914]; +acadoWorkspace.objValueIn[19] = acadoVariables.od[915]; +acadoWorkspace.objValueIn[20] = acadoVariables.od[916]; +acadoWorkspace.objValueIn[21] = acadoVariables.od[917]; +acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); +acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0] - acadoVariables.yN[0]; +acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1] - acadoVariables.yN[1]; +acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2] - acadoVariables.yN[2]; +acadoWorkspace.DyN[3] = acadoWorkspace.objValueOut[3] - acadoVariables.yN[3]; +objVal = 0.0000000000000000e+00; +for (lRun1 = 0; lRun1 < 50; ++lRun1) +{ +tmpDy[0] = + acadoWorkspace.Dy[lRun1 * 5]; +tmpDy[1] = + acadoWorkspace.Dy[lRun1 * 5 + 1]; +tmpDy[2] = + acadoWorkspace.Dy[lRun1 * 5 + 2]; +tmpDy[3] = + acadoWorkspace.Dy[lRun1 * 5 + 3]; +tmpDy[4] = + acadoWorkspace.Dy[lRun1 * 5 + 4]; +objVal += + acadoWorkspace.Dy[lRun1 * 5]*tmpDy[0] + acadoWorkspace.Dy[lRun1 * 5 + 1]*tmpDy[1] + acadoWorkspace.Dy[lRun1 * 5 + 2]*tmpDy[2] + acadoWorkspace.Dy[lRun1 * 5 + 3]*tmpDy[3] + acadoWorkspace.Dy[lRun1 * 5 + 4]*tmpDy[4]; +} + +tmpDyN[0] = + acadoWorkspace.DyN[0]; +tmpDyN[1] = + acadoWorkspace.DyN[1]; +tmpDyN[2] = + acadoWorkspace.DyN[2]; +tmpDyN[3] = + acadoWorkspace.DyN[3]; +objVal += + acadoWorkspace.DyN[0]*tmpDyN[0] + acadoWorkspace.DyN[1]*tmpDyN[1] + acadoWorkspace.DyN[2]*tmpDyN[2] + acadoWorkspace.DyN[3]*tmpDyN[3]; + +objVal *= 0.5; +return objVal; +} + diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index ec9893293b2b88..5b65fef7deeb09 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -1,205 +1,117 @@ import numpy as np from common.numpy_fast import clip, interp from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.pid import PIController + +STOPPING_EGO_SPEED = 0.5 +STOPPING_TARGET_SPEED = 0.3 +STARTING_TARGET_SPEED = 0.5 +BRAKE_THRESHOLD_TO_PID = 0.2 + class LongCtrlState: #*** this function handles the long control state transitions # long_control_state labels: - off = 0 # Off - pid = 1 # moving and tracking targets, with PID control running + off = 0 # Off + pid = 1 # moving and tracking targets, with PID control running stopping = 2 # stopping and changing controls to almost open loop as PID does not fit well at such a low speed starting = 3 # starting and releasing brakes in open loop before giving back to PID -def long_control_state_trans(enabled, long_control_state, v_ego, v_target, v_pid, output_gb): - stopping_speed = 0.5 - stopping_target_speed = 0.3 - starting_target_speed = 0.5 - brake_threshold_to_pid = 0.2 +def long_control_state_trans(active, long_control_state, v_ego, v_target, v_pid, + output_gb, brake_pressed): - stopping_condition = ((v_ego < stopping_speed) and (v_pid < stopping_target_speed) and (v_target < stopping_target_speed)) + stopping_condition = (v_ego < STOPPING_EGO_SPEED) and \ + (((v_pid < STOPPING_TARGET_SPEED) and (v_target < STOPPING_TARGET_SPEED)) or + (brake_pressed)) - if not enabled: + if not active: long_control_state = LongCtrlState.off + else: if long_control_state == LongCtrlState.off: - if enabled: + if active: long_control_state = LongCtrlState.pid + elif long_control_state == LongCtrlState.pid: if stopping_condition: long_control_state = LongCtrlState.stopping + elif long_control_state == LongCtrlState.stopping: - if (v_target > starting_target_speed): + if (v_target > STARTING_TARGET_SPEED): long_control_state = LongCtrlState.starting + elif long_control_state == LongCtrlState.starting: if stopping_condition: long_control_state = LongCtrlState.stopping - elif output_gb >= -brake_threshold_to_pid: + elif output_gb >= -BRAKE_THRESHOLD_TO_PID: long_control_state = LongCtrlState.pid return long_control_state -def get_compute_gb(): - # see debug/dump_accel_from_fiber.py - w0 = np.array([[ 1.22056961, -0.39625418, 0.67952657], - [ 1.03691769, 0.78210306, -0.41343188]]) - b0 = np.array([ 0.01536703, -0.14335321, -0.26932889]) - w2 = np.array([[-0.59124422, 0.42899439, 0.38660881], - [ 0.79973811, 0.13178682, 0.08550351], - [-0.15651935, -0.44360259, 0.76910877]]) - b2 = np.array([ 0.15624429, 0.02294923, -0.0341086 ]) - w4 = np.array([[-0.31521443], - [-0.38626176], - [ 0.52667892]]) - b4 = np.array([-0.02922216]) - - def compute_output(dat, w0, b0, w2, b2, w4, b4): - m0 = np.dot(dat, w0) + b0 - m0 = leakyrelu(m0, 0.1) - m2 = np.dot(m0, w2) + b2 - m2 = leakyrelu(m2, 0.1) - m4 = np.dot(m2, w4) + b4 - return m4 - - def leakyrelu(x, alpha): - return np.maximum(x, alpha * x) - - def _compute_gb(dat): - #linearly extrap below v1 using v1 and v2 data - v1 = 5. - v2 = 10. - vx = dat[1] - if vx > 5.: - m4 = compute_output(dat, w0, b0, w2, b2, w4, b4) - else: - dat[1] = v1 - m4v1 = compute_output(dat, w0, b0, w2, b2, w4, b4) - dat[1] = v2 - m4v2 = compute_output(dat, w0, b0, w2, b2, w4, b4) - m4 = (vx - v1) * (m4v2 - m4v1) / (v2 - v1) + m4v1 - return m4 - return _compute_gb - -# takes in [desired_accel, current_speed] -> [-1.0, 1.0] where -1.0 is max brake and 1.0 is max gas -compute_gb = get_compute_gb() - _KP_BP = [0., 5., 35.] -_KP_V = [1.2, 0.8, 0.5] - -_kI_BP = [0., 35.] -_kI_V = [0.18, 0.12] - -def pid_long_control(v_ego, v_pid, Ui_accel_cmd, gas_max, brake_max, jerk_factor, gear, rate): - #*** This function compute the gb pedal positions in order to track the desired speed - # proportional and integral terms. More precision at low speed - Kp = interp(v_ego, _KP_BP, _KP_V) - Ki = interp(v_ego, _kI_BP, _kI_V) - - # scale Kp and Ki by jerk factor from drive_thread - Kp = (1. + jerk_factor)*Kp - Ki = (1. + jerk_factor)*Ki - - # this is ugly but can speed reports 0 when speed<0.3m/s and we can't have that jump - v_ego_min = 0.3 - v_ego = max(v_ego, v_ego_min) - - v_error = v_pid - v_ego - - Up_accel_cmd = v_error*Kp - Ui_accel_cmd_new = Ui_accel_cmd + v_error*Ki*1.0/rate - accel_cmd_new = Ui_accel_cmd_new + Up_accel_cmd - output_gb_new = compute_gb([accel_cmd_new, v_ego]) - - # Anti-wind up for integrator: only update integrator if we not against the throttle and brake limits - # do not wind up if we are changing gear and we are on the gas pedal - if (((v_error >= 0. and (output_gb_new < gas_max or Ui_accel_cmd < 0)) or - (v_error <= 0. and (output_gb_new > - brake_max or Ui_accel_cmd > 0))) and - not (v_error >= 0. and gear == 11 and output_gb_new > 0)): - #update integrator - Ui_accel_cmd = Ui_accel_cmd_new +_KP_V = [1.2, 0.8, 0.5] - accel_cmd = Ui_accel_cmd + Up_accel_cmd +_KI_BP = [0., 35.] +_KI_V = [0.18, 0.12] - # go from accel to pedals - output_gb = compute_gb([accel_cmd, v_ego]) - output_gb = output_gb[0] - - # useful to know if control is against the limit - long_control_sat = False - if output_gb > gas_max or output_gb < -brake_max: - long_control_sat = True - - output_gb = clip(output_gb, -brake_max, gas_max) - - return output_gb, Up_accel_cmd, Ui_accel_cmd, long_control_sat - - -stopping_brake_rate = 0.2 # brake_travel/s while trying to stop -starting_brake_rate = 0.6 # brake_travel/s while releasing on restart -starting_Ui = 0.5 # Since we don't have much info about acceleration at this point, be conservative +stopping_brake_rate = 0.2 # brake_travel/s while trying to stop +starting_brake_rate = 0.6 # brake_travel/s while releasing on restart +starting_Ui = 0.5 # Since we don't have much info about acceleration at this point, be conservative brake_stopping_target = 0.5 # apply at least this amount of brake to maintain the vehicle stationary _MAX_SPEED_ERROR_BP = [0., 30.] # speed breakpoints -_MAX_SPEED_ERROR_V = [1.5, .8] # max positive v_pid error VS actual speed; this avoids controls windup due to slow pedal resp +_MAX_SPEED_ERROR_V = [1.5, .8] # max positive v_pid error VS actual speed; this avoids controls windup due to slow pedal resp + class LongControl(object): - def __init__(self): - self.long_control_state = LongCtrlState.off # initialized to off - self.long_control_sat = False - self.Up_accel_cmd = 0. - self.last_output_gb = 0. - self.reset(0.) + def __init__(self, compute_gb): + self.long_control_state = LongCtrlState.off # initialized to off + self.pid = PIController((_KP_BP, _KP_V), + (_KI_BP, _KI_V), + rate=100.0, + sat_limit=0.8, + convert=compute_gb) + self.v_pid = 0.0 + self.last_output_gb = 0.0 def reset(self, v_pid): - self.Ui_accel_cmd = 0. + self.pid.reset() self.v_pid = v_pid - def update(self, enabled, v_ego, v_cruise, v_target_lead, a_target, jerk_factor, CP): - brake_max_bp = [0., 5., 20., 100.] # speeds - brake_max_v = [1.0, 1.0, 0.8, 0.8] # values - - # brake and gas limits - brake_max = interp(v_ego, brake_max_bp, brake_max_v) + def update(self, active, v_ego, brake_pressed, v_cruise, v_target_lead, a_target, + jerk_factor, CP): - # TODO: not every time - if CP.enableGas: - gas_max_bp = [0., 100.] # speeds - gas_max_v = [0.6, 0.6] # values - gas_max = interp(v_ego, gas_max_bp, gas_max_v) - else: - gas_max = 0 + # actuation limits + gas_max = interp(v_ego, CP.gasMaxBP, CP.gasMaxV) + brake_max = interp(v_ego, CP.brakeMaxBP, CP.brakeMaxV) - overshoot_allowance = 2.0 # overshoot allowed when changing accel sign + overshoot_allowance = 2.0 # overshoot allowed when changing accel sign output_gb = self.last_output_gb - rate = 100 - # limit max target speed based on cruise setting: - v_cruise_mph = round(v_cruise * CV.KPH_TO_MPH) # what's displayed in mph on the IC - v_target = min(v_target_lead, v_cruise_mph * CV.MPH_TO_MS) + # limit max target speed based on cruise setting + v_target = min(v_target_lead, v_cruise * CV.KPH_TO_MS) + rate = 100.0 + max_speed_delta_up = a_target[1] * 1.0 / rate + max_speed_delta_down = a_target[0] * 1.0 / rate - max_speed_delta_up = a_target[1]*1.0/rate - max_speed_delta_down = a_target[0]*1.0/rate - - # *** long control substate transitions - self.long_control_state = long_control_state_trans(enabled, self.long_control_state, v_ego, v_target, self.v_pid, output_gb) + self.long_control_state = long_control_state_trans(active, self.long_control_state, v_ego,\ + v_target, self.v_pid, output_gb, brake_pressed) # *** long control behavior based on state - # TODO: move this to drive_helpers - # disabled if self.long_control_state == LongCtrlState.off: - self.v_pid = v_ego # do nothing + self.v_pid = v_ego # do nothing output_gb = 0. - self.Ui_accel_cmd = 0. + self.pid.reset() + # tracking objects and driving elif self.long_control_state == LongCtrlState.pid: #reset v_pid close to v_ego if it was too far and new v_target is closer to v_ego - if ((self.v_pid > v_ego + overshoot_allowance) and - (v_target < self.v_pid)): + if ((self.v_pid > v_ego + overshoot_allowance) and (v_target < self.v_pid)): self.v_pid = max(v_target, v_ego + overshoot_allowance) - elif ((self.v_pid < v_ego - overshoot_allowance) and - (v_target > self.v_pid)): + elif ((self.v_pid < v_ego - overshoot_allowance) and (v_target > self.v_pid)): self.v_pid = min(v_target, v_ego - overshoot_allowance) # move v_pid no faster than allowed accel limits @@ -215,25 +127,31 @@ def update(self, enabled, v_ego, v_cruise, v_target_lead, a_target, jerk_factor, max_speed_error = interp(v_ego, _MAX_SPEED_ERROR_BP, _MAX_SPEED_ERROR_V) self.v_pid = min(self.v_pid, v_ego + max_speed_error) - # TODO: removed anti windup on gear change, does it matter? - output_gb, self.Up_accel_cmd, self.Ui_accel_cmd, self.long_control_sat = pid_long_control(v_ego, self.v_pid, \ - self.Ui_accel_cmd, gas_max, brake_max, jerk_factor, 0, rate) + self.pid.pos_limit = gas_max + self.pid.neg_limit = - brake_max + v_ego_pid = max(v_ego, 0.3) # Without this we get jumps, CAN bus reports 0 when speed < 0.3 + output_gb = self.pid.update(self.v_pid, v_ego_pid, speed=v_ego_pid, jerk_factor=jerk_factor) + # intention is to stop, switch to a different brake control until we stop elif self.long_control_state == LongCtrlState.stopping: + # TODO: use the standstill bit from CAN to detect movements, usually more accurate than looking at v_ego if v_ego > 0. or output_gb > -brake_stopping_target: - output_gb -= stopping_brake_rate/rate + output_gb -= stopping_brake_rate / rate output_gb = clip(output_gb, -brake_max, gas_max) + self.v_pid = v_ego - self.Ui_accel_cmd = 0. + self.pid.reset() + # intention is to move again, release brake fast before handling control to PID elif self.long_control_state == LongCtrlState.starting: if output_gb < -0.2: - output_gb += starting_brake_rate/rate + output_gb += starting_brake_rate / rate self.v_pid = v_ego - self.Ui_accel_cmd = starting_Ui + self.pid.reset() + self.pid.i = starting_Ui self.last_output_gb = output_gb final_gas = clip(output_gb, 0., gas_max) final_brake = -clip(output_gb, -brake_max, 0.) - return final_gas, final_brake + return final_gas, final_brake diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index d65367b995e533..68b4f22cfb3963 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -1,66 +1,9 @@ -import math -import numpy as np - from common.numpy_fast import interp -import selfdrive.messaging as messaging - - -def compute_path_pinv(): - deg = 3 - x = np.arange(50.0) - X = np.vstack(tuple(x**n for n in range(deg, -1, -1))).T - pinv = np.linalg.pinv(X) - return pinv - -def model_polyfit(points, path_pinv): - return np.dot(path_pinv, map(float, points)) - -# lane width http://safety.fhwa.dot.gov/geometric/pubs/mitigationstrategies/chapter3/3_lanewidth.cfm -_LANE_WIDTH_V = [3., 3.8] - -# break points of speed -_LANE_WIDTH_BP = [0., 31.] +from selfdrive.controls.lib.latcontrol_helpers import model_polyfit, calc_desired_path, compute_path_pinv -def calc_desired_path(l_poly, r_poly, p_poly, l_prob, r_prob, p_prob, speed): - #*** this function computes the poly for the center of the lane, averaging left and right polys - lane_width = interp(speed, _LANE_WIDTH_BP, _LANE_WIDTH_V) - - # lanes in US are ~3.6m wide - half_lane_poly = np.array([0., 0., 0., lane_width / 2.]) - if l_prob + r_prob > 0.01: - c_poly = ((l_poly - half_lane_poly) * l_prob + - (r_poly + half_lane_poly) * r_prob) / (l_prob + r_prob) - c_prob = math.sqrt((l_prob**2 + r_prob**2) / 2.) - else: - c_poly = np.zeros(4) - c_prob = 0. - - p_weight = 1. # predicted path weight relatively to the center of the lane - d_poly = list((c_poly*c_prob + p_poly*p_prob*p_weight ) / (c_prob + p_prob*p_weight)) - return d_poly, c_poly, c_prob - -class OptPathPlanner(object): - def __init__(self, model): - self.model = model - self.dead = True - self.d_poly = [0., 0., 0., 0.] - self.last_model = 0. - self._path_pinv = compute_path_pinv() - - def update(self, cur_time, v_ego, md): - if md is not None: - # simple compute of the center of the lane - pts = [(x+y)/2 for x,y in zip(md.model.leftLane.points, md.model.rightLane.points)] - self.d_poly = model_polyfit(pts, self._path_pinv) - - self.last_model = cur_time - self.dead = False - elif cur_time - self.last_model > 0.5: - self.dead = True class PathPlanner(object): def __init__(self): - self.dead = True self.d_poly = [0., 0., 0., 0.] self.c_poly = [0., 0., 0., 0.] self.c_prob = 0. @@ -68,24 +11,47 @@ def __init__(self): self.lead_dist, self.lead_prob, self.lead_var = 0, 0, 1 self._path_pinv = compute_path_pinv() - def update(self, cur_time, v_ego, md): + self.lane_width_estimate = 3.7 + self.lane_width_certainty = 1.0 + self.lane_width = 3.7 + + def update(self, v_ego, md): if md is not None: - p_poly = model_polyfit(md.model.path.points, self._path_pinv) # predicted path - l_poly = model_polyfit(md.model.leftLane.points, self._path_pinv) # left line + p_poly = model_polyfit(md.model.path.points, self._path_pinv) # predicted path + l_poly = model_polyfit(md.model.leftLane.points, self._path_pinv) # left line r_poly = model_polyfit(md.model.rightLane.points, self._path_pinv) # right line - p_prob = 1. # model does not tell this probability yet, so set to 1 for now - l_prob = md.model.leftLane.prob # left line prob + p_prob = 1. # model does not tell this probability yet, so set to 1 for now + l_prob = md.model.leftLane.prob # left line prob r_prob = md.model.rightLane.prob # right line prob + # Find current lanewidth + lr_prob = l_prob * r_prob + self.lane_width_certainty += 0.05 * (lr_prob - self.lane_width_certainty) + current_lane_width = abs(l_poly[3] - r_poly[3]) + self.lane_width_estimate += 0.005 * (current_lane_width - self.lane_width_estimate) + speed_lane_width = interp(v_ego, [0., 31.], [3., 3.8]) + self.lane_width = self.lane_width_certainty * self.lane_width_estimate + \ + (1 - self.lane_width_certainty) * speed_lane_width + + lane_width_diff = abs(self.lane_width - current_lane_width) + lane_r_prob = interp(lane_width_diff, [0.3, 1.0], [1.0, 0.0]) + + r_prob *= lane_r_prob + self.lead_dist = md.model.lead.dist self.lead_prob = md.model.lead.prob self.lead_var = md.model.lead.std**2 # compute target path - self.d_poly, self.c_poly, self.c_prob = calc_desired_path(l_poly, r_poly, p_poly, l_prob, r_prob, p_prob, v_ego) + self.d_poly, self.c_poly, self.c_prob = calc_desired_path( + l_poly, r_poly, p_poly, l_prob, r_prob, p_prob, v_ego, self.lane_width) + + self.r_poly = r_poly + self.r_prob = r_prob + + self.l_poly = l_poly + self.l_prob = l_prob - self.last_model = cur_time - self.dead = False - elif cur_time - self.last_model > 0.5: - self.dead = True + self.p_poly = p_poly + self.p_prob = p_prob diff --git a/selfdrive/controls/lib/pid.py b/selfdrive/controls/lib/pid.py new file mode 100644 index 00000000000000..faf5355db5c2e9 --- /dev/null +++ b/selfdrive/controls/lib/pid.py @@ -0,0 +1,91 @@ +import numpy as np +from common.numpy_fast import clip, interp +import numbers + +class PIController(object): + def __init__(self, k_p, k_i, pos_limit=None, neg_limit=None, rate=100, sat_limit=0.8, convert=None): + self._k_p = k_p + self._k_i = k_i + + self.pos_limit = pos_limit + self.neg_limit = neg_limit + + self.sat_count_rate = 1.0 / rate + self.i_unwind_rate = 0.3 / rate + self.i_rate = 1.0 / rate + self.sat_limit = sat_limit + self.jerk_factor = 0.0 + self.convert = convert + + self.reset() + + @property + def k_p(self): + if isinstance(self._k_p, numbers.Number): + kp = self._k_p + else: + kp = interp(self.speed, self._k_p[0], self._k_p[1]) + + return (1.0 + self.jerk_factor) * kp + + @property + def k_i(self): + if isinstance(self._k_i, numbers.Number): + ki = self._k_i + else: + ki = interp(self.speed, self._k_i[0], self._k_i[1]) + + return (1.0 + self.jerk_factor) * ki + + def _check_saturation(self, control, override, error): + saturated = (control < self.neg_limit) or (control > self.pos_limit) + + if saturated and not override and abs(error) > 0.1: + self.sat_count += self.sat_count_rate + else: + self.sat_count -= self.sat_count_rate + + self.sat_count = clip(self.sat_count, 0.0, 1.0) + + return self.sat_count > self.sat_limit + + def reset(self): + self.p = 0.0 + self.i = 0.0 + self.sat_count = 0.0 + self.saturated = False + self.control = 0 + + def update(self, setpoint, measurement, speed=0.0, check_saturation=True, jerk_factor=0.0, override=False): + self.speed = speed + self.jerk_factor = jerk_factor + + error = float(setpoint - measurement) + self.p = error * self.k_p + + if override: + self.i -= self.i_unwind_rate * float(np.sign(self.i)) + else: + i = self.i + error * self.k_i * self.i_rate + control = self.p + i + + if self.convert is not None: + control = self.convert(control, speed=self.speed) + + # Update when changing i will move the control away from the limits + # or when i will move towards the sign of the error + if (error >= 0 and (control <= self.pos_limit or i < 0.0)) or \ + (error <= 0 and (control >= self.neg_limit or i > 0.0)): + self.i = i + + control = self.p + self.i + if self.convert is not None: + control = self.convert(control, speed=self.speed) + + if check_saturation: + self.saturated = self._check_saturation(control, override, error) + else: + self.saturated = False + + self.control = clip(control, self.neg_limit, self.pos_limit) + return self.control diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index e9e7adb6718e8d..9cc657c138499b 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -1,80 +1,93 @@ #!/usr/bin/env python -import os import zmq -import numpy as np +from common.realtime import sec_since_boot import selfdrive.messaging as messaging - from selfdrive.services import service_list -from common.realtime import sec_since_boot -from common.params import Params - -from selfdrive.swaglog import cloudlog -from cereal import car - -from selfdrive.controls.lib.pathplanner import OptPathPlanner +from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET from selfdrive.controls.lib.pathplanner import PathPlanner from selfdrive.controls.lib.adaptivecruise import AdaptiveCruise from selfdrive.controls.lib.fcw import ForwardCollisionWarning _DT = 0.01 # 100Hz + class Planner(object): def __init__(self, CP): context = zmq.Context() self.CP = CP self.live20 = messaging.sub_sock(context, service_list['live20'].port) self.model = messaging.sub_sock(context, service_list['model'].port) - + self.plan = messaging.pub_sock(context, service_list['plan'].port) - + self.last_md_ts = 0 self.last_l20_ts = 0 + self.last_model = 0. + self.last_l20 = 0. + self.model_dead = True + self.radar_dead = True + self.radar_errors = [] - if os.getenv("OPT") is not None: - self.PP = OptPathPlanner(self.model) - else: - self.PP = PathPlanner() + self.PP = PathPlanner() self.AC = AdaptiveCruise() self.FCW = ForwardCollisionWarning(_DT) # this runs whenever we get a packet that can change the plan - def update(self, CS, LoC): cur_time = sec_since_boot() md = messaging.recv_sock(self.model) if md is not None: self.last_md_ts = md.logMonoTime + self.last_model = cur_time + self.model_dead = False + if cur_time - self.last_model > 0.5: + self.model_dead = True + l20 = messaging.recv_sock(self.live20) if l20 is not None: self.last_l20_ts = l20.logMonoTime + self.last_l20 = cur_time + self.radar_dead = False + self.radar_errors = list(l20.live20.radarErrors) + if cur_time - self.last_l20 > 0.5: + self.radar_dead = True - self.PP.update(cur_time, CS.vEgo, md) + self.PP.update(CS.vEgo, md) # LoC.v_pid -> CS.vEgo # TODO: is this change okay? - self.AC.update(cur_time, CS.vEgo, CS.steeringAngle, LoC.v_pid, self.CP, l20) + self.AC.update(CS.vEgo, CS.steeringAngle, LoC.v_pid, self.CP, l20) # **** send the plan **** plan_send = messaging.new_message() plan_send.init('plan') + events = [] + if self.model_dead: + events.append(create_event('modelCommIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if self.radar_dead or 'commIssue' in self.radar_errors: + events.append(create_event('radarCommIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if 'fault' in self.radar_errors: + events.append(create_event('radarFault', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + + plan_send.plan.events = events + plan_send.plan.mdMonoTime = self.last_md_ts plan_send.plan.l20MonoTime = self.last_l20_ts # lateral plan - plan_send.plan.lateralValid = not self.PP.dead - if plan_send.plan.lateralValid: - plan_send.plan.dPoly = map(float, self.PP.d_poly) + plan_send.plan.lateralValid = not self.model_dead + plan_send.plan.dPoly = map(float, self.PP.d_poly) + plan_send.plan.laneWidth = float(self.PP.lane_width) # longitudal plan - plan_send.plan.longitudinalValid = not self.AC.dead - if plan_send.plan.longitudinalValid: - plan_send.plan.vTarget = float(self.AC.v_target_lead) - plan_send.plan.aTargetMin = float(self.AC.a_target[0]) - plan_send.plan.aTargetMax = float(self.AC.a_target[1]) - plan_send.plan.jerkFactor = float(self.AC.jerk_factor) - plan_send.plan.hasLead = self.AC.has_lead + plan_send.plan.longitudinalValid = not self.radar_dead + plan_send.plan.vTarget = float(self.AC.v_target_lead) + plan_send.plan.aTargetMin = float(self.AC.a_target[0]) + plan_send.plan.aTargetMax = float(self.AC.a_target[1]) + plan_send.plan.jerkFactor = float(self.AC.jerk_factor) + plan_send.plan.hasLead = self.AC.has_lead # compute risk of collision events: fcw self.FCW.process(CS, self.AC) diff --git a/selfdrive/controls/lib/vehicle_model.py b/selfdrive/controls/lib/vehicle_model.py index 3c676fbeab98ed..91e26e4ff4bde1 100755 --- a/selfdrive/controls/lib/vehicle_model.py +++ b/selfdrive/controls/lib/vehicle_model.py @@ -1,33 +1,32 @@ #!/usr/bin/env python import numpy as np from numpy.linalg import inv -from selfdrive.car.honda.interface import CarInterface - -## dynamic bycicle model from "The Science of Vehicle Dynamics (2014), M. Guiggiani"## +# dynamic bycicle model from "The Science of Vehicle Dynamics (2014), M. Guiggiani"## # Xdot = A*X + B*U # where X = [v, r], with v and r lateral speed and rotational speed, respectively # and U is the steering angle (controller input) -# +# # A depends on longitudinal speed, u, and vehicle parameters CP + def create_dyn_state_matrices(u, CP): - A = np.zeros((2,2)) - B = np.zeros((2,1)) - A[0,0] = - (CP.cF + CP.cR)/(CP.m*u) - A[0,1] = - (CP.cF*CP.aF - CP.cR*CP.aR) / (CP.m*u) - u - A[1,0] = - (CP.cF*CP.aF - CP.cR*CP.aR) / (CP.j*u) - A[1,1] = - (CP.cF*CP.aF**2 + CP.cR*CP.aR**2) / (CP.j*u) - B[0,0] = (CP.cF + CP.chi*CP.cR) / CP.m / CP.sR - B[1,0] = (CP.cF*CP.aF - CP.chi*CP.cR*CP.aR) / CP.j / CP.sR + A = np.zeros((2, 2)) + B = np.zeros((2, 1)) + A[0, 0] = - (CP.cF + CP.cR) / (CP.m * u) + A[0, 1] = - (CP.cF * CP.aF - CP.cR * CP.aR) / (CP.m * u) - u + A[1, 0] = - (CP.cF * CP.aF - CP.cR * CP.aR) / (CP.j * u) + A[1, 1] = - (CP.cF * CP.aF**2 + CP.cR * CP.aR**2) / (CP.j * u) + B[0, 0] = (CP.cF + CP.chi * CP.cR) / CP.m / CP.sR + B[1, 0] = (CP.cF * CP.aF - CP.chi * CP.cR * CP.aR) / CP.j / CP.sR return A, B def kin_ss_sol(sa, u, CP): # kinematic solution, useful when speed ~ 0 - K = np.zeros((2,1)) - K[0,0] = CP.aR / CP.sR / CP.l * u - K[1,0] = 1. / CP.sR / CP.l * u + K = np.zeros((2, 1)) + K[0, 0] = CP.aR / CP.sR / CP.l * u + K[1, 0] = 1. / CP.sR / CP.l * u return K * sa @@ -36,13 +35,15 @@ def dyn_ss_sol(sa, u, CP): A, B = create_dyn_state_matrices(u, CP) return - np.matmul(inv(A), B) * sa + def calc_slip_factor(CP): # the slip factor is a measure of how the curvature changes with speed # it's positive for Oversteering vehicle, negative (usual case) otherwise return CP.m * (CP.cF * CP.aF - CP.cR * CP.aR) / (CP.l**2 * CP.cF * CP.cR) + class VehicleModel(object): - def __init__(self, CP, init_state=np.asarray([[0.],[0.]])): + def __init__(self, CP, init_state=np.asarray([[0.], [0.]])): self.dt = 0.1 lookahead = 2. # s self.steps = int(lookahead / self.dt) @@ -54,7 +55,7 @@ def update_state(self, state): self.state = state def steady_state_sol(self, sa, u): - # if the speed is too small we can't use the dynamic model + # if the speed is too small we can't use the dynamic model # (tire slip is undefined), we then use the kinematic model if u > 0.1: return dyn_ss_sol(sa, u, self.CP) @@ -63,13 +64,14 @@ def steady_state_sol(self, sa, u): def calc_curvature(self, sa, u): # this formula can be derived from state equations in steady state conditions + return self.curvature_factor(u) * sa / self.CP.sR + + def curvature_factor(self, u): sf = calc_slip_factor(self.CP) - return (1. - self.CP.chi)/(1. - sf * u**2) * sa / self.CP.sR / self.CP.l + return (1. - self.CP.chi)/(1. - sf * u**2) / self.CP.l def get_steer_from_curvature(self, curv, u): - # this function is the exact inverse of calc_curvature, returning steer angle given curvature - sf = calc_slip_factor(self.CP) - return self.CP.l * self.CP.sR * (1. - sf * u**2) / (1. - self.CP.chi) * curv + return curv * self.CP.sR * 1.0 / self.curvature_factor(u) def state_prediction(self, sa, u): # U is the matrix of the controls @@ -79,9 +81,10 @@ def state_prediction(self, sa, u): if __name__ == '__main__': + from selfdrive.car.toyota.interface import CarInterface # load car params - CP = CarInterface.get_params("HONDA CIVIC 2016 TOURING", {}) + CP = CarInterface.get_params("TOYOTA PRIUS 2017", {}) print CP VM = VehicleModel(CP) print VM.steady_state_sol(.1, 0.15) - + print calc_slip_factor(CP) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 00ee9182df1710..d966ba59f26f60 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -7,7 +7,7 @@ from fastcluster import linkage_vector import selfdrive.messaging as messaging from selfdrive.services import service_list -from selfdrive.controls.lib.latcontrol import calc_lookahead_offset +from selfdrive.controls.lib.latcontrol_helpers import calc_lookahead_offset from selfdrive.controls.lib.pathplanner import PathPlanner from selfdrive.controls.lib.radar_helpers import Track, Cluster, fcluster, RDR_TO_LDR from selfdrive.controls.lib.vehicle_model import VehicleModel @@ -84,7 +84,7 @@ def radard_thread(gctx=None): tracks = defaultdict(dict) - # Kalman filter stuff: + # Kalman filter stuff: ekfv = EKFV1D() speedSensorV = SimpleSensor(XV, 1, 2) @@ -121,7 +121,7 @@ def radard_thread(gctx=None): last_md_ts = md.logMonoTime # *** get path prediction from the model *** - PP.update(sec_since_boot(), v_ego, md) + PP.update(v_ego, md) # run kalman filter only if prob is high enough if PP.lead_prob > 0.7: @@ -156,7 +156,7 @@ def radard_thread(gctx=None): continue rpt = ar_pts[ids] - # align v_ego by a fixed time to align it with the radar measurement + # align v_ego by a fixed time to align it with the radar measurement cur_time = float(rk.frame)/rate v_ego_t_aligned = np.interp(cur_time - rdr_delay, v_ego_array[1], v_ego_array[0]) d_path = np.sqrt(np.amin((path_x - rpt[0]) ** 2 + (path_y - rpt[1]) ** 2)) @@ -224,6 +224,7 @@ def radard_thread(gctx=None): dat.init('live20') dat.live20.mdMonoTime = last_md_ts dat.live20.canMonoTimes = list(rr.canMonoTimes) + dat.live20.radarErrors = list(rr.errors) dat.live20.l100MonoTime = last_l100_ts if lead_len > 0: lead_clusters[0].toLive20(dat.live20.leadOne) diff --git a/selfdrive/debug/can_printer.py b/selfdrive/debug/can_printer.py index aeab94ed8eeab4..115b54ea60f4ea 100755 --- a/selfdrive/debug/can_printer.py +++ b/selfdrive/debug/can_printer.py @@ -1,5 +1,6 @@ #!/usr/bin/env python import os +import sys import struct from collections import defaultdict from common.realtime import sec_since_boot @@ -8,14 +9,14 @@ from selfdrive.services import service_list -def can_printer(): +def can_printer(bus=0, max_msg=0x10000, addr="127.0.0.1"): context = zmq.Context() - logcan = messaging.sub_sock(context, service_list['can'].port) + logcan = messaging.sub_sock(context, service_list['can'].port, addr=addr) start = sec_since_boot() lp = sec_since_boot() msgs = defaultdict(list) - canbus = int(os.getenv("CAN", 0)) + canbus = int(os.getenv("CAN", bus)) while 1: can_recv = messaging.drain_sock(logcan, wait_for_one=True) for x in can_recv: @@ -27,10 +28,18 @@ def can_printer(): dd = chr(27) + "[2J" dd += "%5.2f\n" % (sec_since_boot() - start) for k,v in sorted(zip(msgs.keys(), map(lambda x: x[-1].encode("hex"), msgs.values()))): - dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v) + if k < max_msg: + dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v) print dd lp = sec_since_boot() if __name__ == "__main__": - can_printer() - + if len(sys.argv) > 3: + can_printer(int(sys.argv[1]), int(sys.argv[2]), sys.argv[3]) + elif len(sys.argv) > 2: + can_printer(int(sys.argv[1]), int(sys.argv[2])) + elif len(sys.argv) > 1: + can_printer(int(sys.argv[1])) + else: + can_printer() + diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index 2387d299fd623a..2d312408355410 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -27,5 +27,5 @@ if args.raw: hexdump(sock.recv()) else: - print messaging.recv_sock(sock) + print messaging.recv_one(sock) diff --git a/selfdrive/debug/getframes/getframes.py b/selfdrive/debug/getframes/getframes.py index 5c63b8986d01b5..498716faf1dbee 100755 --- a/selfdrive/debug/getframes/getframes.py +++ b/selfdrive/debug/getframes/getframes.py @@ -42,26 +42,26 @@ } buf_info; } VisionStreamBufs; -typedef struct VisionBuf { +typedef struct VIPCBuf { int fd; size_t len; void* addr; -} VisionBuf; +} VIPCBuf; -typedef struct VisionBufExtra { +typedef struct VIPCBufExtra { uint32_t frame_id; // only for yuv -} VisionBufExtra; +} VIPCBufExtra; typedef struct VisionStream { int ipc_fd; int last_idx; int num_bufs; VisionStreamBufs bufs_info; - VisionBuf *bufs; + VIPCBuf *bufs; } VisionStream; int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info); -VisionBuf* visionstream_get(VisionStream *s, VisionBufExtra *out_extra); +VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra); void visionstream_destroy(VisionStream *s); """ diff --git a/selfdrive/debug/test_carcontroller.py b/selfdrive/debug/test_carcontroller.py index 4d9dcbda86abbc..d672cfb3d3c371 100755 --- a/selfdrive/debug/test_carcontroller.py +++ b/selfdrive/debug/test_carcontroller.py @@ -28,6 +28,7 @@ sendcan = messaging.pub_sock(context, service_list['sendcan'].port) CI, CP = get_car(logcan, sendcan) + CC = car.CarControl.new_message() rk = Ratekeeper(100) @@ -56,11 +57,11 @@ print axis_values, button_values # **** handle car **** - CS = CI.update() + CS = CI.update(CC) #print CS - CC = car.CarControl.new_message() + CC.enabled = True CC.gas = float(np.clip(-axis_values[1], 0, 1.0)) diff --git a/selfdrive/debug/test_carstate.py b/selfdrive/debug/test_carstate.py index f88c521d1f6670..98d2f7fc154427 100755 --- a/selfdrive/debug/test_carstate.py +++ b/selfdrive/debug/test_carstate.py @@ -1,6 +1,7 @@ #!/usr/bin/env python import os import zmq +from cereal import car import selfdrive.messaging as messaging from selfdrive.services import service_list @@ -36,8 +37,9 @@ def test_loop(): "False"] while 1: + CC = car.CarControl.new_message() # read CAN - CS = CI.update() + CS = CI.update(CC) while eval(states[state]) == True: state += 1 diff --git a/selfdrive/logcatd/Makefile b/selfdrive/logcatd/Makefile index 0d3423647aa0b9..83684abe5b9837 100644 --- a/selfdrive/logcatd/Makefile +++ b/selfdrive/logcatd/Makefile @@ -2,6 +2,7 @@ CC = clang CXX = clang++ PHONELIBS = ../../phonelibs +BASEDIR = ../.. WARN_FLAGS = -Werror=implicit-function-declaration \ -Werror=incompatible-pointer-types \ diff --git a/selfdrive/loggerd/config.py b/selfdrive/loggerd/config.py index 0759ae2663a55a..9d1c3120fbaec5 100644 --- a/selfdrive/loggerd/config.py +++ b/selfdrive/loggerd/config.py @@ -1,4 +1,9 @@ import os -ROOT = '/data/media/0/realdata/' +if os.environ.get('LOGGERD_ROOT', False): + ROOT = os.environ['LOGGERD_ROOT'] + print("Custom loggerd root: ", ROOT) +else: + ROOT = '/data/media/0/realdata/' + SEGMENT_LENGTH = 60 diff --git a/selfdrive/loggerd/loggerd b/selfdrive/loggerd/loggerd index c3bf23ddb90a95a2f0d0767c2c0c8fc1a86818fb..579b4062846224de255278c29e9ebe5b949dedf9 100755 GIT binary patch delta 403134 zcmZ_X4VYV1wLktHI)yM4Nue+)6bVBa0u)JMfLPigg#rNzhFUPd00D{wtQfFBz{-hQ zF<{l;DNe*H0Sg2y7=#N!D}-y+02PC``p@N7javN&95rIqTLBH?)8IDQczt6qRZ}WiRrL?7wwIz%A8#v~Tu}9KM4YA2)o7 z+T372@4LqLY5UMU4x7Dj52Ze!cjhJ9EtRp)-(zTIT z8eQ@x{d=v3nD$})`zias_xOtMbo-VW#~=4$qwE3t-_PlCXX@XF^zUtY`(9nQu77vy z-(~jeGftd+gVx{ct%5G${9J4wIPige&(bM*1sRqdZ>PE z=n{+dqw{kKKb~*DG%$4BDSB&A|0eYBI$e5=eoX07-_XC`*T2{4?WT6;CvDH1d4%s4 z`{U#TdiI3^+i|jwoJmS!E z^}kkVy;}eNO#g1zzaP~0QT=$iy>QQ=1JBc2^Yzw;^rNjGH|ch+wJ+au$QQM5+4B@% z(tcvkp}Du}==*f!M*aALF6I0z)&D-h{`sEA`YyEh-s=$G`|Kn4I%4h$t#9iRpVKAw z(2ra7@1gqlBlcB$4f(FHZ{O>bBR{IkT(5tfpXYS!N&2VSPupesH>H0^?Vs*-nD1u$ zuX`PK(kHp>kbb;Jmp_BI-=!aaz;*Z5{$BPmZKv7i_zyWUtK|VM;XK@@f0yf$H|yUk zx%5r;-TpIXUZA%Y*{}N#nR^cV`}N~W{p-_Z57EDtJ#+69_g&`*mpIctbMMn;o~*Y{ zwC~>g4BtuikMw$` zU8CzB_Q4ryP!(R`LT*X=&kS{d>hRPS&K;!G{Ch_6O~=^}eYJ zC6plVoNtKsE%3Dc%7J6Pn0?d1Lxb;POmDZ3IcUrp)|*b{8K=;#U%Q*qf zZ`#AbvB4wsrgJ@W=h`;}M+QfEbNod6{@{pp4sV7N)OC`NGR5A0gpU3h-leRx_He&{ zNy17d!_8t=FT3ha+%dn+Lz9~YsKrlx$<#pYA07YOAm^G z8dBYt>3EsdZ@GMC36*#9uk-VN?7I)OPdIpF?z?ohcFsfM1GFcTR7$-|52E7-hdCPg zi2eA%Bg3ch=HwzO+~LA2v^(cKaE1N$!DH4fTXsn`xKme)R81y$;8y$||_qDp;{ z%lj`SS;yr!u@_IHLzvHp@S^w?RDL6u-(w#-d*3|d=((?PnH@i*y8H~T?zEqpJ2dy_ zI_eCDwH#x`9*(F#Z3&0fe-k44_A6WAx0Q2E8| zr%OBUCzn~il7001tW;mykx(0$k5z-xrGhq z)1EBm7Cvk*J@oiR4|6p6TZ%?F`W$=iD)L$E+t|~4*pDANGWa{*-25*4jYDso`xm|G z>`CmKv?p|BmFn0xjRfO|(5agBn|MF|7>$%pdUr=k3sy@!1nQiZX*qAS@bL)`reCG<=xx?ba>m_^%ooBgT z53-LxZ@+ce$l!Clx&G_+!J(1aukq%VN!sU>ePQUZ!T(~7X6!pcW9Pihn>((jJ(|PE z=buMMkhr4%WF4#BnS@)GQh6EZf3basAHUC893A-Q4Exl>j~u+1x7R*m-*EVdbscXO zPNL&*mMPB9o$QOZk=NJ@?Bk!O&YVS)^Ybu!Hbw5|^3StRUQX?-q~dB%eGE>ny6xcE zc4#;<{82X%1yy~wi~%b68rP3qVc$G_vGohy3_L*HEa&e3&c1mWb+d}Q89bB*n1TT| zU%PY8HvAWr-_GSvVh_KId>#8)Zae$TP@R%}?hzw{NiH|*H})NRbB*3~23O>A`|%?# zUidOcD|(UO`~>)9{G5IFkEr!6?DyNgLxvXpnWM`msg^7TeD9`XD8iHPh<4`~0z2$a z&L3HHDsM(F?Y{ym*c1Cwr%gVj6npA&``7btv~JoaRl9a)st5T>$P(fpce$eM>kgc4xAgP&n_NG?hT3&jlFpCsFgn`t z7wv;bZnXC2%>|qKyIH{A=I%F9ZFLrV;S?&roc$8^ZI4oS8`-aC&)(0w!2|6^y*tjh z-Rr2MeJy+8QD^(coXjwo)8*Yv_N0CPQ6me#%+*u-QFn6EAJy&*lmgG;D0g?C{pSOR zh7S(WG47~SrvrTK$Fc{$WginBnY)xXD^E}{xg__v&p(%Nw6U1Fmes-GZtkjtQ^VIw za|@`1Bvy-kV1<3c(IYE1@aBResn||F1!eYfi(S#r^X#h+Bwx$rx3TBnwjV!wWYN!g zv+_II`vf24o9vxgR6V8W=WpygPPGS*8S_oLhmkraV(oo6ovqf()X+|@aNRViw0nREXN}Y_j8Nx;0m`pyF8fU z=GOh(zVz4;>ki&*pGCb&>o)tSO^wUEDzh*CDV3M2@gh4uOTNLr^1S||{XMxJ!vhq^ z`DiyEwC|li;_&awxO8(FxRH>*FU);hd57qXASTKSLm;fD?FlkQz&`%}jqIs6eWJ$W&; zvWoZVPWDwN+OHfpqVIGU28ZU}$GCu>l2Tmwznv^R_i>J$rS-h{{L!@W0Hy?(P|G?=mc(WS@T?xg0``+*0-brNDMRBMq()IgUDzh2n46w{E2J z^31-Qy>$k;B)bFW)45v@SMdn;d9OO{TfLWAXlWugjO7aU2ey;V7_QQ3p(7kk- zgX}{`(%B2&ZohHD$l$TOIqwyF@WhdYi+FSMv$U7;1aUTdt}@`ZQ{chTa7MFr1xJ^0 z0w3kR(%NV1yG(hVQ}*o+F2DT^>P3dm-R!$Maqt@sAFF!^;pE*_IL_DGvN!^gFa-M^K~b8By~kDg}VGdeQ(N8W6%u)nQ0|HYfj zPqp6~9XaBl5jxdrxLZGlJ^QZ#`^1x$3@*{z&bX>xZr^dz#l!b-co2nhK5VZzd2DbeZ~7m!?>~8L_#NKtJWaK{+;0`LFELPZ=9NlQ-A;X1XUR&Zp@T_Qf^(p;N{depqihV==#* z#v<>jDrt9a>@$30FMhne^n{_o7rBugr`RV%$FBMb7gm3vp)7;x9Vzyg{`0V3m=0k+ zukXsdZ|~Obob50##Pp{7^ABetp0ku|jlV>#$pko`z4Ai8U&cQAGEIy&xAwC0Y&Cct zM+dgpE8aUYcMWf@dW#y_$c39uo>*}gM>lMts9c&2>}#K)E_m^!9%Y}iH@Uo2@f>?{ zq5Tit=_|asK2FWbvU)FP^}6sE99^&vH6k~`zt`@pYEy92e2M!y$UnH&vKf5c`N|#Z zq=R$j98G6_OMu#Zh7a>__RVgB?&aqb*}E|+pXTzn*-H-|8a|h!*~=)plcQI&H!iTx zJ$1yooj1$Z(qT%Hzn6WSU#QG*^+(uO!eZuGDSr`lw~EVO!V3?4z3gjqoTZ<#|8(l? z!5`?l&d^Fk2d$=LA6daEMdU3wVfV(q2&%}ewOfj1Ko``b%K2Cw4H z@e}N~mfSe^7QK16o{dGGjUjGojiPPEBPp{c8+4vg&bYWLv1Zb)9l;$rc#D%j(v34zBD%C`?b@^@V$(k zQM!I}_{pTq9)7R=?bz6&7iE*ve~kP3F*~l?|G=Jj%syf1*syPbGXwWgjR*SIX$QEj zUyy#%{^HV+!SlUwY5(WaXIC7jqfX*}=99EnWTzofIelaJ+Lx7a=^@nHW>KF8%_m)Xahao6B$yt)0?_P5U%8*Xu}2rNP0 zmRe`q2QM2L-sdf!U%l+Lg=4%Kxr7c`X8uL&QBFhaxcXu4s_cH} zQrd+xBl~=i%Wd2}!+!P5Blo$Lx3}o0=XcIrGW-SJUiM8oc3G`F#2#8=UwYP<&*x5) zVP1xGZ?nIB*2wU;xQycG@~ylNFS6@bk@h(I#zos@lZT}wsW+wi6V&wvuD)A*wf*?n zBZEWlp%b;?3Hyz+M;0E(o4J`(OP&~(u*Ywv6BXjw_gVWB!$a0ej)t04YZVnzH)?mD z2|8ENi;sGyyFWIUU(c)FRqUIjod`8hi`+V>b91 zdrjGIoIB#X#M$8$lZ=5dH7+^u9ro4#qQ-Y}PTyD8S?BfsGH=H*%d=hVN z<-{B3(-&tit+HRy#ZtUExd%P#%Y0nJo*cK2Sw6BN&ztN1hjvnNdVGLAeMSEOcv`!2 zK7;V4$~G?FJjZ@$`Hh3W<;~hf_QB_m4E~jCC7-a*J^!x3KZNK=tF!DkbaelPv^noC zd+>shxySHk_BHBy2R*2h-8s9MqXA{#aKYHz6}(wmK>J_dvvIn8@8TgV&Cz;++K}7f zkF$s2cKh?}i;tkzy4>1he95-o(tkF-#^vYny-}6RZzexoh0msj#yRj^>3AnK6yaM748NB*qYuz-6}gcW?7L<@{l&z(IWty&){~DFgflrcKDi4A3PpCoxe3kQw5&csH54}NN0^jj-@-q1D7J0>W z{j!G~@%CR)pb8asadxPINBA>Mb@0{f4e&C1*L2;#Du0NcDbxq(QFdrq#P1%lAKbr? zJP2O>Fx3x%cQ2swVemEY^E)s5C>4Rg79DVYqTr(m@)-Ey3A*+P@CNTt5?rmMc2XZW z(Cy#51W690p~9?-s6qyO!#H^soy+IIcV9x~^PW@xYAttM@B;1$P~pp|LJ2&0Bc19p zxcUs0uYgC{tKiD|B2}nCAjMt>udz44=iAgy6Fkq}0-t2J+7MX2fg0+7SJ=DYbMB+^ zD%n4H*RcD+x3dSxE$`Y#zeEiMp~6P?5cqEPFnDT$+KGVI*kgUJuYWv4dmir#=(pC7 z*xMZh3Gn!Q@+A0b_7wOo_B43@NZpPz{xT4VjZg%irglo& z-SIC8r^^1Nxd%fp0|8g8?^aAdw-^tzrZ}E|}!FTUNJJbOm zokgxL=^vz>j78vwz#48S0KS<$1g>tPcEaG3gVb>Zd_K1mvmg-UhT`DK1=LUie8F+# zDe(Fl+MzUf;X715!*0p7uX7*=71~*9C=Z@{nWk9*d@Fkqyn6DWdr8avuCM>?)Ip^` zpjI7A6{_GH*=yjDg;c%)9=n6uZ-U3Kb;|4hTM$_929#=p7t+*07rb^ib)YV#M>(Tw z7wzL7u^)U3d%$sL{7Z$}5~>h{3ZXIb5O|I~0`C7T?MM_n`ypy4X1F{5c5xtX1e{$T z{V-KXfU6tHli;PB${oGE}HNNDWoMm$6sDC%;SO>)>)G8sZi&w^#EXH6_4aWN(45oS+Wc z;FEj+9q{xcRK5#tRrv_iW&NXf_X|`Z0N#C+$_2rbk$v4u76PBYkUR|DSme5;A`r-( zN)@8uW%d~OrYMz9fS1d(qe<|A7?n@CuE(ET`vwQnP+{HKR3QUC8YjU4Fp#i>uy$LQI zx4@<24tSOixO*9_|4S>WW5u6ZmP^xO_oFANd;ombIC%)Xz#WG@r~ISla6=I<;0|V$ zVvmBi*kj<*aRR)$nFk}d-})ZyX$k_{+0)=%_6+#i?^8Qj@MT-cbKtAEyj6fegZH!u z-sK7<@aPYygEDxrPF?}u`YL&iytn>ubH{b4uxGFVIE7OS~NeUlyVAaqzg~&iG3}U^!Pvf(M=NBk7+M_yYC} zc&b1LmIn{97qq+MUyeA<1C{jWyusTg@U8sqqcV7%y#l_Cy~^&b|C=1BL4_UcP4E~WSqogoLo$)V6JjsC^R0!Np74qQf0rCR)BzqZr=hrA7R1A0LUzMR|1f0>_;R+3KDc=N- zJVZOx0#ARP+@GRnK{?=1il6@j5a>GZF{;DsmY2qNH7-j0E%UZ?U&@F2f8mr7av zd(=!&$7!grn>_~}=7#d%=@ryY0en4sSzOltF>a_L0bc*h4pqVDT|^z!z%%R(@D#V- z1h?jYfEsE+pq(UdgNH65?}F#J1I3SWjpa=E!M9xMwqvOP1U6nq9fZJhKjUi;USf}f z*Vq%_a_!Tu>+vsp+TjWrsNh{=@WB5^J5&Id@+I&FZAnyWr{?e*RZi_s@dGx6=;!!TooV2fz#0@g)N<@pc%zm7(&Ht6}}0x|sq| zs8D2&gV%UF0p7ip+DU@1xs5#KxtsrVrkh3YV5Gf(lYaDbgW`9!z@_6Hc$7QHgKuLm zfEO)3vN8k;Z_wbXfXnEugJ-yW6TEaiUD`G}Z(Dvn2%I081vPFc04^Pez$3gJ2A{)Y zC<@-;_G9F|^?#HTN)jprR?!Zoz#A4_%QX1r9C-$OCwsQf_4S|gDXNg`3+QDwdjUMc zJ5&VUou_t6;5+XoFM~JMYj?(91p=YZQH3h_YW6yKm$w_>C7!NL@J;MWABa2t<=U5i zNrNuPM<`xn4}nX^QScU*kAX}1M9*pdWf+pZfIBEN_tTk3flIk8xN6Y>=CQ0CChwD>~INaOpS+Ug7Ojzgud{Bh+!aKcJ*w7QDgRIq<}z)J`5; z$`!#o?zSF(B?v4lQ$zBlUpb{xt_tNVd?sq({tr^(YJ#`8e9LiX{7VN?p$iq%ujy1P zZV<}{z(ZU<1pdj-Q#)b9-T7DH3K1jV%)jrjN5SjtaquQ@C%}U*&>2mFZ~X3_H2+f& zXn&W-1bCM{1McSza^NN2&VvVjOzjsw2y6is)4IC zUBWu}oLzLL8>TzsKgWTl8PLA{Z&aZLUj93I8+>h-+|N582NvQ32!K16%$2-I$% zBZz=++=EubQSc6X41CiJDjx^W%_L8xVg0|7E2N-8i+3muzHTpSD1+`N&w>Z{CeL|J z`A3cVD3JF8PX5zBT%m~0AK5B_Z}=Bof-?C0L2ADOK5B8G3V|GZ4Lr==01xpFHNiLX z4z<7+>_aVkp%b3W57oAJvjK4etuQhKp*pyfZ-TeDe9Lt` z{^SUx;|^5t|Amj3Kl3f+BkUpY^k1ob6uimXG1Hy#pLvxAMcfQ%-_D)@SNs|9B)H7` z6nOA89;D#Tw0GxU1_Cngv*0rCbKo-X^WZY?3*dU*yHD@M8)5w~^S%TXR{n@8l)-oN zkyXHVG^l(PT;_evbILzT=6&4@xI3seZ=;49;Gv(8x4;AcOV_>)9^`HH5z75ChVmAF zlGzV|d6U#Z0KCN>1eY-p0+%rn2CwlLvLXjENZd*1yq?#=&EMCr^NHVNa6x z*8ijbpb9Cdu=ySGG`Kt$WWeRQAPX+f1-U-g*Ix!jzAvC(|K~3Z6u{-Vpah=hOIZeQ z@+GT)&-sHsFy~uoH3&#Ub?^o^)BvC5G^Br8;CcJ1$A+vr*XlrYfNLq!4hrBw{wo+Ibe>ZcaQQ5L&2@c&<;Xf*umKfXyxj&5 zbH`oqIJ=)et1s=R*+Ztg3FiOk)J4pIzF@(dDH}w=qi4~F^kd*H_BeR)9R6|uxHI|P z{*w@p*`ETJ$)5(7$)5q2Cxk4xJR#(6f&?$m2zjU=&j5ptB>|CTL!*K?gwAZ9_TsEzet5D z1bYE@{;g&YftT6C-~&%lJ5lh!X7U*LvdtC+;t)u3g#`FI_9S?RJq14R32HwLo?y>d z5O{_IS@0mA>O6RnJ1&54WiNrtEUU45FYrj92^Ds8$1U(xd@bAH4fZa$v>)JU&STC} ztK{1E2UJO}J@{_9_TVkK_TWw4&VomM&Ntqj`4536FC2>C@}0RdxMZ{{xOChAPq-cH z^_b(%_?PLI;XoHEG;XEorEck;W~E&;xcuPT|4JSJmrNQo+?{`tN<&7#nSYW>!{Cxi zBjA!rqu`QBW8gZI()^D@KvHP}TvBNg+)br=hg0B^Nz>qxNi(;=3p|oavrs`&X%1Xc zX&ziMX#rd^X;EBW;E_~Xk^sNJBdN3uE~&HvE}66nE}66jZb>SwLqJk#13d6I8eC2A z#J|W};L*M4Ymsg6P5IL^wFSwU_!M)TA?xkMx-umB5y->kRz2IKz1@}@fxR-kSTwi}L_4Wny zpPc2DOc~ruz2IKz1@}@fxSM&M@mGg{mwLg2uhF1ug74r#*8-0WQ~5Ud0DDKfJN_jD z?))#R(1i+{Unf^Q8>D>ar{sR{7Vl^P-2Y=LAM82JzcdFzy?{IaBJ5#sFZF_ZsTW+P zaU8sOm_>V(fWUS>r73V}C=FiV@)_`L>{)PGRp%@Sc&QiMOTFm4T>{T@$7S%X>=kxz z{qLn-sNkhua4+?Od#M+^Dyg^M^&32QQflq=2UK|`JBOw z2A{LUx%7JcMIf--4e0M(gDZYbJO&;fqcIc*mlU1=mlU3K+!_Beo#bV-6jYELo(7j3 zo&lE>o&}c_o-^E?f0D!VM!=bWlEVw&Sw7+-xTNqBxTNqhxK80$IQ^&!1SE%7!R39G z8u%98p$53JZ~E?#wTmxk3!)*e)dt_NlrCroT>j8T7hL|(hMz~8T+im7?g+M25CeRN z83va>6%q$e?nP4}1s+{XLpu$=Z8aT0#&vy(WsjcuFa@$uL6#>uaJezegUiq^fXmP> zn(hoSS)P>4fOZ+$WpEkV6>u5aRd5;FHE?HSyF^-dp0z@}vwEWFA+*H}fg2g16c0;L=W`&-L}+#1)!-0ev6D-U659 zNgG^NCmnEEohVL7l5gA{a>kz@0voyG0CZcSN2bUYe6u7Kf(%_YCG$t}Vr}?+zM?C0y0eAX&sTbT!z2IKz1@}@fc>ZyIiMs>= zFZF_ZsTbT!z2IKz1(!ud-GYFZdcnQa3+|;}a4+?Od#RV*TjF}D7bB(&M*rVvEV!3v`JPEmD<6fW{1Dj6I}`v{yhA~7FVBK| zc^2Huv##qaEqmnUS*Q@&oAWHVmuJDFIbPy|5B!|-tm)23+r)va8PM+KS#U4Uf_r%u z+{?4z&I;G*UzH%>vEV!3v!M!}|xqJM| z`&3-l3pnRRDKF2$n=alG7u?IU;9i~uk64mtA>b`>!M!{S?&VqV7LTnMxV*h=#UU`K zMWZwUzU~*~N$}1u$?@-wbhvyP%160<{yU|;mF5}_WTC=F_8hpk#0B5Vg5BGL?=7s z*Y1vg39RRi15lyP9t8JNFSwU_!M)VmbDDo%>g@&G>DQIi3ofZQ2_E?*rQQ_y_FvH; zO@pubwMBsp1SIul!6o(Pz$NwO!6o$;z~#k-q6Gm-y(Mr-y=8Doy%lgty;X2Yy)|}k zr75Ym4izNzHoztIHo+zJw!kIzw)@@kQg5d};HBO!xTIe7iTPq}~d+q~5CO&iI$qTQdXNCH2<9CG|GICG|GJCH1zz zofj9}`PYVkta>}(l6t$~l6uvr`ctx`UO%|JxDfahtp6qT2BCta-VnH?-Y|HM2A7I} z%c?i(IprVy=dx&&#=L-&|MWL0eor0;ul!RfK@d;}ZB{KBZ;wEPEAP+Npt$a``%WZ~dR)Km#gB>TQBc>TQ8b z>g|Bb4t4unU;hQ%vEmFS`5?{i2ba_v0GHGo1eeqs0(Ud7GyWnFNbf_bHwx~hUhw>9 zIQ4>O^#421`ALDd*wfnG@h?ZL`0e5hR2aXQ{&IR2+)KUSnM6)C=yVUT`nFBBdCLWsTbT!z2IKz1((-#+ZF`m?cxr2 zcTc*OUGO#UryW(F?oYj)mE?Z#=0)TIc5nT^_(BQLW$>h6+HSjJ=xU2SN(;&4lXOJhT-n~lciPD2srak z=64HRmR4G&d>5?$WqwDX zg3RwIxXkYuxXkZ3xU8%a;w5gj^lNgU z2^C80E%4p!ZSd`Xr;fYeGL02aXSZKx{Ezb~^_v0hMfM=LG!z0~$>qb~1@;KIv$AsM zUlanew2Fbt(kcNiJCp=p&K;+~^X%!*!1`a7RvD-uORFrnEUj|ja#LFX_s^o0Rnc?K zKhdvK0xEj}C;#dHyCherfXh;>0bahF+G&D!Po`(f7WjJW6biHX?xt#I{1qS|xw;50cfloaN!4ZWI*+Xi zxTNZ;c6aV=fNda7r-S|7r`Y}m-^jOlB+BI0j1tWxw;B2skaVZ z=JE}2`L1Idync_9DfRg4K%jjNjovQ!j&sSCTd}upkh^9-xc@vV9{`tB9dz6o|1wG? zSBId2+%|{7B~?ejB~?ekB~`}^cjuqv>bMbb=AY#11h}N?BzTgKI0Y`LIt{KDF z1SD5y!6jAaz~!zv55AFis0d!??b1E4{@>2mxC|8(H&g*1y@0N96xQ_j z|BC?{?JWuL`d_};+X1if;0%1W|M@<#KeZDCm%kkq2DjAbsDTIs;@_boi=uBKkAcgA zB@QkNmIOG@0!t+!AhRF^E-RKaxXgkKxXgkqxXgl_>w5gj^pjbThYB(a3g9veir}(f zDS^u@D4Xt#e_63q%z$>81yyjF1vPNFxvYcBf~5iOELhz6*MxwqSX$t6bJ+%$1xp89 z7A#$GS+J<}u>N1igUi3Ze^kqgB>+BIqrn&iS1*uaT9zsdkb6^EbTtm*I!mFoxXscmi*DI zF1RdM{G2%@e?$+Y)EfYo1xpxQeSx3IIhtNK(5y{^ba~ z)C(27)C=yVUT`ne~DlJuRy>{z2IKz z1@}@fxR-jt>>jyvODPPH^tgbI1CPy*k|UIzD4FSwU_4R`0CmwJtWJO7*v zrGFaWIqtX#zJ0+M+)8I0XGvJdvU9;d}?l|u`g zZ@ka-^_SF}=nM3|0GQg0b5Nb0SCOX{tHOX{tGOX{unoaUdT-bOFr&Ob@LO>jxQEpSP_ZE#7w z9q>@yqCwY%fTUi>&#Rvg!?k%U@rNfN!bO4n@Hw z^~S(=a``yBxBi#Zn}7TN>>Nxfb0DyLp$ z_ork@y#es}m#AFOaCiO{U#CG7G6K&0^Z$fA46gWdf)Q}}oM04OQf~}ge@>9*e;fkx zjz`0tOI8J!&k5GRE%~5e9Rl(}!3MZ|POyp2W2FVYdpqq=8=OBUXsIp) zWR$86{i9lO2Y&ET_5iqiPA~{AZ_R{U*W*v7pL|d-0u^M3qTpSgH8Jo7yhCwt`J708cz$QWm%T!lAP3&j?#{nF1Y~Jd0GFjz5nSeX30ziI zWpKHvt!#kxzs&C{RFL^y1DE+-2bcNX0GH|A^qlgK_Z5tm7jW`l?<*K>aGBp7aGBp- zaGBofzWzbI+0x&^aDMy{kfl`sT$WZra9LV~z-46>2A7qU6@h>(t)k$vw2Fbt(kc$V z;8hxQ32<3iCCPj1|7wFOq@co_ACsrS{XG3L;5)dTEV!(!a(%9^|G+ltAm10z>w+JV z7ru%uR5~%q?)q%x!SV%pGuN;pL9eE(GMJ zS55S1RLRVKaLLR8aLLR;a9MbTCg3?rGIJOzNM??JOJdubw5m zfICN&WacEeWaboj?XNVr(%_r_PM!hZVEvi`SqNl#l;*&bTs{vzzeVj7z<2LM-_R(6 z54=O=tr7$_bD#_^nYjYK?tiJFD!63k8o1o^HpqL=Q8JI4P+^qML<>B_-T{|(y5I}A zyyAR8(_UZyGza{B0sS5||E~@L;F6hx;F6ic;Icyz@cB-^&iIQ$AjLZr1D8}C2bWZx z0GCvq1ea8u*6xmf$$(u+y-=b4RmuZ7@ak8{^We+=$b%958TMk&dH(TDZ>bk>=bzm4 zmcb?UR>0-UaaC}+=dFQH+Wa1M9RiYi8{m?9o8XdqTi}v<+u(A~+p!=ZH@#hONxkaJ z{V7>euOD1eZvb3UZ;;)4jY@8MLr`IThpuH9TyA%E?ffje11DBiLJhT>j)s4LmeSgRTy~^Y`Qp@Qpl3o388eC)2OQ63}Q# zOD$b+`HL@#XO-KpGyY|1>4uH$jDhMu1t1!4s;|O?Cp9y#VMIo?(Pf;9P z8cKjCxO@_PJ$njVR#xe+!1`a7RvD-uORF3@Z|A||+;IVX9edGp%0J%!b*khAoc!1O z{9+kgmR1#TSz6V=3qiUIu7gJ{{&HLs0%fky0*~;Y2kC&z60M8=7aBuqV}I&h$2TgL z9|DrA1K@HO90ZqC9RinB9R`2A5P_(e93a$$*lp zt58Aif@|QCs_Wo#7u*1syWnQeY5ukOF16JQxYIBGf1G;3*X&Jezz+DF0rD=m+yyJX zk&y!)c*mj+{1A}4-~hO!>L9q>1&6>TRfoYPRYxrd$UKgLujTm~2d}ax!KIxP_!@bE zg56vHS2&P?3X-d{;F79y;F78f;Ic!-ez(+W?zq$+P-XTqxZDL-z~wHu3NER-22QD3 zkG}>4N(WP}Zi34TkR9;)1C(03=tt6ERA1{)z2hU~e#f2hFQd^*y->kRz2IKz1@}@f zxR-hjcjup%dX0cH|Gd--?xkLEFZF_ZsTW*lUYh?Y2*@%y4eq60a4+?Od#M*(R>}FV z!TR4zy->kRz2IKz1@}@fxR-jxW&Q7^UJ3B}-%GvVUg`xe^5ANK%UeTDaBK1?8jURo ztYdGZ^QUV%;PR=PF1Wlkqy3pElhY|9K8%%z$<;^@4k;7u-v|;IczS@MXGRcm9X>dus8E{FxS#U|cIr856Us7)#DoE-rfJ^Evf=lWxflKNw_qo3Q zl6otB0p-2-Qw5jQTLT~G!Bq#B)Y|}`ccLDQ&iHFWVAFdzC4+ZQAa8@G7Ls?sBTfhU zrwiU%K(6%camT-8K>u+R@bk11m(&{o?;K0zgW!^SL*SBnBR!}2C-XSk3%Gk8Tmv)li0WO~cUw({5N05eqq}~j;q~0vJq~1KZ>`(#R&pTAKAh3)BC2&c-WpGKo z6>v$tRd7kYb#`z4ADl<2w*eI-^|rv}ullsXvuD#8?SQX7hrHYG`ucN z_kR4~l6nK+^4?DnT;BT$fzzT__aBCUq}~X)q~0jFq}~{~q~18Vq~3(%&iI#UChz?u zp@O8|6u6|`G`OVR47jA;tl{qbllOjdM!>lU^$X~l<-z5>p8~kN_frIy_kK#?`mG_KpO?xFzrX#2`>RjPgMOT>fZA3S9nZ zMh0B|xAz6`+$Q(TTdD|w)fpOeCGhM`S538=t>MJ2&Ae8eg6jqGXg0C$}6obr!q z-$5N`y?~Sd^n1e}C(ok~)9fgM%j_tF%j~Fw$E=4b0R{L`24nX~>L3Iz4Mo6Xyd4J* zj8Ho%@Wdn3ua$;C^pAAJ8Sv2#pCNFWemU?Im(PRC^ed3}*8ej7icmqOUkO~MUm0Ac zUjkIUzUmaYgUjw|zN8ALLr|%ZH`}FOMzcvJ9`gOo%`gOr&`YFDq zGKN1cOOOG2A_32d6(T=|3@FCgrN9Q#>8qqVn2A1JpjI)cQgoI zI*d9F^}D48c#p#U0kw%wX#{*8mydxbkD)P<0GDf@0*|?~NRPi91R`ZR6GiaGB07Q+ zcv6NW9bM2TtGa@+aYk-(I|Le0ksnYmyQ#LyYnx}6;ejP z8U7je40wyT^Wf{wrZZ6hAB~e2!N=qK()_PLAblJiK@Ggi+YNBpp*DDq+v$MInNW|x z`oF;y0*}!ckV}x}?HG9FJ+z~7@C0us!RuT;CGO{SetP1m7H-Uk3uw zjnq&VT+Wc<9gwjiXUGpOVGT?HCvfy%ta^TU&ENUnZfn8Pb44ZE)$h1HS6FbijV6o-_XCRM)uU05|A4HxLGw4kF+ien%a|!CTyZ!f4vOB3S`0^rg?7+l(qh|8<-ySRh61b7*q;tmqv(m@J5$J=Re={N&! zt$&lR83b~2&A_GO5;|{}!KLF0`24rrel1mpKuN9{c#LO38(cc*fN!A=l)ut{$+pNP zb6t-=?^<#PA*c}J?J&4>90A|W^E(dSkV|R0Gydh2rp$o$0&l0mmqqq)W~a)4mpXJQ zv*4T9bKpC)yYnv(feu$FqVo}yz;l<=DXxIGc)JQN2T-fP`hVbUI)XY>@Uu6-x3f3F z+w5)d*iuSF9nUHMC^-W4RR3U!@U|aZjvxT;-$e%y1fRto0^ezIAPj*ndlbCDM-T&- z14x3`csm828{N+xLsl9BYfhp-27JfK#eY_Y7)30G@o_ zq6$F>_&KA6z?=Le69&(nOC3bO$4?}Wf`=2-Z_I)~`w^-T2hTlBo&aw@PYor(tEW@> z6!_{V$!SJ1UB zfj@IHl`n&*-VVBBrULH2l*(7Zi>Em|q{m+k16NRmI{1zs(h)Skle|`Jg71h@J1y`{ z7m&9dcgDX=ze1Ke=s<e>ETF#3IRKY00CDi<)^oqrq7r;dY0z&V%6 z-;#&Gb61gv!P9%pbgHQc_~v)f4n@IZ-{j~27zAW#6$ej$lsZm;uOFa}li>9$>4;O{ ztA0W4q@RWLe`YrAX$C4}E+Nl?k3UbI17H7j@;vyKNuPU$3gWW9v)$)n`G z^?&|t+S3?R$X-H66bG;Tj>;#%JF}>RB>0X~$QG_vbJTGIy!|wlZ-TG=C6#Z1m-nFZ?Vi*8TgOM-=>^>RSN$(D%t;h z|7f4Qn92vhSDi>Z6a-&zIY0k~Adp&46~f>ve?lGspZ5}V90lL;Uh)|Dz**Ez+=4(e zP8Aa1rAz2Yli;~CsC){%xsW*1)IkA! z{(0oZe%G)6{VxSd{Q(s@jyfoVZ{0}cE8wj&$gAM%X`!KN;PYN}+SlW+4uRTr)KCL_ zaguhZ30{7kyagWR#b+D5!#5-y$DQ#n)30*_b*#SKKdKumsRKWF<^fum1i)8srt(4X z!bZTEf8pC{ha%wfUZD=6;G3VN@-gsSh04dlm(3cW`JaG5ocA;d zzWojAAO*gwL!JiD@^e83yuztE`)yeNPkx;m%0Y!ln>-Kh-%4HpA3cqZxCq`{LFG&0 zvi@IwDh0|Cp!zD!_wg0*?7yf$6}-xe&l>pF-&6Z_aBJ0>)KC)w&A(EG7I@&pO zgVat3yu&X-b-^R_T9Cf}-{~LiabC~+!I%GvIu3xZ_0hdw5PWfsb|?g%-_3*Fb=|*A zzYM>C5QPdmcnuf>SAU@w9OB?R{z5yN0H4om#-!=a_z&}1FJ%U_kMpZsY4FMm)IkP( z^kq8YEcn0{DxU*i^%k%H^AOm;6$;>MpP>$l;B)pSFM%f)l9$2P$7zQu-+}f2f_fu|1$D6c;f;(f)053 zTJkRVIKP6bw)7A7l@>3d{16zwh&m2{r+KUd!MFdNIu3#7E+h|w&;K5^Z$%)m_D@tH z3f^8y6=L9t2zeZQ`~>m@c#&sWlDxP658X%|r=UV+lp0Ed&)SPT13sVEfLZXB2`ZoK zbAA1@oU8MF0i{OyX}19G=OtGWyfsE0l)%^W*eZi>b8beR@mGPs=rA=@1@DZ~8LEMY z-%DOc=jVswY%eAGGO8{YN!Pj8obbGgE#rEwgdjmC#jt-c$){W`mQ$%X#VB- zn)!PHclxz>9S{KD`b#=PLGZ+b{89~g>@wP+F!*SSKmQYf!1iBLg(!H0SHm&z*x6J* z4j$y!4HMvHezr_n5Qtnt4W+=NoYB(Y8+TLr4EPpaA7sIoeUr{yj@?`Thve=RDs*q7 z4hrCk7ZgQs8C)fFnFal>um2OYN0t77{+2v-Tm|32 zCImWH(dcY}ujh4p8$1-D4m#kmo5;K1kss2Isuy%W&iI$|E*n&4Hw6Ka85^X{S!+7QUTM&1Dr zC|YuL!AlExk6-K`y!8UL;|C8fcgtHU0D;9vP(wlR?YB@vA@F&8PZ$OdpH1yV(05Wh zQP=hOlj)Z`mMX-cLhMDV5C@-CBu{{+TI5Oa%$4LR)1C3ZmQQKg3}}x&Ks%HH-!+pi zL5AN@kON5HN1qGIf^YZ|c@F#;?e6>wzTAJ!I=|tkQSkN$say;^zaM>qA`V_)PkK_JV4Hh6};1D+Efr?KJFZ*V@Pf9XQ% z=a9>%_7b_JutH~=3i5dXEHCebqBpLXy5rE5rt9l3ds^xX^gNU@EA%|Z>jdmLHI3({ za%cQCrV3~;T|ITj>YAxNGK~jTO;cXGJO1$qGSgJ3OyiwtJi;G1!1gOWAL|<|jb5P7 zJJWb%;=*;lAzxhg_=rFo~@yf1i; z{O_{y>__jMx^6T#wMQl%)NNYfbyJ7)pPAZA(|Gyrsmse(q;PlrpLNUsd!kUEo4O(O zg{fWsC%o8!{2wCG<6kn{Ikh+OQ+)x$i)MwMS10~_w|m8%2TT4eDRw7+GY?(@;4T#=Fya)VS*0KAqXLamqhrEZPFbQpoh`G#)jUNM`w1)xG<;@&UlgxGc;jt+fz>fLLjPh4gD z4%pZ1IXH26!Og4}IuET0_o3rHT%vB8y4m0~USBhHdHD-h-ce5+e!uU4neJ{(Jb0h) zfQfnc`es@5_a>CP!ZvqNzGLWB=SeGn^#NV}1_HW#mk^!5^ho*K>{vcgj};=uL_W*N zAQ{6yZFtfchQ}D*?sFRAZn)DI=+)>>;~8T-n;jIV@s=?>z4FU-Kkcak+B?(vb-gR@ zHKfbuCSLlY9!^bqh)(?3*^1Lco*s(s!3Grn09leTY`FYUmP)!H=m?zN}!&NSYg#?`}9w_l+@(K6^xPWOCG+a*zXx2e z88@=~>t}ZFj@!u6rne`2MSX4Z#-%mG!JB*M)O7j7q0auAuI`w+eEpuOJ^FRmDSw#_ z$sdKo4*bSNHp|OjvBL85mygi9#)aK~51qf{M3s#zYIY!h7Xurr8z=U&`fSKg?Y8lhc%5(Jf(^cd zPB7zv+o#^Ks4)g~z1QyZ9kj%(msmS>y~LeUdu-yt`}Gj5erD=$Z5nUhJ#~5Y*{MDF zxv4!%x1cmc&Esf&b?OQ^8q@!FKC4FFGTTWQL)!HGBWC-?Q*6cExe5v7~ zCws^7Bex{|r)Bs?!$Y(drz>=W5oj5U^miGa;?KA`J348&;*SqHzOT$p9q$@`s^Jm- z=!sMQ<38gGg)3KydCsa2o%%-yLe;bDHZ+O%2 zIfl0kr*lQYcF!&4j8XaN^aAQoLH*b@JY=}4QM1kg9B#PZ@cD)Z3?FfwuYb@89Botx z8E!tshYep~l#dwx9>b%Cj~X7cjKIl8Aa3|6h9?Y<8lE)#y@sa@Uu1Zi-EvOdX+|Jp zR9I?w*6`B}&l$eV@Vwz?8(uIxPVetiv}goqxkO$v{C!44Wy3EtykhwK4X+x0k>~pQ z*NnhrUO>+R!!I|yVfdAXHw{l2-ZFfZ;cdsA@#kEE4;q1vQQ_^9C_!`B!dHvAUDBZl8R0>Ychz8i9;a;ZufZ4gZYcIm7dY=MBHd@PfGW`G)mIpeOl$?%5Z4;kJxe3RiV!yoRs{(hqoc%&Cl z9m5|pyleOqhO7VVUCO5n_Z$8#!vn7C<9DXt(?%d@RCvblkm27pJZ$)P438N8g5goa zU-ZtuE)X*UHKRh@@Rtlv82&@UlZMv~PZ|C)yW4--2)trc$Qb^r;aS7C8J;uzHN*3U zzixQpKl$?w&L!Ax1d2w5pBY{oMS9yfd+!xM%(uUgAb((u`arwl*9T>qzy zz=1}EjNx+)&l*0@@SNd?8lE@&FmdPl7mUE+63|{WeAw`k;qwhI8-9}E6~j+9ysF(D zf6nxa8iATo;k|~}4PRt&Oh9?aFw&6*`w-}!KzOnxQt`SHZ6<#nrWB7}PXAOVJ@SNe_GdwTutpB$f zfr13I|G@B~;dR4HhQDff+3+73UNO9(o%5fb1xDZ}MunQ;KQp}k|0w$sxTvc3|9j6J zU|0m%5tL~MJ>~EVM^rxeeS)$QL*3q_w(U1^L(G>Jm)#jS?{@{fS(lbG6DZiz)uPInFib@ zl?#j?8yHfRfR_vSWdT1Y;MD^Dvw%wn8hXJm0&doD)StTFe+5QUL7_^(!vy@ifJY1X z1p#j-;1>nFi-2DiN3Pxim!yzb`1bmZ#y9s!nfO`n|b^$jFcu_r$`g;qE zUG)q}@)7X80^UTx4+^-ifR_n)Qvp9E;DLnK^}lj~5h5s533#Z0Ul#B%0k0PDZ~>P- zZ|DUr1l(p87?A>_senfbc$k1k3wX4Ew-WGn0^UZzyXd&S{*M(Hy#)p1hddD{?2ZMz zs~|sEz1bT>A_b**w^brhA67aqPK10Co6YysRyq|#E1w641r}A?I zhP93X+#%qD1bmZ#4;Jt|0Us{l+XZ}tfENMR>Q5u!D1os{P)HN-y#oHQfFBg_M+Ce~ zz#kRxQw_LH8ZR))8yM0=0k0D93<19^;F$tmE#O%KE*XzzsKSqFxY7P*f$_MY&{V*m z6!0(spDf_f0zOs1+X?tI0q)QPBQ<#^p+vEws2&&}4A z0^J{Ur9fLjGp`2uRL~ZI9tzqj&?7)+3UnIiY>l>^&{IvcbNt%3+R{5Jw95CmQVT`JJ8g02+k0?@2UodXX4H$Yni+6me! z(C>oI6zKOsXE#x8lopx;I{_330v~}c73kfdD+Rg~H1ln6-~ecgKpzHe73d?NGX?q> z=xkqGgMkwO3Iu`gK$i;iSwKwAa+66j2U{sVNjO#rR~C=lqs zK$i;iEzp$$&8%>sX@djqpe+LJ1==dmzMwM&IsmjSTL3};6bN)U=u&}>1YIf67SPPU z!GSiQEdm_}+A7eUKxYbcywzoEnk@i5Ay6RDeL$BAbbrv50&NA&0va4h1#J=Np`fh- zJpy#5K&M%4XafNl1Azj8ei(GAKu-W&DbSgqSzv<$Pk^=v^c2umfu0UJQ=n(r0Avfm zJkSLKy#REnKtBh%QlPUzv!DhCR)Dq$^eWI+fnEnXQ=n}x0LT`Aji3tz`X$h%0{trJ zN`Wo_&4L>ocmuRWpq-$t0{t%N%m&)#|2}~12EczO=mLTM2z04H?*?5d(50YRNP`0h zKwAX*Flehl9|4_NPum>+#{gv40}lTapbG^0JJ6*9eHL`3Kv#lhp$!iF0@@(3JvR0GhREaNrHl7J+txwhHvS zpfg(t^Z)w*vIT*ipbG^0BhaM+y&H6;K$n7Mkqr(U0BsTI!=SAKeFSu7q%i*<1CT8U zoB&-Q(BFYB73i~|D+Rg|G>d9*;1|#qfxZCRD$tieXW9hd4*=N$eI0axK>r20RG@Ex zt`umN0tccS9B>D15oj;aR)O{fZOasZ007wn9Rj*Qpu<6z3UnmsN`bb3W-$#8v;l1q z=s3_;f$o&zifWpv1AqEOR@W?)3u}@kH4tOMbSW=wc4b>W=&(G>cI##>uk@5ITQ?=U zY8EEZ)B7@MMl-cS33UGHVXfX>QyW^da8F^myHq4?@=|LQNxf22%d0?}4|%Ckl61w~ zH0Pz2-qPiEZZd4_+rC$sc%pW{boA;2a$zp;T&(YF7P7*e$VAtlC~NlaL9Uvmk}73L z{M=!AdWZ2zE_^>4B?VqwVwOhNEVLG0eITh2HdL~89y+m;2fEBL($PYm{{>zOaeN`0 zJPe$_{Ds`2p4bDTiKsC|)9_Eke@-aEvAUt?F9k#GzZ48T0OB@7hj@Muzd*j`OS!q* z287MQySlMJzV}Pn?6wy48l5gDdO7GEjo$bb$i*O+>Fj8t=YqEDbRyByKrhnibfO;z z{VZS7(=Vv+@3o^VT1x78AaiSLL#q%A^QVJc<@ls_le(n1sO^>@&M}gYYR-_vOd05U5dyQVK78v@If?bW$zMG#KVY-?sO4zrNB^$n^#(T$)C^Jr ze1t*`JvGTga>U%{trl#Pj*`xkw`%zui=^X^0Y680kTZjDtAVcpuE-kx2;rFq{xojqyO}%uUqFES=Gn6s!iG0z6sA+Y_E?;LieYspG8)&o=P4 zfh#&5MR6SQa(+CI&!d#{E&nk`~ta&93(Y8074EvOBJ$6 zIxghkEW)h@F67`-S^x}O%)uv!k!>)9984#?z`%tZe3^A7~zfNU;yEbg5%g5!GP2yY)DcF{G zJuZg?-JNpT5tMRP`7iEUfnhH*LQA>lpxRi2pB>wFqd$vkt0G9t|L6tz{MoYAx5^r z5Rx#P@B#xDl5i2>r3Nk};XJ}C4O|%aW)RMdrWKNK%HOp%)WBc}bMIrMU^Q?d2`3Pq zY2ZQNWxTNR2m9G5+)MfND}rTypbgAPIx0p*opAQ zlCT{Zwd<&ywV@dcr;Z`FTge2Tbc&34iNw}F9*#<*M!WRiIFmNFW*AiZ8;6f5U zPk5z)3rV4j^1i!ny@u0vJfbqWT4()I&=`8(;Dx zCf_0~0E>hLU?2I0w*DJ3{(3_WK8)|;Rug$sG&?(1%da!wA-{^KjJm}g?KbOnnZ0;^ zIVSERtQCudwPMli(pWuT7u}!@%WzxK>;m0lK_eE)nxtneX;Q|PiCdO;Fr*q8TNWcM z7vCh@swGZYjF7SUgl8JKma#T{tMM{1vJHliu^R|4FmNGb*Arf9;6lc(B)rnVg^XQF zIMec=EJn!K#WrGC42CdlK0~UB+t5#d4FDu}f~~!{(hSo4|Hl*K*c2@mfR9K8o*m)xwo>W8_}4qC0^4l`ag7i5T2jq){~2VK~MV`e?Q@` zX5puWvSdF-XFCVl4RmeGlGN9I2D+9lOLbXOl3j23Nv_ueCD&`Al4}tPsKAborYwrP z)gGftMWO1Y>$RbiaIj>4-aZTORIe_rt_{8U^hbp}+U^(5um3Cu`0kC6bF21ytL010 z>f{I>@{1hV?ABQ+_s`Wyu50U)TvuOAa+P~a@fG`h)PsEZFLJMcT>yL6k24E*Dx<3L z-xkE16={A|rljs{*{yJ&J9>9wcQr3rIa=uv6~E&rDObbBc2~<$gG!}E{DG^rd{1rH z!aa(A^)=M=!`*}U$zSBw_~nF}U*yjIi!fST!rnD+zjCx9*+)Ib`~6pL%iPNO6aSUl z$P!=sUpa!!`-waME4OejlN{aE*Z5b!Y|Ws#LwT^8_U*qQCRJ8R#q)W1*1IrIVMi-~ zkB3LwA)}vd1z%j^Cym|J592(mND%2nc!qGSwKQBkgxp^onQIdAhsvu7pr+weTuT;qvQxT4mcf>0iX!flXzWTh}LVk-Eo|hxM%(SS0>24AH$a%T7sR(Cy{OiAE3&ZD+ z-F-XqvYWEWEgzOT@=+J$i1xq!Ry#T$$2qNF@hLP51rPrNfwL}vdlhLk&hT_YD}6iR zo|q=@%fGrHk8v-;`Gl(}@4C>py9teXo@ZQyd+#9!a1K$F3-?~W2>06Zl8bUg#4?&e z;NHJcb2@-n^k*%vGyeNUxrgU2D1Hnt`tgpx%JG?W1@p4Bsizv_kda)?&dHZan5UIm*@yp4_IUz#L5Ofm&5mqU&#jXW^bf#vyFP#f(|f=&Go? zL)nOn@@#2z`F`4ud#b+6r5+BHa$SlP z_g8VE>o1eE0}bq;qvXLnh4FtD@W^8c(jNQM2?|hizwg9m0)Mg=$@)O5|zGJD9z$%GOOBe zLjHv~%OG3va-xfDy?8(J4&U{jgBHcHdR2Qq?~2^h(h07U{nto$PlHT8dRIA;$=!<| zxgt+9QK0yMKja>Mtx)2(=m|#j_{0lMI+?HIU>fNcSX}alJVMr`y|2ofOcYPQ-ks^u0* zje@fk>l0mg*=EN%C9SZw)}K%GWzBfmHH^YVBoc!@c}@w6A3*i$EA`N(p|$o|KQr@c zirs$veTKi7=pJg;{XNuWVZGFHzo>X?PkUNT2+Si_Xx@n__fn5u!B{qNi0f+B5EuG; zQA`o~cCtyGh*UTT8|P8uX_)4IMV^?)wN9-$46sSIeHJ}bS@T<}E4G5Ez9@Vu=<^Yh zYv}k?zW%!01wWFx7ay$KNdCul*CU1U2ZtJV1AYMk@QSP1SdWDa=A-BoY z>PGdV`hAZ)&g*jTx>0?y``Od#>o~HP`V#7fu}8BV8#^U(QjoMmiw)c@M{Jz@^bI+x z)9w*Sm9|MPdGhRPN{dP*Dy|k-y1BX+(f2(d=Uzps()XkXc$;e361=UwoJ;4vdKv~f zE0KQl`S@x%G~fbFB#5Xv12aA4M+je0EypqEMgD%Z+|i=BGZ?K&uF!aEhC8tpZPgo! zcU-h=UfqSuE;%axEL=#zP`9VHd*Q`}QoPYKU3JOv*3#fz+n2JVdFN=djdEsR>9y8a>@OgQ~!67=Np6N+#5=m z6R*VVz(UX=nUXiGW-+|`Uvi9X)`*gJKh<_`G{186{HhFW9)CVq%GDgfvWQ~dgB(CU zeGP{i)jg=|7WB8LeFt4~b}l)%I+4Z=X9d!xysOmRpGMJt>{XrrmLHct;2Zvyd+L1? zGjFu$-k}m96f6 z&3NujIWRYaCvk4@`} z!W(Hp_&*VH`Pf_XAie$lR{6z0hGvpb7VeqCL&;euo&|BDXX2BV23ou0c_U%^Wa4=- z1IsR29@O#baC--Bd8SRU^sIIWk7?o;%1749J|2hkXSmwbVY{iPNf{z`7HJ{oUKQvw zkfly&HGDe=n&#*#kK23oE0=0{AIRXp{mQMAAwO}^`nKNx0_5fpTsS7}-k?ShZfC)c#)xR$`dc<109g|E@=yT^oWDaWT4y zG`g;mSU$!E*VTeLMh9<6n=B{u9x{vaG~`^{X)0{bb7U6gVN`&>DYK4u3YeK7fSEOx zk7R6c+jI;D;sl-)pikhXZc^?}%(!*#>|tzRy?v+;^gND=eTc>KBrZR|y7E;D8*?WX zZer8xTW!6GwT@beFqUJYpsm5f^c{m}@84>9T`?FMTGVS`ec#Fa7nbwqiHF zXYt`~EZkgl9t%^?nZEpKH`cwCLtha|@#(2@u6=;C1EZoN=BM831B2w;xi~`FK5GR3 z+>P}Pb716mOu?i<-NPjzrm> zX7MrRMxWl8{}a@&1Ekz&=u6)^W{pP679rh(WT{u>o7R$ZZ&^!7zkI2;x(ut^7<+>H zOO&>`bd+y1;ej(d8k3ixj^J0^S!mz?v_vxSM3)u@^pv{ZkdIzczqCj+sVfkwtE&gQ zs@D&8b!6BXqGHJ&tZRM97J9IT_-*xIJ;L`vSJa{y)FJi%v$wP`v&k^W){i%TX>`=3u*f)dV)5$t;?QOIc3tW@|M^kAU+Qu{e*z< zM?6_;uYOJS$!vU6zRHt@H>r0W$<&6w=gGQ-UyPP=|HhJnZ=P5qdU_hJLsndAIbh+6suU@?N}_Q_Bg z+kg;f2}-MIsjo82m1fSwru>2z>(t~pCc z?Wwl5WtJeM!nd$ZCl4!NgFct>&3>$Hi_%{~q8N&F%%k4wyP(t2Ye{4w|G|&78z!4o zbIp(DDwEVJ9h(RoxT(*QlnGAK37R6QgUPr@;;_;k?ir* zn#tahgO9`oQ{R3bE+U*ARIJ4l_%lsen>H}oZl9;C83rK~;*iP{RCLc=G9*vd4YFye ze1B7B34?4jxeXUPp*FYtqN;O1@8>m5nblOb2DMK1XNjh=Blz~bKl|0QEEn_7Tr6*S z(~&H;`1Jtxgscnt1+l@VGE7g!j|8y}03lhtI+*p4Jb8?~0U2^r{KZLU1hr}VCWdBPH-TPpo6n_ot)*xr6 z^Vm6pPqX3|_}&U;uEH0>@ZbLJz?4gMa^>)f`>_4})!R3vnNp>POvdLymRRD61^6K* zmHf%Oj`R!ln-iDln$w`lYe%ppesjVb0cU$9y1s$rw+ST{jBm=e0(H}GimW(9m$&ce*iC{6{&~astth+{!9>VL5v#t{HT7(X|K(Ie3L8MqY9m+<)%?-+#!FM4l}Y{f_oGHx3=FwkR<79lNlE+r%?B+v z&l^#$?Cs~o_Za?FG>bHsO)4GYikq2Q{AV=#k1WsQB^DMHnvE8oJ0Y=f4-37Rhlw7$ znW6-o8~tuUl51XeYsr%2Z}{Anth4+wf4wDZ-=#OKegRKMn|ivE@=w;I?RKkKQ} z!AOTEK=;ODVLqcDiyg74uUg)cj`<|@1_UaS@f|cpC>KK=8nVb-m`ux$B6E_YPGS-k z%89O6VJU*m!Dvlx{2;zQ*f-oAvNRC=JJ`2JAjN@J-K0cDpvWKSkNFk?ej&cCqbEav zN{fJ7;!^zvltO^xbH%+p->gPogkfo(rWECc|HVrX8ASjd*qILt{qJ8UiyyYyUlD04XsOF3{)G z{CHdTq^%zuJYkj8e0tu|w4YjuV?jFZ>kRSj?ujKb#xA0tN6fCnz9u)PpK8Ifm+;mk z=hYy$*k}Wpu07^@(Rq({v`Edn1Z`%qPry@+U}q?3j2r=UO;@Ey1Lw3zN$OYpt9F>C zKBw|f-_~$fANVA7H!!MuH205Xkt54uUg=k#ydQ#Bm$-EPl7_bZ|4QETR&I-B&GnFP zjb%Lo`;v?INZs04*1APo2#`Og&)uE6-}0n578vx`Z!DJ{MUxm^c)s`(F3v`e#o5M^ zIM%kwg1Xf4XdeFz|1gfVmos<;6k7+&w8#s^F>H`?Jv!nfcO0e4iLQ>9nKlv4@s(Wr zd9(H`V)WrZSrDcFT11dipffIL*5_;e*+-C5tq&#U6T|f!xUPpc$oaaK8G+8Fzq#A$do=8hsvJ2YlL&%e9TB$9XO4sjq~TiIe3evVJ* z$3pmwjx5VmL{rDa;eIQ5dMDPwdo4=Q280dC{NpYxf^Yo0iEn6g_(c=M98?!|q3Kk6 zD72@h$y~Qjp>m3k>dZo$JZ$)%TUpDW;Bz~(Zt@$vurq7p<mrRnYd%cKeJPh_wuqT7<#L-8bu_}r)Rz-Nw74#xz z)vGv!q*Yr2X!=eA6;F@xYo62{j?t75hm%BFPsQORab;X`;ZWK0i>M~6E@t9+R`>an zs`bG)%K2hVEhUeG)?#Gw1XqJmnJ$TJq-PzjVeN3+q|={r2$m_3XgBIw?P!V^by#x~ z>T?55Y)84&!KNZVs3qdjAJM@am|q+*b{sB_O@TayRJ37TXYxVbSf~~r+}Vdc*F3dc zA1hMux!qWd71Cl1wl}t7ZATWxoN5@&j-e!RDt;RCHAXXsF%>)NrlosK#SZgaJQvWX zVrmv`DsDd(?g`_WgXVB@w{FVF(>D>Cf;Kg$K!M_L{l~kw0 zek`l5nfb~7Yf=T;@Y(_Fu!)w;Tu#Js(XB-G5RD)c z`}xfcYKLMD3Ts#D7QA~38_jl}<*QOyALdcX52Ua*Z26D;QVO$@pQM zthUoR<~w+g#aO20gD${d%$E&ImSs>1LRRwTZCJF8E`WzAXs+;BF9WuN62hO#G48|G;Hl_2NQv%J#?X6ZEpPSBfA2hP@pnthV0WvnZrrKl67pv8hH4AgGX zrbL(7A3N(2tc4dfKupttu0ucacSo>zzGx)#47rk0A1hiGd+@iedh!+$h$`b{f&@fw71p zw+a8Qc&%k3KQoH?v?wCUZS**( z+(WgR%xYG5vzl+Rr!9jOp5EFonzu@0LF|pQ#eLG)V)>Dx$H?rXcr1@cvb63yhew0g z;j$0R=LBb`ZBopu$*6T%olF>HLY*d!zbtKY9skj8hK**Ljho-|fYB_z%`jAlt_0wh zxOSjAC?m{?|7JH~K5*Oz>6(A5cJzoJ`IOPDMa!a?*KqlR4lohFa$KgkgiOT3-@wD1 zea>>{Xx7QMlK3!0@q7A5{>x}Kpx2^aRKDih4%nWD+?&)VvE(4;Itq0lFbcg1V+PTF zpz*)<1n`lG?$K#^DCD-#6?v*zU*gFy&Kh5Z6LowAuZwA+?EwDZmTHpOp0*KuF?%U< z_x-?+JjmME{(Gi2G(CK*YXf9*+?J)K;~2a2jNbU=_!O7u=|AGe)}4NsQBE0}FwmYh z2R5!gup2q7zw}7uY(*<*ht+obtT|IARbxoh5^yuMPF!LrsvhJtW7(1uCzX6=6kK|S zuNs4lT_GsXgYr&IImBrPelRYvBnpps@MC+U_oD(hd(*a4l*x~3(GPLHVc4sCvGMvt z`?u$#!gp0-2l5b=s0gs9C7=>UXXL#eV!-s7ToxN7!G>f=A~33FIT8wC}nK)r_w z-9S|7dp7dpx;s5nr;3L-U;Tl3)zu7_-$%+0gBbPkK}cUy%!c&XMIUTT)Pr@92$ za|-ps3fQS%pE6@8h>F8?n7E(tw;UtXO`iY0d#J5ei9R|Q?=qU*l3X_w1&{EVlU6tM zB5JT~e@W|tH@(n1n!=@!_;cu@C2*J4&L`Y)r2%+HxK@E)QHkz};_iY%Rnqkf4gC;PwG9S{5f%46lt>tLjI++UUEwFh<(0ZZvBHKtjTv#PDOQm0 z2@HKJZmB`5?P%pUNK6ja@7o>bkFYB3fCkdf=(@%VYH zzpXAReQT9^R$B1L3cczmol4PwQjAJaWeA_ERWLa2LzIc&@XpV$ zA;GfIW$Gq_bFlSqzV;c`dBXiDJKd`J>70#&*}Z5*8Wz$kb&PiJwMgdc4}FTUzF`WZ zHQoo%qrq$deBFVy;8h&K?SvjBEV;Y#3=e;n#raNvFE8RSl@go(z|)>(omkZOJo{M| z@AaIP{DIEI@Az)e;R|7lY}1qC9bS@)u8@;n%^B`BpM?+lLu((<#_P<~QDeT-dc6aQ z<2Xkr^10rswcK0HS`?z@W35?&GHR3E@alA6;lJpuN2{4nozI4_V`uoz`7Essh7De@ z^x^7CZ;aYQY3K=>`Zjh}=vfZQ#|N~G!KMhVa|=XB9V#X z<0U9KrU=*ffT_UjEHknRKI`T8(rdwC&Q-u@ruzkV@alO#>Aa=j?S)>g$it0v(p#kI z1&?%|5}B=Z=3FW$S-Y1SHxJRy^H?}72M)1usWsZO33^6>=Mz%9jL0fce{d5XxR7-m za|U5gwMHqjaRpNm+K?J`|zZU>HpN$o{sNAhh!*EP$55zkI3i#ykSKrg{}ExUGM zR}3#s0@L`o-5dmaBu|5KdFa;gVA19b-R2j-suaFrG3(Ul!fCB$akDY3Xtl5h!=|K` zHnFE&JVk@G{vGASEre~mM9+Z&<4mXdB^+W!-qtR7v)Nkit7ZlHX;&y$e9zlF$KpcX zL>c8RaZ5YSo<`&MHGD5P&7XLVjj4`2m`%?iMLgp)|I5avvw^4h6g#u9M^Eu}c4oER z$RH@3}|t!An{5v`no5X>Wjs z_>w)18fB8ZRProvYM3$pLSk+6(h_U_Ni?$Yof^^;jks4!tdO`DPV${g;fwVY|79tg z63`ZQ${|~qJS|W0%w>46-037gu#AmhvrhAnEe-p0?p${2YHZ1~(Dbf^Wp8-3rz`#EE)}iGLl5|N2S( z@Cr7I<(%Y4R_%&caq_^ojN)af6GZe<#`s{_i{FXr36y%+U~Dr{pznSX=YDr zg~CYqF8-tdH9x|h*8Dqu(c!Z#>U5%R#FpoDkwX)HUw}Z?-ubB(I6|?7&hb- z|7a!a*|sk#l4rp&DQ1V@AjxHpmP+i#qp@1_QkrtiYDeC8748yuS;ag|m(7bcG8*3s zJMxLESVtCw{<@0wWbUW# z0xtk4`%Lu6E`AjSAD@fxd0U*M7?s|g$tsIclLpz-o`S!P^1EBq4DcU2#ot|r`dv85 z-Pbc~z-id4+Y?=Vpmh6jH0XL9viY6h+3S&z`;YT=4%Rxkp<$@Nb{*8LksZ_}7*@Se zAU5~+bUf5>-18*w<6zbdmdawAUVa&^ME&Tr| zx{XnE7(VX`Hra7>RFht?r+N!&{@q`jNPUlk-Pbb2c}yEU=zz`?;PVpH{;qOKZd~rtM5Gi)dm*I_ikpb*otHP zm(7^2pE$;!cnPEQ@MHY&OKgl+uR2-$ubCTJG#~mh3$XoDwFZ8xSF0C3kr20sN7BP5 zFR-VzMYS8{BYgRb>}gTp*PVRO3XYDW>F1cL@QT@)mod;3ep~E?!A@rFzu{?HSkImh zeuHY^WTx)-l>W)fosgv-wf!5udkaRV#Bcand}jWW&K5&wJwC;=5;}~JLzpDI%a)E$ zZM~@-chDhRkaMe{M`LdEH+;gYEYkW<q=}{S1Sh zzu|52SQOv4mBsbFJz<35-nX%YBEB))yMIeohTLHw*P_oCgK?7r#od*0#3uvb|NISi z=CPiUwxfDmeuz&jgq%Hb_^WSvgPm88@mqN;A?tQ8tH=lr?1tFWK5ncK;^(zgGr<1< z{C{fvJ%}SU_uZcKG}Tao6ya)@rnY)6>VmI{f~& zYB=Z@aS*P_z1CKx+arN>bXYqzfcPxU5Xfn#`jP-PgPKBEtV;JYsX!lm($hW-|0GtW zlb3JMK{Wclxca(%^EI_kRGfAPi{E^W4Q8*F@zmE@4DN1~Miftdoi&kJ#@EFQ-oWiV z^9N`)T|Ck~nwz)dc)aLq9=V;h&bn+&3`KWN3_hBU6o0Es%hw{fP=pDnNSlB@>8NJi z#0VKO`MX8qZ@ulTIDv9;>+72o(a zYd!3qo?Ox@i!(}m(sO%E)kRkyFyYJ-CnRfVLYD9=b#C~XJXysksJ>9f-QQuKnu;(r z@z3937XHIStXKR8Um*xfnfgp8ch|fzZn1OXrIMYf9AQ}T$3rzf6?6q?%AY6%bS#Uv zjW|MYzIRvC`@3tWOSV4luH-*3$d~p|lkhp0(Hq?KR$r9U1N!p{h^Eu2DCZ#PK9k)| zC6~9+Bkjk!;`(b0_@Ow%40L*fFSWuAQIuKf-5mEnqvERZxfs4yZ<9)D-;(%^vFvp= z>Z{^c$Dt|N>?7R$5jL;WZ6W`*t7^Ro%U$BtB^~T(Zy-?5{11@Yr!Cfk9PE4xCF>6ms0P8#8((7i|K0tx?4OxYTRWO+dh826$j zov4%D`vrghQ8vc(^c6gv@fpuL*zV;;OlQ1f1TXH%53{Fr{s(>rHZ^VkfggiSP1M)5 zwtE(^4+5e8U?8J~J?DchepQN9a7q$FD zv(!Buy=CiV{h=83q{=V(l!@50ax*_W5xKAmJl;DUHw_LQ=Ihc~>%I<*E{-fLjU`Iu zW$|hj-r>scZBHAgd!z9&`Z((ONcH>#d)lZY{8Bm#k6(b)d#qEcYc5`{CtKE2@!Im2 z(iN{_I{U*lbV7&z_$}D^>X*Dv2D9`Tf)v*E{B^yN-EPy1g&sWtt8A%192$QZr*k;# z;)nUh3>KMeJ6s!zXx{FhshgVB8+Py-VQ6Fi6Ms=RHD&ToJ?o_Y8(o;v6uvkskr4%Y0QZt6oMcnS?y`xL!UdmJ%aeD zOx7X%W0U)a8}K{QWGJYPxg?M*-;@e1p0FW2`-U=L_EdF%}+j z9p&FXq~Q7aAwK;v_7Yq01^0TKh1>Sm$+*=GB|*+t41Jv%>Ax* zsM13qW5LrIA-ETR3HWVq=iBr|BLnTat4pwrkGfr;fsdF}fFJq~{3Te{`TYYw35y^P z@EacCbITJf*5;s$Uq)GrUXgWwcXb(l8p4hzZdN>S_*n^xOF)X$O+S%njC4#rbH4K_ zIfn>Q<_|%{Xh}htf0r%1NlBMvEI7IRSuw}85p4B^Ud=+A{$sARaG)n36yg_QC>MXT zPjpptN5CO`U*^ya6~GWZk)iJPv*H;S0E1L0?alXrr;P;QeFo?5Y6?^?YguJxwVN!B576K=wX;cdf7UQ$U8-HQKVATNHB zjbpiA@_BFtHPd#THEdh03gX-_-*8;ZjQyly}~ z0Q1pJs(VSO_;qB~kL%3U``IJ71g)>WaF*=chju2Navy2Ol0J#9xu5gMr|>qxV-zgt z9t1BRf6@|iJt{s8@_E2XhgNWv2l}+@YkRdz5tedZRGk-6Y;TM^o#&awaB1=zSzdL|; z&FRVP9T%B4AmixbF&TT&BB>j&AEGWnO;B!HYdLHr;+9_yzEg|- z2Qqs>6Ymnf+bxN%t*MghbI5Hil@jJkl1(#q4#2(UlPp@7P&-}4yK7jNRA7Pr48l;? zPIvM%@M7K5;BQ35o<)VoaTKJLa|q>7Ww+vUCU~_=`KvSVxMIs8eq;vg-{C#rs6h7& zlu33U!(R+_g*gcr{rhMmb}3%(eEwIYWAB-)_kc~PR&8ggBpp?(K>vG+5*QEYCrwW* zp=&Xdrb{K%!5g*MyD$IuOg5yO7hE-)B>&LGi7(RLBpV$&Tk8RIT`B}O2yp0tYDkbn zXD-69%iGUlF>Kr+K4KP&54#V3*RrsSNw`cy^_zzid#WQZ3d0-F7_ExT{)2e&EZlNi z5187o$pLwliCO`jMv^$i5q%>!RP<3HFe^@l`tQppacInMGzz z438e&1&>zV!=uH?^&YL@ukK~RrlO&`VoBQ%Zef^1=YS6mbK?da=EccWoR`d740Q7; zzVb0+%;XsAhKi=RE%#Ur)u|aNeBuLc)A;4x>=FF<%P72IREnkIQM|F1>b8#;?ZvAJ zGgEozy=(=$O|gZcShSCgr95z$ORTzX>(oYcr{VR61FVF1`HVGT4<_>gpP`hlsZ>FW z;x^E=@k1OiJ3hlH`|F0}_y1vL-S7`qT|7gJ#~tELQpxZEb~;5D+HAec=6s%UkTv&` zQ(SA{=bC1zy!K-j&ew*ydGPHAS>Xs*U$qLq3{#HNO3%NAxb91KRpFP`syZW8JnK`% zVeW?p11=*6NayBXg3gd+zV#65_Bhrohgb`ixtE_fgja|WJdeZdJ@)gy;*Soql}-H| z@}Vwjo`Tzw%7p5rpYXIZERH?)5r6Is>+0>0$KQt^Z<5p{AMuaQuy~8lZn}#V8NYph zLc#^J>+hDD#!&&B_5C?KM!D}px;~h{ZpR#J?r|U!)%nE zzqCbl-qP{a^oqmWkMVn@)e1U~a+DT=_Oh)pYmXhxeD7<9%{--1o47^;-|( z<->OKkNAimn6=L~RAjeMR=EdVhKzL9z(=vnrgxNi?PGrU2P{0+e9ABVz&e^7l3PC> zb(VDrb4U;NqXW9!L_AX7gFcO4cq=n6@#IgQWeM!9k9oma_6S?*$!pKDcBV3O>w&!e zkL;I#B)xl5kDo-V(cuI6?^ZXg~Cg~)FF@C77bVilXuPUC%=Dt3(Jr)WI34{v~8z%aD;JeWO@s^wTR zj=jJhYF=bsJ4kyYr7Eyt=z>Q@X1774v&^SxXtQM3R3KAVCi5R#xy|R_|HkGF3aUZK zF!yM(TaeRe>hmoVO9muKGgsrLl7`PubyazznOo|%t1v8T_=9)@g~sR>cst@(b`WL! zJWwy=z0~?LZ1)wJf7Zivm*JUkx-rA=SarjXYlh!19`ZXYW9+MeJmL@bMtEyz!A)(H zcGJ6_=FV_!$Y{oAbX6wsm&%zJfAmjWrtYEFY8ZMil0&cQ`IO>?f3h7iM$Kt>MGzA} z@hjKZ7TIfes_Pk4>Be+xaqXH>Vcc{$ggixx<`~$ktWG7)4;+VXiSI9D6gx zhj-|xc=AuLvPXHxo6MIC3@RRQQ#Wv2`=J#*7NUX2wV|#VZ`?qWI-9UyAOwqvF z6n%oZ&A^=caUPjeKS6BRtBhxu9in7Kn;o7W=Juh-6bKB}XNU3l0Td;M^%%ra?Q#4| zri>5wzemNl7{y|yHSu&saibESe$s6@Piz9>=VVHOA^bj*@=i1L9yXHryPu;Ajr3K< z^Z9N{Q#Nf7U+t#68vY+$VY{+*SKaikMLS_&ak9Izj>)lnx33b;e>E#rQ5xr(Rc{~4 z{DxF>m|a%3{IYv*X9yrv^pQh8rrWpO=wkFRpHp3}LU1@pK45d4kRCQ=U~Wo0E9>A1smwHB-j2gKzQa&6Ev3mtzN7T|*I(p-I+a zzi=hY4FlYAjFeHzO?*3T}7l?-0Hl;4{WC-vC{2)OgrT;JM$*D z#41m)eQ)wru}V1m=*{9cVwFxZJ6p(4#3^0zhU`A<{>jY_?G% zX0q=1v+b3Z&^nY#S{%+(Z9Ojw7f6eEV|81Kwo2Nl2AQCTIkA=cuk z&dL;-Z5dR&x{K0=#e3>&muD|x1BLZtReOC*+m7*Gvp2k9w$teUSoyhlWgVBNxD6}* zq?_U)`xKc!wYrATq%hgazwVCuV`8)QRziBZK^Y6Fx`ols3;M!HGekLnL3I1lSL!>a zhVQfTFM2B-S=#ITuii>eet%D;6?fzQHH- zQKI{~sQ0evLeOnEg?}$0Wd+9}37Br`P)hx*s=RCqFXT z>}|ZXk1~ZVD&U>^Dt*|r0zL(wkrNVq~w?l}PM|3V3N>Wda*e zz%BPFBbdiFeyg9-hrfNF(vAfb@DumJkW#>3?T^o^`Fun_2!Ef?-|YwC*9u5Dll?ni zm&?o7-#@W=Ti+@F^xDbeinJU)Feir|Gn18nk%i|*z!}FD&2xDP&qz^%`R>8!ShEcI zrXwNWo#cag&(TUxRE4=?GWhndk6+Znze7*}~kmEjSN+R3w z3LlY%z`d>sh48#Ir8|4UkbK0D9Q!XwW*CxbhUBmRg5&^0(yU3&W4?w^?aNeV2=DzM zgnoTlFZe?UQ^A)XRC=>dU)H@VdYMlc1FyCiLQlLx-uL7k9)i$xLny;ASM-q5fsHgI zn;GWP$3im3kPLd69~ldC_`!|vamd_5FY_tmlv%9oC4P3CVr6??;tL+ZY<%CtaO|y@ z_~Az&G+Ptu!*4zeOA8Fi$(rN{_Mjou0u~>IrB((%(6IFDqp(!FnOnvysqD~8e9Cxb z9{YMTuN<%RXL~kN9=7G|4({kYOy{+Y*2PzJGo8+_9f%1HTr zoj>UbrMJ9Q=c71Hzxk8O{qi)OzvxM&gFIg6qcDx%Y7+SEb^fwR;74eD6r-jq-FSz| zV4vsy87O|uWaP!^jSZoYx9LLNr$FdUT_|@7gt#b_p$pwN6+(~eLa$7P(1W5-lrEI= z6l!D9g|T0oLO=4ZS@3DcG`RdVU-FnTNZzcoADxbZw&?6nrh~m! zXFsH~AA1_?M|AdQPlG*7X9w%-r)GfNOlN;N18h%?&A!>dtuvJs@^Lg*f5>(em))3adz&EI<(##82leV$)=8fAaLlV*Z_bw1d|I(zg2RP0S+2k{LH zlx}S1i~R5c^uuRf;MRrcNRPe1*DXZ%@BAV^wh(xa7x>Ucz%4KEjf;@rzrMiFE>c#o zODcb2u`*OX!~JI~y?K*=DS_;@7x=Bk;Ju;p70)R{d8;`X*nW8qgXSYI&{$>R(fyUC zJa4pO;$v;fU^Y?Z1vU)4X(~TqgYiU_N7_-i_X|AJj)6H)<;U#G7*^vTr#ka-OB6qL zNaa(O(8%H7l}j+y?sV|fY-J;JIQUumoZ{f~mcm$f6{i$1a-XBP(=v=O?Cte@`U;e` zbv-|_5>=Yy;FnfFV8;653C}B$GHbVJwRjkt$zFns)Y+294S3%+R zbsP%wHm+7)V-wc#H&(;N!Rz>~)k-M~UB^q;pvGoh2M_H(U8?lr_O+N8POdGEQ3=(2cd^dQV>EfL6^KL#t?wu7&?R5nAi`$QQxQ zTBE7Tqj~-cG=KSvn4z1m<&n9{0v5A|pM4qOY`UiSY%W#s;A(zr1Ij5`&7a$X;e5#& z670i2+Xzc5R_oGp@tLcf}Y628XCW>)-}3p2J_-7UE@1^l1A=J0AE<8m$7t} zUdAv(k#Q4_y~3#=r`uB^}=eQ@MMnsV5u#RB``MQx9)! zWcIliKVvaN>uOcut}CyKv|GrjD=CO=U8OuXqMUz{QocS|xQ z#j-wQ`MfEn9zjLsd~7;!_CjZO+s)WsJ)X?>OfgwJv4NqD%7swgX@)7Bo2HstVvkj~ zMcLnQcA#lti;_Im)Cv+G;v@xn+mj(-?7}pOl0n5wrF zfxM^^=QA^Anp&}0V~RJ+-->LI$)OmiiH&zNJ1WxwIScbH>} zXXkOEKgTqet$46Fb*{`grvCIGZm}kh z-*pgY%cz0Fd>l27qVogEMF-j%CMUZJ!HeCT!WS+wMMpc#58~Y5PN~Hyy434d{_!GH z7f7wd0m+?G!GWem-p?a@PHEVvEi>bGJjBUFS{v7#_N6*g}z1<<~OU4!mFe2 zh{EzlqVV7#y?zg-xXv53qSJ~KcqC!RZ%^J9#e5|Foi%UfX&49|#J^c$ijN$Eay6>x_EH5$&&>fqRI<3!p16VnQ216>D$s1zq^ynzgcFA3+SkyLe@v%y+Or( z%c*Y<8pW+EOl{ey7(R7{DZG=~R;@E^#{cGF9@So>wNnLb|I5)9Re_0my;r944_27I zV#ydhL}5cC`~4*u3s9#DaL>Sfjy%Bv`XTnlc&C*!Ii>hyu4%r^l85uOji$D3)GlgWnj*Fs@_K4C#kL9; zI`nF#@U0t7$64zAd>%Kw!Pbo6k(&_HW_QMP8oGAz#Z9K@CJ{wiJw|HvC}O{bQ$325 z(NyXQ{Fya5G&`e~s zHY5^S)l1AvDt13&`pu9?YG+7{Z(T2OHL=*Y%ydyEFJ;`R)SQ^srk+1Lk^eu+t~(&A z5e#FAo-dMNhB8FlitVnGFsAtriiqGH1q z6}wTRSYtGa#!l4Z_u2RExZ@<>U%r39ySFntJ2N{wJ6ql^;9*qxlzzMU{#kuXH%QEJ zn<}{30!$luvbm)VYRDz3LZ4sPFHo`8G_zvOjx55e0jwMPlU9TlR)i%{Dgxww(ZI~| z^(O>HaoF(2$qO0LMev3V%nxqq+vqqvteq8ptV$7lV10A@d-`7$k=Asu!hfz>1iuq+ zZhv22s4b8DH&Jm4{kPRPJWaPh#?&_+eYjE9`%v;jy&KJZpx+dfrc_dA1vyP9h$%v@ zXhSvwIis`=-7s&Zh_c@5r%h>vx>mF`+L*+D3n#0a_)|B%rfF7fG>3y9>}-W8SQi+p z4L8gg_vf0XNgQ_?K4HZnAnnis9r2qunj>)uu#?zBbl& zc*MXLN3E-7v-qkR@30UtEVt;N@a}(Mp&ABYY0x01&D+z|F7mi3*nHjAnZxl`>F39) z()W1Jbn?BDrSIpA3+WGV+<%Zh#RbdWv^_|(y&4>Whtihl@G zU>GU0tUQ1Hp33uc+*VkN^U>!OY79pc*=uZ#Gj3R%=^}9Nm&XFL6YhRz+`np@PH*||XM8AmQ7!XQQM@4O(-I8fG_sU9&L=G@CEPR&)|I$F+%z1|;o1u3*QLZjtvkK~ z3^xts(a`>Ia|KT^UMra5%pZ7(Wf*=Cex%SdUsTqaIJ)g8R>ITl<}V(1cg2En8yRaN z+m!|5IWY}e7PQ8D6qbp97 zUCqoL;>1>17)t!sns1UK@E*UKZ?I_%TMraj>nXOC9hK2i%|E@Fn!lbs|6QxX+Nt>| zxh~3Wt{6jh)Nj^u-(oeNm-|3;NR)9~2iE@*#72(0NuZQ8>?Sc|H_2YDb=4gozayx$?#Sv$ubPXc z0{Av0-WK_KsBP(wXKmPwuZQMZ_h+S0ehX0)R<@v#EyWqa9<+lTp$~OwB}NJJn-bjQ z3}L>qldBI6Y>h-w*#~AX5NEC*4T}=~5N&GCZTH8S04D2J}(GYey|8Or0r-sY9J0 zAozLINt}Vh&;Q&m45R!c@g&aOr*AsLcEYSn_4%De7u)``rCr2{IBEcHY)TinG36Hq z?=85d3bS#~l-yPPk88PR1=YdWqnb#xZX*k!J6**!0nh(|!?2dLx*J>)-!{N4#i1S* z2{Kxk&vg^AKL{#S%6av^m?GS4K@+=+_q5;A*3P1zaK^gX1A7bnX-f~WtI)4G-;%J3 z%JmTI)3u(W8y2j;wz9yzp4C)PM4o)px|LAbFA?=XaFdmin^Z6@y(#$9n_gld<>22t z$#vC~6i38Sy={oL1f#Lzxs2>OLS)(su=`iSemqt?N}Ir7-rx*vw`o{$u- zGnLIitts#WC1X1Wm+P3ZiNm%FHRJYX^st}!Gd1Xk=2PI{@f@?Ac_-V)EqJzj0YCqP z7CXI@V|#*HP}_khXf!+lZ>P@6|HCR6_AFTi+uovRn@q>b+pJp-6_KC+1C5nd8hp=; zA|s5J9t{%bXnWA)zlENB$4$q|{E~IvwJ4-kV!&7;J6207Mhe?+<_KWx^@rkyfd9e- z?>pTRnWhUbg7fgrP!Sg!4246$i{DUjsp40LiXC-%^5=X5Ng}l!CN4+EcDF>WX3NJ^ ze%$8ZKzC5h<^(Da7l)uD9^FjcEOTwRLZM=b29PaRQ#TY9qhS6>?5nGd1(J_y3jXFA zAB#<~7b^mT#ftc=guk#>^-ZaHuBMD3Zl>IM?&gIfAcJ5jYhF5vx5b-2v~09ESy)+? z0zMHxc7Oa#Cua=_)|835sW*T5i8w(gG^t0PV?=}g@w}UQ>O4k_^e;|4-P@Gm_cCU5sh9&#b#_OWy&4sNfpM527g3PnrtwXtuXY3izy?`!<4(plO~Q81Dh46=w8~C zF|f2Lw{01GX{s?zoo`HvL1>MeHr^HOtFopH+1Het=Sx>XX-aWQX@12h^~V_-{Nv^l zDShN$4EGjr-Tny|Cl)z!*na`8bHjH=yJ}a|EY8LrRBHjnh2H69%4i0$nw6pD3bRYo z-;>4NLR=ZzF-06EG%iiyM#Q?M%TS_G9MqPVnFd9tDT?l1&ZcNn{s65he3i;*P*u%h z{?)e@<4#yh@jUmD$I9nxBRpoC8KSEPHzTfVV}L2QL7=&MifBYIoCuTnZmQU+Jcy(f zE7+liL#Byg?;<#8qt`SsinaH`4%tfNF-xpq{(73YPOE?Fi36}bq(B-qUA(I>@I|;O zLsP+&n^u7a%n&blj`u7iKGBBulqN4}PAzAOwQVI8H?})LrrbBdL^H*pcM*8=a1S-* zwhE)uGsSwW8psw#n8C_!t#HAEuJ0Fp&H1xMf2}avgZ`c)jt|V!Lv!y4>>pvutx=H{ z&J_boz~IFgDw%S>s7y!ZqL}I)IO#XS%;ur)Nh?A{x7B%6*TS=2X`# z#`J&>ulfV0jY*y$#2GIlhV+D=?Zi@z^-UQoBB82C)7&bW#a`CD2`8x$ZiDiwsyAhf z(xcgmruMLOJx%(L==Z*3-Sd)e;lo!Od#Rio9Fdy)*v0fCxOrLv2W!tb;B&L+9c#+% zUJKuRij}Rtzqr>-gY$GY@^Nt|8TnU4dw zM6rmESIm@=E`hF0o{Pi>%s(DJBc2KuiS32+)v3dmV$Xms)l3;}V@$a|)lFfM{GK+A zPZczd;V|-%Td*VV+LvPUGRgH!HuYuvUIV(QNwpS>lbFuEkS>IocPtiT1!2A$JyIlEP`^REeu_}+^<%0C3;9DqA+Kek=x<}w zp~}VpC10&F!!mI|Xf}AvgZlDd%1YP7wUg>lkq4KFUud(*uv{$bW20xUI+KA)FGBTy zv0OY7k!_>Hb+Goboktwpnw4R#-w#)a4g8f-IhNok32Oa^6{4YTF`hWqE$FjIUI&{v z43iI2Z6dA6CfcqPYem`%xag2owG>5Eo26`ADQ4Hp=I#3x1mBLfeerC(=_QCpYF(p` z;^4RxW++(uWYW2OU0~KmmqN-yCEEn0v{hnRW^L@7SBZzT5%#7G#<>ykub~yC+T8$s znJ&i0I~Y%w%9_QV4#wkHDMk4m45u(%46RwLB(;e0CXikP0S7D!2NTwk41UfB_Ma8M))-#DQ z&6kJIN3x7@P3U%p*i+aNLX9_w!LG2^j2h@hJ`1A{@m?mbNr9{}6yWIp0^U5svcrjN zcsM&Iw|4~XD+$l5B0bt5M)((ND5-(ymFJZ+*^bcE^VLl@vwgH#Y*m+2FOK2R zHWa^)cEe5Y1uoFz?Zgc|jkTSWL?6w=M*q?lv91$uRx7XYwRlt;^R8fa>sI0#Zuz|E z?_k-V(arBgAMTA(?KZ4pp$qh<(z`{UP!4ry5uAPA5po)vVKKcG8cNJzr$NiV5v$UX z-J*w*-N9MfdOe=~3Rq}p&+cIVe%WFrg{0j zyrK{@G_rMmN)6x z?P3DwcHQ>>!mat!9pVUWIIldf7*obh^wmG%0G$d5i3)InK5WhdHg^jB^$EtBQ>&d~ zX+^fwT1BSz;Z8BatB8Bs5M}vJv6Vxr8syT`onj6>{N5V$6(B>r>lF#=8o8D@QLbx$-z__?-M_# z^(VyAQ=EMX3@+i3s*DfH@r%}rl#y1a;&b!UXAoR$7;CQwobqyK&R^a#W?4>`gFgTr1(;M4JfiC z6dIF`Qc~9}bD-rdXx7Bk<9b7lQam^_s#1Qi|fe8tJ-%tACl52Yb|5SN&=@6gwC}s{0ZKL{OF`g@K_~HMi zxYvipJO@|H)i+QFo#^RCuGpu8gHDuST5&?X8^a0VKzP{bfl?~V3*lyN*;(dt=Ar)8 zJY0_rw5HrH0?j>AqIFn@BKwZ~H-Y?)iZwkE8l@pDDtLg_nF#6LKPvW&-V$O8$3Y|f zCcjWznN`(l_>QJ*3!APUeJ5;6<6)EAF)=tEjW9zEo0M6hgokQl;?aKXKz_W4##Fbh zW-%|{A?!*EQ^TnsG9DB4wCRLcN-;%;aBB52gi~ogws2~Ph3*{_>nK=<8p6mLnQ}Fa zsmgIoQY^Dr=p!HMd0gD14DgGajDyM7Iw5{m0*1YD)4>yBD(J8T;Fxf&&Pl?e2y`{c+Vld^O z5<`Un77|X28}#)o7C-7ZPYkD1r^Q4e$U*^m=)!9#xQ&E2Z)sJYSf`{B@UMB|x7x~% z?u^Gz|1<*LcUFwCQE>>_sPHV7xgOtzrQO3{(Rj_Fm#%dV<6Y-s{%O4XGFY?tEuA?l z`uY9Cc$dC8Cx(|a$d!ULi*Kvrm^bIdYDLUCgmm@Ki)W&oS>f{&MSR<9)znxWuUKw^PqrzL_3uVY^n+dxu_E&tK z!?aKtkMT)&+r)%Zf?Lj>Zn%T$PoW;v=To*$7wyg^x)O#1# zzAmKDzh#=D7H|v&9Q&sN9G8nwfNi;`!~z_bi-2oeE-De1FBiqzRw3`$U(MnT zc4mreh?}By8Rp1yv6{T?sfAK8Bgi}5P;=l5@wV3e@o$|qyP~wR8fY@MJ$Zxe6x*NB?zdv2Df`iTS}iIK7L}%0 zl;g4yCKheWM#tRMWup@F*q4n=%8cx4Rp9}pG>iGw_6~XMR`69>xoAmgibV|5hLnir zuSB*l@8LUCE?R(d-Y0z92p6=f5*N?Mjb2>?TGETv zlU)C@&^1;_jUyz#CEM89@+B5zUGG_~WkK&EaEjLDo=aL*k8OTzp-GH<1vbgQcuhNa z<;?;+pg0qU>6nQ+mfFg$Gy8;#BH`3~s)SYHi?6_zN>reOPi?7Z&78{TP^&jwr)OU| zLG9d`JBzH_KTf}Vf=d1qP1ZX7(oGS=VK`k~Vi8_NV%S^*W?sT5RbrJLK-TG(A0(Ff zu3GJ5YMLUm!06(tvz$2QT@3L(K@GRaJxLUHi&zsgLVlyew4mv>?De7KSN53?vG zs@P!`WuXg;`)?B{_uzy01WJi?94bR{W$%o~+qkmsfq7PIv^Q9XiIaV<3}aTtc4 zYYmQ5?c;aSxv@$DX0NNbu};-F6JaHc(U6|!NWeBm+w8`IhdGR~l>FJ@rdyuDv9>WD zUt@nK|38e~Qry(BTWbB{V>gAab?nByLf#=T>d27ejQB`*7Nx(Yvkl>dKdHU1omkp1jRSh*7$B7 z?ios$x>$mXsm?m&DJHBEsSbK~?xIA^*h5u?DcjUVgs54(+giXo7G!TZG|`haC_yO> zmU+&T&9*g7yDl8`I@XKj`4lzwREL?1UZq)YB^u-T)cA$#P@T4*)1_IU0=4Jm+Okei z=*qCLcZ+r4ym1-Uuw(?)znQ5FE2kCe{6X8iSy%t!_QcuHxSDc5a-|R-&PK5c*y(P{ zc;#-&Jz9!7`>+TnC}%PaJ8UA|X`v5`lC-~D=$y8Y_W3Y>><#1BZTPUyg{u!KsVsY` zxW@E~h}y6nU~y%7-xpaHKD1CjWSP>B`Ozw0_Ef=Yi|KWBMV?msv5QLZY<-{N&z1;1 ze<$B^?1gTMrjR@XSWVZ}4=gkqFDoC=-dL6(ym?3q0)P-^MR0Ed1aG`F#*;#;dxX-R z@@z_A_B-v%p*p7ovg3Sw(k6&CXvHzPYsf3|EmbixyoPzF6_|G#fSb;e)Gle9q*=^w zCWDP;Tk(~FTgLZQOu2zo>2wflTa20lO|^G@3bnQERce!9z5F!bcc`iAFb@c3kF`p* z*ct1hwJ}D+L)kp462{c6EPNo=3Nw*M8AKpoV^grS;!-R#k$tJ zZy`5K%+$HB*67mTs8R%bq5XkM1+ZGKSAVt8*KaNK^RKkE8*7RW)>l;ow2um%1ZW39 zC;qBtzH*;@D}#998xy{oVb+*E2+Wq%2lyXH#O820IZbJyHIhHcOa&F_+H4fe5DHjGDU z{TYk>uoUV~Gi&hhpeVI>S!|T?r5}*$&yA-DlG*^l^m%U>n-9IL!CJE$cP#Yn-zs|z z@6nu^V6Xq*igYeh0qgR&g^YBj5^E~lxJyDUfc1Y<`!K1N4Co6Cs>4-i%3Yf99-tcv zRMq6(w$N7qAG)m)uW*;1)CRm&0X52IwOjy>2Y9d*eE1Fxs{`E?eOr z-l1D{0iS1uZ@Fcm$$)3wQpvmAp`P)8$5`R*0S^VdtrfocHl3}Hip`^xSXBGtn-)6o z(n5dUG_!`Rr&f?|Q~ySQS5@HdZ2=DkJP}XzUg@2U*?WF#)Lt|VicaI9e#RG7O}W2U zC7pp)Qk;vmZPqfdF3SEc^IQWftrdQ}NvoQ$rq0Ixs0oW=nfb7<7pfG}E$W}3a51_z zxNHkhFb1-T`6@W`CS7R?@G0t4AK*W4SSSah)!%QZ;5IiYsX4%-RB#%={Q+KJ1^$Q3%BB?dtIk8od7nf;Bx!*~?8is$CIQuV$pT1ngDhNWio{C7&x zhkY@Sn+ZZa9?^!r%q*k`^uY(JP+xukq55C33-tjsz=dk~Gadhc)e^#VRQLfiV8btd zHBDxn$g3~&>Y&^M!v&T-G4JAO%GG-*QJdhS_IuI%D02*5=T%aMu4(9f)8G)57F?9~ zD@+!Q!`{+YrRixh8;CL>Rj+<5h@H7?p>==Ku%&*er@(7;y&tQMW7$B$uRj}IIRyfrRO7~CrH65@N0mX;1b1B5hra30_;zMw zD?fmRv1F7S`zIv~VB!8_ezxo7Q;_3&=>#~XHTU$V#RFK|DjT6LepA#7?B;%fqwe1a zf5yT5Trth|d?_gQ5zv+T+Rw;sAX~{tx<%|LtPH{a)bnL&-$3l(e0B*lW`Edn=;-x8 z_MR$ItwE@#zc1VQc?rUtA6#WPY!GY22OC9n6*tMnybs#zvCp`>9~~J4pZ6W;Pyd5n z3}SI5XV7CiaSeYg9hIXtgOOnoG7S7fZ8DE9)84^oGG(b>545P-07>Ar)+H6Z=rY9( zfuAz}uKKY{7cG>Dfbzmc4sWW(m5f6H?xBLc#sl02;IViX>Vz|7_+9Hm>A_N{ln!sN z`99EGVK~EuN-rML#Skgh)fb5O5pDV?^b&+mFVVJ-K=7-FWQj({cELh(0N!zd?tRRH z%bWtb?aD`f*Y)v>lg~&NBDb|?_(ruh58Yj(xZ`V9C|EP$}`M87-R5I zQ$}DoRvp4=+9=jG@bP-cl!3nu_){=G3N~dN4Mw;SLJvo=&=N2>jUPizxufvS@@SSM z=yCYtXjV~J_JG!oW{q6U=PfiF;qa^n^k6j0m0)K0xK+Y|-)yL7JODRG8VYQQ)jws; zU6YU_0)Pq+%#%N5zFHytJT3ilPP2jt0ttKr}ksmm!M<5J%$C~gQ=!eIF`jQtDb6&V~IR% z$~gABgO=`NF!2=z6QPkbb3A*m1Rbo1FlF4w{^XA;(xvgN5!Zp=1Xj`eQ$&~iHt`j> z&nq3iR0BW<06Yc(zz}cq4c7hd)6@xULzzKmc^GP;IQ-Sd-+TA@K-N4nmM#%PsrO{o0keOQ|C`C|O=KD@C~ZJTSkS0=EDG}rr~+^? zRY2B6O!vKpP~W2>7c-p9Foh5EVL5rQoIF@go?qf;rExgV0kBG^wzTy>8YrLZ`*2fr68z!)L#3|UfGfX6Y2 zz$M!V*!X)?X)5ew5_YRkWqksAfEf4U+{2&6#yQ>_rU0)q0`95ISK7o)aWpY%)x{?d0Ewu42#-^uL zR}*`Nc1#ESeJgw{;H?4w+zLOBTj*v2UT{arA5sqRhX|Yf@N~SsaR^@kR10rN>0dBC z?VQED;)C)mey4%X58vmKl>@U}6E9C$DC7%GChx@gpW|=-?wLozYu-7TDnkn~u z4Qf1_RV#lU`8IHRxYFEqlcQ2}lTtKuHk%VSDiYUV1jgRc>9RD~Y{1LffIQ=z@^Fp! zi!&71^0u7AI_k4CMn%%{Ijo$}^$zWr!)ll3Deur533^TL5Sz=weW#zc+wWAUgqN3m ziW<#j_q^``uK?wsVdQN}(3ql9%9!iSmkbeTAyHnT9fr|~RnrDLnBFiz(t?zn|+>zuUf_C1Kkbz9~q8nc)UQ1qm!1D9WiZZBrB z9%GFWtdE_ z)##E+9j7^~SqCA-o35^AR}|G9#mKQ4ww@+8q=V@!D&PplN<0(ixHO3H#{TFiMyE$< z)izwT7P^Lodag!+j?_D>;T_&Fn!JW}Lf@~_?@Ezt*>vYZeprh_T00c-C1~+NMx&5X zM^$Hb`WPjwL;XGbMXf&{!0urfR^}*;SsNA(PjG@Ykesmyc3R z1`CLL3w%z~c9Y7B_YZD*b=2bL_|Co42GH!M1UlNR$46;$270`ixJV|0Efw}3rT7hO zgwXE>b;=EFuJbCYYtHnZsPX-Bvkn`H7U!?_A=Rz3+lbDQavt5)IeBeZlg zs_@2Dr3&2&4_oLA25@ijRG7%$!d8^JTUhwm=9(3md>vWhQsGoJ9>{QJf*rB>4PQ2A zlMR|vuadBptz|RtyZcqj+RDnix??%43qGKFBhu-utQs2ySb{PZ4yMp=ScGsYms)%S zCZAqW?aUhpcQJY?eb_u9n?-9`?jg(^VJQ18ixb8krd!{#tsa|!#2vwGzP15 z?qMqP9gFrfDlosSzJS#LA%3MEC4Yz30bjrHJJ!d$Eg*%%YSlIO)MU=$E(3tV?^q4L z$3mc{OqiiI!XFuitHm{<8dKI0TJSwuUGn$L4;T&J#rR6WsOk4uPSw2P*>B;>Gh6l< zN2sqEI|t&oGuHr27^SI5E*z<-jL%C%>R23UAdt4Raz2lTAy{v$(R{*hHnv@>J$E~+ zRQg&xE@c?wh01;0CR!2| ze_-xlbvOY>9WX__unN)l-9nW6c#HG^E*ue`=W=C5+x0Z6xC-t#!;Qt^=bYhb#o-5> z;p>aTzjcQ1EDlf4r4c(>xaTHl^0x}wkNL&dntC{|Zzro(i6?3rChXCKg$D1(-A6}H zZb{lyasDT(%V_GM_rg^qK3M|}(UYAlI(98^6E3@$ZelEcTjEOb$qEh1Y`@{4g-W5R zbC<+#aN_CvkoVbPYQKy51{BMuT98!xjX`xtKQTgfr>u zv}gD?Q(t4rWR{1a;1~uxQA=FuyFG{wX1h`09_A~2wQ-k5%*Fa}w|2uNMAdFHyoi){~XT?|@6Rb{{6ZN?oFh`{3RRFOo+Nt56PC4&H)c z*aL6xtl<3?dVG-*bJ!p(fnlfjcRB1Uecr`57wWK|EvbGg$3ojH848~BYu*vaegb?x z`cm(|E1NY4m)In;W|^vjg2?*->mhu2kwzR~Jp(#oUZDg2)R@YfU+;ynQ`xM)QO{lAB6NJj=$KZfo7{|F;-V~PaqD*B*>NS~DF}_Rqs%e1+BUw#yUDId4x8?0~ z04o=~Th&CEzN;lHmhm-N6lgqXtcle{-E^TNxhy&!z;yt6gLxjPJjMBTnC3L`UN!}0 zoQl8c_?v;hFid5pYOs(w3)7k1OHq|0ENV*6eHN+;0r{nsj#BU&?j0o=_&-Wg!$FdA z4w8&?kOV^boA8D5Uz*ahm%W|1Ux^Kr`o@{l5047}izo|i&eqNx<>j^MD6jT^ zl=mbo$X0VZkk?kWyIo#=8n3kvjxn4XnnQDrVYc;d4rLv~c8sezboLnAz|$ujXCqq9 z2d8yGg>UIu?V%Zc6Jv^>Py)9BoOyy-(Z)&;brrS8O*0)MOmv_oHyq=G%ZW1QpvfCD zbEx_WRWDbR;l9V|t3Kfqq-pL?w`sLkmx^7Q&hwx^x1QMi{>N z{lrEK75CDdpWp=!<cP0mWgWxsUAnrNS{-i0E21ZuPQBvv{Id1~{&Jd}c@$;BS73nc zZ;Bf~M7g|kH()Y)v={57%mMTR5YR z2luakq_yW+mGF+ZJ9JbX>!cR$pa%Qzy~Kr#a3h3NnR-1>o*USQXSL1$>p zMR@b+KUnDfGqe@Ig(l^V|*q>SJ3Jalc-m4|!N=rT| z-2CrCzxkNmvG!;BYAHAL+&XKrveEH>!FK%O2ML zwDUFgv2bn|9k|B&vwOR+PI#K4e_@rUSUZX5D37}v4L&F49mQ|p$=Xq5Ymw&MQS^tA z@s1+DurQBz6x)Gs%e(4FOg>mu_pF-QQMiBxyp8FVP7}*L?009IWM*wm$fUeqFs?x7 zU-%0PkW?>0lM(8m7I=jna zFx6GD4FV_ZoX6&9*gC z<1@99K8KZmvWs@y!Iamvo#x=X>=e!c!rTvK|H>K&FMl$}+{g5MnWP=XN0ZtUw5p6$ zw}y9C;~m^v_+$lb$8-pW+E#PK@w~zB1X!s%XvAZdqJJEQ@aO4cwuGf4$7 zTrZQhQ}{C$EukAv3v(|=ou9FG?JI)`KDE6ZQPWdh`K;t%L*0;Pn$bLLJrAj0LWk)3 z-Ww|+qz3FX(sBw5YZnTdzYK0oCcM@y3-|#`Yut$q+)jU@fGXR~&>9$dj=yfeZ>7`B zEe8h%`!ew}L!ROsVlxcmB|^8R&sl{2@%A_u^YG`aiC&BE5 zY{NE8yB?+Jzu8n_#WvddH$u);-%;-0u$j@@=x?4rWE)L>jr3vP(bCsYV8S*&3lL1_ zU$ao*$u@fNn$7XOg((7F5uD+w->IE}>o!{Yh9#8Wg+h497+FixDP)&+^ej=+WhfYp z!i?I}H|%R)KJB7r#x1Zw=3T*oZ)wL{RL_;~iCI_+DH1J5z8OrNEv%*#g_kJ2%(bv~ zA#IV{(NAznL;4%)IUqGuOoQqcGOvh9+bn+7c@~9R@2v4kfj(L9f2%f&msK zV>TADkF@LvMoqc7OP)w^>~6M&%(>i)EX5u_S|%VZ8);LOv`Q2yNTY<_R=`96+U1%r z3X-o-`Ur+gx%j(@I^z7LP$#`q0hdimdSTaLsw7JB@}+Mu6$%{6{+0#0xo8Z#q9JBt zlVDmXO65FigFiLA^~s9;*1SWM8tKcN{l?AypFQd`&Mrq$J_< zuPM<}YUzx-+Ea=WYHp?Dp3)hT+$9fZ1hbbECj9X=UGb7C3;n`KS6XV%okHi*(sZ_K zi-qPMpzEcj@*MWMv=l7dtV-p}NGU?E1KfYbv+=-b1DrBaxbMQR?bF}$zE-{3ur1{4 zExqt<2D~A`h63I;`8bbHCO6(f;XV+e_7+O?kt&pJ60StVGR7E!tSR7CS^aC8>LbMo z<+jjnA8DvvhE}MF^zvB452VIrrD!3n0u3(<#r&~_=9HDX1)kn)p%jcGBQ@T0XL+dO zjAtF1Wb$#wQg^AWqKKn`*uH>cmevPTh_4jIRwC2L{d|3}R*N;&6lQMf)aily9W{KPwXfp7g$3wfo&6A%G((32Gs{y<%m-UD$A!`nUnxe=M$k)NC=X9R zKPkv}>K41Ara&>={rB0dPCF0ulWGXNx6)ESsjE*OEH|%+r7&zN(^V^_F)?EZ6EMq%|N#4d+9}( z)L+=MnRkV?ef6E5PoSQ`8lUH*Y zYXFs{210Tc{aING_jn)KG-zb$RW!T0WKnP=7^h zc_NO5DzsTCHH}FNAYwY4&jQT)tU<@O78fS`yqd@ko_8-QD1 zQvlULRm}^wdv-LsJ<#7bj? z)hHtt`Z8{$5w%d(r`EE{{tsoX$C))toXVPHE$efX)psMksD-i&DC0e;g%GomcDyI8 z5}vH1Zne>|JlQ}SYNPDCD3i-MGXs1!{ugpKHWW0&MI4e-*^fByfc@G+vp8>qIVMhu z*V2zwB_H~tj#M>qw6z#-UQFkIQA}q;f!<(D`f^=ybxzzsPwGgGgbo`hwl3IDu+qH) zcG6q^3%V^01$RJqpcCD;oPEHWf&FS5Xm?$yWsuE+(%&m)L178Tr0fk8Tu<_K`Fkz0 z-G(Jmle$ucM4gqJ49?BJROWh+tLVf{sSUV9QyPKm(Qd{_-c&VSY9{QH4I;|7PZWM zMQf;M4c^l$7z&QJ#s|!mH3b~*xdwQ^*~RfI8wx@+ArF%=hsb~PeNaarA_ADK9IOX~ zYBakv8sk}4r1PMg=PyiGdsyWibT)zx+_5feemc!bfW>F7qvHuuw}3(r^2VChWgNkl z9-69vs*NAXP|&#N^wxv5my)*UD&f$o4mZQa4Te#WF_D9_Oxrg9Sm4(|?bG)1^D zW}SIVGiip_uK}0rDK5Kziu+phnwq?@OW{OU(R5OX-auJYPc-5~WJf zGgqO9#jN$)iD#Ah-?tO@Wb(=9r=7K#p$PZ2yqlDaXIrnP$+xXELWo~OGuomNR9wS5JU?!yG8MFyJ{2@;Xhb{oa@W)8MLS>| zOQ*#4=n^-i^L{mip0}4i5N4!Pw+;Y~PUpR!AMNiT4Hr75Q%pzntTobUYe%V0SIDQg z$!ApjL7t$grO2uJ1%1|?uZ&5pRu-4D1~&>WCvYnpASVn_3tJQP#oOX7Tdbk*BnbHvstXWBxwl2Qr8t+TG0D(X{ui<26`>JENt#dg16|3Lb+HxYJ@V2Jfo5 zKk-}(q?MPuQH?ondujJr#4H~#G4~uN?a&5)`K7}DE(998;9!U6W5OoAsbZsNH!Y=@ z32;J3P%M{qC?|=#&>(A?t$z&V{Uc^S`BRr(7dnTmxKd>xHp~CENRd^+!5s8!V z#w7~@r#vLJQRTI$aA8on(53Uz)sS?czcFcbT5%3$en|(WNmUZ8PNJ9q`NaiDMfMp^ z*++m4MS%Qxs-7yfD3OknA`XGhKqoqFZFI1I+nkEY5kC{%O2r(+9}CT{(|Mc9T4?s2 zfe8hn4X#9;C0!T17g6|ZX|M1BE*zb0Z%T>;$@SGLP=wcIO^Y-pSr!x*{2s3gu6j)a z>M#dWR~lRY5Ntf#cOi|LBPBKFX}10W$az|oaGqc#JRr)Lln25#JYJ_eRl@L_4M>_R z)w2^0G@iv>rtRlSiT^L*rqRZv6;6ax9SC2VD_sz3m}u)fG`tGX)jX-bV8GX=^QHf^ zut~yuq40%#*3u`7Uns;U6CGjYtuQ{AS3(V))^t;^ZXC{@PnP-6^0@it>kBZ2;X4o9 zr0YtVc)YW=LMc-i7XRj^Q5lmI7v6e4U`Tt)aT>R)r_pGVG=ZAVO0z_SpiQG;CMlsz z4d4|O2K>tlXs-z~kGtp5MU%8u*u9WuERquS6X#*Ld9AM$L_rI9f4E383r*+IwlAe_ zzQ=f3x7|%^rhyOe!}&P65I1&8zOD<9kMme}0rq{OgD~J~*~L>RE z`M|?%t!0+L$ZpOx$1jnxw8EIVbZ@EDqKt+YG7V<|YpMyl_CQc;N^yiEUlia)_ye@22K<8_)Uw-LTJ)7*_#Sx1xgL%nevjj;jE{f|^F@eh>4y~{!_2gVgPWUF_{)2iOZN)+A&;|e`4 zWAk(({BpioSSH=mCib%u)Nz6s@_`^qQ%BG!IonDwyU1N($TtuJifMBcP8D3T{_73aLpm1z`2O*;bLWg>*$^D=|bjAk^K7kO2(wf;H(4=+_leQk20}iEe^1 zs|NE;(>)F{rQ^m1Ez-I4f)TTC=#>x7rT#0W9YO}$$12IU=ckaE_bmS?kg;A-&$8a# znDlgZae=OKg}_42RYm-RSVNPJwMIl)K`Q;e?{oUN#qj^7k0?}M%9wP?iT*xLA22iM z^QjG9h8AV;KH=ItMTUfUUIwmf{C~?pr#uj4>~<<+?L6wXS_;RN$O^r#<^Knr@LqAb z6TN9xolJDlNdmoHCHW<2{s(oWg0#_z^pJVfC>^YN;x^@U$v5F9%;MjQ-ptdO)X#}t z>v^=B(+kD5$eiAR|Ak&@V^V?>z36%7xHZystuS?#*>|0^R4ZJbOIz1V_X1Wak{b$y zP!|)Aj-$!Y?!E_$DdXwI7ms2~THG->p)(JNBw5(aB&*P3^3>I#0;vWLFggm*Cp>Cu$0wjsyXoo>7L%N zLW-3DZ_T&~j1ve(+KmCO!L;XrEYU|f(pw>?fqD3T9$vRafgERs5fchid3fzhIR~U> z`Ya?+_UTgo=Fo$Prg)Avhk1@JQ`H;`rda5=6g5YBE^=%`0?*-Nev>QxE(qHvbAf}+ z@^PuE;2S>K&R81u1@S_ICR3x2%qL-%L_5LQi4IQRfB>2vX6! zGfx_)bzk=dGIVZ|`5eYf#vv{~)bXq|%6*Dca#=dLSC*;IL0K|CJ}YI5!6!h6moHAl zq&0r?S(P<)3exkY3UFidbeo!uo3~Eb^nll)C!+`?vS;?Bk6wd z1C+(HMtp9eDfn&6`USG~`kWyBVDqNO(q)~nd<^wHCdcZ8&wv@^R?qzSnS{$pMt^R0 zeIX@ih2Ec<+rQ*PSk0&Ay|1LRf^g|Go+FsDU&H<~J8mEDNYOSK`IKUq9%I?wTT#K|yFWmaXJXj|WmWB1B&8OVtT&CMF5={K* zUXzZNk$VS6tJ~?eud)xrgL&V^G_jiwl-)nNOHMO4Y5!ZCvVlj zag;4m6K^@hyfX|;29>cQwguuwUZfRqD-frVDFBE$739lWT`3^0e&ilbzYKNt6DAL( zixuT=!l5A)Q%O$He~0XpGaUEiq*an5^lSMmSC2WblANmbxb>l3!b=~j1M{7ca&NzF z4gf90*J!kJGm!Qu#}!vy86-XRj*_?NPa;WGcSJN^m-AP{VL6nZMa$;}@k2UZMGhC9 z4W>V<$Xf+@uz6Kgd4eD`97+Mz#CbVP&8<-r`)OAWp=CAYO0HFa%5}SEARVuX zVpa__w}_QzX#Mp7*y>S>YU9GZ90*oNb&xBP%X{*N{#WtpjB=_7*K$ki%AsE3SlXxCb9-@!oyx{)v9A;mW!Y;rxZD=F(Xb5DJ z`4b^JT23l6CcWs7O*~dy9#LN(M1$kyX#HHIQ;nN$$`YSGJcViU!Zd-1i7}8_T$uuh1`eR$ z26CcsVIU1_AcrT`wd&*wSH7wfg$^IKDCI#X{OPEZ2v=iLPp2{y2GPX^a!=hl=yv1) zx3ENJCA^6fMzjwF{&&KN=-0a$lOml6dkvyh4dofa;DNNau^is%7z*H(IGoc(l>h(I zMZ0c>2>f9`r4oyjbdDPVU?-@iL9Rx*jpS&dmRd&QQfnD?|CcflI`4EUBYhzCZ7lZ{ zG*-F;taQcyg)Tzq=}vS%9!Sv!&^Q?JiJcEbDR+Q|F4sfRs|85 zGb~6hUMDvPn0qG3nCtD{&wRb9{8A_6G&WyqDI+BK7OZjy@UX9iTJ%#xf~u|MW_r&L z(28LP4x*GUd;_c&~n&J@}`d1pV3#w+w_=v<8^gYP-532luG#x(QoE;lJ)utz42-|;aZM*oR>Y9CduV$ z8mg-`%q$%+}SoA&dbw=s%@6HU1i$> zb~|1}K|CAxA>20{f{ZF}B3(+7`||Y&uGd3-s8MG*Ug*?Y>7V@+7HllRnORxF#isJd zLaRO$+y(8WVIOm17nx~w5~wQcS);njUaqepD>sLbsM)?>Q|fxyM0Y1f3^qpcW%{+d+()?HQyIueHsZs3$UXGekxLoIQGO3u)?L8s$Te6~ z6no0A1D2y|)hgGF&d2m6+1|ZW6PROtuga?wvwtvwJlkXz^p>a1mpHq5Dw{9?EDsMv zH?yUuQilpIH{Zp5XhAPIM);@??d>H;C-$?_)p5G$zW!gjXid#v8`GTV4(~&;z2#1= zm4f)>n8K8*!#n{aVLNmBtbs6!WG4cxzzE0Ta|MlY7dAb9?iQ#j&=5zDddp=6k6voM zid>PrUS&nUSTmx~k0pQgO;g)Mqkcf0r}?6mpYk!iTFYr+$w5SYl)@OhjwQ7FKE+q>qdYVu5l^ab!WO-N9^ez z%X+OaqpQO>^Y;<*{a_0i;5q67@k`DOERv71LqKU{S9P4(eUv;-44#5=IOeX-I4lUi zZ6lN^zC(4Igr}36 zp$A5}afvMF6fY<>*qBtOQ*kAP*b2(=q~R&@1z}$&N|-7S7QXFFSyScf!uZbSIn(6j z+WsYJIn=9|BqMgTI^}O%S}fa5USga4ER{2#5_hdPZ;uCPNK=PSB4NdZ@rUz#?~kt_Z)F>t^UZN%1t z*hwd1+ik>*rOA7){7Y+FN&g>b5e;xloD;E+Y{VeN0Lq*rSNPYwrGng0Cvu%^*mQ?tq|RbHq4iCDrHB$J*~fRqdf@=vyXw#5}Rki}7wgVGk*L%h`%*!u*R zZuWtyNJmD$s3I2`$g@yShdWi|B4eJAjy!T4Ak(^~c03YpG~)L|;<}k`LQ3&ND!I--OuC4>9F|^J#15%4laos^f`_wf#gXj(2pPeXbzJbf=pu?30s4<`m;ii$ikXWh(xSnbj@h zH%9a~jNjOYy#5HST4^6Xtr#h&w8fHYn!qcb#|*zr&0K-~j=-;>-?-KSyl(LG8H(uX zbu#;bpLS+Hi{x&l`O$0d+8>qU;NU^>Ctc~{yY>;-qPSXx`meJ8C{FI`O<8TldS;656)Qw{F4D}y*!!z4SfGa=Lp-a8?}MKQG~*ujroV5`7n0uS3XhJ6 zxT`c`UnYWE8A}5rAf4XG-|cK2mJa#rxKW_KSjO>q1l4*{6yno$1ax^o55z zds7SS>jm*-SGx9*JvJkvv!5tdi0&OgW_DI~(q}$MWwY+L-0(w+S$IRiCqkrb0}jVq z*olU(#}Yz8Os^WWYrXwbad;>1><#wktzu9Yn!m{&-J~$cU9F>z&MRJU|HWM394r?o z-yAg&;p%D_!hY@Sb$ZdWik{9KKQ?JY2fxTDrMFFyD;bdy_IhVJu?aKP>1y2QCTWuU z9slTXk26L89pP%)2z#zG4cLt6L-ptu$^D{#bhsZiMgP`_jqLQtGzo?heG>Mdk6gHyDEVPH%#9QrX z|8Dz8+o^Uuqg#M&p~jzL=P2`YY}(ZB=-v0Z{Vl7Q)n41K{3=!3u3VTJ67Rjb*Z!<1 zu1r&dL?xB(w3j+~4}WdHC0Hp<-|+gd4z_4-?YEz|X83z~!;9>d#psbpR8@*L*gyg{ z7ZXopt9)^nj=>N2{>4!Cb(|y^amZdEYTI;2`1{*8xP#f*78B*sa*VA#eo(JVGVT{W zY_Bd_TGE8W_UYoUtqHrRaa8MD-pOf6ExxtCA{Mr$9pBpH*nQ?(dwbg#NJpDJq#eN) z%Jw#dg^y?&am4O08aEdYsT{Fx{)!&$Yb}gbhg7?RT^T1^t5*kJH3mL=kQJu2cw)U@ z9kFi_%LKB-selF$FJ?PTKz0Mj66f9X0~P~HyK>+c={#X^Nrfshpmt-CVt*@@C$;<1iIAJPgxF$HJ+@LMf>)Y~ywn|Km_R8)eC z^D>{6CQF#YsP9^SzPj7Vy+2tZYd<~`pup`P2Vqg1G(V? z26aHsMzRL?+#<}@!yILVP1D1wmk~Bm535*4*jPO*N+~07q#kH%Mr(h!k4|>9(Y8|1 z8nwrAQVjM?)vXl6?P%u~Dr2$OaC_Q$d;VdsF4z_{h5i-SmTR_9;~6-Zy9eMHZUe_~ zd)m>?>-NXRxy>l@Pt5-&H=}-k+WY&pAO%8ZZA~B3>Z)I>s+XAEVS`{HQfE0DdN~!f zLDkE&x^(4FdwQ8TnSnT+unqaV31@(TlUdh0?JxUo!B!+Rwouob_CclVUq~ohXD(ZG zsi4^gbKJarpR6*MZ7^2|nR6VAtFHIlP5T_-9#Eb@sI024jHgUcJq##MUGIil_8>w0 zw261iZTq+P!YmBLjK`|kvL=D-y#h5+*(gF5=4;FX?3id%2p%YdR7Mg&kCVS5YOULe!!TJFiv|;vB z!4&@n($_LrpRBUun@fScg`G zNX?rWiE-mU0NLb@;rE7G$KW5mxT_vNdL?vjJr&$L&f zwDQt_terszo7^bcTV5Jt=#>iWlei{%t0O@jCw9V4ua z2F^<0^fKW*WZ+~bP;dq5beTAwKpfsp4mROjfv{A5JPB04qBKIB*MJAmHRz2;FpA$) zQJNzTX~3INk<@F3f)^^1a7<)kCFzkMEJIrSHXZ4FB`H+QjHN#-Ne#t>20X=xrH3oS z(-A}cD@&hWjEc~x7Zt9TI#m)8TXpA(( zTDQv$D*O(cvvVLDd4v){Q(~pY4=qKyY`DUMHokR@4^I>PPNB{+9F8b|l!+aD-n^KE z)Cnlar+*lM?(~{J> z%$vX$;#Juf7-N}(NSJ9XjwD)gvt5NYYQZQ>@Z5omyb+*oqQ`?wYI^VVFs}w0EfIkl|z~G6A0~c&Cf3Bul zTLS})PZ1fq;p309tMS*AI<}Bn+QuLQYL!s-V8X?FOHae+z$U4NcSj3pxvx*+NP>}2 zabQBTBv(eFDWQr+Ld8wJ%UepA9u~)X=eLns1&Q6_v{_++gJ*>c#q?P3!VXfZ=-3gf zmGEEDcsB#Tjj7-gaMs8HK8>kh5gqR=O|)%czrrF|%zpWt+?T%WB8{t77k<9EAm)P( zY*W`@I-U!9Cv}zf*ea%R?^M_fLPCp=UBjv|e8f14#&nnJYJtUC;AaRF)WFDv!?7Il zWp^oFBY<%Q$Bq?Thkiyjx=V?D7}b*2+}$DuhnxI5U^TU394|(=n3Oz})+N(gQ+f<#;&A|KSB*f)yw8$F z*oqyve+kVe_3e+s-Che%N=mV`w7*nSs6wX(NO8_AJ;idIBCN3fHAPrqaeF!2l;S9; z?PF51_==iFg4jBWW;`aPh;P)SEsvoWtR1DZG#XWG(B5QS4JCCdht<|{y4@N zw`$SU$ARBWPxoRi`r>h^MSxCtG@*%@yK~uE(^z=6{7#t4i6+>K5QC}{jyBY8fYhLL zSq;8Lf`)_zIu)tNK;lW^*+{hrii{3qzlKy~Nozyv21rfBbG2woe<{|v7y(?yZAvAe zM$*f;NU*5v>fq3RNPIV@joVBKtgJ=p1Emh((ePL8+)&4(9hP4yJUO_sbCjM+IHv*w zOO)&VQ(;?cOaik_sZ6XzcLqvL?jZ+Hpd8|ByE0xh0X$*I0Y^k%7$nt;m2npJPE7eMzu8Cy?CALFHkJF4(s2!u8$jY>bNqxm=aB@MF~$xNlw;kmh~FO!?iO1 zDg`Y6WYvYmxd|^E+Vuov{aSV4u&pA>q*T^NA!ANu3a0{#!+%W$CDjRM-fscTpydvu zq$aHRq$XX}f@0H&0G%_*dN%-0nE>{J5sri7xbDJjI5VU~SFojR{*bvwBhEbLSEuWP zrR0QVtQU=N!$l+Qh6^}4kQ zUa5(97o`niK|7k3DMhGDwC}hM9j;C}nNn-jS>!sjOLayqd{U~VdVT0Rv|jU~PKMtK zthnlaa}2+&u0z??Y3-9blE-yunobfvREGk|DBZ8G;rCzHp(k{|MTQ@_4t1|iJBF4r z)mkTU3@ha-QTNL-{MNe;RoDI27=B;_bK3pGbg1R7Lw{D|?85RqONYvJ9XhM~jWhh# z;dU6^ZWB~=rDkEEQZq!z{suc}XJsj6Oy z#i{BzVkR2%uxf#dcpd7m>QP!dDnDErYOL`70Xm+@zgbnA$g}eDxP^xim-VnYWrUs6 z!={%JR;-6jE+gy*J#5+wWdt751D`D;>?=L&sWQTL>tTb-2-~iQ^$!f2rsi;?9@r}| zPz_tBhjl9>Y>gh)p^UIxJ*;&ZVT<*!W>u&CQ`~Rsfep)u__`jJP)67*dRTNBVN><6 zYUZ#|l_1YMjzuvp-dabi$fHcCL<|hygf&8`+fm*v6!^I< z;cnq$&21?RbsveOgb~tP;zyCRWrQ?O99)&UjFb|@zEx?|NNIA!0`SAPZ}1@s<0{|m zs&r>0rnm}RA__I43|d!p1UMN*o<7+&WO+mYa}z{j8AHuy8#78q?k zD@_s;tJ1<}rRJRqxKsBv$i)_|0%Z#PEwHK;31;-QVCaO@Q7KewwT@BQcDH{YTW$-M!7XTv`a{!B06xC&2$M9h=IA}WKR1&XtU)gqt{QC_Ek*Tt7u0A=5-S;Y7##(7cOY^5l8i9b<`^k1!Ec`pGEyP9 zeMSaxg8OX^C%-nnC!d#V1*>_qh}3h8RIM}iSw;1@`lc$DcMPT+Fb7qs(zLLT{KD8c zQw_`1!txQOFF*3MedKKs#MTFqyjzH59?|#kChIH zUsk2`=cO*_iNFQgZI;W383xvY9e!7h@D8^Y?Sg<})DNx^bM9|ss(%PsKz~Svte&(aN z&hkh@s)dl;XqA@)`hJ2`IjN+gUW#ZcES3uH-H7OK&~Y4$sYVqD+g^ntCt~%gy$+B) z5!w8!l6UPyX`dh>bn;|rt>~^oi7!cCh(oGS`dlfQ;-^Ss0wN~dVX=5)W_J7g@$AcTIZT=bgpsTTp8mks4~koCI*9m&9rm^D&d%?I z8+3IF>_O*DmwGvWLTR#gyoy5c91wWis&c7oLAI_1*;)$+EjZBr#%?FpnN7)GsYJ0e zq=n88b-bR8x90)y_O!nd-`$mQAUse)-by6SM3IiD#1c=YTQj9fbqWO3Om3r&hL_gb z!ca?JpZq4d4qXl>c{b`y<}9gsXMMG`ta3Ti)0HvUlxi1nZRYSQMeo+q#FC%P}9%kH z9!&gK7@e3SjS}qi>q}Boa?M4RUcpLbt>MnCNH^!IRoXjq9yT7Fq0mOw;&q&vUDg{G zzttoMuO^`_CH@t(2epDGvf_xc30i1G=$Lq&KC0 z&e3`%D=?1t0W#@@(1yD*+$P4L>o?y-CR>M6a(2K{+&%MG0+=ilOn1Nhd9$U*omF-I zHbbbMbq~Pbx{fzWo_1xlGy%ti(*QS?iGB*9dF}_}FY7;;5Sd`ELrjMJ%fBT(nfMy` z^Q=(qfo@d7aMyFDhC7jY-KCca+*~I0!fEkaQlfk@1Yz)dCye&LC9O^U83}l-HMR1K ztEtjnLL#~F<8o^nYI%n{AWvMRHnfKSI>rF)<6*SrZE3dnNO`S!9QTeCqt29J#dPMxWXIXh4HV(_TV8K7{Gr)q8_epC}T~>6|I!|j2_ZgY45!Ac0&QGsJQaBGL zvw6Jt^dhOA*dh#f#$g`fP$^od<$#WSn?iRM-Jh3T<6RkzO}td|TH&k0bBXl+Vr`W46@Lpc#^rCO=v9_T{}r6cdg_N+JKlVN)Zaua;&Ns5HKpDr zlrAro7ALiYzXz(<0$T&fg2IHwxDl~RC|%5vTFHk%$2THQQ7CD-6cM?v6eyqlpGQ2#c}$|g z%cTr)bO_HM66yGI%nb&F@T4Mv8hE5E`EOPP#6V?S?2*RWt_l{6b#tX!6S_#~R1MaeuOg%Q+VvVPNVf-SuM6T~T5i53yw6owaGwdLYb&Jr;?7{2u~J$u zhNZcy0c2^C(f3&$)RgCc8{Kt zy+>C|9X0YHZK_l`oAGaMETu8rvH$V2--z zeP9fc@OCwnsM-h8mmzV8!L3Sk158T`R!i~T@DHVlqBzN};?vjbq=%(`kWVSBw@m>I zF+^7o?f6LgEM#2}^IJLp4IAe8;Z>!Y-Zkr`X1Mk_m`-fKF8M$@wFY+(rM(v#^n|`% z!s{z)fn#9HUlCVj;9FpuGZ#ar{sVOijRN+TLP*&Ze?E=PmCFjq+TN@3!g{*GCyW0-Lg zFMv6Wr2U!Oy$fR_Yanxzkc`S4XveI=Nxbm&FbZ&Nl7b!tvD0o>#zYfhrXOPe07PTI z>wY|z0C9*3v1=(JeYHti^&mJa_uzR26Hcff&W6pUd#U&1r_-0Xn%jhP4SJ)?%p1K$ znj)5(kiuJ?^zc{ARCOcU(2Y(-xPC}f#h-2HMh6Y5z>;aDliQ>x#E>9L-7cldg$UpU zu^mA)d%M)17Y9ymm#T;-Y;=9QbmF12g4R%#;LDAI?rGO6i|TQPG_&`l1I~T^8JFR7S2Ge1hd&guV8eG$Jw#?5}{~ zjhf9uD=xj|^Y+&K5F3TV(-lfUArDW?E2G}j-TDRW4O*zbP ze)BdRzePKaN&{@~;oBAVcjjZeb z*1dZb!#m;z!Mg$Fbdhc5ci~UcV5>ObruX`JRQ>4W8(NajUcXIy{<`h6 zT5-T?Wd;1&J&RP*E=h-@FC&yiT^GJH{U|@UbC-tbl-^!HbAwm$28Dg9qve~ zGG&%Adgc-FJP40zEtX)~c~|NocE7eDOl~E%y+%8}P%@~OP4-Ra1F$`T*zvF+eB6ZH z-oW+*FE}HwHyYgln8HAqP7)3*n_z4P4D5)$6XZw5l~*ZAlOF&OnFA63b@ceVJvF)fq4Zig>PL6 z6h_H4N-rlTJGbh1PcR-H)cIGup15=tCOJQv@IJpr`^w4loU?Vjx{QbCmHrj4E0*4I z*~l6bUN-U@4E~AV!WmgfY%iK0q-Fbp5qz~mgIzp{g-cJ^vo+Gf_vC5&E9qIWm+uB z3&s9dC|Q>KiJO1LgO~DbCqX8x3oZ4$6b505L!TW(7qGys>O!{G4nP->msycG?T$1I zT5bz+f29G6>~ub_<5kx4V$kTi^-nzHCBB9$;~f*;6f|mzJgTb^pNGCGKU({gE#gcl zyN&i~77U<9m@s-XFQBnlBv{2uK;uooA;03aPdU|D42f|`%wRki;`}Qf3~_b?Pc-3OyhTP)c;jbkRRKBQ|1-_5Ag7BFSLsLvIjZ8&pKq(D?$jv| zHr3^;RIZ}jMXY(5(ksdX{o3Gcy&Hs@;Z}Y>HOs=`o$ml+6b`HYP866X9GNavl;?^g zf2Q%3WZ$784)fvRIK4lf4VF~XOn6Tlc$qRiQdu4=T7LHKs4VZWiY1r4Q>)2CMRCGK zZCGfpA&1+)b>Jm^_~ddZ4!RX5zwS7AQ5%>k z=Wo++{5A}a-^38E1N=0L^|UJ?G7Y{E9N|44FRv7A>o`Qcp?7J5++B#ceGV}(R=4;K zd9I%0ffCN?BkamVnDi9Ym3t%`SG!``nahJ=M~pVAG29-wc~oP#U9r@&p4`e852KZU zc!t}EXSfk>YdyJ^_`^9miumHbb36!%r&ft_lKANb8ks0}ajv_dXNNQd&GdI zI?EOv6Yu%vg2_AuP-kg=eK}SfeSy~3N5elZqMkn&AGAe3~P|<&}z=r5ZKR+POG%p4j|7E z&5(|*CH^{3^BbaWLTOGklskw!f1=nVIayx+(`{lSmfh!RaFRSq9CMcTC*cNZM+BWq zl50iGMtB&)Ju|HsEu-~A;!m8#z0GoL#6*O7W?I~*P$V(M<=qzSF1&q?G8)PCO6^lP zmjbM7)N*raU#psH402&Zng^xg*B0V_O}5HVNajk216_B zVFBF4P&I=gOk7`WQaS_;z)1_lVN1x$CY)PP1vO)773j|+cz!MI z#?*5(JXuZ_U;c>}C!^JQy@c*0%TW>UAR@17x%43>o0+_Mj*^?o9gQaRe!OJihMSd0 z!e7X*`|;v!DmM{(l+eYda)R8Ed4axFI7gAqN*ts z6XoTQAc91i8JBVqAVHFy``5e-Dx35B!w|3h;pr> zyD0jp!4@Kd!U6D5HL2WC}o-7TRG56MZ>{sdia91Mv-a~{npC(JGJuNI$F}YZz~$vEW1oaAMYO~EZQd}Qc{DQ2y!#BU7F+H&S3Kde&GfdO5$sTm9E{1?l0lS zf?0hnu{goKTl3J|!vuFB+|1Yxe3^+}r*Zu{2AiAC(23S^hp1s(96N&`#?Gn~3t8-F zl2I%-JZC7ijhvkFH`Ac65Yw=HC-PA%O$C|&Gk0b=cO!h&^*;_P)WQ-^)2cRd)U>k@ zV(y9vH^*nyn88H}eD>osM0VqMCi4lJ`Jk_h3|p{yDxkd@h<72-b|rGyH)cMHwX`Ii zk6?d3EPS1uXw4UOMs_eGyGj`uU@!tdW`r984}L$SGcp|X7W7v>yFD<;8TKttf}tls z!$RG8N-tT&uWO>|tI=5VH=d%iZRMZ%DTf3)kSh0xcnm=vtKja(Usy4o!ttl~&rotZ zIWaMW*=PjYPOkf)>8{ge;A?0u+we^;q1o-^sIXM{Z-4JB zhBcy!)F@4^U2b3TZTj>K4M@XaJGq2brOAmYPlI`m^%TCWx<2(ns+sWfWf(MrG@AU& z#Z<06w5Z={8r~j_NB7e-zdf|+PsX~3HZ?m|-qZ!`(uInCn-%4M2=mDeeB1ygE6PClt4#o~cAIFf zYBbjTjA9z!Q6BBr4HoF*p90YZUQx@8;YL<}oUjEBy5?+Sk#7v+fX3pgM0GmJ!^^}e zt{i|f>oM4lnQ*!oIK`FeKquLEEeB(l@>3-Mr_Sis_IwFtfsN$!I#%UF$8x5%wJ5CP>iaWKs#mz2FE-&v6OeyNvilTDo<)Lb$J*= z^QOgg`6WDy^7E@9l6Tp|a=4&w?7H!`?Mb>kCbR|}>?Wrfrx7&aRM)srQ^y;VIA3@7 zL}2RYxFT^Od8*SRPPrv{dY3M}A^?^~YF4sE2aKNJw(42oSJ6%a%%d;+@Q8Ph29|Ac zMABDIxwDhtVc|6*6oq<>%5RNG1<&*c#pD4E$8G>`HUa0Jq5+S{&qr`##+is^kRxyO zv^YVhACWt#jAxXVK`G-N|1@w~5r@GinDB=fjDxn{biEALblltxbj$mN#5kMj899PP z`IL^4YhJP`Gb5PYti&v+pDCeKw7uQsk&)Bb|1Jg%cQLU+m+s--4sjkmNh5n;a`Wkr z-Yq?3ys`RTv3Fm(JX8=JC-G#m9P8`~QL;!cFan>J`Ztl{G*vt=as3E-zq0CGOpAMA zwwr!}j`V_htvE?yZ#gwW(eW{>+{|Ovd~CavE599LiQ$o{S#*DN zlJYY!+g_>rcVU@7^8hk`2BnYVdS7s+{A9lNBqj8bqvVQQ9S$I~2Pi4k9_gH}ZuKddYbFd=t1={?d{ z9wJmMXo!YP8(6P^cB}&K-JIYm9sa`!@LLmRbu6r*H5*vX;Q_CD+!*c9`D38>6HU0m;l$EpxFL$o-GyrRweI^t-|;MY zTCOZM`ObUuX?e0BF8rRxkH8v4&{4mg#qr;Jua7{(?YQtgw@{VxsrYRyn61Hr z*#P*dC-uF!wC!QR_7l5}Q~F<4>jS6%DjC1<)P+gZ%i8`oN`Cd>Cm}ubR9er4J|nu& z(o*d^VB*mc?5e*p%)lH-UF+z;kleSpO8we0BwzKBXhyRD<-KpU0R=ZuncP4j_G3rr z#AwVndLE&u?9i&z!z+i>!jQ2&*1Dek4k;LCTlDGWBi~bpF_>N!aOxPit>|b>FLCM# z_&kNJt;WOCv^>NdCb-{aS}UfP_^oc^v+VG@2Gha+qrmt7^}{rHtQ;lY`i`cKm8XiwzoR>2 zDkDs7X-H3l)kAGH+ zpFi<1op>It?bstEzaW1lYWMBEE6|h|<NKFI+odD3X^>MxT>4qhtc&cIqfr;aSS#|1D( ze$nbzV*(8e`Z>NR;=h0eBfe4S^uu&?nw${X75)k<1FyrRRdG+BdRJX8eDpA04Ul_^ zxUT9Mmz=`i6)yP;v9LOB|CjfQ`@f--8CXtS{|&90A+K`I0YA)F;-LrUD;`@8`9*+UDPF;w&( zjyX17DvxWt57D_U*$^}Yzw=N^YDvYTv>e=ErQs;3n19e}d8Y+v=;~TF_u3U4;|*OV zUlGEZ=>Vhl-ln}@k-Qw0EN3sR&6Qhu$1Im^V%Wm3v?PkYyiN6W3d>$ECI`7k>M}DbAcfBi@2%(WWMPE>?BWbx@U!1kao3mQJW*3#uY3j#v3Vm51H;erk z1Ppa~_igHi-+bbVj|S#p*X=btb{PLTMSUdCu$}uH*-&40-1d>YMqIdC!&tf=80~b7 zNx(S#MIgqVi{EzLrgRfRWxP3A zPe*9{2@rnXP4hp&7VoNE8V`duf`^_u!dxJffLH%~qyb^)E{%upH_C&8XMj=l$(UX8 zDR0e9vcoF6b}?J2;uwJPH*=SF$5tq)eeI`O#i#5Tsj}CxLw;5aKMX&kzuSx7l%_x# zw-?HBVLSbTKK_(07s`vn7WnziQ~grt>rdr5VMF}_`s)FUK9l=~websRq6K&x?~=o< zVNVy9COxRooBoA7QViLrSVF_M$s)BPV~5WrV%`a9^4BL#)aeoo zJaKa-OH-v~X)fPRLyuw7FkZ*2#&~!*(V$^zl!=EXFCKH#MJ7Dgb~`^WAElbNq)4AB2UWs&XGD^$p0hfHdvaxZo(V4%^OyXuFJ>5^?d_ zSEpgJkXDK3k0Q`IDCc1M*ZozR|lweGQxU2b# zxK)3WdyC(0rI9~ji1zhXn*WoWI&CFmsgrf|#%Hh=pJs7?1)1@xsHVc&g^)+Qnjh0b zqizUDlY8qz(B`fvhdm>0&Al0uvbw!8(~_nV)c_HX zEFf{#T4R-V*M5cv~fi- zINV?it+h7RLU+%~y{!X*w)0ziR0v$3Szho5MRS+q1ET)=Hg?U=)^fRWZgFT z8Zxz}aYLrb5tnAO0$J*)U#p{zI;}&#BduRh8rLgenuAK zy;>Hlc(u7h*e`OE(yenaTqN)%$2@zm;8t6Ft&VzXCbN*qCSU=XEHGvd)lue5W3kku znZLkf>Jkdug0|`nNP`XW3}U@8EfO;QK`|RZm9wE62sHu!v5Dl%a=P<#9q(zzgZ;$6 z;}q1TuPH6Xjh-FEV2j8^zTm`83{rE|%>!@6s#sW}$R`ck7z0G%Je9EWOM_ zEhAUyWge;<>%M+!$hHX7`ZxJe;SuV6PL5ADq8rjTq8n}_y5UCjOP?#Xx#v`6t1BGl z!MMnm%OVZ;=5kqN*7udg%O3}3krhxai?sUG=XaPfH2#F9{tj)9`9#%b=RLtaf#97W zzqTgu+6FjiYxbuBdz3_S{ULj-t2baBXnt@Nm;&JrddCD@^3dx`C5#5k_HvYYT~2du zK+&>FJc=UG`$IL4K9wl+PhMMjvcVAcTOb=ObA{TzkuF}xlIt5Asnws@j+(rYX8(yb zoe>*p-=Fd*XAeD{D_~vkChwmPTKL^q`W<+09TI#WT+lr}WY_8UwU2)G>-N`?I+z9m$fz1z?b zys};`9F>*}=ebWP@fL=rVe5Hl8iVU*430DvFXhN^8yp#KaCGbz2B+0@j?hRkHU_8X*K32*AJ+TYbQMppVg&*gZ#ah{R$EGQibpX~3;y^hFqc0< zN=#!(YeX;Hk#D!Uf?Wzd)KiZ1|wSSSG=(CmLP;YW7o?sJ^C?gXAidCMxz; zEtyLcf>AgvIaMI7)BS%%Zptd0ts7{DsEiVqZ{Wg-rV3W2k@Gb@>kT>b1C|ii-Vec= zAttUU3pUU^D~jkD9WRve9){;R97paW=wA`A_;lnBD%7!w1^(l=<+YZk6eSXgzsq=j8&cuY`+*wuC^gK z$p2fgOk;wShn>Fwffejc=Dz6zC|FapxmZjrZ{q&X^(2;422^auI9N~1i_;9Cnr)y_ z<&+5dCb;3{;*}rK{BlZ%$a8S}#;EY;^f@OluA__Pl)=`y;7gq{P1PB6FfdHQjiS{% zvwyai^-;56{O&;l1}&?>9JEHkN>arlFwUdyJTS=?T199-gTdfJW)Oa9A5oNDNq4yX z8H9gboxw2ptE+Z}lS6O|wOyGqxU$aTMuyggVE1oJFa+aUKvPUCMgfOsL=hRh6DYX7 zFszxrmL^L|lJi$2&*k(sr=bnY?w zUQxP;&wWH&6nJKSghL6+cxMMagC$^?%Q?+&$;QP?Hd?=!?dum&&a+@!nzi;e8MIu^ z-9MtWAcv=SX3Qck#%=&YwF^%e5Z2YUWBsn#gZ`mT&eOi48@po$fg*|yKYvbx?#$B*Oa z=+z2JO)vg+60O4#q8{(es;rC=Y+K$3p?XEUYj%j8GCSbjsm$HMAznv>vQ!i;?|XMt zQ|8&MBR)_!E}Mu&?|G-zQba-Q^S*aRlyX|ICL;)l)d?p4A4IPKAU92?*W9MI_{~GX zT$Cngp?4_sC_7gClY@1?PM`*?}>Pi=Ih5L5SD@8Djodq z=2OKuWw320(jZrm-C-RGCb>@kG_}HIyE&46yxxG|1J!UYQEx z6}$EJYW1iez-= zDzZw;HFe2*^n86K+4;PVSDEp&nty*h)cj6ZZF|RrH|0ILTwhu1Y^LKKfgtpne}6pG z{48{7{Y-eN@6p)?;IE2~=Vd&t=HDL=y1{o-kH`?*wovw)b`EyRCjT0s?=U-Vm;x}H=tEt0|h;00E*!@Pz*Ovmb6#u zi6?R?=>S^S1G(Cq%E%hesno1_Qq-^LXrX?s*ook>q{ za!n8|b?MDcN=xhQ<(ldQ3%sTW-z%MzT4G2pg>_b9ZPr}0GmXDPaDGFfsky*4`Zc;J z8D;WQY{J0|^DOe{FOB^MPH{``x-QDp(ibaO9gU1xS_Lq~&)$qT0Sz{QEUjqt!;0@s z+klLja7utP*o4!?59h$cN^F@KGvTnAPiGTOLqD9R-IRvnx#cvpo01?-&!cpw66?H* z^0c5PzXi$iyx)+Duevx|>zOXS^?xN!VO2CGbTgN(cf*KgKprJHf!|BV->Kt2spC8R zMsyHLwxHo>TQf`Xc^T?d&TTSiSzq_&(iW$ZVjT^fY1ic#=RzI$AqGZ0H;8q{{|St` z%#-a+CSXr44Sq!FlCp(y+QGoS9SrPkmL|DDmcGyFX++0c#yVgCH^Oi~WEtzhdcsq= zbo3E)4v*>nHz5?y67k=8S<>N#4YSJ0CSHc-QorsHqH{UT?hYYV&ZV{8l}NEl4(;o% zw6b0VKHFRNsh}sgffGcj{cGki(pZV!vZ*P-8o=QZMWyz4)q5PueTKWtw&n0~pY#C+ zsNTF_u-t}KAzLiezE($D-+&>=1pEu6$+Q;GmZV`OgYJthtr-8U9O{y;MA_CZLsNpg zB;v{SVX!^yCLp2Yn7@hG zaZ$C%#jJ?=BbU*to=Wq$Y{8>>3_u#Z9pl@239+bzeV5Ulo=W7<9tii}g87hvXO?ck zG-Nk+Q(gm|u?4dUdE+^_&j26cGZF5a$%3(U8clwMWi+{$(ocLQhYs~pT16d)e;W5l zXyb9F?M4GOxtWG-C~Wsg%PFxpN_+Bh>e5?jRdEk!bB9^oo{m=aNJhsTdaJjR7%^ul zc;YzNMq&&O-|C@5y_MF_xKh>ZeF1jZ+XjeAY&JI2>TVDDdd^^72EW;CY=zD84*Pp` ze?APf2Y%{k6mh#DnNtuQk9udQ@)ptgxeo0BO)KD2VJ6<~ay*SEZL%|zYQtYfT6rt1 zT6tjq=se1Ui+uy=bK%c=c8k-(@3X+x#3{PpWImAIDfqEiD;ld$Gp+79pf44()&2ca z3hSdp$weA%{?MhA(nsmjyim9E!=MX2YIck((bq3WyFy#4yNI4pcT=#a{w@r4H}=qu zK1yt29r*FnG-|dHpDzW^0lcp?*$;95yOiXI3ftz0L_S*=@ zRt#CcTN23BP80&uT09oI)K5wE>x;4lEpr8;1BXyh-;K=i(AR6iS#IDs1bU{w(%Cs0 z9v1XH6w7Z&K`~TAQFOwCoo*BGq#U~0Uzt!re+}S82#77;%P+w*FiLvV za*%r(;izaM?WkxW+iIeYBk3FCAeYCK4DsY*>hQRdkTRBqI}?>;g|@Oh7A*2h=jYfT z%51sSLG2y*FdEZwg}Ai@PunPiV>1`uCNKU}Iuuj`j0&f)a&uPP59++E}(d+@r)DENWf%A@m<1NLh z1e{bqoRj!HZy9wNsHBQ{OKA2$D9@iuY5hPYHtgbmODle(96CKvNr`yWz}%o=*0NaM z>9vfK1}RZdbAZhix4cn{Ag@N?lN*jIi)rK_B~qTO(d36Lrul=E_I-bOAGIsJfhtBniP z$i8s_l&UllZT!Cy2{kY!RCyWAe?sYC-3q+uXF?V0X5(ozt+ zETN5=SQ=Y|s?FbsCDi3fWwy9&5$%6c={oHJo5Cp8ggbo+9UZ15S)YQxdcLKX4t$LZUK?-SU#Za7*>Lpvc@yw}B{V)uSt$NY z6!w&o(|8eZxtj1M){mfNvlio(iF$BzGq#m98m6PGgF|al;YhoU9K)506gFJBEPlM0 z?hIGvi}8zS{?kgj_z-zdJguA%#KMKNV}vr^Hh@*kF-vK{3sfQAF(Z|1t8K+XczRxd znP|;X%G0H`2x(j)ait-DMUVEi7F*RWix&xs7pRI=U`)Wj1e;82@mRfkMk%49GXXvp zsLhv1ftPYnx+*o7u7<9CHB{638jI0&u#Wd0nqY@%EUt1i;YFo~xZ`bFyI+aH zYmPv^^rG^(Z3m)gcj6U4Zns-Mf%Cv%dz5$Xc%_9HSs(e}{HWCywXTlg4yU#ALlT{w zPY&OPXnO4n%&#TLk4cmdYM%{r)HZJi<~M#JrB6~)g}k%3dRbs|iVjD{8BD$SMWSHWnNqt|CF> zy2$DW9FHBglDAZ@Ra)*qzFt6UC!^OJ^fq0dtb8Hfe1|r^gf?Wx+jQh5B|#XZ=|rmJa^-P?Eu7KX)c zZ+lz4qD0uNf4_;2ZG7;g^0V-RMa@^vOkz*Iwy*I#Wso3xvc2x3qo7~&x%%}9Xl%}cZRn^BX)hq=9ok3I5)&x|$ z6v$n(G2S^02~DQCZe^F)_YD>Bew@w3D#V%B13CK&a@RSdt#2vsiskFL)@muj;kMAaojo3pU+E|~BxKqXZ6 z9UrPftGMZJP{cB&+dUAA0}K~0O7*fi3q<5oR&7j( z@dl!+JoV32T9t`|JDvP<*a3+&Wuv@cKDStftDYs#O$tlF-ODwzzf9o5K;U>B{7p0gS2TbN!)f`u%Fu45)3ef|)mjr@ZQujM zf(hpW@~LJVw8e>cDNCT7l}ZAQS*6q~lQ-OF6_9D{&mVg=P?)<6Ox$O6Y?YE%CJyei z^2f1Z^F7amGta=meO5bHE02ov=TXEOW%+~Pl{7%BWWsCXhxg|iHCHwMipVp6eQj_f zSH?H9RoN97ZSYnAF^vUz{yQHEE$KX}6wITBsA!0~O3wt+8WU2sfdn2`zpvDmvr+UO z45@SGdXK!X47Z6{bG)eq%EofmJFjTQ2-c@&;sjuOsi}9cSHao5v9D;yr{CDB9EdtT zOB?P*%(zWs@tfBj*breT3=w+F@J`;Qyk!#`&*HnD7h8XtuG$aOrlL=k55&GRXzFLm z@M@{>H3oc!9YGWLX{V=Sb}79|4YR9#u7oBRHo!ucW;%b$hHX#m=^NXgsyj2;x9zFA z)0(nbb}btBx#AG_P2=fHoDT#`ngJk&+W;}#0D*C~Z)*_pE)t5>k}DE%w-vjsF1}a@ zcUE8;b!(bhg4sq1mOwsCW68u-QD0#9be&7H%l5c<_q4yEy#ctm6v-c#4P3XGa90|* zg}~jT{Lh*If`6J~XNgHO*g!gxioR6(Ix8ZU1#_;CT`YRb4UA}2PI*qOa$u?CmonyD zJT1b&vzaONnlotBUKk4fjN)Rv`HY8^j(^3&?$<2L;lfOK*QZmteahs1TXnoA7!T$M z#WtRR>TkKIgJPAx0!`xJ4_em=vSaWbazN!N#5ok*W%_OwfQ*jm8-a$vDef?80i|WB z8kj2=-2SDNS&ix(Rz`@5nydIGdUPMtdUV5WL^s@se(o@)X+bYj;ZiNA3DZ-d0=_PNu@0C13{PktZ|3PV$oB=NQ zwhHZ5ipu#J;35}pCjJ^A>eD@NR|5dwR`J;sia4qqi7cM%x7P;$Ih-5B88w-vRtkxx z+Q*bQaV|LhpOQkZV@liD%n<(~%8tSK)KBryEQGVwYNC%$lXWSb;Rap(DG3rrj1F^{Z({Gz2%X}QI`F@HfI^Gz@Yw-YhEwH5zysMJ} z@xGrzQ%_*kbe)dZoAH`H0A5q@hf|>kO?aEZ-w9=h_|atAauT?iI3Cft!zD5V%%myIXU;9_NqxP1ymp2B{|`;&O+QpY>@l=5o16hbVl$!?xp zqCWVOh~3-G4vR&3d;%Y+|7=a6b;yz1FYS2mw$W#;awm z(z5PkPokVlN``ZYjwdjl)_dO{4_Tgt(ZzHV-iS%wRzE9Yf~`FOsn;dB8M%H@>@7Y; z4I%#!*B!RrOOcQ zd*e0HE*{UKji;NJVHDz?$fAv)v@6PE;;-Xr@fFBBQ=zR_l;+MM5Cw}^fTDPwEssi`^7P}7x_af|l2Kp8$efs%e#4moS+ zc-xUSZ#?`%?ag?YC9xqvTN7UG30~(PO0+fB5$o#-G0|MB8pDd~mfG zR}bkkByds`V`=WsNl}aoZhhFGhG(XD|GuSE7sULrM(rpC(KspvG28}-;m%B*=!F)efEtqU$j#LQ2GOeXBj?Ud130AI5Wgv9|(qX$W-m+JriDF2+*k-IZM+`|2#E~y(N1zwKASv{VHRS6u#bK%A z$2tbB|3}$%$460h?U~txw7Hu=8U#o-jS_kb9Tq~7AT1!h1gTP_Dk@4A0lS#>Q;wqI zQbdS~0hNF#MnLQmK~X_5D83?CKr93)-*fKFY<9;`{3E~3-13}q&u!;6EMN_u9b9M~ z=b43u6Yl?n=r?GGXYoZmiS*2o@Tijcq52sA?p3J`%O3KBp_jr({_(6}=+~eD&ZFRl z&)6`%@(~`^s)d6sPnFum2oyM*Z8%R_IHmPzNtj;w2u~o6t3eRX9xQh)vEfX&a9j;a zI)>{))gtCnZUi1;I6sFLMd%}Qe?S>1u!Vb}B(wRuvMr$b>w$YG!fcd&n?q@lddu9s zCf-!W8;0xr1Lnbyy4bX>Vxum=wuYhG0N(MNai3SfJh*HQt%}q?$@Q3cX^e-Xn^qdr zR{xDR0JaJr_Zl1C19NC=6!;r&;yDo@0yn0V_M52NC%;&ntf2}f`}8=i9xtrw8@2goVQm+>%)y(%6? zu@iA1EX;=Y+iXg6>h%(ynQ2aK(p7KE?#69jPt2sTPJL1CI+Iqf|3Hg(4($b|#TSpt zHqEAb(Ryxffr*#Oc-RMFrMYa`^N|)fuUFgf?w?)qdbD0YuvQnFwXs;sm$k^WN7P36 zmiyT9w_rZlH<90f(yQyQ<^BMMq*9?I`5?~Kj2s?Sb_|EvfPb4sX*Kl8x!X;=QH+Ov z{i=eZU*7|~!!v>vw|f@tuc2pa%VtnytUgy8IHLqpz~0v;IQBdZwBfa5zD&Wx;`Kqf zp(dlxLy&7_l=mIgw*g1bqBZe)2d!*69f{Y6hOC*+D}TJuetm*|n|A1C+MA%KC1fI) zck@`Ak9qspM>o^O1U*;#W(MUZ>U{$`fyy%V*~&BQefyoENT2?0o> z>gYd39k~g$4VT+pSa^^wb;Y)XPDgd@KdP(G)*MmDED!9(xb$Oc$d;*4q5FWIL3Psf zr?tgXjdys;)AYCyE&HaDzv}6Dho{F)#ydPOOeVa;lScV{^p93F(q}tnfs%Dt&qXgb z(jRjD07P~qq)fg*ci?}X=dq)FB^>2L5oUjn=b^@WjH(@w*EiDv``+`ucZwtlx2Fmp2dP6O1vf%-&J(bE#XO$?ONLV+AIm4#w` zTPW5yP@Zq4`xh;xNSHxNkxGqUhl?-Jz|G?Dlid$ufg;VBVv1DSgwk8#Rw}Ec5l&dRuF)HV8Z)psX(woL!4OZQxBTaHP!$!&>d=HhN7O*hYWSs`5dIo?t{C ztcTeUe}hGG9>vp?8fELNs>Jcxa4?+SHz8Q;5(~%Iv?Qvnp5|{}gBY>_^}y8lRvXaR zN+6omu5z>(grneaaDb}Vi!suM)7`>Rn$frIFram!cDL7;C!K%|9!2|^uVOP1F055> z&D8?zkUTbtjjfF72 zE90TrScjvC>uq?;CzY)4sCNrEB`LWvOubC=NhwXPVCtBG_qHK411FqE@ii-H)LH*i zbNn;jY<>s2^*1zaMt+GiN6!v%oIp69v~8gc8b>$~-GNU15!SBc=iYjps=bn5qV>`H ztBw*QvpgE@qK9(zhf-AkV z3BmRz_5p+$%aCvO)7PgLr_OHabq&woHeOL;T<^IaRFss1KD4ZIH`raC{UgUx@&LUa zz1Ux`>GVe|^X%_!Mx3=rw3ZQFDih!7*`I1AE*zlO)aK+<(Ez<=0i$v0^I|V_hoL&o zN8^{zOY`H%yJ5-?j)4efIxhKnket&fN=xrF#n_61t@3hDuf-i}X&J=iJx(deFGmQb zNF2Awi0f8Vvx>+CX2$AO#LYJ2A`!>EE|rf(mpkS!oPXawQ170B3)*nS88_1y&!Hp1 zt!`09Gi`mlbV?bdKd0>+&3Bh3QTZS}Dj*vdX<#<%8`+}sbpJ}NRFNWudgfsVTTJFfQV|0zr^d8i&ueTM1L+N7~`XjtV?H%K&hAa%4|a01+BqnyuX&2`G%hNcYH z$K+<2B7MXFYpC_j7@9T`-N(x&-XO-qiV*N*8nfsM&7vzb>K2Nw zE#|(!`_zWFeGHu&iMe#4iPw_xFqgh69_G^PfVahlw{i^KI!b@Ca-M+FDKzU)q2`mC zGnqn#hjZjE8^9zm!g&;5o07q!^$_hcQ03WdntrII@DrRI5v;2NkVQh3XO}!RR@c>Q zgF1$3JK3NLDxv7)INiU0KS(+cPSgjm#IKglvf&J~a6E14!F+v{bz&z7$7jRAw7snj zC&j`++Jy5LaSRRTU2$ZMU!ap%N;{mfbl`lZR&+^6UxRR%Uj?=}$d~KRz+QRuL>tEI zZtdtOIx$|qBX<`<*+?gHnH<3C*VT;bKsPz}KQ=sA@gI$%O*iUma_=?q8ZzF#Yrxyr ztzsQEg>AIqc}LO83A%qbZjiE!M#66gA=n9auPys5u)%q_k!UngZ?7c`r^yr1_UD7o ziI>66Zx>XU8Q8tm-G-ZG;pVq1={iZjLCxI?L0N&rxwzofxvBy&=;W6fzZ@2qIHm3A%v616K)+bYPkDzRekQi_N1J^eBamIuRzbn)bQY_L-;*z%6l zdxkzHO!B34q8Dc9sm6z^6CLn>xI585_=u6o@;hNTsuevj6q8KfVq6Q~Z>E0YGQ4;? z1u5%TH;l$^2v*i%)Bve0PbXS*1(27!Lpb~UYHXkoV@-~yRP~loQaV?-V2;))t zUm*G_!WqODeu@5M{~P=ma>5Ye*`G9&?wO@`h1JEfVW>ZarL%~9>)HRy4b)+_KE*nsP!*)32i{DyLFQCK(&5>9l00BB z9~Uy*Ko@806Rrfe8*q(maIpb!PtDQmWy1T!mU1(0FtzmUss?phoP*Tel2lW5EXB{& zTVIKyqn9V|^pIfN`3jYpg~jxTmdw@bY56eWx%!RP%UDto{)*c<$bv$y^W^Qc;jOpu zT%Eno{2id_agZ)!WKR~98iz|AoinwGmZd(;`iDum9 zD&k_yxFW=1)>%^fR=utoG9F*@{U(Y@)oYc^T%f0`eK2{1D-c&Y^BfdvG`_K8j$MWL zRy@MHa~N)e;Qz4^uhDSxe^(9fVe5ZSg7+|eb(_8*>O*ctIqC2m`gWpTXF_mG1#eQU zL-!woD@D1g7OC=JQtLoUv5`8?>S9vm3iZB2@2Q>5qvdz#Ss{z_*a3cfL>!gfp;xbA zsR?uJ#c&Sb_C-2#hu)w^A={?eb(Jw;Wf{T(YU+xhUz7{|1Q0i+Kk@3OHWi=(&zX}>jRe7PB0sF#erKGj7GgTa`Ro7 zZw{ucMS5P#iTGaovio)(^71vashE(qfZ?phH{1R!HX{6gny(f?{HZ~-X_4Mt`*slh zzDUnf2U6Vv5dV+{73e8yJk2T4n?@DNE&}gGR?nlN0)1Rifx~j3zo4rA zz2fZ$X*ll7fi!lpzQh`-fo6aq7#)~p2ote;Cc?(&X|QD&LI|bbt&b4(Z-C~2&)9?L z{=4T-JfZoP4p6v{(`3mX&by$~SK)HYcZ%0sEy5OAOxUc#Dn57>fvwNzYpfBG1#~OF?8SeY#ZtO*@%avTK<> z*zep9(h_dz4}|AKWp4}!mSG(VKx)YqM#Jva>s6_X(qNo*z*%F%dBDOc4Wqa2)dw}~ zIRrKtZ8UK2S^uMfJBd<|;b`C*vHg-dE}}LS*AEMM+#_n1%)U>Ls9G9Z<==xPnwv^aaslT z{`>=aU9D+<+WUaMhGL!xY95QtR;o;MhqKzttWup=AFgg2=yD6x9bWSCgZd;@>jD-Z z#)9dRfwZccNYc&^q(u+wN!p(SX(fJZGD}=@*?L)QcB{VG4{d2oBHGgOhxG;tH-U)% zx(;0JwHSxuKO0EN%k_kUPheI&OGcB=8%wu;fNvfSq`ZMEEbwS1+qV4n;R*{}d9lm- z-iCO5@3g-6ARbp)%q?(Jm_w*zK7#cPDPlOJcOTZNoR07Aavb@5Eu?V~{ zO$BLhIfcHEZFNtt?NgCX-i0yPWcE+iD%@`t1D9nMUc+^5QGsoQ#tfush5F=#cUfp2 zc%jq9#cP|7LQ81_>3@ZKR`NdNf%e;{%uwg3e8~#Zs3FRyd@ckV}bc=hCjmpCrRh}+L`_`i8S+T_)foU56xL-kI-{sP@NfDR(P;|Rib z%!)|rgYX2v&T^tPNh@d$KkeLJAi(F9F9Jg6bRergA3o8DoO~))wqZq zIFZT2nl)!Iq{V8+AAN((>FfS<^9p^acJX@Jy8{06#@Exu6?$^P21vu({H1B;8yNQ@ zFHh`z4y-YRxVJOzcc5=h_R3T<-Ccp{!i{uaR*`OAU^>Xcc=s5k+e)e@R;l4#ofGEe zvjqHLeSKu$Z*B)_vf%i?2w@z5Uw`_9^vPMv@g3L$PXnO;+tjWC+@*bK>=Sx|wx}=N z`UJ)ecwgl8C-g=&tP+ByS*7#$6MAw`-{6UodeIa;K*zZ011I1+fxJ~)xVmP5ysT=9 zPQ#u=3mVzic*OWm@XrNEP&6+@TABP+%wB+4i0pwONurIwrGE6?lX~~u{U+Xg#;dA* zvE!k7ga&5zp05@x^#w&!u~w!p^+$(A85I zI^NKiPCTUt95sie#j2s5VpBWCh6O@97^lp)5gQGrIgbMEEO=UPUFq2kLUKzz`;qnl zX{ZgUi-qLY>9?o#jLRT-f{~5^sgn&U!$R_)#GcV-N0rGzBYM(%bIJLpo}ezKpPtb> z43H`_-3e%Z4P;H>x`NRo#!Tn>1grKt6pfTNUwFUz`6Anif$j9{A7@}|xA&z_-qhPq zy(0K-fbX|~za9X-8Q`+1^=M`*67Egl3!u=nD&;ZW_~FV%Ze3!PNNV(~K4h4rW{%J* z3lL}RnO&;@`Q*rI8`b+Qsz~bz6e-NJzglj|!Dsa;YB$+)Cl+;wqPgaNeVx&;TH=>G z5{o*Tai1fO7fUPSVvAbm(xTO90^h%mR<5pGV+ytqXArAPaZy6Jjnz}AI8ys=XG#4v zdS2i_t5Rmn$pU3whkb@?!4vai)sP1*pnNCoSX;S>5X6u#7-uOKBNp0lCRjK=CyiRC zzoW(WrL^btF9MpHO1?^i@%G>>xWk5b5;~LumO4v1uIHV!_vcdX^OdV#K@8diWrzF2 zy@Lh4#R7z&u^aTERWjy^4pLY~Q#`k4!x>=VxS~s5*r4BW8O;X+?SZHMY_DL3%2A{c zqEN|?E}2qbqIbt`f%`Ec7wpq}p&IEF5cs7T+_`}^s zIG+mqDTnUxhv!$OKa@jTUqi3Bu?L-aO@B(xyP`b%hxef6TlK;H%=8d`GWD-o!ZWZ=d$p8u{347KDm3uwaiVAc_uUPSJ#Xk82VarnwLl(XL+%uS+zQCQVJ3vm z&d>+=-qxMRJcF*RS>v- zIHNjip8by?j*tEy#iibU31)ltkLXSh?9{WgOReayxAcxy<*CY8Cgfqh-7VNyUJfAH z=q%YC+GJ>T?TB*GOMzi(Ml>xc!4DS&lsD>S4wmsUohk z8TUmMaoJ{ESru{3%(#O0tB7o1M(#o!Pou3O;n7~IjEgPWQAJ#m8TV=xaj|CHOTlrC z;226Q(#^>A!I3g9)Qo%9P2G3tH|B0ZOT?2et_|j7N!A>md>MujDSwUL+Hl599EtuF z*er-Oig+W3e%+;aiMkWv7*H3-;w{j&yY(k?rQ zaji4?E7|cL9JnE`Hiq;2q1}32`r&;&QTw_Z54pM*dt zgZ3a%0H)f&e&RA_BBB|Gyd@pFFsuqswq^B(*bjDARjeTX=%>XH-gmVPwqm1 z9g7pp=?C;%wes5Z)B$~b?r12G6?qX*yczSVitGp%+N~H}bqX%2$z7?}XZlDqSRkTA z(DR?^7poM*9UoNcdv3!MvNkM*3zZGa9Zx@guCJ^TCqEb`9iBV0nVlD6Yl4{-`Rbv6NKGI0RFuw~G;140r{|%g}22N2@M;iL2 zK3Ky(rWd}{3scMZIzXnZ;f5XlHEvf@i@FtHl7dWBm>5xqZu?62-+#xcDx0KWs|oRV z@@j#!Rm?n;=Xxz=L+9}QS9*)wgRlj*iQ8B?aI0F0FI&0bR$U6h5B}9GDJ$0> z)7t%xZ(cCrbqdD$9qFu9qPOsP0n>1Ypz%YR5@7N&!Fc9BCIe>>OTX7|OMe)_ep5zt z8$>gy+6XsJHGV+NJ`bx!^N;D*X-YfVc}&mKnsqcT>l?EtEV`t}54y{dumu@fD|n4` z3HaH~{3I4_?m%}O*L&5N-WJPhTFUf%G-SMGA+|m3KaRDQ+uKv*PkM)XxrqPMkx&$v z<}~oi9q~m4$d}@BeExZM$+VyJu_2B=h``|;y!!Tw9;X$zp^Lxhi_{mX`VSayto&7< z>uN5u#uiO$bAjFgv~^6UImQdC5#~P>Ia;fe&4T=@>1}BFDZPWEBHMgn!37MiM!OJT z+F>ypt!amas;?&3=t4(1UnpkUA?}0j4t&_GOw08%s~u&Z*0UXDz>zD9e}f?gev*N) zvS=l~EHG9U_h73_EgP`fjt(*K^A_+YCh+Y40GxpZu~V&sIsUROE&5%b?3il-KWPGY z{13oOv97Sg2E4W{<(<*9vrlu8;G`IL$#N|eYo7B>8ho9*3*WN?zJ0Ko8Et7N@)nG> z!doLs=eY2lXMOWyR#?gIZ+&k-JigiTxHM9xs&i1BLwZ@? z%?&=fTi^MJR}|-vE>^&u>YVYkdAVLcw}lyW03~#-roz`L47TZ~V_W+D550S@1mFeg zM-5koL|9~5PVgCOeM2tRmuh{3Z`Rj^Z24%{04p-<|gQ`+1E`kfh*#jKKhI5>4kc$mzzx^D=27U3nPt{t{&~w<2SKNvg zor9n1xmLU%FTLdBbNUgra>v>yE%|k)di3>qy;Y^-%)>6v@;YAr)nu7EigK_@+_j~& z8Q4e8C0YJj`aXt* z4iXx0!o2oOr(ZwoLZ1x>sSP_+Pkb?AFlOtv;O zO=&@Sni$p2)5vO~yVkm;vA5}^md4(u z^)2PzCOTD3gvOcTob@P}p`?oS_f zdlw*FZg@hN3mcvmn(6qBLm!&U1=ja$bOZRFXMG#Z{E%7J_d2xlXyROohf0>~skt|r z5g{llv#pmV#=SSIO2s{Tl`1oa1?#Yow-f@Qr}vxVjF!|iTuia{FUhQysrdpS;0nOG zn$foGJ-`O%QINLdezPh~&Dq`*>EtM*mdWQ1R+=%&xH6v@WrW}aPDdM|^p=ztAzlfx zj&he2QOi#?MNP#B$asKNv1LCFHAz16Q>k~PNY!3zM$;li9*%R<&PW)=ffglNl(<9H zwl(AHv76Gs8p6Lx4>`-!a!I93^Dz}i(f4RrhBd`K;sO4kt_GDd#gj%Sby1<++?2tx zR>X^l0M3CWImc`)ojEUaNKEXO#uaw|GzrH19*W~Mijq#FoZ>mH{(r;d_fB86VLlyz zxgc6}(;jce?^YDZdW|P5PBx+LF~Yywzbf&UM0@ha*J!a1SjkfEf)>7DKd7S+prxw7852 zzF-kDuy^_WhQZ3&3>s27zRZ&J6tPOJ;i zG7S2xWDlka|F%LYw5y&}q2@Dw9p&|8&$1Nr>O>nKmtX+~ANA;Ds;KMu0pw)YSB4lK z6U>FWxa&htA&b`RqKj2`eWRcxI=X0deSBW#cK}#vdBk|A5#5?5dTG9fv@=a)X^%Ig z6KTSKnN<+Oo)V%Srk7Nm>Z08=kkEx~c^AmdtsuLF+PhI6}xgKGyJ z8DejhI5q{Y!!&<@4X3SzgDXL!GDUVkn^nn=(jbVR5OkC+Y&f+n9Hfo;5N%fZ!tgrO zJYD!t4+Uw;9gLU(#6%n7B@~=2T6cqzlbNEr>X?DT|MpUNYVQ9bip#bQ0(e!?DzD3y zEmjpLqN{tYesI}7lSR|&i|&pmKw1J%F@Yl(82hxZ3XF|}6VX}SZv&o_MM(|BWJi?6 zaZ3~UGf?7n%c}yTo!L_z+Z1fTsJOp25DTg-ZBMXHd6R4dTlN@Br=AA%d_!@U_GlK> z%M$6Sz6R2L^_|0!RS#)=ZQT{&U=^OnEcP0PHlS%)qC@T$$is>s!eSWuLHlU9!%$X* zW~C}LEEkmu`q_h?^0RtU@iHw}sy7YM3cQVU^xK}eT&fSq*7# zW6`17vxr}lN!6N&WJe9~j{Wm>^Kuy^NA+HZUtUJ2ZY?8BP`$r_DEm=AM@H$!1+fzd z3$fCGXa_TYJ0pM52br{@i5MGs1dOnuq#e zHy~#V@U5G8n-~w*U0;>&aX68J`#GB0@Ddu(JuSfZ^_jG@g-FZ&9(rK?E@RwL*MK_; zxNy3K+HilVUy{{QB&ogjBf|Furnq0gC~&q%#T0j$NyM7cF1Ef+kKkR_x9JhQy}tAa z=FTv~oy=U$H87WhHNys;yyY3e#&m0as@7U8&&@XRzGNP+QHgu9JbA-yc<%aiq_w~+ z-x*Y`jkqK7AMh7g34S%d3z^O}Ds^IGPhO0T&e?i&v5n}G%SOcbH#1)EYtTb)R08Y~ z{xv;V4+rbfJ=r2R_jwbq598rd-K!eYFl=}M-upJZ&Gjg$t;o*3*Tiecc!RG2Z!nAq zdyhBT@VxbCCGbK9Bb?lAM00v0Tf~jH!G!-C>ft+kugdNKjFJGqzy?1KICxIEV%T0x zF4ihIwmhe`NYBkS;lE^fEb(6zzAvgO;D_7b-Sy~5JMp8I-xrw~RNxlz4x&Zw(rR8DOv_#0`b_H8Q8W#i%LUQA z0p27o>?p!RZsO0`cSokun;k_R4V#G%cNCf0s7%s2p$+VlNx7Xw%QQ&|Lh-NWYhqB$ zXCc)h6+V%&Oj?C>TK!Dw(jRSQ9h2*wfHxI&Wv-zpc1Cxxaa|8wcNW=0&qI1v{3^!7 z;tdpkWjrkIuroQ?hF6Wv8F3f)T%;c}Xn$vs8B!SQu4NQMOc!yT_D%+k>>|2ouVv86 zE@)PtM>2c|tDv-LkP5nCkk=@aT6Ps_+C3SD3Kp6y*JYNCq1TmJ#yDdgaGpt(w&E|i zWf}BASEyi=iFW}a@s_cxssK~5W5B!1hBt`~32|eff?gRk)Gg|3h60vraQR1f6Mf`P z3E-m6pN)^QVg#^8JFfY|#!^ySgWaCsCI@;ZE}O5TTkY#aQ}&3b=CV`%(O3EPaa{ zQ7+?i&^^17DW!*)%)j^c5Di1pIa$mN!1oLi;aXBEJupbzT5^3)5wBWHGExSQY0ipe z&bZE$FE4O<@_tGQE`v{@b14hbzPGDn$RRKB|C?RIF*w7h&1(n>effN zwEQMCp^xY}|j<9_X=3y6_oq2H$|?b;9iDa;6T9|Jda-UF?!|jdm+k& zg}bR$0~E7taTXzjVzz|Up^1IPVy$^N{n!`9m>))o*NdZSUHY_(h$X$BNKYwK!3}e# zd0NX~hr5+*a=O92xh|FZ_Y(=#?*`Ss_*5ipS^*cg(JlSN^e|@H@mMeVv7hK!BL-=F zvpnpeKUt3T%#U0~9eo?x-~yTeo_IoMNqSkWv_hT2yzBeA!CLvyMO*r#j;=QGau^Tu zl&j)3gO)Mf+HJ#oflCQ-YfCTEL*R9Q7^eB+xo*bOivvV^4Tb*W0P%@do=PPHMSJx# zIz3RNYbWZ^*o7jsMp-KS)|kLl$fAjJSJb6GgGB9+zd$FTZv0YL)(y3g)I5=*_M_B1 zF&HcRx8w=`J~C+>`K^p%C^vo`Zrqk=R+TsE1gl~lMCUw8d8?9Pg9T2P*Q~=;q@!9R zzp3PDbs`Fiw|W(~#FOfxE;Sg69w)yk4HzowYOmHIXV0iK#|yx{!k$YlCpgh&cG2$X;#__%gS?iqyv+zb=X$#`gctTd)+ z{~HhO3$H{hx8dDdx1`!=fmdArsYMqj3IB_v%!`Wm1^HLQtALffVJ!wGEo?Y{f)7rk z2qM33a7 z@bP;fUraJ~5CR5ff<>O@M)8hE-Vvh3aH&pSv6QUi!Ys+UyR*N5m0H27JdUE0EaUR; zZ+BcIzK>H*reVPIE*K9RP))PUJvWNb#=hp2wGL(eD*#xA8R%&~Q;(_EGA} zl8BKaTBTzXL`LoiWMV`32i#O?2uc@2*^={0Ls$q-tU_i(m{6PYCW`F5_9ot8#;eK@ z?0BXjjI!b7urP@0xPzRd#X0(Hl4zj5M=i#PRh9l+sam(epjH~ls9_a{5`&rCh4Pdt zF6~0!PKMhS4TD1YQ{XFpzb0*+BDSiNY35WhSX*C{c1;znMw_e7$W*5K6xKu;U(F*c zDF%E!Z3LPa1j>|B)tm9U(PybR`R~Do!aAOdd}8IK2Ypp4il-J0x(UtTCYp1TSP&A1 zws%G2undZsCUh+-iIS&@8`ZC9@ift)S20&jKCNg7tQodcYWzARKNv}1^z~_i6j-L` zQrV7DFa*}T#iULbwbj?DE`DO3e;C}svUVZGTZu{qxraq0(zxkjM6n^7+kfN3Jy(SG2x8e`vTXc1${kQ)ND*I( zKFP*%KR?S3Zx7l$L&Sxpcm=m86wNB3==uuP>zM%1IXQN$XOOL(xy`9nIciV zG{z83DeYFVkH*gwDNQ>dmw%6-sfDsz0-j7nSOhf0{;u8ev}vYD<;KNS3#y-?riO%F zF|~40MQnv0P8^6ai{nVN*8aaAE!5G2UrHQk}K=l!NZMJAG7mjh6 z(_8U!YmBz>Jvwq8chp-d_P4bjgLO?B85Yq|FPhs}uW7OFs^*Q}M*T17EhFxF->ebz z_8d_=t$*w#3P%&n=hK-4pM2mlk4Gu-u8o)D=;9pFyGk?nRSPPNrRbo3iwiD{FVJ$x z!bRFo=>EB4ocb62G*{$kk0esld6)@)fyb;aVW-)vm-Lv-Kj%Y_sIGAzb(2?n#X`?} zW?baUII@@<-Vl47w$Brzw4dfbz7l@4!_;EFXr-Nb`tcJYiwft9XNFuuIWNV%Ol@qe z*0oqgImeY;Bo`VlZooAB{YHy#L9r#!=37K!y_eBau)dg6-lL}I?g|bwxQxv@3QotN z=x>4R>+=L-Bb~2HScvvf0(H1m46}BKuwqoVSyOPe6MtKl&6^3ojty4k9+ZhxCerTM zYFZ+8h-^YSUM9&T{Q%tvIk^bb$+1BsxQ!<>WfIo@F-v=%r#A9-pkjf@b< z>NvV(f#_Rs4#@&{>#W8u8*bN_WD0iOlqWu$WZlo0kLG_Y;!?0vXSA6nXh%;NHg+QX zDC^PO(UWIk;R>U2-q>k<`*02D(_^ zg(|(gTyHq2g&A-FWzSoEtV(rR1!4JtUyT}UQ&30X@Ycyz^yh7&9X~qW>~`_6TA*Tn zlnURGoF%YzxD@Y-uMC^!Y1IE&|NF4C0R{hjzfl>v5Bd}5qNPRU3-9mvKOtaX#PQ0H z7b{zA#s-G#!Jx2ea<0~$x-As3QJvp0TJK>sjKNgTAm-3m@k!zDm?-}b0^eHy16T#H z3d#8vR9SKf-4lK@KJ%kr<)_~hs zgsnyxw=J1w{1zsNG@JAIb=4v^ z)~Rn@q=LU9Qw!2z{cHvAu(=wATo^FuFH~_U6|AMufs3N7ZQktM>j`)mgiOn$iY8o( zz<%ayV3P|AvvYs72k~#}T{4z|xG?a2>4a>k5^%A#(Ng_V9RSFvqL*GubM6wYCcMBR zL&QMUyoxYOHG9qY!Tbx+*YhtN6R{`NtoaX_~6XmYB zu<%{;UE4S5*dB*5=Qe-_ zmWB^imeVRoORu7NmP3wAnpGfL=v!Gz%So;s-G-q%XG- zyVW9wv@=O~;LU4aow7ZmZ9wl*$v#d51tRj5RFiCo{VYVJ?E&_=LZR);Vgu_BeJmT);xhzaN${0l;%XpN#qCMbvS@Opkv}mzdBbc0ZGu04ka<}N)MF#ndORc(8 zue>SOjV<-Obeh4i4#497)q_zhhq)_G#vlyePu8HVcf-xPE|w1Q@8KA_c(<6F@GFzu zjXd91=6NlK?pY$zI(+s9q(Iyz#z6dV;IoBEb463Z4|RVb+15Z)^V3`vL*F5P@|&DL zNAr^8LGyM){=w*LS@cI^C~YYQ2R&kGU!yD2H!NadLXg1^kgj@%AOSP=zi2Qe z9}D|v19@tO#8bCrqFJ}`D56xC^IxyP$Z{&j88XzEJ7Ox!Nks=H;}l%>fVg?Id6`IW zD1%%^(3Gl@yN$SfPM$dEZAhd*i#RG27f5MHK-QxcB{OTkfH*rBy(BE%d5_S02C~v2 zAdeldRY05_ud&3N^svb$-o-K4%r~TPnOT=v;T|JA$qX;B!hJ?~Tven>jW}Vjo`0{< z4K0=%;c8WR6r2=>($CS+dqpC>=+9%)`8B$Vf->p+$a&0yGD#e+D!EDGGfASLjj4fF zmP9UtgZIp=e2=nJxZ4QdWro+c!t;&rH_Y%6SPH&cY#WiCL4LK{%D}i-@PXo5B)PCNUIue%zV>;>@y2h-par?Q)!9E8QN}oW6cQ zbPDWPJ$M^mj9e8|EKkE0880>fy?D6R|wHdwr5Jo>00&G6*7IkQL zT)5uiM)rVU`HbJ_Q>uCPH&|eJK-?ICDjWyap8&EPJ0Q(UYVojWl>C$_^yffp&dNeE zhIk4|btk_fh!cn9VbSD!SWK<$;g%GAhQ_*pp{n@h!OK0!4c}cux_&tvdY{qw<)T^S zn@hMek1x7U@Cmpi`siiwTDDw7h2TNwCeR!FzB$$D;&RbF@prUd?5|PKD6q15LNoEz zOLXb_h*~uJ5#dVO3KITy4=K)^GrV*?1Ra?Yl@ia6U=Q9;ypr?rTB1b*3pT%eW9 zM!lVsT!>Y`oEREgDEe#7VrWyLn3Hx&#iiLS&5dv%?KT*iUXBeB-Bg_T#t5nxb@Pe_ zlgyc&n^$OY+adpI9^=>Hs{sV~TG02_1H($dUUDb2%V}|(+#6bq0s-Pj-23pRCy9lF z@6F&O0`&tred5K`{XLz|d2ws&ASZR%E;2_UvvD#*W^lzC#3fNUvf<)AqX!c`3^63p z(pc~QmqDx%mYDDuj?C}IA>g(K!PPpgcvLiv{sl}QgY9v=mLEq49u+g3SQh4sS=6G{ zNG<5-qgcer|36XFu?NrExCC{BT4aDc0d~X!ITfHD{q>m0 zi~@xOZwH`PkEREn7xf%#QL&m0j7%MM5rVSg=dV>8fuFd95ODdA zC6tUN5u&OyX#5i*eP(-;_F*o8dDlRD9wzkIOFb$o*cfw|HsU&Nf^axM%q6%1&UfaA zD?Hz#y_rsfNTx7J#3h;}$D@clNT~|`+6kNB=3Cl5PUl-K$~%!rXG%SK$3}^=JyjhU?@cu)%*BHxE2%Jit65?n9F&XnOyzw0b2DJ8d*c^kotg zBng?#tg8PeF#%$O#D_K#uP_P3yN3Pm1KHaH#E!9xT}z66(_JP{Da;dg zdRd}emZxzL8@u42wefT>^Mtqp=828U7wKJrFzMcb>Yp`KFw!J<9wo^ezOG6RQ=fGp zcc+cqL?(y0(WVO0p#uNZ9HjR|nDYdal^IA6%V^-Anr8&)W(P6{R)js9F44D7iPW1K znB0EA++zFJRk%LQQhdGr7UnKyEOU19J6k z>5Fl=XP23by+%Zc`9x|DS-q*lGZ-@)e;d3?~9%dd8 zx6I^WF)Hc?DQ3Y0lSC+!$hig*IS>;hmf1+mWDcu%C|=_dRp zh7VJ(UY=nXl437yQyY8&!z0f5B5it4bXP~x$E)F~8MB>|-WM&R%9Q*>@83}7CsDL& z4bFSdcpuY(liO(3`=SmBlZ;;n}$Wmx7Uc+q@`Hm@oOuf6PXo7zpfFfdYR&? z<$V+R9>ZVP4@7GE>&Sr}yr;YI2pVRk;8~GL2*ZkKdvry}fECBJA_FALYhmzyffhv3 z^0nC6^bBoYE0Pe7gEY$#KFMVC=e43{n|6SZV<}9SZbWf)3x~986>lsSS`9Lx-eyQ6 z+dWA()Vq+{uM_Fj(}IGld2gnf>qIN{6IzYfyoR8}HTOd<|4Y|Ux|cAZX@oQFV8E(+ zTyt9i$A`E^FHnb%um`o*bJ#4C-;Aa|hw(Fh={Za@j)u!U1|eS}^NIo3KX$5EM9_uj z#4PQtNV<8w$QFfIY_SH0-_Yju7#NnRr8s+@j_D320P`d1(0U9E%T%SVe_%KS+>7yobO9{!tSaM^qZ0mvR@?g2l;YyZ+ z2OcaR!-V4Auwcn&vEd?aN)b4Z!ev!(=*h8SFO$G=E-PcKcx3{petcYJs*S)vCV;r> zX!Qm$FY-mAUdJT$``$>3$N$@m6w~_b*nw2Dw_T)yRnRNhKI_&_j;QxG0d5{-I zc>2Xtjn&QE71h`!It;tvhhZrRJKbntk%%jJn=3rZYXYki?p;`4vE|7Jm14DAmRGUA zyy|243$DJeCd*5vWlNQoj=0^-5hy;ui)WaMNDRg0H!3gkvDGOx!CksS-xrDM*&j0# z=#ap6doF~!NF>F<|9cU~jRj}owaG;cfbh}?%6dVh6_f<#h4^7sUi@Ed%R80xBD@IU zT<;|#I6lLS;wH2_j(f$#-;7^4QnLK3CWw0xVg70Q_lkEzwF?o_KiL5h{6JGYU3e@! zhALhVQR)b4fyRz%z9?ewsF3`>(~F|D_Iemkck7R+ob2M@n2Rl|7<)lcDR2oq4&9Ch zq*WNK;2z+a(IDY|P1SvF1soW-o~u zA;ns0Dn0v>XyZtI#hl%K%}ovrU=h-r752&ofJzyX=*hbn8qDAS*nkjsWP@P<&tXYt zHF)IN?aN5Z{8mU>n8>3-Us$-8S2AeF>c|9oc$0|MUJ0jFo5Z8q@^EVTGCbtV!j0+M zE#W+UOQPbJMNUXzs=EbyR}x4Ri?FN+~(LGg&DE5Add41?}MS# zrC20rwL+ysr7LehakmI^sNBX(MjOd*G5>${_kVAIO5?JY4wsLLu`pK)pH{28LHi?& z8{7=qxmk>gz~S+Kpw<0hl(t1=IVPAYAGMQfG*q6CtW~Q#U7CZ#mEmtA*P#h34+&QJ zd$P#f6{XKZ(--5?Uj{T51NUlXk&^6Pu+0^*NqwDL8e;#_4IK94|AcGN+P znyz|#Gb$>-Tu)?F7_yU55%)$YWo-qjtD*MQRa|H3Da)^?pSOw_ z?Wt;XajWPx@_mQF?YsEph9=fBS#WzZXtEb~2;!s}gVs$5^Y7#XKid%(*ciQL;1u_ig+;5ob#bI#rA1g!>4Q$@qLnzSl-SAJDtM+V{E|9MT#rHI^0?E zZBA~+E`iw~>+ocG^T0qudS;WTN#AS}vBP}$wTo_cTF@yS0lUkN(Sv3WrlQWvVOCi0h0!|=Dk4<6&jH0K!`FUx?$X%wWr zllehgz%A|nAsiD(FZ1^_i=RUIUJ+JMH6d5iAVNHgVL>d$Sm=osA*3B;3Z4eRS&@=y zcT+Dbg`JoUSqb<*mPZgKLsO9-2k4i-ArjJGQ_Uyy%(yX#V>9LY#H%Oq$p7veqKTt7 z+>np#!V&-3TZ9<@psW~IF0u#F_2EH|Y#aB0L>ze(gtbTDR(FI2HB-tzwWkk1ml?UsvJPYICRZAd<5oyk-$W~$&C zm@0tec&~1+jj2t{6ynyKOtJg#eVS8>I=Iv%QIAP1yao~rAvZ{@w~<)RBoKFxNupn% z+#W-2cK;0tko)9j_Id`${Rcg~OQhd4+~nyTo9%*Y;AsKG#*=z?*m$~;c|zPs=84I` z2R8>{#yA$8pP_;_Cb=(|oZ-&CvQ5u}3P5g{ja*kIhq$(;3NE5Iu~yfZ^s|cDGnuUP zMtYb=J-_?!5)xQ8u>$%FRL!%7Y8)o7&oQrtANF&NBi!um*2qUJ-{a+q*@q<5T!6xyc*xkcr=v z@h4n^RZf5|fWOIxzk=}*x7^gl4dmS|QtFNjknl7w2L{xObF}zfkv?v$$$`Qg7;f<^ zOE?Y^HuU6qY#dBw4iJ}baHQ2x*FLWfbghG=Z!%s{tp2Y ztQd2DUUJbJh_sr4!8S`6Z78JF&s4}1OCcZ}VJQUvZ$Y{Mh14jT z#tI3j4nitn&>WMmSmw)ceqWid-Z)0p*pv5vHog`zUx=GWf4(bn)LW_jdm?>Mj*0#Q z+o$0UzA`#ozUy$xev%EnAEP6#C%yC@(7kl}JyBnMjB33vT1S*N^>T9(s#Usz)iiqM zeNiXE*UTG>s1qtjr8SL#vUr5L*ze9&y*sdo>90}&V~h2w;S>hH&Aop>J0IeYoxBpeqe(C1rjTmBKlIa?Jwg09Uq8V^*=)nCSM*Fu$daH z$V^I0?>k8NH2(hiKs0GH3yIl^c=*UZ;y5n9wZT5($w(9EBi=$|K7@~WL{M-w?{nn+ zP_&8)$s{IdTsrU;mpgbPg>g#^^TbmJ{`F5CF2SXljS1St z^Oz+XY2^eBIP5LHk=lPGdPg7p#@H48wgcBo<+q?mK7!JQ)8>z05V8wJU-&LdgF&_h z!*fDO($(4^na?LCjXez+p`N_nHj>SlBq9}36?N#sc^uY18dX!iQJiRU zQ0Z=gYw~f_NI5+{#Z3*5h?x~kPp`^KENUcJsbOQ~9BU78zx$xxXbg~Cs`uXiK?V3f z6MVr8f=>AEMgHIuzHcIg%9A5pH1!jaKcauRc?N-NE5L^1`v++W@`NrJjV-b^2p_}5 zg4o|X01j4}9^OY3zqMDNx5^vgs`q+I-6t9iy4RGuAdz_>yVl^jxzp?Oo0M?1_emXBkhMJj~~SH zp1P6V{8F5?P9#Z0cY6b|)cAEM9iWzwB6b_b+7SPNxDpX*f2WGCL?fIP%seDE^(y0L zjXe>FE>jIi9E0p2zb!~!^!V_cWKyPQEx%$wmMKVEM70i!>4~Xaa4^r+({bmO3-?c< zxBVK5OW7z=r|07ma|l^AJzp@rJvbQuh>hL?iyqS6{LDqd3EfJ6GFq?ylj(8J0>5&P zr2A{p+_ByupSj{#P;pdB>gpII=`kGV8eyZ{&7zF7?da&&IEQuM9Ci6dB-FUS;ykTk z|K?hp9zj=hx`HNug9F1~R?zF;h_PB}1tlH9t&&Z^hJQH)Eh4W3^*~@XWgX(V_2jg5&(n${A}wSp(op#koZbKQh zd$6PEIsjWG!6n%opj`S2(xTTmDyFO7mUxef;p(*@_JEgaFE|K9+ywKp5TBza--|D; zrL`+r*)h1G3T#MIEF@Uj*r&|;98%go&fF~V3S?Oe*Q>ZEk4AaJFMJz*U6|6=6AD#f zEBgtMF0H1tejMMgeHZCXMO&HrQG)k7$wGY5&0vAUd}&xhPblsPvlgTS6n)!xSQaCiLG4z!#>i$7Q6sPl0VrA<9cxyMmi z95T^3?WUe|>9}Y!xe3zUdFfK3f+590@Wtb}+prUuON_%lHN)m1EYuA9$PBv~VMie! z%b5CePDS?ye6lmHsO)c4K;+$JrkhxuR{kWC5+{Kc+sIpgou>^+?uws~uOTG+@F$VX z42?S>+NAuB%)f#muB}_4;I<&Tp+;rmt|vsDkm81B^2E>0rbkbTw%M@0MkeF!!T5cl zN^$s@Zp=Irs$f2q@ye$uO2kRe#Y;nEIBWN$$PAwY)E^-X`9?V7$o;cukb4|TnXkDk z?z?;3w(HchZCN2Hz_-FSC`MQk!fru2t}1^*sax+Jdv*izSn)N^(w3ja4Rs_FTxu2* zKJf2nVy82+egiPU#d7G+^Aw@Fw`YYagCbRB``@hP=;X6VT-dN%YZ`Y-BsGOZ40Is} z6&Dh{je#3;7zvCE3%hMR6W0AKmMsrj1b#cIHch&4X~@xZ#d`_bIavi}whdDSgN*q< zr03sK{8oiM;8)Qm_A5mG^dCSOj6qjk2DIxRBD=_uX5tP9gwEty5 zXZ`u#8D%WSY;YM&$!Ir3{uhlh7=vn80I_O_akGl-k<2`?`kZ${=)t*wBTL;67OhD{-A1qi>4|2 za25l-k{pdx)0D@~40dmvAELbaCmQV6koZ!6?OrZ|J9d%m1g)eU8%cJYIeB%s#a2B^-jg6smXR$})h8Rk&5Lvy?BMmpy z+zv~@@Xbx`!QauN4%oTz!a{W;H>qcE(1O!Et6|0!R=4GHq~oUaxI<~#aJ)*7REX53 ztesaBEmHan=7pqdr0L z?nKBTw7-RC=-fH%x?6UJ>ir{fqiZ0XI}XYDYK;p15t)grp}=`i_55m*>Z_PS7aoL` z-?|`fY1$n*#(?DwntOW$x}c4kvi%Qk*&))mrsiuQ{v|K1H`ybN(-q%eCL=>0SyQo#DVTBm?6{gm~xX*?0EsXS~-;D7i|DSuxfL-@1WkouB zb$tMN+42YB(8k+v+U>$$st0+8_mE@8<;Xh~`%Ym`6;pBD;PEh}VuPx@`aaUJnL=-! z!@j@=kJ!fbjb2RiqnwSk6TeZH>dwRvHWND9Noz(wM>%^$ru}NvWY@3ML3a+WK03_X z{cM4+|jDjIxE(8TJ_{JqAiCb+jgQn{dt!`y3(M zeEcSyw`h<5LW}xGC(xZv=MXJHqy0{2R*hyLdK4vuZ9^z`{_MtdaQF$@`JyeCmt-9qjDcb6O=Ahm4Jy`d{NC)bST!D6nRvJ)hxnp z*NgbpTt8D%oHI+?{u}j*bM{JhVN*mJ{?d7K1nV{=!aJdLq<1m4P=E9r6~#GoYjg%3 zrtu&OmJQ;UlT{tH7fZoSCj) zOtn3G^55g*l?bE!9BrzjD^fjjbG0Uk?*jilXZ(Zlsfu^LY^LLimLoE{hn5=B1pjdQ znlvK;rV;To?MiUYt#&!sYz;S*4pIZz@B^e*5Y zkMhe-&(?I-)h7Q+J8L=? zYxM->(-Y7Lm($adeGIhm8xb(8_!EGSpP-vlU@yy0(9T-U79nNx{-3rtfzRpq;>PcD zlgJ~OOLhratw9h;?2$+)@N3^ku@alYR;0smo8yZ6SSJpb2UF{sH!1jO_*8_RO&1^RT2_*kLxcZUs7N zJQMWob#ew+b~+)NuS_{}HER}B3UoA5*G*+105@weU{M|U-PCmCb(3@yQtI4G8$Stl z3RJb?mZqxbw>4GWgepi?xNoOeRsD`k3{}kl1I4Op%q^j+QfG84%E`wPZm?WA7L&re zf!?@VB3Nq{5>Reo(Re4FN^oeAk@*mhGx!G z@%_%};+Y91?8QS9<0<+4SRflJhuq{*L99Mifscb&OM-iX*hKW$JT{o6$pJU{^kF-i1P`Xn9naEJnBo(doi|o#>4h88HD?%bL``v^PhVeVf0Q$WkMA; z6meA0aI=1OgEy+of~w3GJh@xc@^dt5+MkCTN6R}On=gumvA>r2N84^;o7^0 zb@dH?y$b7Ax{c0QHOeHpl(T!tXkd{Qkc|bdW}x6Q`L<<{tgHNf-W`r)g zjy4tDrKucpTP3MaNSlBbP!{26pXvQiJoll+YAi^O$>;qEj=IICRAYYi4grVq6ZB8v zo8}3yzF0|pANETlNO~U$dZ$q_%ov@V#xVL!HCEB`0?WbZeX`AiT0Nm2Y8v!c(0)~D z^`v>C)_(m7d2K}@-hxgfEQzhL&u}}gIanp-th_4aw5AL(&c!4pY$d|TCa%3c4@-7n zkxZ5%lQ2D#*@c;82adv5-5pFhxIiJNwtXfDqfBT!83oBKQjknE#F<6&n1npai#+-y zbsA-#NkG|xitA~Y$(3L-1b6GE|B%W1H+Z`c7O1Ujkr^8`JymPzGO4|^SXt$gUw|Et zQc}clUbhBw<3~c6?>}SxFya|H(48R-jb2VunQ zAJ`83w`yIBilnJEsna6+JUZaYgjlJS7@9S*%YKHdUSsFhk1k%Dn6 zvLw463Q6T*m_=!*sj?znJQncjeJy^|AOOuqrf4$iFh2!T6ly^qW66H&V%#tleZf>G zY8Eb`%S*sHRA7{YT^Q79G~VKs9NeuFkR}n0lIhb=1ZSW9%0H}&86WCHv-_sd$iK81 z`(Y&e7CqS5YXu__VXF3ZDH{8Oh6(zIK``%M<56L(kqdE70_=H>PYlECul^1GG>mnV z18;DvkMb5@R*%J+Vt8IX)>yuCo%@Beu;398db(I=aI?~kH61h7GAIkJJz&<9xfPA( z$Z!_u_z)cNq?ILbcb2zordgM$16YlySnz`7hzKVMT%6}Q@mMpj6~UbAKL+Ay8mMBm z+E_}-b*>Qh02|ZqA}$_185J*XqNI*S4HK4+iSP#ztbEWzy-3@TFz2c^M(M8GiHi4x zCwxr=Cd40KY+g_+;M-)++pBE0F1ZfTPh#;- zV|E!=iD6eK#O)e?zdq8Jy2fYJXNyD1BHrJ@s~~;pBIzyTy)!Jkr6=dF@^%e?cj77^ z+JMb){RKQ(WcLERGgrAwL)OOg0KyG=_-;Ig$7buEtNi_jtcu@O#M!1uk10ML{MASN z$D&*JvTnG_H#EdxeAQKcz9Eb9oL>x`IahgTBNpm9(Jn3(LLCpD8ezoL;|ibB2sDOV z<(nF@_gy<7-5#CCxF4gRv;%%)=IPfO;VZxg#StH)cEck<<^3D8Dz5eIaTnr- z!>fETg;%!^9}1_HtNcV`%yV8`;h{}g2w&QSCCkUe%O*MP3cnM@s&I1@3zuhH;Zad+ zgWOjHzEv*3Rc*e-RZWO?Q}Y~r!~VFI)utKqbCSr)vU?`Mz4=ilZ%ei^$sGLdN11>tg`2GApI!@ zM();*d0MUe>N0QCf`vM)xcr>A_r%TnNiA4exoa+;*8+m5mCIQN7RuvVGP7*SIoY2Aj=@6}WowYPdU_?!F3)SM zK1azL?)O&RF<$Bw>&^da$-35V1dgJ?U7!i)uCQl%sX2{TX-Ma3z2e|)brBqUSRVq~ z+ROZp&shY|Y{hDZcj<*a$F*+f%Nv=iK4 z_Ij(vx30u{fVbKg2y`>l;7dHR4GZ#3xb&P)L}{tiaroU2PhULm;DOLQ`SdpI2baot z^EZ{eEy+A8n)&lj-(pw$wMG`^G#|0Mj5US&B8yZX^)8V^X|*hU)EL~=I6p>8S&8)r z+PszU!G;)OFS)TA7~rFRi}VKWmtarFql;#KCK~W6J}{h^M)UC97s;NqkQ@21{3Fh&K(eL>|A> zjz!6LF7nX!>=N$#t=p2-=1n@VX!+?yKE4AB>Lp>RMaHuV>`Qj^h|WB){knLfKLhav z6A7%O(1P;Ci<;EGxj+*YPhPeo3y_aqC0=8n0KT>1SDwVXpS57FoS}9%0xc%uFlBBwbxkPf{w{$CzHuRnVc5uKg zCk^jcoc+VrG?P+W6c%HmUt=YbtGWpp3S$7` z5~w;i7!?x4MHu4qS7FfxVNZ<=6|=-Kfu$0m+8v9EZG-;>Kv1ikEAlyQTkvA z1{b7}!-z|r`dLOg&?v4meK2FvJC7;uJH(|=>i1Z;yTXMt3^|H5?6`931cPPB>wU2N zVr=UQ84nsGGqQdpu*J$^;X)8aQ?{ooi|{-|98&iTWf=v2?;^j{12z)Sjg^+?T;QSI zFzx#M0v|dUfr$vLF%DS98bNV<#(_^Gn-$$yWjW;n@B2RUv4||dU~Moe3Ub}lBL;sE*jDfdD=0Jq#20G>Za^w(1e-39 z5d_KSej)vPa_^onhU{N7BWQw`8b3gH|H%k0|00Zl=XPUGWx(GU$`(d2?L6P`KJ$t( zc?g}SmlPF0Tar9f6-fe0O5sAkn1e@Xy3IDfTEXEg=c-P*!2NnL-vPQ7*CHvjC_H%3 z2_&Nv$QGRdwA45jXDGHW;)-Q0$z2ULSVQSc3k9~ycu-H&VzBG3+E7FE zrR7poV?`N!F7T+{v_|p^ztacG`lL6M)j(I)QoQ)pMwW)M1Qy6YMHtE7e4dBC1NoW82~0`8CHl}UEOy?_2S0u1m_BeM+R;6D|_UyO~-cmV%Eks%V; z9887;3k0}92rkI)XApixOhiK$(}r_GOqLi=t!XmE6z!=}miA)m{SRVVhqTlJS4-TfowuX8RbiIRo}4}-o96b=N-lGyu&;@Eqa}>_IjxA7_?A` zmPKWS_~K;MMK`j+eOYPC*rEa>LLf?Z)#V%-_x+AJ&vB0PVf%8}Nq5b7G0Bk{csL4b zQat3Y8(XfY+J~5Nm%_UsK4qe-I_>3Uv)+RXEAN7Ml3Z0?azkXvLYtYdh;H;hh^~TB zT1d_brOlHtYPpN5oq*v)u$)7kVXA|ilZN*z&QjR#O+>>knuPR8rW{-ln)43m3%m=s zdok8x!h(WH-3i3p1bl2Z7Vkj348)?`SJt_Ij6GS>dsH!cZ}|_*{|-qTb>=i^QO}e4 zrX7dIm?Q#3@~`5~RbptBq|U~BI+hG^;df3R!fWAOs36``EH7?BTDpIWpz5Or>>Heh)Hb>=$9W>7v9H^MLc*vp?qdv(E9z{#f6d1U#AN^}v$l@cyi{X$&{@WL``rNnlu)1WAlI z$5$e$S0W|V$&n;59LlCC#4r6>K$5M#eih$HFf2nA!m zRIH(jFchj;0;}vl7zqWV5KS4<8>*b|+2`CyME-pxpJ)Z|eva=E_y;>`J zy-V^^oq@cUN#VjMis@Kw$cXCQ30N#i#~T}dMXOx^46#@pqQ&~bU^JMuCDx>lBy*kwYo&KopGA%B>Rl|X7I9`|An?KqC;!yP=EiCxal)Iy^9C@tUfqzC zM%B0yJ%_wOAAy|Kx_XITd^6&HMi_O^)U)&z($_}bMA%HC42I2aAIM5OB_fT? z(}v>x0^a3*XZfvxtc}uEFO^}avG1W&&Cc@o-(x<(4fIm|52FkUg4jACtyY1&)Cc%Y zc4<2Ece^CUo1W!CiL6SgYUEs`?aA=YiEyWRaE32VWWjOq<%PLUE1{cfTzT~zXi79D zL0&OfnuXW2OXthCskC#T=b zVnH<)f_Opmpye!9dNs2tc^mbOYP&#IhCve>&d}gF%re>zQRD^=qID^^JB<$40kf%k zG@EkHcmXa@>P)jqTQ|{1)|ryzqjm?5F|v-qn#r?JtrM9I zTTt12sIsjB(Q}2(q0ne^Sjmh1lpqr+7v#$97H#G?9_hO?`#P8GM^%YJO&rS6qdfEynEJa%v z-_<}U*YbBmM}q5MN-zWD<3QFj_7)iz5XS1PqdnnNFC4Z>>a@^x~G7Mo0<+H5U_7Mxiz# zOw>6~ZLEfbZt8jjlGwjF^_(}WguDOUN3bUHyFc?zBN)D>4P|h|BiWlB*=JPopvsNW=WX2n=FTZ@uV&te(-0u_CNv?j1fA|RtmG7P8 zD?ee~jWo7Tm=FCXhfV)aSws1clf2ibtc`r(B;UQ7Rp8%!%3S5uC;915S*_B^S=hF~ zUa3f~j6w3vC%NBP*2)R3LF!5V{#fLYc#;Aq=L@X?I_{28>>445Y%N8%$z=VOCTAzY_06z|an zA3|F}Iv?ABY0t+;c6`j$sd(sA+T$I&wXm8f`DG4?;=}4U5jIZGJxb5LhmLm%;i9F% z`z>DXV^+g-gg5<|`G?09$u+<(*M>Uw9v%Bh_H+IdHdT3Y3&ovRNMaQY)i+CmE~}p4 zW0F{?@(0iou}O|mNisFtSxGQ!%thb^5$2SDBSbmeX9B#gy65m26R`dKMGluIqM=RB z;Z*<~Y6E}8rV{0Oo!ZJY`DHf0GZCBClfW1W_U#=0vbN$Qk2%5HO=8U*E`q7T)a&%r zb@kNGvbEIJwA79>k(zgyn~gb8uI#6>tAJ^YHJAt+VcU;GMf;DYn-h z+iclevB2<`?5cXtZ_Fos&T2JE1Alwb%#OkbES|zRc0Shn)O>86(Pr5Gdg#iqeU^v! zD-IQ`Ly(@F2fCl&m!`2sywVibR_=I$e>jDO`1L|=^&ymA4z8*%rV){8lInojVA>>8 z4$tO0r?8V9_h~J14kna~xlh)|R$?7954_w% zxzQ*Jobx&S(o{A@ma_T4X>cCDp3Rp}V}3zq@Qt3e2(FJc6S&0xV&F{!UP=xhI32Co zdnfqf>CDG>CtMh)L)1p3Q%7~wG97NG0M?x0$k7@3aR1*XA4aA^q?l%(??l#AH)J*2(gz<@6Ht&U? z0#cTlEW)n`=)m#T-HgZR9Rv*^{CS+8n8~U*F9fr6g26TuR$Tu$Z#0XA`r43be$~QK z(X84i2)VG70h7KUPSxt@QT}6~Qi-3Q#hUXvi?E&mv-h9PdiwVU725r~iTzi}N!$JN zuPjv;l#poS9M*zgn9aHfv=Z?9yy@W2H!fpuSB-r^Hv)Ktc@&WFe;tXR<+Dfml)0?0 zR(8rpLp%FM`|DrDzmc8oZ@ynuD&qf|CnPCLr4sB9Po0<$6?K97a_m(|f{ z*rEG(l&ars9KE9rQtqF}KJ&kML@%IHd;zg7*i?2o&X>=}o;*g6$$=6UlM=9OwhB%p zke}F-NAtfDVYCVO1{%j{$kBdJegfVn;<4X2B&WOQ$lP#h`W<2t8;*J&G%CFkEU9yi zJQAe(SVNGoWbAIO@gFj|dW4*sJb6-zrq@4~>(0_Ca8GlGjJi5V5y3n#lzA11-$)}| z%n~H^85kXnYD#%`016q6^(P*+02aLRC*F4fv*-$$=L{Rj!1#)1E@N$7!k=kIP~r$b zwouz>6(&=MvpW8HKmD`pEu3w0B9kh`H!NfAs_qwG-0=!qVBnQ1US}H@vA5+-M}^M% z3Z1>-sphVNJSSnp5^^?lMmnS-{RZ!wf2*_A$h;ydql8VG1xLwO!`DLOgK3{wQtKJy zV>R^=`QsY-SNt$x64@|`zqv?G1$k;G>L3e(p@7slp$^ch+AD6=dX>(0pq6R{sdGE9 zNu5EOw_%6H%(=pA(FjW@7_6=!L|wrT@tYLf?nl01F{YfYe&jzcX4B2ts5H=pUcH|^ z(KLJXM_q}f{#LyyXMTJMlyU2bCa9D`K}~}h2|d^es?vWD)CJ^A0y6wr{z*V6sc?AY zjxAV#r(##u0eV??AJ)p6b(p&>W6K<=tkk|#=Gn_wxTyh;na_OSwrv!st6rc}g#~(m zI#RSibKy<}!}?d6Z}tDVKx2SuDDOCalk%$T1qwRM`>udnTlQaAoSw9T)pX1@W3;e& z1zRuw{1fk=%6^pB9O9vAIQfMxqnp$P)|y-vm?6P2dSJ2BS?y7*(Lp;rsMI#MnTb#GppCDHsVdDkvDK z^*Tm!ywwjXdh^<=So!8Z7`f8IY%G1o&E1;tzjH0f)E6RK#p;oW_N-zNa_htV(JB_C za4^#j%n0j5Wc%q#Jx7xo3azYW!47b@&Q}p~F_~I|2B&hfDm#ky$33ah4k|3!V&4|Un_#ZG1z>>YK zv$R7S;ke(H%wjB%O)WsbHLSX8AckG`NN<7Y8rIEpf!|xh+~m?f@e*q>V(OX48?9ya z3)x29?RAK6SPQm;@PY2NI)A#c)J}(+WKHmSg{R@PCjTs*IV+X$J{@*qNCev!p`{;c z&c$wsTdCPpZaVzON*&_2(zPRrr7~C}I#^47%NcyabDXn`%V2>dj(!^;@H0Q~of)jM zVKmww3L! zfwl9iSe=6{n!e{Nzrw`u(LsLaD^^jEcey~YxS{-l|ssRd~hxbW%&vkB*v6kF=X!Vy?B#9DSepc$PK6?>X z3t{9MmkV6FWaS{=w~>9o7KIeb@s|UwVHiM_AgM8>_4CG;>hl2R-FeS*X7f6s{l}1qwwP1Z5t;0e7XfvFX(VNuU z!jAc2rUrlFO!$~(K0^yu0ZY-Cn1yW(sssnfVD7(_H4WPaVoB(s^Wah(gk@85c#P4 zTYxSY6ybAV2_@|g2!erRVvN#jd#WaNi^d0q^Y%MgMP^07ZoSLve2|aX$$YyW!FqnI zoO2~XR_{SV(b+)@kf+|XKB_86Tc-J_w0C$V z!KD6dkVY}CAdEGN`VGVkEdaUMaSpQzGanzbI20W`Wr-zk|A@WWPHyI zCCmwuyzw0$vkN}hn}Ji7k2r-sCUX~ac21V?k%uw+`R-jf?jg#aKB5r-dEdjmCjGy{L0W*GTCYUjHBL#z! zU%_sqZnON4LoC9=D0h3C!_vumgwgF$`QX%O{oCjqCxN@4_Z4n-5$CZw=M;C$F0Qx& z&_;^R01a2T+c1n%uJ7aH_c4D96gYwSfql%~OPgkh)gBErGeiBS6ELZ$l^QF`n@D19nuSZFt`*KM1aI;Gy!7XCE#X`7qrAW*#YUDfs= zV3-0`WWpnJFsJ#c!kG=`un71huv>7UFjPGn0@DT6jnYA+AAyM% zV_U#4>Wz9Cf&nCeJ_@`XMc7_=EdYs5FjCbPVW{$!ecXBw>s4#_@*fYvAvqP9(n__- zJ{>Z7pTq>_KiTsdU7G?$^(@e}6sS%B4(U1s%>?E7I$eKE>7eU2w`>-%+LxSPvS`h;Z zbUgrJr0Z>VP75)*uD_-*UDr)sr|YBu)nqUMk>0}ZS9Og9#p(Jn2o}}#gT4Ix574#m zUjFn4ay~Ck*U01&F$i7%wi~*3KvRsnjbDs)fIo?(HN`POnywx6dL134{s|mRQnaRc zOL@@=(n9T6NKLc9Kr!*AV;U=hFpnw~-REz^kJol`djr+2$UqQ6X3K>XG`C)ZxZ$d5 z-}2RX4r`^BkEZ$}qR2?ju2bUe55vtSe~)%hL81)_=`eOmMmh;*FWyswaixnk zhiMQ5w~qc;7}xvyOcOCfvkoNcO-S?(0&hSJ6i4CtdgEe(!4=Kuqt|5Q2R#&@k0n?o zD>X6-K}MgWGJ4b&O3 zXrr80N?y^9p%P$-#80I+#|H_?kmt-mWJYd%+i}r_;cXvFHZb*#4BX3=l3P`4TBAf* zbjAh>)2m=Z5!O5d`|2qcqg@V1V6h^K3sRpTPDlefzXIl7jC~VraO(^ahIrUZK@%*( zpt8Hbp^Yms;3Y{S>^8zGyc*`9Uf;vn5iBz+dw9qZ7Sy2x5>W^7kzsJX9tTk72zy0RNoU5hV5GZvNv@=HpxtN2@CPzysws zau@eGhCS^`yLqo;ETpBVIPn2m8v;jEO<)1)K=2obibM0|7)<6}U=AX!-S|MHMZeX1 z5C8F4;aGi~VL3$&2fafu$Qo#+p(k2~xgH>;h%m(G2V=bjVIP17Mv}>a)6jgua<5#K zRO*9sgK60Y@8l8=y!5MBeBC(j0fXD?9 z(HakbRV<_-t}XC#ottMYhihFfomPMjt3!U&a*c#S$cy^;aaJ+J4}q!9pJrfg4rleA z!e_WV2^uRlSV82*LX`V%?wJh-wNfIkRmNC~YpfA2A!v-v_(;&`Eohh!R;;Dx`m5g~ z&QQ`uNRzynP5ILX`H>O3@fEzZa%uwKDnIPqy*~NF}FrS3g zcE}_$S6yUOKbG0Wk?2b4qNBKlc5(T^|D37lH8$+xeNVvQ;Nx9<#tG&VHr$Rts`J>4 zOYqN2bree z(xO9gyP?fwdj6^nqlB&LliGOLUa@LMMQCaU0Yd}#1aFf16EYNGR8uBt?R*ErfCKUM zPB2Cz+qL}blg!Oh4aK8&Y7vT@tGBGd2%}bcK8Zm;;^>F4V)+ONRIeH$Livw?4Z~AY zuz`5HGf-N0l;oOI>{~tt(DLxxLMswPKzI)jNcKm+`THP8 zYjlDO1~~#JDOf!X9DR_J9Jsfzg7-067zw?&UdfXnH{D`;+@+Nv!(?fYQ*6nBOqOS4 zW)UUV200=O@x~y>FnOBE*SLt%8G{_7eu(}hUc1`ZzK#fUJ^Za0h31o`qFd1EH*dms}Fo>PBO)5j|Zt7WJPP z3+N5x3E$B2xeu@T3(j*V>I~f>S%O?Oyg!AHL7@-Q?wy*)QY=!$VLh$PH<}Mpqi==B zlDuqZ*1QYsb6MLY^}Wn`R=%*K_)TCaDVr?9*GYO(f!|w*Gw$0jvqkckJF+_EGG>zZ z?cn|M*d=-T4&M9<`(Ez8gS%X1=jFZIH6B`kJK{mvq4CgUC-LCL-?@gZrWM=yjB7Cd zZKsq?mG8^3gmdEv`H1@n}1JGgwCc7Cv6nN{yL>toXPm}rpWc@l%11bjFL zEG&L020)Zd8vyB-t;$)P{f@cS(``KTciIS}1nqxk5fRt6;jSYL@8~P3v@HegXBJ&4 zPKA|F$Qn;n%DOOkY^xEp`9%MpxJ7Oyjy2E0yCm-X_-@C(h zSgJ#{)EcCbkN2#q1q-7;A)MCXX_7{m^nuCuPz4jgp5di~?U5((ct>-EMOEYG3^yxn zDElKvY6A>U1EW~>?E;o^`SGW$1Z@);PBWc=H(K2J<7QnexW@H>Tltkga8qV-R#ug} ztffiryOj^U#~Rb^m*lg$@g9zZ9NNks-GgIW^X)wJJ}Sect=#1Swwm7B${RhvEva?4 z@-~ie*V_4#`IV5cL-5x&e(M2x)h0n|YOpDXb_i0SL9zKT$)v7C7%d{zK{dB8G^S|9 z6xv-BI)4kczo17Ve@+*G5G?Y@g&@&lsbi5xeyoHG(LUQmd3Dny>~8h^4;dXpMyPSw zsBzh-aoN)9AhmgiU^QVtB~jyMWbsQ6S)@}B7)K-z{1n?naWAkxdT$Hw^e1kL$pijq z3>&C`kw`-tPTtJd{K@9X+qaM}TrltX2s^V$Tlm07EYf8;5GYXxBznYVl>U7)svBDD zn+|?qe7Lhxji<_rnGgPp#r1j#f~00q@?3nb7Nw;^ra~fVI8Y_b3SpFa6Y_JjGpT=) z?!(Qz%460`ezIB9E!cP;T>T_{$laulTkDNwnMc5ZFu+(FVB5XdM>JRm9z$%2V=R0>RNGq=<0cf9WZ6#%|xMiR2ZV z`QoS8)V7bHI_Hg2Od$gLJzKxvHz_)T=ly{*V3nS+$@1|{-1>~glurH>#i5T>(3P`) zJ!3cJGMo98=cr^qZ{n^maGBKYP5k{AXvq_|@`W$p?R#JoFYyxbvo`U_m$+ne6i<7= zV)@yZESyc;q@A*)%2Hzs_p#yfz0ANql?!U)A=n)0G0(0x4j|7%aA7n-y1f)D=nBZd za1<;9TDnb&JdE175#f&tnz=6SXy-hvZ~ebgn%{9ydYPR0 zgvapr8tMpp%-+POI4b@O%zoA^!ojNPcgn2r2O31y<3yO9rcR-VeHOs#dBVpjai6=~K} zHfh)M95E|BIG+HAq|#3@+HsK7cM)<_xF}i3 zSp*^PAmlI%n=14JIEFaED0SOQ4)m@fdcc)1jI{`lH~N8KtpSaN%U5f#VqdRg@ZKCx z;m|_sWuKuO)G!)D3x81t445g=j(C>Vlgx{owi|b##A(rl~ zr$&PWRUBQK%NTTNMZq@>B`O1AvffgtZVFFO^(6}WZ0KX1$_u0+?&{;cXqzTzfsYx+y#5)OFg_tg_D4AM3QKS%nSS^w6@7yLg}#n74t?@le8=kTmH# z0gsRemK(&k0!qTd%ywpJs451gPP{AyFXZ6FGreW+0*f;)pmq$)3zpQckw#oXUCe!p zeu#^Q#7IhX-(u)SKHgLD49e6s@gd@8f2B#$O)vl3c=zAOw|Od^l9{WkDRUO2(?*LwccOKIcxEfD`gMtO7>FPN@|%Qee8m~YDy7A?NG zp7-}wcFXJ6^PuudH#rN!EU);m2W|~KFSFM5*3tQexp%BZ)d68QcLvw zyfNdpH*=Kg#)rO@GJCj_?$~XBd z^JyB~DnO~|b_!)&Q9>H=m9x|Z^<4NPe;lCfl2gCpk%3AA&7p)l%+DE=tGjh-Ivr2> z%R#QL^2`yK_~ZvETjUeze0i{PUmo-opH~S3g%8uYUuETlT<$AACPWG59#xe0|4~gDAxBv461!UYo$8?UM+ODXkdI{W5;c@da!Llj zUPHMqPg%o{)dZ15z*Qp-GRA%G7AE@x$eNOH?Grfc(&#tSKBu)KNSE$*45q=<2blz7IaC!&fG<~JU zgpB*C3HyFJ&d-RO&|Jf}f(KgP?2PW;T_O}8-^q5# zdluoPS%ea4xJAFo%b656o*V%Uq6)!HPO!NL&`5GqOY&S#LJg`*TYb#4Z8eXIMBU!7 zn)fBRW;GvAaQSM!oZ!OMd^ceGIZ(wC3@wr%=81TM(V7S~W@~Cp!tj#~_UTfWND77|x*^MY(BMCj46q|vyQ&-tS7t%7 zDR7O$G^9n5t=%GZQM?cxuW}JQt&8%!9fwxSp7k&|5)zLJ(uaUY>T-(B#}1G9Ye0A? z@?Wdac^i1xMkvZ3Zi6)P6T3~-H5HC)sQ7A*u+4C-au`08!Gd5WBHDWY^FIbV! zMW)CgS*+<*mn*uibJV!l1w^VV!&dT;MoOUfD_E)8K+(YR<3onY&NWx*C|y^+I_#tm z6PWY@5y`g^&xfxm;mLn&q_~vY0<`X6fzG2`ZlqKU2o+VFMpqs06`KSEz?~_ zVxAl#yYo7Yjq-}FAyLoVXC)usSm|qWHZw*WQSbeaCe0OVLJT z2A;x!x?ru2&jJ(nY3Sm)8)-(%7}rE`3W{-}o7$|#r(Wo*TT74&jWp?+=SBFP6(U#f zGZ9-P)D&pt@vzp%`)D*Jqwp02YG#O?Kg5=k_WKInLy;y9t*cy0yQX>66-nI)f;JqE z(V8cBtKT-8)^Y|kRorVFL2N2|=4kBV9melCw7>NGd;A`WPfUWy%`d}J@mfN2huhotu@!v9n%K7QC9Uj!Q~3lGV-kmx7qt&`1= z1IggUB<+(ol<90@z)xdfh8;6gb!PCbEAy5vKrZ-NQCVNP2hWXC8pxeja-U{OWk-t3 zifyJeHI;b@=}be}B(xqS`Rr(=u}A0insXclQ@cu0Y5Zce@|J_=RvWJoqlA?UXrMMv zZ=@!ygEPFBf7rm)d}xd^mD-ZOVsMQ*VCUvaJ96L`A56+_u5>NgWulqOmW+6OqA8Chb=qbZKZ(}AjQGSx>b^2boi-r;A*vzS z%@*eZg=k-as=<@rP~Oxyh;ORY<*Wq;mtU^P>eNDUF)4>P+qfI55w#KDAX`A?k*&iz&%FX~`Lb3@?U)(`Ir$0H>jKr&TDc%x%c_RX znSVjJTL_V=%FDD?S_{=3XrLwxZ>Z+s!{g~I`M}mnuh2RuH(i@ygRN1GG;~oQYddvM zS;_CTR+^ETYrm;9C%L9`Q?y){zl@gK@rQ3J?%qqWqeb6`jYD;$=JKH;J*kKun?zcv zWCSMYs4mb>p*r4N&cAD;v~#YGIBGQM%V<3MEv2*@{037Vp+ETuUs$V;SUQ}8k6$e) zAE;-NYL^MtGg1Bw`Vata76P96P>(yhqg-T;utaQ=N((1b06MRcI0>4D%A=& zLSbvU{S2``fT7WM?ZUwf)w6zYD{0PpnZyUd%Jo`?#U;H77(`6~uQ-AE^5M2JW`3l# z+}5F6Dn7gQrrgotSEL;Frd-h>V}mhr_Mlz~ADk;ODu&zYmTNg0VQYo zQk7->P`G1XWf}jjlM=;N+l9F;cvM#qO`&wnJb(MXFyG#Kl7>sTUk@y)URuIu^iU#A-S`*Xlwh`% zlIq2%w3PqYO$jQoe+kB=%eYTZ#jka$9uKi?Q9!B$Y6$fL+KD1J>mtM(_v1SwJ_xwf zqNNK_xLL0(e$KaGeTUft0r<{rRiJ4lVx@d)xj~wLR^-zLX4LdrEmuRJG2zp1Bic+=ov@6x;2rpVH zW>>1u5Wh&z+fUEC2i`+6`S_kn_0rk228cC`9p1QbV{=cX5`F)>rf`~Q4L8TVj_4Y4 zYpU%boV~C;@g7%Gy^R|Xf-u1)@5UsXEqNcMBkxAURiLywo)fY>gx}`)n&KNh`Iy}2 zTO6xb(rmd>3&P>KaY_S^ir^vofpa8@ib^6ORUIDqj#AIJ3=*e180T=jZ|B~$bwM+o zP0jSMca-R0l7&hKxZ2`E588Q|2bI>xu*arIJE)wO{@^FxQL40UtFzrgXZtZAx?QV1 z+e7|=ZFimRmwc@-uB~YmP3Wa`9HPv|P8tfDIT+F*AC{)t# z$E}1nKah6BV`dz92>nt5Tq_0GZ zi(_8%HwMhsQDC6B@SzCzEG{B(5ufp%wyv@9JtaaexrkqXPZ5Xt#rs{(+axNXN)r%x z2c*^fAg#qk!rQdF1;_ zWlN?xFjVw-={O64b`6uAP&E{+1cnQkd}K2TF*>#8a4WoYNeZ7;47JW zws7QC0~x@|GpTos!--?`j@pUi)LOW$RP>G_k8{Z5#n>{Md!WcTwHCkezEZK$R6A;} zb{Llh>-d`M0<1L-RlH*&kquqjM$)3L{7`>w?z-eR8^_q44%R<$fJABauc|Hhf4YOcLQ4k3mMRoLv2_tuE!1|v?~asiu@CXP-qDXT$0kYmLM|-VTCP$hZW!E z3YoN!UmC1baVigHtMQl%rrNy2NX0B~TF9FZQ93y-TZmOxo;OG-Uq*AGG7L%_P@Rrg zDpunK{LT;so?x^V<3CiXR3#HWNKa60twI`LZiq%aOwuaWfxZ01P-SSjWQ0p3B|UsK?>G!nx(y0ikehY#LOy1gGO*V+uur*(hH@{+ z0Og8kd!!QJQbI4)_WAtj zNTq5-o>tNGap+jox7<*57m~!`^AulVrb;7pXe>MMZZkNzkYf@KF>u~(l+xQ0AF8=Y z2jjwpzo@Ra$nZK1SVNm3txSQ?akIKBh2bz~G-gf9L|9Bl84AOMn!*+#jQpt02s8Ys z=Zmnh84e;$b1|QTF#2$aFmJ4Lb~ZK=$@Q2j&fglBxKQGN<>f!afyE4{;+G^3Y&^Ml54t zfs|qfrDA28T3bD86CO$+ z5JBu4o&Ce}uo@cckn^B7Efti;VQB{y<8xff9Hu$18^$VysV9I##<~+H9du*88#oP} zo^Gt&pme%!C=Ks)N@eUL8^<9o?)8b%(lViLfd!vOI9YH_VpO-_EHFwIT$RFf3*IEc zVlsj#OxN#vgpmbTM3|x9bP+Z-!&`)D`dx)EUB6<@y{H8z>lU1i?om6FpHx@vuSq*u zLSf$$(k`&zWC`(h7Mx7O2w}k)#AOi+zI93~8Cme?`I-fvqcGiq2LQ+3f=^JKUcz@o zX+Fz1iZG*uJw({pj6)(!D`97Z*_W`01rvjRx8NZ_f(eKcGTj6!%;WEm!AJx*8r0Tw zZWav`idUrh;f{;St1re~LN!-^GkH*9<0r zPXA==UlEC!(^AaXZCNb1bU{4T6 z2igWvI{k$7LxiE8{hcMLwz|V$2}P#H)HpD**U>`4qKZ~{6i=`R-ZO#Zje2EY`QFwU zqju^nGBmVI47Su6q_`ZrIAXM!&M3wGXcxB^UwILVSb)r^1zDwHEyvC^LnvmS-uO7_ zirZU9rHT^mB!xHBdzRNJkSa=X3Vcgfpyh8B1sWU*Btr__Aub|L70Db^N2Rl*#Aw#* zEFij$+SkAbqpgIvV=@Fi#M$5BjIj2?%(?-=5T!^6#EuA~jQT+$ba}voU~0m&%L7Dd zNf|G1Pv(s#AbMjm z?>hmmr5VZmqX|lw{8;7I35s7p3P@gYC?7U4v_w5>V4&!*t6*ym!t+Zt&)`WDlnNn- zu`8Xs3b9CW2~0(xI!_z#+F9P`P|hA}Y%&j>sCb%36ZXs)fgQ+)OjMj*4+5<|&;%Jw z>|e~~QzmMj2YV*so72C}y40o9*SMV!C&$GN=IB&CX6 zEt!v@_>U1!*9aN$8|U)fla%hX7vnVh%#VGp_$gD7DAX>|v(I(Uj46dK57W76 z3N}vqOi@Z2UJ!${pd;6^*Fl3J4A?67X~z^NcqcB+QuI~Bg9pqBjt=^RJNG)Vci5bj8QnE+Qg$1SlG9FnMAa6awJMK{X5)kr@kt@V1cVot#^rYrP_lt8@m5QO{sP}K%l!3E( zCsnEMY3JNTQ(~i@tx%Q9RaNLg>)G9{*YTUUz5q_iG^1w0Ye{d1G&eX@!L(IU&Y0Oe zXr9uyiYF4h7`rDU)e)C(z~WvwNcikWm>QT{P3;Hnqp|*ebS7UjPl@u22houwB=rfz zLsj8VoVj?=IR?Hn`_p^P)FBdXe&zTrV`VcEYeBLxv5lJ$lrj!J!G#hwsJ@=r?fC;CH1CF`Z)G z?%c0KOqbSD?E&$l;%g6&|1f^Y$gJ#TN?Vh|@PvL@0V|ZwCO#@v8E!dnjdC}u)Dp$d z5IO% zE`}DR=}=5K^0oZy%>ONu#WC=DT+6>NJrOCcB=#k<|7~PS3>AG0skLruCl(5{PiPQ$ z9qhugX53La^{o(H`K4_*o<(@};yHyUA5ZBjxJYC~hq6B0_3g6X`HY+T(l!gvIy`6b z1WW@Oo|I`>cit}B#$O383mk5OI}*&U%~SjMC{+`cRs?r0UIFmqH$(BTqEwRp1#S#m$ohZ)n`$W_bt4^ zOWQOArsD}%hLRL{qKmv!d>1^4%d&=cDC;7(X?qv}c-|=T^uhapB4PGv;*P(xwbq|5 zfL)Gfeb=e%eYsleUmzPilkxPxlZ*Rdl5$+JCid|? z+bn#(udwo}*=JYuzGoYSk!A#~l1Avu|B16DW zj@`4>#8I@Q<6sc5NjCBUe3%190PCDYLBFsd!&BfK0T+J0XREYWlFVoB*}4EWI15Gq z`v5Kl9Cz-X?Fe9Q1u(V*gfD^tz(l|SfP(?Y0S*UDq4-PpY~KQQ06YcQ1MoM% zvw-fFrN|gRY65y+1|h(jfCB)-0mo5z?mgRTz*&F?0M7zmqxUNyunYyb4m`jEH&8;r z$G4Cku;1z26D9I$LF zj9~!7Tiv(Vmf}aHw)bt%DdKG;OatL|_iab;-lhG0TU)%(>VP36U?$)!z*8OX+tvZD z?u>MR)4JTZ{RTLy>wR14m68m13uumLBL-P34H*3z|Fp7QnWEizb5rV4o=<09bY! z2moFHJOa3PI`9F9&jkJ&sBjkW0i`*>2Q()GAF%8^-~(O&TnA{$P5}Y@@LmW4fIR?9 zuLUC<1OV540Rn*G%kJAo0X|%Q-eFdpCgqpm_@j048q* z0l-69AOQG$JMaPP>;yjGx^I9F=d)b+n)j-@Zq!jHp>?L zX!`;L09U^R0l?=r5ZDMPJ+OrXmX#max&T&kcwid^81DGMmIC;O(*xTUz%C^o*iHfV zaeiQX2sps}z~-I_36umr;A9uz1I{W1e87~_zz1Af=7Ghw1wU3Z5CF_nKmhRDvLNs^ zTC{Q?0C>a|1OQLDfdJq&cMt&l%>xVoN?yPRboT~6V5RcF-vmZ|fDibFFYp1oQ~*9; zpNhZ-9N=dG0sI*34+4O*0zd$8T_6Z-M!gLJ0YIq|2mn^73<7{#08;?lRslZXxazCA+Dzy9@mdh(w0ob#M>-rkved$0a1JXe2)o~J*HQ_nYmV22%cUT6Sj za|ZZ|L@zb~$6sOq#?ChY$6jgx241fJsjtwV!B^_fBZhY@;5GVlMWxd`e1raMUZDTZ z>G%IP8$iPeJB+`@09<&R0luol?=k=j?=}EC?=b+=?==8h@6(@a@7JHv4gI(9x{^yk#&`g8t=`WFR9{#l_0cW*Hmbr>EWj0Rk| z)nF9QLkz&#hZ%s0hZ}$^k2C>}{k#6$n$w?i z|Dit*9;N@Ty?(U*%%t?^fO)PzW>6ee1hK~&fNge|dz=9nnm52VPrvUQfb)+x0FRkx z?FlBpg(vFIP+EWPa=`qP^#7KUKUsh7GtHH!=+DW8q5%X43kKk7&H!9|kpVdSVgr2J zik1z)g_jzD>AV5Bv#LMKuh*Z8Z_uB~H|o!=HT_$BtNuJH>(BPv^=G~KQ3D8)A2$Fu z*kS9F2H?a+2DsRkG!4Mu*A2ktHw?hFUH!TKP5s&Zmi}D*w*HJ=qW>jU&Nxfo(Vy$z z)t|+lpdvWF%m7^Yo&mVKZvamH$N=Bb;R*w=f29F9_frF~*43YZU+B-wFZJjAZ}eyR zxBBmC|DFEqG0n49YLyZl_t~LN095B&0z;{)IaUT5909^c&0eHj;myh-5 z2|HZmu}QJV+%JToc|1&w>18AZQuPhvW7|2{f!;-Alqs$6}b32~1D zuFstr#rAE@qpXBW%yX3umO0=)<3F%f{_IPd1Lj#uSukhQXNseiV3;<69~yAM1Q>s& z2f39s0fv^&j9MJLzzVsYQ;{Fp!xwpuD{Qg%;xnTjmzK|rf*o7KDDy8hE{|S)W>jMN zHD^Y3t`>@CMu{sNp4TcV7hY%O+-H>~pAWdSs-!>m-0RPbl3aRtb^Ifnd^mln(H zpML#D6TH%RZ}&XY@9;cR@3aMMvdz`vx>6pPX~hKC+OVgre9WFQ`w0W`ux0{3(cx1j z%!ALK8D&qu{=Db8{Y5Kc{!0etnm;X+`>DO&IWy`W8i!?DGVkZ9+bmsZf+}CEUL=7a z?0@Sfl&(`zeFijAi8HltbSKT%shPAnbA<9a@!tD6#Slk9PjAIwJY@d znfJn##^uU^3h?+RCd#Fs*{Ywp|A$>G>nhdH9TM*U!c2K|=rD2dS0;G+b9eCgOAP&9 z$r)qpzGp{CPX0^r?5HLfd*Inoo3k8ndd5nwc3&Ulb0+=9MxX0U_9bMNIlsYC;*ebv z%Kw`RNf>>|*-^nb6A!gg{SF^y;@p3P&$;(V6Vh+C`0o-3mf2*59j4|?gfstPg?~_) zM@h`=qx}vGt0@)Z{$os>k;i(TmB(4(AN>Mj-Wg#2@y0#KeC+suyLJRnd2{OhQ zlU!xyFYf=AprBzcXGL6OlWXkqghMvYx5p;1{BjlGHp`rRrRTZwDiz>(!I_ab&d6VV zyJdolua%I~ual35tp3&gA2A-+*)qy)KF#I+hIR9=dWa>Q3zRL_ZFSa$DzC=Yh_8k@B_MR0o_FY@~ zH;I^Ji8)r;VD8eQ>mUeRrsRKjT^Q#HGpAp-t%!T9^N1aeU2ei$XLNM>-Ot{#$~@!W zR{^%zVrt)n*kL$uP9XCG3t_J)$O@KzXoc*v!Q~&R05=&t=bS+H3M=8^j~zD7{KU#x zXN_I9xz<%NRt{D2Tz^`gNp_iI%e_RZg@^$>n~Qq=wGdb*@2ZXentWwuz%WqR*7$9JSLdEMuktmW|`>|73LnhH!7YJ zh+V71V@k#t_n2njItjSQCbzFwDRw#J+~2I^#yT~%<*Nh@JQJK&+qk{ewrivQ21$hoxkQpS9?spy@5&Dac@5!PC_NMGGt2Sw%#=}9xXdQY z?6Jxr_ZanuF}qA~`nLKr%`(fZaffYoIpFw&-<6Nt(jl6#LZ+ExlU26a;4!-l-%d$y zbxvT45f+$al^J$e;t{JHvcbsh^=F#FTe}5}v0M}+1x@DIWrc}5SSi=o;}%1wKXeqa zLQXQvS(drL8gp!Nhdu6b$iN*{=r+y_Q#@kGAN(uM-pPyw^LI8=7TD(2U6qKvdzk5j zEt#@H#{9%piJ_RiWM|sS*to9&Z>M66GJHRYm}j0V_qXypIP7r?;MM~y_zv#>+P^q# z8X_|iN6rcCKFEXqvYVxUb%?nCP%As%7R~yc^UPX7mIZFG!Zz!iez?QMiAPvDD~z6J zuahRkS?0OO>Ur+}s-UG|lU;6ez#ii&5O}1OGs3EsOtZlhyIf-M_Ez{P&olUF&ojvq zv#fKET^_S)!HIc!i-Lk6YULYDvCBN;kGFDWm{o}tmf2#H$Luil1S{nfqj!{;DXz1? zI&0ixnrL=ocK>G;|wEra~2rq1~aTP z&mOBhVT02d*OSSjU??asc6WQmB-_k!zzWBnZpNH^h7~f&0rQO9Lq8^2XO1VVF!W6Q z7-xs`9J0#Tl>5IUNDDeFaB|TK8E2Cj_PD~(KPe&OJZ6St&$2>BS>-HStg_DrgZH!$ z#u$0FeoV4-Pxn73sB2hfhfVg`WAI)|oYj%t=jg~|=DG4*6Xh1$Jm7$l=c!0c0w%e} z95-2Fi*=r`6Dvyie2MNY0V6zSoS7F$$UO55zR(I8XNy_(xyA5(yiytCWKKmHXO8o% zFvli$+2_=Y^eg_ecefzHHD+05f%~lSgl$f~#NIK%=(Iz|6t|h>!Lmdgu*v!JZ5@|5 zWP#!Psx)IfU@z!)dnAUEU?1R%T16~2Ji3dSEwK- znPQH4c3!E19J0l!75Bd{NUfMz+@3PQHKy5MfdkeUdzD0-WshkNnPd0?-WN=8lW88Y zz|gDpXNqkuv&Yh_iv|#EXbAs{>%$l;ud(-Rv&2Bbp<#p_ra9yaqYv~vQ`}~rLsmKd zS{3CCyUZ~-V}Xouw~X-*gH2@B)^M2_7E6M>V1s3zu)*=yD;1M(uu^6i{#UnwF_xKRojJBxVvltW*<$1Z zD`$eigv5+-wq)T6_rD-0XxL|s1GYK!M)#ThH!1PInb4c z8G4AVdy5q_&J0i9YN4lJzs*7);{F!|T@9NYu))wny$2X)xU3_i%yW@dw%Fp3eNMjJ z3TJH@V=OSu1`FI{gpzq++mOV9P*Ii zq*61+@rtv;4D(!OnT?A3-w^C+XmjknD#4}qS-~SEVw~&mR{?Ib#64D--LM6xpR<4Z zIm7?Yo_|0EnPiq5EVIrUqaRc`j(y0r7z!dE((&J28z#9@m5^nYxX=1&`-gSpI{V!G zh%K8_L8iF$Q7hz-RnBdiAT#W8jlusgAx5}W6vPGl%y9E#_LzrkGWv0)<fsR-lDa-L-t*8~kgon7uRm~!|SVer!`!U<*= zXNh@MxyAFEOY#`Cd???k1Lvyz+WI6SZ8G3E0#$fGRN@el$djD za^mw!%rrxfw}*_g%?t-Dac0{JInNeb?DK%ZCm8n&7FZO_3erq7#||r;_@acT?d)-d zp(k1qqYVA8L&qqyOt8R3)>vYj+Z?dZNLmFN7RY%PGlH6+#3rlku)z~{8TpbKKS>1` z;|kN9__BVSVV(1AG0QGjIN%;5PgWTw8T^V$G4>Vrza(gDXt2-j=>t1Do<6|HQ)~@W z++m*kEc1vp2EM9NoMeyl9J0mOg2YTRexV98&k9Qyy8m^-mWB>n9J0gkQw@BPL&PxC zj55bLR=B`A3+!-47}jx}u&3oLV;H8zTZwqTDvE`3eM|McQvf}2cpzyiZx zmzXIwxyTN;IAojAjKj+W0(0DCg)P>3%nrlf zl#mOIKEtb;32rdWI&+MF%Nb#Tb+*`HpTlRk|BK%?z%%U$6Wm~yTP$#&H7>VwXxlIKdmDC0~q!#vknWsME)u+1(995V7e zXXtWghYQRx#}ZdrWsNN!u+Njr-T&~Cj^9%vE-=d$%Ut=s4lJ|FT?U`;&9|>YTwt07 z7P!s|ciH42I~=gj$sf2~FK||v;L;C@1`t#<6u8G4gFm!FmKc1YGr|aunPmJ&R>);m zPTSe$c*mA7$xzPiVS5$jDFRd5P~8OtF{|3@z)xDAP=EiD~Y! zz(ZCzV4dloNz6QltT1}MTfr22%%1Q5p9l&X7P=C>)WH8I0b@V+0Owie?k^lZZXP-d z%>7aYUgmWFN(C7FwFz;b1&;M>C8KOI#tvtHCr@5QIXK__F9_lqHke_LWsV(5$Z2+& zXYl1-D2%YdIQN)h{3?~?0;|lk#dY@CW%w1&3S*r3y$Kfu2|En?vq0{A&G};MkufWP}ASv&MBcx%X%HzbEKw7&7n|Gk%R15fe-@%XOBy z%?8K*>Y8zip@K>=&Q)f(!943MGc?eTWp=sAA#11qSzLInlAX089<##}_8GaxieBds zF~%g*Tx5YOtgy-^4^Q;t5rfXw+_m~~o=G;CW0NH&i`PjkC@?Hxg9#omdpeQRuUAcE zs3SL6VUtZBvd4wLsl@B8Y-9n(JK&H*MtvUf$I;?GPcX&kIVYn6iv>aLv?JS`KG&aH z;|?QluxB?o86~;J9NVmLCwMYyaqb^ZMtv?ac!B2`VdsYWF>s@kQHGPub8PHnRArov z3*7%bLHG258%xX?hDruzlx3#4!z@!bIT@81xTyiS%K^h7&%e>_VTv{8xzDc8$8RRF zuj6cSp8Yo}(TX7aCZ%P9drY&>0>igB8Pz$>4$B;Je*9zGW0g@3&vSzh6gM$cv}@?lpQA6 z=RAXD-;@~R!EI0c`5(cNh789i48SO>Y_ZKA2OPVd(!JdtGRZV^EU?0DHrZl_eGVDA zy|eKS6=jMU=DB|RqC|qeh8E}UAQAT%d#9~ohLaH;*kzT`e{}e`c1M*t{e05O)=l)z z`Z0PJ6J(Yd*4SeFZYsg>-EHB!Ot^RthfZ)jPkYA{Yb>zICOhn~&+NSn@NOk! zf`OPr$SLNSVu{PFvcd*;*k+eK76bQIBEkB7l;}NP6!%pk#+l_R%dE1-2Ae!$kLmk4 z3l-n@nN*4J{Z+~er&;9!<33+whMT9K^N{6=`yY)PSVM+wu5!Q)hTdz&jB=j|HXmqW zJZ72E87t#FyR0zyK8Khw1|Fm`oMM4#)>vcveeVDGgC*3k!pQp#%p{loRVlg63WEtN z=K_1&WN1Sr7-!<&tdQ$0@qqQy_J`OyRybsr(GQsTLr?F&pd`q%$13M$9TwKv=lH|y z^#|=G6YMa{nTM+YH`w3_yUaX71wQ27GselJ3b4cid#o|}NcX=jSQ8AmJ7;E9Gk%f| z9D9ZioMh#+olP#V$2>zHHUY*Ne5ML;k|oAj3&m}TMFp64-J3}z)_ios2X`Z*@ZS*F-vfqTy>>L?h0u0%X! zpTXzp_%S7Bj5TIBzNF+#vcd54CE^l;ANK}jjGIid#~hO{l!qDCnaf!a%SFLZu*vWz zbYOzX7h4%KEHL*H30Y>FTO6>(NX^8VWNcYN&a=Wio7`fLZHE5aSz(;T*!fB#NHfn8 z%WSa0Lv|T@sTF=w2^rxMliXm2dn|FlI)g8>6%4b>C^>YG~OcVt( zua$^d78rP)2{FPplMd;Cg;Pzi!jK7UGxAxLW0FVAabnekIm0Fw*yB1wpL5L_5V4JEjGBzHsfznVlFWJMG2T-gK4&zV~-_Hzgfu| zg84TafXnQ$#32J~X8ylEXNoJ#v&=I0*asOxDCE-^c z3MRS140o945z7p}+W?$rlLdCz=8zNbv9gP7-TPI9vmcOveMXup%s7WkG5A3fY`Xtb zg0hBb);Pl^XW8LChg|%S6@JY`ncxP~++~47);LqOLhgUq1h~Gb-`Cyuk4enH$1RNM zPuRku;7HJ7wq_4`$nZCm?o$$Rf6Gjn`izM(%NnOYD-q{8V1c1sx8`$J%EQm=$I`Zb zY_P_OFPPAUUQ8?|1UW&LfiHTHt88+IJw_V_R?6I$Oo(-6Iq_xB88F5U3mme_@HbV2 zN%p>C#T?%;KIhnAZpZ!a3N|zhxX;M9>=l!o{Hn9S1(sM~og3`1$Kbb>{6eRli%c_e zk>^j_S!bFZZgI$cMq6IRP4_<~h&9cS6JJvzZn4c>_PEa>~WPtZZrB_iI`$?PsNyJm1}G{}q`*lQPE7r{`&GQ*ckzyv$YGW-LHnPY?N>~i9V4&V3O2F95E zk%UZjBxIL0u3urIr(bixz>h8P`xeGzQIHg5m|>nZRylU1k}}Rd2Mq5^a3CR9m}KZD zR>lHbod2oknP>P1UfE3WgiS90%*vVXy8odc+PnXA26U(~>w_H@*k*+jKR1Bq;>>cM zWv;Tp3ftW0fX9sd$bJ8X338ShF0;f6>umnQ{qG14H4Hgqv?Jl6L&iMwEVIlZn~eU_ z3YcQ(3Ij9F1~WWhp3z^aB;#x_#Wu6-ar;+ACHk?$p&`bxU)w`&v%o!8c+k_4C+u)Q`};nM=W#58Yh3NKT{kq%g}+dQ53`lEv9(PJOjTo0H@gC9((L^$UehA zQQ{+8!vwR;u*^Jbtgy`{2Rvrvr(R4~$;;xDAR|bz#1+MFJGginWra5<3 zLe8_o2AgcM!-;E5m}y3Tu5wH)KJa=Y{sLYyJBFHwJvT0onPFYeyaSA9L+!$mu7Vz;AV6ibu?IB5eg+ ze3A)p^(mfbozdSJhbgWuc%Bna^*rNjaEVS z9UgGV#D7Y7mH+Tyijx@$ImI&9*x)+b9B{xPL%(-Mo?ettu=aEbxz0RWtg_7pC!b-) zoZ^7NXPWTUUcHR-fEgY>OJYXvVSP4?Mi=p`!jSN#}gni+1eR1`D>b?&pn*s>Ba$?(8d zFu?+|JYbo}tTA-HJ?8?4EHQk>gc#!vlZ?L9L|I{#3omp3+k#cWfX9rUb-MEsa-Lc4 zyj((d*kMCO?-^rxwljFWUmtir!iiNYV1|J=>BlKHm}Zwp4F26j->fnWuX&ycmRM$;d+e|{{uYNu5My-Y zn*tMDWtue>xX&8TxR&3bN&54WeLwY zH&9@f`z&+71}EQcWt`@K3yhq5Zs3F|PP{`RPP5Ee*0{tr$KGjzoMQ9_K4*eyrf*O@ zH&7DfG@P)?sdb6D#4fiO44xaccH(?gu z@Ba4$n;M4PWz^sH-(!lw4KwBxtDIqj8FsnK;7$Eo^NjF_NsfKM)^L_3rdj1GTWqjT zfB&Nuht3TIK4`^^Gs`r~Tw#M{w%O!>6CaZBX10h)wprjID@;_akSpx*gpr#&Gaq)1 zxxfsUi-Nphon>yb!Lg6%$SHoc57$mvnFzD_kZULR-_@*uo5ma8n&ljF@PDiSmA(mZtXbb41d)ga+)>$l5BE; z9d2{THq*vCVu8U6Jlq%Aj$y~-1(Z0JYL_)?n;36Xthlg?2m|=r?c3EZNJNA@i z_PEW^Kl+?;4w>QPo`tfpS2WYp2Q+jz{#}QL(~REHdw?nCnP;741}{}&PP5G{2V7z3 zPR;=19KTFLuCu~z)|qI_$9hpP6f_u~^nziGEhc%y9FJMz39AfTu2P)(zDhC8;GKQb zVw`h7keG=p^yBf5C1&zUiMe(lFN?c^=v^EdrkMV@L&V)f33$LZgTGW#MmXdg!*{hc zjB$lYZZpR{me~EZaX9~5hmSK?*-D8Q7>>ICGr!j{>Xmx6j+|tPN!FQSi&ge{$nf3V zl0WLlU1r$-lYU%3mXL{o3A1~RExEgipQsE|OmUt0yBC#OP}Q(E{f^9NHURH%hR}EQ2??Zd7KB4bHR63WN7HK4Y95GeJ&|T~{3C z1alfnTx6AXwz)iz#+)q92!Udflkb4R*N0J`WiDXBA_Nk^D57=g(Jr+Z^ zx^6TSc08{KR&&F+ZBlI;4{+TW<2;jGVuq{Cv%(r1Y_iAB1Kj`d z+uAD)DF*+=sb_?HOfo#71CMX#Iqu$G!Uy`CG43Ns6O7zfA{JQT z4x1dX$Fcjl|3g9MemXwXfQ+%iG`lP@aeoO4gkbDnbYzq{&a%Qaws^$;>E{oW@Zt853FevR9&_xm#FZI`j%Btv z@gRvAWB3s&!6e&7K}N9fV0*|l)=nQ_ll$y&=3foKd4`krk}<9_$xY@smN0QfSZ9eH zZm`e5zv=%-x8foCu{bBl2{J6P%O&Yg8HOHi!dzs7HFkN#;J-V3 zk1#=&lAh-QON>0y#F+Shp8t3Ee^n5i^DbtLkvSc>%n}={^MoDdALaS~P;$l?dbBNI zjsjoD6(3_SpXe}gz#QXgd&qe~oIc$5}BGEHle37R!PIL5)XjGW`@CdC17TH{^oD!US_%WQFUj zbI2~&o@#=RHxb6!V}@f-vz3fxJkL3HSje2-e?db-^a)D-bfx1w^W0{YeYQCM3=?CF z;U{{I3FesPI?JrH!F{&bU9?3!VL0s!JX=35KimD!3R)Vkdu%pMi+d}6zj}#mjxF01rS>R<18`7 z3bSmm%+QNXoLTm{&G6Hl5hghP61RyN7M|w*ZwYD|nryPm9^=b8{-@K*B)6DjlO=Xp zXZU<8W{N}R7|qyHrWtvu=b2!g6?WNY=;`i%;AJ{I-6>~^3(Rw!RUWg&rMwlfz~D2y zuoz>9X@*{IMVw@XvutvOJ#I7fOci*A3UZB^qTonS;^HgKkh|<~X2puwd6h(qo_n=K zJZ6q3EHUsJ6J?Yw#@JfvBk-E*g~E#@?6*Wo$h~9u=Y+R;X3o& zV3|!e*kYS)_SoT&)ptq!JlF8u5;M;{H(6ziEgrGY=zA=5$zf%J`Jx~zsI$yNHW;qh zL&iB^mZ9gHAfs$E!4sxA_g;sO71p@)J{98p`%RP!48On`V~k5ovRD@61QnK8WtBBH znBFiEo-p)6r~CsZz)2>!_#q2muWA8|epo+d+2tP7Ia~8l<8yh_7IKBH-0Am!L07{X z2dp#lA}W|{w(M69xL+RiSA48GXJK5m6Pso7HYKjnE&YOhm3eW| z%s!*TOYAw*ocOF#vceh%Y;(vSgP+rpQ;aVAZ#pJ8!!#$ppg$uG{W;6v>B<>nnQiS` z925mDLF9aim}KlrwuC8GSYVy&Z1IqNPJP*)zSQ0`!Bu9t%>s{DosL(4_h%qkgst{LL z;Kr`|UlG(b)H(G{*XHyA4!Ozbio?PbyUa84Er*KJtTD|tS2$pekyn`rlRRdQ6W^AP zb8K>o9Ju2FPP#I^DMK<@k>mQQTCW* zsNnuD3F3kZGu&f|(eFsa8hdPV$P-3iYv4VJnE9?!GJL5@oVK&g8hadTOY}OohjGR) zmxo&{z0Up5{6HcN%WQGuhxU$RKeBhOXOs!fGRrK>Y_q{WyFBPPE2~O;g$gpmG)pY7 z#Tt8TGX7%|T-7lp7;5M;`g*0j(#n`%o~x{~#s+uT<^g*gJJ6qThTmWzjIqij`^<6X zC-$D3Y;pFd7Frb41d$8)Gl@B5o>N_k8Tf?`Y_WgZekf7N9x}m2W?5pHeKr{SrONPx z!8e+~uS|>urdeaLAZQ6H?6S_>uN^K%dOE(zmN3RmCb`87x0z>$Rd(56k8SqZ+Xi z8Rl4Gg*$Ar#~zbcyZ@oLD#g`i#<9McvBMH8e=sr5{L#d?^(Pa1n=^B4Vq9jLGk-QQ z&auKFo1FivEn}9!vI#TB&{=s-EnZ{K1Sf3J5B&OxN2i_x#u$3LJ!71^%y8j){kX^) zCx#}->`0<_sL(mrkK(KculJLVDsiLh{h*_Ew%Fr<#p$u@N6~kBgE7Hv=Gb9{Cv0;1 z#@CN}oM&j=o-)c!rg+FagEx_gF*cZFn~NN@T%E$*<-&|PfV2b~=z zm|~VoEVFT!>;3&-f;|mw9&^CxT_yaGUywwVo}s(x$VnDB&l)Riv%>)kch|4#Yo<7M z4_n44tIV*)RrcAqN6`#F>;*AphTLVAeHJ+TPZBZ9HrLo=l|vpe`Vpu8o)R+5EN59} znl)D0<}L^9GxAYqqp) zInCh5RE{yOG0kFKP!R00!ecf$ejh94GD9DC1{i0T8OHzF3Ylhud3IUmfSU|`!i1RO z!hPl8I%_<9kO_Xm{f|FbDK*p|X=XL|nrUu7)}iG3ycKbuQP1_+^7Yu`t&B4a|F?-S z!6l}-!vcq_G5!P#V}?DhGW5x!nF`{cQ~_pq%seNb=+H3978luPli^P}WQ_5cX$I4_ zf+jvj`OT=k#(-H#dUVsW$4qs|3AfqnP7^m%(J^- z!W^){;L}W)Q3n6VRx-we|1@D9vzQZ1WhCYt>s(@o1@^hg@MpX*nBXz93_aZ$V2U+n z+2lHVY;njwqjiVz8TvEDELWc4{+9)78fx5ToAb}qk$px#YlVwe%JQ@9DI2VDk4+x2 z$IySN(C3^9#yQ6nmzd`otK4Rbz5jCm`-0H3t?=_o${4qq;W0~`&Z-QPY;l2I78u<2 z>jK8uWts!#7h>;)#mAu}9*p$Ra`GE+H+i~BE9fz!`l ztY5>#8DoQK#$O^aYpk)(=IQ6`u*rVI{XZ0hzhs4s@t8@TFvH5S5^|SycGzO+d@E<* zrLNPLy$=}YI8&TpmI;=bWQ{2{nP%t9?*EZssA2qNO86Crhbd;6=NhYQvBi8|VjeTH zW1@^R@N)e)#w=qjGtL?lY%<9X4>>Ff#$F-uSDgW-m|>o)ta9m<_L@Tu7+i76FLbyV zWta)hFw0pMIL8X-S?AQNRQe)^^wlcN;A>9rzhI`|!P5_3YlRHF&fYM_aMOT{vB@+e zZcTwvRv2TQ^XzbeeJ(QiHE+^4=+D9h`g4;V6KY)G{`UpJk^y~?WQ|K~pFYR|dyIVD z7QNBTnPrY;mblG2kJ(}HO(wuN!{6|tVS+o%a`DZ!hO2Kj!jWGBj2=DOfva46XgLboGZ)2d3Lx^6!Zm)41UY0W{hPfSz(4% z<~jFvXM%-y+A8j_&mqI#wl(Wk${};iy-Q-|S!aPQme^%+OAu^X0VCXDoV!eMe7JN%W#+hPj!MU1k7wSzx~{F~=@fA`%O+f1-j6{!|4SW0!kBQ^B9QEkBos zkwbZY>i*9P3L4U^aGf0!sxzeHE~D%)!O34b{hmv(#|4Id=GO^~v(5~6ndgvIMt^1E zOtQ~BgT=1XDTuMbBsnW1itdhnX=> zU9I#?U+w-E1SJg>Zn4f2b~w>D0OO4Q(m+gbjcL|d-~nq4{=vi<=YUCue&rR-I75F_ zA;wr{@{gzA{{;&gnp|RsWe&N+=&vPUih)1bQ^r~40$a?n%XJ2OwuUhtGtKd16J?Gy z?y}8JQP2|%I6QseuR8w5Rt%Jut7pxWYpijdO*YtLlS8%`{;d_As1SS1GH{*#TxEm( z>rIqH4p@v0y&!()Q2pJWa@}7UnBxXZ44pe1)fr}s1NJ#&@JPQK3`a38G09bCxXlu0 zZ!{b=Sz(W3Hyw^bS2=v4;V6EU`#*Ja9W=ylp#$Tra&KHh9#0HML#A#w97TVxl(!#_ z(wt(Bvn;X8ItOeqbcdlI*|ea4l<;a3xZ`k?V3ld^vT$`#B0)t%;7(@B4aWN>5*_+C z9^G>m7@8XT5lxj~le7P%63jFB2ZxstR`012tTDs!dzm0}tp9(y&Ic~)`u^hxUl8z; zJG><#BH~48Xk?d>Qej<-l*)>gQ!KQzNZGPQMM_C^B`GV*vyT}yR=38KZEim*XRK`9 zmQ!l1*e|A3Y`bmFSP2|TdV0U-`}_SK|K!Kxp|AJ*^?85ZpZ|ZppYP}HKub<2+y>U? z5^uv-wAmc05L|mPIRkSqp{mHpV$ebYYe5fu16T*{2b;itumyC^#UAv4&0kZ}`Jr$S z+;Rmqc8mgn`Cv2X2K`_aSm_FdH#8$uBea37*HG1<_1i@3X83{mV8ueJ8Z5hkngTn( zW-tJ@fwi|#k{%KU(?G{65&|>s!X7LrBcovbJ!A~DuEDOC@bVDf|A&xWPE~=9dx-$L z!Di402EdH9)I^Y~zn`iF(<;c2=nqmOpa*OL>mH&2pyOc*&_@PA_i_5xdi)Aj;TOz! zl%@mgH*6p$ClIPhfGTSTonQzo0qu{4_)sbl!CJ5%^nodlhr&f9kOR8GDzFx;1Dn8O zU;ze`Ct$%B3vo{j&8~lJJpdYLNgJ2!FA+3f45emRA&<$!QNeFa;QBRXo&;?e2 zzD+~~o53cqu$B^nWuWC083LW){%1)LY~MoFgHg|sK`<9=153fsDaL=)^W-o@Re&xq z4=e{4gC4LNYy_LYHt+}-0?W3N&}rg%NeFBLJ>ZgU*n^dzAIy1yf`RQS6t0YD> zz>=3p=M3Y2@yp~8VhPv?R)KAx2kZiyL38Yh)Dkf*#Q6Bi;stj-Sz4z?@w~7!wn&l{Yd{y+{&T7x%zKlz1{>cc zgW$e>Bm`>jk-_MgDEs?l5G)2gV2+JS*V=X4Cyp@E&jK5HY;C|2xwt|hI|1cQ@vpZ-iFc&N);R3K6 zECfs9Vxp=(WBk`56n;)l!E&$z?CK<;u`y8<{~#ey3lI@>f%e##s3I^2>;j8H%Rgxf z&;fcuC)fxUfqt+Y>;QeBhX4Iw4%qom#=i@}_b(!nfFEoG^Zrc!6 z^-|?v8W;i#KsynafFA6-z$P#+NXftwP#Z@^!8CA59|Z%e!E$hWKmNd|Z}4NmAD9nr za3i=8T0t+^brQtTafdPn5aEqKG*@e!MxKn0qBl89rl4GV@`)# zKtC7)wdm7f$9QT8ECTn(oaQ$nW7z*|r}@Mq4q{L9iASm&v?Ngy&oA^|OjDh1QPMlcujgC4M%1h#{1V8$%M@ly`Eh+hqsfX%Z` z^Zp;9b~YsieP9dNbRh|*&@{PZ46Ff5z-G_`_JfUJC)^>%6?of^CYd$4si83Ud7;up+WOGc(rbD$GUyN`^38_Ezo z2sJ;T#2D6tey|B_62to`30MMJGH5%{33h>Q@K^0Jslq1G~U3&|XE2WKt3^4J-nkV8J7l0Ca;Dp!O&= z1EzsZU=&Ro05iZ4*#8(Ana=2VoQ!~VpnLiTdO1QBgyjilF3A6N`ppQR1K%I(;Lz8A3vo4^pb_9dF|JleXBjDl&eP}88jo(zJHSFzuKQ2rVT zWD)RF5&#Pthya#?6{0ti5ZDiPfGNMk{(Lg{E9}9-Ut_Bz@D>SRm+>2#58-r18R4thQDOCk_ zv=ad={43!(44*G>3>J0b7>xQGcA(|&*nuIiP4xfJ1Yq7#+I$u@`xW+J;n&!M?O^$A zhVwBxN7aQ?RX3dnboNjpa0?g!>w=Uhm$pAn!r;CW^bs6*Pcl(~Wv5SvgMwi?Ck|Vq z&V*fHUi2A$^ASH|&+wa%BslI&H~g;F2 z9p1u5Yi48Q{C8GfRXs=ka2 zI9W#Lp9wp`@+;1S-C$$EnQ$!_bu}3Vi>^DvPcYJXZy^G$LFy5GV8Y}`Y{eA@UolmPU;gB`f`cO(GDzmFa0 z2er#-!rzksnDYnxf_pw7V_?)DsbR3Z90Oa5q>E7Uq!waQkIpeuz;0tJ|6x-4arXJ=SR% zZ+xyr$zR%J%hV_*f`fm)(6R91xTvW36T8)-9_y^k#`C+w7BO>;x4uGze8dVdjP4GX zPQvhBwWG&6H`PD6J8Ts@^G}?G_*ZzoI@)8+O5Bsv9nPQz;&-XkUTaod!-d`9&N1rI zTwAIt?X|{_%f~@pA_gxtsh3Du)eD<(QFoXlrl|Ob-c*Y&uuY4TFFn)FQ-^x3>6YyC zx_JU7@Rm2DRo9jYDdROvw_n^H-bc#ui`2{@DQ7#o!^L8?UM&q;XGgm(QJcWbw7K2k zX6zz=QUy)K-v_@(?C(~Gusf$9ubXciLVxzn=qUB!<+h3A?G&W=vhMH_p|`4eeb)5x zo_S_6|Hdpz-G1D9Zju|j-SfM7Jjd?Tn`(2P^}NK!{O)kB5M$L|B1Sh|t`3QVJ(p8M z!hfkd_^QX6o@AlM8?NZ)n~mUO-ZHA795SasEj?~cKgY6w=8?cpBy*4C+9s>|Yt-Yo@9FiXS(i`e< z&^p6fi;?p>v$22lhS8;xn_vqUc86urihu15Y1_}$gsDl;Mc126z7^y0O%qa*EMudh zDsQ0wNt67~8*1}O>!buXq;+w3*r7h_wN4ygjA}>KZDQ1>lh)MOMz}_`;-qzQTnpmv zo791m*35f?$R#%quPmu?3sqe>3h#h-!s`PTJNXm)eE94U_EPD^@OJo8J!c6OsKu!J z2Rf2Atqv{-2Mqj4)Fy}ke2Y3AvQCU`L*1h8J7t}!I&*BX@u(T?$HKL`^s@M6O={dX)@kD{OfDrqrx~PedJRAMa2dP0 z`HC^Pubb4Vkabd=7c#&!b=sPl(2N}Q3uY$u^Eg{dJX*>xr6vEHW1E;5LQO;Mic(+2 z+9t-2!`bfcaH~2e)|Qfh*7~dNa3D&}*65L_-e2psHzXNq>HkoDQR@3~MpR1^wXA-q z8Bv38(6^%0FJg?q>^G?<^w)?e1`inkA0V?7!{i z8`YGaDC!o}8Y58&?MK}`Mm-}rM6G#O50z9!J!YsMB^!>H?88|7m%?f1FlDF}Ve90C ze8k1S>kc>SDM~!t>}+Tc2@O^coIVO{FU|{qdqd# zrbFF)shj#r)bUhmhfE@R`9!ToU1HWM>K;_5QNVcA7BN=eqqW2~=X1Rp_41*XqS7FG z`A{8Sbcg*UE9FDo-^mQ2moFiSzVdgyd8AfFjsM3$TgIcdpzc=JC($Xy_MZcZqBZ}E zwa~0o)W(17t)(|5s`o$A&U#a#Reh7eLh54{V$S`SX}qZXa%4sSQq0IEOC;$uYCk{Jb2 zJ$wb9RQkCI4)m7jo`|&z)ur`N4oND(joKL76D~GX4{B#z58Xx&^`Yj)_b{jHsvp&z z&_f03Y5=u1G2$vwn?RQv*Avc*B#dqu-xGEk)-KeHqyg29>a_NRtBg<&>K0p1*rKb6 zKGdq@o^W=oQ3yY}XJRC&gaB$+N>8}Wu-2Gy>r;EeYxRD1ZlVMI7&^P1clxa7Cb-ad zr}c!l80K!&jP#zc*EIK_d(kbLo>-y}y*hI++>ag{)Dr^eWz&1YZX@g3x2Qr#4>PY` zD-P6@tR6lXpsOxa_xS@A>_*+5jc+5=gKC)>2~G5&7F^I14j5IK=ttLP59o0L^!>SN zb-XP#K|7bhHAj;Do(x(CYRknDHPMBdcS#Sg9n|;ZZRaMs(Q_{C2|G;PgPwcYpzcF= z&L7nM68~}hQM;}ih#NqSUnCtzkE^Ay1QZQ~I#Bbj?_ufELtUtAZx~SBs0}v`s2=*lMQB)_Z&Lfa*Z4`ObjqLan^DhiS$rFKX#+ z1F8qLa7j-%#Y`8q;JX8%e$?!x18M-(x@xE|E_ zy9ZPsYX6|>M?F$D5E?*jzh@vJjlIsk)uI~13AJI(fa*fsQr;8JFv~0I_XbptsNWyx zNIul&dk5nBQGIKf8FkNz0o3~Ym>A7zK$}7telVyz(6^xH#u!7$g> z9MnDN_AP_D554qxD#J|Ak6!B?)C1^yUKrH1sieQ1S<LG{JTuek~C9gI;?9boT+mBfT$^Md@Hq*kjr| z&^;gZg!dTX2`==sKgqObB#)ZcI@lN<^!$(MjHbB{-P(?BWZsXO@z()0fV$*RPk6Br zs!gXS9A^DAd^=F%KkMP!fQ_uX&>PX&(;5wrp8feic!CGL_=}!!gW=7G+R-_%R{K$1 ze;?RV1W@b#F|Yt?Jhoc@8Cd`m9H_2;^@Kx)D;H|Ukpb0>8v0KU+cmuoJgBW-vI{U9 z%!lsziYhiD`%zoI9#8|Q_HG)?2-VJ`_w>lhptr6A)fya7U8se9J&_%k8@1thq$?zP zP-{-G)JF;6rcYU`vd?eD*&@Ib*!*(+~fF8A?SEem}Kd7Bg zxVtyprROfuf!e+b_hzsQJyh0f?q(9*sAa3kyjjN{^p0}Ojo3casPFfN%(ZN4<^j?+gB|EwDk+N*>_XlCaBsNA40fYORZ$g2um{!oNN>2( z2u}2&*KQcp{pf+mdcz^Jp9awPJ>JWgNt-2~LEfM2jcfxQs6`ul!^a}s9KEH6hA>;z zE#XfOn0rv0H_>jUxevX1^MHAxA3dtJcVIaQpjVgNV^2YTHQ-G!d}{9w2n-9JS4 zpfA}v816&wLT@nr`_U`BgL(ixG(^{O7@gaCBNJMp13m49LEVM!`&np2lW7Y zOY)$uT}03S)}Zb{cTF7BUFg-5g5kyHJmE$!o)U~KwI0;9>A`TT*>im88B>FDrlVJ` zAH4>Bw^{e7Dbogm6SX;bAEG3q8_$KJ@k(gZ6&(f|-MQ0KEa- z9G8ijlSw^ius1l+ThPsoO`;3kJu4VFHb``%S6w&|p5Q^Z=i=Y&_!4|kL{0Rg2Id6i zbV{#{0D9WRgSvJJZ8=1Dpw|x3UFiNnJ;9A0Lf>Mf=0PpLWI*+ycFc_=p5RAyP0dylvJyk+b=L-YjiGLrS1&o2Qoh0|)fO}5Ml%z`}k(_^j+hSN00 z!I~QNx1E{c->Kw==;7CWIn@aS&f?9Yn_(R1=)IAkV)si-&m(6+VgO} z1eMcQ{ap!q;dg`KW{ESkMjf1Ko0d=x*|sbg?l9tbQEN(qVWxFGPAz)Dat4>g32!uC zF+mpHp$=SNOHJxPuDFBI9*;p%je6+<+l)BZWh@SN>jvYU$SrpV!~3lmT&Nc2+GZw| z!r}BLH2;NW^rB^K&@P-Ruh!ehJ1vey0K(^evLYOvu#?EHlIp(oSG%c_$O-A zq5|8bq#Vcw5~!3y{s>E6p(J`CTd^#NQD1#yO;2n_Kk{TS+#jdEG)X|+QyUCd#2Uet zd@}NUP?ohT#N3Hquq_xq60Pe=Ip|T_Nm$bOdZYSsHVGF)dSAqe#G92gl{*K zxL#y`T`=sSnuENRt3}Uvg;GkVc%NRAOJYHZ@VZ);Ys*YXyMkHi^&pQ1*B96(CRtER zkC|2V_C|FO`y>}+eYZ(|vQf`*LL+4UPa%yL3@xaZ2I|9@PiAzXx1m>3^r%wH6zeO| zFEfnvzcl{0T*>(Q8Ec`DZV2 zy>+9SJjXW4>Vb6ZqWQ%3wT;m#=dlSHwkFsv*fwEzMLgI#ptm>5$^`v(gig{5Xw#oF z(+GXgY{MML?Gf@YB&j78Lmq=Hl4|{OqndEBZCbJi((-1IZ8YT7HH=eZ41R-(7=M;~Lje;cFmIajexA7Dlkk~fYQFkRNdH6IMh z!_}FP_1wfp^!$%l9^#Dd?n5tcqmN3Qt;W2O7=rBjOHdAe^<^I2)#4(r-zd(N!42HAnRsGtH-_p%*eV#w5SSqf9>`$o!Z-ne_CF z1@(D0Ehz|@qnVapJgp|@*=CI^kL}~Zj`E!_%jf$zGFefvozLNsilWlt#M_m*<+~bd$`73{5o2 z`6gKbnLo)SZ!yV6$f{J6Tw{^}@j2NfpV+L%720OTFXV*i(;zQvWc8a-j@qBr$4@{F z{)t=+uTAM=vrg08xtRehD^y}5bS`w%81>4Hyv|4MJby5M%PzOgn4v9V_P}PO%Px#V z5ts8LF5_I7XQ!(Jm$T?OkxSG2_<<=>oj@sMekg(5o^2-b(q?0R_CwmI_HjfYFM#6$ zsA*Hx>MP_8ND)&9L3zfU6C}uks+WZ7lFJY07h%%@=^QMzzK%QL`^8u?aB(C9kk%Q4 zbt@B8vKO)|qmQ?iSbjojqSQOHZBwn#)tMwN^|q##dix&rmed8k1zKOD@2pk3u4FY& zyPjt`{ML$#hicVf$Qf0T4b#uAJvV$4yk3kA;`oPG*iy#BcEZ+5a=6ep1Wl05GtI=d z;x}lWX@#>m`uG3~hPx!XT!Bb%-9XWD`gmhDD`=gXl#kks%15zS=4}1&xK~4 zT=0zCotb9yK?V!@!fx?*_cQqW@H@Qdg>B01lQ+nppRlH?+>=&@J!Hp4ea7vWtDiCQ zn06x>C%#@GcRXW^fnvy-Iep>MSSigj#(Y-`d1QfUdGE7^r5`f;YLndftUl=^g&+$q z?F&~+eg5cKC7TqRV==ua&uoydpCzN$&*D`vYy+%Mzci6lj+%2Bs+8t~XVnGt5vx~h zAi1YbWjq_LYM+=e!wOlG-xn?r%iFf#P8Mxj5V{_keNI&T{Si7T?I!92dWq1_ZZY~^ z1!Mp+9y0PLW2FSX4Sox9{MIeTQtW}uzq~KJTgZc3)O=Rgq$bGSS5Z(QPw8%_O!s1y z4H5Yhmq84rn)LL0x0qFbvz#27b(i#2qdT zlYG!_msz8?Jf{vWwxy1TtANXujAN(M_MBQU9qT- z-5T`z0ouaYaTb{wR}nhN3GISDCf3hBua+&OJa9oA@0ap?@VuIQt!+kvAF>U@G`0M= zbz)Kzs{2;rNq0N^ybRyWtnZMa>-&aXs>;D{2wTgNzHqOGUvfM^(+##(GdFfVl@H*K7LS~ej zMZa*XG4GT^maZ_}UTa3LgDhKV=6%^#X{<>}e#nA5&FEXV>OI;Pg4~Uz-uHKrD}AL% zC`Mo6hF1FZv9Z5o$*N$HO-uF?mbS|5Ctv8rlxOK= zY2OyY+6Zfucqi1}YkBs_`7YIXm!u>Yvl5C>YfvlnsW#b#>bSR$&*u^2E!~?uxhFKj zuYIhKFAV(NixaYEpoKiQA?g8N$IxXt?KO}HjK`t zYz=DqIAVl6->W}4ZzzYX`~eHOkjsWUmcG+Wc=M*S`;HI3prVgMKH}{f9#8s?pYS%q zOQp@f`DmV>?C4^g_?hBVA$6vc`Sj$Ry72zd>S4jBP zXNR{C9wNL|-;WCdFyXSq*B{(IVSywOCEi63ZcK zo?*pdm(E4Z#5(l0=b4IQ^hfiBqT63Ed*9fz^UzGVGZG#%JY0IG<#zhAgpW~YY9^d- zMXh?7NmYvUC)(QB8#$pDzhaKwFTMKSD9#J1{f|n$$u`p}a@miV-{Of!GR8s-S^87T zFV5DGwtgWvDF_|kK(z~f?>6H(D(wzh3bIqk`?r~!4M^9|`iz^t8@B0Fd}1?X&Q4j! z<=k*$JZdd!p1xbMwV?V?^)_21Y04(b7KAS{(GA~t;TsE3*S(Q#kQFVP2%89S%GAV zviVT+P%9;Kzm$T=<~kt+T?6eirpzvh^cMR;wVVZehGiu)0;*dg{gg;U{?d?32=@@a zSY5w)LP`Q!6IutC{bt(I6Mg7qzhNkI+QY$9QXTr@z2=I3@izS)Xp$c??QMDLAc-5d z$;K|#3KxXSlVtVwmj{%wt~=>B&3)={uiW=VDQL!-KG!7FqE`Qwc2fVH&AL{Fn*EMB zXD`~O9}dQ~K{mdlmfmVhoe@ONd6z*nq(m}@bx1_`LP=V_2-awCjT$I~J|gr(+w>!f zBqwC?AIv@eW;%iF@x73(qd2aDZ;3eGDvo7yIo=1|1+8B%-z?oDHK_%zFw(T|n_XI4 z#a?$GVVFg{#DJf>K{Dv0XB`A3_>4YQgx7qVdMDsuMM(rBBWO4>u^0t;ma}B~MY+-?iB@ z9@3&F%SR^UPo^8mL?>QkO3=O_1BHK0PE)PlwZ%tQx2QwkwPi(jwW!o(_>!x~c^|5o zOX0j9s(CBnD&UTMsMZN*|41EJ3MWr@7G2JY);>~ui5qLDg4}A%Qrq-6Ij!FPkyk->!Zq zSbInv6Uh%67YLdTa=>P+f)?Cl~k& zzfd#pAmfEbXa!V(E{?53%=@BGy}h1Ki1<;Q9C~3I(+;_)3erB7M*2dfmJ+{Hj}#}@ z^4q^qtA%P8YO2~@YKtG&`UQ{I(w3h+tKKiQoj1V>cr9Wh(GfyXnw zwF_3z+FeJ~!WERH;y>yKg3hCA2N<*cXrJ2k5t#_!Wbv2ks022CsghTMC0)`DvZ8l) zsg3#VqiZ_{@yc5~+``RpOm+bze*CWyTf5^&<;cbj;{+ zKDh12)K1|7$JEDy8Qtn67*pEar`E3~U#@YSJ9evuZd+Drf6Q@X>#<`^ zwTbX?b=~ruO=VnItKN3orlk6N*d|e33?S=uW`r&xwD+hUB1ESJRq86x(x#Cf`ME7epTq%Y2~i*%YmE@3+}i>0LCF z6S_!fF9%`kD24YNYByT#xC>`R(Q4gOR7n61`6%4NG9qM~87(BEGQT>&O869$ml6w~ zZ}R#aOu?>3mvLSURz$0%cS`~AyOA_}a9sM?2^Z5IeO#?yN@jwPT8uimm2R9wvqY8y`;yMuRq(`BXBzgwsGK*-u)LOQK3^}c=fSQ_j552uvJ$5%^$^+G|sZCHZ z$F$?>%M(m-t@qH|*2bzsu+deqdbZ;nHg;6VtKq6+)!y|Ky8@2zb;8xesso?E$zAZ= zICTIn)fIRAtbU;-GZn?D#5H8Xqi$MF0T-{a#m}k6c4Xnov8{z4*#sW=nmDydd^D;t z;-eKGsrA@WAiaXFqJqR<7q;6;Z;LH6-9CZc*eL#T;KgPQvt}`}e;{94dKLOU;+PAB zHL^f>;XC8hj&jN#0Pm8nW^hO0#&n5~>2Xf-ek4xK`yLhC8As1Zn=m827BXe**?EY_DtoFG)Zx^InbLY(DWwB=Zp`b$dUM9#%ShFRKgo24y+&l{^Yy=BXs zQh{8E4IcCwkq#_!ExgNcsbB9V!FNf?hL4gFjr7yb9WZtx7K~N%?xiUBRR^V$ z%e8IDO^{qRJLr<47n4q4=Gj$J4&Mpy zG^=WnSygg9J2ZlqPE`k=a>4Pio8iT1EO`S!&ZJW|pADlO|wGp}qZxdg6ZDdDFer^~ePvUm^=HhPxh72k*B{8P_=OINt*V zvGEbrdp|E>b|=wFGD)p`L|sr}J1@G%s&1|zz4~Oe4ji{+!twBai4m+)yD%7cY~t~7 zCmGd_RjI=esr4zt`;U~u&T3JgqEa8g)4mjSm0*90S`DUF(r{7(QcICZT`p!lDBu|U0n8J1{SFM8_w>y_EAz6E9 zz1k(#fn2qtl1dY!ay422HujW5Q$(*TX$-Y^q)<8rT<*Mf& zB1dbTYA-m>i-A{MY+k3n#6|RCr`oZOA;(VCSGy34)E zDXO;8W{IxByb?c!laKSYQ26=$VRf*QtTd$^*Z0ZVfrnMh!=#*(u4X=Ln{7FEvAOVW zeRy!;)sjLa7$8VreD8f&Z6;1?6p4=P1pW-#!l@2COex}>#scVt3q|}M=I&%g4xglNGGX-m&^{`HAn|*f+u4vgIO{0RJ}eK zYSZ-`G9KAPnQ2NdTWF3g7vWZ?jOwiD6g_h0STCF%2QOX1fJ3$*uP;iTmM-^_QO@eB zA$Y0ErvbPwqF{YV8JEHh!*Jm!3R5 z7E29F*+{vN`*Eqa>>Uy7`q{}^dKW?BXyh>0&ZjjmQHj-*#5(u5ntwY>STQ6yVL8f5 zjW<&t+G<|HGv=xt5-BYbN$wG+%~eMwl6{m&4mwN@8GVd!=O{UG6P`O)ttQ-2Fd|&~ zpv2FI&y!Yq;=X9L_Ay(EYI)3Nakxe?FUMTm=;l`rF^^AAn?YX~5rqbga>Bdjs(Fu7 ztR)mnI^Fqlrx;~e#YuL=Nilqi%o=;xQgsxss(ypb5$l{O z8;BoouuZpi5SB+Ay$}5J-oc%3{FoBey@4%G9mY#8)%WdImoA&r&tq5*P7~z>6-68^ zzgL}l!gk)6GD*atUBIMmB-e%2;)vDXzHcVC#Y4ZXFp_J;c&(9KY@5h>#Mls`TNmRT z6rK#teA1RRsTN->#rnD-4+&CSH{rELtXjlsBUTe)#ieR5u~HjGi4`Qg;Zk*y@NxSH zm-idmCErsQJViP7s2@MU6jm{dbwwBB>O{;l<|(<=+mv_qJkwMz@#f6-Pxt^bct0h0v<^~~m z=MUf2$`H0N#P`6D9L^5-rhJ(SB|9r>=s|9%{(Q9>DyH;uGuus&WtXeHkkM-|mq)?O zbnPNq?(*Z|0{qKpzrn1qGl^N$nc3h!$Y^EI@SD0O9Y?(T^nJ$y2R&1gv>=#qNSE|%nTh?^fmBX8Y9v9Vy z58?Ihw()N1Zqs7rHf_G@-c0;P#M}bu?3p*TA-fBP`;cnrGWnrZBC_UW*Ma>|Uix1e zd`W@Y6rv0+JsvNE?Cr^JNgOVSzd+oPUAZ zR3>e532j1TJCTR(;7Z{4El>-eWBI9mhUKRdqb-ucW2@A`XKd$9z*$s2R(V&M0pHaF zW<_tgN}YVhHhXd_0VCb!&!z3II<7X)Vy`DxVvk*=RzFMU%5|B`M-ybOOYMb>c7pO? ztX-;eJajVqyM}MRrB+;o=eX2D!gWW>X5ifmS?E$bAQvtn($K7k+(vluD7@T>T?{{R zZqir`7Q5u>VEPoq!VyvRe89WN$8+S}ZRTC>$Ci=}xDA!W5j&~q$caN6;hqt`Bzs-( z)uZs*WwiPTUV394_Tv8tvNmp|JRYrmdHgHq@Eo;ZtHnF+fwoW7mCxI3(Ye>isRO4C zI4ZbCt$Uu#7QwLxh?5(&a0lSVELMMeRz|@*7Kdw8>Q>AM(zgn7)7E*7x$^v@ba3U- zVrwy9qAq%l@h10Ui?2~TB__!62S=W8rPs(Ij?PI&VqNoPeb5stMLN+Rx2 zcu6EgB4V#6^2zOL^ETUgF|F5_6J{H++NptUl)Cd8Ze3;UN}dg>2f0TuJ7AeeLnc$R+)5oG9tX1 zYd^0ryYkIG*qtwTZfkKRZe1^;)kTJ}%dv~)M&osdIIDcPuk@3>JmyP4@et z%5yLW!pN4z>S#Srd9Is=7t4u1@gcl*47GOZmT1*@#+E&|q>zqz^YEEUa#8{BfFIg7 zC0DgNuXg;C6q}H@->mljm=RTXbL3p&Iv(I}R*A1NVw!JO3m?U>7_R+hwG?i;cFXXh zN`u-7kAklRv=?tyuf57lQFx0wK!h=xdhAu|&LcL(rp+Zcs|l}(O|hEy8beq6&Tyxa z(~5=s_Z_v4@R+pk99N6xBu~rsL)KwDv{+I(B_^*|&OJ9#IS(dh$JrO*=2n&Jqb!xT z8ijVlb=|5~!^JPT&1g&2cPTm?0|(X-C!EP?OVlO;qSKbh#x*mp4dc8e>X2~7%j88wy2^N+ zBaJ1?)Xdj;$_g%1O9fj?)TY-l0#7z@e&2RIJ+owZt|av?_+~Zcb>@ESPkHOH51Wz2 z%eeuY5`7CZwitPT$#Hdf?u5)(gV*;{a*?*BMD5(oh|x`qWaZLq^C-z$Ze%VulFe-( z**&8qTO>9{_UBe0H(*mhmSv`p2Q0~^+^TIIC9V%%veUpyM0WL)IPIsrx!Zj=$9u;} zGMZp&CTotAc%)nBVh->|aa#l*DA895Ymg*5Bd%j2t~)PI*5=mfX2Ta7$!!z-u~FQ% zz;~7CtK3+*f*ZB`xH@$q6?_vbV2S>c<^~sX_VVE!TYSoO+tGNro-6#w#;k>RELR73 zsS_s`a9zvQ-ko%mg5|~upLVm(CGIjf{drMt)fO#ROMgq_A{H)JtA8hx7IN_@Ni@SR zHj@Y-uU)Q=io0?%3Fj?3H?Ps)^d#h7Y~^ybNjML2?cHn4F5LM`a)ZfH zJV)=pLqE?+m;0ywQF2iP-=*gwb8ZE4O6l1-sU3xv68Lmp1~%78N{y~BKCJlAv$UD7 zZitL3ZEV^S3SG*v?p4Xt^b4(N*wstcuXL$#zhxgFS5<3EWka2Hk!O^QG!ZVmR8M46 zAhO&|tyX`NstO=hm8zq-7~@mZeqo!Q?))wj1hK4UtjHT%xvpA|>96H&6Vd7;*}3p) zBRf6}tSi*cU*n4>j@_*70jPL&)351cmZgX*)Q)#-Gvo4+^H=Bx2eEFE)q-DQT{S3r zby0l8H5$h9HZ8ji*}1|vTb2^Z3BFXFTwX1LuRzv5UBD^NSM;;SQ#Q_7mvQxGL=@=R;gu`p6?s-_%_#Bx zgnL%XY@22A5iUNpQNz|IV1oVTB(l0jfqk}ZlX6kOLc1AZ!n9$)0i_naN3>2*DA?n9lZ5UeNBk< zBijuZT?Q?uo|o8H(2t3ljk#1xiyQTuk*LwvLjEX88T2qQ58!7|O6ACtX+k_#@d%x=gz6c`?pa#zs80*i8Xd z_uFJnZd_)sl8rjohlF0GcK()j&ohF9P|j8Aq)<8PzPIH;{~ZPsW((h;Jb9SkEpOU{ z%wHwb-R$VKtJDDrtOV1TX6$z{ZdaXMpK=RwJ8|d{V~df!ToA5`ObJ)9N&d6v|dY>Nc?3!qX515r15Pz%GQGD>AthaFP`}l2N zrRKel-@u6Mh~J9U66b8cweTIL-zH>y?8Qe6KFl}MYjlG|KP^Y1#ugE-i@JjwmwVT7 z{eu_ zB)f(bRNebzqTVc5*Te|_85AJWHc}Wryr$lJkEOQ*G3st(=F+|=^hJK6*YDy|Tn@U` zFmoYV?p6!`K$Tg=WO|$zD(!By18Q9E-RAkjqZg`!f1nVRMl{R!skysV@(1Lc?`)VS zxKEFhnWPcc7K!(}*%EI?dNX8N+3*}oM{a|6l&M2F7?(>pYhjdj>ufb{KesnZAgYC! zJ6p})&x4?^Os(EeQgvne9jLhGdnt37Tm|D`0J&M`XO9V}X}_l=`D@v?+@p@#xd-4z z&c8>k{v**#Os)xT%ROo@+?d_!y$`6iAk?0FWRjR3cOOgoJ!WgWP#W%03lEUb`g_c5 zMdzsX2bheGnO0-{SRFBx%vj`3Jju#r{{fFY_eh`5iZR1^^#O^&YRG5;r4Z3gKTywb zxl45(w8gKqu0DJ92oY&C-hTh+e2&SFoIqUgmep!u3&X-SN;)3Gg&!HO4!&TuTu#f3 z^&?lRX$R=4U5IOSG0tAW!@z2l`XQbxNAX-txbP!Am%~>Wp5wg8j*rw1e8iM~)ThSn z;(A2qhqn0Xr4J16LpgMhDy${1`l-f-Y&Gs9?zcMDm~X>YW=E^~?qs`K{1H>ZzBR@J z+yiu$HR|z?sC(^uYNufH_teRcXsjS%rQa7>PG$c5kvtMTC}UQ{vE_(GYdL3e^LEvX zQnJ=~p)TX_n(@X1c_Vx&d_1{}{5cW)@Qc@~1Ans3jn28>c#-0RE4bf$DgXVfp)ciI z2yzlsL{x2ImRi=zVbJ3Hjm@m@Au@8m+Sy9hLD`Gk5QHluLbfD2WG`Z=q|V_-?nN9X zZ#V5DcenE4EAE#IxeOfSJ@>2CeOPgNCw|=7%zcd_*hO*U`KjQ zdzebUUw?F%>(b@n8!oXgf!{w$+zNRA{c7FEjK5aG^_Sc+4z=rJ+S*O0SVCm&#Pq?t zS@Cfp;?zE%pV-7Y*2xa~xj!?kix8oW7huSB4;Zh~#R5^@i}{g#56JU3b^D;)yk+HI zPn$kC{F;EwU^(y=4;t?TijnIdR7=~4SNEWP_>=B~+d@36S;vuQvS#=i;>j)A0CFuh zBWo;V*yzU;jwK{?Es9*gKhl;){0=yiXgxBAqNKjD4|%x*FbliD~+!rCKx?8N^i zlag8PYNZ#$)s2#Ya`^2J8e4ELvLBlavmlY(e#|}LiSQ|z3_WPf@IJU8#s1VbJ0|TRPTxM|_7VdQQNJtZ*ub3jkeb=f z%tQEDz1>Z?@FQ!v3O?l_eNKz>AuoPN?Zn5thC$nmm$g@7c#SGW*N@z~u&X0n(;4GG z=?z*nz2p&<_*a@^t@>4mtk{2L-YS1&c*V)QB|b9nAzx^uEt{g&|CP0*uJSnFrNL!2 zKc4Il51&IMg${V_VZGU=XpcdRVv`1cOpR%$x4RIJRH}uCc;@Y>99}8n&O>;I>i%Cc zTK&1a_Cjy3RKGrCo1NM!hL>ZgBn$>VR-<8}y=`Z-0W`u;J`VYs9t*zm74a^P5yPzk>;&Vf}Ia^GDk2snM!n zB@dO=9ZdG2^=eZGKKs`j4})#^46av)gmYD?=+AhE(D~@uX*6SZ1pWy1qaB#UO|dWd zb_Nvv>8#wtASbtSo!5)py1{s9iP*A19g2evAUmtoQ4)yuR;%RCLC0fi9yrFSx(^$b z9X~GjvE%wzQfb>#)Yi|L+`ArAdoh|*{P^&ek}ey3lE--XkrRpKDHejqRq_|at9fGh z1SRo`2(N?BK#pt{9f)pt-xF#z@lxHM;qfHgM|h=2?Ie6*fN+^%iJvQ<))2n|!W~bZ zozIZTkIbiiBg5}WmD))q6sf-Dpk;?iwBmH>%Z;(d8SBUeE+r zhAf6980t3`wWnEoHmbzGlV~xC<{E_^xM%7oQaQX-jP^C(%O^({`Zuq2>F&%cKnLw= z{oiTF(i-zJ1#XLL)B)U%tEn+}BzM~7e$IK(X-^x+wysT7%+qS&KgeXt)A~KBE4^^p zPY<7~q|zJV9V2+D6!DP(UoH82d4jxkopyc@axG*Eq_n&oL5Oj!$?I1bJTS!Oji^S*E$#NMc_vN@(V)e@~+6|v9`1~_}v})XEV~C6iv9R&J74 zVSLPRlfFn#4Zt14HiPh?<0u5*zbUc?{ZNe5%zqJ4+iWbZ6>w3T2Rib=y|`NVY<_x$ zPoKm#As4F!0eL_i5Yq!95>v`ANk;Z(A^63cjqdDthB35Rf9I40U5I%O*4njvIir3e zz4qTsg;=cnH+dqKoW{obiB+hlm);@bD2W8&U7OWOqFuaYM7U(g`7AvNerQ8U-4(%m zHk*e!6^1gb1d=@qd^M5lk+pG2>ZK#{97QaBB@YmKWV1SYgd7Jbr<~|Gx9Hrw|1fMj zG1P~x2eNas+60-}H6o9CXEP!lkVr=&-tEunky4N1y@Q(5cew_)TDY#wGGH^4oNyVn z<}+!`Ir2<8Ey)d81X(Q^|A$3?x{XbHo-U*Q{4d*txlY7}*M|2JsjVXTD&iF&OH)QJ zN4nvCwQBX3lpybi#%&P^Up(GeZG426{ZQ>BJlgk+`dHAuMV$l}?tX5#KfP79vVM=k z7r{q8Kipnw$PK^!Rkiv__6mr#uSV|R>3-DSF48OT%IAO5U-&N_so$#-{|i_Cf|?`f zQEDl;vVQy7(}&l~N(rB9mRXMcC6A5pd*BO9KJp&Z58pY$kL0mK=Z&RR+eUAFQ6+xG z^x=K+>_;6J;l5G$68I)~@h9~gxqDXuzi$-27QST^-Ur`q@K+CW)J#BNln8C`$42my zi7xoii>il$M7v*7sbA9p_P;#562-3g1)hjrmiurVj1it@79jGh=_UNwDDfI~-neqt zh8%iX9l}RU!7KU(bBfA1W{bC^{m8uS|I4xFX9MK6{|!Zo-bc{Tl|x$2ZSn<1CiFE~ z_$v4!>|F+Lz0vHwUiiu%sU62CWX+HC>F|;OoM#l@A(PKAeaQ2L__lASTdDgk_}A6yK55a{BiFnjt6t~#?;!U?NbO~|j<2i4<2cPx&-LN77^=(= zs}Ox^fv`Tr4nu4~w5z`f8${$9sEBE=NJBh!9MOg7H`sE-C^hW_tQRp)7vq`{*ZxdS zCDK*r2|8Ns&-f@s3`On@k5R!BHpe(`Bb#;$3@>J;_p=}B+`~`EvH$YCH@xG?DA0aH zr-4rs`5j#7A6+=MW&%$v1XaFg?6=yG%imLna1&knp1DBQvk@Tt8@T%S^oR1f6>whM zN&kv0tRmOKZyCW$@;><5_tZ}D(e$4BSg;LWVCw!+?43WRe%@2_PGZ;fo>~cVGyPZn zR8k{BQ6f5Gk%DBFK+6%FEFnN!dV0*j$IIg5a$e!j4vxWWEM|Ld zo{*-hc~NTVeBXS3dMY$#;Qgs3)!`prLMcfL9y9#L?eQRTfnS|GWt;8j#8$#1bE7QM z&4hQsS0HQG4sjhnrTjG><9>g(dk=h$`tvC%C}NTN=9KM%^bW)>tcNBbauB}%_v&Pb z?XmWUY!I&G11^jd zC1+0g3HOgbI6H4n_~H-LyfegG`+-~`%RJu$*RX$he{+(vG?UlQ6vv%ZyUy5V&8hz5 z+3R{2hBfd*dy*7Qdz}vZN0k^RvHCw6i50`OA2>TP@gcmP*md8i^6%;)G28ol2G)pT&%CaB#9jrwbYYCgE_kYS}C zKsg$OI{Txm`S9%rjgJYqb$R$|E}5!=KXy?6U~QZax&NTrIR@XMgT~=j5H70aY~Plj zQOzxeZ>KJw?Yjux*<$#vK+bPb>!Oph78c;oid*TekxSuCgy)UIx4`F);3eMy`0N&A zi*DJ;42(^N=`(V+<$%v=Q8QyG4{6I{F}4DZ^ws)1SOJhp)7Z88QF2?<0gPj^Bcy#7 zPq5Ua1MlGI`JmgFPD=+Er5t+GOm)cL96f?QV=diql_qV7WgpaXrTanDS zCd4Mkr&j;vY|{{?)qgQQ;_E|h#hqWu8PlsSj!WjdK0Y*w*}dvci0J+g)uuQcJJox! zcy5hLj*rg$NOpKxW40Sy#s*t#>@TR6kJQYuFk{5=)9T}PoY~{&pz`gC%m&&{ebZ3;ySMJjfvgd1^pZBBm4B=b zL8exjaikkZKGACb6=nWdr6v;YBYb3Y7ZYCpv06%a%zm8idX;x0^@%i1U=(l7Scg6~ z22cQ5`$QcjCQI(G5|X(K@oO5HGK`~KT_2k>2HX*HEnJ6L);73SG7XoieR6ia+W$v) zooXQtN$B4a;x@R|!bN?eo)=8{L~iS3U6hLt8H174MhY3kJ|BK)fkn17$*y8SV)BGI z2cq*6HS-)?6@MZhd&<&3wO<8)>=S(`XZw)5Mr1JuH~A)CfvjEAHMma3r*{#Q+crE$ zk~{4UqP3~S@yS`mrG$^1aa@Eifgd__?8GY>g_kS@Nk{C9#P^F|j!`B5v}MfkVO;^6 z0W0+p+4nZXSB=8Ay`jdRlYDMm7va@y=9e72$(cHG5=|RY3oMMO(xl{gWZOB^TNT0m zZN}wUAF}-~YA2@C3;%a`=AGogO}Oy-Vzlw7tb8-l)81kh`*e67rG}jF*`LbiMy9Va zO-5Em#s9odS5Nvd9Bu2tFTP8bSETd5L`wUFcJzd*>rN z4cRJwaZMA#Sq&K^;?OdR zY}v~g7{#Fj{>Z0l<^&S&H0z)OuH#d+4lbtiQ)6Np>xXPNl*~BfR%HE<#s0P^D%GBx zHK${gl#2-`;;WYM){M1y5aNTht{(2Rq(~|(wNft^0i6Ad*RFA^9?@ZdXsO2uN`48+4jTN zw^J$KVxijKu7473s{OajD#y>BB68sSk4Iiwp+ucfOV3T_68j1BjA%_jZ9X^oJWDe~ z9^u-e0PBOB^`Z4#)`yl8>X6u5zv1jhcJ|?asBsfXIs2rVGm(ITljgp7F9AQ}KB@K& zWu?012g|jW{-L&FJ#Nq8T$i=K~j2l{S7DhCczD!_2fIprWD? zl2J}&Mw`{N8B$SB8!06gySYe3#qN^Qip3UdR8~`ut5j4}uCf~ym8(=_Y?-ldRdA#?!D8?4D<5&@R@VI=Q+=L&i`}IJ@?*?%E~^Jo%|*RKKg#N!$wi9 z|5(1AM9GwWB57#|bn(lsmXxMZ4RxPNIWVTR_j}oKwTnllUS@UrnQT{B`58Uo3a+~C zJ82%DNn*OT*giQyf6M+WOZZLOc3`}Xe&n|ukc}!=@`bVUI<*((`{Ji&ni+h%*9d&Y z7o>ici@li)XF^ium*4Yo3@l&yk<87&@+w|KmO&jH{Azsb_rJo1z(Mn6DLOV?5^Uvg z-*@9XXD7VqJ3Z7kYeqHUnUt;;ug*T&gX##cg_q*CH}P%u$+Y2CK%at|52KBnVp1~M znVhzQjxn~^X&u*e^8dYYe=oincLSYdYZ(`3xa%Xx_re>$m;I9|s+RA~Rk`P%w8sdt zh46M$cU%>2*4n(ug0qs}8*9+GPBVP>6z3cp9eG&8?1Sc*s$q7zBAuKkrF&%YR0?+e zpt+=Le3gt_?oQm*gR*-n4WN0@913IIujzKl+R5B_&d1p%DN}T+&7`(kQQEIcuYO-{ z$V6$ykZjCk$P5gHHVkdl0U|38AN~8`T|@GX#!H~%k1bWBGwh;O!ZXnktgS4ZUU=59 z6ilNbx(N^OEOmsthh-h%F`2``l_)TESh|5a+SsPkTdIk?7lrm6@5$WhY|icm{g3e1e;#ZSaL*X=&U-i#Oo5pS4%s$EYit z5zMv}1TVhaZ&2HCHBc4n%EG7+cx#wqBNGmCJ~#7$icz*GT5#k8BAwVYaKu8v^zywXVNm; zQCF>{Uilw+MMLdTvY)6iSxi=2_ohsiyjgms5+(CzIp?I;L=T3n%{BF!f6;5B2hA&( zW<0ggvSk*H4LGi%dd=|t8ortEv1Oozp7lSJS+wLFP511GmL*4H${v*8{yYzWHWRpy zNZ|$D4)2M;1Mt0YwUUa-)O~$Tq#w>i`wfZ24A=(c0B^&H^S;S;T8tEAV_9xYXd2P?$NUbFy5NCUj=*O1|?}d2h%)nD;x|N2ed>BBXG@lnZc!eHcF!62d$@u zf%);WUEu=Y)_rKUze9P)4~{zxkO5Ck7!2u=s@Vh2O_2GyT$#A#_&E%hwYfCPN@Obu zw?Ffy+?(s1IlC1QP;l>?(OQw#iJR-kzSpe>WhF;YV){l>JJQ8RNaC@WR|Guuea!O# z=Ou^MtY*9d?g`^Yjl=VjWgSXvo+IRG{jEDfy7jj-QEYQ)K7k}^^aicbf78X1WXT-% za@vyyjTNZ<&3{>!``kE5Nbdw|dciS5(`YAJ2Rf2!Q>MlD;!%YMcy=uAKaBPoz`InZ zdhlrMJS%o^KcEoagOI*(HNFZ@FP_y?sCnG`a2sp%PQxR+kJDBFH0*W1%fdZL((-_) zmf3$IoigAM>5QEsw8PYxTn_VM4_SX(iaovsLRrdcUTP8-Fg((&x)d5!ki}HtNtT@B z=}$$JuI5&AuANZbWrUX`OF7}bTEZPxcyP@w6mM!3nH)a(@<@q({{euH3lnee-qmvbP;*KQeR#(|iTs z$wx{z%F;AEJm2na#+f4}Z7z*|o-EJRHNsqH!rWYB7Z6{|D0t0UgRBo8-fH~tq9e_M zcI4wJL`Vz4{@5<-LY2oX6Vj0hDL=Jk#EPq9!PKnx%>*=;+OdMKCCrCcl7JyphNlWm zV{1q?)xawdI`B02zEu;R(Ix`yue@enj|PA}z_IqLyC1$cf<}7}jq*rIJduXfrTKf9 zcI`9Zpe*GT2a|E{BI4Lap{Do^E*mvs2N8{S-wW(GQuYJW&=z8aM#}m?l}XM?+66Q< z9XYCiL|PSu#_M`Jf!MWMA<4@DHv_KwLkg3MJlQ#GQuc&U^_oc^;aT$X3GA^{;LM#M z*CT2ROpuNGyVoH*`Aw=gYS6rG^Ju4hdonX{-b6{8=bV+kdE#KmAz?My_YqfH6DbRQ zi5_l$n2e_Dhu6Ww%c#ZV)=ndynu*d)Lbl3@Vmrk-C%RG2n1`|6eXPh+rQj4AXs3zl zKy9hAPSHUVb%OS#%5G4MdlEy?1`5ypF>~Z3Nt+L>3c@mA{Uj+@Sdzw6&OJ(p2k1{5 zG(H()|K?>H?W<1fwRnVNq>nd$z~C~B8rz<9nSLt2c~hi7e>g*xssS3IumKX>H37J7oML$>s{6%OY@yG)7`g@@7;bBWT0(R z0)s4W2kzU~>DdoFzMR3)g)wM2vqQc`LvqEjgQLCCfaR=ZO3rX)Uf}Izv+TIgiq%Rh zfjc7bDtJ^F*M`slKRCzC)o)+_Tx2%P9~>?DnU>^>vg35;iD@G@hjy?m1nr+QTiq;) z3rIEd7GqwUEJX`gKop)cINEj;65qWbS1xd#m>!4_y@lv|Zf2~g=M@wIJpB=b`r&;y z%kFD2-rdJC<`zjigJMW688kj`VZZYQS#*YTW=s#7jDb+4>IrR%C;jtYkVgr%4e@jy z(QJKJ$v67Ta|LNrw7>0VwOuJ`XQ7hcGxgVgos{#NR(0KA$fb^!STpj~*U1*bC)E+IEpO~< zq*wLH*Jm;(IVyOTDERM;kOeGeUSX;SL_L(D3{S;k|_O7{`7M z-xnb~>q}Z6>7PSms;VM=8x_tI#!JtkF%|yaTA4H>wSr^qNX66z;Q)}s`NIm^gV6gG zQ|j-fU?Fh8g0X&}L)M-{<+S6>HJ!aU7pjw$M>WT~lMm8S{~*qDopX{hs|U?%{9~Sz zMdvzarrB4Aj+R;_bwo(z{Pek`mA%@WIO7ArEIjWIv3NBE%$2628Ba1=@`!2oJ!`Fq zd4a4wzVK@bnK;IZv@@MxL` zUJ^lHA-otpx`vOd!c##m3Z1j&Rzy(JMtEHq*D~#bH=@MI!2q6Sj6q3S6T&K>mIT+% zo&grDt7ZOqgtrkMK44c7-i8su@bD67BfOP^?;5^0f-wVxA0&OkV}>w_<;JwB-tV}% z5W$!dcvKC2TVGjOhbN&%)}7BvAxhp_#C^no5iZ>zLz($J#`i`FITrvAYPSE#)pQjw zS)vPQu8laO3};*?PEO|UMs!kk&G^jP2U&EOv2t-{n6Z2~9W}C~$jQ5aBE)hNt~`Tu z?2ad`LqmM$z&;_Lpm_upYEb{*`R<)_=J7s2ENs0M!tbn!hF5{G`Oei=7FRTEUu) zv6E`@4|G;}YO&r@S0~SU{E9(;8={>$%Rl*7S@|nQ+QM7L$89FU!dqku5o~3*=oRYp zqX%HU$c`;K4@ovy+_*};<*$-{iSyX>_PS6(t=*CznJn4L-o(4N;_C3^{Ylnc!g%HR z)A+XBNq9ayJXbyNd4IB|Df=i*>`#(d%ms7+;c(MbiE_iVOE;Sr&^1JAVTnCfSk3br zTsESNCvTTuLb>&VvTl?8iq^~8e5WfuD=Io_!)?^ek8}mx>v1oAJmr}98ax&CR-0`$ zJhJ6d+GHhgWiweG0QS_&FfckG7hdX|9a|V3%~8s=my%YMI(hnH2}Qp5&+-Vr$^Cz3 zMTTki&mW66Uf`XihV~ik#`UnBbD2IKeYgxb0yHlEd_V_}H2|Y|#qCnc zvKcgwQ}m#;{M$oE0WHB^!abbjCp^hRc$1dEGml96<=XFVH+R2IDvOPdY9w@QL($@_ zvA6@bb~xQRG8z!v&*!r)N2@=mb;cv|23mP)_l(P(Gm71D(NQB2bmm%oY;~#I3m-yW z7crWat_ifhdPvLBFlZiweDvY5Cr28H;v;Bm6g96IUeO?1mQi?h4O~7_{;>lzu zHj(WCQ*L-pV>?YXPTvZt}snLMdKLfm%Z@*MLrX53z!8KyHi zfohQpOIaZ1EvFTF?vVM*X@y01jIV?$WR-_kLIZr^9oDSWhR1t{Y)45taGdY};R_Jf zS9--AL9^6|?ES=f@hrGQ3a+35c_KutBRuyGS*PK7gpVyVE$dD*d^h1Sg+XiFiE5gp zU1`BhzagbE6P7FVS(3K4MEUY^=XB{AxQdkK%kM$>3&h{hGW;0w8)Hy5SgEr5JERU<$Q&+IatHbHN zlUG`5A>E0tSLxV3U_&t08nI#}r$qA}9V1p2&OLYX=sMXNkmbvruE}Mf0pf(0Sq*$d zzWz0}*i=r|2kw+DTQP?!^e(^$^-C9xDKh>-hwOaes~=`-{e1?&#}80 z=ECH)t!BX6F@p0s3?6uT?~;NFZkRis7@uez;n`tal{CT^JRy$|FTIQK3NvxXrPln? zLwM$9Yu`_msO84DW|sQJb+vQmn(FmjSm@gBT>senRW`46!%DMU;$|ASJ9Ohgc@?}Q z0&jp9hHA zO{&C;@+{q+?YvuNRI)2q`Ir<`B2|WzuJ9f1i8N1CYV)+Oy?g9dMLR*I$Qd^YdhwJz zCi^vV2~cm+P4V!x4xbe{xI|EU3gH!x>5jnksa1wMv>&NVgUQXk`8GUdkIDAy&|VQt z(mp9VYQN=?)ojCFYG@!X!oq8WD$ZsXD>fQQoPM*FGF zXbGRB+-Z!maJ4l!A821~AzmxI6Sw{FopS08Gz#zI*6O>CSl-8F-3?@<)Pk`AV5z)Z z$>5_emWv(1Um{Ok%fRPOr}!V2v?}DQkzaHNk9ug56$H4Sur4Y6c;?Y9$IdOkUhFjgj2z|JRR6>#n@B4r|| zB@^5OXd`?Nd~AuSy9?fflB7rUN(7I6v$5%9pR8kYbQQ(m!8!DV%>O;(Y4^j5LxAP$^I$YKk=_dBv)GgyLNZeBx-QZeeYH;uzY%V;1i`l>( z0kqCTNXyAS=k~Fe4K+bIU7s}@%4EwQnD147Y}spWdkLSnMfPhr%Eu*|HPr~usU}>F z8e69tzsw9TCp<~@H>o}8>-6s8%=FC>A_R!gv}N$V_i5lb8#O~}XjZ0jzOqG`Zm@D0 zR|WKMkyQ$#wpt@uCopO&-_Qak1C8w}_cSVMtE8>6B(=kzR0bTvhItsJC8^&k)Kaa1 zr*8e}7(}MN6hSlNhZk?<6JjVSLG#L;y3qq%At}|&pd&cT;Ktp>tm$0eZk3$XPPI1@VT9P5mXqC1Jf$tNo7e@LTgFc^_8Dl8z%$_WVO*7a z;MFZMzXp9(Vd0wPD#FVm@CLXqjH|w8xVJ^NpwH(0yX-&9IsK#o*uuYuwh`5xoJHr~ zH9o^x@Z7&k&Q0j(eNryc-_~bj6~8h0&oWp%!fLDICe}AAo|WB7>zHXDq2>Cz6S2&km-2otU=O$?88kk6mMbF|={3VeM#9uAM|{BDiP? zz*8g0_gg$%-adrlSr0{Xx1K+Hsc4yg6HPH1oi# zq3ucQvkLC#5xiRZ@%jkiZG_jpD%%OSZGKg99&z%~R9Gjnd)25XZx+{D`gFzXjpJ>@y&7z(QJX;vSlqt#)^1OXe~9p>n-|yvXcW2$3#c% zdnkY z8#R%)2aR`i+Fz=b*|#tY&U=Sha63(~@)k}-7NaJ--WzhFqq^P;ZSbnT8NTa1*>VeJ zu>uzGOWLDz5`vyuY>PE>u=P5_^XiE7;RXv35H9$(ORxa2 z_&wQfjYzdbGL|`Iz^eE7+7@tyLOt}<25dyb*ttuqs>|eKw(M&l zJxF#EYCpVMlIp4F%5H15<2#NNyJbl|%7ZYrS)n|2t8+$t7tRWVjUz_`cXG@klgJQ>7`MpkfKeaFI)&LESXB@J zW`7{vz_}S8L|FUGrM1Ds%OMxO042tjsVd1wNK4ZG*&nR6kG{5kN{uNOQW0vc-{7*b z0b|f_9-Ha~E<{iGnr6gG%s4I3Y-w!L#HRkiJT~R?u&NF-Q%$abw?xob2XCezNA@KIWrd&RJ`cKMu{bp&TWV zc)!KRHVk#!=V3tvJsB1cm-oQ!ru>?prfd}|{NI2OUS{!dMK$o6ZwG^qlR1K)NcO|~ z_E~)kz51tdTi^%bI(nOf?Zsw5CjpuRZOs}GT%`2CGvMJnD+BNaVe;Bsl22g}{@B`C z@!+ZXSkD;GirMoGYfj_VFOW~ruLC9(p`k|yioxq-$33h*Mm`xdzuOUWy&Sm5IeAg@ zr=b(QW+G!g%`gJ@!0W=e+EfUy`qbQ!JHHA~WtfmEZGe|X;LY%&Fs@45;R`;Mo%iY` zM=yiD?ih?#%D4B@wz@u-G(UqSzh~-i{eCIuH|F4eqYx%btDp7e(0Ou4R!G7bl^2UA6 z$uSELnm1>TL|1+=@Yri5{eI_UTg5?{e?PHGg8?63BP%sv{Xto$0d>KE`>v548qju7 zx(P@dAz*CVGe(AAur@jQ4b+0(yeg<44 za>UQkLdg1WtUH0zRVmms%U<#eQ~!?TZ$u#s#HkiaJA^a}#81p4#X zvQ~FL+z$8Q*6z93x`wo$Nh^eBn7mXUR?)i2fP25S4C*BEJcNu}lSh^RuR+PtMY4P& zYmP?5>k&6rX`Of)zg2r?ozNP=7W-KgW|%ETn()4FWqKncZ-PwQ%>AE@Hl zjS`$bM8=l34wzN&;_qbDgU&f=?O`f3yq)lE-$~*_&YUUzxZU4}CSxoie#sp|9!Pr# z9TgG63khFggy)=JgS!)%{~g86LEI1TiNIUn1Mu*3 z;29CPwg8XG<<$T37%uKyo_%{rKdgbf0zG3}waPcbS6DKgxHm_T>47&JGE?qH5rZ@7}J0~YqxhgqvPb04AkTr52- zTab$B0P0z#xB+0#VHwt_dk$MsU%5hNKT6chAIzu@l`8yU(0KQi{q`$ZOFrUsC#eaI z1r!ltt5>_sJ}n7-|2Gk0!9I~3CUw5n=|)d#Q8X7%UG^hs-~EN*DDLBUm*$*F*t+PERn56i~a z6)}O}F*ez8H{dpIF$eI}$4U2J*<`OFdU!8)Ur6P^$6hdK`YomsGyOFsa_Sb+-xW-M zX^E@^L}$tJzfy2*DA5PAwovSO@{}U`MfBKsN!&`VGvkNMXLfwR%y?N6@0y|EZi(LF zjL=y(%y;aTxk5zJUBJGNp%DZnU#(Is*K5Z!K?;8{!!$IJW{OxUF+@K{%iGhs$2 z@?-O?dCNeyC#d+6C9<^z#ipR&$w;@CZCvuTz#@B5ypY z7v#x9!3oEB7F7pM`y~`dvLv=*(B31dD&4yA0qqlH2{0{h!cfR)rjh)F^K{8Z!sliY zKDPbn$QK|yBaCajez5L=U5p}HNu9tRm+V$J0yH$bmy%_- zq_uH5>UD?KoYstw@C6Zg1w0=hKK$d$*r?Sa% zu+5opMIGaK-Qu-*1Jsa>u4IWRXEq160N1&@odCjZ%TFH{IZDd^L0R+zZ@(7H+JIRy&0G^k{vtWwlsqE1lnMA;2W@}v%pHtJI4)J1Z52cv(}Bx*pxaf@VjJ6i<}X+t3o z!f8(^xe`+%@G5vk7}qLnfS071Bh>kAc#6Y>RB0D{VFca_pBKhe=?FYKO$t6|agzB0 ztB74`lJf#pv5S<9y|k(_mPTo^O5t9haZs`o*qSqj%*6F-+ z+(J1^LC?$~b1P=jLb(B8tC=MmU*g7I&#dv~9QX~bEduX{w}){p68lvwyJksZhu(M$ z3)dp{622h zk2%ZZ$;g)Sml4kZ8a2~q!tKDM-0UIqp_hN0EeBqvL;~4bBGb?F{FVXXnDM1j2+xYZ z%i!)XuDPgz+xbQleXMCG$Hb$;WVB@3kvS+YzvOh=aq+#)mpBU0k8@A9e6y3PugsCO zSF{*%hRlO(W#x=*IZ_VfWnOD{qP_JMMxY_n-LXs$Eh3{4jDoPQq*P{0VkcS>W?Kc} zGvN}2sX$}rwi%c;Tebk#B^uNh_^UcfEbD^gN_p@K#+Bh^c&x`WfYy4}~%a>BT3 z&4u?ID<`~0Ga5KfmgsNM@v`MLRyfUstuWj?LwLNrtzn*pGR$vG{z8UzeY&+1p^D>& zM*TXn96ntZ?_wa?bAmNce|5SJ)RQh~yp};>ZfK^|tTuQ{1l|R24C88UFT7!{HCQKC z(nP|9RB0BxIs(s!uL$F+)CVt~D@$G{U;9vQi~`NTeRE|?5E_>X1HglGWf+*$k0#>= z^`c+M?A>JAf6~zCfH9o@LY4wzicet?!)L9JZoZBw=9JJ%F&6)Dgv_#g=QMdk)wIvI zX1y0qlf$YeJKyT0-s@?O`BLx(_255EmQ3SFv>(=Ynrwv4&HTmq0uB)F2;-XPet6U` z%z`}0eFICR)5b^6h4+VXjqHW@oW^Is)Q|;oJ-;!PXK^jdbNF$DZNqKcRqe&oa+d5z zAi3!*b5O89e=56k`lidge=#v`K1=5Ri})JHI6G5U#lpvu)fOCl#;y^*3qH1Gt1)fx z&a-4YN^JdS$tS8T*^4rL66$x1uDExwESu`X4;Fh7 zRsnm`e4gadkB;v9A1q$rmHhAbJJ=bK&SFf)pf}! z(K7N$N`^GO$^G+#RuY=g;7!eT)QzCqxMSLDdO~uoB`^XXB64_Xxc|VY?v=DX80bEm z1?l17K{*220LE)M{Dwz1B4ukmTXyR2uCryo#@dGvr(dQy+7RkF+q$y<>&elQd$B9? zlCo-c(tbJq0;C4+fRD|*8t0F|wNP>`UZ{m~+R3uxEiQa>!xU)g4pT8c(@H2fDXTl-ch%k3GI05S~B<3I-zZI{1h@{5E$I8gULWf~H@u zYZg3(=knPwtf)HIsv-Akt~k$?v;Z@Bg-qMU3|<=Gv`Fc>L!%3@MsxJjyFiewhljTX zKfLZ-*@%vqS`-`iu*-lo2x}eKCwj)7-%GCHD2~eMO=1roBG3Ofk&!psO&zf2Tv-Q9 zt3%1yt5B`0PBVNr;YpfElP2PtD~JEhIM$DrMcf5B*?SWO5oWL2UIHJAptTBqP)*QR zC*$r@8}-(5C!StP?myV5&^(a$M+R<6?p@$Mjm3%m_%fiTuMIn{0Z-q#a?iUQY|odq z0a`);G_OFqHBw%IwJVpkhL%^rm%%J(tbeM2`315Hm{eIXWbQNHlE)jdIDNMbFt!6| zne-C@ZY=N}emq?W`L$ps<}rC+?Q$DW@#oiK!6G^HJ(lo$7s>VS(Ir(UBF<&-qMZr<2pFwJb<3kX696%@>VtA#H>=UnJW#QuAVp z=VMCMelumYSQ6g{?gJWQoDUdSEK3yb0j^x6?+-G3w!eDXFDwl1Fx zt7I=>#-6zM7JALaQqTj8x|r(I6Igy=>cycQNK32*o{5k?Z!$H2XCXr4iq+(@^3Ry; zu4B%)SkgW~{WfA6cb&_C9T!VEa7_;yRCREi)#lbrcprRhw^4UHyf*RHO>Ps`W4^%A{W)avR1XVAF{RGi1Z31 z>>uUu2E|2AzI6VfGdVc`Zc@AhoH@^Fwxk}^6kZ~qe8@xlwU-QyM(KccRgR>8#Pv&2 zvF@1jea2hq>&1M=i`uFymV5NqvsAY0@1CXd3BNJPCCs8l2;YVV+}aT0eRu|zVjSOl z)_{Y!&Bm~gxiPPVFL0qEyF}jB-~JLA<~PQES+F70Q@58%!N_jc~9Et7&? zU~MT{-lvQBf%{5jqryI*vB>QO_La*15a?+z;QY_VO4gZhox%a48_!DxfJ3FytuSvn zD;B-SoplGR?B#sR3fK&MV;QgtxbO;D1+?wELLSlI65f3B{}}BW%Vb!EQ-2+_|4wFF zKCk^bqgLCm$Imi#g!3)wb%ZC)`_0g(PaF7Orpu1cSwfUt722b<+y{tId==lMB0@dk zMY>8qbGpp#W4*okw^kQ9dAclBP+dM`zLN8p>2iCYb8>qA%Fw2yD%4*xs#-6@(#dOe4Pycm!4j91D#0&{+TIr_d8Ft<^5jD_fxFfs*UlG11S6H zH67JM<`+X2Wm;bh>DkXn(g!wHVza>wH>PAB?Y@Um?Z(hiQ>|*bo3;%vQL8?mDyJS` zYR|vXs=7L2&AU<79Ux&3&{$IkfZiLW8<>t{$N;Kk>Asg%jj(av40j=Jee~7QOT;qE z2K!4>tVOtETZ;YU2INW!$|k-J>cKZ|Hp467;p0cU$<5;$Wq4GtPxEjVdL1hnK9awn zAnL&j6;B1%ZclL=Z;H?N)1z*bGru4Qdyvr1uc-!4OV$wHrB-vuaY3``88_dw!}k(d zvmBgPu;Pdi8?!p%r!z_Qg+uCNklEYaG4D|pEWFs(L%rUAlhc*%%H zY9f;EjXGGf^X8J^(kabcI+@P^ZD1I#L5#D-aeh46HL~$*Mwm{1b+YS)4b;efWkWUM z{D$8ZwKAXIH2baNb5iveMwDA+72(Ongd5wagQ?81*K-lr@eLDQ%dN7T;23Ycv5KE8 zj&Hfcx1m0Cv@$vj$~?7HyN*&TQ{~iedHq-RT1)FVkt#H#LQz6(V*I&PMW_)T7Tn|aI7e$m9SFD%JGG@l@&Z_k-1TL-vj zS}e=Iak}Dq3G?yl1fs`mxXoJgdK$UKa+}Qm4(JCS;0frH>VU0i3GZx;@D6x*XKOP! zUz9>gCrb2QWxV|X77KWiPNYU~_v1E~mU#BvCQH628-bv$rAJvW&uIGI*tb-RtEk2c0wL`u`l-&$O-j9^^qEczC<5fH(fxS~U9cH2+yP z4q|!-P{*OTULY@g*bhuDUS|!Uhh1YnxfGxO5bLRRL*|LLGCU3IqL{B1$+fUN!*f*_v7*7+4LOm`@_AS z2xCVU&1C@I2oKM3KYRmm^`=_9`(cI;Jo>JRDfxI>i4lHb=YwzN4GzQfn3f0{{bu+^ z!ee%!%vgu?0y}w!LlEjwhgi=edinkF5TjBF&OJflIy_x`lku?jTRuCP;mVoP0~?88 z%>aCWZ%iV~*B`A(*!w7LDuQVx@IHi$d)ak(+zsOgyheCN10}+<;*&e^}XwvjT2BdXn{5CM`U=A33EEPl;ukY6?EAQUWs%o>|3ZqG>ok-wI##kM$en-#p92Vy%P9(G~GVJKvajPwMEv&xaOo4 z{w=h_tHv(Ei~lBX$GB#tw?qg}-pZ!I->d=DV|Zk~-8CzEo7`=q71Y{Y35(l^IJW<5 zfj1(n3dd$ad0PaolU||4jd|x+@$$aiH8W-xDeKcLu~{v2RXIM|<%-Y8*#|cseJR6Z z|GSjOx@OIo_he{l9<*va<;E7=&2i?-f_i|C*703>0G`?^!zhc%Z{;HOF0LFG#L+Hl zo(fg1C0Ft{n*LMNB0I&gb$A-&<5=u##Oa3{hg>?96FIyI_Q2~kvTjP*|IWtQQ<4}@ zldeTri^HA}Yi+a@#nUYa=5*Dpxzz+OAXuAKa5K+O^ri>~wwT;}fFyvY86hncBLDPq z-hOxohUhwUs{2X9Gp^U?!uKL%ESG$E_F+x}{j(R1V=G?E#ZP$8Q+(3OH7luy@Ftjj zO^m#eK!p}QZ7wO}+^r<_w4@zDS?4}OE$i!+Du4-XmN9z_3Shsm<C>FK?ENI!Jt`t)KpsSHSm$aW$(Bz6Y*u?Opob3^~#@sh}%NSe0}l z+#Z4Vz+1w&Dja|}J}1LR(xI|2wi(9fJLRP-QYQU$7q{>^CVB!j0WD#@&Qy09+#kkO zX$^e+^K$b9*DTxmZG5GR-~NA?cX0;@vu~GSWf|LLx`W^1?NY#ROzU=f(rV|l3;fU1 z-L{V}q84~x1l|eX8^+a;9{4Vl>T$pG?b}%Dg$ZdcGT?0yxCh=G##Lz{+`nCRySd+4 zg*#z~tV&^uNZt`zLfRfxM*_SRxBb+^a>4SHNz#+zO19PSkp0A3)I(@^OUU{Mi_Zu= zAKo6u)gm9fWrvZ?>F43z944c=^usqq;4Sd_Fs?c~;nh22x08D5MYl1SxwkWz?T|E= z1&wXDGGN~hDF@mJG`9ANEm2VgMu5Oq8NJe+bQx2CaHfx8mTcFN-oV}bTvowsz8!)qVo1j|;%t0D9{D*-q0U{Q4aI1wgm>&>xp*jL^8FJT za*|&h8f83+vLF4uxF)*zyw6KAe9_<9xsd}4Py0Wrxt&HMaQ z>@Tqt**QL~40!TR^M<__cj-Zpc@64?AZZiTvKK zq0xQBwLkx*oH~_mT>md?BB?`g&%eg!vJu`9fw#e1!?;@21#d#BF_8@5X$%w6tR}z4 zdOQNpg4cv`Rhkd4_?MiSNftBSl5&1yG6Pl?+X&>do!d3AC?KC0LjRV;X$X1#O&if0 zs=i%xmVawco)r@S>Z`|3ZU!d*XMCR9;UoVJy&aB z*SNXxUH_I7reme|T|Tnqnzd%ZyH>X#T>mt_AGw9_JOy-@;3=9Gcqu%5?bZpef`_l& zdf*$v56t7q^y)4cbr zF?0=|2%X`Yyr``^w0zX|9yByZ-~(`f7*|`8-{6X?+iEKwJhfp$s+Q4_?!^;TY^PQ9v9uxIFCm`rRK^8>B;BoW574+s z&U%v;YAFo1JT1_C_&$VI7jjp>%=Cm@^cbaX2^nK-GoHQQ$(C%?YfK#rrVapmA{0aN z9u>w0eR{`(r~f;de~cB=*k`T-2FL>N)P(QHUvPC2u3YU1!LQQ#qw4*>#H7|KDls~%M~|(vuIF; zRkRY(pWbR#_%=Gvkg;Mwr-3&-XNT=S7{@j}hV#!uyq*|a!s zm;%kb{T=T93`t@xW^Ka?y#~L)2W&?;d_bvy2jH1R96K-9!F%9iOHnBBUi~zvg3k@+$hr!Oi-Kf`40L z+#HLq!h5&?4yM$iH*yJYlDkiEW!Z5xn$fy&Hpp8!S*%NJ# zmSL!^h_4u)L}*9sAz9SHcfCGf+=&fMQjM;IZ;O?6Dq9kF$h?&p02c8aEilO&cgUR7 z&Unw9)G|*dnZh{9IhoOBA)(>@uGjk*Q3<9mEgy-nU6xA;+m7}rAj-AXus({QF=HzGj4#;z40=9 z3U=(JHqDRWeazl#ycEm_4gigXfggAnv`} zQWyL?%J|y-RL>{Ob!gF;V~6TOcoyBlu&)Zw0-pFi)io=t`iRgZJ;YNb%8d!)(Lj{6 z{Fst`azC^v@zA&l%>F4=0Uv9)mUM>6&2J=l@pL6hK|WK=9)!bZ$2!9M;A5*u-Hq^p z#6!j`7~hE}Bk7QirF=Pz9)sKbazHODlB7f9?h)j|^Wfp7;f3cWNx^9}|7^mIIqT5d z=A55c8!}zz#|c zcxr!y+yn^kgJ+V27NG7+7!wuzAiP@F_Yb`(hZpGO&yh3{9i#7lQ)Zu`V8S8uGjKP) zDN6x!`yGeI%})M4W}z^yIckA-v3xSNgaUYWg$ZeC_rte^agA*MFa6&kiD#18DCZ$b zpT|gCbS7=2+9^wvR=5svs+pT+O-egmvIUx!aMbw5(u=OBqhvqfwuGa^d6r%?O_cfk zre#bD&5)*DwVyFzlB^pfSx z`Hjgxm+r|!)f1W#Dj{;CowC{Zy3AcjYP(JzpIXINw9%90`h}!cdTMC6=A(u1qEqGR zg|0a#6y_fa-uC?I)n@~QuL$E>ZpjB3Eb{q$8GDaKr-ka(@It~DoJLb%yE?8)g-?@J z2-~*tTjJupEiCUBherLHgVT4(JLj@~@t-NfD&+9WaEWV*EGVFfxz9c{+MzxBo!8{e zZ=92)qQI4WMei>Ug`7apN^ba?YnpSc0RzAODQ|`+!^5YLc6b(i?9PlDAAm1BN4g7i zw7Q$AL|1Q?yDN-V9W!*c<{6{em42cd-MI$waAr`v|-Vq(GeX3?|D_eUF4dXUUvTYipc$z zYvS|Gk?d$6o}w@z&3r%UEr7RadPly>MuO|aw6?|LwRNJPd9my+q-45$Od@}vr#sGb zC8YKGLZ!8F5>j z!YkqHQ!w+fPDwxCb((G4^|IuA5~#a@51_eDvQ_*}cAif{&A*rZ`rFS(_AcO-R-igm zp_X&kckHyojZ*A=MV4N`b!|PTGl{_QNCxTGSZW8prw?&D6PT1-bI5!W@q$-4z>oB< zKg#?flG(gQt|-Ec%C&Nj{M6R2 zPE>u%A@lQ=sV~cw7tz($*U7qzuxrJi?U4P6uHmRfg$B3IqcKxG(d$G$Fi4X_Qi~dd3T0(dQGKl zgwB1ZlwXWlMR&43;l$$v4-k)GhW(uvWmyGV5qcVWN)I80R!Go5E&c&`@trb!v1<+= z%sS&jJwWjT`+aCM58U9{MKZsl`l8l{4i(zvvItk+pcxo>L7w@Q>%{az#*|C~H6dN? zsJ$Zy`gGjU=OMFx#Q3`<=Mu7C=C{_{l`qKBOK6Ju_whwBDkJ~C@wx6KqVGQ0tr1HI zZ$h*Eqjoub3B}X}2w$aoM(G;&$^2q%vxJYGP}Qs|Gkg`{F~m2Qd7Z$$qykLpB~q=X zvW!%UF)#Oi$+;Bimiv+J;B<9Wl#N4w7hdX`I$f*05pT2nQ~;U50%(J`h-@dWZQcg? zM1R}=B8f{#B(U+&s8@%;b9Tt7OK1Xpjr30~(vx<`$|bJJ>1_{&c6+tGF`ASfG{?lL zop_oe2=&0%BV;_CY`3Y9Bre5%&qJ(V_1R+|aNa|q>a}U~6Ehpm3>Rh3*)FS>QpSBv zp@M2h8w&O|$#%4+ZGJd3+-PHjZ+KXSm+E-(h~$)zdf*Xj^;{KWi%NJ@CsRHV^5~(_ z%{q2Z_=jvQp?42$mbVG8Wp2@lbk>Zlt)WdqwYQ-lA6}$p-o8!Fx{Qb=9J{-W_t?z4{lxPH@EO`A+$yr93jl3ckE#nkm*{<=*{K)xs$wuVT4n_zM z5Wa7hbQ7MGy!+5-p|;HrpOvIi$~L=8PAH{pTlUBmr6|aKYkUHY@wO=LpFKjjt?xgw zo8P%v?}o~0@!9!wZT3f@TyvWNPyNWc=2)&r4DK3V>`dm z72&lJ?;F!Hhd(*Bzmepf)dXWHg4#cD|c0Lt#w(aN_zjz5>zXC zN1H6YLi_W74w-Kje4tIbOk3@8{TC+ypDIgqN@H~dHV`Vb?T zf?T%3HBkz$bh%^J_gKr6+ABGrm_Wke);A{Fq8wUgOLgBIPsvBJ`%3y6MPOd|x|3{C zHN-45^PP90H8$tMTM=5coR~g5^Y-x}GOCW>oB3Vi*gw9|+mTZ~)(kE506aB2|2n`MQ`YY%EfzV#EvMHa(R_UNZ&_OB_(&QGm^?0d>A$jV>SI9Bw^s$XMo zS+6{zznP!OZvD;uOuo_I1)uS$G1o~k*?m?aR{n;?L{}f{c2cr;w#u@7oC0e6jVn1R z@4sdN*&l{}m2#Bv07=)+=rI4aig5r>ktL-AO0XD{kF-VAA!HPz2T$^TnST|@^LvH< z7JVh__>C$3idxd=i~|U@^h@_uRD5qg-w-2kq~8kkO|V4`^~;hK1bV)Zbt_ya&8Ye^ zw7|8XRIUbY*9P~yzw0I2UJa|s#mPGO|SgSN>(^N@BvAn+~ou-vi2l`5B&yV7m> zy!5o(H7BY1JIkiF7Q-glQ;t!E-%EEnMpb@q8I|R-TczN{necB<1|Z z)DP2P{>&YoHUjq!vlhe#a*|nO<)jdvaQKkna!oihmg22|5W^o?+Tyyo*okM3t1nJvwmS zwM7n8(00p4X>VFdf7~MJoM=kl6Ez$%acI{lbd!A4u-Rd&@U%w|YJj&OWK8O9hLCK( zn%rea51W&^{U}>hZgi-6qgNrE0k2m(uK%mdzJ^J?$`&f9c9fw&U($IEBYam_xGHKU zyxk^SuAy~y#Yi`DF}!U?8~7++U&UMVa6-Nx4Z^``q!pn4iSOvTS> zIgdG~P4G@)C6qioI?qn5Upyx75G(DV!>Tj-T5v&|oW}U%5a$i-on(gDW3*(#Gtj#9 zMMkae+7zxFZNTE)?d20*eZJ?k;~w2A^)F-a1CNA!kC!)71% zWib0rk|jV}>14TCe@mvy78RX1r_Y`J}V(+ur^M&Jy&UFf8x)pgMq-d2^*(wd9>BwrYMGPLv#elX6e8 zif`m$SySSg^wYWZnyIWMPZ~BJ4vlZd(}ibiEB6*~@4|iHmwMB!noeAEvJ9gut#@9i zWm>_WOjZD=$ov~gtL79Mo^GJp9+s6iQp|yTxrYGTiqmAf{*IicMozhZ6-ozAm&8>R zRPh-yUw?gtQohP{(y4*Pp$$VjS=%&b82H!@XLKxhQPJ?|khYJ1JS6Y0qP3@9IBYJn z8Xq!O2brr$uKhwjg+e9)ZBYHLv8^U1mzwxg>hx`rFTdthl*zTt86Yd@N{`Q#g9ZS9vx z+D)uu8;V0mDb1fRi%|-`0=Etn#WVrs74U=bOq2g~vat?61aC8W=1SzXVjAK8ONWhl zF18a-ubgp{%Qd-2Z(>U2qHHK@uggGIrthc)U=t@p=mxN|aHTNT(Q6k@<&DM3fq^;rd zA!AvD0-Ht8hi4N*HA5`NR1tHRH_B3(q-~A+HJ+lrJLWR z>MMrLuW#<$$U!03%vohuhDP)d(SHYnJ-jGBDk|aLjS!h5u33&Qcul!E;3k~DDN6DW zIWiM-?__m#1I9r zk?{N`?#a2Pr8EM&fHex=+(i0UADc2Ur4ziq+8pl^1{I%nZpzdn2f)Rv$c8GOC^>6g z(-VDnF>cfhvzaDyj!Bu4ScAX#CYAxwa`}K`x|AN5Vn3nrN{!B_xG;DcMJO?q)eb;sN>MkYj3M3ErrCj7(3NLqXx)hqn~t6I_jQ;1<`U zlp0{_z2-ogFtL#`{nu$J6DKr-*MsM2HfA@>ZVw$5cw z86l{4lQsh6ulz|();+YC`>Z6dveXm;+kg(n(}b0%>B^xY)Ij|ktQ7CEM4N%lf3Z@0 z)J!q+2>ZQ^nIz_w$rq-~kbU>L><(oI9~d^CWJ;Lu05_UO9FrWt{0FrxNh$sTGI!a+ zl!>u*;8gkePperZ42vy%hcThF2jOtQAoQU2CF3# z0^r7XhDVFF@RFGA*U?KxfL(hTPPDe~RoT;MNJsd1g-L%8%X%{tUcC7q(BIUocU8*B zLjXP`tvbgJSHZ^`SgV%(O3=p4DOj`d>AgkkC ziVwQ2kM^XpkE-lV^)5qp#ec0a{vBj9PM}w{AZ!29T#O_fe#Dp#96i9jz#3IB`%z2O zzKMeRipHjN@uMm_-2vMRGbC?$l%y`Z)s=drN*=T%w;Gbu91SW8G(_J=DFa4oY%kO+ zXWYp#)#OGSUo!kH&O{H+6$8d>a=9mEiZd7g-a@O}-A*!5GUW$H+W&9w`lI41&-5i3 zbQm$*VQwRdm=L8aCPc<$OmH(AQmJ7hiIYepv7;GR+|o)L+GZ;%?#!vQvdTtsLiVGT z8c5J!LV!dRR5a<9J(3hxVyI#>wY2MY>6W8&G@hcDcJ_Ji^G$cp{=Mh$kKZ}m_dd`2 ze((3=zTc1gF$^kktJjqshO+XL&yrKJdOq4IN?AR#TENGywVi#I`#+yiuRP(qGD95A z%F?CoF7qx-w|;^ZNo{=+r())xOqVABJo0CBewzB=Q*((~2wZO1$x{-C596(&=`%CO z(*X8;mz}Jfr6ECF``=3D)q~$r1^TOP+PcagI3(HYd|gRtUQm zY};)Z$QQttF0hm3GUo3EJH66-4PwohUTJeB`Xk=;xKvbt_WNxvV^NC;d``0k9H{rt1J!b|;5dkBN=zaABn$bAxQcoS?Jz($tAg9q$Bu(Cv&Ltsy>v6C}W+MCbOZ`S)@ zn{Tj_&EjG85q#j+cjbb1Y$4XctJL=Dqg*b7AnVuL$#F3}bTrimRiFzt=o-8UTUqs+ z#I_WjD7HJXp38>E90J?=Wt(f#Qz>>DY{@OCmIU)*u+G-1yaV01(Ux6|#GP3RTz{*M zy92P2={~&^Y(%BC_*Qtvaa*_Le=>{$_ifP`)*oYkd1t{^-)1}iGs?ZT2aWhsk@qq) z{~(so2l05MzUz7zTp9IXXJ9<5u2==58o=?8og9_uUJ4`Gv}BBet*x|^ZS*t*I1QLD zp1zy%WF5k)vjd&XRX6}xsrK&2Dx8nowma?Qn1sv59`(w8-!*0!WFVsZ|0JA9WG-j` zTUP~BiOhBC<^8_p<`6jZemiMM_UC)`sIWRw+%6kmi=y^?W-jyufSbN;V}5gH!R&nC z$?pKmDEY8g#_5)gvh~4a@jVO(sr%YK-N0_Jp$E{h&ZKzJC}4k`TCRM{v*dml-R8_g zANO*~ngv<=kj>fUDtM9E<>HEGQ2B>#b^jjUGEY4~YrTXAm-yYlLyy?Wh=hQAyw@oz zyA5<(>JhFzF4c7An#n!B^epI%@7vBdX}OC|po><>F7R2b0Y3n%R$|wjUICb^j<;g3 zQHtBaAKJ-5Y1`GX4;Fa~Jl$Z68*LP+p8k>VvJAixz$VT~o@wB~<4#O{Yo&LgC-X3l z-k-p8neXgnJVD^rJ$ABxp1Sr&zQyToMVEF?$25e|a1?SQQqTR3i zZT@lY{D(n?{#p0iYP8mgm5kgjtXQ{wkPNCzTYWiMKn*aGLq7Mq<9c8P!Qzv^$=wo} zD>R#312*q~F6ErleII;;nY0aj3p~m)kW_bp$po3&lGB1Gjx9e^@ z307i0z2Z5iU!U?_p1vEm0d@8%-&JM}ZsVPH@`Ct%O50|Pf^F}@9LYs}8n7EMkfz?- z=3SCu9l>*X&Q4aVNBrKU89~4qz}@Pf3cZ(I5e6(jf`tQ>N~L_<>;_+~&bHxi1lw@i zieDnO`4(R^g!}#@YVl97lkLWR?or$Mgq>TVmCpV!4tA{DPUgrQ_!wB{btLmBD$!#* zf8ptV9jr42)qpMRvz^W1HQuFOK=ZgZdeZ66*YIlL2HkMNP9~fNq)!8ut7T6k z^<%D)XC-CH_SVeoM%7=iov-n8KLA#ShZz7H1MBR_c7Y9l#k(jAr1_#Izm_s>0Nb8o zcZyp)sO)aA{s9ajDeR8FJnZZ^_{gBm-HPu7`c6p@WMv*hM}v3lSD#Q1AMh>9r~zqV zzy;Oj5=?kuK=;eYi}zXg&GJC8jCfnXww|%Mr@8F~ICM6I)1b#TOJ3}qakhj9UA3d6>?|r5`_1$K3*? zDWa(qAPY`0el7@*!w=C!D+I~nB{hx8K7Lq903+8CT*Q=*A$vq6BUap8a4 z8KA^nyV$vK5qGTua&gInbW%_QK0E-)(;{XOt!Wex)0zeWa_NI~QUDD>xkl)AY0)@( zNj$_M(`Gerp-a-La1pz10lRULUg#IljEhvRPr$I&j0+f5zdP((m0vGi)P$d53<@WO zz(_GQqLKHb(Scx>Z%w*d)#J-m4=u57S1XrTUbQ`Bm8vy8zMNGr#xR%ztuU8LL@)x3 zF8nl!14#ie;xQzeVqAvR*iqjawW`;br~aYWSEd#o_q7h-@>cJ@$u#%CRK%K`KQLBh zjop!UpXwO0ioR5~UB-)HEOV|bNp2TuT&eY!Yuu>iVl5}PtL#_tAK=H-hF7hn_-gfg zUbTw6v6J+gs%fR_fOc8zX?BJ)Kfytx_9opbX-54NtJpERwck8o8XZyMS`|jC2QjXD6}IM|<;m^3~(y&12+8!^D<{GT+kqzD|88 zjW`i@aMYOoDIK-{o^s}98dSbS?7oW`CweJko2U=3rYvxtmtjmjOB{QKa!ThP{1S0Z z4`sy>`mMcDB!=wl6;y=op!Dye!Sr7fn|HI|{x!srk0ewPy>}9~uBUzL-Nf>po^|*{mJ?2W9LY%IbNtpkW*>pnZw%naqF3 zoP$*TUD`D{Ybw^Io%C1r9{E}?^VRNfIprJSmq;`nq8yrLU=`OgL;UNMA>9*08;D(h zrmTOKviW-E4~|lX_mHo11{;>lyU3U5o-z;2m-eG2rBoQYB`xQO3v>$;?ar?cjZ_Q$ zIwm3`Y+2vmv7p&En6G@AxK#(GDQBKY#dlJME~Q=Mt|$pt9tqc4;`aTNWe3UU=!!MU z`zTWQB>BQl$|-Hvyq0+MFzxDoOj)91A(BOXv+l`wbc6=x2`c)I5sw9l%|c4oHp;>; zQg%&J)_j4o@grT}4&5WaBTi&eA74l5)E<|~)6_@DHd7J2man}Cb&yS6M%?g^G|a!1 za^zD=|4QnI+lVJ`rfkv`%>6m_r@lr$SV`PR<-eg}eHv%H;3+z6oMjKx>Zv$YKwJ+$<6}MYqsF z*L{>>y?j>aVH5re4Xbs{$NxyX*jCE?pHW}`A@S4(;*g&*yo$0__f+1uXjdB`AI-d& zH~D(FRfLG^^fM3WV07!@GkFvB^|~dadIk(!Nj@RlD5QcLwA3+@nkPcfkso7lM~w+R zHTHj>iYeXFMqQyvy=5ByH46xJ@Y$DqmG*%MSH1Dy68rTqF4;(&gH=vaR|lnk2l-;> z(IEcXW=Ra`C@$@#VV)ipGY?R2=%`M$Bvbc*ag6px4eeSqj-`_?`wsa$d8a~3+`}ol zDK-A{{4^-}Hl_b{8je&G7w9e@)}tVhuM2eCp#g`9LtT_Hz3P<|5y!trKdFkJa$bnB zImH&w8GkiN8Z`YaWw?WKSjRwn74fv*cvOaob@@iac@|WCH~Ad>NGJY=_>>OfN?ox* zJu&6}P_O@W|3*Vo*Q~ve4o8~F7nBnRuc93Pd-Az@Ml0AzzTkcGu@%H6Cy6s#DI=4V zwL2;64KK%O@d0MIke)k53M7eH*8XV<8DPymo3?qxK4&IxkE~k2(uFqf8$%mZ^+)thL_MnPW=MsIBkF ziKRZ8Oi6r{KhTF{jW@1wO17x8F!R>_o@Oaosl4x6McE@imLq+fkZD=}ihBAXYq6?% z*RnjR*XFYA>hX8sI`#Tpxg7`7NR8?&e0WmtCpfzG{L)(EN$B^L#CEkwaO!{+e>3*D z;JSWp|LgkI8Q{Mh?#52i?WFRahuhTAR%AqNIuEm%)66z=nr35a?|EzOyqVML%z5jk Nc{|Q1Pu%*e{|3@q;Hm%s delta 405187 zcmZ_X51boSxi|3HvMuShKng9JLXmVSYrsNNC=g32DHI4$A(VolR7qihfGY$j5}+~x zszxn3IMt0=PyfN~A5bgpA5f|G5A4M~g9k6V-0zm^{I+lI8JxR<8Gmp7 z3bnb}e!AzXo(=X9la8F>$cNR=JVU!>+-QGjQvc+0CK;;d>n44m=T7^}la88usoIvu zI#u!}^>ej?)0GdXpL^_ACw;AFnSJYi3yvGs${wQr|0z}OEcNrS`uT*~zF*a?s-J!8 z=S=(M{Z5>5ozgeemZeHKk4x-Xy&pc{ETyy6)+QA(?b~~gJSM5+Z1odTKX)oULjA6( z5~r%)&LhFUSJ=<=_8)h$+Uiq37pk8Ps`M@DcT$!5uKM|j`ng7J*OfbuYwgLCkLp=x zA2a#zp7ZUqCLcB9V=DRrM}MGxueWcXeEAVsrL)z~T=lbF)tkm8?oivS?6)Q#b;P;q z|5hr!QvJN5en!>L)yi&Bzt`9cr}WP{Pi@UpTi2`Kw)(wAwKHUYWJ-U}DfX>XPU-ou z{pghb*|)0bg(~uK_4`Mvl=FzH|6geTdddfS;`Y@25AV6aK6?M7W?!WAZB^nvRbrC* zy;J=hp?+?#*Y4ln^AY>@{ZBdiW>qGoew@csD)v44U*jNUtJTjH>gPoJ7yBRCbCdnf z{zsm4H<#^KzdxtSpTXM)s^8CY-KokW>`Rp`wa@h(e)Mfh9^?|vuP>{g6{_UT>gS_e zI&FW}cjn{|sjUy%FZ&Lk9b;dqeqXG9dQ{oN)z4k_l?edcU3j-`Sg4s?{r;|51-mKDn^(S3cW+ zNU>*${q!Lh&NxjKyi^4aQ-zLG|9_P|d*d^i$jz15eJ9$l&0IQA<;~zP_H(OmqhH3S zr>ZHZn%y|pUOa2CCt$CgwP10b3tQJwn=+IBsCR zZ#t~M&(}{oyz@8qv4<`-=crAmZty9p8{)braIw&})K`-I4EFR)@&F&#h3wh)k;mAt z;P(BuQ2SwSCqw1;Gqz5%-#B#XKu&GXb^zB+Gi`?396|KPyy)uz)$fV+@GovO~4a|)VI+XI26eMhKG=ZcQ4 zvab&e_8rfg< z>e@-P&f|aC6CwMA!v<&jR9be@H+Di1wAyMOjCRn!>_sdD#xxXYP5v)`7w zXYwBM)t~RwH76fNXUw>aq9u+7*!SE+J?43@=Cj9QRDKEj5^3k7nv9Al7u=O?MJAoq0&d-K4_Zuur1mhmb3?%Dl|FH%uwnANYNz9JmGifdJx)S6_g z+t_ytv zd*&{f7UgKt*K40T_vpSjZ`Vuq^>YW!wY<6KbUF@aLE=0z?D<#7E9{?RFXyQ!#) zK6*X5kIO&F9^>h@iker?z%(FlJ8Xs>90(75+|5J*qc%m&AMH`)`kPbs%>$R3b>1BQ z4t2AFXZ2g`z6)u0hq#H}BWQ&AVT8R;xpU51zozn|Tz&!jh5-2n_Nd#=wEc|ackJ_y z8thxi<%a%j-=Q{dP@B%+ie76!a@3^@f6US8H_=}D`DFZ(JyECDcd$QT_Z;58_)U%$ z|4y}JJ@Bq_XOpt*!RpETznF5ZW`*o0xQ_J_EV>IKBU#`JFc~VJMRYb zM&3*wOU0bkw)41Gd>J(>qw4|oeGih$Kq#?q*-Gsc+*S))yff)9+ zvu4|;ZNvrpyC>18S= z7iEL{6m&61=buAe%L3tWH+z*r$$_h+xs$1cq}JQnlWXh~ju~9}1>VdppkllEBs|RC z`zE_Vk0;ryN0P7S^3SsG-e*5@%;4f*^5*onXz$~EkiTPJ!6P+k(4)m3Ios|#c4^Na z+`~v78#ecwOJ{4zC^fX3E3BO$nat$!^AogxGVABD=Og5D)=y#I#V0b#?Jp-k*4X=T z>R7Vff2h@|vnJoR_#n6F7+1K(+2y{~++5?2_UaD|n(KIT`9;*Lw0u1oX4b>( z`PZquT#cvM@p*ETy>vU zw@T#OxR<}!bC2wwc4g-h+xH%K^uTpoI>t-UAugR^ubgH-f81bC%3c`gpZ!I~9Nf9Q z>g3_sTR6JoQaX%9yhD5JweRmg_lF!UjZrj3zl@)*jFxC+85)^oln@0 zEEqIb^Je11v;#8ehn3GT)T;M8G**+`=3QKV`2dv<^Wod<4SPSgqzua&A?SE%qasjy{yMyM@IcmaHJc2#*3#Wav^K#OB z4$Qfk8j@KXWzS#fR4@#gwJX_s$H;lnW?ZM-N#QYGO3G8&r?~uztEqg>Y0UZGbDZ^T z&#}(Lnmr6Kb}Dx+SmWFFVJ9r@dxeWtzi(f8 z!qUZmaHBJf6u*Axqe{j*%IB(Dg|E_O4zSNSn$F&ad+paw80}&GoqL0|y)#m^4X7MchjYWe;`3LD#?_5ErMV^o6v5!ujY@c}2X?>@t zZD(9nueI+u>C%A>91ik&&>c>y|4rU{DP zpTpbiWry_-Ea&JbXV={vUBf>AGW)z!2hCe}vo}qLDM|kG?B#2y@ibR2u$O*FzKOjg znUvkPWN_i{xT)|Y>S8aSrFYoJE~j0U z7YcvqjKCh#zG-Q|zJE!7&-dN!z0Nu9JMdT@%`e)&T{74g;?4U1*$1Dtbl}#`s)%=& zenq(0@)h>Yr>PYJZ*E;|Z$E9Y?{eNOFR|Y^?S>gQs?E7-HWqj`2JPz(3r^)S>ofM3 zmM-o432*LNYQMI0u=|X4%UHr6ca@LP>U(d1Qa{Z6& zTc5N~ShjTFUA5^v+eeGt%d-RK(}Zl6?Jq4G>^sLBj`n{q`~J%JtEiK&{rAzn$?EiU z<<5v~L$bSx%kPFOb&uQ2!A3J_KYzyH;`_N+@C`a|yZKlibc;mvKG<%0v0kE3H*$1kxZxYNVgd$-zGE`MoZgf}-{ z)ji=aWZ!fc?ehk%ex$n?+vHqI+d3;eEy?BDQ+n+e&N_NpnzsXelkIoUI&I*yyj^&j z+L1-dX7=^x*sIT8+VieEJ?HT1W7R$O_Ok~EwsM&@@6f*O6{xDzr>p< z9+r}uekawRqOK)3{aySM_9N#E_RTn+PE_kD`?Yfh7rvi2#}1-e^6K>|>|55;&dBSg zpSSNG=r=Fm==$GMEq)crNGW%o0E}UJ)ltoK_i-PWZ}RKzL+sy>b{11FWuD{P**D+W zeVKknzMrx2W&8Qq;L1H*Zr&|aZYI}XBGZZ2buzJg7tp~6r_)o=7T%Bdv0KO6tIz#( z&u07oox7mtK6e5i&!INF5wn7Q>l5~Q=MDBRT={)4A zb5xc-&*aJ2Dz+BbvK;#b*saxRiuk1BUgZwTH-d6vsBT4irval`D_d2`{LrUo|1n7CVP-$=L&V)r^)Ulyh|iwBkfIrj_Fs}?-hOCV|Ll1j9j#N8 z@9&MUb4B`2=IC&rea{6;`&RJgzLV|eFBmkhi|QOKE>bd4F>3`Qymj z?Ek^nH=ON0!+9>B*-c*N^4}sq!`Q&DA+6!SQ_}HYs6v=O5Tp4|gBlKiGG?VILMBTsZv%I={QF>)!hyd%cgQ=yL9KoipMGPUPsO z@6aygIl6*9?tk);_=cHw(ybK=wf8-U{)e9hU#7WKoLGK?4mEERAbaq#>@bnTPi4c?&?_?nMWJ8AH3?3uN*-2S~wkh+2@WT8Uq8uA=E zm$$$ZLsUKwUgwSro>TwEhHI%p$qTqAzzAjNRF}cm+)w2z;G5X1;A=Kh`5O2RlLK`K z%=tQ1Xn<$go8Y_ITi~&8P&;k#BD-l^Nk=H7bozr-!3UmZ_k-8i1K{BTwG#y2#2z9y zy=&j*Ko}|{9-@XK;5*o(;By|P@^SFQ9dw|HE?3uo#qm?!i=FHWs85`+r@*W1Y4G?0 zY9|A}n>`D@IjqV%<1Yt+4GXCu3w-7YPoGf$*;%F5mGFV{Z8feKU@ zVy}X)XRm>8Vy}abu{SzS^DnxH_NdhfxR<2GN7e>U97^SltGWlT#qI|;?xb=7@Y*bs z8VW+d#|?$S{oGIlJT{BkiGpX@gpB3S&Q~=~Ms@j*=I_XD;h=FI^eje=oIP>2}kooJ19>-2tP`UIX8F zDwS`5$2U+1P4F!@Qu!8m({(le+7Q@tGga^nQG;@ZYBp{A!RyPXxknrT51d6F1fLTl z4>|6Pf9YU72f|Qcj6Dh-_%iKK41Dxf>L3mt{{(qLb9eq(w^1Oe1)M`#lOa!m?^{ov z0S`PzJCp_Am7ngOp&WSaYtw1|TM&r<2UW;}Z~ZoT0eq-VUIgFwHS!X;kJ~Q~nY71p z3Fd623KghO_%3-BJXR&IgUgv{fLD2kn&KuexA$_OB?0!*L)1YVJjO?0T-|*DJ4;mF z2R@Sz%nxoRo}&su2>70$hC|@n79ZeV%P@HMRPqS;{IkfT;A7;b5raVQ*;FA8Zk$P; z1TXWBrofZuQTa6Z{PW2(uB-7U*S>KP1+q}VT1lP*FSA?VnK+d%fXAMsGg{Q$8UK+> zsX|E)D9^B$!PBd$d0#Ck39jC$Pn=ery1A#bu7JT%lR6Ym3naf+?JGguSyumwa79kL?Q3oY( zi@glq`Wcn4fX{h_yawLpj_c%|_5VC>r~wty>`id#xCJg9`}kApGQETOgWPNC?{anh zEq;kD+!Zj4<;T)%bTRM}Z^yy6ETHlU@FIH>e5>Qm_)9?`6Q+jJ;2YVq;0->qJa~b< z0G{FPvij|ge>p`_u26vr7H`+U4Sv6*4lZY+0X}mf9ayvDH2(q|XmtYawOYmA22Zj3 zcn9PF{QNNvKe!w~2t4^!lLkc?0x~Az;F{I25*JgWvj=OAzL5ANb}A=>YuQZW_C| z<3M-7*u)h=;K>K*l10G7>{0L_Z^y@VHU1J1kUdR;r{Z)38SoNsXTe9EKiE@`9QbDE zPukSOa@-mJa_TA^$U}wFjZ~okzBx@^M*ljUp$d4Fw`-ca^RLJi8d|{FL#faNZ#aJ_ zryecvz&i54_1)`$FmDIJSIwG2^FIOs<0(3VD0qyw}@ zxgOU42@Y6LA;Jyi!FR5qh6>!+o_1l`d{{_Dgj>qXRe?QYT&!r8{lc~pb4H` zOYOA4&E;27pbdfb>^^Q#2C2o{esDPx0r0@p)P4}WO>P=t2(*5~*B;#eI(Y&-%$@|7 zYo7s6a`~+5YW&HOdDj>!WVu2CT*{Zg8@ycxZ+@K4L`8RJ{7b=_9#FoUJ8ps(*jwOL z-uCgE(Q;t^kJBvhgXiy^LeKvJ2n^-;nt|`Ri98Hm;_V3dk~^t<6nw{e^4Kt}|Mzkr z0TpVzodjQXH#L+3ud%1WSM<{x7#Ytg{}`M5D3J34ZhkPNV+(u}caR4U-9tN60G9(R zgB#}WXjE4qAfvYq-uNw*Z-SR@p=;bm=j{NG0T~lv?$-=LKspYCM|nE}o>qg%dBnhz z+(8^%Qh18Iv;Gg>z_}VK%>Nv9kOB97o;(X4WzT`9@1ycom#gc)g9C-GfciUf-k~CR z!ls5w;L%OwW$^hUhZ^Afc)B*hjn7iYey%6i-ruA#6jJVv ze+h&+5QYlUaSS}p<>TN|J_(-X?NrBU{_WaAdz$V9+(9J;bKq(2*aDXfSOBl^b`gBt zH%;oe1OX{n1#fZ3HE`*;0dDYLkv73M7OCHs2>~hSNw2qt^cK93@W6#<2blsw}mvTjLBTadw z1YUT;*`YJl(=P<1U==+023>+0c))(^hy7-pqb-bb_dfnD7c|Y~{on!K4uV@;J`8@) zh`U#&5rIJPP1@Zk_y^cy;1Tu&c$2r2;OnY%K~t`)c`QfP{vQgYp~7;mkO5!Co&_Ib zx4=uho!8yTBg3y!#|1s0yv|+(Pyd90ur!)w@;x*dQ5O|(Fd=sprQoo`K5vULtBaeZnc}L^m-n9qM@^;E|I({SfSLz_` z1>8JtNWmOBN4`OqrU<^-CFI2T%Wt z4%lo!V2lGz@Nf^UG+W@klgQiPb@l-7fQ&7R4u_pS{Gs!(B!y#~I4y#XHP9cqHNd52mZr}>wg zMSIll1l%Lt!fxz} zaqvX}>NjCRAjW|txW%3V-#nWd%77PmI}0vjBFFBnqxSN($wLJ>vLbl=ElyD2Y4!@Z z>`<-SO{2|F?+zF;SQ_B_WDtSNtTFhMdt-%nC;(n^U5&pW1Z0Q8;7Q(&fXgY3f*X8q z9tW2*nsVG3|FWkw-qSQxkW-fhFY$H`T+W;Y-pe~w(A=GWa_Y)jz?pw7xt8E^hU(z{ zw`oi?z>~b)29Lgd5Y2ys6Na1#IkEtFnmY)BO9v5fi_1sBrTzG=@H%Re3nrk#@En?E zDew|^kOr4m3$oxAZ|B72b<`4fke2|zj%xgkPH6#LI;emb+El&@E+5>ggPZM7(9>%J z0=bLnb5c$4@G9~a`1%i%x50Pt2Sp9;M=mjcP}DSh5Rgxb`oZOsq5*LEq-YRaJ}DXk zmk)}DU035z_DDV{8i5M(Nzo{{d{Q(9E}s;QgUbg+6S_O&Up^_C)C0=plcFhb`J`wX ze3UOu20VBvU79R-PC3ng2()=S4<6zU3gD~Qi{Jt7xCEYMFMk5o|9d!4g$iN*ptixk z<&s7IL8ILdE+2mmf=fFQ&pH3ZxuKXBaPpt}j2&<1!F~Ms>Kb_DUD}~KxRh^#$4#!# zf`D{va7S{)87}V!FR+Kf>;I%3ih(zI+l)hC*Dq+WB*4S3kSD?A6XGdwnfGb%b#-bd zL*7~c%e>D*1)29baGCcOxXk-JxXk-Pm#gb9^S;;>P~SbupAavBmwrh{PzF!DN?rkv z{EEB^?oNAW{M8^J^S%!5&K{r7I?PD`O_ISh`~d=?Y|w?|9Sq{azF)~hd1c{ zP8|fnm;5hz2wcWQ7+l6gq~kRICrgXefV3GU~wpGbjA`3!i(Ew9F3 z76MYi0#9-W1@Ihu30$UG1zbLhUvu0U|8m6gY5xXPXz_L%JkK5b_(S>9PMJLbUS|($ z?#{pTWJ(lKE#S<*(0a-PG4M@sngwz2B^UAZ1K)cwc@kXZ1DgLS2uMCigG)ZhfJ;8e zg3EJ64qToitUF=-FHaJAs36Y~1#o$eD1u8qD1l2pD2vPbUlKw^0=)i@ucA{|1>eYC z1DAYI2j9V$rU7mS`PwugkYjIy%a|~DY{;Nn#2xs+lk9%*0JU!#0SIKd;~@AR_At0_ ze;&NxGX3JfqD=lg>l~Tvj+uaCtIofyp%|2}o>1Fx6K{ou)`$phe3_MqpKe~gXWsY1vLIQdV##mycD@BIOlkANrHW8lMl z0CDhw$$NOy$wE}ua=KzGS2KEc!kQFMhF7?{G;F8R$;L>peyuux~ba&=Jg9AQzLTqGdCi=nm{fmw` z03KFfQ{y~>;F3f`;7$^C=U^BDl0_rnl0~E7l0;+Rl0@U+l0*|GyA6)U#6dzdZEI)It{ue zc;r~}7Wl^bDQfq(ce%7pB8ZDpKpxZ55A&79spnRDtQomh&=?p^VL3@ z|6vGhyzr4{XiV$2H~Y%aM_^}_-@{zGI)@8r~+IL^wFSwU_!9&wI^@7K8ZpKyD|K9G@ z8#s_E_`v1MAOheKE*}Q>Z=iM~;OTQ{kVais{mb-A#3&Gh3TyaX)HwJCE}sCG6rKc^ z6rR%E8UOMMT3Qb%mmHn}mmHo2mlU1@mlSS+J1N|qe|ZQ<4ljU@@(~xoC54y3-3pn{teG21z>cHT^ zBx6OscEblQU%L?ij~zsVIt1P{`KB`h0r}#P1bCGjN`uEfO`|;n9=eSVAPer#kefLO z$cn`RmlaDMTt<5VTt<5lTox=P^3M8SMtd15$Y`&C%V@8H%V@8G%Yvoe34+UlB?K-DmauYn z{L8486-xvv$ciNjE(?|z_zE6eaqz?^Y0xD)PV;ZoJrqcG0`BzNmnBbuH#d-{!86=W z2Ay9J%YqNzZc;-z2!wf0EpWM4%!4oC9W8*%f~5#93zo780hz}Ya37!2D)@5tI=Hmc z05`aNligeYFX2E7D#(hZ4K527gAvouNH9TpO<>Uz0?ctrCx9^^@6L+OY^@00WbA}d#M-POTFM; z>ix_(saGAK?=!Ie_fjuZ@KP_hmwLgy)C=yVUU6Cfd#P6fy#Du6FSwU_!R1~t4lZwk zB*4wRzoOBYgn;oHc?w+a71Q8yub2Usd&Mj`-z%C%4gzwsXo0JnMQ2PJd2qQ`EP#8d z7u-v|uB-7U(@*Ac1uBGjzE;79+3VoaP6Ir|<(s-Y<9~<)Ej^&zOTFM;>ZMyK?*P2i z3obhp01v8u-T4=Uz#8765V)6m!M)TA?xkLExmS$mVEu2+;M5BhywnRG`y8)&!IOWa zv62Nhn&dgpDgPK=>h%K7P*WcR<$J$8xR-jtz0?ctrC#uu$=|73hJcrP!M)TA?xkLE zFZF`UqStIdz)QX0Ug`z+QZKlddOtfs>Lu^2|Gm@;6};37?xkLEFZF_Zskh73_4iV5 zS3vzcQ~ZWw6x>U_;7fRL#lgMQ3!Z*M4Mu1DB_Yt@hEm`woC@lZM*kCe27D8j&w|(3 zbIRTEFB!1S0ShX4t6uQno78au+)KUSUh3^Q%|DsPl}^At(l*cID)=HkLv?UzrvcvL zcADVxo4o#SLBLDB;9lzG#3N_UOTFN-Ljmw6?@-W$z&t*(5V)6m!M)TA?xkLEFZHr} z>;KfjoO+>xq}~*GbR*5{G4cGyf#@`oSgj2EZlt2EiruhQL+krTHI*fTZ3CxTM}F`1C*1po@Wz{)Ida zzVEN(iO<9OKg)q6RH(D3z_+re!GkTH1>kGgv*NP;-@t*K1bF=~sn-JE%H{Lml6ni^ zl6p(vrp)6q1gbn=E8x9+s%zlVP940$?KHsmk()*n0+M=L;F5aV;F5ZMoRDNT$qxC! z%e+GY*VXuw3VS&agbI>+L*SBn!{Cy7BjA#HW4b%zzs;#Pt_PG$>P>=2zCiOg1zz|Y z4Z1Y?ULK6#&Z5_ye_05~sy7ENsn-IR)SCyF)LQ_j)T>@!*a+)?NxdbgAgQ+uE~&Qy zE~&Q)E~&TXIprVkwcffHaPpt}nq7W#x&bb!w+Sw(w*@Y#w+$Yb&mbE2b#k)Pv7}xf zxTIb`xTM|yxTM}7xGZ|j5CkOkhQTHEM!?5-a7Dpo)f)p}^A8$~aq`akKk;`8B%s0^ zu8;)Jx2b#zd^49%gNM2OOqZ+cznlZvu0ZE=K{@b^?@-4UxTM}ZxTM}9xI2xV@mGRC zo=<5Re3ZQkF8QDaZgKfK_%8N_a(Dbo29(s>gbI>+Ti}v<4NgeXj_i;RJjWgTJ5KX& zCkFzZfHMgUNxeaENxdO(NxflkNxf0<`XMH*dSejqQZIP^eonpMyZY$c?bF~(rt!Dl zgRkM&6|yD-%1Qca^&GgDdck)MQTaT$yr*0M_fjvrxBmB1FI4bSFSwU_!M)TA?xo&t zSFitFM@LZa4s=p4xR-jtz0?ctrCxA)PuUrNU+hl3t7gzO^MThsLObdQUvUL_0DKW& z${=|Daw;Ek-05GYO_~Qw7%IdMq#cTYCqG6F#lU5d#=#eH`w7k6`Iq8AQVTfKZw~(> z5-D(b_d5+fG)y~`1(zMlfzO{djpn}vfh6xx9(*~U>H_$DKGj9=JbMYe%9pb8MOgor zcz#!*!lr$c^K0Ohf0Eb1<@Lk{xU8(2;C~*8hkf<23%HFW)=dnw90|Y(#istrBwkuGm}s2A5Qw={U_l$<^6Tz@2`Q zt8?Izsx5Fy)p>A9)dleCcK!~6A_OE?m%t@em%-1zA={!6jA4 zz$I13!6j8E#AW?2xjHEUUjIw3PJwUZBTj=$s?LB*s?LI&lB;tNkX&tn%SW;E;BDTa zB6yv*OWRTfaA}S$H8U6k^q+lOA=gWK?>ZN1vLL5 zAS;#(xXgkqxXgkaxXc0zTxLQ3%dq~JSx|rqG7E~}vS2BJ%Pc5^%PgpP?jC>V>)xtf zz{!8=1A@P#Z&|8=%Yvm2E(?|hxGY$j;8j`ww;&)ZmNvNDTpC~L9;C8h@qx>N#Sh-# zv2{!U0wl=@6u7KU(%`Z_$%4zQ&AG0ni_LrnEvQguFMvx!Met2rz64%lFYE3MS6QD_^nh|% zpH#tReNqRP9cqAYdx;j@OSIsUXw4D?yi5!3Wm<4qZdAd&L<{aETJp}z1zx6w3SOoK zms`UYxR+?by+oVW6Ro=bUZ(8|bY8{tgNI+FK^Fj*KZXf{%iqF;z}>%vamHU50&VUf z0=|nq3NBxq5Cb2+onDoTgUjE-B$T`3U*@rwdZB{+F-!{FOTFM;>IIi+oa;Evzdbx( ztxmw5ejz^M0=P6(1mDf=l)!`BP8mG$G{0O>fq<8K!M)TAE<4l!ALAWrf(LkqS|$X% z)C=yVUe1Ja$-LAH?xkMv(EB*`vU@KV$e;6sp@Q#gG+iR#J6_^-0C@bToRYyM^~Ss1 z^gb4t=ni*YsYXN8eN$PEYOX_WcOX_WbOX_WdtISLD z-*`aJ$(_{e1K-Gl%MUJV+yJ<|Di;Ko7v(|^z{>@jYczVpP$A780k5z}!Gr8EaCuQK zE-o(@Na{^UfL|_%aYIRPNxdm>Nxd0xnZ{XgGsdSh2Z0Ujd2nf{03PM?Mez0PC2(H! zs+S8OAgQ+kE~&Q$E<02Qk8sBg@OA7>*VXuw=_jeT1r;Rqw!tO!8k`}e9Z9`@@FJ() zfbP!tmsM{_4>ohCE;9Fm&K^g&%{)|&HxTM|~xbyOYJOAPkkX3I2TvBfmTvBfe zTvBfuoKmm)x9z_M>wihTS*ReXHwP}M*8-Q+n+KQFTkxFokEGtB7jVvh=iB5<;F5aF z;F5YP;F5Z);NI7T)gU0Lw+=3;w*fAxw+Sw(w*@YXUb77Wd40jy+?|rw^WgGOb-B9!l6vD^0rgKma)kuA zq~0XBq~0{ROydlA#5tqx{D;6gKGhbuG?WJqbNK@JFnbYPUT-KVcgMeEE=j#*s357g z3NAZT0}pY>b?_nfM#pLXN$PEO0`Bya)Y}4=)Y}G^)a&ESDF+rhl2*NbaPRBFf)Gd) zX!M7`_x_4Tbr^hTj64D^?{7rG-2w0G!iwOMdQ0GvdduMQ{ze6STf@0zYW!6p zARh~?fy>7N>)`USzy`Q{EU<~rW2NP|GyY|iCSIpO)P@T3u|VH9x>K?YQa|__?jQhe zu?IDG=bwBmFr)>X`6uthgu&%wfl+YTp&0lo?l=yf8{@YN6A+M(1t!7eV}U7f`B-2Y zTs{_<1yA$z&V2*c|AkSy1Qt|S@eA@ixGb#-;PTE*5nQHsNnFa^Hwi|6~yaWPba>Wqt?1 zWoZ=zmz&xUxU8(guB-7c(@&OG5vU+bt0=fEtzzJ^w2Fhv$||9|GyiftxRQE6xh$LynvJc3}XpbXoF|i4X!6+NS0PUa9LUT z!RMR&<=8<8$PR_T7jeg7@HBe_Tvk?5a9LTIF$l=gDh@77t0Z`nmsTlo`B-2E+z8TA zEKA;5|I1x)9x9|Cro>SI_y36oT@gIbUILd?UG8#q{Uujdx&oc|eyZS-s%zkqs_WpA zsvF>Ls&>X-69ST}Ti}wa+u)L_jfc8ZtfXomxTI>oa(Dd8=#^X@fC};gWDs0ZbqHKi zbr@Vyb)@4o|0GvOI{|n4Nv@88ORA28OR7$QOR7$S_x?cs$s!0yu1GT^>R z{D%_YtvxhIbKs*qNG%fr+qgm=Jo^TxSn$N5)Nv6!Ihni!?wdkhX7|?rlB+9Fp|KxT zsDewXu7OLcZh*@)Zg#tASbQp4-2r14yTS8c2B|dU1J7}JKlo1e063*;HU5GSkX#)C zm%HEyxa?3AJj)%&z<0369e2jR9GT?m1XPe*odlOuodTCsodHit>ebwxfAw!u;;^)U zGykgJB+r8v+B_J+{r|@)8C>pyOW^7*nC5>O0)^6VZai#u zr%Xw`O{gHLw*@Y#w+$|-*Z7a__T?_vCob!MNxgmv@cLg;Zvb3UZxCEkZwOrOg2Uiu z^B;80A`pUfc*3OHU?T$oncrD(ncq2Z zSz1}(va-s9%gV|uKtPsOMQ~YKmB3|bRR)*4;0m~`tg7Ul^}l@OOARWl|2qxFI(U@5 z0p8|8+63SC4z<(ja&`S{Z&RS%6;SH}{zevqp9LjP$XCAjz~viX{NS>(3V^5oSM}?R zzaRu;X%zyOrBwvnna9o}3ciicL=3#eo>1pN~C5Qy^ki5TDNPQ9{3^MTL%7Y$xNc;nyX0dPsxL3VHbFS$Ad6(m=O!6j8kz$H~j z!6jA4y501?lQ!NRFeFzez-1|x1ec{)3S3fk8k|zK8h;rGNUqL;%Tg={E~(lAmsFhx zmsDMF+!_Be{Ulcxp@QV<61b%5GPtDb3b>@|s^;$elU!ZX0?z!CTwMp3yWj@6+yytm zm-9_(3w+D|y#8-PpmqqY0S&$}ku#J&klY6@cfo#exeE?}%Uy8r+pzwZTpfZ6au*y1 zmsA}AmsA}CmuVaqm-T<0=W9X&y#AlbFF2&YrJ*!^B;HKp290Vj+Ti}wa z3*fRtMer)`Pzk)3c1V5x2Lh6-E8ub$Tm_d@T?3a?-2nF=MX9>!x*Gp7xa0*$qX?<@ zJGAWspBJXV=m#&e2hjOnCJpND%s(&n>H+0m>IL^wFSwU_!M)TA?yQpC`5%XXmwLgy z)C=yVUT`nRUlZniPNf3IxtsF&FxAH(s1 z%X>wBaQPTc0Nmn^gXEp{zn6NULYXUs!M)TA?xkMvI&a6j{6zJY5PV7#T>-<`!=3`K zkK7+ue>hd-a0bG=*|XqYq6PO7Ex4Cx!TC7U!U+Ne?zjX##$E>Z5-qrwXu-Wi>$;XW zy-W)gEXlOsl4#rDweM1*H6H0sz{wN&SzmW&;;vuB8CVY}mql&>ToP>%ToP>vToP>< z+)1=<;)p;%GHn#x$+XTR1}=#<4lao{0WOI)`3NLV$+Rh`AelA|E{Qe+E{Qe^E{Qhh zIVVoZw3Zie57dxMn+KOQZUJ1@xJ7VDv?cJ3^2TWy0+MMf;IhW8f=i;UftPt~)xjmv znhgkKPNTut1UEiN-U466<=fypPNnh&&jv}r8@arXypuSWoWipJDh#m)z$MWJ!B?D2 z?S#N3(T2NRU4O~6(XN1cL4~(t;OqF5#=%SMNpNW=1wQPQcg9~D0!3~p11_mI3ofZQ z2QH~M4=y`YQ0|U@xi&-GaSWzR) z>WzX+>WzU*>Wza->P@hFFPuo~O+p2Et0x66sW%NSsW$^IsW;p0>Vs4Kr|h}zfFW=7 zSm5(6qf3?tmv?#!;POsS5uD!XQRA-!0eP#Z3_j;l>bL?f@AOo`<(-~7xD3*UccY4C$ z@=i|#T)opn^FIm!d8;Q59u84HNP^2(WTe66D>Aa+&ATWM6dr{aPOR@ypa>PJchIFN zfsfuvUIv%^Q2{sBQ~9d6yl^53q$UA=;Y8MMb#O@_4RFaHO>oH{EpYF97TXYz1Y+!r+oWBH)rgqTn^&p_uEZcBbFDyXo4* zp+e)+>2Q3?j{Sq{8Q9T4t(@8;>)_yPGJb|bu*LUff1;BT+2f@ew zN#(=fGFBqsIg^h#3W06xG4L_&I1WC_9VgKLMLU!N&xL7rm>CGjb5RalrcDt%_BhRg z68O;E1KcxM2Cof}SI9dzP`(o>P=yLxjw7#ukHzS{wK{ly9+hu^M~)$HcDcI#`yv!* zbp_O49iBkm22XvE+{Z^QgGM%csE`>{;*@Z|6-2G%lheE`VDr z$&27+_6m6YBsvo{aNm=3X&UU_4V3Ir8!EK8A%iQ*sg^V02alf2mjFD&+wpE!3#e15 zLZUlhBzZdp9^vw7aOofmp5pQrcqHQVtHxg*0tMbKg2&wo>Nx>iIkKsw7_M3(AM0Yf3iR@c#ma=WHs&sm-T@kT-FBx za9JM&!PWYJ=6?tRvOoxf@8BbjfXn(I3NGt|7`Utt;@jW`N)`wSs35EHBzQbcmn;Ro zfjtdA^JXfa6_*<*87w&o@C{U)kJtiV&z?u;jtk(^x#J?ZxrGB|2xJ!1w5)>5`k)Rj z&k=3#*niS22=Z?kTfxt|XTmf>5QtE~2!qGjqu}9B(J76CmzU51q|kXg?fzEdPxh$% zMQSJm6?!ecX5b8+qNG@h?YQ&;!atBh*k4++r_*%bBQvr%vZf2_941 z?)+;&ApCv0W=-(yH))4j;1%{Z_-=NC+mkbGeT&-heIM5Ua*F&=LC#PBT*gEYyi}wP zLf~?SBA!$JG5pKu6h*y&I{)h7oFeCu059@(5`3sc9jCx|u&2QrCI>PQ*zq_ulm(YF zlmnMDWPw{xQagF@73^jK0&xL$IXZ@c(n>uJgg*I;+ zPtm22L6qb2K5%(D4uQvcJKW{!`Vak?PEn*QU>JMZ6X2C|Xh$>P(oPn9<6rm^fH$0W zobgwHfb3}ryvEyQaOt=LKJTy8aUI-<(E&7+yW?L@sdU_e3jQ*k`Zl<9Y;auK*})wL zz{A{eu;VoU^2uQ~zblxt5OUD)P^?Uh} zf&0(p>F2mJ{^eB1d3v>>f^=YP@6LcT-=Piy;PbhIAh@(2*4&+cafXN%aOR(M90gw` z(+@n#9Vfx%jHba0+xhuF1A#3ICb{!J3*P<*9dQnPAG-y<=v^wG2amBAx5N5B$wyFv z3f8rB>MP(a-mZen0o1_P?Bg*ZF6;j!2O1LK_5b{TQiUdXl)VjJ;sY>#&^=b<0Q}%) zlpz2CIf5W~@?W$=A@CvgF!+*xQ~3yZoZK{G5HQZ8=@AE)BS?YQcsmW=yYwJ;3}wLE z>{-{<_?PLIj8cUhR2X8nz*Fpb@S(G)odWpIv&oCPJM(Y;ITR@A0p$huGWZtu3i$jO zwNnSrewY&ucvEe=^S=dw0#~qp)IEsS9Yv!u55DVY@&dT;MDikd@E7~Jm!|Y1SpQqs zQH3&8@bf6IfDiwW8mfZt{0+5J0}pbBt$Xeszq-}BmMS#7fV+c6dM0@jJo`TK7P$Ww zI%93{t<$Ky@n79%)G#@*_#hD5MMvfb-}g820Qjm4sDmK*wjWdZ5O{$5HNy~S@{>;l zd~6kU5Ct!vMjiv-u$nrKgD-!a$|uM>>;JLGD3HVoJE@@*_{k6oQz7REJfp1+)o(JD}JGD~)kDW#3i{QbO8Vk<&D?z}&j4G7DQ~Lt$ zsH}hw4N>_j_}+7Ahid34DqmObj(^F3k)Kh822@D#BC-h{Ig=V{fg6{Rx54+^L+u+C zZx+z}i^ZsduM?p8_fc{`xb;)=0C@REYB&hq`Y?4I0^jymlLBD~jD3te0={$lWOv7+ z;J(?kLox6;&!#xItgI3y1a^LsI!=N&52TJ$;Pvb1h|}PeCbg3R-*q_cXqMeu|L?kr z0y(Hq{xP`)-h7li4<6prJ^(cb}R#5p0c+y8Z zR0Xe>sC*54&*@HiHU8=l$iG4jHNeYxYN!c5dOdjyJjTxB}pb*4o6A&o=ohl^J`T08qKKutNp9bGFM4kcP+D~U9`;6Irs&`yV6>?A^ zc`Q}1(3es9Jovr`$qV3Hwo*GqaasR|_*#}EK;?|xcTq!S@bYt1paP!z9(fgfIZxLb zxVeX)Z0ZmQJwY8ez(==`H^Jll9MJ;b!I`lQUZCl%uK#~`UxLWbsRJMQ@D4gMKlt=A zl@EZ=KZnW(!G}*K54o=Tm+6;WLxC_<$Soj`fcL&h9tE!+Nge~=y^nS@uDdh-b63$B zNaz9O)8C>BN$?dsdQ;$$v#H|@_>xg-CksA5(M!+&ISAw<)Q|rT@nD|JSLZGE~UFP8BNPlAx;KrAw%M4Sdakcb9`eH z2H$Zhl{X_0D2-7d3Z8j^b|?lOSxz1YPsXX81o)zhseF>Wv;Hq#MW-eO6~<(p558y# zb&vty$%!iqp7=0zoa=Ju`t!4&)fG_Jet;_E!5cPpTma8rLS6))*Guh`z&D(xgO6>e@(J+5q2x*M1n+3dgh2TBbc)j8@ps8H;G^6@7JNG2QRTp6 z-=lUcc5nT^@ofs^p~BEh);h$JvYG@8BV`y{Iwu3d>id)8+_=yw4=sPU{wEz%KN~h{92G7d<(x+ z6L8!a|1$lGZ&E`+s8F9qXCefif1Y+I4Bqag*ZU&i8GijBrnx)+B4CaI^S#ay;w4*ujNu^tGyZoirG_$kKzV8gc@{jIB+r4DR+C%cqnxVq;FfxI&7FS*2n_L(s|db? z8!Ca<&!djZ;GxIJE8y0A^6Im&{$FuAouV34*l;F!9i1;(16=M4n&4ZXq;^`KQ~oic zMOq-Vy?~Sd)RzMDU9Isy-Lt@dA2s9yZ}Z^wgYV``765OWybuUNAovEIq7ZmRUaA4# zd^PP*1bpN5^!8g6Jp5-WZ^j@{;4={i-+U2ONPw@qigq*!-n*4N1-|hrY9~$JS^sZ3 zj4EWHLVF5%7Cg{LnK1`mc$&&v;Oph)waeA@U&XIV7rFxK&vM?OJuQOE;3|QqWEOz0 zd5U(Zg8m8BzBB%+5NL6Q8u-{j)KDFK%X-?;2Kf5lQu!vhF-(KGrQ99=k^!6iMnW4Z ztY1tW7}f4su=!4MANal_W8h;aQO9x3-TAkfm)i*~ z;LN|&!_-g`e8(H)Dezs_k*C4yd`2_io4&)Z|7Rf(_fu}q@*4_rh62~n=Yn$J%daK3 zz=zmFKkvT8$vymr$IoH?-%eA(I8i#l= zH;lgz(Fr^|fmbGQgWqk(y@-;Z@t%`XnV>>r0yjqPSBGOpZyNtNvJ<%f=JCsyZW-VG z>&Eva`N$W)(lgoAFK%gq3bhHmHG%tY9lzu7d;MA`9~;T{23)r$@bUy+y>0xC8@G+T zmg_nG+{7K@$I}ydBRhWi#>hpVRpYVk{xansx5n`j%Z*<<_POz0zMU7_iF{%F^7;E+ zH{UZJOB8sIm+kQzlD~1njsssFzr24$_oF)5!T(h~&~e|$L!VRU%NTiC{W24U@k^yA z@`uMSU;XCzF5l~nhr?eYI&$Gi&*TI2abF)<`+2or@&!y-FZ#sz{m7q|V)@vU0xe2`5 z?JMa#tN;46Yv0wu1fJ0@!N;`4T5#lLOQqea`|GmU^_`KRmkNDse2+}vRrHY=5A+-| zvgH1r=_C0stN#qE|LbXvti9iTigbRNgUp_=msZ~Gd+#Tar zXieb8o#U7HPvD_0*HUZ!uJId^@4j*dp}wR3d&e&y-!OqcHjX<}TmC>1J4k8IZhFT) z?b%9q`8z~xNB*P~-T5^BSk=6WDg6el_q-T>mqMTnNiO;B!wq%nU zX}*z#j%Vptk$$yCo^eVAoI$xum0D?^9(CjE+y+@!Wf(qB<` zE_wI=dx|3usjUM((K+468YAC$pyyCiZ>H51@ARA02C`m0HG!um@XULi@_6>W0k`+u z1YVlJ%M*BI0uS9WPd_7_BMxgbOP#5g)R~&>9{EVmmwFEAI%%=4qMat<6L|EK<9BII z;7M%`^2w)@mU?f%?L9q#XD0C0_r~9$_5^M`cKY}geA;Z*hlwA3EkEeHP!2Q~4Rxclzz#|iQZFuC4O+9@F9IO^0vXCu}+?`iX zKW%Lm>fyXLpmYzd@0>f`mnz_r(HF@q4ESS-`{~9)cFNP$3L%r~|k%>9}(MznidV zPe3xKjS;<}_!q{nP}T14_42g|ylIc$j{nQL)7*70V`xMV$dy%}=hg1d^^RNL9>2V$ z4RXDFRU71@b@PNc5+40^+iDm1jf!9?zVo0`wmyrnsv6AHF9pQDvGo~KgI0UzPHy8b>b5cC4- zxkK~0ng=wWr+HBGLCr&&AESBLacBHFd!(-bB3gy{T7{_Q$7>$be39mH%}>@mp}BdA z7D#G=h~_EHKd59}cxwZOVgz=&vmtL9P7 zKcRU{^V>9!Yo5_O;kr70=i1+{1(I5Y^_r(Nzf1G9=2^`%n%|>&R`Ywk^REizw7_Sy z3YO+M&GVXnPV<818#OO#{v~#||B@E4wF+g;H)&qcd_?oA=6TI)ntxUE`V0JlLFW<_ zv_M0v@UZ4h&9`XY()^p6w>AHk=Eg3W1?u>}qXm3kz%U-w+^_lLng=w0Li3>JPih|0 ze4FEP{li*dyH+8h`42RYYW^e5W19b$=5fs{nwtqN@QfBnYW_c(r!=o>p4R+1%`=)m zuX&c-bf@17S|F!Y*rmCp`AeGTHGf(2g65-|7d3yyJO8RcNek4q3T4e-)x4tlYnoRz z|CQ!7&Bw%@>tELbuS-DvZfL$+^QPua&0CuPN%OYmZ)k43$m@S+`n{e?=0VN>sd=d5rtvQ=5bgwwe`_AmyjNS@Mm3+Tc}(*un#VQwx$c~Q^+;%e zX)|oFV;NdxYNHg%@SH5tW{X8c|`LynnyLiLi3pB zNzLP$n^$Uqgci6;^Q7iOnx{0^@9)!^r?m1J&2J#5>z~yEH)<7fn%}IsrTMLz=QaO? z<^|1f*Sz?Ww*J3E3zW19rsieMvzk{l|CHuc%|EMoP25@k-=_uY5>Wmn%^R9;(!8np zh~_QLzp8m#^RFxK%)g&@WiC`M_mmb$XcfwuCpF)$c}nvgnx{4Yq2?LQf20qttQPn$ ztwK)oXEe7o|FPzI&39^E(EM3;_xcyLKvk>Thrsh%2Tbjo-->bP9*8=ZofrRFN*Zlue_U3U_Ro(yiIs07T zf&wBlGCQLp;s~Z*F3y<)nVF>`l%b_LH<(_;A=FZiqT4JLu|e+BKxHEJl!{MgW(sPi zHUXAmrcq8@75Tl_Ip@MwvCsGS2d{J2d#%0p+H0@9_HYJL1^l{zX9#$WfX@){8v_1< zj_d3Hn*t+KC~#ZAvjtohPDFDAoC){_0apY(Pryyg>3?*^c7fp{6etvMHv!)z;AR2e zBj8O0{D6Qrb>dWislf1bGJu~Ha4!Kb7w~2RUM1kZ0$wfP0RmnFTx&mNz(9c^l{Jil zAOSZEc!+>E6Ywwr4-)Wj0gr6JZBm55XxG4yA_Y87z*`A;F9B~O;1&UIFW`d(JWj)n z{vRnYx(fxy3b^=4QmTOW667-kJVC%`2za7^zhDy>y#+?5fIlGM*#h2Az;gsVNx(M< z_&@>AGjMJFKS*F~7YYm$@InE9NWgaq_(%cYBjBS1{D6Qz#_IDQMuET>Cloj-;ExM< zxqv?*;8g-XLBOj8JhdK2|JMkNN%ahjKjT&ljgB+{Hw$>WfHxEHCj~r6z>ODPpj?t7 z38(m@3NnNO?SukT1w2l`pB3<40zOT^Edu_WfDab%AukAwkpkmI0Us;i3j{n>z%%)G zyW|jCq0iC&j%HbH)JPU_A|g`x-uc(eLn`z+0bah&)9BNnO9c8C(3JvR37WOlbZPQu zK}QSpAE2!QeaQwOO#uD@oh8uMK<5ke4bUY5eH(P8K(hfbpk0FjuArj@+5@yzplx0N z(gdJ6=q!N_0G%(;A)reHIvjMRKu3dS?Hdee13FruV?bLQXq!(gfV2j{CmwW`K=%Nh zFVKmgO9Z+v=t_aMf@U!d1`GrpEzm9s@dGpvQqO5$Fk^ zD+M|YH0#h{z+}+T0zDP9)k)hBWYYnpIRVhKKxYZ`Jka?9{SxRBfnEr@QlPUyvyKf0 zECU@a&?`V&4cbOgz6wB^Ag~5>mO!ruoiETEL6->hX3&)aoe!FIYB1m((9r^I2W{19 zn>I{70FWjKd<;5Epm&1K7wFGGmk9KipeqHs1T>3nFknCEXn{Tm+N#mE6Pf{s0i+26 zM?q%^^a;@U0(}~Ei9r7Xx>BGkL9@;c2Al;QEzo~}wi0cN&<(f*AWabX2XvM|Ujv;l z&^JJr2=r~xl>*HM!hpC216)Bz3$zDlD`*?Cp5_5B0BM3ibI@4=9RNCCphG~H2y{5; zN`a0B&AK!g&<1q0K*xZ#c2RAVb~OWH0i+26@u0H=x(DcdfldTnBG7$7R|>QhG>dOA zU?AvdfgTFl8gFY57!Dv!5J&-?CD3C)=L_^W&?N#r0d%E6r-5c&8}v^G9WBsPL0fGC zFdaaeK+gi5CD8Lg=L_^ppi2aLA?Qkh&H~N4H5jlAbhJRP0By4hz$yS~0=))wmO!ru zoiETEL6->hX3&)aoe!FIZ!q8;(9!jDj*oqy!`93y03SdgO`typoh8saLFWtfXP`?2 z`b*H20$l={^>7-Hwz4f;h@t5It6r=K#u{PFVN#a zmk9I((3Jw62AcJ5Fkmw1XeVuxa(t!&usQ+I(?O>R^eoU>0zD6OzCgbOxpeqGBA2jRJV8A<| zqjj3*eXqamKP`eEq9VJg=1G#;PLdq(VPKsimtA{QF1Rv+ z71YjG3j81+fWO@R{T(M}SsiOpW_DUP{@3?%5*u`jUpgf}WUHQS?WUH))6;I&@%mcw ztXeJ91K+|DqokVTCgnuk>Zs;#lgg;foZEGLPPC-stvadsX9)MRPbb`J;KP8!GQu+m zPc!gmfw#2jj5K0o8I1S9NY?Qu2+ue0KY^#~_!z=V47^pWn!i}bM-pCX;7`P=mD^-A z&d)xSa3<@9z6yM?j`z0_Bidjb03%&z^d;PC;HJ)MWwMU$Lc)o!b0zV^Z2DKr)L{@E@OMe1mpU#LRMy0GqxuJvq1inqjLkMR~$4zl)fsXqT z9&O-}z|(cyi*T!f_X3`*<7UFs41920OSC{|Ffc0JrD}?<^18Zesk#S7V1#|xEx!4r zJgsTv{0g@}8a@Dc+TB5o4ll?ExJKU2VC{+d_~K0@)X|XgghKcE=$ouZZ)JE3%QF3MJ>tYEBA!ldL+QcLN14JtI_j9 z$gLne&A_#gGm_jAVq_T%A>S;CpokwVB#wh<%R zUT5__cTBBWP4%FAiC;XW1zlQGE$H%4xUrzSjbPM*F01K1LH90lU}HhIm2j)k z_d?LUL3o;hi$S-J7+D5G2)fmT=Nq^Xbjt}ZF>oR17871+;6l(XAeb~HxhJ% z2yZ0lk_c}k=z0_05OfVQYj-g22)aEjwV<;(8kt#Fm&=LV^Jlqbv+>s(Vs0FM-<##4 zz4f)+${Ocdj(KYl_YuS!i#Ts*#6^4G6LGtc0vn6Cj|sOL9WO-OdxWPMxEOKo5F^WA z2oaY@c)o!P5x0@>5(5_^E|>610~aE072(Y2M}ZN!K+7(&El5pFebA>v*pJk7v` zh?_@vmVpZqH-qqe0~aE0D&ZxKMBJ0as5A-)5jTPGMj~!3;f+LG3gL}J+%Uo$i@1Sc z+!1kw@mj>?)HD)t+FEYkb!}=LHvL*d&^?3S;>Jx|ljZwp5%wo|h_F)BQtDj0(caCu zXB%8o7sxF?-?a{`^wBfqYkX@3GGyuO5?$LTjc6lHKFFL}t(86$uchMN<1@sv5wE3D z!b)%l;Z`kdN~45${ebW^0~h0UJ2A2hh7hm$gy$Q$5U+0%USi-vysjs_(!hmy%^{p= zQBWEs#On$hF`^BI5U)!Jw;H$*uL}uJGjJhZUm!foz=e37MR>k}3-S6a;U#*!mWnIE z$;7BM3JCF+xC|CG0(h6RyW=X_UD47z_qQ674;- zm0%9j;&sh+ir3k$!mdO9itqhRZfTowwINWa;rBg(I@wPP)Jx#~Tc8fTUU$dogcfd7 z^|HU-zpPC=ndseE;j{p);?nyU*2;EltgJOeE4%mqC>wU2SN<-yeya2=oc25Ze#2kw z{4WY*Df4KpBB}f1td4EzlKQrv)v@H&WQTQ_#qo}}< zhX;RFA?03PndG>-I>~WmZIYwBi4;9SDcl5vUe(Y$T>NzTXmErK+Q{5$|~I= z;%A(ba`(Do8!{HYf|->{So{xH>iF)uE(N<4pPH*^&ZjuldFGtlS`OptIk~gXa^!+b z*kR`FQ_3omo2vVG**Uo_+gr(RoRizgK0K;QZo%Tu@xE1Zm}@nTKGaY7Bw$HxP;!Uz zNDXcKuA|{qR!PM@cXemWUIlpyE2{t=42!lyMw%p*MM(Y^_IgXB_rOAFSAe>ie^G@u zrHLe?rP2U3$`q*P?_*_WutB!9lyXUZH(A<2Rh*_Om~2#$P>{Dz)~dL5R?6M21lQc5 zrz7c+H9gZbJ&)DvIY4@%oq7`agXd-U_J2SLc|S7@J%J2qkCt=uP`O2tc6^9gKTml~ z`~4nYa9)mfDW!8Co_SdA=CT#$zRZ6hdlYH(c~nn|yf4e0_{a;g*(D6pp4{hqd{bw}1-YN8 z^tyh|(A|Z4yM|x90L%9vNUor0E-Y{RrySO^2TEnb@;t%v0>kpPG^@b!Dex7YH>|u| z$DQ>~JmVSL>^kg3M1BpWpTo|0Ui_yVZ==WNN~J?VYE)rgL}qAwDfqs?X0P$b=!}S` znJJmP;*ChhZwr3s3`c*^U~*xOJxiq>b)98LT?hQNl^t57UkOyp&zNy+My`GeZ7z=fH5g^ z%^5|C_v7zhlp}1dV9FiE6jTBA2T`ml!s56I-_8FT$B9~)x45u(mNdEwra0+Iv!&7H z`^-qb?&{yps^WrF!tz;WN-oT-N;Yfs4G$%^DtU0iRWvD^N!_XfllX&|WdFdmu1fBC z?}J#`jFxp~WB=KVFhgh0QZdxmAk?CS*^Ox?O(Q z-BIplQLE0ls8Xhfx{#OsCHrZM zOwtacqaB0!#cH_=A6hN@yOx?~S{({{5M#0DjWqVbD7HsqEmMI!SgwTFt>|4!BiZ1UqpK?1!s4S5ap>hzioSBi-yW46 zr1~Rz>34+^95bD|VV}tt;TT~56~Yy7P{kqkheq&Af6GJNuc8H{>_eXPj~vLZy7O`W z$kR+(E4)*^V*_r~ji&JH3Z=&p`tX*{yDWE?ql*SymWRvkggCOJC6(u-dI#|xSLFH5 z)+YtC4m|a$+(K7ryDAShkz@FWH|4$$r<>FOY_u;Q8&xoyk|MV_>gs$7%#y`nmMsp- z_B3wJAX)x~zu(b%@>bSA3y$HCvGjU$GxZ9prDRHSr_dNa@|xVjRvLw2iDGbypIr$= z8+%LLwfX9`%vrxP^Gb5sKK%U;e^H|Y)%46jb;+<`wcI-*KC63X%ArUpw*rAhlT=i> zhx+s1FmvJ%$CdOU4h;Lks8S5^WRv$)6meis$Z#`!yc^Sa#DON$}A z%DJPwiN&#C>ZIc}Gl-V^DB9%%+%uZmb=9->FU&e3zpA|d(t{KJO zsga}o$HmIIbi%90pP#)FVYih3Tq6fI-%1k^JZheVWdXc(Fo?T4Q@1~6IvP>`H^9fKDylipC z7DipMIIMB~k)!qekR#l<#lv3PCKYN=xuZgI~hHw_@O@ z{}iZBipxy700oWm+XbtWkQB~O{M+&pN;KiSB|zop8xXW!}OzZ>Z~;#x`>{MD^2xUO2?f;!u09g{Q@3u)uwwV&xvPt)K+9# z;9RJa+q*gEgCmM}ya^Tlv2GL#9ObOaYEUbh#@Sn2lGZL9G7<0Zj zOy65q%-RM*YYt7K$iG?xpf$&QHF@22*2nvU06DiiN?|Od)8oXb7j4P3Xz2iry_yV)a-!-PSc(Fbt^yO%0|gOc$6D!(LDw^ zY>zBao-D*LEW{jKXpu8hN}3q+lqCdnaSQdmP$@SO<)z~}v!?QyZY*GMVfo@F>JqFk zqjt1VEq>bOu&{ia3HNnbS=8|s>XYd5%6F~BXZ~X?E^mqTDR?9w5rhcC@CVD~H(*Ji4IZpE zDo~r#J;(S(cNXY91VJf!!qRW@~ z7Cyy;b!7wm`DPCm5MuK;=JrJD)p zBV!;_#N29YDJC~kyuB<--G9HCR4m4o=BNO{QSXJS&$U2f(OVTtKzt?QygAfwSClfs zKKJAEnzCsB5htbGUC+%cC{`Y=(W*{X%AVuzH)Wk!-;?~8rYy#m=LhSzVIdQ&TTeYo zy{WZgo3*|bA2gS8x2%?DHoL&5uXRhB~ypAPYsVum>Pb!$<`3TSDb+3tvyG%rD4O$*foeJ{e>s>$+~EOWb;D;Nc4*xpWNR zhu=b^IvS1!+%M$G+C-#{z?I&tb!>B3@NW@&_K!MVr1%Uaagm*vVj`)fZo*i?<_tjO1& zbp!}L2ftI%i~weq-G?-T53ne!;)?=VxT%_E<`0=y`}IATYlxq{1=18P1+KYS9P==T z{(v(R9P~JNGe5659vZ|(wl6qgDR=~H@DpIs@zr*$i}5n|4i9AOp)Qh-hmoz_c|j2S z>%k#t18MvgnSL*dl;E#nx#?$r=sdP~;L{xX2Y!9im&o%AuL*JGe6RiE%KfdVsXrY?aopfINQVGz`wKHaU811C4Yso zPQ1JYdo$uO=%XI~2AuY_7DvP_xxgGLw?6>dyfm4=5z1Q2m3(g~YvKD5I_I*t#WDL% zO|R;1wuP~`1Usk&cUv!C_x2&5ZvwU*N2%pXW*=$N-afB`mP7M~ zmn(bv9K`P=zA1`@o2xTQhB#tAvKH-&VqeL4Y;Ji=77@4^oj7-brC>J;ypV?l?I~<3 z6Ta@xceg~~mXei9E0!c*<^x)>&hqDcZY$QI(^zP|082+p(x;J93KcvfX)2^zPT}4lY6Q^|1p7u>W8M!#jq}&x3-kZ$Prao3Q#dpLq+e-hZ>Gi z^js^i=$0t69A(Ia-Y`{M<6VcI9>DmFTCX79stp@#y;!Ah$$Zhe45r6BiX=?Ilqz8h z<_Vnk^{eZ!MMd=(JEaX{$KURAmVeNOg+$+m=g6$gM&*3%>@5GI4eKy$-5`h45l~mC zsmmPXux_B!DPQ|vu#QeA&;O=}3gw9vXpM6#qjiARIzM|kpVXH1Zn+7fRXA01I;Y;R z=y>?G&^%=j-`$o);s5wlv}GZ>d+XY=?!B+0GCao?NHIx@FMtl9sYlR8Jf}vQA?jV- zj}lJ07@2Dwd;qdt)7fxpom={!a|^P}!vgg%SToPawQ{`Q`rkw%)U zFj%Fde+3205t`@uruLY&&QN`5?*N!feMPL(ng~v)c}05`j)*ResE_C}@SM?1=OZcT z+y5UCU1;d}#;PL7v7xLc!J;dAa2{@1eH6fzg`bN@ubb z$Mt`hHUrJ^k{n0)`3|hb!@1X(9}S21(X|v3o$)B-y~DxJ{!zVa{p`aH)3?KP-Q9ln zue3<D%oO+yET-zOA{orZ z1b_*U?%(j;53ogX*-&AI`S?r7mS~Rkwc{Hqxh@FlOoU@ax};vlt(!VmYPO%9Tb}m{ z^1W-4D|JqCaxBNz=p|DrO;wmy7V`=Hyg^8;RrWx$hyRg8p$-oyu4f)Z{P@4qWfm%I{Ie?#v$G#-v3J>XuZAwety(>$X&+^y1vZ4Bk ziqrXlrb2QJW^y~j_19q5g}>K{4fA`n;;zL2!kcG&?;6S@uezF^$!KmVzM?SuRYkT( zxJxt7Ac;hHN;C853OcHpG@2r-ml37``XYrgV_{S_&csr2!xX*s02)L+oLYjhjbr3& zxVb8#K2QpstEkrWm~aKM!3=agWtZzX>3JUgauN!IW?LOqSS+37e+RM-{tg6xyRR)s z9)WhVyM9CBB!9%us{_yO!J2hgkBJ(=7@yHxD*i8`i0ZGx4L_}J+#@!E)LC~-i^clX zH}@*by@tb8WBEqz7M5>aUW^`4&`&X6*yARRc3MTMBawHjni%R4s2LaoIQM|HYDd;8 zG+A#~ncl9L>sSQ!M7tW=!w2_ZBS+0+QqPQ7iz5N@RLkC)y3v~97+sp-7+qER=pw`E zL4Va9G;Q_UBQv|#dSu(N)u(Bw2gX^qbu+yJgYZ7McD^mFO2uZmdX2)`Ldza6{e{NE z?=<|VALvy1F*t-WJOAl~YiLVnGB}CI!CJ`g3S33l6)$bYsKpu9nX$4bzul1qcEs7) zf!hULh=?!y|Cd-6iSN?FvFds}P#8L~W?h zl`4!0z`w)sJ0PrYL#T{5KiG>c4F2p_Jt6PHb-N)`fHm-CzNpA0(AHhbM7T@#b#hJ5 z!NV*Cm*LrisA4EQJq3}6gXJAD#xgy|Sf-Pwui!X)2(B?WfTksU3=W`|$5;x6%I@C| ztxaCLn|WNAg8OGA7YeznNN^oI{Z~G-XkyJXNP5O!Y68AO(~X3aF#S_9-*XABN0-wr z;0W3Mf`oC0KP?of>$6=YhtmMMRUVLOI^XrW15a&s<{S2n&a{La4XK0$l z-8sj(KQTp*NGdQkSvf{(eucZnczf|?;moBu?we7Jchh@Flc-PH?4zG~Yy@k=n>FCJTP><9*m@=J7L+>B|z?-2{l+MYw6d?4(1r`c9Nar~X>t;WD7ic5%D77EPZ|aA3KRYo= z{le&*mcZ)vxt85}Gzf3)1mmrpkb>I9t}5xKod?|uzO0z-S6fOpRf7E#CquB1%)^XN z4{2=2K_D`R0}I9CVNjZvMr%V<09iVPpo;Nc5*`)Nme4uk)d!Eoarh^6LA4cUTxbE7z@hP15Fgl7B`k)UXo*~o zMP4R;Qv$9+!o7|J{Odwi@asakAmTNt=Gro;=0LuTwIVJ10_r*Lo<8S`}3XvwY znSs`sG&^XU>PZwOE6@pKcGE_q#NWOOP0@N9nmUkg;1nml4LpjTMQ{pXbi4qEQKF(? zr*u?5$RC1Blct4<=hxCyF-eJo7sPeA?-Z6aC zC|6$|nZ*2>uDgv|nbae1--KPlD^U2iqjKq*d1@!Umijs zKRA*9*@i{hZ2ym?cA?ZKKi2V&@#nk;MV*_1E>NJY0rRy#WOU2BkQJXeq*#8w>W-a? zOU;)*QL-E5>ZdtZ9>%*Tv6i;1yF4<*@aW5iM{eWUj>bHiX?S$jUFDq~eby*X4?H$j zeun7L5T|c^lIuNMUuZ1WrN)l^;X6F)`u|v}A4(;{LkV|z^c3*BJ$f7%1$t~F9=(0; z4v#7|1AgL{tZXVf_#+>e%whwmiw-nLN=HyQQ+n`Ed~-63?zsyJDUErd7tBqQYGf=I zBBh8E9-zgpqrjr>i^Sf{9Bk#+lUbMt`64RF>hSrQhxcdk5hOGRL(uFK#@?@2k>#sZy=pbZsOjBe)UBq>lmpPhXZUzW^4vkpk6rq)$UcZI zkRQ)^lGHxY0cz3A7K>_)Ah=ck=P* zwXP#r)6xGl&lvVJ`agQNlC>5!9%kID-c}8 zqm;KW5}ftaccB^el%flL@jwf7Tp95tVpxB1o9a1-UdX^5F>_|-tT|INYLFeZ0IZ3()ImiXB*QgKtGVvke&#)F91!$RSCD7;fE9AG~H{6LJQI0Da@;1i&u_n`q; zy`bx8gXL#`i+Trh_N9}06xYtTA_|iVu06VM`}vcNG-3zh5RIs4o|&=$jW7lye|H%3 zX9cJEm%~{2(50GEU%OM;Rk!4tL;r`e)J8nN`ZRCz5bh7`L|Ja}b_?Z$Utyu~v#ITi znfiRJt7G06m-chwrQ%sAP8hWflX^S@T>+ZH>u0wm zx;pl|Nx7-`FvtIJoy+1OPmcjc*uO>-=HVME`uZip?uN3@XLY5c$(((Z!8&$S(8LL1n3<9WD_*$qYH!ZQuahl&inW6V9GpQ4v{n4E7Z+`|g z>jOkzkrknbGfodHrn8etb#YSN!8UDI2KM0GLf8kFG#)Cuu!jEc^neyZ5I@^6K*b9MU|Ds@0SZ2z% z|H7{b&rI3(Z~VaU_|H$<{-uRcnJJ(Aivl@1Gvz=3#&4OKvh82^72v;N{TG3~9Wqna z{tG`UHZx@<_-{Ok_Ya<2#e&#JC;7rvEIQ=mi8}tNS?ZRGff9|brhHF>DE}n?Y!#cu zSRjvGjWF<}FvwnwUET5%{Fl|Nb?@pd9NRCZr}!y~@p@1?9`M@QD>KC(6=edyhmR=V znt)p+r+MET780L`sCzPYpkpqc@F!VoUMGy_04-P11Fg4V+9Kfk%;ImKaFVacVbO{1 zh+e&%k6tc_rmu!_=TVN5JC5WvU16XttfuFqC-~VM7M|SiL|x!L_8o%#67=|n#vglttIbqaG~CIc?gmP0^@%CMc|*glW)@_kQ7wMs*468Tihwo zz()jDfPd^?_=^UkhyR72G!)4K{Dx&IpS6y)w`oIR356?$L%LsQb;+L2Y9`hoR_xt= zSNvlBiwAO?Q_e5&SSqHQIj5TzZ-FvO&hGG7Q><_(4XsD%*Maq{qwg-< zfeFH+i5VVJ@pk++|8B(z278Q+Jjv5Iiw?MqK*_|Yor311CQ6P-tRb6!&o^=w>v5EV z$)%>}jvw%N9-Cro2=XTB zFPd}xe*ElCY82e^7x-5d{@Df=;#PoG(9Hxq0~5w0?Ox{QPr^)c+)$i>Q;+%`=gnVd z(Or%9YCC`0bem1?H6K$m`&t}NKqFm`f~M1WO)JhIpMIUSuCHR^^Iq|-v2Tb+1%KeY zh>kH*(_}T#sL)TV5O=E1^FL4_yLy~^ZG?$MFp+NIbl%APLv}-WPl(iAOR00P)PX{} zA3q*hY$J>I-hK>+VmJ&mdWx^!$RfR~qmW#kk^_F=UqX`Q9OIQ6S^M;cFohe_-;7t6 zJlRzbdH2keNqB%}4~{#WnRpr0M|#%u+=J^iMAomX%r*Pi<2e4M^-2VyEyBJC!-C3` zHYiOmRVvY7 zF72wVLn^Qq@2b10QT`-6?$-hQF=%Kw8bpSpBCVd~sD~Om5!XQQ>K5}$TUaa`|2+@S zV|_c$1daxD!$8vNMP4n9q7g8%o4Vw9cP&wu_++MdU{vz#Jl3np@g&Hc38#3oL7C8)C(H&e8&(cK!i) z|Hq%6z_Raw9L8`VvMry#l|`}O@A>AfEI#N~8LVJI7n10-8tuakKnJyvM{dBQ)kso> z=HUL^Egy$ABLI`jzboUh`79s;!BLnIgXeL&TO2#^n+~YkBa=;m3VgVOr{}W-3a>&+ zh`+w;6;@9?zD*!(+q^n?;%f(^$q7H9j-&d}OC9UwVosLSSH+=h zXuJvD=a%6t)K;V2w3h4?hSwDZeIVPd{d;1o*bI{TBI`0Nz)^e530J%s1pH~#R)Gy( zCHfI(0WmjAaiSsxUZ^lhqe+i-1C=K$_3~$o@&P6)Pk2O305HhfP^lDS{qLOx=w+}I z&Ps8M5e3lPz?iS7`H=4c3>_Tvg+cE`H0lORYMfE7NW%hSdV!`)F^^?7KL%``RMUfG z*8ne9OujL3Wqj%g*4IY2?`z;^YQbfA;yQWaj+O-3w;9UU3oSW;)>9d}Yj$Ttf)Le# z_Vvy(Sj6iM@sC+*7=BG_2zkWUVt=>}=>s8Ij*;w(6A?OYzXn%fjFsW;hlBRVJJAYi z4dHXO7W&8h0|O8YeD+8-#6OX8mNqHrMp7u_PD_cwNUNDlfa1C>iW%7>@0kU^cnCtA#o z6H2vNObg&Mc<5OAsi$gf*Go-*pqIK8OPzmEM_sZDJ_YDo@Ng4+`Y$bxf0%;%kKRZ5 zjTBV-OBo;jFblBJD3C_?LZbui?csnSczK9=xdyk>^A?Y*ao}xJN?ce=*rPJ~!LT6v zddQ^V*-pZvehbtv6<8)q3-`peUf!Ib@m2t%oOV{!)luWw?2EzNgMxJ;bEIDIWv!sU z{iMiyR_DzHZ)-Ar%`PJ56L>q%ZT>Xe#V%#9TWhsvhv^w&<5}SU0Zz-k7H|$Z;f$7A=!Hvv`&jUaXEu72&g?Dl zwv-yDetm?W9?ilh-;rkK^umb{da1gXDr2f2jdG3h3lr2ynCgdtf9=sP3Lb&ZPt)R5 zIw+?}fa-J}m{XdZhp2mm#e2Vg1gl3JM2?1hE_!^+BP`gqAx6%nBd5%8$uXmYto2UR zfdn-(8n;6`;)NDCtqQAaDKb&b9x4^v&`>(TJce-8dbocgdePVZ8t^>K@*4Jpj%5S0 zII$Tzwip~6?n=|hE7Q> z@ytwVcSOGtOus30?t<=2{qeDwB=CH-8v(vCwetrTT<(qcbd#BO^Y@PKD^0{8?5(Ch z(Oa#+-f%YtZe6llS?&DLf?CCmKmRBT3-}GnXvxiDXpe^d9De_LgxeowW1=q}raKOj zUmZD0vJ`KH!I;YIT7#GLR%?&&=&@`e+j@lOk7cuBwnKhvI>Q(Uh{1|E=1<5|{--w$ zM11oR-uE#!on;;7A3TO7{_BVN(Z`sT27e(^b0OAOg%TMb+D}a%-A~&idct^tUs}(9 zK~kfz&ULwy-%$R^eriRa6kkgYY)n7+d$G>GT2?o)ae)`000I~9RM22RoUARhf4?99 zOCuEgY7Vn8PBFRe-e7iA?pm9)WiIp@hpu! z^Bwn?z=pFAkMME0Mn4K26gUpZ8-Y_OA#ff6or*^v9{-LXoWR;lxW^|#)Y5!?58tm3 zqPmZogjb0U-;aO1k17XdrtB}}!zZ%DfOBY{80gm!=#}5`%@c9%_||J=5y{Et9AEdJOz3+_9D=?y0UzJXj$2VpK@ptr97vaG8ky74#60-)BAHv2POIx$- zw^G7GRX8tqd~%3Soy5Ween92q6medC=MdjKiT#epqg92!lE%W=n{ag+8^e|z=C{*W z5B9=g-Xonw;Vu5R8+)TL z=F(9<`7rl*l7+M0=vumVJzO;ONfw~6Nr!pb)2x#%$GkjAPl3IH5TsJPve!gg`S`EN zp|}>~iVkX6ypHt5&d5_ukMvTLaQ^i+oY^RUiI+MF{7vA~EI~=$dCSVVo*K-!R|X#H zX?vIt&0yB%0g!dx3cE6*WP9_&d~*gK_8E4F@6SNsNr!mA6xKTVPGepOQq%K-)J4dp z{h=V6Uf|FhRVdxnsL@8F27bpEPGKP|@DSfP1#T+)R#V)+Ap)qCf@1&wLvd?EaUiZ+ z&bbEj(NkF}D?iA0PG#+z6~2Mg&-fQyzx4e``)U;*I*~5nP2qlp~S#qz5N(Noz7wlAuT67i#=N;G4tLy`gTn@dJUI zeC884p?`B4>kwCH9_6OGzgV!V9Xeo|E=pD+RpN<>l-+seAo@1Tb6-M>f zrI$jw2Kr8+#71X{M?0zsC^ZhHCO*ds*h-X|!3H$LhmNCETKVjyDK(=vpE!fHO25;C zKebTPpKPH{T9BDCt1-_IAD*EN(NysN&BHH!t9$s_Z~567EFq}S{86Kh;XP-v!AyP>nAzxH30w8=I-S3nW5-CT&ujp zZ{6KOGhU?{AXb2NKUHA%lWMEntherJ;XV5E4gI;e*4l7TUSEMCsht60aPFv5!ZoG; zFWs`rP?$*y@6y-8(6=4y3o`O3yfbZ(jP;gIg@_Rwse~C-{i{Qe(==x!WhV z5OUN}mk#L0WE#foY{ZzW2YCGadyE;}OgCmIp8aUd7~+#L;1~WM#_TbS`S<`oJf96Q zauHm^pYNUZj;*0M`f$yX<{M6>eXDNojNk7$#1h9G33S{`J9-yg0y8ZPqjM4C>0V9K!(7 z=vM>k+tzG9^-n~M_JAn2EM$Y(kNf$Gg;;duTyJhJ`fwrhl-cI5ioUer(F=1mx=j-= zf7&II4_kz_*2S-Q+9K9E{k|bEL@Oi3_r~>}P`VO~hqLh7Hg5a3Mep3h7ZxEA2lyY0 z*a=qfRZ&S6`+mf&OzSyU zMwqn4S=9epX#3OJ`7Zc}5HdaOtbV(n4_(H-Fy&zG=S^N=(R|T6Y+})$+t?5nruOGs zK4epPUIF`#6({lM?6`-#95=BZcM0R>Kk>-^v{08OZ811<%s&rutC1FvViQRe& z51i37k&5XxDTB|qgt~O+aRtn&xR?)nk9i7;i)@9=L*@(K$0G;+dfn?kK-H>I^-@cH z)mePu`}j13F7-dGo*QIHOOS$R>^<>fQIbnne)tpih^g?IDM|d-M3*nxum59t@ysNV&8|QBteu^(_p@i_Cdb@1rdp?87FD8?+@jPxPYtIDDkFwUf z-nQkpbiEn0Jl#8}F}*qFPRZQXLJ7W~;<@<5KY2Xvb2ieOKKpGLnqwYs;j2G~`xBs` ziUspMpEGx|BjPjm4!v&fEH>6ntN-^wy7&}JBjWza_2MIW$1j*?NJWxvZi@ytXlk|& zx~KRmUhMDEG^C}axS)ll*p7REE7AYYxFK3jp zE9MK2vS7EusKMdt!eYMpC~FftvIzG+k#x(qNvbCJWH{a}2*tNG%rRX)0}l^K5N|6K z%`D>o9L0klSAc&hD8{=v#qhd4rI-&t=B!|7F`s^nMSJ`V;oa0+g?k-k0le@S^EMSq z1>t<(F%}n8C^^C@>E>E+daxT~+Kf*vn74M}O^!4CZ`EQx@Hl&%ZR^6f9cS%K)#gqZ zX2;pt=0o%tq7jeSDK$T0$wx~W*^-6`IUtg?K#0NxB#Cy zsOZC=7?VT7Fdp$rS(Pt(-BTZrnlewMfO3R=X0c-8RX?-2tO8#T`h^`0DL}Q2mG~xE zD3S3iO7uylO6P=@n%DJjyo@LQp-nkk(zJAF6kdKpBc4$$ysn(pJWy(W8}W!PK99if zmn6+xiPxqy%N8Z;aoSS1xC$9W!^h**ENE!oI+^$WjeSg6&DU!xkf9f?y6$3ryPRDb zvVTpWAmE+Cgq@sxPY=_KphVreQT{`T%z{ z5IkFv&c?Ys#$T>xABGm13(z6XmK!NuGsDHmoT+~^8~E5gjP`6_#q>GRGs{^T__KBSTP2FB%>PvP6H z16@AlIoE}`=E`;4knN+{S-|(yV6F^K)~$RS!vT{p<@y{28L)|itzZ`|)b&Gnxr4pW zUNs#3X#%T- zAL<|?TR83m&*V7{7#5YZ&ReO_YBhH^DtJGcd&|lqUErIfqRwp;tIQwzg?X8B%&+6~ z5M)v}MR`jv=D;9Slm)st*r;|n|I?%lu4nglQD(93^pP#)1glNrued7Hl}{}WZaL3F zd3BW1iw|>C3Yf!Mblpw)lCcC!(S;^TCz)5fDlTkp5>Y*5_ECS{(o?y?k}N#JOL@Um zY94}b7M#QLH@m!)v8J#B+>;&oH&n)XE6;nDwtr}lV<-*JA%h$|wVO+5QK`3b(}V=~ z8WNnJatlFHF^C`WSF-UA^H+l?E~5E@0Oik+QwVTMK{VEkqy--qn!g!Tv^Y??#*|6P z4c41^UWoElh-^d>Ej*0zsg-#Res7_?iYk^5;@+W3EGtXm{X&%h_Inav8Kt!5FNZ3v zn|DewjI}!O&CJqg97i-txhv3Oef zUH(#}(gmlS-=Nzfm5xZUuiu-NHA7ys=&cBiQd*)w8KNgtiSq7oQJ?xX86S(@;su&) zf0t5oaFXu8B6NSUjIK=RU(~auvO-oyp|>b7ippCl56SH9{uF?181qTukG507n?KSp zD?xXT`MW{_flSeBAi^JnB9^OgmbRTQ-ygkHf4bvDV#@?|?h!%tYX2zwhWX3o) zD39NWg$41N1$GZNqw-PPsPYIN6{jS#19^OMoHCV_ZQ)1bltfmtg?n|u^^+}pXczSS zdt3PAF3JR!yM^!Xq6}wG7l@9#7u8KDw8L!}b9b5QI@hCBN3*SlCAzS#uZdgz^ z?W*)=UAFL)t|;c%QeUhmGZ`hWZq`ej-ApAWu)~}AFWq49x-EQFZ>2Av(OrpTTQ~DH z-IaKjyP5CDReptkWKlx7e-GtHHe@rO&<6#Y83mT~M1j!F{8De&;klU)?~Cj0O+37p za!uaD{~n}OtWD|EyM47o-nHGF}qVl8Mv!Ng< zgJ~0F4=U7~-F#E8c^rmjrETcraQKEl8#ll({ zB`&;>Lb)0%bujAPy)bYj}dL3zR^4m#p-E>2Eq9Hue5Y9=4aC1W# z8Z?7a`$PTj8+G+3HtOoX-l(hJF#si&Z{+jlpa4!G**ui)*qGq7djU|E@qzq*W>Uj|HUpPpy;1zmE`|(XfmA350>m)stox_y`3peV5 zw+5r}J74F0hrs9WYC-`#X9!g08j|A;$-zS*nQlmqHY9%<3dtlx(nFJ+&YHi@KNyI3 zaWRB~hC%3`4SL0&L&HE=SUODU#rAE`C3kM%eIHV+>}^A6`s@7gL&|hE&)`o1PHoK| z4ozb=@GplWpu=D1UL!Djwcfx_k3?a=4Lp1lqP~0tgrp68`X~q;*g!&wJZ~hbJHmCz zFF8pLXLha&&4R{J(Db6g&(QcGJSPR3MsvPDMH$G#q3K~|9&5$KKc=57~8a-=RX4G3WEuyC=|~##(+6?J>NM7ng$xo zW(MB_Umf>*kZpBM|?m+Q1DWqhZEcpDzWuwS)~|MD1k zFB`mpIxlY=c*EB5v*W-^Gxj@$}qWvFPehz ziyW_XWFH&+mv#Pu@!)6b{B{$-pJDJ5b$;mt@cZigxQXD$>U>s{t9#<)L^SBuTHYoV zzWsBp?!%qAxRnUsezum!P6BQ>@Hs}Is!6c;`L#ST4a}zvW*38bB@N7OYx%%*Fk2bS zOKbVzbZGo%4Ilm_@X9rMP4BJM%`iU&GYZ%6F;9V+XE3L(<-a_ILetmq36p_OFz|M3 z`Ps?JG8VIjPk$PCh=KpMhF^Oc@>MFImjV2ws#lV~hTqOmve?@y&zhnP?uL)jV+)3MJ*}$!6Cq zv@Ury_m~Z49E2WGdh*&KDCttmnpO z48+Ft)*NLp+p&rdoC^oOyNbUw7geoW#Y^TQ8Kkb}uJe#VGN5CgGKQtBB0KxC@YUSw zc^bv5__F7fG}dGl|KoXOz3KPYut1%GvoQYV3(CuE_iH@lMP;D8oL|g>jT>H6dNoxc zQjk1;*Ee`~oX?oAj4q0MNhz0^{2K3T!?bvX&s>ht5xNYS=8M<(nwL@iSFiHeOl2N_ zVS%!pEqIkjFT|=~@~eE|Lae2Gys8&$FBJUeRsN+71#he@LctK3eX^1dU4#Z~TFLVl zDJAULm3(p*a`pI?++!J>)aF%wDGLqixU%T*GFZWWUBNdlLCf~9;J243huNAH{P0o~ zSiC|nFl;3i=)qrIhJ2o~!YJipl=^cym0HEGWP`hFxn8tjIiIy$87|M{GuJA;`K{&P z&0Eg?V;ARLOSw<~Q0hi`%ZeGOrz3EyTVi*?PPEY>y8U!rS1z7^IlT+GAs z5mwJEE}EK8;S_F2dmGX}EY_u;d<)X2vvldNvx;uKMba;2>AIiEDw_I^a{DRMg$#_V z)I3uwp3~G6#D2`+_NJyDtYAt}Wm8l4CfKzuYFE@E$kat4>ozYu;-pE8W(Pg zX6$Tw(ZWd68*c3TK}9XvnLhKv`D4)!JxodM+3H7lNUEv3U#YnOTLPRw&`H>KGd5q- zEId6GrLk#zCDqg)+m}-oek9ctz_3X;muhN-{n8iM4`Pe4J$Xz0#!V}`w|`OFNv75^ z`*I8)o@ScJaG3UCnkk&FN776$vVEhqYI~KMuQqITw4#f2T02|8LFC)}q_TI8NoDVz zk;)1#OJ#PLHuNh?QBk_-DVceU;o(o2Iw;r(@yvN}&Wxu_oza$QXbTRWjJ6b-_u}7% zOfeS%1EEGJJnNiGMrU zG>v`za8csZCJ)A>M|kWsQy?Ed#pI`ag}uMiq%O^=RiZ&rnn7voDz?c}P4Vn+d|79* zX#juIW@^g+H`UaN{g_hp$5fM*G1t*W(E1e}534 zILj0VDHW$?cT0sCx_tTgW^XI}XldvH7XNZ|2?ivLlg1 z_Jxoj2!hzMSW|24ONq6XR?)>)1hH=!#ZhZ4L82wCGIp_rDmtZ>suD|WZHZcgPJW;J z-kW3++F!qaBs25Qxo5lQo_p@{?!{b%28XXVGyn35(L>+LqT^O+s941!G-$}JV&PVK z*s+9F(&YJXSOv=y%~XBgjiY*FjQ*jsWXvIDViBaI%4u@2hUnjn#*8sW1$2aKl*Xy0 zm?bUz9%LSEtYrRUjL|_T_aiKW>Axb$9TG?yZ|qatOf)tW&;$zS8+%aaNyfU|br&u$mN%zQGU`R{So{TNZaQIN<02CtX;;dGOVnEC zwW&E)nk?EZlVH9x&Dd2CeodgJGf=4(c{dEHRhnX0G0r@EhOvXbRkl)T*n|a+*@D=V zbIj(Iwy$k5M-;KhgFpiF12&EdnT~ME?ooe;OJaOoy7%gLB5J^yfk2a^HL%u+|2pBq>H6&wDY(znD!nr?l8~FHI~luSR$CzVpW2f?`H& zdf+UCLCz{Ah`peJdBG*)I|dF9ZmYp(yA;89)Hnb2i}8-4%-Z%E{0rA2cwNAMH5MxH z>!?PB{(d(VKBbIlTRnP^2eVYoGj8_HR;sC!hPAs)5!R>m%)r`PmiMIF3XJ}A;xFT8 zlR+y@G0`ZcM4B+aEH42sayR`Pg?4bH@2*x@<8VL&x8Vkt#{I(GbcW+j!>(N%htU?x zJNEc-rSX4uHy!5q34N=+wLrhp1I$Hux?qu`TSvb{*umSx6oHE!$%Y$T8W*N}Ra0>c?iY0YvC*|P zua44qu;D|FXDI1#HoE;vz@ks0*!iae@;DKEr|utf26)6PR02k!Mws>Yy}k) z`?XYQO~J|U0piJaUC`;Hr@YITVzdQ1MX-s;8u8pVgCB}_zxdV)1$J7^la(^I&Z4L?8!%os_A60bl|hOsU~^1SBzyR2#a{a> z_b)D;Eq@aGHshg#PavntqL0u6+H;}jH`9dPuTjfvMhmNmCmk!`ltk`ur?C=Q6$NHv z$u%4W4#k<bE4@=% z;-89f(uQ|Yig_)^qIEh}%%O6&+*Wal?C?h#PZ5@lLh*u@Do;m!9CwlI;S&`h_fv9B z(Fu*Ct;Y7(IF)T%P1fcKTDitrxm9sgSW7&CB6`KUv%{xotQ>HLGncfyB59P~+@Ovq z8-?oelu%!6V!t5*lBQ`JBK*zS^~JS%`#nTS5(G>e9*m{Y81bafcc=zliF|3W*oV{P z<}i%5cjzno{YVulzm_Np8OjbNWxG=ZjchE23&-NrJxee6k0ls#YP+E#D5VL1qHSrC zo8pH{@n)$aam)vsigopYitzs;l(KNGh%io}IOQ$!d>b!nVnV2E@uG%PLa3t&HXKOy zFu{iNret5mazlMUBb$rId@E^Kt54sMJ>C zX`i7QExYKU&^{@fPZtsYfqyPQ~MZ(oKZENo%wa}#qhDG?kZQy}lC78#w5d}Th zR^hO+tvE%vmq3B-#M{Dd>>cX>te;y_V0&?fFf<;^_^YXT2eE};zP#ffl)k5I9s86{ zUlW|9R@{N7I8lv`Vn_QQb!lHm(NBGH$ce5Mf$;;lb?N;i8(8m53zNjoSWq9NZB(e) zNn8&B9PEOY=I@Gf9TB5CiK!^?wX&(DHRW_x3UtvLNa<>74Y%n8{q|!_)=m7G^16yH zf*w_+D6auON#MZS!gYM|=RK6?e4EmK?3v@m@_V4zIIY-IwDG&b7+TO%bQAU~J56>9 ze`~-DWiMn1uUG8A7*8&}#WF%a>^JBwehY#bAeammPq7r-OSGX)r@SOIS5E6)aicx0 zzJ1UMgVxMGVif<}+ecig{jN?aeMOwHE>BeUFtn!pzTyg_Mg9|7a27u*EPQZ^0C!Le zFZF%0I0P8u5a0L~jFf&#f$Ews)Kzwnlqk@vzu3pnfE7^C-^|CemDcAoLJAxtn7KbKi?DM@`-nv5--Y4!kFR;B0w3Z%rUdQ{ z;5z*i?jLnZ;PzjDGmEfYd3Rm%86moqQg$rVF+v?<9cns4tS%*$DI~`*oEkNp1)CR- z5K{#Am3TB6@2{`L>(;mi*z(c3FseLC{81QC#{6=WxK0qRy3*>85gO;ZQO{4rVZvfp z%KZecH`t9Hd?F6=P7^UMVE9w)>)o)(zQaEi{YpVM1F8wMMuC>78*b6qMyA}?jm_si z6;qH8CZgiIjTJlk8bQAVAG>-yGFA+J6TwdR!m(mFTkldxy+X~Au7)`kyM3O!e&%2#*#x0VtKbl6Gyb2czePe%)l-C*etJOU`92=%Xu`jikZm}L^-YCc0olZ98HgcfhQ@}jcsgN24 zo3o~fGxP}!@B@cnj+3Kxbv#j;Uv9R?)qCy*M}Jd36t`6h-}yTAGJjLp6K|deM%=>L z1Q}`muvCEgqiNz*z2B8EH1Eo$+$WVyb86@oV+iAsH$ZPX{6k8T8(p6+y0?x0xww34 ztiLIvwhe1^Ed5!d@>SSpxuKl35OOmQ|1Sth#pan+*ji0rCj%190ekqA>GGA)B_ zr)G*jvP-^*3VyVHme@{MT$Ucs5_|f1xS2AX%b0S1Dq{++!mn1;c~nJI84d?;x?IFo z)!Ab6azVZ(*gz3DSh?sUZhT`Df1IJ;JpPK(4w-U?%G9l>5~ z)NkKK7)5Y~m2bdqMGWm~{1}`!xO9!@FA{54DJFWsuIO9*;GNIK>@pVKT3?_-cc7(S zSmZ}ei^U36U$a8WLd_LvV!)w?O0zBhMzd|dSUjp%l(z7e#??8D%XRsA5~Urb-cm6t z*3LmXSJo|dvvUyCLpE4ugHCo)`C{iVc?Ihh8h!%SXEnJ3t?~*T# z`9e(M&G-8+N;co$L)GT%gu2k0Zy&AYDgxVD?zZLPMBx`7id-Q^hkA&Gbjk;B*%>2UC-V}n<L&T{@;?KrqspRLGGMA4bfcgATJ zrOR6wNeA)5PWDPs@-C`h&NlT5(v&t0O}Xzkp&wRaFf_!6MjXTte6!K)xk_{}_+{JI zvr@#)tPRt}D;_2F&{|j3wPKsMl*L-NK zsMv%@OOcngXAKrI#DU zH41^=@Y}@!rra`tv}uzVE*Izv>1!{n!I$|)^mD>38fp9xtnll;RJcjpRmwx{-0g?W z;$?-PF38sLk~vcxsU)Onh*|1zptw4yX_gq&N{MEQ>yC7^ja-z>YwB&)N`Hsx7XPSP zDeaBQEp`anlqEJRC0%i^NQNz9yZ{|qZuu7-%wAt&zBPoK(1Pq?EV74rWmRDcQj${P zHLhs!XOKaB_*!gEe|#mDRWxo^zR0JYwu%+Y6zOCe7B$@}wz7MwrrbnZ#hib(&WGDD z#7VOSWyL}~H+_w4u8gxH)Vh4tLgDbEk5rfbHw!6cc;CZ)?=C{p;NmizPm$EAMZQPY)JzK2Q$quPl)ED5YW{s+(PgO~0KvI68lU63Xgrs(EQT1!FQs7$&`?(a= z>4#s7wWxEJR@uwSAt<|JfbBsCQ9AssrSsttc4EaB;-E+B_`6F5dawx-6>4MZNv3ba zZZ`HMWh`!3W@)?lsa}B7P5xGFZo@8Vdpifb`K|Z~PB0avHfc~g?Jez2F;x6R)lhva z@awaS48_Y7*H*E=(Uu*eAHCWkIw}rt*X*wC5G(lJGAbEjF}ETQDo^e^wdiH%AT4)l z(W|)nXwA;j9Mq6W=XQ$G3Rk--@iL1^%Clla(-KZL1e-~fBA2e z;p0IIh9!4##s}~uht>adxDMPL}(3E?rqEbk3P@9L1K?&q^ z4Ata{MYuPB%NzD-++n>_V}RyY(h2P9ZNeTtQ&Yl4?Apb-Jz@;ErQ6G9!@7x3<<)+%r|`a>x*ZS$9C@;)C3TbWyHrw_#*?~jHas<{ zql<6DQu2;12D5h5zyrOo; z#1X>iS9IVQy6EW&Jb;37#UP>MD~it*>)A%8_Ol^#bH%Uqm3gbPncbEU@|MIKg8dMD zzzH$3jqSNzl6S&Kx7g2aP6Q3j0-6@kw4hZgeU?J2IBPM@@xZ8zkFwk;|AZ*_DlG#a zYL$>d%lw|>lKH<8Y3+C@EuYK%Pvi1V--#jKHo1$lKa=FITYOU;cBOwOR<{|*F7cyl z--$nlmzM3H#^+7x>%F1}{drRS$wte5G=A=TF_AYJ#S|EzRX!zluWX0KomU_z9c)!b%CQ<^`ukQD3dd>ZzN9(f=Y8v=vlyXD_wA= z_;X??Pa@tsC;lp5d1j@>m>s3q#%{PH;3x44Ta8Cufp%Uz!-nE}urqmH5KpqY`2MF8 z-M%1>XXWwzv=a@!i0@CITInl1zbIySm#hQ3ShD_-_)Lklwh6kQ#r{gnvKwl;Uls=| z&x#$1W?sh2v%jNp7tPiky)4ElSa#z__g};ag}OFsZ261mEYSDAzL}&9|5dE$oelTP zMyt+N`r2YU(WYO;NQHKBWT2b>S|aeOSih9kb}{zDs~WdrkFv{$wp`V?6}M-)b5%=c zibrnL@|tEByJvf^iCrqL!`vj!2Fc>L@ga5lmLCw4#?SM>SxPq^TWLAq6dQ=wjauc2 zn}zQl)BWq%ixhNSl-YW~dpS_#b-uiy0HWC-Jo9&;up8nq)*9dO7TD4oVn4rZM30g- zTZY-!#h874KZ4wEigA)Ruq|>SEj-GCm5YDPDL2J7dSUBhI&({WCM^C77s+GAsl#Jx zaa(L$ss`*aqU;1I9+Y^X@nt!dt@U-nuv8~Ym5n2Bfw+hjZ%v&Fbcw;;3A&q#18X2EYs~@2rlONL3zr!bi>;ToTT@c|i=8U_Uggzwo25;Zej^+GMggY(qK0hLWm1O=dJjr}Dmwcf zRTBxWjT#=f-)M_X$Dd-cNkb@>ihHlN*i`rw>pguRSjo#sO`eJOJH3I-sl8=U>5h{s zToQyk1PR_K$C+r0N)w)o4P+gd>@uKvTjt|#7t3?;y;AOO7kk^k5DzO+&2By>us}?0 z#g$YW$3M)tRCC9qE_{oNbgQ&)*=3u*7huMvr03a1!Im$@Wu>6S(wU#X6ubW8Ov`Ba z%LCMeHq+8oQNwPGd+xPZu}qN~w$_hHmSC##w^-Q@q|LPS{aehO{DyUTt-NJAWj563 z(<%Rt`l_30(gJZYrB z1}HWt>D|TtOAiHh;w@IPn^ZVwU?Ds&d~RUPCcoLVx%0hcPGJ}F+iP0ed&6OQIC#sP z!V(;Meb%l_300N+b5QX-fo)EKTaq&z@;ojiAGLU zQ!efnnLSp}oH6&V?h~K{7j{9(s>Pc$nK338#=7*odm$~VR+IPmsE~eZo zF7%N*Yx5Rr#T}wTZCyK++C)?pKeX@-YN{d3k_XGzm#QNV%-E@dk((!*7m;0}e)$+f z#stqS9A*!(`?pmYokOzTl}w&Yjq7%vcgK@eE5*UC@l^F|8SS0LYFZQm``VJ*|vu8r*SF}2uML90`%}OmW zYcuaRwN`(>O(!d$R-e(Ta8!CtfbYJvQlti+f1Bcc0bZtn9nRje(j0&-)UOIl5Nh0} zJ$``3sL+oAtp@0575d|E6cqs0R|*u?4xRv?DX@}<3jXLf$_fN{QUSFaz-l|(w9-gG zci!aw^qf1&#bEYG=ycP3GK68{yz!=)Rb(6W!txumwG#WFOd8sylH+7_Zh$4(7^)h^ zkTMiK#pN%#jp|chJoQdPofSb+Ut_!1Vr+5i9Zf63SZh}2hL!$!t{P;~O^U1xu~t1- z4R-Oml@?-nef~PR_GJnBo3ybCz)dyqIDl&bJm$Ju{K5?ihyeWhGqt!c;O8);uAsrk z-k_yb0iUM9_vcyZ6TtW8spWlckZX0oD{1h)fO`S{t_I(Con}M=e*CFwR6XFkF-*sL zUJPoa&vmla0C=bdUVjZ^L4en)VBK~4v=+clD%i0(z<)o%+{`s|Rut>07kcLrs{@4h zo+#v<*Iu{NZxS}=Ai*;FN zWxtuZMl>s{7s_6v_8^ zDotttu!9Cp0Ql8kR*F->=~wAl48U9dQcM4K#Y(FH#%x*(l#ahjBN_qRRs+ujxGBKX zRq(A}>2_m)A3jn`hXZ^agR9Cac*d{PrzyZD4gCEtR+Bh*$ZQF2n*{TLXUp za3z3;tKgGYs9ik3=P~L+b98V6_;|jRTvYJ;S130D;4vEb>&sRe3h*|HYY*bCSExyI zfGcR=P5?Ur+))K*|3W)k0KE61LfrA`&zQb>Xr;$Lt5!|=1?Qyz{;mplCcxVRz676C z#+$|IFVn`>Kq!2m5@-OxBMe9CX#|#Drhs<|K*>_wH@HU{i%`<1pMNkn3w?EAH{#B8SMd{se)@Cx@e_w03XEXEZ+A` z2{-ZE`1G@MnX*n-5SSt~;Kw=3De( z;4cGz8}Y}F;ST1io~Vg+_gbdhqqV44S61Pl5xZkrp*}XZ?y61Hl??=KXj9mg`O9ID z^6KwuR^i=Z$VtU8Y2p2!IjS6Hz;-jw$y=UFy`G z4N*lq*qsHl9p|m|!S8gtI}7pr{z9?APJkRY*hX9g*MkifUSFgcJy?KKGdzb!rOEml zw5r_1jG{?|PfUJdYD$T1@{`0VqP)EDr@8vM*TE6o7> z)H#aqkYXq&nTf*3P0YuW84hT!b&tlEm!cep11l6*L(i#PPW(h&`-954yDAqKz>gsb zbvj3L24K(@3a+**C-{|Hfw=Z@01jeV3%vK7U8{SA!vrT>%g-$ztTTPAOm})@>Lc#f72WDNy7*pgq zP}L7vows20W~PkI41*zwCVa@6aHH(~kX3TuiWHLHeYO(kg{LDd>i~ERfNMGc47oSo z1-|Mx92~?pmfQ0K(nUNUg};&b`|vkDI1dz{Md3({t=HC}&{1p$<9TTfz(%pru02qu zEPj{4pWAQLXEa*<2bSViKg^=G`c^;CgU!s-{N-p?P0ya6K{tAfu71Qu;S~-j-sxlZ zx=J>DDSJQ;d?^oWP&ncDy1@sR{P|=}z?9}IXz?vHSnP`93_ihJKsLO~g4k+7Y_%xf zWmg@&K4szFB63`Q`aM58Lcn*u_M0r9ur{vzJp3rgaUZ$vy_@vxQx?O5@%!hS6g`GT zvvT-;@+OTQ!y+Rp{h(^Zk5uO?0lX8dj|pM^82}6Lxc2(AmA<`6C&$2I)3K#~412fU zV$kMcpAS&aV$UAOzW}@ic+O8Ff7Z>A$xkDgU`li&eD&o&?XXwT_wEX-VYRiuR@(pCuRZgpsVdfd?IRWrR z8vN8LE2RQ{@{|e>#}zuC0bWOi2aW(d4Dk2y$uF_6-7kU0W8>YJaz-*E^`6Aa_>4Yn z^>PHd%|Ii-o*M>t+02;40)&C5Y2zdeYvy4G(G{eqi_6i?NvyhWILKc|X8s0?DRrsp zWH!e;uPpB8@r$~JOA&S0Fv@AZ`rb<0>H2KuPI;4=1X}?4_sOh-(UOr@mYSxp3PRd- z>Y2jo`tT=j5I70~pQ!})rLZzVmroV@>_rH~nd|^gp+Weu0LPtBiYxP2I)$BZZwP1s z>U1cquo+hgh98PC|1yOq)W2g`FqQe#sETqoF%-Cgzrtxc+)swvH4|_^wY|e~D^$a7 z{3>2lZyH-9^oyqNr=eTKXYEurTgpV2$Rp{IRMyqua6?lbF6$Wdy*Xq$3(*JqfrHl& zU8ZjbeP)GZA=9t3A#(_8l?j>f0(2u9FoVqz(#z4q8EhT@{Cp;x6rNsAu>!w|kejhC zZ}}K<@ap0-eQLFNW)+^Km|3hTFE(Ko>mQ>TFIKbsH{WS44Obq*i`zK{clCa_r4i7tsHy5;L$LFxdtQu(Dy2^7&Pjk>*RJ~Ga7B&!N`s;G2xm@ElSOPkP9@(EZ2n;p%h0>d#!!eGoKJSm zxT0tv=j2*xES^&bnfcStiAQ@D`=nyj#mjO&cR`Eu$vuXg<(L|kDjuiX%P_A|gKDiq^cV_I zFp9i)jC_`})$jL3kte8#oz}t~$sw_sykdk$6VFx0^MjLgnaQ}RFt*|Tm(Hn+{SdfETxgPH3X()Cj^AbnPIz^P1<;7Ktnn4@sz7`0fzmI|J^ zbae$AA>e+Ib}QK;pR%wNdFl!t9#!4o6UA~KSx(34;h7-lmuIC;j$JH#POa$OI=_ViJ(v8QR-SgI9ern`u zHk~)%=c^HS5k%UjGk>RZ$of+dw0I8CbPWseEeZ(kMRBz(#Q2VnKx0?4nzVThTaVDH z5~ygjmBg{w>CA&2J%SMWGi9Z-h>%N1x%J}EnW^^{*;>F^(Bl=GeMGHHw__Bu7ER9Q zXSK<71`TKMOFBX$*0FCWe>GBEM2vqGyn+@=aBFRm;35d^zeF3?vvus3!x#x)qIMgY zuj47aH06QUxAs-0k2bLC>=KsI`gSn^|`u?=bD$i~;6( zl;bzEZU@fri#!8L;MGw(lfCP{7S9TY)vj;usmq+j1113LGcliI5&U%Jg5{b>f#jkK z(YIDjSlKfECL2F~z{E;Ls?cDl z#MyH6AdD-5D^@LmHdjHbL_cg{uBAzgS72cQy!>5UwEDL4Lv6}`$^3bFd$qek>@TtM zu;NSRP^>!yut#d4AlccbW=Y-amWIccgjXyL?@$u%UK&2IBwQ#BA6pXs=m@VnPpYz& zIlIk*CGLglKj8Ok=`s^3VJoXH@rSyv5^2m<<}d6zL`%1_h@n&QFn(E8({;%ox9;*= ztUa=V{4?9V%0V6p2j+3*I+9cV{2=bKXpLvHgxChNa6HgmoRKHvmc`8mU7ZqiPzN?T z_dth#A55dNnODGk__Tmq$J8FuGwTERe?MH8%zsDcP@ioq#)-?R2;QSPt>4C~yC{Oc z+x%}`aB{#}nz$8{Hpz$R*)~==m`iT(jk<|j8aWr8|K@fX8b?INtp10n3D}m`&_Z!1 ztPPEFXjnE22xwSJBHog165TpT8?#xYaOogj$Y!^N2RU@$Yvvhp>X6loUk%55HTjUv zUbRWhOEv1YohACTuFiX@NB7nnGh3Hk zvix2{UBMwfzUf|#_HJiU>_xOGwR1Ikyq$e(%+JUPq%GgF>aHU(rvDIsBk=dZPjvfR z){}L`_bxwCiyfH2YV{M1-@&5g7(C;>4$b?P`B%sZG~Iw-6zA3MSsxv+QdLYx>|ld1 zFvI@rZadjBWA+7z`FJN=QZ5wm9nkG5`VyXz9zQ_K&CFLgB$C<8dI;;zQMp~Lr_Wr> z7tFyQ_b+ZT^amLHl+T)ej%Ms)i&!#Xea}(AZm8b<9L4Nr&jN!%TfIcy3+Yw)tb_bM z@)_}&t@xk_4BGEu&6yqrb(n+L!@|7&-fyMyn0v%2b-Rb4n{N%oa3EgX!~UGS1JeL1 z_wu;59-$VeJwC<}J+^zD6{>N1lajVzA``do70CRehqx${{P#5(zw7DnTNfK;`Wuqv z@zZg@K+kc4jiz87@KCObQI|OtjuM|9TcFe7;4MqA>AM5gDr77C%|R=n+s)R+I-6o@ z3yYO^*+AreQ(aWJK8l9#V-YccMF8dwZFmy$7{|szVC4p6ggr|t{-)z^26qL_Sf=J+ z*0L35Exl{d5Bpg7U9VuC7n^mrWn1`Zy9B%l7vml9Byq|9G zM{gOYr>X~-j|c-Dh@!*;EPApFbhX{w$VuAk%WKoV=DPlm`i9u)>tv_z=f(OO^Lecq z4q_KW`~iwQhzu*{0JS@ay%;qQ(5DC4M*ch?hmB}?W3QFwgCgJCv&L07>N-xN;9kxx zhm&jy_*jT%N;Tog+*i{voJ6N-a(antlR{%N=b*Y{j~%9SIhfyaIzTUTm`|X$J@NpZ z=`pUHxwk$}MLu+xY9C@Pg#CwU!XeB9U9W+I_1Gw3{9cMY%%a2!;69k%J;Hi((2>Ke zpU`M8g&jeR_+>x!Ji_`aMULRPbq@s`Wl>F5f!}>=p;sDaau(u`n|K+X@pBsa_a*qw z=S5~|FcW_BT1>_7X%<>=l*LDdqssW0ncr?7hVO@j*xkITr$9m7z*?re(BlI1;N@Q9 z&wn2Y$1vmMvCkZKjP*ANsXx%16KrswU|4jIp#j{aLRJ92?>5xW)EjWc8se);NHCpw z!3lX~c>?}?nw)t8%n%wZ;Rxl?(&z+`k(&(=$sI}kc}Y;xR7?Y=`iGVG;c z-?78O**z3_l6eXp_E3wHtZGP3kSR4U2z?u$m~zL&lzUd4=Y@nd@%+u$8S3qZY0r}^ zL#Vf#V!mfrh4eGza|$8*@-8baIzvhLE;QOhGfuH?P4Yo2DA=S!-)N)t#j`@f_&xtF zXkp-A@EZ2HH%*s01a|?hfO=2R;l0G)g!gKZ?`iN^vWpI%X7`0xxXk$sCamg!&mX7h z{ux#S*W{4z53F@)9`xjSd2$FG1(UtaUlw|uz`P7^KWL&BSwozB42T@58eGqQcG!Kl z)oTk1*oOJM#y^IHO5uNQ*J(W3wTyhTT^H`cP`|{Kfu45`p;^}!CRuB1OafOjQ%g@yUND{%xq0aDz=?ay(j=%5RXhR zu*H%m4%^ShWoB)S&!msfvFb71tC{XjLpqkAGwqx>anWmOjn5zN=`$(MXgSeR>8*N{{6@+Y`+ zuTvCx9xlFQr?u#w#{Lwwe0(SMyo{Nz zT06~$FS9d(F&XJdn0Z8c{`Q6&88SF!APL!Hd|8m7YxoXAJUdU+mJV{K(Gu^Tn)7>LF(=Yiru!Q66XlS~pB-p-Ln=3cS{No$S zy~iS?et-p^ilOKCSlf1=eT^k{h_wP)*kgllR&qdW{lF)>Q98Y@b2u#W99BgKTW5@f zx(BQxp5+u4)-4otk7AwT#=kNw_t}f}K^`S{e?yDzvxur}2P_Fep5ku{lx$_t&8>h4 z3FkAp@lcOj$IJ-V&yfn=xz8{gu;W>T+3j~0XB5sJqoju{+VLo6B=}9$hmX-B{ARDV zVV3q7oq5Qn`aHt-j}U3MYa8et|582RaW)Ohhb!f7qt*Gq+Yh{tf%mPp@^s-5$HV9( zn_?cpz*v6A4yXVc`-lYzEwgF)BR0p=AB=fDafPO2tNl;kZ4~ntwo18X)1<#JrijBL z>R;?D&-0j)P;ou88fds)+o1OW9%Y3VbVCuS=) zbRD6M&si9~c*aHwr;bpQ7XXL=>{kFw1=5~bzQV}th^*y^*MV`71~&N<+t=Expd zGq;+1zG6*`*P(DG9p z)m;`C#0avkfY*C!7KJ%V(ZYyK>f9gnmxs<^%_b&!R{t zsjE;ilV&(c!G75T(OnF}-(Wsk;gv9}2{t@5HRTS}(Ge#poc*=gN?8Z^;-VKhI7@!Q z_3~8NS@N&!0g?0cFQVC(JdnihM%2r0hV4zDrc(024%GSr4R@9zg*azg;S59Jb1w>e zUd${u$xoaR+TAys>4CG9D7bw|F)mUU4=$Ufh}tqNM}yjW7pc12ILK5B*)hBdi(4*q z%>|_KS?D79d(W^VJxwFs4+SX5=!&;~T%kgh%{16mYOQFma46FLC&85Q2NtY5V8I%g zrDSLZC}eo$Dm7+-AbD{=HF1+R30UU5<0dT;lHg2bq+{N1(j0;f?iM5UDk}w*Dc0#r zgF$CsEr0;48>ELpD;Rm(hO;eFdq7@~m^2qG#(XNDbsqGqBtQdNlHh z=t(atNF#(Xn`xL29DV3!TIVD65jujTuQc8@3bnv}#~DSA?x8upQd38Wm$470Q}ixN z=X|B=@}C>5l(7foQr>m(AU{8;jZnCWhWSZ>4&9p-=-Q;5U6MhI{G^usX2lg4aP%7b z`fPo2IptHp#p8Jh$phSR3Lcom!sT?p(*f@>s)gg~V%<$k5)q`3n#ia^-l1?jJ;?J> zk_h{8A=hl6t%8Hk(xsA-{_vNaX`sJUP1v!C7Wqpdu3v(h4(%wts&04YCOYg7OQzv+ z!gnMeiVcvGg;ATxHBs`S-2u{jLdQ+CptTf$SJ|XiLcL8iCs5ibxNM@RAZe=b$41&2 zBux@dZKN~7QX~xwmWBu$l^=`9xw_;*Y4MUs<3gm5gg&VA5NU?cNcjw-m7!qevyrT! zc=#fN1H1F&^j5kw6YY{wK8zH_TQ}sE+*1ozie)2L9LH8 zeV$6+06ux>8rL<9El7<@Nou`LsS^d4*GVnT3$UMB>K2#FpnxjUr^1sBw6uyeUO2yj z%7ug12{;7jHSB-jwE^$4++SOg*ICfvygmW1?Hg!$ICw1qj|i!SFl__%jF46fE!Wb^ z2&tXWaswq+1@9P*_Z7&U-t<4{*)+DG87{WyU5a-z&Ks~hEp&@3Z7`p$Dq*MZh4t72 zD>X^Xg<@R6A)HC4|G=bEY=JQr$2_H%RM4`XmV%zJVLe@_4&h0o+kn$;`5)-Ej4ikY zy1Pr!UCRv*SThJebv^Zolv>uc`A@QE3I7R>$JuXO*PA+1wqCdRI@(q`_o0N?g7)cj zIZ}#9?5>IR5;pp;Hr)Wa<4cLve?2a?M6iiiPX}rsetE1X&zjPR#1~MPn{zp*-|Ii9 z-7B`BVyl!SpHlRN^>n5teE!lpLaG|o^?Qx(2b}JIH7Dr)xu#?_omZ+OwqR^?oNlp> z7Suw3^jS*}z(X*tqmU>hNki7qr%_V7MD7w?7e~&s{eRG_0Y07aocEAC^WyN=D9^*| zja3v`A6{xrrxEp~u09>0nmg96F5&Eg^uXAHKwaSP*D-~81N7=k@s4dd-S4x&Zn75I%T<}OYKWij~8HB_&6c8(gMO;~d+#7@8zbBmC%#+2x zC+yGUbIgxB=`#^t(|Gr!lTyyEUP&WjrTF*xvwt&$VNObt$I6n1cn#q-Lzq^_z0n0K zJa`?sLTKIvZssy|ip!+fNzQ&$KThhPH`9;rNba;U4vE>Cm9!^L8lhjPK5G;&#R}tb zmukGUNZ*A&^P}ns(r|rk75-%c-~qTDH9?vqyjrDpkEUkm9)DRyFPp*bb5~Kj=IFCB zaC0f|F7unCBb&a8l3Gahx}egHsDeAQY~oVXe^E?kuO}tq{{Lt|Z6S zFvLz=$l4mI!P1r7T9brN@jDUyR`->}-jPNN4OjAvqpMI!!4IJ)??}xArRQP%jsE? z^gsw&Zob_KH7gwbg1UA=XZ-6I=CfU-sd^y?`=z@{wPT8Hl&w$p;QTOiIA7Oj2`rqrh2VHiS%h`iqndlV*O=W zQ%nnUFw)5F`1fTm$uF@op7X}|9WR4!8CF&}X^k;kpXaSeWKbkR`hl*uB2H{y?A3ANiL;VRaF zu=BG;<}(AOrGnuzU|bvT6l|XLo>bpx^amoP_{)BjH(cuNw$TJ35ioUkC!AYhvYIDP zc5>HKpAV339A0F$ejx4Chuuw66xod&VK)Nc@H`P)#}gDsJzMZOU=3lIhP1V^4tE70R?<4jccY*)0$eEKE+p|Cg}V$syGD7V9cuMnvzsuVM&U5D9$>dg0gkB#eP$PfRn99wYVF8*V`wCCV08?d!2pP~urU=h}S?+B~y_ z#A!C|f_S{w`I`8rA(_jeW|jlJQ<9#{S7cFexpr65Xz)0xYP=RTl%i0De+ub-b|j2h zsVM$Ssp3btv4E>f_oH*;q!w?b1CtbsV$3=UI=f5JS!<)C^P^tlF~#vduHGDvX@dCq z=B?v-lPjEO-ZKGXejy!~icXZS3PToB?j-4e@a=q>FNKyU;thGFaLIH0O~2MsqmiynY{6O#cY;#{#6H!iN`DfNa(4SX@=1}Bn%WG_hg5Il zH6T1CsZuFkF2%fPON!LMl@n12`=y-4g`a<=NQwV1;e?2kq(^g0D)IAzA|+_T6zRM$ zeE}s+MFSlR^G%f+3dvD)WUBN>(vxkk;U_}{;0e5&A)osHf znDbul?+M3oRF_i#eK$=q3#aGs*5G4anJO6t&+EWRH@KMA9zg~a>Vh@u*n%tbY3B?n zI%M@6!0@aUc%(ON+W>3TNjg7WC#4}Hq3AlFTxUx05z~QJ#2@(8fnW3+^8Bu>`%r*$IE>zFsM<&Pd;er6~=p176rGRp=yzCK_y{VRMG>@X^OVN(jS$K|To9ED{ z^QBLtuHtu*FepC*z|!z#LJFQI?_@g%O4kccu+2 zMYzpe^TvhJZGGZSD8dPL=L9hV{C^2z1UL{wi%T<0N}4l=E|`!;q|PL^NQ!Hg&m$*~ z(n%px0J68>Ej9f;S zj^#+W=LnU4pD#Im+%@?B(ns(!!p*CdqVK`!17-$&KF`5<=)r^cEVWb~@e4T*_y52H zef&W1a4W^*`D}W*SPBu^sr0&z{2y$>d)fRMB`f(7cM{lSf}Krhreg0lU5f2tvFkOn zHIK|T*z66RQ$hQ@N?XC@z2<&S8?a>1ru-d}w}JcYhix3o$43{N;onKa49(n9l6ICN zy?QqFSt^AXKEZQ^px6IGuxv^al_EHKw)yf>>8f71INiKwnY2_dgwLj=<zyb5hIUlfw_rqL(YAbxoqC+r=MP zNr&>)OFsjzDy5(49896p>GDdczoR2yJSMJ8rFNo2U|p~%Ooh?8bLTmlUfaHdbb;+V zNItWD2dT%Yw0xBmBiu@*1MkZLRBgQ!L>{Z9?m|>5jaV%OIPU~DXVMCv6gw2-u$rqS zqa!xUD2y_-f_bZ@-a>S$xyc%Cy=BwrLb`NY=rfHDtd%@{x=&NZ5+F)C2Bvy^a%&__ zqX%nYtvWV1w-$$M){2~Fp0rNFOV-C{(B<`zrWX*oG=EODNfWd|ayGWZV@j_pd7E2p zkUR{+{i)_Yo1{pim*W)Pk7L#VvjI4fR(Z8Y#IsE%$6%_NA$gcDZIMz0q3RSu0Ut`c z=iqEk*(%i(B*ZMtY5I^k8;fM$Og2BrmTnt8$4=4+qRx!3)y2_|CQ-luIgqL!lO-y% zQ~Fy-2{5~vdBVRoMV0rLiB^hE;R%0FVR}9mB#9Y7vt!{acP0@(>U|s6A}(<3jzU7vFBK9CmfF& ztc=vJUTncWoo=xS&y?YO{tm|=N*gN4=Cm`?Ko<1zIJMB$Pp#yD@7(fhQSc}>;rxbY zlyk|+o6>GbZOmiOOF?>J+c@*`3(_<_H$mVfZi06~oAaelu<|;F`uq$N?8SF(G_0Ea zEWHrck2RmXEcI0iRlULs^&F!XTKqB2*Zfo+TBZDoq1CRB2}7#@^DX=^2++G6vcbhB@O=n856={V%@7#1bbPd3>AYJg-4rEw>2ag2^b=Uy zN`HpZ*?6Xu-g#T9XcY24q7n5Rq72ek#9lfzj(eLRGq-}ywZ8R?)K%E~+9>V7znuk3?cW+$vAxc%N;0TkRb|^y~ykJ~Q zglwc`kEL$|R)ZCn?$QV=)y8+F25aDyegTJdg2WSPwNa=y((G6u4VHz15$4f)IhP5q z-si2skDAhvF~_eCL6EEo$~Ynn3qR9ISsQ7FgFb^ z#{3GH(=^Ooj&dWx@C4ARHy!FyH5a*!aU1Yy|&*T4$$CB4ueQuxX- z!nwgT-dFBwtN^l0Lor2`?<-d{%C=v1{P62Js3|rwf9xlx>Rs#Mw@uAzgH$zp2gtoW zB|Cr~Hqhzxb6*amGXe5dA!HD34U}^Y`2+Dv^jyUJB|-8Kq~8@+?dS4a6B;Q1Qsa6;f1{eHn zD>Uv;i)zS`iQ%vX&$Yh?{d8Ohp2Lc#PjImXmacHZ4L%J)d_y887|>!;SxVA7kky9E zQ>EGi$g!pzVaV%?(WQ<83hsl70# zU{;Q!(*>JGpv&Y&<-<4uL`Nml;aYN{5YeApqvVjp`M~7{sPR7-prT_+(za4OsXvX6 zl6wj-`q2eWx0gouZ(ga$`EBy?QIVoYX~XiI-zg<&Vkx?V`cr&ud4{mJA4NukZh%HN zhtox_|NqiO+ir$DJhl|wD*Y+Cj@(C>rPA&AJM`yvnE$`fMb7L}itbZxNAO%mjqAwO zsBT@ks?bG~eV4|g=fCjCF<>^!=4@PcB+r-oDD|7h{eU~$;eK?cE@ThU=uX$@RxYNi z;Bs4YdfbWMpj##-X;Ue>3;WUXXt_3jFYJeCIm7dP=$78H%WGzBL=E!|praLfMIuw~Wb&#Xt1Guh?eD6gRY# zE0jy|QfAzEiZO-hEWyb>^g~P8Q(1CwPdR&_Cp~B>cd|{VbJF^}O1$nYLP{9g4fZl% zV^yu5P=pmPYE*a^{=r4f3!@3G}wC)|bwrws(Q8-;KDg;%rBZ1W%6i+Nw zJPKkciU(C8uQqbTf1$%C7HX8D<7G!@S{u1&ez$}?u_fiUqfe`m*FT=P%CUJx!V>URF09Jx0RDh zXc82mxCyD;TqkaD}hBmo(@Sn*`|*G`F4nuAw#%4!-Xgz|gS-gScCJxrebf ze-&cAAdzzF^%<&<23GTY0qeDYDRynX|#=|<&Y(((`6?=lqmjvSGAP5V8C8zA&8 z^`9QDR-Pg%>OT~-A?P*qrNq70lcGAxk%mK{_wco2c;ZftaCc4^{jtqiiX5vnVYH-X z@Qh2{O4=c(Ctc_$cPyUsQmWEsNW729f7=W>5H7K!6oFL`M5#($RT`dz%*_&<5`bGY z96a^i)w=B2-By<=0Vc{Dg1k4Utt=XF);4Z(MHX7Elk8;74o(-TVJCTq@Te;v;|EA+ zb;?7p&d5VvcB6Kk;TVs)(Sz?X0Bu~^p`Q6fXZZ`g5bLk{&WGJpeuKNw>aKEMyWo(m z4^kA#7ILa8!Qm#7fvH^;OIU23#V}YBie&3_)u>)Kxvk!ruJ@6BDZQHs%#XZI zxZ1_sq_y3x5L<&&r)g>p(YGQTUI7P7n1 zj6QNtV_hIp%1);W^miY*lkvMw_?i5>4buk7cY``XIgUO*2`2<{ao}!zC>#hfNAXM@S!NHCkBR|5 zfepuX?T9mi@ZC0Gm<-(J9n}Ft_Hfy#cdP~sKE)H!kx$vg3#U6$yPL>hJA5E__HM(0 zyqEgpvvWL?#$5dOP4SFIUUaHRc^}}O?`EBOHty-u1QPMHWo*h_=%7k4qyx{+BdOU4 zxsA}e1JC+>>8la)CZT2rbJq`Ltnm)(NLxqBk;086><*QWwa(`5!smuz;52=D4dqh^ zs;PV$lKDH*2sp?YF0_YuT9V8o_yJgfm(c+?`6&)?4w}LnLK|5sUO6m5Grc6uilDi# z6wM7bn&~)qWwiYIA1LW+m6Q&<{N67`sk4oet`;r)NS-Y$>_9#r!@Hdny}isGKbD8< zg)CIWC;vy;wa3X={r{O~W_Ra#p0#dkvDlqmYq3}?R&HzTE;8<`2w`faqFlOAZaZH@ zE@?;d5ye#Pf?mvtxbg1>^hrSjEzF)PlUv!IW{3q|i?UOdB9hqxwpOR7A{ zc2tP&OBW~EMhW4l;O8)LJJ=78#@dz#T0lq!{?H88U?c3M-k}*hiwagU@V6v+imi6U zD&&^nNTViGY<u4v6bHRVOYV z2QR0Vjb|YxHW0Ta)tytt0Qx6aD65&bp9c9f7n)&Hn9fx2 z@+r2y*m%f+qZ;L=akNs>Bp^-Wev~-f_LT5gZ{L#Xwy|dNPOycQ%TBMBq1GU>+kp+e zLhGo3PO-NY^>o`B+#L)QFlD+#tpQk~0Zh`t9IeRbww+SIvbCnF6iXLR17%4a-8tX% z45jQt7FXsa;^tCsx2=AKX`2POT?V+dI-H}Gulo#}*(~JsA?HjRZm8_TMq;tlA`z;M zqrEMR9-n3FAhhm9YiHRq1b=V3ILnqS4D3TuFW5$RM|Yw$A?|)c%4Cp_3*B+-+zCtP zAl3I1mKRoiAs@S6upJZp;Y71-?JfRr58aw2)ux|kL$8IeqK9SnRK`+kJCuc5{2$H? zJU+)Z3S+y!jql4jwuwSet(TZhZI~XY-s;!lZKHI9BdbC0>JduEt6XtRhr5k${yf{P zh#uGU9+kcC1~m)q@q_N6P^(cy4a(E?XY{Bo+C)V6(hIFI>8^;}GFKZA=LaD+(-3P_ z7;zsE=NS;63POz55qngW#*t{~6AXxhgAo6wE{kn(WxCrxanRb_o%4VJ%Tb0!XI`<@ ztr*f8AUO<3je?LmFSgmcRj5|8Tex!?8jvcNA$c|_<*OLh1z<%Pux>#3bO~8XXJ4_! zRt#$v?744r3zfFhL0Inp0V@gp=4lnHL{~NUt5`*71fIvZjP{_esz_@CQ1z7N1XWLM zPWyoLkpYRD7fPrg^<|`5y=t1aL%x)}v^H>8#F4GsIqMCGi-Qo;xtw(?LYuXskTC3qb5? zKx`F+c=R$I946QIwOeY-H49JmpcSv#CZ`SH7*MHA*pTd}|HrOiZ~Z?uFrE5;>;`u4 zLC$5iQF(2UlakIa223wo=zcCK;MW9x&4RRB-Vj~U^}qLAUo-lFp2bE#ljwO_^`qv? zZTCyh!NJP9)Rh)4w>^$&T2Wj2d%5kDa46e%;&t0Li_oJhE%Mq@(*`4|cc$Q3y;|_F z*;E0Pb9*-1vj`XtsuzB!g~!9si#VTl^7gbmqi6{V$f`y20hHCm7t3o;dld3vKTdj&n4TVCXESNW23v}7ER!~DK;A!g4$9jhdOkIz?V+bd z*q%(f&1rpF)+W(&AUHYPg@)uQdUAxV&h$;*Xmgr{A2NOWi)`<){ij>-; zE16x-X5d122VHy*t2~s!`;##~*EU-ftF?b8=oTd_q`H*91M{!+PIP()RvITed}BYb zEwTvPGt^B)dq-sxu@kvY+D7`m-VHTHxYlA?zAn__uL-aEwk`bC)(w=rI2?Y zRyE&J9los}*`fveZh$DY-tIQthyTi?6BE=L`|nVT_8_Fnaaf9#j*f_+$WLsW1a%|q z7=P(goQYq_ad_LEUVlWg2}|13=})1mITEPO0o#9sZtZBr0o8r-fb9iq4P>L55V$|H zg>kewpV_)t>*y#Fo~KaM?`rLNJtHuaazpJj`z;>+3NEYiwYYgF07h03?wr=Zbp@$) zbx{7Tvgzb_b+(}o(VN`1$#9@UXoJeO$xE|LvU9I-KRybJSMyqzTyzyZFwpPA_XKmBX zLi^UdtWZ#MJ0j`p-um9$diY^)t}(T^VC#uvh2t}Qc^7PJ&B{u29ruycR+M_t)?9H$ zVwiaVEAJVAX_qOi6F;ww3S9$1rAtb{M=-tZDJwF`3!vdu4oz-$5*_%cuzPC;JC&(-; zmNhj%Mh8J|GeCOMsNe_N{D0yBZ^qqd8Onpxt;=}u=#REOdD`OqIb_W?nNty;?NfE? zxiz2E!k#TB>?+vki#4hAa%413yJX8wb0w)e z7U)yDV4jxXPxhE2u`a8-vCwah4s!b&`hLA+!(%d+TJTP7{Qv;wy?^R-<^|XNZ&*yEZ>B(Kv?jT8A`Mym)`G%s+Fl6~yL_`wp*@tsHAwzVGlg}55`G9WxD+P4 zOeb&JHkXUz2*t@xcIUiqz?r4vIAq_Uzid%~rNa=Gxg$eZmfZxlvj(6RI*>b(;&0iO zluM8|6lWh+C#o56{sLc>f_Wq9k6X4L&QIaN3?BmqR+Qn{SOB=(G?ZgsHuuddwVk|6 z0V{DBY1CyE7K zG0VWvIJhazFpH^Wei$E}O=*`|bavJogf@(!K`4V{zCK9q&A>WZlhA^%)$_t2*E&d2ao6E*7 z-zT8M5v0u(u?(>`=Z&EFaM4*Vj@_o<={ReE^QHmkB^}3Zqj$o^bLHZ=LUDMT_CW(q zwvOYn(V+)J#b(wioJLjspM@dYPaNjL`(&c{p0x|YmTZiu6@m0c3I0eLDvPNC zzRJR6_Y`%LFC&FAWU-Fm(!%jo!W(Geb+vH6tfiOLaEliHS7TqFNO76j`g9|Z;+~9I z$j+%!6z$q#i=w0`aXHpHU5z+RjJdIzWuL}$J4y`fD=L)>u~jP99i{4a&}&8mFt}24 zSXQ`FA+}Um>}~z6A#!x}lt`w{9=%hvZ>T*AzzxEwboLO>x3KzaT5N^x$^JH<$7G=AYnq7VVGQ z8;%5Ta$z%^w;B#M;C5*)T+D2)GBvU`ovLD!ed}w9>jj~0G7YICb_gqu@{DUl%j$^N zg>%WYu&$UceFeH0Yey0ttSjynmS)l`^~BR*_R1bxBj3b0G1e>{PU2SUxcM>S#Mxqf zTjRyc=7zHy`72ZRMq+yw@0pFn#=^No+R#W$w0?sG zYCbN>wy{-&Aa8{Rk1%scXk(qRqOKoh?3%a1)+^you#?b#K=d5$HR|jY(9G@ai29B<;XX?W56z` zStj?9CjdZ>!?s#fB~xr#O$qj@!Fv!qFb+>}iJ5A$V%0y<>^{;(PqySKSfCVVijf02 zsmWB+vj9QhjH1%;imM7)Q~3(^TFTer;6uJJ&Vd-cSf?yLD|zFQUcs{0^2KL~51Xsm zn+2?&%q$V67W7KC*f@%FQASsoK+UPcCQvct&ld0LtY@!v5cy_TZ8dunA7)jJq5g^u z&GsDlq-5)er9oZA3Bvbv=|ESpj&2ln3>kEVQ0K-fTkPcZp z9n~JHZyoxpo481rSeF)d7oC>+$V4%V`m?)OMW|ViHuMzZsL{Qm-5G%()`!-C9m;`R zZ6M^a*TDm4F%IP7Yf;Lennvw|1xsU;!yYtfR;@>i?iI82=AtAu;q)z%3U2kQLV)|Q zUy%&Suh#`zl)$9RXKwAg?C!ARrE3eiLCF6J*j&EiUv9~$w3;3AGe7`N4e$J31 z=$cb}K%hRFU+5%AeeO%z076& z!O>!cKlN1MMo*Z813$G4gy9J7v0h>~p;{e^>x~vSx)u%ZEhaj*YxqMMAErtFiVxEy z?gdZQ3N85FI&`47m?oTvrQ5y5WFa5)_Yu>DbG2!B9}HoW>!^m1$-D1 zhWwtdL)ZI=sfqo8$LBCzX7wDV$>gr)#Hhp_NOhZI`&^Bl&UI*XU$JdSy}IhD^5Iv% z78A43T9}O~*dRl8oso?qAO3oDzOUG{w=xoQJ69w`M>53)RR(6*Kgfx`x3 z@wBj?80*}t;XlIout@yZYG-?6Ox(T$jvkkLtuJD!pugC%Y;iAy9XKpmCYw0+-oTx6 zzyPorgeZ)4#Zk>1v2o2WSTLG{(&n&8fC}*ttY~M!PqBAlij2OWH-UBJPqAB z%MH2CjHLrPVycs+p4nUqws{*?01xXpBOAf&+JN^+EM*P=oBc7sVFSPVDw~^Y_=g!E z?AKX$*Vc<6FB@mY`y24vp&AENl+F79kZu5o10gz_AH7d(5G5djX85uFP7E!(PfSa_ z&RlJdv&_xaTO`o8-**;%%%S)PRnx{(y4$6iHkN4ar?`X_?4M>~>-ai2rE`M?=|pY3 zS14{t7@zQ8X2pnBqKtQo-A5YNq^Lm{J6r?Bddl)>iTg+`&2NqF_pbX0?haGp{h<4; zb|1MB!+srM0S$`WM^6=lVaLh|Yomo7Dkm&e3(NbYoWO=!;D_ae*|o48<%HGN!nTwXR!s|A9~zdY zSd`0J;G3a=N|;p(TTxC}DY(mAqjJJ-Xkq!~gk9Cb=0@lJH@kn(0%w$y@T?X#rJS%6 zTG%t?gng-nJ!uT9g!=tl3mg^AtK^So!JxWjuttk%eY(f|HtttIuZO;-D8bd%V=fAE zJMQtAx2kSaaV1Z~T6ADI)Jg%m%Ls9vuqB!g5nC~loN-K`U+yB+t??uW$Z zg}i8L|FGC*gwhr?jiAKrO;p>Ay}t6bC~XHeq4i*IR6Vrq%!ec>Z3l6iZO4Wnaxl57 zdR|$e{Wn$htOdCbgKVl!QZCfD4$z1 z{R#<)yXSpmn`QQl12pfs7vMi%N-+j;*#A5DD;H95*Wl$B5rsklbEe$toS-cRzqabg zeHN4dD>Z1tNHHa5Ib>l~u36dpF6ManA6K2Oj1*&AzszAX5eC(DD~I8KH4w;r@FG+F zI*<>6$8na!kH*)FunT)?(C|mZxSYSLDYM6v>bm_y7DxsX3&0$N=}Q~e@IPPyj9h+# zJFvN5-|YE8#VMRzjSfB{CfJM2#r2ir*}H3)7VBh~ET;Rwt0J?%K2;ti)@od2HYF*s zHU-6ELrNu{QNwp>l!(_p>(!vb zSH)zi^_XZE$oz8p_sl7FJP;9}_YVCDQf=j zFu1CD73q5!3gzy27W5)j&@oSg<~0)Q&P}Q+!mh;SalSf;eL~zIw5m?+pA=(-ebt%h zWSaV<7@gX#N|4n8q`o$!AlTxe8Hi9yhOlbYY1fljmReGsqQ;`sy^)a;X78_-+Bbfz zxZW%vUfg(OcoB6vUfgfqO214OThS*I#PL#3ma^PRo*vaH^C@wTP+XrrdrExOD#D*? zO%q$t;-|%WJsnAkkPod^CIkt1GNWK-C8fw_Z2EB{7!Vwe>JNmw)$pDOr{V!}J*xc- z7TxSgH0K$ylkh`T+W(9=TKJ+WjeTBBqmj>w@p6%Vs&QatTKKFuK;M}Ki}SVdIA0%+ z>-TWyd>W;&IbR=-H-Q@*m(Mf~*m{RmEp^SnhRy2AlsZxD`%jQF0a;*xoEHSy6p-HI zU2ay7L=y!AFIS=i6UFwnUX?M?KW@gel+TMe(J@Kv=WLH;EKuJf$a~1lDzHMOrUGMC zMiHF+fZ!bJa&w;(tI&q*v%#iG;u5Ez;jLl3k1K%pahID(z1%rT2E53swDvi1zp$$c zv%RYXwyM>1f;>~iXhlnW-hCu1iZ)CUQ^-15Y{SN3ytYzaC7kc;&e>8av=Wv>ob^iR zv;`akr*22m^vPnO@MR>WOc94!^SK+DKShjHGJM*7zwdwXi^E zjqGJS8%@I~tHI*X8niy*&S_!5ss);q8Z1ttyjfz`m(AvLqafzEwk3^QmHr}0&wKt3>Nlso656v`k7_KFu! zpnQpry->DNXUF0dOCx^;l!d>#G+qGAcEFf|7W!6!9FAi`S%%IQ2Ron8=!;_dHd=1# zk-39Wz|p~!fnsFZn052QqwbuA2H=U6==N;vF}0Vl(Ni({Mm~m_kO8J=5Pe(bh!3TF z3lHyVlLtJ!S=}4u@t&{a$zvYx)%XuL^M7(B%6L&siR=tOj`JhpsDsd&7saVDT{wxQ zu3BaF>nce)R-*K|Vw_~SHLrJZ9VuI4I;3Ruvi8AMj1DskPrf>!m zJN^a+lCjuP7em=S3tZ(mJdh-Byh8=`arYP8=q>5YJh68285{CGWVz`*l*Ok=+C2>b zzPzmqpCr-z`bZQvU(ARZu7xGsxf2L$C(%>$#U;{m;B) zY2gAfGeybNud18XBFjeNVw>qcu5unQiz~U0OcCj?1!bd~N^592bDzP&Ewa-kh4qr- zV6R@z=Qp7LT%DzkZk9Tpdu+7iB}ncvkq+V;p)0BZ>OvV+GfhMC17DPNJ9jYftiR%okrXJLhl z_m?Y>`^)Gc-0qxp5usJ!k!aB(aarm@_v+J1 zA+LyW)usgdpRePoFVZ~t=Zy>YM+>P58f$8Uk1jPlW()%-c+k=Zrr@xFT9`gC1&8(3 z!U8l|>UeU>@~m9Q1?dA1&IHG5(ie-}s*OgX;OqWINwjdW*uH&3#N(^|4kMiRft6_s zrX~3zte!Dli7x{#ImyP4xh&95T~JyCKGl!(r^}cNSCtO z$t=7l{C2h?mI3gYW>1G;Fc8)@*bM?(!Oe+3vO=Vln>kCU@@G;#@_WTva#dQ*b(8I{szx7pNpW>H^offCo9B8m~*NwYV8#r!mV)H@g^o{uY1L3grng+)l8v| ztFVc+H5?B=BV^|)@e|8)C<5*}Xh!Q-h;@A>1>%E(a4?Kf=LzqG`2evNH`)sH@LS>@ z$!cK|qYKZOeW`Cla4p+G>xf&CHE3#I7?gO|iB_S=%88R{{K`sU!?Yb|)_qWSMVh{V z?RiCCDAM(Xk=wArU{>loFyY(`Xij57-22`_ee>$d_`dCUjN*r>7FvC&h2mdkp|X|l zY>%bv^!=Zx9%89uC48w6Sc@^`Gd;{sh-!8*sXp;rRA$6sHPhW}zWa_6CaZ z=)#g+f@^v1l(H5O5Ec@&DzG=8nVZF7!b1X`+bm{CRgniThE=vu$`)}@ZLR+tifhI6 z{?m`;sa66l+ajKB+X1-Tf3?GxJBz?YtAJL;6shpw~&i+ zup#2ZFg{YgM*M*(NJO-#g?r3&wvtqbwr&?66S|dB+zv6#`VphJ zcG~Wx*LR>lsZvTec8Kk*FR{0B$fDN=P_X=!*mkQic|Q>G20N@`a6^bCPS2?Z{w&!k zwx(Mjpx|^3@ zR^j{&U;C5daEq|<58txWVw4a+2hlm}4}UGCy7 zF{i=z>)*>_uE!IKTeX&uYOb5QkyS-e9*ED zuFiFA?SzKEQpzQ9p4D|7EaeN?zPcnPS^L6;En-^>A@e$=UKS@;{_Gdz2hroZ=8EyZ zbGGe%U*u2XK66YLJt*ilhStAOYEooF^KTS&MVxK9_ZnE*z}AVrx+2CR>Nk$-eVlI0ha9u57l&Y`Z3Yj*9q&4*nu0Sc|k18I#Pk zaEF|Vy8y*XX^xJ8-3CY@b{EWn-3G<&hg;iiP~61=9sgC_ZvFHM@>eeYEc#6h3&6nG zB?Lxy>oB?-FyH?s-c!~ILA;90xDJQELb3X_*c+oYVm|;go(V z+z&yQ`F03i@_xc*7Yls{(j)UMtWCyq64k&jQDbuv&}gpamC$+V6| zPUpuO+~W*a!D1!Vap(MaIkXxNU!g^2X)HNzh=FT6LfUC@u(;xh2bf>&GGMG_TDYAS zr@#td>eOAADOS-#z;JmKyY-G~4Zz+ofW4rD;qs`@0OlN|mGmYU!JADw_+1+mHk)Q) zXZ3jl@IzPd@}`vGY@^{FXFQns{3{;JeD(ovkO8mr6*^&&h6{gOqV`tFDSUp3W?Q9s z73So~1b5C~mqKgf9BNbNbBYYWOMj+`;nFCf&m}q?F2SM`;a7{G7&#)O zdxSAR6Q1LUtLFQ$R8>-Wj)e{T5kFI5gw#!#aG9=0NJI5bSjiXzB7c>;xPnSG5~q5a z8ZwVYAvmt7xCy;%ljaJ$f23GZ3Y<0y!L#E=tROrqthK%ZS$e^Ft#2o{FUGSsrK_Se z!FE3)D0e&e8xc{%H%*dOTP*G1r|6FTqNLV><@4_~m2rI)sftyY@q=$yv~*Fh{r_JMRzXF}5HZatmuM!FI4QavH{JDMIZ zwHM;QVoUORK%ONd*i#P??j>aPku+6lcj)JFz|{r z8lb8xG!*GHtZ9sudXwrdG7P zq0~;Oa*mEQlv1QHrg=Wz@VG!yBPmTda*i?@Ne`!=Jq!PFN}VcYF~J^z>pZ@eX#(5H z{D_9bO9*bwESjxeE?l5vjii8y{6En+5?9~cL>Az8psZ&B$!ScWacEL_UC=UU@2jQn2k)dI! zB3_r~MFmr3>YO5F=4rduA>j!g-&NFv5Ay!ZH`Q+Xq{X;T%%A~jA)ExyzC*^&(XFf81K^0 z)9ofwanOkuGu7%C_le4KbFtsK8SB9G=oQ*Tx7jL&5InX@|27Sy1@eKt^)HQCl4fFRjCG;UfCXN(i+{qb@Phr55zlNj9mao)XYW~>+)PUD zRvVspsQd6Li{Rl%KcF*CV4E-|9&Yx3ku$>gq90up{FDl{w^q72EJ7{1?;KrhCZ*=} zLK@yf&~ca$9uKr(BCeT-utCB#Q;@3>?`=sZQ>D5% z+U{sgf2T@qVh;oB6ULfke%?E&%kxYJ_p;s3le0OR@2)d6y*UP=_s&p3bLm)K2c{pq zXooMa6E*}*%H(1-vH+c|H0)>k*j_Bl>}jsXEBsLR+lz;rw0Jvpzw_8Zf*)^XDe1uT z1f(llgA_dV;KsUMlfV{JZPi0{=bAk=;AX{OLi4S3mS(h+GUMLo@ZDix zSXYH#3WL$ZqXKUJ?x%AtrL^>Z%xH{7f&(j$+_AdU%AO5ESIrFf%)(b$y5umo8kTp4 zoM}>AT3Z%^)iEAU&%$(^v4GEhoW~$``f zut92`d6hZOy=8fB)boTN=gE!Vi~lcadHPV%e0n2bbqIR6Y=H$+(6s?^n19jmS1JSP zry1hBsm8Gs%4cX^E9pDjgYSx>r&~+CW7e@OSCOG+gO&Tjo z)ipoe(!!kW*v|e9P-($}^rRx#WrFlG=Y@*viS(T3vu8{5C=pG^BtX%@==lq-CC5mb z!hyRq!c358CgjGcAVTaaA-`yTMnWu12x^~kSfYFCgusub>oWyA#?$!p11cp0kiaNj ziJ&sTZ2&nDhsCQ1nd;(I+YqOV7U!)~6x&W37c>dW*HoQ+!2#L@zC?nxPMljBgpFM@T;2u`SE~BSy2u}83 zch1WOoJl&4qb*rFNE3uezi(m($zrbNkHmO@0TZ&08BBhHw=&J|2%YL}Kke@*WmwmL zi$R>%cWWxadUU8Hdh`yRq?G<;dPlz5+fJcJu(wy~a^cIXx0n-L1X?hk4x%0vJ|XV- z8PGd`Yl2Gj)3>y(6PnyBr|1&kg%?jzpKCZSpFb^9^mWOQs;HL-)0-~3~-yx(F{7zbH16W-h%-?~= zIi#-6pCDBxUduu?C@+6#qM=P(^3C>+L7fjnoz}_+B^U7(Omnn^o{R;lxJJ1~NluiFwg)ID*qOvfriaF^U zo+aTC*W0IjW3weZ-uf&`d+0eS!TCB!V3uaU!^?-pw1pfdr5MW-%u@bZlu8Fnar82Y z*Wykfe$b-N+EbL#4fCAUCuwpwNY5JZ?aPwfkWjr(Q}y#Sz%rcnfM#!+WksIjb8u91>~nGj6&${q)J6`CuN-F2a)%o z_vvKFpaBap!akXPhnC!qtS#E0nIMyeCunRhDJJuE#z%YmSA4V`eq6Dx0pI#9?e8TO zSYP=Xoww^DtgQ9u9TDw&t+zDDEDSqII~qpT^+olSVqwT}(wEXtiZKhHp73S%msW&X z#N*mpUX?-8c){}0QEe^n?ZHy9#S)KDWy|)(VN$d(`zzmyVbWx?aQP_3j*v1fLlCU& zkA8O4w`>G@@c4{l++S5MeD2Fq`Vv^m8XEdL-bUXDze8tjos`=O2)7k@>8ppO=Y;lO zQJ-AtV$9nJSEiWQ?9?BsTK*-i;D?`{87a-;xvw&0-5Dv>XtEeNDFX-;4scUhR3S#- zLB(C>w+McHd)s20sEO6_kK_1Fp4&%Q$OPe%U>S)-~)bnk>~z*llX3 zPdq>T3i;^Ad9;bA_b6R_1QX9N4uiJ0I!m8;;&Txw>D>*ig-}G3X7qL*>O&W&CVa^Ia|B~XJn)# zOuO6}>Xc>nTnG7F*DQmcE0UzVHjgJ@klJ z56dEWInsW*e^CPNlh6;wDQY%QaY zFEaZ(bIUIgTqfmffxNNOGYg9n+e*N&ptYeDUB0VT$2p+Z-Y${lTx#sht#{)c$#_gm2gIhB6)>$Pdz^%Ef~ij|ARH1K!>eIsiQ3KVSH&O_tJd(d`%1 zZHhD_=I_rnIkmu4aE-b@dE;|BJwyZkg;*p#i&|m~_{gehSlH#ljII6#voJa@XkErR}v`D&Yj+zThj<|O}?1Mg~ z4U44|>#z7v{-R3JzH5u6Mncr(Pt-UK;P3uKjdQ;qhY%;pw}7N1OH`N^vGYfzwCrOw z;yC4~*c>qHSCoGNQi zDXl^LuDRp_EKNtd$|*;9w-DEQ5wX(fLM)Og2{-+%ahYTWHM%0 zyMRpcz9~IMufHQT75*-!1Mh%>HAun~oGvb zOy`QQvi?yqC2qp^y<*?Pn;?XOWj700tZ&~I=?NjK@ovz=%cvOR;&xNUHmO@wbdaC8 z8)684ezHv(8Fgt_S>!Xj)BwEC`C^nWC}6!7(D8lgz9>&n!0cT9z!4s{9RDCV*$&NjRfz8_#n(=;Z%fr_+OJ}r&O6W^xuUx8>ao9e zpwCy_ruaaguefn+Mep+!x64j5Ka-w!#)2U3k#_DtiP2NKf;2WSPofFe#-8mh%my#Zr_fL{`Qn$~gA=Z!H2S@TBwbiBK&!w<5oh*zLA!O-poh;oAvi|s7 zYUwe8fnPsw;dFI7?X_8G`uGn505VXD;~zEB+O-h_Jy+I=nk53Seooy zrr~i7R+PSM*aPh};H}x=>vjYhva^c@cpe3)XkD?vO|Aj3=MF0TQd%KI?4T>Rq!i~Z z5Xg*N!MGJHcy=v!PMiTZdpBi+7337lVAuk!vHvXJEb0%I=4g<MW8R;>yZGC&>HIsNe#~d)zi!aa(LvgtC-6nu4^Bw^g=EljQcASe1C3;F9g##2oRn(i-DF5* zw(q#fCc?Y~Y6lm29af>m!53Nzg-wtR`vsOikv03*K-^WU!?6{mE`Pp&Dpwcu!fqMYYsHN#A6I`X^|uyn1rKC;uf;DZB^-$o&PM*hB^-Yy&OT7U`>(Uf3hTU9FwUM{qZAAEne76$vfrt!oEip z*A28hpMWNTG9AVYz$@Ep3Si3hd!DMe?=eVPPZsQ zCo9nDXk_Vboh;oAvhuD&AAM3It1^>SUR@f=;<^M`FB{03w3+_84t=y!k*bfT7AYdH zZ+~&g%x<-W0k1DfmZ4GQm-xIDDHwTar_kkXygG`x7m8&mFGXN8*56X62+Ha!ie@HQD9G{f~UincL z=fKE1C<`kCW`wB=c7kWL8n5uyyR`ogDLHW=(-l++^Ee-*wQ7~nO{;_|n<)8DC`-Q; zaV7L|`Vr3jpTX%X$bW8-f}vcOiYWCa_+PByJ~t3Om0`JO1Kr zlp;2iOr%?XNiJumM(hPJiESkRRajbKkj7HrNCUCGifHZM(vY;djDyv%g8IAw9bNbW z@K?djME#5de9AH$+@?u*?5_eQ2ef+DH$VN~viL7zbKx0cc`+6PRAOIq$hlFGfHPzl`); zu2(nEo>Hk#>`}M_^um9dMsMzVO1Uj98UDCNr_A`OGWE}m5Xuzag*x9r=hG}i2#d+# z4M4NU2bzw(LveScRA)CWj~|$qs)F^;c|gHhgFGHH1%zL$^DAV0y; zDR@xIPq1fD^DAdOYaNgL=dK~8t}*6^;f3}6}gUu6!n$$h{ZXTTe@fhJqzRH69>DzwO_g%0a!o>lIX zcOGDBiWF&Db@?sf?YDi&(egR7Wey_h z#}4e29V0J@D+M0+9BtQ@(jxq4y-&Ycee7D_l^A)EIsG97D19?nF&zK%1k+`{;*28~ zzNH=NK-gROuf&7@eQ(pYTJmsfG=SN5*KXO3e|^u}dee)w<@@Spz@@JO>+fi_grBl9 z+wWuS;0{Z+RVI6^+*C+eM}1=DI3edv8XGIG?xoq@xG=Rd`>T2QE4ZpFUyHXoqy@$w zFom1)rc%)*`aC5Uq;p&o;)eBv#G&c0qyH31(e&g>sj|;qNA4Boya*y#wqHbQzG)bB ztRQe5t2qYe1ckM^dfd#mCN#HeYbho{PIG>&;XTfH=qvse5B+~OR?~i59g25&EiFor zH#p~Ncug1&3iZF@p|2Q;@$Vf2-YaWqULxolt>Hy79{P%Z#Y11gS9~up;61aJ!t2Y& zoQWFVKJbHQA^(a8Vadk3ZrKLBrfYr4N%Ev{o-VIUk-sntN4zw)soYc7tx*{zW)mJE zz*lgqUrVw2=D|Kxf7MkA1B>+PzljVuuE|})_jgnIS+ljj7qY1@oJEp*V?-Fe^ayTY z_om8TXAi_TK@ctjM`N^tr3nJ^j#2Vf^HgUpvvAmS3{X+%K)wT3`{p&5s|GzC6+*cq z7zJz8(3fi&5KKDdju<-ALVjuBt^$=b7n6qZUeE5Xq+!OJgqf&+WhiN%0Eaj9$8^0z z>k52(TFQH^X?TN1A5;^Rl?WKjX)`^=?Wh!(=_zh|6#3HSmey7)z|DSzV!d=urK6yY zg`nte9YuEorE^=kvCwKIjc$vzgQS&wP$;K6ik8nc$O}f`Tanp?#}e=r{OZ?Ys;xA5 zUNCZi0zE#@TN;5q9M|Npu`ye{Z9Ui! z;voPw-(M-g@&Nwqe!^CdS{%of8@*hWqRSyHRwGRPTI_Wc!gw+}<&99na#6u5VX-uz zgB*BIKrNt#gLetot>YvC$7R5|SI2SJq1_$ioW3E9(r~;6985bq7;x(AIEedErrI;Y z+W#iyUyH2go7Pdjuj~mBr4BUc;!tRQ9_X{zLyNivBBvA;aqkDT`T)0HOJ%iMKH>!+ zZZRM(4?^t3i2ig8cljA|z??CJjRqQLp?xhgAkHX5q~jTKGoj-f6y8}*7LKf>)Xo_9 zyCQ-KUBUO@8?P4V#t?P2x+;5SVGT~3J!;6P?@C(M8T!;aE9n5^uhQ_NHT-S= z13s@{r5o_$R?={XoNn0%oX)%D1m|VQEff9{1FIc{(wgo{I64EKu~#wx|Gt8RE^@c@ z%E0q>hGBna81`FDEmwt^?%Si~5uaq5V25$tF5P{PX@VCPMLSl|^ez}^-qrm3GA+x6 ze`n(I%$rusUJoq~l_=i|`l}0=xbk&M$&{1h9tZBK)i@Ed+T=OU+bh^#V2eY(&Sdm* z8k>pUr1Kl9edj2R2HXF@=rtIOUo_A#eg(y3$tl*V;FESTDNAlOM3;+zSmPB37DmCX zel7mEfOay(0GSEWIIanCFF4Q!F)p%E*B;zj_x*CZlqJVmEl5LEE{ct-!d9j)@{TVu z|8gEYwymIU*(m4DH)uvSc=PTXv^iTI-o7#7@Rmqhta#`q>pStR1bCFflf=0Q=P%pR zbLM78JO~sDcP}GnSGi3dx?9y_<1)j>O(f4ag~E04XTzDmhK>!^OaL?iumEAfn>qqB zeI^^%tD8DAICK2>Bc8sgBZ3RiN45PMJMR>Qd%i}5z|@t&)kuY-mQh?cd7x0doF;aY z+s8G7zfuJlT)cUvn@yRpJZx~mfPVPvczi~V6%M^lmk_sFEyP`wi+$oOi(+uUbUCGW zms4U+y#}H<4R)p&gTo_N(8TU?hk6dXQsz3S1@<0{@>FLtwwV^slI3);yBw1qsW4Q) zsNz2IvDLI#QHK$C1z=e)S=T-u6lWLWyu6HJ@0HW?4g#-WwS_Ap-|V)7ETNF4U<=}` zfu7zPvTl;yDFc0|zpI(JX|Og2#=t8f$SI9Y7kW zAcely=)}G9fNEGG4AKVj6N;-*=N@v6s99W@PzCuQ_kZ4?hkMA0DbK;LhMu_=_A3e= zs5|!aR`OhVjW+Z^>zRZwMPrEJ$-ADDsu3tTRd&iL`UyXUE4U|}zk)qM`C42FN_$E| zH?av|_MmCqYv2^eH6dHKX{G)>L~}z@)c@}RVoFAN=u;yT60qamC-tt zu0(pdmz)u#+~%A0()traO3T`JqygtQ)U#4reY_xz(?*A_Zy;no8#1MbM@40 zF`JO0jU(%upT0(m`p7v#>!ozDkDT0PKXZ5{*0RxA^IG;EZb$gvkx7J{n{H()gGvGh z5st@gs6WyGt6lutIAKRsU#nD;M)s9ECca0d6v=sWI@IKU7<;eD^DV5CIPJScd-}@B znOB(&bxi|ICR2`n?1@dnYisQBexO>vvsf+#=3X5W?vcQ(yqr?{$ivRyInC}br{@&vm|IlL zdN^bBCj2;_cZ*}YT{Cy(^3K=FdkQ$*_ABen4}6`4e7V0FO%#xUb-ddDvH-5wx^o2^_w}FfM#NYqLKOssTX!Xbr>(7E z#S2d91hd2)TT0UhL(AFms;bq!so{2KT&U-I+`HnU^RePk_{Rp^jY}zZh`hww1^()~ zz=LZd>e7WF@)OBFA`fm%+;OFWDQt+Nzalan@wrp1@~Us*P&vgch-l^K#k#cXLHQ}m z^9b#{JEAc?I806wURq4I->ei*ZybuKVamCYjQR4 zjTtFd5}Z>&mkA#>}p&qG5ZzN5{rTgk-)-K5+)sQEK-n_xQzV5tF&hn z^!o=jyxYiGc`fVT@L&=<5_r=Mc%xpWj7R0QW;?YUCs(IGAC;dIN*B{pkIB27Uw~Go zc^v1Vj%xo*Ge$L54z7AaX+FM~COl;`)e%9x`S7e2Mx20ud5k>RS{+4H4pc;*!XXgWEF|_R z=~5}qm->X9F2uS~Ad}wk(Qc>e?keg-T3lcbuZnb9`wcC4adHr~YWuZf^6beEE%@`V z(DktxhkCz4?R#T=xz9MXqg@{56i%w1JV}>H`LF2iFS1&bNWu zOPHCjp6}WIKOiSzXR)0DIpGz`84t2I<)jaz5qBvd$j81T4$Yc0PMKls#J(k@OUX=en<`bf^3ebX#GnSZKgow8*#cDS58N zS|r$0e03(uxIywX%EmoOt%arZH2y0$NRFQ*XIneMhl=;(lID_cB3h9DYuWCr`OA_FMSwB|O$;WhP|#PJ(I2zro5H$z6+oJaRgrrPNcJG45iiPb3L`6mv=_F# zzs?P%=_KkA#Zzc{dam3>_-Z~453AIcex57et4uL)HA>1n%9tnj)ldF%d}DcY**wUA zJv#{d<9YIo%24G^fcp;dczQ}z=F3Smb-w&$r+?sNF4}u{19I~+WY6JLIxtU;qwEFp zV12UC2>jx4anFmiVFBjpRTfbAOY&`D!CVSoi0#yxbE*A8xz#@v$bv??_Qg_w71 za;Gw@a+TK_q&+nR(uza3KhFsz@hD2JkZ4b(`5yW6yCAtjk@!K-bp|Alj^s+E<%_UE zy?P$)SS0tj3!*m^G0Bec)qprkNA#vr_gCZx?t+9%vw|6y4WvN^q|Q2$sX3j0Mea91 zX^Xu06~ZrXDAFt-r5TW7btJ^y*%U)$b4=@SMzqB|n!Q-|+=awq12B#x-<%y<5oaN? zN<|bmr=hRPqjedvv(5_{;jiFmp?q~2xd5DlDo%;6%x?n@$2GyKHDZaJs=tUGf@5kK zg2OlEZ8qR6({T{DBMOR}_|f>hOXS++Qx=Mt1VoPk@p&E5(USgNBDXIWr#KWR8#qrH zaE9nO#Vu(P$(@9^=g>APYn^IIo2nesdg{Hv>2APjuH&G4t-n<6A~iyD^R{)|OrJ|* zm&&`#r4JW+F}_{{BOADLetSWw$v_Q!3mCNq(rDak*uz;p+gJD+YugXZren+GCglRV zLxGcU_&Lu2{HPA>PNS^l^26ogpc@G$kPlH0G~i_DIR0kz{c?F=xj48rEEs1b>=9ZR zaBAr|xHT;Ab-AEi9NZcfjAMn7!5_0i8FmJ3Oko&q7#iioenec^+ONa)DGjGnA3vfjWhe zAh+i#xq(uG5`RILBv1h-sJh>nyi(f#AE03Qip?z^#)9Ht8@<^e59`*6bM}&2_ zcjkS0RLm>WkqSCCYka!h#O&#OaC1_KVR?r%Y>n$Hx0s9+CD>yF`?!kR3%7QxL2+Xb z5fk-8zcy1_}(y13Q}FTanqT2rE?J)+`!D76)J0 zquOZnpQi9SU+-tzxfNa)ne4bT>jUfuTc@kGX0?>uPawGchdUGcCMG7A&B zTmxRuJSyBRPaarB!`sYwFuV9yJV;(PblNlnUMz4}D*rFx4*flyVEjFtzAlz8vnbS4 z1qz|6C?u)^rMvM=mm*NQ+g+dj_)u;dlu{QGyOvUS>nU|NQV!Y!U1$7M_14gbrrxFU zah!pfFBGd^iyt=w@e~G?KW$1V;~zoADV1N`mU`}$+X(HZvsGz2*&9SAk>fMTO8&hv zAH~3`N=U;orGz#dT#6gga9m9&ejf}VzL^YZQf`KKeJtasqz0oGN{7+iI*jfH%v<{) z@!w2QEg%j|xm%&zX@yq57C){ZLZL^Z&=*01Uh^z%2O$k=q1*Z1`bchVZjF7FroqL_ zPw?a9iDut{YRyk@r3DuchLWwQ^2aD%y+HBod*twz8j4DN8H(=KQFJ#@=wpsc3 zDRlc|c|_1)ly7!);DY4~#p>6>HxY3^fr2$c=6)=x=>0?$wP5+C;tsU(6Zub+3pXkS zRU7EWiG|>D6~i6e-+4{+*{Aa3R@d`-wV_;LX*x`Ra1BOx>oBSthAt+We*iPKA(QFg z0c^qcoJ>(4$$?{BTp%;-Qq_W~UyHw!Qm{2B*rUijxL|$J9yzY5xD&1ZO#Uc#97@iQ zBNgQ0;Ug>?j6no1{(m=_W_&Im5W=6QK3~YGscV@-2w(7=W`s9W@HCxrr)={L7{4Hl z3Sfp+1M?_Gxc{3cj7AAXhaiUX8}H3T}@4IY5+`n&5sC0DL<~&B?Um zkbEq*4cvjb~%tYN?xXL>^kno`D@*9H+$kx??h}JtAjSa;RQx*V%M3 z-8ce!+idX4gwFgT7pDVm{MIB(>wNRgt_-EZ)QUo9-T})+m^qG`6k1t*Cew;9<@V0{ z8s0~Y*R}$9ZLz}vysiekW|JxLD=ej2HN3Tq2OIZ)rLPs}!^zfU16~y9`%2y=gg-~a zj{^5SR1cSX5aVK@JQ&x+${Whf-$1!Bh+V++_V`4l+=`;d-OBFg>BLbiyS*@xgk$m! z0r~7YhMg1BB-UIS`kEb==Y*&Kgj86h-9Gt(@?Z_$y~2A}@`h({rOT8(Zx>re94nmy z>s5=%^Nkkw_(ZyNN*jn*0QlNOMlhnSpe=u;}S@ zx1LUSBi-MpAxzz$RY#h8p5;!r302wzE#Rdya&@8QB;3G_<*fJ5$O{CU=6KLAzwSH< znwgu^o<%t^goB$3hXPXMHEB|0LPLTSVF(`y1Hsa#L%I3gM9MrX=Qy`&cmo*^L-@bq zff=))VjMHz?V9L2eOAV$VoN5{m2+}NTZMyu?cQBzn~IwiyWl41hP$kL#4r#;x##6a ztbach(mm=h0S0O?x?6|Q-GGU|00!TFT4nInryE3c{Qu{idu5&n zP!JTA4Js~h;3)BmGt7lsQ*m3CBUh=(P0fZ4ZtIf`y^buY6w4wThG}I}(&}6O%Ft{( zP;=nG-}`gM<(?Cc{@`^v=XuWiGoST&)^BrJx6_rLb13`Q(0HY+EsgyZOS`v11FYGh z@D%S9O%ugj^Rs3(KXoa(pTbQv%}#+PpxN)hE3~HNWk20Mmk#_IIz4x}f!Bob#$E^B zSgePKW?#1970#une+!*vHd-1hr8+AL_J;GbLt_c&;GnNoVEcRuvw=L4%R$|KhnzPU zeEkFq@&+N3_bbXd3KLfdAC9&G_n1o`{vNttIXQ<`{So?CZVBX+puZ7}t9$0v^#{*f zAB7XlXIb^PV-D^8Gjwn6OareD<6-vjntWn##H$n@x8W_AQ*!LD(0E5ueu%F<*ufJe zQkc&fwde9MZV%FZ`QS~KeC9LqEj$MAnlejo3r5Z=!LE(9a>ylUi08{oWjgR`a2#cf z$GXkuD?%Im>oTDHlj!tes-~WmBNsZmM)A-nm*Uwd9@?`vu4MJe(E76T@^qtowAbF7 zI3|ZCj`?ijn9trg3jZh6|2`nDhjC&6JBs4ge;pE5Nueji_x7}yVYN|RNUAxNyB4ju zGLkDmcTWSUJCMR`NM~Rz-8};+@O0=1<;@v1{xrHY8)nd|)74!XaEK|H1Zkfs9 zM4Wl~Av6LHDKz_PMLKSosWW+mTu;17}du<l;74#^ zRDYV&T+t6u{dLFT8MoLdb)P{WUq<()fr0lv;|;qGKNyB)19+Wnc&Rg<%2B_{{TA-Q z?9FF5zG%tt=_|6=A8v}^_StDxMf^OSM#^gI+_wz8;f&YkI`H~HT;P3g!z-Om-^uEo zx%V4*O&RYxixD5&xzUE_nNE)@>h#`>F9Pu^yXY?5V9Yb^ZcfyU9>NO7u*b1R_(w$*e0 zfflbZYG9+~m`x!mopz6vPuY{PXg38b2}M~{RqZ+m4%tvaLQt%?leGA zcOtCH(cxQcz}@d4>?)g_8)o1YGaj1uYvQ44-vzu38(zITXkL(-rR=|zHU+77Dlgv3 zBf$8QuEA=P>ysW!s9wC)D*YqSzA61HA?m=~k^BN?z6k2q%PlWsT4V#BcsunBRXZuE zx6+bOb*S^~R8+y*%zH(sdY97bcDhYflcE>kH81ipS2y!Y!^GQZt*YiKt#6}as_NT~ z#BBNui|!3S`wW|fgRB5$>Xsej2k2W9EkC4Wp-`h7)pJ}HD7O`A*NyO58#B!kXW(S$Yvx`x zk=~C{S1aF5Dj8Ex?c`KeOfGr0p^A%-Rw9FTYN~eeku;HT@ljIA_wnkDvSSz0v~7qP ziR!Cyo$$mZdCmkr6%%H~sD?x0&mtuL$^^gLk1~?f2-(?rB2&igM|4ZF`d;*AeB}#= zBP5RT<>zZB@RgEpIkt|+;)>KDzV&DTcg`?sOz`jIAw-nw-^oL04A0e_yuw6p8r`3& zW;zRiq@VP&hI^|f4Ek`|vk7B9n=s}xV8YYXrb@vCJ+e1*0*`?@QE{4@YE}&8GP->@ zY@C0Ud>podUx!;ibcF+84}k^vPqEplx)ZA6JW{@(n8xZFrP(At<@SlzQWKwyIyGWde#QM z!~{p)lt7$7+)S-U|D>xcEy_2!by)$q&wYyxu)7I}{bYNZsjF(l$+zL4XPjcgQB9ou zh?33C)g)g%n91?PSY1)>XC5;K* z#qBc_nkBTCJd*8WW1!6h3dumTbP4Xxc&iytZ)_>Zm?`?U& z>r;eFeKmf`7yzRpeQ(qyioyS8Mfw^l(o=ZH*8`WFbE#8h=iFOR)(c~UQs{vk_4(){ zNVQj@Kab)$#dMn3O6ZXQKpJ=8QB z&|R$;=1aKGz4v(|;dy()gGRz1mV`y_z4Nq$Y~|z8)USuyx(lOmrNIGab+ljJ z@y%PjcEXLzM?wI-fgJW?-L@c1I0q zUl?hVYe@UZNE zFv%DZ78;z!8O;y58T9|qe8z`w^iq8jtSqLSk6q9BRm$~Who%~RFL7_1YBEgKl-H&B z-dDiE&Su6laSmgiu!Rk$u8AW>(~92e-O3juDc~lxr}EB7>UR@5g0GI`uzX9}dXuG* zt7aA(pZ$qAv2^Xz5mq~HfuC|72^*gqwrhs#x1bu&_p zukI!>37-zVR<^nW?nxWmA`{LVO~-T92bCLcp#^=^zs5*N;96@fD+}>;(feLlkEDNJKtEVjC@>Wv@_iVJ|C1sEWAv=K}kL3zW~wYfjS-i)`H@%CH?-kz?N>#-cGYKW##pCW!6 zPT3<=-=bHG9`$nX)1wn>uzs|Cz6)&dH(c)bj8Ho&(}qyUNXY%>aLOBb1zap4^0!Y4 z7E6&0x4^_rh%NbLq&h^-4K)OQjTM5f;WZVAt|8wr*}{fgcQ`G%MXkP|(%*6PHozw^ z5BbAvpPzxgHG$Fa1&&tp{3<3t$FT{B%}0L@w(9+B6DL2Go*S*cQzMSsiqpLvwg%X6 z9yf8^u|#9k?KR?f8(I`Tu>)?fwc+HMINpXtV^weUiaCo*;DiEy(=F@d&danR)i;sK z8`8pj_3bMlVMfD()Y+YPa*$O=`(bKL*RDo1f1H|e1thN($(ilW`__i^zKP^*M1PM{ zM+a&`l{TXO08 zPgHNbMJs;1_Dtg=U+ZrbD*0BVWjR=|Vnd2Bk&yTGb5$6GU=81qu9b%{sM4@75mYi! zZ8UT%GTL{n=HqTjUY^kx7F&ntr}2SjE#7e-xEH?JiuVla4Z2LHIc9}=O51tibnl%p zh|(viokApL3f~kBrsK2r@z1(VfSZMVZ5_ukrr=%FcU zODdbJw!0eUPGDkAU1P;$bE+R^mnmvmYAK()pcGBViKgZ*;Di9^)MOv@{+FlGlSk9G zDQerRQFQcl=k>HvZ0Sd_@l-WUNrri*HlAnfqk5PfbzLqVuyUYRXU?T4(!wzR4Hz z)`zG#;7!|EX&Q&ev=2c&r!a8ytu=zPKLQ-zGn~4h9pvE54Uk}r?lkA*cMAZ(BfqE` z(qhx!v zSjf}Lc$N^|dw&>?Zs7mRYkSg%8~-QN@$5JMcSn2n(>>GG`JoM=CN1mmZq#L>8aEP_ z;)+O9w>we$Riq?c-B@7Bk+x-sUEKxlOv`fMIUic$ZzSYZ&cL&n{P1pCMWkaT(fk=| zYqLGF;A5dCKRXQk^}ruu!|!b3dz0wz8EOxu?*M8&Q%zUC>rZ25s*UTID#3u(PzeIM zYLo7o@BLe%WDCV*h@yqtD4vBKbcvG5F-uL1-o+UJAAgHOKj0q68ifv^PP0%h-yA^W zXQ?ffjRW`~hh%zlmU^?|!iRUN?_Gg~QY#B77!5zx->TI4CJUuNnyogK;l{JoHgZcE zH(QO7GwE(TC9MKq>n6yWKyqmc4nokY?`QBeAC*~WAbmAk&1>@}p4V-5-OU#@^TEG~ z7y@R%Q`X>_oq0NY4gNpD2Y(>F2e|1nPpwN+=cvt1?xiT3mR-wl-MYFD>XaXj$zw4(7T4>g++ffcUkK|6J z-{-2Yh2%pf=BZ~tS~X9N&3y$Q_)6sj+)ayTPVb0cqfi!_A(v;sx2077B6<2kCeGiY zA1U+IrG8#mChJ~arbuZTpQaa1#7dJfHa>frd`fBb$$WK$NE-tE0iUr4P>Z|N_RdG} zirh2Q#@#jX4A-kB<85pqlY&8R0~;BKNygil_T8l>%6;hcUFr?;NXooho$vf(=+!A; zi!m$H6oi)qe%9Bj@YkVVP2t#L9J2rvHc-a}pztQmU7#LUTmwobFH{Hl0>_-yr>Al& zJa4?JZG*3b2{icfCUjwunpUH}-A%1*0_W__RyKb&aokO5!aeH1)b4}fo8fxR_KEpF zYPP?ibnQKAw)B!8?oqqf%)6u&I-hEGVQ%#<8_j%^rj$%$3)DQV=Map0$#152@Yn^l zo@Q9?;AncW`!|M{oo$$@CMNv5j~m0mrG4l&x4O2M3HC29!Ln`!H*GkvF@nZ@tjhTX zUZW{lN-r67uR2Lqo&bwW)ZDo5*&KWUCm)x9o9)J7>$il`F3<)J>_=lRsL*O+l5LcQozz)A18<+h#J}b10wR@lhi2 zM!xv>aD)VI*JK~(@8Z2ULIOul#F)=->$hu0n$NqCjw2_+`(29HKX_62j* zB(NXlE<=RmJcMQ7=UL}im1e5c=x>zCUVl}hzkyY0DHu65w5ikC5BrGKS2*m8ApbVD{Y_p#90;^4F`2cehwed(d)YI>6t$OpZ2jK5u; zB}1W{M|MhI^T~{j%(OZ3EGip|I{w6RH6}V7aBGs$;YTaimRZFAkAwC5)i~_!*Vk@y zT4PS@CVTE<@pV}3Ht;{#{(#3hB#)orJPx!I-=fw` zkAP2V$60|ECTO%;{T#m0kGPUO{as-t(AKn7Z=9H#}rBWd4*>Yr`GSdB(Pd}%~SNs=n+&J6ZM zV{y0nUMi39)EzEu|BB(#;K zr_krc48u(j%HOV;H&dO5)uGCuT)ORHHLKuWq;ml_&N~^z|4Tf=m>_#(1>+N>^Wu8O zmNA#g*gy6*&Qxhy>j z8@C8)Yq|w$?cW_NJpR9ocg)~Vedx|d)XBAf!Lxtc{Q=33s!@$#kRSY04E;;q2+zLW z6#FQG&_jFEm`BxSbxhmA^-Q}x_oy1@*QylDt`?dWlv4dy*EG)8zy@;<$oOmdZb-?R zkV;$7g-6v!jSHSth*oQT}tWW&qsLv;$(e#+_IG`>)MC#(+AxgfH#!h2J?M{TXV1!Z~Q@kPDq zQIG1klUpe&K2n(ArrxZ1W)1$Wbo>abeTQcFLV#;g#KUa=uPVIm=K zyQ8QM8`G+lYNP6KuZ1<274R?sJvP9*O+Z&my70Ib zEO*4R$^wG*@&+h~RR(b@u9T5axDjA|%TuZB>~TB@L#ZD`Mv>fm8D8^_zq zVjSMZai*u$%m?6;nwgQ;?Jr@Vd+(@TB@3QXr^utV8P1p@0>|9N%>)Kl%<$tfz0(j= zRA{87BaOS_)oHjn0BM%4_)^)k`9hV371xupsd|P9tP~oBxKNQYnEgVt5HG_C2BUTM z%giA|51su&Ny;esoYXx3{$4duf)!{z)&ZXDq3OW~RF1O5#H54_8oRQ33c|w=$N}64(0KaMqhR zGQfVfIu0!9U zMNiuBs)(bqb?W_BfVDY@v!gq&sSUQa2@3~#ZoOJtRyOsZO)sjKO^Ll6B1G-azX}Y? zzb2o&?C;4OO^L;3xmpAdxb#}loe0Ig+11MB3-BV1OK)qMR-`tqqXA&EGPnBkqCTe$ z21DI@U+YQ-Hlu9!epT(<*H}iPv4Ez9e|=30BBlv8-h)iu(X}w4AG*#d6&dc>UCdv&F=5wW9`` z)E3HY7v*kJ3u?s6x8iXi_YoW3ToW(99ffXIhc_&)KQq%43*~Y{$BkP3san6fI0pUd zg3ansQ_CN^Sjz+ZYtG57cTKA3)(^+h*+@1rNkYXR{AyM4vo2Qgh#Rj8x)Y$GHqcY> za8tjLTh!i0)C=B_ukjg8i?*mYT%FnE0q(qgU95I{w;I+rYPQ(d(~YOTWnj-Fa>s@KitG5F5+CcA>mCuBG2~ z03B)r&8`Ne-``M^Qp@#XxI}U9J&ZEMgP(&q8QdqqO!wYRU8v<&L?x?e#8$P_)onTf z6FLoTG@X7l_iRJK)orBzYUu0|UQfOAt zTfr9R;bI>CmYNicS!!*dYV9EwM&>u5K5waa78tA4ybzs(JDq@M^wSFUK3rtcN+YdJ z4QY=XY0Ya$TVbT7){wT$NGph|A@Lp~F$QTyhtgmsrf8m)7FiTgL)r`@Ex3lXsYaS& zO>0)kV}Wr-;)TxtCOFba`=>MgR-%s24TOeyG|$D!7`18I=TRVQUdAYpfAwZmk0?zX ziMAPp;TS$k)$U4dQFop?WQIGl26$xNb&*4$- zyaNC-^KuyIV;61Tre@_nZ{TG!9@avbd9H}ZYawoN=WVy)ZE#WcI|ygoW8lRz9(IFV z6A#M|*8^|04ex#zz4MM5A6F5kdniv%W5q6qQTTLsT_>&S>^tg6a}A!RU%k6hreIE| zTF)5EkHIx4HWGutD(8`q_w*sG!E64$nnAnYRR<`ME{c6mCBJ5?%;*UH3;A$9=1OhI z7g%^5nNGc@zNT#HLTlew7hVru_X+O2w{Nr>i_4#ZS2A|H8Z0~CXpT63#x}JPJ@|nd z?- zs3+Rdgi`gjUM2&uuM5|ThV4)j!x&8K)L=9@{6<>7 zL(NV%-|VV>{HI@>MvpImYc+>1X3;gpZ>vTDVh99eqXd z+?iJK05;SHmTiI|Z+SUJ7VOCxIhAWLP4)*ahp0oBcB+G}%&*?-GAaygxV;0{#M(&I zF-f4;MZ45YWnU-yY?pf5gfHL#>Yjqa+ra1Ba9u?!32vpYOLidKKeyR1GE31sW9bp_)o{ zSF7RV{aE$*6`L!j#fe5y^;R;ue))1m^MH9?79n=-rBH+u+dm4QhQqQx%zC4I0;r9=K@^8V#A3uaT40olrPkKmCa!C z3$-csox9sp%$I7@Hb3DLb4Qt64-+()miz{)STmve0`$8&AYQx^&&*P3dz$^F+9Kox zUUKF=H&D@+YHZdbJZsT+WIQDME^;XH0_Y&pe6d`7^F9c0ah}nE&VQ*6QVLV4|5s`u zE)YR%jj1T59dspWXDG=jtX&O6^snF7ztjr&Fifoi`mcOzo8bi;{!7*XqPAw{D;geA+hqXmYXfd~11V){V=tIY)f>nw%p(JQ2WUHsH5A z(V4H+#^DLooG(Nc$}dw>Lok77vOj9C+S6aW>`t_4ulj_7Bj_MmG>zD&c2L|m(2Tx8 zbsfo2PpkWb5|!8vC135sdIN|11`m}_4eUsX->QwB)4;rbFjdB?K&MibMbp1kpB)s4 z&(>;F;!(IXC$h-FLgV=!yyu8aBwvAoRp=6aXBBH_xM=s6bk5R`Ki6Cj`DYLLcD)vx2KX1kR zhwvRk&TL0#eo$|74ng|U`*G^Ad%xONUPg(B(H4*SRSl%R9|wk){IOq6a6|_Jw5^2O z7MFtHP9}&heg}#>p!Td&+V&EyR^q4SBjU_UC#Gi6yaU*!@KqLVI-qt+TaEP7j_4x) zJUxL|?xOEm37U?Sz02L;g=zo>&{nY#W8 z*0K+)cgEcZrdfy&T3@1A{Leb&osAg>tLRK?-r0DkV-_H~GzdzfqvHd^Y0j_M05q;O zwf;@*B;7`!liPa9xzsc|EWAm?||ejVOUdU0Ui!y(QDy6{siFBivx zcC`OD$eh|%pX0pQz&!>Yc#hM|dqrIM!Y-`8nQp@!+Kv|g4%~}vblhYE_oM%Sn}RvE z9yZ(-?I`IFb+Yn_fqM+{vmOfn1MV`+O+?sm&$Xp9f2dhmIcyW`1>-(~HYba@*G~-^ zd;voOo|YoLEH@IGux9ky z>6#wG2OqqgY4wo8w)FI0YEI8-!1LFPjDhtSlQ;_p=0=*&5Qa51)O-fBtf{=V+O=Pk zdl>J3hZU}uH$DYmijBAaz~L$DliyWQhDi%nVp`30s|4`>$!%%>-|G07uDtvX2d&A* zE-cJP;*>gx9vdf;XzmfUkFv2X9mB&^)9<-E?dI}?^XK?iaownwtNa^Lu5iE}e7}~B ztE133=arE6F>uEFy`*A&S+9=8-zr6C+u*FZqFTn1GDoM}p#_{e=$KCSf(9#~!PmgtZXG$#neeFh#_vC|(=U z2TY=_&h){RaJ*KWWx#pBhBMQ|@ph*8<5%DZ=ePOuvmQ7zZ8*bC9Ng|)a9m9vXv}$9 zWm|=%Waz7~ zF0|5DVWG0{1>>4R7B=DZ540ey5)O^%)cHhf^lQmp;0sOq8`-S-<1(w1H|)0bYA z;aRhdQKx=kKF>shfI4-z`K(v?gLj$F>or^U32K~IV!RpwUX1EhGnKCqPmujIrH8=Q zV|MR{=2mU(01j8L6Zg`p>7peCRjHYNCChY?3MJnk51}6H)Y)RgS_v#o^T>O{UZZ49 z?Y3=cbG?Hw-QYQbdDc4~SLYcW4=1+t6x!(A)r!tksc-l>NQLahopvy~lHf3kibJov zaV)?P+vlB4HWM85_hmIv32E_En8;I3H-Bop$WfZKdUJzVAS zki9wyC7($+ihe;I^J+7zR-c4~nkHOMdQ1_O%FbpCmQEQ}YH*Ew8*Pw71H}q%oI*Fi z2HL>{Ep^gmhj>w0^dCX_R@Gn|=n1&3#wkD>)Dm5lznb$66a`xG#%&RotV5{rY#$Kw!62ox#waGQ$Ybq`l$fuc#t;UMw6tlW`KOG1S2gnA1!j(GDIem&~+C!1Q8xCoBR zc_bY1c05G*PN=uwlv;6?;nvb=Hk?5wPH8QAB2@U66j*R9t|7_rLocQYGMmwo2=Qz83UdvZMO-P+VhvuW z^J`RezB4t#F{L2 zc!RWtWf=zAw*w88UYR-ZHy9Ff9w|SF9*Yr;lul`S!9~q5xu`C7q zf$OV^c@Ix78-Z3$DYl;Ishm!u@%2Qy@>d!?T2J`SqO$Po@`pr&f?-9l4ekVdOyk!T zObzObTt7#zmK!Gr`pdl@IKQP@<^IaV!O4Ly)fXSvh-1^=dJO#6+i)H>aiG7=u_DW_ zO0MRo)XI+&4drqh&U6z8c_TiD6S{lh+^GE8!oTUQMwCJ<5~cw0b{pbg6Hy8&d8~n` zEjxBVm+_Z^5_A86P1&{&;RR0>UemUiDx8RxF2qLSWMc|zByt=_@m>Rd&j237z*s_l zO<+tfPecQCAjN8(j~mnWMq;uf-{kmy1Gp&zV>0rZz^G+*)yCol8!*c4<8fksjn;Nq zb;?U{@3DP832f-z7eamF#XZU|jp?&^k(`KA)OhH8$l*wzk38P?uFBC+3YzSDxMro5q&nAo3xoIH8-oBd!n13CA3|4okXTHL8DX5&459t(5TT1_2vRK z`UI3A3|80ZbhNxo=fPBZ9k{vU3_J(p;iPKta&^41*dv3JJC@q;rlnGPW04iYbi8M= z0q86pXdM)r+rhx!&-NX49r&Ywk7(RT8-7k|$ybdD6VR3a6nqoXn)MK1*14E$eN$=9jOiOt=4lWh2X zQ)q27k)6v<#CqGwc)hMe{$3~qSUTLzhSw~G(wmFi+>4N#@m4V&&cnT?GY!M)72w6$ z@B&h3dvlSM`=f!knDGW(2i_n!50)fXC0OnATQX(0K%sg$f#$UkJ#&i;+?yE}2kl;y z&;FPe1nw6$+^xwJ&=Qr?3IneN<6%X{HSzkOPy+8Y8{SjNw4|l@UGYZIv{s_?lvW1r z*U%47U;YahJG#-56*@}!+(s03OkWpTG=BTggn++|@) z3eON7o&OilUDVK^Mgbht1q(AWL}u;@h{Ps+f?3dekkl(7 zouA;new=2xO9Uy~6DT`VbWsXBP(h|hRf>~nLnf-dRY`O#Q?yQE>10U9ze;|%E^R^> zq?L~DW|n)tt?8S^KDT*&NA4I{0|zN2%IM%ys2HT9v6b$)*@@@Km+d-*yafe zGmo#jwTlnUatwL44Q~{C2GXi_Rnd(}G_Q?Fbrwe!E3~?e7_G!6QB@m}t%RVGZwo)Y zm`L;5ifpU&?g)$YUD1_;)ZeugNy`5v>e81%YBtuL%&p$Ry1KE@n^+H=lW|t*_b1Zy zc96cC>T3*)XJ8TW4jfV8kf!B7Tu>#rQ zc6F&kmbhD~a8kj|c-WmK+G?vS9PmmMH_QCs8KBs)u<|NoL-7JST}^) z#@Q&|1d5zjl7#2)o!k@uBB*{Xr>k;gA{}Ti3Y7dneJZ;GAM#YT^LPA18SmqE`Yjzq zxf7#5nQE5?$Jah(+@PGu#R8*vnFdY{jHK^7ih&9S>diWdrjEPt@#ZGMiOP&PYS~N7 zE2-!t>dHNgi2{vj1p4_`Db;@+3HsTj%fj4w*^M;y`_z>Nb!*Hc@9qyvs(OoPnesb} zo8@Oq#^nN-7VHiTr7yEZjQjxonk^C(FU}b1B6>{e3BO|x_ydqejbXJ|ew1!8Z@}sIETB62VUcm&lwHVDR%Y z^P^WESLX-SM+&NsCN_Q|m>;CQ0e*PiAb%HY4tF`=0l zr9=!r-*=_pXw=+ z9bIB^_HnJ?Ms-n4$`TWd>o#C1DauvZkdF2g4IF(yP%9-l4YX1sKSnS167llQ^ieM{ zNN!K{dke2Qs)I$!jB^P=N?0LVV ze#xfJB1)!rJRvwHbFgqyVILvtc%!vB+BH}mp*4UB4Y9aVw3yj1UXHLX}md%#5XGeZ_SCeXcK}_+C}7SPJXw6^rA3{L>{g zI69CO<5fLWF#_vK^52JF-qKG9B|nC>*+coWJ}n+5{O*_5G$6$q8o&WxsOy#@IP*X~ ztK>7GR!#EqSc>m2>MQZ}XnLp6__`cv!ufsLgfv^CA;yjkXnKDU>u3h1G*cu&N&Q7@ zIrkt$WG`BZ6t3${-EvE(agyIaw*f9-)cP8z&$}aH;jnS@cPyn3MBibq4(KxEuyo<%>5$?|H5sj#Dut;`tGL;M#jU3+tk=?<$2mesQvEaJ2 z?PeiL;)aMwS&gQ;Q}r*!eJ zBE|dcJS1AvL>UXr<-IdB$$2DKJpDZkc0N+qv@_=1jq79#J9n#3orc5C=YXNv`FJ$j zIZUPpMu?Q$O)wf8djJG6jIEI|j9o03#%t_2GlzV*UHk{_2|q982eEJFN5)P zV_zN5Fm|yG@0off^G3qhjz&lr^|@F{GY5%Ue(fkCmI=C|-1@K1p>FY3HnbRUr6~+~ zx4mOnyj@@vH5@HmN_;ep87H7VvusNF5Napw7CV!=KVyvQIZU!B#)>w| zxET6)tQhay{|I_1h2sM2Q;Yuv2GY&>BBrONL&Mi0d5R&q{_DVrC0b>O4p(CvSK&Uc zQaoE|W4>sR_U;Eb+O?rH2vuI5c_djW7~@v;WzgouV)bI^uY57D)!_YjhRG$D@T`HU zn#{wEe0WCPj?!S<>*af{!%JL7D`R7LbxZ0b8`G%<)B3N&o2oI*hn&9~X;tMq_^PhT zR8Nm>1_#E{7R?+uhKFmO*P`{MEvW@Y2)tTD2C;-Rji^biJBU4FBjz@VA#ajFOaU<# zQ$}Bn32hp!i!GIQtt@-*vL2k{^e^Pf2*j?a;;5>&Dg?4`;VV*EXnato~ewux_UQO{glbphT-&DF}%VwaJxj%H@W#=;#CyYxg2UN2OM* z?!d~nVWpW^$h({RP84YcHS;Akw&;5zu##<9p(YmczV^0WPI&Q4Q{>YZ!U)gp&>H{$ z(hvG6#2k3cXBWl0eaLrdA)N#h%I-)$N~<;9JV|ty74l3Ht>hBgF-bIY_JE?F-Vxl8 z)X8FiTu7rQiwtc>87ENHjpS7{X>t+0KUuWBvAUoa$}UZSLPhgV%&enGEw7__XR%rP zPDkYeFD#VG8+#(C#T3ydWbvnZvDx_pwLGQ9CiRcJOhNDq-a`c&`qtV^1Mj?SqgEZ- zFh%t0UfqBpT&I}>W7{UILWJ$~^05pJSPvTqElduOcMoMw6=UVIyu?{11uS#O}d0aj6@+noFD?wW79FPqR@KX?jB5x+PVVfQpYRKLvjk)O4C?RX>L9 z%q&gqwvB&z{hFk@DvN2>G!a>+7`2VgWn}t6aQbE>Jv|L(Zx+Q%A(ND(C^|Gv3^ONz znV3(FIDyKdMnr&H+Zc>B8ARUq-ZDH9oH%Q1b7pzRVJ&VOJy1UnS=f?(gWf_pp{XAY zea>tb=+w5+sbtSa<@)?vR8^(M$@$di4$&ui0J8Zn*I9#QH}6K$;yXla!B%_{j}ww! zH(0FXTa#d1Hjt89cz@MLuom zh3TRLAGxzSJ@h^dX3_f{jXJL|QHs+0r|bq;_Dw(Nt|4KJ^`!Z~7xNiVH#1 z8SIYMTqj?6PT~J(b1H#xkS^1XnIf`H;)<&3x|x#z+YLc5Uwv(m&Bi;fpI-~tM=>KU zym6ljbbeu){6Fx^&Hurh0wUUbfTsaS`ya9-<9`WW?_Z5=j-bV}M3Qp@6h-;}?hV)%Ycekm#?p!r4y)4o`Y<5}^_~N;=?dH< zU8=cMQ{JtNMOCv#O7V8BCL%_>OB@l2j+_QX5+!B%rF1) z&Sm~J`Q=lt-qjHc%|>>eiHN*Cz%LgiRCwuJhxDdf=ZOZ&q%c}OPb`Vs&6Y}rX`y+| zw4+>=j{%M+Av;G<+I+EAXyg<0!>@+WxAR4xY@H+hRhQb;r}Mh7oSr927ci^?u=sz? zAb8v`EYVIv+tx_%}0*HryrdjPB0g?8G;}RDTm1MlJ6aNu9oZ4^kk_ z$rwoAguLunnwO%I;G4Bu@b}#m&{TXh{}J>MzK`3^-y`j)U>+0?A@3kmDlGaRfiqH82c~#N;sYN5m@GmDX6i;TyFm2o+7&LqcaGR^chL;v#c3oc84Dw- z4I`tS($Y%xv^jKQ5#o9?afew`?R~laeriqMNZ2$Fym9(B@8O#s{&a@;eRI&HV|>%k zFU`(FFAZ?a!E+-K5p>F*mD z?+eWL`TG01HPLYEX<|z52Kw>v8jNG0{}E1Mi$pYe z?-8p0kwN3fnm#gUd~1Ak1RoXXden)3YJ9{8G;8lAY&V8EcN*^-o9}U!2fu&cc%Nv# zcj@m-jQ0)9_xbw!Eynx0=6iQ5>>dWtD@H=Nnc&qwc+q$tY`!nm->;_E7K>B;*22}- z!sXfBx#PMDMS;s{Juds)Dsg#73nrFV?```b)NgMa@(SeT?@xu&u>#RDp@cE~zWwLE z>TgT&EtP(&CeawT7%%@oJKPu({7i}WiUxHT{_iq<&_(IUmCqU!+_ha4&psM>ubAL) zV7xnHdr*t08Tbe7vC$mYE$a6;+MeR=K}{%OiD=^Z1M={ldeIrc;>a*B*f2Mz^$(@R zOGJ9+1P*#&W{jicQho(B2|>~N9<|;}#Z>2BsO9NZflC`QFW?_4UJz23e!36M z<4QpR%SAusK0!m5i&;r!vbT-a!y1opQGK1cY2{ea&{f76IOrJlqCc05Cgw@!C7vW6dztg1d3F?VtKlYK`~Cysc4wKApGAK^Alk{>DDgpbZ$DM_?(H<>=I*Vj5{_l4h+C$phON@c+{s;yUyT{qV)q!))+f7#?Yd=+_lup`xf%wO(Y)CuzqsB9aEY zD1zv{hed|+b7;x2hq3m@aR&lN{T~;J1&_h9EMO*cF#9?>)_I zaT5f@&SG}$jql=raK&{4AK?A^W>kL1VW;EzK)gI~HI02-)E>+3#Y_lhV#akaF$42% zSYiE$jfuI;1k&mmOrZ4by}^{Uk3r-p`y1A&UDKDR>9;)HVIwkxi6HIVYr3Q#z*o5H z*UAHS;`1<%E1?GX&eX){cdKwhgP$rUZ>D~ai=?sf22(qjsVUdN)D%dL5J^`XQ%#vE zq|+d8(K(#7JNf>5RXNE-%uUTA0j{eBh5EdU*M;n z_wcd5UwlMso)F2?78|@KFt1qtWeR-7dUqI63x|7iZWwzzj(F40`ciJzrq2JEv zNDHS-!i>SF*XY^pB26AcFOX;*QYsUL3n|KJ3Du5l52?HZH7gZ~VcLWD2G1FwerX`w zyi%yjs<&xzsfgAyxNh_uMuvB_3@zJr1QJ&vJiOwjj%qm*MkrfYTfYk4w|N2?Y! zacX%M(ZQ7>xpuPUb%19E)qNIow|m~A={rQyzyeTVcTePM;PQ32z-4rZnqg5kI4}*$ z?*1Tfyhv+K?>{RBE8ZB2d=9&9@Z04%tUqWEoAUYt-12hI2JAk3@i{R=sT)Mm&x@=q z4=P2odwGEW_wQad^mQ+bWp}pLlTM2xd(yS7ji_RfnNJJ52A-(ia0nR6z`Kv%R))p}_JV(=DrOF`GIYqel&{I@-9> ziU6lEN1(WZXV@_6(G*yU3nY^DkF;g5Lk@*4)g`{+R0>lH~^!v9-{Kid2j{|DH<-Ok_Qy%b34Yea1OUm4NE;v2J5UD*-rb9vg9A2dJret`MGub8BwoRy;SdMw_9kG6(OH zLmRv&p&;iw=-IUxAHND_edA-7gZ{Tx8y~wJ)N7q+=SX^^N;~1FpfzyW+TXC?*I7E9 zG48y=a+SBZ@@&5IYO?5yv%QZjg~u4pYr&ar#vWry-1aV>5fgJ9*tg) zvESiZw0}L+_J6gsF`)8!Emq%XEWUEr=QvKIFow}WHt2s%4WQ4U+}MMPpKan@mAg;s zF`F3*$83@tx$9dZHeVsTHaX`Np3fD^-hc&CcY(|PgK?DA3rn$`fejd0%gaWN<06MDZpTYdBC5E3H0x!NJp43l!!{z;qh7&X9UfK8VZg`O;4ia{ zk+zoMaqSOf9K<4Lc_Y?5edNTUP`E<;_Kl)xkSjpr@)vqxqv$1?aV>#J442`%=)^`* zFBNN_&3MctU~;?*Vsdc4SaJt=-p0GfoYb;NbP2}l=?!?i$4T>wME_t{kf#ujQ$Vgr z#Kx7e9Z;0kIS`s`56)04k&JhE?%|+-S45lOgkaBXe3I*=oL7J#g?L8ev8|JyeFX?F zFaipvHZRBs@Uw}GfCy?G2km79)V3~s662&W9HuU>q!zD=-lmkz=$=;*k2~Sulh%8V zisx^^Q6v0v1rUj_mR9kAqg|lI1-?i!DkISN0Ph0KJm4c7-}zS(p*l{{3;1UByI6fX z`ZW>m*nkjRd`?JW!CPF6VA|m<29_9@-cViH+B^qFIE;%Lz6YF{mp!MHT?1(oHt3#{ z4wtO%e1&TE5M9^ zm=|7|@yHeuP2P+u?QW>jsM3m+{4m^8CvFcbR=oNi5N^=A(U#5Vvt|^Fdh&7dY{3c` zSJOae!DVQdwY&xhMkROk0)#Ti!=OYP$HA;+q`mqgxP`W7zg}I*?Y(?alb|8;u!e1w zTrk}d6ciD_W5^%}g=`T`$7n3@T&`9{l!xgG!`2plc4&&jl_?mgoC37JvHuU^Xo^GL zdzclJX$Jli?=b+>PR@IQ#ZN1!nMS#l29H6QeSaG7m^6_07DL=*h|B8J_?03&tP1WT z7O?2}KayK;gO}~B@`fFa7Mv5AF(WY)ANWEJVEheaW^d)f#nUCzkUrye(L(M`FT9R0 z?rjVP`>AZd71vQpR$yR->o*>@2{i{eUZlmaKq$N%1THYNrz6G%I?UT1=Xe3+bIInxXhyP3q& z>macdwE;-Oq16UF?m1Hh!x?($@Oo8*MG;-0h}Ex)#4+cg zb=Lm#%vHg4a8&@oacN#d8&^)|3TZDHTyc!=vrV+>b&*uC-=MLGX)L@B8VeygXk3H@ z{%(7iJp^g@8#Ma)OYYJoPXgT{Kgo}5sS2}5ewq%xC6aI3WbibAd77{BROr{L7aFa4 zpcZJh7)CsP+loao>WqztGUZ3WHt?rl*IpuTF0^ zbO3s<+2}pR^pMuU(7|OiHs+ig(>{IaqTZJ_czFT&QTnO_d_(+{Lr|c9@$l-p8Da2x z0X8-w-dE>!26WTdowv}&>jdT%X#qan2+y5(XX+-+&`p*>?|Y`F2fwdQZyIz1dc$q> zTucvXzpT>>Uy(&OSbt^FjqvnFev57-Ki%Zmbkj%E&19#+>jvgkkBMKM*D26V6L(&k zjn^>d6=_?TSGJWI--FNWeN8JjBM!k=xNI(CT6$>w>a-?6FQDbL(K^CDhqT8Gy$q#} z+eCbPG1OsJ5GQ%sklEm{7g)Hk-l!k88axbT9>!irIT;Iio8p33fTQec{Bk+j&O9J( zoWa8yl+$IpoCQxBG_sh+sOz9H3UY$RTQ(Z2mF&ITY+T*RTp_J4bJf6AxdhK<3CJ=u(9@vx2Roo1 z;l8@12SEd%HPuE-tId#hYOP)Z-ocEXRy%<1mWxKsfd5B=p57*F3-l6->iDT-u+0}n zn;MBWxO|(r)MMLM=dwREg7{Yl8d;n?<0<}wBc*W%gK$l+J@Hsc>?oqhjlrlkkB zuTHBEGy+=DHd<9|J*2HMG&0rH2LW{^cxsm4+LKw9l_r9*jxXu4SgM> zBdsS5*$(u_Y2|j&SbmCjY!_`q+z}qGQ%2$M@^;a~nGB`S%=ZJM!qNLHl=5qPZbgy{ ze+4VCT~~_&*G3+D6!<+%W%>%3U)O^h?&>J8S}3{dcyfW3Xd-H1;FI{;9tM5^?~E`o zzKYPoz?m9TQlzH^K9_KCy*FOjrr>|}nQ|;CO~6`eEK`W$p&gbtd%mT6N=1w=OKGI1 z0kWP1N9#&Oi*_?XK>H58QSK$(#%5k;jSf#i9{=d@8&qotqQfICuLC@|F?k2p(Ff2S zNFDeVD6qp0=aO{!I;xAy2vlZauy?`g7Nu->q)niMJ4CPW|NW$|l-}XsZH4uz{fF46 zIN}v8z|&|*0+usstu6>RV#0cS!s;>Qb$QTH=t$sQmHIM>6r3LLf{pNfOc-@T6Z-N) zksLY39kS2(}B(ygNy2L3xbYMV@8FCy90X~8u)`%stWbm!o?2z zb#V_&WRbZ(_%Mbd&v3}rSewD|(=D`R7dBh>rB8Q>W&?lXssxHHV0jSRWE4vm(XQBJ z$OCu0eBNr&-`Oxodx&~`B<9q?#!4)@sr2naEK~Gdh<|*9gAu&36#g-`oi4pVEk71X zjs?(-Z%1l;ElgZ$+mYj4SVr%v9EfKwe-abM9h&*h-T zy1iUU+dmP>EwP7`Mbv_D*o``r6%g*KoQrIBONN3cUP9$iE?g|x++PS;u1#G(70IJ_ zK<%vl3CO{rYLgj`o@h*a>uJ9ZjcNFGV|}OUFO^otKWFnHZ916N#;8zS0qp>Zyfp@i zZcG9ez9tD+kvFgIw2^p4^AJ~MztyyOq&P3%M46u>?37VSBR?0b&5b}B)7ZeNX*$2Y zAM^UY#vB`JI#4x@Bkva_oxcDgHZ@K9N}RJGN)2>GxBlxW8r0ruHz!~2wJH(U6D??mCj-8!rE-3Lna;M?MM&q6{FIdLUe9o?nPw;_uj^J z6xSL*pSh^rcfh+3WHc$g&QjPuocG%DERElXv#p}f(uezST;x*l<(u{}zI_(oY7t1| zc>(fpiRO+0Pk)?8x=CktC1rnu;Q97S8vl)WU9O_K-->sY-1D^eTT$ZY6J@e)z%s?% zhz(d~`ou0QOIig)D5i|dKbPy}pvZY7{hAlOKAkDAHVY^VNF>^d(WYDlILB#dn*UeoVPsAb7(0u z7+v%x-tWNG;ok8`%kStpG(qwdbKWJA=b%);hsf9W9O|ZLE;2K(MdtMxoG6(A>OF~b|B`4cNznS@U8;yc1oV-@D6EZIbK&~dFACYsUjU$R>T+m3Nx94eFecD zP+T3S#!77;2*b``I`My^p7L@Ih5m>$3O+kWc|VHTtv~8s87~F@y(UZ=Tvte0=YV=1 ze;4pq@0Fa&k)L$0TsS+YawXJr78E)<+R)h_abC(ZXDRn5u|)agG=23Gd+cdC`4dXS zh_lr5fEcUH%AxT5@RkL~FAqNWi{x1f+bp_#IYvTfpgB0>zSkzK1ZMm3yT-=5jd)kf zc$Z|nTaR}K!4FHE_>ZeHC!;&6@u;FSVDh*1jC{``-x<(w;CuE16yT^XT=F>cyU5J# zSKWUu(#x@~%0B_t6vA`5G*0@Ol`syoes4kbeej`{&O)4$TLxD_2&ldHY5MGE(IBa& z&z4A@mbTBbjnA5a^fB7AhYIf|?DfhA+#?k%5d&kCLkaP!^ElKyVy zY3g)H#3@rx)5t?&NJCBY>;k6dy7$Niy;DAE(2T!%dTzdwWNU|vb60i zRCy{q?i}(LH@&wZbvZ2RWoU?ucBz}>VOydcq7jNL$_L7&gP#`q}@QhGH-VExj7(5C0LA z!5H+}D}!d$`Hz^4#h7!hjM*;ok^czFU<}&t3ZNhSirxDsso&pv8@Tyzk>x}k{Q&K_ zQOTs(BjRyo=?U6&1jkp^#tzFP*avxM4((~Kyhz@oq82~=Tpu}KZK2$pHmTww?N(gd zf>HH-sz}>TbERT5Xp2wijNDQ|xyM9oSY148Y2l4p*EvCV9s>ohptZ-)IFq1{kBRiy zJmle)k*i)!2n{2usCfm292arnhd~b&WZ@qUsddveO)35q_UH9GE<#$e*l$SER{jcm zrk>>AHu$<9zF?}~7-|W_^T)Ml`Ek**O(N1iP@?|k-8}bRzC1WT-BsxVMgzRhM-$Bd z*Ter)qg|EYs2J@T{eE1ub!xsDUm+6o|2EfBTF}f25mc)oavz|sU&@hGi06MzH^be1Ev{#j(6?Uc683DC%G#VEV@JJU4HsPKg79q=)*H2FZxX|_5h3&R7>(afUnu0Q%_L(S*#vNIzemC zVg&TzF;dQn+mz!KH2s{|tGrV|IhCT9@=#sB@=U_#hqtM1EJT!+H1!oRu0 z33Wr|%j`yh|8k>N^j)p6NQbEfY8Viyn5^7Uujpy48w_&5g^@>EBY7HNL3qR3(zb)hH}6mSFgPq-2|Y^3g2Q^o zNgO7_pMyhTY?NK;o(can^W2NWjNz_%Az`_7o?xcI%TF3UZYTVcHid*`4MK0GB5`W- z|EKLu;HoO#Kj3o@+XZosvM&l;a79H$a2G*L4b3h0Ef6)caw#>-<>H#V93#in6txs? zYLp9VrnppErch?4rGRFb{c=G~3%&36nR5zqEU=@(sfVN<>M&5`J?y;Cn!vi)UmPzX~sXG>4-5P#*D9@$oE}5ztBbwaz$RM ztP>*T=KdQaq=JE9pae}H0TLnr^9|LQA5FX_)M4QkNh^CCJXXtrk8zH z32({RdU<>aKg(FXP>JGGp(iRgbY%vPl4=!f1}m&~@c*E|htr2-m-QNqYV0biu_y=l zZ|cip+bsh_zZm@;u#vUW-5?H_Dox%BAu$8N247aU-V`7pk=GYR@V3>hA_eM9!%8@- z0o4bV@U}HrbLX3{x4HS-7qRF|AG-@wa;R?&c zn2;TT9xTJUKIn9Y)}eiDH$YKz$@sk#+!%`!XOJ%ggzPm~ZF$Bu9zxRmL08tdzi5)5 z^vmBRKkT}Yyib2&{ob}ukjH-1so(+j6M4>J7ayKilZ86pL_?H&xhBKSiG6;_P4Z?V zOdf$k3O=?!u4+nJMC2Tlq+YG8q(6M1q^ZdCk4o|bR!1d`0Kk7z(j!qyZ(9z?ld^Uo zba$BSk&?2nYD(I4m6R08_wl><%XJ8Ehg*f2EZ zi!wQAD!*J)E+v|#M(Tz&>?#lOXAR@?E$1pK{I5t9h999-_!r>>px4pzNhQrs^$MP2 zey6KZ!SgFsaAL`!f)g;m;a^d~>!5;<(xvBDMQSufu8Fw6_@rTSFwb*xbLKAvupaX6 zt9*X|YekJjX#nd&VY@&!hkE=&fo!AO2LM{==g+6tk!$nb<6O*gx2t@45KC&|gahT& z?=L})DQIl1uF`|uVnFC?TkAptLSNfFq>{VE?4%tHJwsE^7!bHZ@fE%AObC?d^ckjU$8Yxy(Z6U@Tv9YtQk-W~C@z(5@A z5*+y0h6)aRY@M(2N5SlfbLkayZFk|4{9`Sq)X4Y6LLFAGA~VJ`Q+Ky*#{a5?iudl% zJg7DciF{Gu4X~Ah@p~&s+{+i=!F<&q8#l zrkbF=SyJbbQW1KfoFd+$#otBT%wPEa5Ed?<{Fz@wX#ER$A5I^E!O-yRdjp4MmtBZ| zU_a_sJ}7z?>BNVin}P3|r=m$tl+;^@r(r3*KLT%OQ6J0_j-p{nDJ5J|F_?%h!T#O} zlm)~62igj!kBxlc&@JVgCv|>+uFI+}gsSzXFW*w9^Mg(kwWjYbq#X~$w3H@cbk^LF zk!j6vrH@pw>9SOCni$auZbBR>xL0K&|3JeU8d)DiqIDtxjznVc#djxD0d8?9*yBh9 zaYTe1Q5;J04@5#E8E6FRH0;nyxkR5Sgh(T_p8j12BE^U!BDMbmk-Jy;mtoA}{I`nk z07q{P18F9J&!~d<`5RCUArUhd+dZK36nc&%MT? z-2bxoqkQ|W@blp;q}oHh3a4Jic1<5N1_2Rlm^JQlnOFyI?g!wy8KMi7yN|3D-VM5xDT1`$w5i@*BN zq>}hC7ON{KUEvqYScsdDmEMkF7v5%*(!P6&-kba8zRsDnUAZ-nmFfldZ`6pTaS&hrZ-H9QAHc{`q=y7 zX(R4;gc4A%wYH!idMuD6L%j<{7GZcsd8n<5MZOel7|?q(ep9K?KIBl_pbby`u5ZM} z7Gvvm%I;_~Ur%b8CIprsZs4s0rB^)TkvrS&5>L%@cXX zqBSzTK230HzRZ8G&$=3W2rd7>s&lHO_CvM<=-FH$6J69fRhRJNvG)im=TKLAX)6ol zH_J@U^4%i7zX5COLB%1dUMb>_8nCJIkt_UE4P}754PisJ91c3eBUwB7^(%Z$B#V~I zF7s27EL6t2#EnR1FiB07pW2wM3I7&ph2V(xhTkJIk`K(wOGU$vf;tQIxB)?t`_)0*((8+8| z0?nqZo*ZAqSu++Sw<+S0%`jw-D&hm0u{ghw$G`*@aa%JM6yF3D#b#} z!O>HTb3cz|AujSrK&)VXR*V4BEmEuU?y3yrsh2NG)LH=&%M5HQ!UWUx-reXE(~lso zYUkeXqGo<{ zX(IZFvUaS7T=)}b?IDf5Kk*&ySxedDBEQ<6g;z7_P?vrz<13E2S~{KsZvmUdvV=Ot zMM@vwBHcu{l>a(@zk!FU$nH*(diDs8w{EhiWhir-%aZDYQPq%CiND%`^>6$cu*QQg zi;3!lpKWa?vI`pa`QaO40k*dVRbQL+64r|{<5+9nIF2=r+^B=4I1^Zq?X_~SAOSW> zfCbuyUgC4&*kU>Dr(D*N%`t_e$xNpUEa?^|QUB>ZUQ(|?26Q9U9~bz?@hm*(_X}mb zI^sx9*YW#TJlF7)T;RXQvx{=hh1^pK%)|8DSRgPTmc{NimJ?bD0{ArHbOJ`f#CyD~ zCgAGF-U(6$X_PjPB}giTh-X?<3(~tHzX96}-0N_>RU)%^842xlj-I~2$0f3FsO=-w z^V17iZJykj#rPitk7LJ(8GpLuB0U&8M67P`4?45;5oD>|V#P97N3%4EHeD02+_eJa zHX>Yxkf;BKvHQHISRMKG3*7b;ikfhN3?Yi|?ZV>a`4{+~U0C?gLTt7dTmwzD^QK&wT1>Yp=F6Z^h%hIkaOdbT%UD*a&%IwvR^_Tab=Uck5 zxVkpvqEcRS3yn5P8Cq9rn5`|xJn%uueR=cwtRwICG@B=9{m4%}&4L|k5}_ai5RH;f zeB%$?BZ-ak-hwo0SVSX)24@rAJ9d?Q`MMP>%%IDMv{AMh8p}K?6>P+NF}O|bC}ng5jCrGmqXZ@+aAdYsrvOK?EX90^Hj-F# z!qf`AnN8%kw8cQl+jhL8Rm#|eV(K=OlRylR4TZH;I{<-!tRAXqA^N>&5EOApFWHQa z2ywXv6SLdUVd{b+#Fyf!9*@fBmY6*f(}EQGBnccANjXDN{zA8e>=MArHL3biA_gav z*zY_)*qsHXK7&kIbDz6!=%9Q(4R`21mf^HEs;9v)BzPCUA5QOpZb{2S^&+5hecwP_YDc3m9Pa(3A8vu-Dg~xFS znfEg&V6(lh9D1IQKgoi4v);_b3fA@$MH2owTIY}pO4~^oD44S!I?1X~&g}M;4I-_* zS^$`GgIHQ&5YIv{js~$K?#Tv`2OPZc8RkDG->mE38>)M(G@;&w$ZiN^5~NA$p9%C; z)h`?BH?^;%{y}_rPv&pk@`Ho6q3rjm%hr{>0cn|U&dkn&)yPO&kF?CW!|#(JtVY`7 z#A|ty0Z8rDfdxsiE7SQ25AJPjJFzN@gfN*)}52SoQzPA_i zY}6M3|H%Tz{ZL^6qrsaC_#_MPCJS(a1+*XwaLayp)TCK}rGv15EO)&+hjmbE0Vd2{ ziV@nzMErJ#Cu_RqdA_DM3%2T79tEvENy|T=EQXek2(~2k6i}CIc`l7MCH2{I!_u{k z_)!8jj)k6_)eNT!o6_jGB2LIqJ@y&giR}WnyR{-6Cczpn-e;SW|`=s&}vg|dY1Y3 zo%tjg#&=LV8K}T^BO$}Y>{56yilQJLMgE%%+x$SX^W$mHLT1TTWk!gAlw{WCNis`` z)0!_sX324a5l5K?{DaI|=`zEoB&?$2`b^shtkiKW{s#ft!L%qL1Xu!O*w-Ny$mmtb?lva#Ka?t&xVmuNd7xaQrWje_P z8}VN3CPmxYSF{{ib4>-f<+LCO_yyd$mRPE2Y{FWFNlgG?VJbd&n}~M+t^;6I?sLxZ zkO38~nA1P-In9C36!1xX)yodN7(tKoWW=Tx~&Mee>+%sNKg!o^P4q@k* zXXADq#P7n>@&qC?-<**>2X^u{B$+vPnCPKapaK-Sb;~A%)WR)CT4AEr{4M;R|2_bd z+}YoAkAWgC%bH}Xa;g5KE^vFHJ54F}z0n%741AZAYL zkM~m*9VckERqr4!QXh@Oazxw>#P!qT3_;e`1(^l`_Zb?5Z&s z!>+QkJY+Bn_b)}=Fq&_Y7KT`2eQw}j46&}9<+BE}popK4i6o;ZmhZyS1XjeMM4td4 z^bced>_IH6!5-DVE#H-KBa?kFiv->e;^Y80M1H;Q6ud$#0j`NfJ4P7c7hWr!6j?L^{A#L*Cr8qpC>6~nhdXZeny zr~rM=@-Go8Nf3Amx_`sSONT;j9nSKgVc45(Nr_F-*y;wI@Far{!`$D{9K>G;@jRUV zOm=CiZp=ux&vkM%W`1KJEDCDJf?g9|IE_r&XSbxVI@=$!~PBpXLUP%iO9k?QN1Be6v57teF7Zuca_ZmQfs<%}{jhlgG3OWIog)gqrlx z&1ihfv}%(O3F%gm7n&1oR=xoUG!sF8FH8iVWdT7Ehgx4UR~xVg8k*aP8@^Ccix5u( z_6b6BG+^f*BN>xFJ;Q@WvLNdon3>~TY&U(*Q=f}{h_ovFX!^@EsgpH+@})3Y9WM0e zI8KNDoGOjeMYH%KV0?@v8%!R+Gv7Iq)s$DB(FUJCjzr79=!_V>uS&(JDGeMLiWaH@ zweG+|sv1nHN|gUTk4|wCb)cKEu#)Vgjs#2|7FI|iq^j2cpenLuQq=}YSJlst{;nz; z5L6LOxvD~ez)+PLq7jX7=Zebq1*tEwq7e>vRO3;tvaJ*h`k)3D$(kOKP>QFd4G$T` z{2H}{WT+;RqZBngvCx}Q8=E4{v8{S;6e?r*layH~tG^&kh!>*D2ltg$P>}90e-?F$ zDx+T%fPSdbdVUS78jV)-&bK@cVWaENk)b~aj-Fgmoz7?#_2g(&)Gr;N4ffs!Rnq?E zZ?N))Qv?sEWA`31Kx>s_PH3lT-mG`k@$J;@$e)L8Q;}YzrPB(lP*7nz^?kyJ6;|<{ z+)gaMzkzK9DA)S;z8M)N0RWk?UfE6^0$FKoVU0se!YNG;vbrJ}c=5xPSSO`y^#9GVlB0WjIm#-xr6p4%FcKLkV6gX&|e1#=P zhM_1sQB;!F6#OP>tvIa}*B1&Qwf4e0++ZNB`YuXvv{OFc|1t}S<^Xe)*gyi;B{oq< zaSwS2MKipYTp?uz@LylWKH;U)#6(BlXEIdwB~pj$OoZx8w9zpf(lIBD3V%Td-i-I5 zI`M%T@fO!X%(3_%5UgJOV>*124nGg??XhzlIv6`=tEaNsWD?LO-%wzRjBTh!f4q?-hYa-H`pe5(J4Oeb?mh>l!A1B z?iAngI!5#^`S`>U>m-lW^R?3R9RN1Uw?NOg^R&q4?1z%^-k-UI^Ealm2>A=Rw@zn~ zEdx70poxahY}^-`BB>2b@of&EK(W~NYlR11$@|t}JMg~Up1&JQ8-IkiRRcC#xP3Zn zA~!zGqh_#>T4^oN*I`?)2wQx`PPJ_JL5jA*i@^$ypNZ|g%o%W&`|&jYeFlpRZ%epS zvELBURt-j1*>a<#(iy{zb4>-|0B!Ln-!YTL@o6)e+NVfs$p@j)4FF67t*b!8D5*P; z7cXsKJ!-}GWp610?7TxN1MAM`KQ+2fjw~x{WWKjg>ZP@*-3y&D;W3|~- z;Pt#;>@@imySF$6*@RC^V|8eNUJ;X@2J>k1H9wz*Cc^YJ_n6J1%X5&cay^n!&98wN zw$&2Ej(nv#h*BLe%DDY&zGgNH3Hk1%wgylS`Rd}KJYkSMtq-jKnx93Ua^!Tjv@T}n zg#R+&;G67Y#$$9w23*?LyyqNN&%6h0(_s&ucFGjPbLKE-`N&Be%wYIR~mTkyj zt@!$7jPXJ9SifpIERI`-@(pv@GaiW#>0Sl@=*+J;o6r2T0s?sj+{F3V>refP%L~|u z@?>MLwK30Gz|8)!Iv0zuCueXWwqzHuQ?zfn;Z63b-1sX#Vj-JA?*Q);y7o(r^~DZA zp?#!=*V@JJqw;lJ#Acc%^Vu0J$oVE=yRe9Lu)YmxjD@@63tsX2$i1ip_mNy{C+#~- zdyaXnG%v2rSZ9XTg@eISN!^sHd2xM+mTDoWIXW23#`_#Rj@zQ-J@_WLGrYK_fhN%c z4XYqR!{1`qt)D?874L{6J6`o4h>QmjGP7p7xfxzuB*({jGc3Yx=uMgx(jisPqmsG- z2>QeQE<$s^%c;YhdGZqG5>(}kFd3CV3RrmL)%9Bdz$s`9h~o?RO$HWwg706#LY$hM z(6^s&E@3a|>g&U|EyX|pTDY;44VKjtJZTyH^zm+3N}T-C34U;q7WvmQw#NlLT&u>{ z&t*M5j*4#}`A3JH;B18h+(_~b=|I-=B$YbjyBeDz-MNzbJ@OeUEk+#iJ`nCl|5l|< zQLfsMw1j=AunL;|j}^?zN^~N$Ri^z0okUH`M5pb4pyLHPf72>jwkK;9hdms%ng|4> z)o{|PPdN6b{t1*IZ=^$~kp!me)QaDv(;vRz2j6BvPTzc?yFi8|$S@I=O)%d?C4++W zhTyLUT0=1CIFDM%0<{_k-995v`I20Cg01~3B&0k>LMz}D_HQ-u{BeCC25nHA|9=!u z_<{16w^*3p8bBIlyn)|T#;5f%cB)jy%(vKFXDTDLK6QECT-MlQj9$p2fY2>f6tVDx zR>X{oBEEr2A&kwz2>yis*1s(x37m|;a8Ua9MRai};t;)vyFM3cl(&D*&%X^X-J5@4 z#ohikYwUc}9N3vRUB$M`$tU>5RqRW-`RClm;Wmg-7#j69^7t>fE0)9MmS6Cet65^X z&mcI;C)>eVd8|uYu=^uV`P$^e|F@dCS)=iO4xJ{|mA6AAuk&EUsH0zEHTNq#)FdYL zZ==3=x3zl623H!>;x%+E>zX%iE=h#%bE>IeBJ5Cz5p`=5;;1g&gzp!`Xn1i8KQA=H z`Dlg>C+^nb01LIl$3Mr^Os}-W$lfP0qPA6E{HYE9;2jp&si#4e)|V6MJ9<90Q~x*B za-v&4=dNp53ldfN1q>*_x1aM@*069T9Kz`do(u_MG!X3qQv0BtH5e>H^7b{5{Kn5| z(i0W@0?JTA*RP0$V*l%Ta0V!crJ+r;wOHVtja)8#(jgabp1+p)5^-wgtAp@MNFqxQ z`HYXak6q5j>oA;z1q@xs`gp}P$L>(7qyoEG==|*%Ke!HUEZ{G!V-3A7R!Kj5jQhRI z2Kc>$F3)d_4{Q11*xib)3(67t_*X7x|udaZrPf_`Qpg{QMb@Tn`)C{uv*# zo;CWL4Plu&%Cij1(!i1X8EyyRCRy?EyQTSKe~6exFsAY{Z-B+EN8~2W;)ZWvZt|+n z_?QhaTd@7+2G-W_PtL}D-Z*dj;|6A-Bs)Omk)QFFnXImJK895MxlFWCoj>C{GFfzR zH6Sg4!;U6tpX++RC+wV#rB&Z771T!_(KH^#o&E4xri(22(2Z<2o8AbEhnKPF2$3&6 z%0o6`;yU{%AGe9sb|G5&@Gbp2OluAvBZ)-tYnxa#dBHJ$ZxibP&v&p0zuz$J*U-(z zFY9KMc+RmhzMeLseE8R!nVZWSct6Q!XF*r50KsPAeGde|@3Gd-`T8uXjokehU-=%a z$Q#)!tjPO%nu8UQSn4-I2AUX@!rD>iY+2ax(*)sNNf3rr1t34oJH9-^$GlI1*bPDO z_gSC*yn&Pv4X>7x2<+A1cgbedAqb@i@9_;`Hf~R4ZzcC9TJgqO$)`tw3BFOAbeE_+ z#O*~KjqeKqi}Ngzb9jd>>_yf;vO>mVj_^HOa13bJ5&me4)?$TjWo?|^0qCV`CJUdj z6$`2AszNBJxYyB+20 zDfBtY4`ylbH?nXp6}BU0sp;9w*~tSWZ(Ik-z1bl7%@O{2HV!eKID*@AAjQ0qv}NgQ zNHGU$esDZoDp*8k6KeTEGCw0H85KVaQ`eobvCP=ql{otL2!F)}$8PjRAKEY?-W<=Z zA22`HPM+`!t;W}Wz&b=HfC1FPm?F1Y(cxI)B|p$w^`(qFth3P?o8b$pARj61!BOt9 zjcp#HPxxr*4wH@?n&`Pv7N8RE$?#&sgzv|CQU=;rv2;f$EyiXm(!T}o2J8XAHlVf0 z6p6cSXN%-ZhjUkMXF;amez1c~wCF{tm=@;26tQ=*1Q=gLslM33o|XsZajy?qgb(V; zQj9F9<6DY!`W?i-=2#ROwv(Bwt$>8|c)sLA)}&g0hlryevd-G6dqc%db6A*%5V&?2 zdW@{|s59)p2MaahJ_r!EVLH`yZrW-kyrR`LFQMsTvRaU1#Zla%qbT%Q5dYt?4 z7C=9jQ)Rl5Lwcw>-N=VTCG@pNj+9v|6U3(zuDz-g?ABhTZPVgZlRC^Gh=La*jtKtv z9|-OO!7C^vjZx@)bP2Zgh2egNB@T+zS`PQ?@z~WgEZY7N>lTw!b!Jk8l|>D-^MkvJ zHm7I|8NLCu1|(K_qI-bVqaaHQJw(BP8Gh0(B7v6{DQsro5bocA}Sg zC6C|R2_N=20My`z&zZbymUE477`T9IH@@*llRs`Rb#V?g@MX;%qPM#4j_n1Xa0PSu zZooy&#GeQG!4$=hAK1mZ$sZr#uDjXbT7MI)-g}Ytmk$NpbPW3ra@%fJcPKXaUA4t~ zc-;w!X1b~eDU(@>!Gtx(@?*uIHlA9k#EPw(wRNNn)b?~oM_k~*qJCR-dmfM6Q{l%V z)%{xof^6F6-V~5Cz(znUXk60C71!93zh#iI;L9LKCA9$Wg>NQiqatJ!;u=5dLRKFF zYuFH)NpbqN>|2O?PM;s7lhqlzB5z6ni=`{HX8A-=W5!kOTh5HD+78SZJF|kpFxT>( zS?DXB1Uq3LHiObhA<`kGJcJU%`b{YLU3zC0JsFoTgtY%IWZAIB6n-N=9hQrfjO zP2#r>v0xs*9}cuoil?r*po6sW2d_P>Ts)la3Au? zrd#&n8*&la6!m=+%u$gNBx(lVj*2wO;RPI4+7TRb-7cminb))pK>?t<_KgMtM~Rw* z5H$6kN5KtbRDX$CN;e;N)m-~vQT>HV6S9AG*j1MRSE9}C2K_tr<+-Yd0A!Rt3&b8y z@0?wV>MG)p4#^2e2}9CCeXanis=oIR@%{Utwo?%Ie^Hx!^`N$gC-ep#%qHZhvnxJ@ z-sYML?(~Arrn_LtRm-3$N%LpL3D-Iyzn3B=;>WGaLH#87q zQ1I+0%wiQ3se;c%TjGQdlR^7r73LH-m3Hh&T-$-2Tx>g$Md62|Zp+`u}w$OdaDh8x^wDqKNDTp>Q810XsXD!LE7E_)o} z^$xHQYqWzg5F@@iBbi{N5z=V*Y|>#hd~WJpVj2ZmOen@&pg0|46iE z4*Iuh88KFqbjD=L2m?sc4IsUwYTfj)^{=8Q$GZ6?m@{zg1TLY4$LPO=3SmkRgTitH z_%yt-VO5A;Qg;Eskm$PxV(5SFr;pM99B?QoZ#0+d-=gb(5AE#h`acN~lGs0@I9>l= zAnvjH&orw`4JIJcDPZE^bVvOo!{hWn7eH0@KkFbLa1i?60%AsEK#VNX86o{|K-%B* z55g~y=%D}C4v=q6Wp8WE=sh&GI_dR4*+WeOOfpU?i*|c*JK>my1!Jo!!-_Srx{Jv= z9fuhPHPC@l(WL#GUartxjW;9%Vhx34G>2XTx8cyMHWyQ5K*wa&~`O$fzYLl=rv zO|1)i}TqS6t)7*yg6%z?;*cA++Z!DhXu8jO4r>VzmuUNu~}qfLqKS~PRD(vDT7 zZXcPhqEG?=2u=e5*|G)k)I^c?4noLP37MWi=z>n@adcq9(dC481HpWh25lgXX5lCS zf=>9F7-QxR9IO5CJR`Qjtkvt4t5Z#lxk z{ZyUdsXD`HsI5y6@QcV3HXmt5jTUskP;cNQosam0_Hb*-K5nZpE`y^1Z*dd@`wj>B zxT9>Ao2VODJ-u<11!^xC4l2i3Y{Up4Ev6dcq#cmf#+`n~cwP+gj8&8##2kn{+RxWt z!P?xmW2}M94)C+bSfo|753|i$`v4DI!C{(Ny#=6TR0Wz)Ct$Y!Mc9+aZ&xWVszVgI z29n(5t5v%QoNB0IEhcUFW)2bi51tqekj2XpdaXyMNAVM`j~3)9v+a z%<$pFKUlbyzlS(llfoh+H`b&!e8N|Ljyp$!+0lw!87SgCE(hNf< zp$L=?y#=+}1{wPoEVk`P2Y^hsnc0D&u*2_D?P*#m?e%Ogkv3SQHTZ;&KaPR3#UW2g z#6J_HZo(M_Xv04`4cGIV$C*!m*#W-Lt!p;Ov3{aSnsy>OdkG zPH-=GX&r?)8XUh%GSLS|J5g>LldPsVy;5tEvtG`qo_Bcjlgx(} ztp&yiT*9%BF#0v4<7Hb0yar#%T?zfnq&tl|{KjE$gEV@>6Al?9vz%;DvO+kw_6%UsF z9~e6vt!2-Be0c#n-crC*m-D*L%1*q$h^1UOTHy;6Dd$-`k5eF(j5W5^do@3+&-Q74 zRt@&%vTxaZxzaXsAm8;JYcD^aOMA?ITC0fVW92N|Lz?C0p2GcoCb>s0zxX|l-23G6 zgXh@ia`7I%;0JbI?!HI!?8*ldL~+d?jp7%%{K$FMDI{_ayfk_p#4uEIsU^l!Jfv(1 zw}%Ap;o%opTlNz2kYJK_m+_}}^Klng&!GN@yQKTKr2%grkq7rc?cv{CV3%4QGpU`X z$!h8hCv~G!THjpAI}@7Ugl97z$w)u$q!uZm(H|n+e$-UJ(`qU{yzECd(JKYnEMf4V zo(l_yl_%rd@;_mp5Jlho6U-$+;-`ONuh5QO;zbr~O5(3yWbN9$05Gz#hL%=p(xLzr z&M}h`OpDeCH1PKcM; ztvq3h8#hY@6OfZO4(J|w+UpY7P>V>H#^PTl@)}f{USXC{Wv6DP6`Nz)NX^J3R$h~U znKWPaF%8oa;NM^}@yl1(KI<-sk?@P+_Hb7VQAdlNB(*Q>fR^+zZxb^Jx|Ho3)Wfk3 zTi4ijd60s4v`fa;H8zpGvHcbrX#-nS#|;kvqbw9xUKW#NE-#F5%=rmWQ^YMyxZzvy zjLRE8<|D4ccQJT(?xw4(i%GurG5_@!){d?yB_G{JB{)L!>`wkl30(9}?B=!-R2R0B zFSv#++p{0@J=bur=>cBzE=%Oezry!y&MrRYR~Bk5!-u~kOa-)`5DY1Z4UD-abra&K zWm-$VR#i4IP}&@n_HP>)uYQb^)6g1iVvGXcR7yxR-vSzjL}kz@NtAFs-OP`P)&Nbk zKDOEafzV(OLjB7}{mV!F%a=wutDS1NsHt^aMg6O}n-96pTDn|DzLw;S+>HNJiv8so zAM;b!abeF(h@XNn0u}Huev`U_KjI_)V0Czx->@&32!YLE5!JEiXk4aK?PFg28*Ay& zP|trMhll?UH>yngi0}9xTQg*lu4++WEcF(mkW{w%5X44!i3>AA9MRlLo=5*usMe2g zfi~{lnfDQY^gC-SKeLm!y#c*}L?#B1G(f)!(u95^hCG`PM z$M1@uF6B@wbK@rNpi2a%DXvm%jOH$-H5-rJOsNDG39$a~vI-_JY$e@dZvRZoxXP|3 z(bF$V8-w3uL3tnY<+pGl+K?Px?>0;D%y}Ig($`Dq3gK68vupC|96q8H^)WezFE3>S z(wA!UadjIsMak( zk9<_qqjWedpR2k)`A-X9@9eb6Lp?$G&r{#h1&IKh(tB9^$=^Dm_F`_eA=ARO##;xxe0L^-M!J zM6Q=M$1)M6P1NdiETmAiPVXkCByi%m)0={KG?eL8cY2rY;N$*8onENv| zpB?;-GHuLMu4{^Ky@T#H6k{nPKKLQ48xjf*cI%aNGJcZ{oZ6;^C%5qt57`{g7q?>o zg^_nQKDWi2-DZt>z$11{Ub>xMe8dvHs&p*D;2BrS`thgjY@p{~z~u)EodaH27>Yx5R6rIVU;_3r2v2?j@sZ#bNa47?-T{C5m=JCr=JLwF5;B}^$SP4A7kX8Zl|Ck{Qu(zp;jbV_IuNqb z7I8>cqQ`X@6Y>wsm@Ca0#gMQzxYha_Z`&(^b06DD8z14K%#t%d;1^w#Ao-mS_@6Gy zVxLVQ;CQv+dc5x$^Pn(S3qMeo^_IJA*KYP~ zx}9$JjC4ayPVbaw;-zlNO!*5N9dddl@?(HJ1&)$2XmBISIAUZ$9EonLF5{x?GX4&> z&~YS9e%q#0kn-x`eae=wsw()!J zN|bp&;C4N-@8-#kWFH>yp=8R9z$Tpq$^mP{;u|(?#<=wZ?Tn8HKzMI|If!qnri_tm zZ{r@GN;Jtd&Ql2uc350XfPW;(s6HUbGfTUIGu=}WS8(FOcyjcT)b=*qYOe$(WrODw z5F|O!<(j)u7P?f^D!yLfZ8Od?w$nxb5cvb}P=3-Fkvf-E#?ue-=;}&e`QQiqV09&& zXH{2xtf}2M>eZcQ2XfuL7pc_cTdFvWVhWr~!LD!O=Mc9ya=aXtGiGDV) zLu}Ce>O{I(fKG?>2DYGv+b6XiYbWm5@c>D1BUdmwEJDbn(QijN7 zHh$3yRlP2i)lKTN&J8|wZqg)AoI_mbCe_5uHN9cYYTVyjvABtsB6r@=TX|iM-OBfS zE73vSz`_RodQehlXTg%MEqp6?^+6%lY~}TQZ~(4Z7Vqf;fi%p@9p|GQG0A(k@+d#$ zt!S)q+;K8RqVu#-gIF>WUs{|M{}xqPD%x}4Y=f&b=>s>ZUpJcMVQ-++Px(}Cl+8c( zS5m1$8ms=vTS*)~Hm@yoD5nk|7odDAAMxNF1C<}-;ahl6kaAnTnZ;SKvRHojK3@~8 zd?T;U;^S-KeM%PpvzGEmjzw5onJW8d@mE5WKjc1s{KZgZl6+vRmhYXdd|VjvPZjSG zJkX*%FF(7L&#@>M<>0M+WVmuwuK6C$$^l8~W}Z|>X~iEzD81wY@v=bvP>*!4t8|x_ zic;z* zCn2KeaNW$eG*r6E7Jq)Dp;9+>{QG78vw_*NFhHd>AL29ieJr1W7ZE=%KpQ}(;;a(l zXEvYX~LGG4l@jCvpebVAWj|Jvmi|SA+JR$!u@qEg^L6Dp-82+as`v<@o?RAWpd91DL|tzt}{Hpn~8deo-M54JL|U5G|nF zswjFzX(;UVWn-EFLsu1|BN`%mF|HFiHJP3APxj62@JPUcB+*vZ_S%N;hm+X40g&pzpBwm=W{M>s$I+iJ6C*bR>QXbMu1A!fyKn<%&C#@< z+kl&qmGEjE5kC;dO~+q`Hdktg?Sp0sEzLQL(b$WpS*TZlL$qS`(VJj%z6o7`XEQ#zQ|MGHx*oWo;b0*=93t@h%|>#=VGqP!lJ;$( zVib$EZ>OLIn2ZljQ0qYKj1hUX-^F-;AMeR%4drUuP1%!+CABRO+Ho95YgKSC@vz?V z@pUZ}pC$v5oQYmE9=kgI@H-g|DE;n(->>2`q2P5_e~20%N_sGs7tv>(W_6G|MJXuN z@hTsM^FUk)*brqw&r0PYDLUh8)iFwN9EwiGrcYE*XG>%Ph-8RH($|5!mrkC(T-Fcd z%fB*J7%UIsc~9Zy^E8v2Cr^vTQ0U?YzA9G1H_?zQ_fV|T!Bl+;B(V_1l2DD~xO*$5 zo$tc!nsXgRlN&uHo#lgDDczlx=auoTt(0hQd>OaX*jj4pOSRP^|Iq0Fk?D}aZT%MG(m6byVt-zUb?6t6Ivg{Cr2no8)$*qw;ouH;B<^ev?tHs8zcIum1NS zHX$uHx=|T(f zDK_reNf{Ne8k=N9FVle@d2R8D@rqBtGCkFin-EG(o8}V0Pj*r~-72xsb1ff`sKixf zqehJE?Ck+zmcnT0JAh(!NH+s|w06K#I{r9`C$Z`?%*sD#u1 zGOX$Jj{k;o#u{$x3KI=k%fq{2QZ;HVU)&8Xxbs?W>!w6JbuL5uE(cnbvXNB&9z4^NWfN^E+#J zQj!wKesPE^TEkZ*DIw86A}$RUP0i0);LVtW4SU&dNvK7-RfKO1C+lgakwy*e_IEhz z0Vn;kB&D<8J^8V8c-v1n&>P5Nz4q8J$p64qJ{HR%bSF-4Q-9vPm(sM$uVAg})i~Q6_}KzPj#uLx)RA`9 zkTRos_lsEmx%8^5#T(N_TWf5O({vG^pxhULdqCRtQR-N4noYjKtE(Fv7xSF4 z4J`SpwSgiJ#wy;^eAMf>Tp=9Le>~|G;}O@DlGQfk*IO%Ne}qK`V~D`;%sx-*3s| z`zr0deur2ohoLw5Gd_NR5^Wv<9H~ci-8Da1C0F4wJ4RqqB(0B{r8F-pMUj&^auxE? z?{~THKxKmEJ-j*^#a@7AO7~l0+z?IKCi3?ODoveFm)l4h0McA4xXA#3!x)jcL<>!judN4fI9O@qJi*|? zD+~aRGKo3Hw+vSLw979Re0$q0?OUnCA?$ljfwcM*{qUjPKh#B3zLHFU9 zx9@5mJwyo?o*CuwgBq((t>$BfD1GWz%G?BqsTBc|n~s_5ujUtrDD~Lgx3T;nY8gJT z$+_21rHN7rLABMq=TL3lHesj|>vv)mnioi9VR(F-vCdMAgz4wR)qMX@C3w`rP_+=- z@x_TI)dL#GT9w$mqb+(GtS!bS1e%5Nv-8I>oVMUSypjWgpKw4J2{P~>@mT~ii^N<; zvx)A!%`hbxm4Oc!ro_oboUa;&9@@llbto1Y&ka+W`5oi<>M&pvaP6BcrLCkn)i0|k zLr?hw&c_c|f?VE19ydN|xZ>~pE`IVFmt4d6@!^W6^%`EY&{<}C#qYz;pe@TO=zjLx zpuHqP%bgH>ehp3sM@{NnNR~=S(%XbMDxuSVDB%T29)oM2WZ)&-(wQ*TGB3=k(zQyX zP<)c?=T(>~iNJ}O_E1dNz% zoxn&H4n=(XC&ag0#l4=>Rv5(WAIB?6K;OU3$3Lftv-ghC2jAx3Jf}n{9>6vnvOsf} zPt6@>?XmSXf~VhLX-PW0-=Oq{;K9UY4fmG=?(=EKxSNUDvlkb!&T z<#QFIy$2b%90KLlJJ@t|uwW4#Y@V-r5O@t5TUV9U!1P>m2^5iezI?(+rFQt24%iBT z&4Ac0N`OzCzQuPSUtB(2Q%6#xk-+hh+C28+Z+6}aSN2~?x{+znjiiToI6V`i&C{^zN7qwR3(^sAXTZ6 zrH46OEd*{_Y0y>iy1s*G^W$Se#mReeV|?%cTJH$ja7nhGXWM~wvJZn)XRtS(F4?9 znR4 z*Sbh@!Vy=oBkyY?|ARN);zyoW`m*hB;k3W7L|>bn!NbQYecj(i9L?OExMeiN*7HTh zgJ+Ia!aU|6fpi~edE%j2_NP=eTeNRQM@ZEp5ke9H^Uc=?A6vV_21SWk{9w}n?BkgB#&imj%9Q*g3{ zuU7I|Il;@37%<`WrdGRg! zYo{7;>=>0MN0R*2CBT!6kA1w4*)XkJKvDUY91FZr$T!JUQ0;Ag@kM2*b+(`82pxf2 zzW<=w{8aXkvj`h$)2oR@318spPjT?VipPBIMG=>f-J9Yt(WbaDh$H9d?uav-qfiDd&(@Gx2WDwMRB;!&9G#@$I_}otoMp=wTSgTFKcYrKQ!4 z;!w6Ul%qCaXxt|9;}#8x()2R=iSo?M{_DGnGS(Dv)3fi1IIWDHh;uBXQN&DaTp9^i~(eu3X)bKj-&F5{K@)`S3|;p19kjhkHq)bq#^k1Em+8v|PL zB$XD=cigkn3?|2X*k7eJC_>YSREq{X4{R3d{_JN}(O~~w;(7k+T7wnPnFs0jb!f12 zBxEprxJ!W4kZrb(JQH#}1mslLOu8&ZxqxhuUM`-_<0dHnv6i69mKzqNW+Dq&?tYwu zAk@NgyG4{+Zde9iJOP%wF|gcn&!fm>xf6&3-E!xH1G3z46sKEmnutrt9!+t&R;MG5 zEH@c(hUHEbanrMhia1THlMv^q)&JXaGXvFTh8$6@K*+I@`g9*Ts{Zf}?G1tUB9$2j02|yhg-};IY2DU8zn*E@PSjc{0 z$$QQq)T_tIbj>b4LY!e2Um%W-ifp5N`caW1hZiJbW4l%_}xp zL5#FDX$4l49PYptiYd|?9T#13g#jwnmUtH_rj6dMJV}96TOOyt?z#fSxzS4PJha>% zK!z0RLR^HL`T=uFfH+G@jOISc0+IvN#s)kX^%dey$QJmJX1IA!i-Ndb!p!Obz!0U# z2*6Op5uqlK2wgEyiYbb5#egX7>_Dw4cGjhm7O1vVxz`k>A&km|mlQhBFoaN=69oFAE{ga^$8T(MJN^c+8_Md4+Xqpn;_H*#i3bnKw zyp|Wv@_bgF?Nrk--$(;K%C&`V5z&`Zv1z*;z8*@Hyln+v^STlg^t6$$i)V{Mq{DKe zFDK%d@^XF(`MloJ>1en^ZC@?Jksr-tpz9mhSJ}CYkADOH7&VvkRc|QKUdhNG3cfU4 zp|;h__<5vz-dm=*2^2&5eB$dENj8|SczQjB>~!Ujk$vVe-etNnkhW_!Ob7bm0)24x z2#vGN5vGDqmhs=GgOUe8$(y54q=ni#E#uKMl&u6hAySU^x-6;VQ8>Ep7itxoG@&z< zSeN05{8o1>uqrMAb74k^imJ$`jgEN1Ox!B8Zf1q=Lbeu_hbW@*)lAKI;RZs(z2Rvs zOXFD;Pz|-H-iRWop|dn7s~&Ei1)jr?-S|$4Bp#n@9Fe@67Maw_Z)gZhWBXgJ)hnW;5|xvzlrxwyYL|*j|Lg6l!QC7irYcbhJY06%#VLxGpp@aT#BqrbH^|K!bKQ4OP-Ti@vG& z7zpBNRYME{!DH?U9x_`Aax?OEoUO!0^hYM6oh`v7Lt51i5Vso`8R1r{Iqr2_#!oq7 zxIq{i0)yxj;cH5y3=CoLaWF7!m;Vc*F{9Fg}WQM@lX$!kuI;zWlY6uXIc!Y1F4l_f(L0oapi}UosdHS8~VC2Sdrot>0Uj zJYT6%PReS*g;(8?NG9@dG2b#@iEbHo#m;@PVL(&o+W38Fy)>x^a}+b;Lf@4p&Bkw- zTDoOgJFzH7u-4_AEl`?TZ$+pLUeDTVHn}g6Ord9mMM{mzv%LtbBddUiVsu|vjYz*A zS)QJXbh`0OpvQV~@lkD_LT$rEEk4ImqXOSR#M2e10#86AwXXrt2MOO839TytsH&Va z;(J%bKZW?ujd(0F8+baRTyH9V*8eRo13k9Nl-&B<-WLZx;TxyqR-a#H69`ZJ`LA~h@op4WUau7zA9%>Vm0b{Y4wTpPvVyweA zMYp#YZmSKJ@x_a=;F1DbNZo<<%?G;wQ>)w z#CEy!t1nC#pIbdcdDg_Ads~@geW~QO{mQ?58ejY8yuF{0KKTjpplh|SMq=2l+xAR6 z+wjEW*^B3x{+r(azj{srSKjU0_LF#i!&9TwdfOgTdfV=E=eAwCciY|#k0+iPcpBhY zji z{F^v-!uZj--B&AtPJG;2;O-$-e=l2ZKff(=S&?(z-F5!SLt-d+2!LzSO- zh`WQ8hnNoc?1S1@elif}+%b2-4&{8THNM6l_T&HZp}bY|SACCp3@*yk{xR{OYyH>6 z|1Fb`W8lfK)_-4mLh`thIF`)uw?UK`s`?mGi|ODX7K(JtXdrk}7+)hd=&I6pM6G`H z9@*#N*@ou~o)SD|c*5%A<_%M~8aSWQxyF&8^o5V?nRxQ>{DvoH5y0?dEy|tsRE;E) zwFVC0?|SEvef8RkXBgtL@HocNZ)b-*Mp`$((i4xgbL%QU2dcbN`Zhc#@hk*P>vfN; z^k4bo>G0c#F9YJni0=W0j5s5#^_cv>>G^x}NA}~m7sc_}R^|Qp>ei3!>kxSWPt1Ch zq{`E;$~&cx#WQ1l?xU_XJmjS0FA;%fP?cvQ-ltWGbIdb2|B-!|{)|O9Hb1v-QjObk zgJC~HHh5O!c?r*Zc=rDE$lmM{6o_#0Md%wL={PWV{xdb)oUF%V?e=Z(Mfv~ZnbuOn zo27@2G;V5f)+Z9qLx%Ln06HT1fBze!NJk_+bV-cT!{o;>(BL1WmEn-qO^2OGU(~e^mkHM7~;<9?}hy7zBRaY^(smF#!Hf}jK5`nFH@2{U%h4T z(b!2kKJ}J;R0}6*-W#{($tnfdK!8h91B5=SB`JB= zE&Du#?;(5-Vb*RCLi#R*83=oPa?5@IVZVbwgfJ!#hbxe;&QTCXcm-h@!q%VNvd6q5 zN%5bfAPCD4&Oo^9I2b{A^TaLtkMCF|soPg5*&0b&ck-6KF~Z|t-?9%wc>fd_L0IcF z7(v(`UT9|!hJAzlYY~16#t=3>0|pQdLiiHGVF>3TOh&kl(!aZ9KZYGxaqD+n9k z1OUFu*&AVFgf(u10KyoAlM$LrQ8I*{2zOCB!jlMVA-sYx3}G3s1`zf} zI1FK}yHEwf)}FVm_G9?5klnW5p$y7xd##O*;mH7u6gNS2eQ(JVKwB0grI$1i&M_VkHK!3mr2X2oUDY0Rn{abAbTiYJ^J> zo1IzpVf~ zLhBtB2(|+7Eg(R6JOc<29#{ng2%T300m9A*w;??F4iF$*y%q=%hHb#WJxh`bGckxq zn7Ije+#^hW@3wt1!V-iT2$ycTZQq5^XX|bI8H5>GPJ+$pa_bf2#Sy*qX>$i2#TP*pa{Ax zqlm4x%!;rgD1ss=%f0K}Lf)r;eZKwm_dVx(zUQ3u&b`+)07tq8VCWA9;I#ijtTX** z18}8h0B-(GzWdetz; z+3U;a+zsS&@rLrb6uhc1>+)$ zc&>aFlFu`MU~$m^-|)kPF@|1b09Kjf&WjDextAD#*(C#Tz&^)cA%EL-WQ@I6$v^Sc z@_Do@pY7Mk=j!X_Z@d4QHyXf$R?z_G+vD>L!06iyz%Fx~c!vR)c&7n4{XPS5u`HiE z@0Wjpt^A;TZmr8_?nCl9_F?%z?5py*R+oR`*W~l~V)+F@@Nxq%bcF#f z^1;$J0NXe24^yn&v_H&oJMXFxwCvW zC*^bQ?(*4<%ID<0`olt7Fm)dTFnB)$e9I@({SCnB2N-}04>SM|;|5^-AqHT5MgfdI zLOv%G@^}2$ex!W%XXUf}DEW*%T0Wae`P_U=zc6eIW*=(+9x(K6t$dsTI6h|pZZpUE z|1|)QS!d<(3Sj&R^4VeNJ6fEQ&%_hu^O!l-o+O_OPnOTne8B*M#=HTTd5QtPs}oN( z0GmuP`w{~%`BDQgx?}*xUM`=BoP5r_N`BL=d6RrDzga$$Mfse1t9+K+Y<+IQbv;|AwHvsdO8Q>BhrHrw2xdE8iGXQHpG5|wAF#z*d%IE&iDI%Smxy448Se6 z**ucZ~&Q zYJkg~?&}+X;Tsy@7Y8d&63SWO}m}K@1r-mJ-eSg5jik1IV<&1ObjaI_co3xbaH=i1IPrmlY zT0&PU_&o3Nm>Dj=MS&+@v(Ci3z0aA#nuL8HwePV7++>#7_i80OA5Z|dK5S2aW-C5r zPdWE#1G4oQ1u*+L1+)33Q^UZ|ef?$cvr@MpF8Gr{S?10^H4Og3R$p*xnE#FYKPQOV zg7}4A;8H_{T)oHyT0Y``?(Jyl@{X<1sfkOxrz7jTTFJ3X6=dbBm+6Q?M=p1EOtkz1 zd(5LNJ*!QGU2Z*=r1N@y=Ov3|7Jo~|8BltyCwfH->=>O@;^=JL9lN^ z7EhUwgVQEFQ1P)nWbcfXF>|ezu`|$0ElmB}*70!Y`wWhp9@e?Q4wuh5J&gU-!Yd1SR ztnlC#r-yCE#!nBUe^BVH6vnk%TPcrje|nhyqqE~r3KqG^8k2WCJ#6uaeU9Em{-KpK z#o}E~7lwI3$Ac=nY%q7%(|$ipL6fJ4@jn@e0TXR8&&j)688_~s0|p+yr^3Cr#}p^; zr7#|_!^VHe|Fh40Mj5%!>0yaW_bI4U(DtCk@%x&X!Rgb(#9t&Z%jg5Np5X^t38x?A z`#ml78y+R*+2sKPfAtF$zwr^_A@d4Yc&H8;cWmbLFf2dtFbid?@CcPlZ2XrOSbwB~ z82uj;7$D6wSD54UqZGo(qpgt1q=`BAnA5}H-(17T>KGf3Q#eQGyw8>YwLoq^-WlM+ z6O8+J_kUXu5llVN-f@*xw%BCmNmk6%leO+>#L^^ko_U6!<$bO{*98CI^L5~#3R^TT zYcH@6Mqa2Oc3I+a)&l3=BL7ub8lJ<&5*-ji-khE*DM2{;EQm zDS4k&hEM6pJH5|%*$O%ReiL%*13Jfpk16Q1uRrc^GP_{`OnyQK3MUUfsWSE$yjrV1 zC4p;9al9&l-A_9k-2RN~$kJyO!tm#9m5E|CpBu;a{)<-5xi6W3i7lPw8UtsXi7y+U zH5QVBk*}zn8J1XQjcauiapP+yV)^U#^csG{2MSxvadO*=xpuzRa{dCXW#B>+UaM1# zaGPH%j|tuu;fAT-zPuCw4C!Tw}Cy@xNx~nu*<>8*FUhL zp-wT$HgoK=!u%Dsgh%XgbD07&hqCx+E&PY zrkMVT4zR>3=dQF8w)P!1Mt))CXP-5)&IEUvW$srx#+BddBsbV)VOJ15$N#zW@3e~R zOmniU1Ds`zOKhKfp95|)5>ObE95Bb--|GO6+2q6@bbvDqUFWQkMaH?x%yrHxj3oc4 zG7mC;m%!MOm9We3b*=0lR>JvzS_!AG@;)1Eu-vy2j-9fQ>*>g83*p4oCSa4Lljp}e z%oaN*U!T$8(Siqp=%@;>(PGw_=lHc+%oVmyp0m#$W7j`xBstJ2R{o_^++~Hap@p1$ zf8^?6kMXmv9)@n9lV|(AX;#j;dYIvM;Ob$iAV^>T>S2S6H@~uRylsttA~Y_ASUQ@h2a}%DPwFf z%>(AxXNi;NUOlX{ceAU9U4}zf4}&*8Yh-~jZZOT+n_oRFGS3><+2$Sx?BCq)%13Tu zz*}5BO!AmH#%_7_u)+n_S!aj)42)R;!yFqw`F(61WSYw?a+MX<+2k%e4BtxrO>H%! zT)vgxl}`w&9%Q-8G6!sM;?`Ek83xbQLdLnx6g$jw&bpcY7@ov?d%LwpsHB{GxYI@wn4_CzW!MS(fjtL)^QYLb-o;E9Ce+y?-lP$Ru~} zV`1F5ukpCeCP!lC;Q~XqcK#d_!sad9|ACWaUZ5nPrA0 z=2>Bxdu+4E0Y@L{{ac%WDNZxb6syc6z0V^KIQ1Bvvd}pu3xc{J&ko~OJo$JNbCFFJ z+2bxlRzC3rE9Wc&w=)5w++vy?=6K8sLn-5Miaq8TzP;kQq| zi;Qz>-h^Cci6vHf%oZ1(VnS9KzLNzp!RAwSm}5^f4`Xa|?rHA-K(OLLBqEVX?l8wA zRv1WI8E4qxA_I3;D5KnFf*ocVc)Ct9!Uj`pv&aG08M=$JR1m}kU8Wd*hWp7WR=CI( z^Xzh)!MplMW{iC%8CkLkshcO;A$->05tW*$Zg{y3_%071(zMBc2 zZH1g*nzJl2!x~rEW`_gz8M?ccKgR+YWrnLPaf8*nyZ;A*mItHHmB=YZ?&0t-$vku1 zWQlvMGVnZk+H09qE_2*`k%_p= z20LtXHfusIFmx|xgmF&1*a|tv63eW!%@%_%(NRt?_#ZmXSV1r^NVCQgLob!c1Ut+z zFr{@2v%v(r%rf{gTgOQ@S!9nD2JWo`FEnhEBZW{I0@u+J_7Z&WD53_Z{%9-~}gnp-Tga3H7&B5$%cOmn~`h90B? zjIzrV2h4J+Xr-KGoeOMnnO&|k7&j3k++&i5%y9HP3y-`1lY*)TX|@=Bi9<=k*I8qa?T5Jk6YsEM54t5QeWcoG}GK> ziF>Rv@P3I5v&R?%2@^5QEE6m;%_@s*u)-GW?6Sqd``!PpVDk-scL_tgy%$E8J(3g`S`znE1TJ zq#q89GRG9xnP;6nPZCU%(KZV57^>FP5xut|CnIl!8{|6 z)d42C$qXCJ^O#kJzhD3^vCmZoALq<4!aCy|FvE#2+7c#N=Mp=tGB8(g?F7*|2~2V9 zOAa09S!SLMZnDc3ga7OPZ)q`OOf&FhE#?esEVIpR4tT)G5}T}Y z}yt-^6LVInPh@X%(B8lS+Fl?aKJ9( zUso~L7=6S?2$1hMY^X#$8(7dz4DBDc1$25Z%>J;OwaEmP-TpSmCb+>Y z>nt+$Es0!ahb8uTz;Ie2J0|8d(@ZkQGArC>lPz{Q@on=y-Tj{tgayk?aEDoTS?1Vx zw3;z?xyax%6u=m_m}G}Jj(pdIOt8r;J1nx#bq1fQfTk^eru)ArNP4iv9QRpa@_Pp0 z0y``+uwX?Dv%v(@7t3Rw6>hM}7JHnz#MyY34l>GRrnt)NvkE2_ls#y&#>}n>S!CeZ zPCuh;GsV&GJB*C7$|PINvCmD0pW}TdIDM%CxyTB)+2k%e1wl^`$T+2!nTS(NagKTB zSY??l?y}Dw!_U?7maX6v(@e3*MOL`ZCL8Q=kAdg8o|n7-Q9(kGV4hj7vB(~49QlC( zIKdug8G63=8Rr^PtTM}8mU+kq$F6X8m|$?xCo3b&Ug7@71#2E;*kp-a);YGPMNBa8 z0$ar>Ge7h`mzigcRUWg&#E*1{iwwU|p^UM{G+WH^;70`$3W7g2A!pcOihZsy{36$o z2_7-arM3xKWP=@cIq?%K%sP~evBN9}EOP3nI?56|3>L1`$`?CKjI+ort1NTCCTI7x z{^U7BFR?X@bM|LC!8Mk+#VYsM;t~5C`?-a@)O$>Fi#Znd1Qo&PFHFQq_BhMXk`6G= z4Q6=EGRHbr!bvtc!wysIv(E6#w3;y+EsjFFN@u3t^lK%rMVVL9i>R zv%?kxJr#43!B<-;BV1yVvA>y^CDypZHai?J^mp$s``}@cS>_l&(sC}d$tnvS!LcCl z8Y}vT6>^#>&N9m!%UorRdu+4M0Vn=x!q-|MlU!zw6;@bdoqO!C&%o=PxvSj&upoVv zJz<_{)>-5(E9|k!k-h;q#X#QsjIzQM`z$haN}-Ig%`68jGW2?%h>Y_1l>46&ET7g= zmRR8$!*9^CV=H2ZId)m%=ou^G7+aiTpGk(DsSIOWWty#PPWIZ*1XdZlRvzO8L07QB z;EEp}jBsjTVlJ|-pbd7|WWYq-ldpY$^xyK{Xl0CXlWDeCWMZfjES+^c%z3}b3J=+2 zVf5_dVcQFn>~ZXz<6-zsCT4;qW*H6~56i5w!Sr>Ghh3H#e6#Dz7^~Mk9%dN3-tn-+ zB&$rb!JScg>~ZjB_dj_3<6)?1?-=LA4g3@HtTWHx4Nc4lYmBkUW%gKQ;5>&mcsz`< z#}sQflE;x7d!I|}agCw3_&i|#JgpxH;vP)gMCFXL#0={!vco$2+-LZ$2EOU>Fv&1; zTxNywbB~8DX4vN{!>d-#1lvsWkhy|j@n%}Y6*gE8sgx}S-e#{E=72GVZ*Bm_m}80+ zW?5&REtc73jRPJt`gU7<3x%-8LRPRZDD#*#j^EOmV2T4SGx835%s7MNI>iX{jI+!+ z)|g|P>m0DjNXbVrlN`I1!Z~@Xuj;b0fV>m{+bUe z#yNI-hmW}loni2f7RJ3h$vgReM1h>+fNKRo<~=IEt3$_;Nqfl3-5ff0?(Ph{*Y~6L zj?+wVk!fx+#~qe9cTf3jvcn$x4Bbmd-Y1_CrWt2pMUWCyndL5v?6Jc9ln!z9zBYxY_Z5g);RMVonVfE4Y%aE-e-py9x>19=b4A2&o8J@ z5PiOubA#bexaW*2T%nD1abB`TPEm>LB`wVmbWhUe@vn;dBEjHLH%-KI4oq$_=L2VxGsWGMY0XQ|z+H0qcx>*5?3|JYt3;uay5; z_kT=K_8`UvQ*5)u0k;|1^ij+tkD256t8|FdY%1ixxRMi_pZ0T^eNX%@M}3VUpxeE;nVXNIA=v%@GGOmV#Alyiz@ z&b-s-02kQhNM9DA(NKPNbBaExtEaljNK+g8FPH<;rND?DVA;rA+( zQw*GMD;PfC{a+L$JSa2EU6vVnp9z^|mqiX(W#|H@no*9Fj zLps9fM~u&XHX82#fuQZdA$vSx;36HVn1Ep>7-5=G=Gb6`$&Xqgv+S_QK5Gnr)3{79 z@-Yi!_9^_*v(MV8rMg9q#~c%iev z1S8)y0h25;$30dVX*lgnvd__ryx;VkNzPp4{^tZ`4=QZ1$v%4=|E4YZo)vvdhgfEo zH5S=mg%jVF$0R$zJeHI`1>knibZBw zVTDb0+2houI(DhU$T)M%uy>iQWUOT?S!efB_rH6&gv;#B53HDzOmUuhF0#yRHn`6= z$FI<-mWdeUDpRa5%Pkh!W`&_2It!dl1AjCzC)wmOdn_}w?=UjTLnat392!6{%`)d$W1ekp zvBwTWKXXPHW#~@|XPrgvvci4VIbesAf3`J0cZL|{0ux+emW540S{vQf@9vm_7O9P%( zDZ@-K#xzqba)~vzuC_w9*=Ow7guikK8RG`i++>b{GYaMmo2;|{hP zi3(tqJ+>M8qZU8O0+@WV0+@Y@_qom{ci205{#5TDdjDx>{QjR{;%WX-ZKjy#BFikZ z!A-W==71w<9s83H5GJ|69Gk3g^64gIi9H6NVZuM#N=BJuiuq?0R4O>|pv*(oIP**s zGRFb)4E@D*WSrYfF}R>$hFIni8$4#4&1cDH>p3Rw`QXXOV~TmM7X(#7hb>M#*WqA> z;lElr6YMd|sppx9IX1ZPd@JPiqUR3V5*sWt`Wt753GOk=9xJwbdn`_1x_nGE^MUKBnCmCa#84kF@$lrZFF!^`)za_|d zaL5V+SrakF9y1IbX(8i0V2a@vYatV?GQ$?j>~fO>b{YAHt$K+G8E1xB=KoPpiJZEqN7 z;*}DaWtkl|dBhImuQK7)26(jzxyuwsmbH{gR#|_IiMY=`$6o8q96PLxapAS@e_F8W zL6I%i*kzNs*Es{+Vd#ug%qS0;;7DFenPiFUtaFns?y$>!4j6g8{A+ZYDW+dvP_bas zgDM+ru*)vT-=H(s>VWs+JYtHm6?rGmS!JIM2Hs?)3^O=zMi^t4X$IbGD>=>*(*;5O z!FhI=WuI#dkDNWyV1oP1a=c_K8D)iYY%?2#7Z zXPsRb3B1#F@?erBrden7T_)rr1819vQ64bG;JdAiVV0R-gI)F*SToT%zRxJ5OfbbP z`>dQ(IC~`Y9u=Ovzz%2F=MsYf12WFgdriy~^DMKAT(;FjC1sZCgdbboMW9ucDTvF_0JyJW0Zk)E94~eoMD;stZ|7=Zm`E~25umK z-Te;>4n2r*{6i|{B8x1s!Wx_0V~WuAFaxlfoF|0h26W;FNRZLR-i% z6W*U!# z8av!!pKS(jsZ-yyfPx?@NOP7&R#{_%O&+jw^88y8$87~;9NUq{X%?AgjZ18Dn>`l4 zZGpFPdzjz>(>!J&Cm8#VikW7EIkr!pf7ePGXXMtdC6iobhBf9nV3pyft>YBC%rSTy zEB>B>*<+G}ixtfAOWgmOVEz&nGs_Ow7zpbCqda7aqq`>L1j|ga!3DOt#sN1Nx~)%A z#<}=?Tgqh?Sz+zu``<4}6dZamVDM5ay`2G= zR+(a(u^*e5lUK^Sqx;|4H?d&qXC`Lu=O$*2P42PBnFELDPM-hP1Z*njR z%DBn__ZXS9r_8hdFD+;6-`?Z=(7or<$Tj{ZrL8^d8h>+AN6)#&p9M2OS`a^Zfhjhb z@WMXRj0UdpS1f%#u+0nyEHiR~SY3?>}_*M%N6JEHcL`OKh^r z?u`m27L4Bbnqimo3{F`&W87z&BR4T2!>lpQCYRV@nSpzom{IOC!N8b;ImI$(SmPqw z94*{b;(ZLvFr$odj%nsuWQ8@>*<_nN4j8(x3C`6aCYa(P^DME-ZMN8BpTV1%FXsL) z3KD`Qv)pHq$E2fvd94|92@vjxvkcwe{a+Cz z?r%V*xyKv_EOGi)R=^A!th39JTYLXM9lG0ikF~G~S!at4cG={Bhm1@+GmP_?scH9r zTE!U0r%cFM7FlDBWA}D?nd5*vj6B3IPMKupKDLm{ zEV0Tuci7?Rea-VwhxESge@syIAk707*=L2bF^SBu#TE9s%gBtwbw3j_!yGqQVV!l3 z-d`T)*k_jEhxtB}4E?A3pA*der$m<6kK}^p=N}c2Rd|IW|o1%gG?+KXPs4cxy=C+aeJ6BArq`J%?5LfJXk*CtTV+Hv+T0O z;D1>NV;p^mm2-(X7K(zBpvO9oA1aZt8HxXG3mD-p(=0#C``l!ev4=YgT;_nsk5KR< zbs}M%N!Sy z-e;XH9<$H+$Jp~nDVz!RnC0YS-GWCIv{umYVDxdW59b(qw1Ju6)SLu1S>ee4nt=1{ zv&?YPz)W!R@d{#|6*k%A%oB{y4Tc`$gNyNkAd+&JxXm&TS!3#n4igU;e5?B zndSnE%(KQCn{2Sd$tTNuoQ^QgJ~JGfw}p(cP#4SzI$UO8&WadilL@w&=FC$hvc(32 zPjyx}$>9ImbH4ZLV3%3; zS!CdO@;T2Yv+S_Mz>^fpFn5^X9@C6GUp}V`f{I|CO)j#-1_Mu)z%Y-P;K-r@m}HUb ztg-Pzt>xH@w3e|KyCw5}<-;Va%(2G`r(a?|7K(zNV4Z=dI7AGy!5H_LCez$ykrOYM z$Ypj}W-#qNM!3r)M_ysYoMwgdY;uczj^@1oboYN!kbJs|ndd%h?6JwrBLU-bCy$_$-H%5%w78*y|O_appO}GACK6362EqlNa7#V$Lw~Y%OMzb>_Ia zVq!K}Xa7yMjw9#U>*u(3jB=A{9=^p2nR%=CxwC4^n0SXyX8iaqx&H}4rQ}+%$|7s5 zu+BR7+2H~EJY?{>3TK4ncPf-4?^5WA@0QO9o1A5jMTVYde8$;+xBH(F1lQ~#yKFG~ z9+fi30rLz!-vEqqlPPX7%WW39!wOg5XJW?6CguV|i#`_^=N2<;7X&52*!!)N)9i48 zffu-zjIzZPM?PQ=Il(gLSYw_|ZnMKK`;2|i;d`OO%>+~HI>h*g6v{$EP!}ZGI(dOz zE;INdiHvZSajr4NnGY+3UDkNaCW9YQ0FxiJfUM7tk68f6J}!@Q%(KpZ*8QLTgb7~k z1LTwTkQru}Wu7^fxy}YR*ybjC++yG*I`%0Oag`}9hIjIhtZSLMIV2hZ2# zGs12r7(2`|@Cvt#VYZoI z;C%N#E0`3NnP7tp?6SdNP68ubzd)zhV3u8$dCVGv7g{+}>@m_X;VYd5Cb+~bw^-&; z!~JgvLKm5kD-6BLA!C%AOmK&32ES>AjIet0oGtd)XXslde6@uz#tf5OW`+%x82+{n zG4}0(0R)NfXwk9+hFN5c>r68AUDxL1`>e3UCTr|*m!a3#+or-9W`Z-!GQ%?0*kFTQ zb_#;vYwgANOvo71OfbhRD-2$&(39uvbDqK1IRlJvl}Xl^<31}qW|I?_D3mFN@;bse z3j;w`Ft+OybBZ;l*yaictTXa@?|t7yTw{@&tgy=_moGIDXD`#qH~7G6=>(UV=Gpz7`(G7Ax+>!$`&?uAEe2+cyG(Na_YN0F|DdHTvc(d+EOWpL zLvM9G8Rsrj++&veEHe8?_rE46|Iry>gM$+foq<)Kd`vR@Clj;8DqC#vi2W1)tl+mf zWPh=h++>z}Ec2KRPV^MYSq9&(Gd=e|Ca8Ll<{pcj`m58)HMZI3fIELv*gM>czblN9 zBZaa24~231p9*7|{gdxsrLdA~%@_}vX8e>b<6J>d6>PG_|5=NP0itEg>!6H{~e67FnsDtcqkAe63#Jq_-W|(4yc{W+)AzSZr z|BGYS4*MR|7%r=rF^=BU3K?UO3#>86CO6n)i=p@Xq&wFNIl&AUSYnP~SP2|Ksu)6;u2mhCb`C zJ<*xr6f;b+#7)+@!xlU2^N7Jshx|!8$-tB4agzChpem?xmkl1V%kg=MpR+ZLG07w| z%rMV9cUfcTDGKH!d(1NQdEbAkf_cCckDjJrj-}oIsvs?BvH5frv%}#38Soh1S#&=a^=mMQ*Xe{b#!WO~L4b0XWUT7p#y`=9plGS;n6w zk^5{i`)n)a@^kFz7hPK>SZA7T7J1AXBN-iHj6J3@1ugoLi9Cq2!VLFV;xX%-e69|i ze4hh$7}@d(_B@^86f;aP&qY>QW{bP*^MJuG8#R?ha$P28TbIh{BGUs2YQ=EB`6?2w>uX>MR7Ul&pL7r(AnPZ71mRV&Ys}LS? zzyU*bD|oR2IQ~rE}CjOeAeoTDL{a+WPJ=kE5n=G-#I@@fq z!!ElVaOLG%_;uHlN$xPirB_%vdu*`JHV5o6kkf&0*iuHn;r>qv5*|!5%^Bv{W`zSb z8F{4vILFYoGs8HynBl^!Ow0}&?6S=sd+alCzH9wz6LW%zf?!gR<`i>mvBEx^3@;mi zvkYC}3^2~rYwR@-S>_RIJZ6(4uXU>!VcCeoF~(U)3PP{bYVPK>m`4mYB)-9m z+;vMb?6Ji074I|37B|`F=o?LNku$*<$C+fDIVM z@HchlEn3ACvn;X9JvKOCmve7b__ur>Fv1Fx>@de8mN>C$0nDsgQAbeqAh4sdx7izJ zncxc3486k#2^Uynm2Dnyz>$&(zilB*G0!Y3EVID|5836^I~DpJpST4& z36_{-l}l`KnO&}Mz*UC6EC1cj1Q*|9t5{`;hpcn-y%u`%HG@r`3-2>83k!mzV38Rv zG0!rqtgyi<+pMw2;s;IqJ*WS}CT5=*PJP70j8sg_3_ILs;9^_&Q5|NTsf*qJh9K)f zlSLk~#v?X)%nmCbH^3$CIioyaf@2#x$2fCbW{Fi+*=LJ0pKz9T74k_7X1?nE-GY?} zN*2{>ys2XheO}=w&)MdDO&%j()#^(Xu&qNZvc%&H z%u^5qFO@xISd)x9pV_agIn=EpVH6F3e ziRQJ#LQgO&2wm=UGs+dFxWzo%tn!czM!si4&M^1`zkXnh+e~whIrdpPd491x<}Yz} zSY_x6<6YwZ#|2}%R?ZkpoMn}3Y%%?Po!}-Tdj@2jdra|=S;j8)$;l+^C(qeo=rU*L zhi(!8=@FOi}nEO94G5gFjc7-kBENjfN&27-ImZT<+2!~TwW{rB1fxtc#bxHX&MF&hvCBTkf27c#I15ZL z%`EdQbCV4gI)bj?hyx~ntkR!q4U-&gJ3O3Zh5KwV^%D~@&ES<<$_TTJbB!6UGtUi{ zxyc$6Kh>ct-T$m$;6a&@eXU`V6IYs$p?wo_{AVUSdCuU^6vPOp7-xzZrkQ7kWo8-p zxsT{y=pc`n;&{h zn`Ds*)|g|P>m0DgP{-k9ydW6ss+?0Sae-B?vc(N{xx?Tut$;Cxes4lfvB)HA++>?O z?6J$huN-cMIr9f+g26w!|2e^)pnCEGTZ|v-05c5#S|LoZ%`Ceta=;2he{x&6z%Fwf zaGQ|>t^SKGB-|l&;73pmOW@O^j8y~yuk2pYzbp5Gs!M<4E)UioM4j+>@deZ z*BSn;YsUnSnB~OZoe55{#`(Xy|82ps2Z7(I^yvTTIve<=%Jcn~HVtX%Xabqm5}=gu zYSpSiJIoX{YK4kbqgISsF=~ZQ>#SNKO4V*wh_g!cVHlPD>>R^R*;bWdRMc*ESZ6o0 zjbYR}yNzMhzNE-7H2?2?&Phv4|9n1r-PiTp&-?2+=Ls-Kz+%t?dO#oO1#7`NFbp<> zZD1SN1NMOSZZhbjPeBjp2P?n;7yz5WtzZWj1LI&~9fspyIQEkv*aB9AyTAsp3k*y6 zAQ8dF12ipIeUO6wn;L^2FaY|%Enow<6%2#h!B(*N5G@3Df~Nma;BSc!uB%Qk9WeGB zrljCLFa+ieu|R-jX^CVv7)VbfbM~=&fllyXMj}}TrkN5+KiCBZ!F^yeSeBVcc7R^6 z8>|KsU>J1%m)Vt-Nc#TE{IADoK#1ogk}aTnav~W8?N%ayc{U>Kr)fbq*gAy_!B~DG z83s$HC6aAm0*r%p2L=6t3_vH?4wivkpdUO42Ef2f^7~>PyInyd8AE6U<6sNu=piG} z1@?eGuwfPj0}JLR_%|Mz=b!^TxFEq#G--*2_<=>o(-L4M*bIii2-sLeOMp#a0!)C; zbzjl9Cs0E0AXp0qPaz^$?4k)l-y#YII!>phD1aMm0eztJYcc@cU@PbayTNL(pag%g z2K4n((eEdcAuzCn76Ti=buo;s7^Xf33+Mp-=Mw>}25Z5{1vE970NX%QDJ=$8meJJx z^l>>Y1-64euoJ8W>n^7vU_BTCtv8d;01HnQ{$SCn#JXfPMsPJH0~6Iaio>lm6=(+& zp!Iel#MvD|AJ_yofH^;;CBU>h@dqt;QJ_J19W4UZfYo5*JyZa+uB8HCCusVHv32h{ z5*Fh=5(abX={qoZKLrtdfDCBDHZThA0~27{g9(0=N<6R#>;^rcsUeZ#ySKS-bdn3{m4pdYLTgJ3<_3`W2Xa1R&< z(;lJ=|3}S14;TV{;8w5}>;=Q1{bAyP>*_HQ7~4VnAqoJxLCbnF1dG5RSPnLWd%!5z z1NMN$8;JKUT@oZ7xE1t*uAfjt&-yUZ4gHEs-ECaWIwO|wsgWe~|2uy$p34ap*A(mu?Kj;VjVBRJwHpKjI z`)MNCieP$*E&xlPCZi-7Jxd8e4_F3Pfwf=_7zDS1t)PDk@xUg~l$OCyujm4>@&AYi zHi3TO&k;{J*bMGzrl9LEoIj_eU_I!ZkdapKJQ2b67Z@yH-mi!NdS0YOz*?{yYfq{3K{{f5!j1agLjDXw0C|LGK z3I=w+&nPx!@b`g}5xD(NOe=5)*Z}5q(#K%MU&u)K-)X_jjI>tJ1xCO!aQnv;5VU_n zSAmXCnE!D~R)mm4MlLX6&Pc2Jlnf`ryC^AG0S3T5|0E-@@?T^G_JTQrOMI!Mp@9|{5%fMs9_=m#tQvyOx@nh=`7ReZ|C)+{U7#~NBhA!Hdf>iw7_}IVJ`w~gz&5Zh zP6TiV=#_-PYOoh<04;;~gGFE~=mDLRs5$5bod>8GSPC|SAus}ZzM*1ZHJFo=!TrBO zB#6-iwt_|9QWLNoG<}D@16|;r1c+`u%yb1^U^TiIYyc~Uhz~Y{F|ZvpO{O48x&SOs zKb-V{r5T5l)!=q8JUL@sS}#T$g57jD*#ov_9_HVKq_50}`Nbm%Ogzjl9%*v01q^{v zuovtB9g`08i$~(;98S8yAm|69U;yj|o5AYIhxvgcgBgs2j@-k^9NRjk1%}H;pI8qk zeV_xZ1>Il}teJ9{e+!au`(b_w$>;_XU@_>N!e9d3U=8R8P2VLRSPZsGIM@O1I)->) zJ7}Luiyce6br_WxUT{kuH3bu33)pfTH3jX{4kt}^`p$8fUqaFq)A0ung4N*s8N>s< zU>IxyTfqp}0p`r4#$W{)_%1D5K>A<^To=XIfsp_`v&i5W`nHfJ1HH2;0N4a3M0Zl- zV=34iS_tf3fFEdDNDG0{6AtrBO2!iC0!=3#PL_drpdYLTeWX(l)`FIk4zEj=5z%`R zO$%0m39uP-=CRThQ&TVqR)gV_$q;m(LczcqFab7$&f}O~U>R6>DlGz5yJ!h;2N(lm zpeY|Lp`u{g8SBUZqwEZtMgqWQ(Br1*#NqoC3=Ew|pG~95FC+udwUiowwO|m zWeiHte-Zu;R#dPE43$%JFy|5q1{PgL7l7N>VMH_4O=7+qi# zG~Gc#z;e)8K*qJy7~Tl_!7%7WH{D51Ko8ggR)JA43Yun7fV&t2p!05O4wixqU^5s7 zJJ--+vzY(wYiTlsIA|)&;GbY)5P<>E1s2~+0l=+bEf@uZU;=Cg9rrQ#Ko=MV=hLML zune@%W-x+o&{R*s!F^x@Xt|$)%w9*$AEYD*6%7;wYyeG8MmgvJwUFbsylil^y9Fz*=(x(>s%g{GcMjebT6 z!JK9yfZm^zf#_Sw0Gz*#2w*8_p9g=DjKD510H*yKf3WDc_=Cl*_=8(s#cw{F+V4mo zZh4Kagj*xb{~$&UMym*~6A>(ZgBDmo7raRgz!=y7_PmWB=xoCetoS`$1UCGELAa1U zZKtV0&mYMEEZt34fpuUDm;j@K?~(rTtOFg)eR&9~RP=#}X0Tmp_yYg6-4D01OrkCA-0OdaL~JGh<~Dyrd~_| zz-sqUvIVR^YlwfMkzMZWp`>XM;T{SMRxTalcYw^6izy(u{W9X8hF=8*KTY=kmDHGw z;x`Z=5pE)3Fjz&waEz=XW3Z>1f`Jvc4khDY`Rx?!bo%m+A^r(QR?54F_$L@yi0&EU zpJ1fv1Jo2Oz7K!UvTlgq|1nGIhxpwe1$lsimoWbiK19h8mOM<~e2>Ahekj=hIyTTH z;J(M{3b0`#34vQfWW1Pt{Rs*NhCv@#{S*ZR_dH9@z^%{YFZcrfXAu4?{K2jl@dv%X zA)j>^TYpOvfxV!Q42oVRLwNNoG^Lxad6j~Jbvpc7xbOG1_HVA%53xM{&(nVk| zm;kH)hW}Y~+23h$u zXri-e8qfoJdngE40R}_|n?c8y^eNa3c7u&yGe*u~R`d}M^bAlSa9e281etncVNpQ`VP!V5CM#W4i7CegddogoJ=-@vD{>`2W*{^ zOnS~^a2=COwt>6yl1T^HFfGZ?>u4!QG8qPoXC{+z&@_wi^C?In@j%ykvy=RsjzQ#1 z@-Gy!gn}`!`;=tTegT8*^kmWx`oSQ$1B`&>B@_VM^1UR#o>RB}*IIb)u7Td9HEraN z!!ReTDKEP;Z9-tir0_*uCQWoq%bA(x!gTWACgN3?)6y(w{aS4(w9Pr*ju_;>z>L0R z4w&YdY<-4^Zp>Q#+w#BOr0X~$y!vbP?SAVCs(ioIG9xslZ&db@bb|l#NM%!|`pK8p z8I$Ai#@T&I3xmY+x!O5kEi`-i+lVUXs@?mobF*_uqa>TK57nXl*3+{0%_i2sqg6Wx@VmKG^dYreA1U0nISzNGl3{)p`%+=p&S ziJ-(QLN7zF$ELsber268y%~OF`Z8j}_%)%s)%R!Hj$Isqwm`>b6Gh*OJ~o>k^iAm9 zY3jbEwi#wS1KYb;t^e9OBYo>)wGEsUUEIfCF-0*xe_5UJg>|~>{n~1oRN?O9T>$Eb zFRMwX*%nL*Lc-_JVswt>RBc4PIL9_)as+*o#~22)W#r}OcB8eN*Oz1m~I3vwdiR}`;t+HC<&HS!&~6m5dGq1vg408XS(&7^ruZ5%^^!T zCr!F7gx{WJhTo)D(p6yXREMewOf^kuBPdbUm+X|RX6vJ$q_do~Pk1@QKwa~rsWWpO z(E5v+B;t0)E9$jg>v5U2h>ZaE47KA)d2ND z+tqizvd)~<0!=_E*zg~T)rQ`K-l4w#qp5io*e0(;dcq-A+XIz^wL4d_L;4o}cpXfd>xacsHzWv%0Ln-LSW_((Gk z=n2}Qh`WB+$KQg6_%#Wt6Z);knu{i-r8V54vg6jmEHCz!J6QtN(}%6cX4OJ>+$C9k z%v8tA|(oTBu16&JKzD?}pv8TgCmgk?<(o`FdZ{XOtxluY9AA+r*Na z+5VlhwAdSJ=OJr;whPdhCF8T6PGt`K=MRR=DdO-7Sh8 zR)5AVGmbf5^+^o-WQOS<`jRbr!r3nPlJ>r2olyrbeA8~0QmeWzNqg18JNMG->fWUF z*oh%1-{sWWr1iM0R!H^7%v`-KqtFg$g-+v8(h5 zaLYb6Vk31g{2<)u=j>W|*ZyIi6@s_-q;kt{h1P!Amy8?HqwvzN`;w(b;o|U`-oE4# zqvkf&YG|Vo?1CTclhh8+v>j{qLYoKFDTl0u*#T_RH?p#5)yxh{*ufDVfqM=Ob8`&d z{jEM^64+&lK3;-ram|h?^xR=R%#B?#G|~V*_@*Q$4kMoc+&ZD3-Pgz$?nv)XI*d^f zf#;d}hy7#lrp*3Sm9i7?gXVtLW<9=RD%0Q6pR6;u8{UxB&kK7!+y~#D-Jfc)>;Qbv zq>=Q(@Fm~rPnM+ehganGCtXJT7`)m#!V~a%TR$HHjQm+CV^jLs*LCiOw@>X)&d)UR zhj-?U$PwvoWw>b=LIaRGmTJy~j z?7T&qogKq&IIW-WDB7Zsoq*Ss^e3GLcO1(xc<~5#!|UB6+y`$sljb-41MuLIk?=6Q z>6{TBfrmW9JSzs@bbddl9a)63642HQ7)?5L}P?u#z%Pp0Y4ZfMSBG?Gqz&@}Hb4M5{i ztC26X`|@ELfkv+wrZH&SmHkPJ?wo+OR18x`KCN?Ae=^U=7aCkK9O{GCUOh|$P@iv@ zhM}HohG_&^bnP&WLG9Nuc#V9aX_dp&F^x$9HA>}%Mz0^HK4@g+FbzPPZy2so7#i{q zhen`*8;2Vw2Ccbim?oh9n}_2%IH-85hN&Csxn-F8psrQJGyrw3PGyuGhUQd5Qxggv zAK_Usc)PF~c zW=EhgXmN%sv$u?%l-@K zeFR>2$v|?8UY)EMyx2RCdU{Df{ZNllTgN7`bKyRUb<>v_-vDax2~r6sr={D+qdFx#COBX zZW~BijQo6X*Bt{~($Mn@zt_!*J`}pHX7jxc-g%) zhY{{rz@g>7f#D}1H+)b1FwgSAiys_FCiLD3Kyw-flI~RX;qxCF7(N$9;F}r;lD)>r zhvu!PGxXRA35BLkk&cBd_Cfki_jW@&pt^UK4_fxfKx$(NK--|kEDA%H{A8F$pb@AM zHwJY-I!qH1Izk=C6WTP8Y&P=5d@v)xIG$qiSw=&i`l%gZtod_zsnJN2U71s!qAe$hnNu16XL@I4cZ0Ohf=l= zTALnE<`~`qc%>!cCxIGJAl&IotIx8%l? zJ|n&l9?P~-7GD*#=Twd}_F0~a- zWo1kgExI(GbePCz^~36;0^6)?X9tH1*<-r_QuMqtGrriW3^V zmRTcFl8y4wVV1c8aZ{z*S!m18t;OC|$uzd$ko&NFhFf5cA@)}34jtHex5Sg}Rvb=x zSS?#>TWDL%yT5zlyzoSO^I_7~-cXx;=tXPQ;@P(Rc>(N_wee&gEt2}f*^s}8lsf)5 zuD^^+TbiSvxA;!s|PHOoq{m7R%bCH|kH>m763=l82>!En^pjo{!z?ZN9-1L(; zH%+zf%Wj63Z;Z=UC7*B19q{0jY8!EL+px=iN{*8F*Ny63F#jt;$ z9KSG%LD`ONTQFjv@B+8{&s*;auCoEYDdSgo#(De^Bs4D}EVI?o%IU+4APY z3bqkQwbLq%uTNt0$H9Nigx3+?s%1Jk1Z^2G(qFCiIvJ21Xi;3cako6!$S00_7uoVG zs7)_0^VLN~%-GkzwobG$PE<8$)dW z))22VMEiL}J8Xz|8)6w^>5w5lYKRSpjr;>e+G_C&LyRD{rw!`jn}!&dG}8_7?}k`( zK51qc;@6auQEfqMG!61n^8NjM^5k2wDL05#mudKYx?Y{}J=?;`XgkbAgCW{WNi)|F*BW9O zVx!d%HyUCCV!O={UogZ7qGhTfzGH}SNz-nK9~olNg{1jiLmV(fKVthahBzsxS2K)g z$uq>+LA9)yMnWq+&d|;<9CMbEWWFI@rilwDqqR>nwAF@V0MRnt5FZT6BD~Oo*03j@ zEYf5h&=tsLEpZMh++o^siyn*#{EyZXub40jh1ix!NOY?;fp zU_ltsJ@e?)8qiD8wbafCvLwk4mlZ>Z#LMomvs?#}D!v1mC+KQSTwnw=ZXlbROM;37pgB81-29NV;m- zF!i{}I2R!XB{x#g4gh6{mLemsjgM#t09ylM1)dG!`GS;7E(K-BkbNf%YBww7@=sLa zo;b*lOu(-n(UxOt&cz%MPBvQQ_($~%IW{-yl5+<6sSd6;KWe0y6+%usWstAL+69Ur zbpEM>`n8&KAC(g3Pev;urq&qOJ*p4>9>ge)m6;@W_oMoX=PYN-IM?vJtx5OvA=Y{f z@u4Pd&6$iAEE&{qjy#LTxx^Mh?Eaq77hgA}2A%y9S{S)myHAj7g4QjDNu=x?A-ycja5zi|hBR$zyZ9(K7WKKb8mOD~%ZYy%ynT&0bAAL+8 zcsZByJc4LJO#P987st5(y$Rd05ofkxs{`jo#O)%!_ZaQIe(J2rhzXjcUc_&WWSbGY z@SKmB`Xk8((WR-hG7LPXw?3NRYcyZ(xqp~p?+@X_OXw|EhI$RUn{<+_bV*>eNPyUGTW`$S&5Q9FWI z(dsWU3a(PFlRJ=`kbA}TQML4J4%~6HC6^B-+odw^Zd8-bv@OW?T~0SGAC%8L+NH5F z`1UJ_C^Pt@joJ*J*MiuC6J;F!Q-l>luefS3c~G2_8`TSE+Gb_N5yKa2?NG=%(G5+z z+UT5VA^p@`b_K<|SS>t@)vX#kihrGYLmKW?c^n>U! zAX0zid@BAX-(Yepwq=0EIO30lCkPJ{-lKj+R#SSQRo5`ar1+nTyY{$XF1wPY_*%7a z31@K+w);BTSA23q`Wdkn(NoD{E8^@>Dq?Okdg=94UGhIYq+VMh=Rw43L~U(2DWqR4 zGckT!RvO7(Fp`1`z4Zp823LpFva?CShZyu5DQpaB%Yzjyfg`}`M*{kJz6aiXqijD~ zW9D4NB7LLUPxspr;(F7dek%LB#F$>dJ;>s7Y^Eti_*D_64VO>#;-sFU{e%_VJeX{e zoW2R^o!o{PMy$}TR%OAWuv-1Xr8NexsToXm%Ubg)@4$0@JavAyX9Y9jfkA#>D33?; z7C=jXY^*(}J~67Zw82Gq72)!hR{ ztPQSPqR=I4=|EYl#dJpxXKHPUg~Nh5-=K97|3*7@P zQLmTT@~p64nAT^@sH}F1vIUV{Ej-Djk^03VYx`jhEm25sP1x6Bpv6 zPwID|bFOFQNr|sMsdZPb3$gJfI!3zdQ@zIKFyg`Asx?b(g(tOPSG=OHQEBBzTz`Ec zN4u-uO8AmL8g2R?>c=HrvtuQNdPN=LeOOi*cEzi*`JBMbN}C(n0Iidvy`gT-%#3ipAyZdVK)n-Nvxg1%) z2cMOI2BC5NAmXH;9dFQg>f<@KW2e}mwQm~hxAd^_j<6d2;G1gcMYj9}LF~F+OfHI^ z`s2i?mAL4o*cSPVYPDf7C5#+G-Y4?iT9V5*Or1FydCR-T>3;*GgVXGR<@Sh@p0)+ut$9dKj@A&rWJ&`G^K{+8pYG<+kr+ znQr1eN}JX^(%Vkx7ATj8p$qI#KVyi(vPvmpkNlDD_7lF9@GkZ7SJu3_u&UkqF*fDr z#HdE^Lf?aJS*_HDFRaH+2_ZJU$L=kKACRQAN2uI3bj$mL$$&Ud-K0Lc*tTez2cblg zJbQ9M*<}4`%?0(pKdAUwLZKPkhkZuglyn)GE;` zKTta_L6c{{3eBE7p<}7Wk{0;srbZrWOmP{X?x3Ec=J}&Q16JL;Xf@&qr!6I3c3WzJijtGMRd+?{doQ z6Z2Db>E(EJd@5z0o9^n;%5Ih)5`??dZqY(rY9aM8J86FG{3~=#T4!P{TCi(Stv-YU zc7xb=*=CvBAoX2pC(aqp&*-u{5asHB(Pt|AN>Tu|_VuGVKT|8vG{@upJT$uy9iQ>w zE#3HWlltwIwmFlwBji~S-f2>wBjjxQuhG$4xpSm-ba4e8U9w*-t{{h9`_)Rp`Y+Ua zFr)j6LG{${DMmMmgnQIp2|U=N(ys!yekns>ZhGQNbt#x*|Jq3Vd>)0hw6|PE+O1!! zZQ@qkD`^&*P1&?buR0{!zFxiOyl9?2wR8pAral=a^d?$&pV};1ald+7u)1IE2Qymw zX|wAomuC|1%KFvft8H`hJ(&me;4-xn>_)j9FR}HFcA6Rifog!H9jangSI;b8HEdHO`Cg?n*{^GNp zIBC-mD-NT;^x+0I=^9!)m~nu=!2@B(hICc1%4S#P*VrtR>XFMt4sB3p+)gdzj(Rvl zt-prEHf5+)_fq|CH0-@-C$|z|zERLp3Mvb%6Kq4zGjyr3=x))~_1D>^n!T92GSt#* z8OtVhNhJfg8L7aeHX~&?O$XHKOUPcXq4QO2|9S>{E*)V~`KxS&);8o4lTp+i52vg0 ze^Y~+H8#_XYTSGTX)8UgcP_57jx?ZGnADo{8(LtZ+KHCmH1WVuW5YCs zC268MB*}EDw@7BX7pVi+u@$XG-=pro(Ka=+0W+$8b`zPlU>=;P_CL!~7sc*T_xtIm z9?Wji{V}qADhDzxqPYlD zUe?hK-Ggq;QvW3F^nz@aU1giQZcp}sQE$W~T`!py7mdzC^lJ1XbQiXC;4)*%HK3P{ z(WNoN=zerR(+vM5Pg|auc=mUur(f~O$Hw6xO}$iQ%UZbQgag_U&2&S3`Vo$Ir~D+b z9uliOQDxskE834^kJN0Y>Pc$x9V{i?gj-M2M}z6zb?Iu?B{qAu#0=t%7fo8YycIjm z@RBOXn31Y=Xg;HxO!RKU->7ndR9VuL%islBYUdE8apu$XC(44xZgZkqb3ZFgT;fR= zaKtdZcAvUqm2J-KF4}tRX5f~{qKo4T_o>%b*``lAm~$ZMHX%H8pZa{2?Sx4QE4?I( z)yn(SwAHpb=~0_HXEpitOjWDENzL{H$##hmzgInl!zA}{2a;Ws!PI-NdJiGL2Z1Ki zI!+dHsfC@Lqvtr4T}?_k`RWuwPrh0K=C{#t(gM;-soB?z|E?mnS^Qdy^qSV9ZN=9r zyV6GiHBe3Q8c$aFKVUBOoP0n%^~RK0=Gy6mo+1lEVXgx^aWcb##7%bx)KfnoM)4_X z{cQw_;|_`{udz(WliUxe{*L?u+SgapF#&b_t<4)9YR()nbKdhIrfk~ZUjc4{{5UZVzXBj>uAD!;~dVvd`Hw2gS< znvspzlq>hCiwV*;C7j8#ZKn6+}T?%{TDMAKWD|!V@{=#KEDqwrDwe`_7 zTPx+EAIibX$X7<&Qe$*_2=^_L+0B`Jk+!i+453w$z=k3c!!Oq5Y$Btv!`h7=S|lfy!c4#TsO#@!Pp`S$W-7oooTnX7SD(Y#q4-YP-hY}}d?%HvKTS>+GgLj|q)n$8 zL;AKm)y6v+X-iHwdiUZx)q8i+yS~%4Hpq0&rQT}78ry7Z#~hjvKds9?tTno<@-8y* zYTk2sI`Idh5QNjYAZa%`G2#WbUbAW36vtC;4|pQo!scTs-d=?B#Dm$RpN5h=&g zyXiBpk=~Jg79za*bhZ9brW$5dDqgon)Lw~KIZiw$qo(e3m0w4A{Wyj36COBStsvYP z91|`BQQ|kEmq_ExuQ8%vv5i+Xnq&Sku7W6z>IyT;}p1Oxw-&ivG5GSd2OKv47_Wj zleqViRWae(bHl|yP}A*%uh&~wyh571W);x6V) zRk_M$vKGPPBsOGUY+h_1zds7eMR4*@tgo~_oTPnn&G88}-eLE-W!_V%+!ry+gT zW9UatZm~@+jw<*csY_ov(6^HO0QK--x1X&RH}Iaoe-490;;p+`een;<(M;gMbJXSr z8VA&#(&A|GbJTv(tmn!jb>R%pB0B2aqcifM=bWn+H?m*V{D}Rk2&X2=;r^S{Yd^Bh znMz_DC3y5o1ze>CoRA(nSMC3i?ZgQVHLKA!b)x$;de3t}t#xuP^h4Ypwc^K2kidDy zCew--I8SXuoKUYmdzf{_bh;+-{L21t-sp3>w1bE6y7ScHhm3TV6_9ucF?600z5KJ#fC_%>=JfNho-}TJ z(~V#K`Nnqi`Sl~)k!eN{_hy2QY+$K#Gy0bE)n-Wscy1Yza6VfJIUo<(aW$+w^gc-HZZfh z^-QL_+&ms$aC9bR=&VPN*rv|&i;2sT`AND7(iL4x_rvSd+MsPthT{TbosSaBd4bv; zq^3m|=r5F<-{(+ufy#eG-d+*&$QBdZPq=rCE-fjycgrtOKP2Al#&JsGCR}v+&~H-L zs@EQ|%~={O9bII}z;q@fU>w~sjxHIyG+izH2@|hjOgss%CA^_jt=ejveHvz9jEiI` zH-JSiz?NQ2y{GBWqUsL=nQ?JazkZa}zxZl47{^&us8oMxCRc%rFI0;kr6D~RYHzDD zvGPPT@?qymz&Cat~Ps>#PV{9&tGNWM2u9jDhbJDk8 zq<%<1PTNJsgT=8|>kk%-rATr=x0?{j`pDIz8@(6($YP660=?%VIj|Q_be@B-oafvV zd6|cu!2ifuB>sN%_(f{PmaA=u`QGKDGnYtl!Yh|6-ipmluUW3Q zh38y4V7XenkrgnYZhwLq(|}Y*^drkCGsb~li(ZdynthdeY9oiWHZ_4bxqiah2-C*! ze=1}Q&&srWn7ZoZCwa?RG;B_ni@WU?j~?ApI-llp{gb>lZNS_$j!Rf{B`%q5m^<{e zW19JyWE02SuB$ociD^?5u31!))28~nSIQE?(-7eu7ptXD*yf%QBk;)DiX9?+&lp`= zp$I*SUXN`$_e%A`6TBUAmXEHFIM(7Qy4EBUuhg1kx$}I^kC%*gmfYO`AKg2S?!>=Z z)3x_vGeXz}W6~6#7ERZD) z;u5u2@j%&h>FCCEk+h^Cx^)5-`PRz?z(L#m(|n~ICodbllu1cy(QD9;+#sa+f|{<@ z$H=i2yZbV=Z4=XN-({(HAQ$qI;4*axG2P;o*8+TZM00x8(w{P&%GGB-W%SvR%De}( z>j9>pUZytwl+`2TRXg#SU4HrK=8(2*kO=5?*rr97sf^7M;c~TbGxNIqiqR3Iq_sx+=ug#)sn{X8M@Xuw_K_|+RPiaU015?r>I8Tm3n>s%Xnv0 zp;n+-nk)2fRj~~m;5T9LC44F}l>iiN2#k z<%d~mcM#qwRiAi?S{9~oy;k`&9nZ zJhUyjMlA(7v!30|7SnPOOV_p9SC#2eZ0oh7%O&~upj(vf=PWF8kvK>FxtY^p5vJu@ z?dUVni*3L5fO_wQsfC%kt{s1xvGcA~o1dY8b|aU#7JhUtav?ZP&&7pl(sL;j)reV( z9lvJu08qIRq~u zzRWgxw3D=4<@{%4jahuHwh>t4q*jzlEhCj$=fWwb>0!-n^nM~KwW7QAlsYg=uGRK0 za~!*j0&Jm4O0U(v_bl>U!Z0QEBS)ho;rsvSwW8}u%RS+mYt>FZ2~CvC!AYtv?hey(#>h3BM}*wn!1rI!}H3TMj3+c+eU4|n4Nl_t(rNj zh3a--cBtEbMJIG)wo{p{RHj$W`ju4Xm%LSptIuA*v+OEX5cLoGCO3{}Pb#aEJX%)f zX2N|d)#hKyxoqXp-QG>Occt1(csjWLW!pltdj)6cmD+Rta=&Jej%TMXf&Y&#mslIe z$)`n6Q$D86k7C#3Q%pKC1mwlNv|}~;CiGft)8EfYfAU`ps&K!Jm#bIvzI;p!88j~R z_)4|#1xlZDgW8rcrEq!!n)8OESHLj3LrvJuvMhH~^KMW(iI$%;j;qN>0d7!-2tU91I0U1JI-Z4x59SY1Lr=S47!#<)mBOA_W-OFF=!aNj;f05Z-o!d_kX^9~~!t8{wU_JK;IK zgiD&HZ_i9uy*JwIPrk$y?HMPQTqE6ggZ}N_i*5HGopUw1!!M5)yqCi+@~ibPF=NWq zXTPDtyOB!$YA;fH89{RYz*VVf3%BFuRkLuL(STG=>QXMLm%MioJB;r0>&tx`cBNnK zBw9L}yve-Dem!e2@#fE@EgO1ay6{i`euMVJBgvsdLV2xi@lM~}s7^cqQI zrmFu9FXw9T*+S-~E6>meMH>!XYE~;NRS)JK^_G}&12n2`$2803&pk%oer%_@KEkRM zz$~~)duu+k8QXEw(V0ik?Kc@;M7nh{YO2Xlm4vKB)=HJTSV}b~qn=pWr$Dctdfg=Z z?Cea;+MBc~lG!Y>dh0dH*MZq^lRn$x*!2{um9uIcNywL}OwWzOzSWrcva9oL?PWHR z#+zh8JTX0TliK+*ZQlk?ol-bMZdmq=Q==mEZsIT|CVH{EQsoRl_UHlTX6z`ryh4H< zh89O_r(|docIgH8+{_kmlUn>LQoA&&JrjiztU-~8a^EF0il&85o!FxV8}E?pRa$J# z$BnJ~n7x=Jv2=&5H&md27Cv$UhX_ANnFya?QL|pBC!iX9iO-=u2GffY|OKv`T`D~W>dQuV0;+u^NK@$CDwfA>)k295~Yn3*p zhST)Hi^oZ`7QIMMGl)4~PcySM6@B)^m>yFbIGLu^_^3Ze7&k?jTB&E7y_h98tEI2; zC=ei%R$9mO(kW`~Yqk?69Mn?J?7$~3m7HykWAc~R?8iObS*2gp@l>;_RH?-gTG&%H zy6#Tg8wg*5FX5+@5?+9o>H%2}+6XTnCteJ_tjaiX{y==xA<4rxj<1LC3d-<0Y- zA1lzRs?>V4Nde;2lb7kfV)feVwiEK(#z`dSRvwqCRQekv!r#!aP%!5fNuY4DiLioO zj6~j6J72dg%#5H_sXyegDV(YQ}IqaNge;D?F3c- zw#{h{-o_e#i*~OmGlFeZpS{B{>U@(~XjvutiRs0wRQ4`P;e}7)Grqru)peCxA=*|$ zYekE#Qrpn-6RSoyuQY$0aMNnFpKvbwk_SiH+oeOb?6zEKGv)T+(nD0Oh0;$@tKVY9 zaj(`_oQZ9CyL3{RiCsiuvgz1=$n(f*nGlUbQ+qlG9Q*C^$TDc%yHSObL-jd%lU~+z-?+ADD2>k=~ z!{5{T<+rNMAd8yq5A=DQpcc(EJMLmK)u{cyr*Ayi@fx-G4-{$B?Yzvmn$M&m#I3jM zAH`*+o;O*4mTf_ALAOx4)E^f{8+!P5wet_Q)6(l|^=}}}Xu(?J!}_iBj{LCRK~OzG zWkfYCou`()%Nv()t-d5S-_4nSRO}fCBl5k^oYYoP91rpk3DQS4c%_| zr`~+I(RbC#6QVbuueVn+p=vMXEZf1V(bxcJ`%YmQv-8^HCdg_mK`gTS~1&Nrx zagN-)vX~S2?zu~QVUp=w!#=ETe~)yENyl6UCrn+i~CMW|Or{(x@hlmI=hWdWKrv z$quvco&##qNmFKJwh@bp{e_J*hFQKwKk1q7=K!F|6CIfDHO3Lx199@=r(D=H7&qWF@ZMu-86OlhfMW2 z0z)~?^!&7RReY6P@h3i`VpeBr`nEjCR;Tk_hi#de&?Wb(-5*klrh8RC=q#!~I=cvd zF7$np`tE%0ef`ar$HLCgwcB~SFq**wNSAB0crEXT+@%J*8>N%zlF;5#Bu7uzp}oUJgBzebjp?oM|YTv&^Qr9 zAG>bk{FuGqL6!bD;zb)qFG&)wjPQNv1=y(*r4!SS-rJy75RZEXC;y#s)r{2kBefZ6 zY4MNs<&-GJ@~aF!C=a#LjQDyHT ztw5tO3H*&b{57f-i0L~TwWqzzR{V})Vt6fDjJuE~W!q>Tl^oxzcrml~+ z;k*M~+RpU#clDPO+F!TUBPkN1UDSE+yK416=*pIdjq4C3yX9fE^B){~qg1C&qTldc zxkbZmp!NDoSkHPI3R~_}t|Sd^_bS^JCr-csH<*Y3B55F*l5kE^W}Dxjgm>+e!=O zj&WStL|5XH*@L-VPtX*^#QVt6B9(HWZ`EApxx^fkpcJ`-R75YsHk~_FEsM#8xiOAX zxDW}n@h>CA==hSLwyDnSMso*`o(KtaPtX`K&PT*a<$p}X@}R!N)}ocEv;WBq31Zd; z_1D6!*jtnhIkRKfoY5^Nxk!yu6h z)d*fia5_=s-DrB-Pt@dp+K!nKBdSChn|vI-iSiQX)YzDC@pV1Qi30t|Mwf;vL+_;W z+V#^~os3Fc%9exPLF6sirb$+{;Zu3^dBk}1=_b?#(Y{nP@fiMy_O@lB3tM#UH=Wo; zV#}r9292mST`UVFj~rc>HZ7vsNqB}NpuN(uKPD-t?9XVF`H$$w9lx%v5Uu19nPY{y zF0^VA^+{PXCdYx9j5x0j`_P-ec_Ggc-y!S~O?OC~lHusbg!W~A1Q;&=x!rkMDS%jXwm1?e$g26+VhR)r;L{8)Z+i5 zf!ep%5L)~>wO%wwv-*u-WwY8VxTRSw+|NGi+Dtsno;zWQ`s@p4PXkir&()g!xCJ%j zO)A$(m**zS(9P0Kj*%|#vUfm302GuN4TQS>pGlt3MPEk!ybBtBCuP}=+d6zA!7n4t^ zVg@jKb%$om`RaOnCw5>~{?fRS6^Dd>srG+K5%y@|X3sMmskW)bUop1IwsDn~_Z#LA zV#7AI9x*+#P2MrgP@P{f-u7(chYlH(X@I}+y8A1eb5hr@IFIL`Oqigie$Bb2Xs25I zHRq_#w?~gZ>2uSwj2(1`*l&=8_G5ysl~YZbEd;fxpY_?C;{F~ADysb8qMta&i>TSV-chr6`-~P_% zbj08FGaBa|wXhGrl6Talf)(%RH?RpRdq+R#MX{H>qjnRV<06>~qMB9=O&IC@l@neqxvWm8X>s1?22;Yagj$A>-u|vJubY{} z{0owCatO5RuS()*TiexswEX7wqf6!bIftrtwQ!I)k#@OdRXDE!E&j*R0lXlK88NEi@F3mnV?K1RwBkfx3#`o2#|JmkV7$iL_dCOc) zUBGT7ykQ)@13fTCmvVQb*GhZLo{_VSZ4Q?LBgxb^XD50ct$&E>khQig)S?9`23iK$ z=?BX;#K8Ofi)x6qhL~x8L8h7BCx7L~BN3dc$c6SuGkq{PK`mJ@<%stJcz2N(zf4&a z!rq7He4{+6Lrn|%LG-bstqnb{SEUEDcN`Z}3r7ulqG>zQvK{OFL0Z&9VFQ%barEek6T!PQs!hs?-Pq;CkY_9NZSXg2E-cDxZ}$i<&zNFKFORAf z8KhShRSyXIqjH;O?$Q8hNqnh!>i8TdZX^1ULtN~fR%Z7YUE(^?>nW#+bhl992L8%2 z(F5r2ziKDV`OVlRe;r-!B7EG2UW;uy@5|wh(lVomkN`1`ES=bnf%Qstt@+z#I!hlk-i z;Tn_bN45+4;GO@pUQh5G+vER|v}DR@9-Y(}(P8uG$g$yS;bs3a52d!?uKJg(BV2yt zJJDt6B|1NH<;LW7=Vv-o9z8Mlc}Bin(HYR<^TGqWWJZc>+G3SwSqYA8rU$HWvAp4b z@Rm4S<7qdzajRr@FYYShDz)N@92Xsi*TZ8o@7YX4+a+nK6ja?Vqfg!ySPwEGjz8jrC&1=RM8a_PM zU;*6wt~D~0<0*XC91#Mzr{hjz;3rJdRfdr!RBrJ+ z<V)DFmE#3;>_3n4$q5^0pLJ0aOkqi>) z=`x-bo8)(sF5;*ORD6C; z$G70Hu&hV&-K2aQFC23-vG~Fzwq{GOa~B<0&ZXs(o+{ziMY z+#%edLD_O7?O-3B-5ercXL&v-Y2&b%u;09k*NfsX7W>rV&${KBaai2EUsj=Xd>%b~ zWCPY-6UK=0*de?Ro;4&NX*eGPK&%;KfqZHsQgV!98;w&0t74nhssXU0h z>VT|7Zm&LIO%Y+B|A2G=b=3Kq|MU=ncM-s`wM+8HlZ)zMnLi$dCBu4CZKA9h?@B#> z({OasHB0SpaPc0)HR>?Dd009ylCJW7+N!^LR}NtP_$5C?r&SG=b&yARY}r)8t9~$^ z#kw?zyB3|;@@ayvf#+gJ%O|q6+6HfoiA%$lTf70c7~2IL5G%35(}hb|TlKm2k&FYi})xr{til%%OZY^UryXNnzM_B8siSK9ig8 zdhm48NDoR{E&=xukavKk_+g%e0l7TaHPxPhWAzo86Qntp!6Y?dzJB4PG?1`>fi5W6E&y}B23(B<*$c=x=oP1sjoB$xez#k@m`Cy}@nj_62?u7W(kn*fp9 z>k0JuHcokkfg56!HAQ{!mKd%^96M?B4nF0D5#*AiuYB|Y+Z-}K57-IZ`U9VnX#o!7 zS^s;MPPhj($_vr%$Fnd=_M&YIC5dY?|Gs1?=HKo~8IT>{qty5&{UAkFsW6o{2;~%^wa@4a0eOizNK&=s#$3U%Hwd&fZyP)*k$ z<82E6umNMIlfplAN+1{RhigS>SB%VcUigZ`WJW#%eU%(HgNdOgpGMk_ZVjrAXLic% z`L3xmhXG*)_wP*9TD8vFEFby$wr-4VNE|+ARlG@^wy|>PnT0d{>@vl*~Cy z$W$yAX}bUMcXI)mr|13yS%kT`2k>aCS53M*nI{RKVhg`XFh5U~W^9s2gSTQzw zaMOH+;S0w~N6?i&!BUCMx~GdFXso2o(DE8fA|B41e3Boy0(+&{(3D25a%|5$o{&tH7&zdP#qa273?5dAfE~67t)qI1j@pImXTgEYBCy;dz`WgxjlnGM&s`VW;mrw17T@Y0T#Sx z1j;^!Ku!V~uQCn*3AFSOWZ+H-0dvt{%WX=s5sDnAb4bbaKHD!&Nt?xTEf5ohX3~ee z2A+po(;Ha@RKr&|WijDwd6}|G{|j95H2>+Fj~p;>2R-^%`FIwSb#0cU9ZLu9m&rvg zcZ%-=F3PeP9(bYZY}`Fr15t;JHQq+}PIzoNwVK?V#lv{EXGsUPZS7g|^|7v5*?Y!E z8`Huq>tO{yUW$t-M`!kEc@TL*wyacnNgR0yd11C}L2j?gX2`mS8ufh0ESoK9#{suR zpdT3KMUe_ONYi!SRGc}SMzj?QJj!DTOIY`GJ}bv*yI zlcZSxos(s;{+Hy-D*dm>m#6i==}zh5-`;vB-SJwEOL;%$dL%!3`qJ*z`4RmGUXn^9 zzv>lPaDrcJB{%`*oM&a)Hf^jG9#0%dHTHNf|J z0aw4mU^T~`cYawfb5c=s32Sv$!YkwO0K7bgYmGI)ONz{l{J0IzoERlF+6kW?hxfv> z;_zX3Dm=DLdH$_j(oUr94j((f*OkfA$=hV^iL~AA$H`&@wlMGE!{edIYvwHWqEwI>%{DN z!O^|i@gG`jP=*L#uMV>E;?1X0dJ+qawetoJwjDw6Z(ov&PI8@?lNTp=E5UOKHuILu z$rHnP=EPCzgL{Lr<;Nu2vxj94-{G7?0{vGE7+=9~-2IZwox?JGI+l!~QMJNIn^TDY z+?V8jq_(naWedS<-k-`x`p;7cX+I*_n|^N2>&gC48Bl*Ni+~y1eophzqJ84UMA>(t zJ2y>RV>=qVu9K&K#EN9QoHmzR9iF|^?e&sYj79#B*Z+#;vWWleZOaFuE{zH>(Sm+x zxvW$9PUPA)bgYWZl)Y+ixpe(6dBJCfJbNxFC%mk`lI|S1+w;-?N@e7sL z$C39U=Mj%Cl^6bEbczeUpsn#Z#VItMZ7R1>y$LVKf>Rh$*2+_-a>JI8$=JB-<+}8)G4Zhr{v3r&5xo5!eW1VB-qu0@^mM5L>BhR(kcX z2h3~#qo0?#rLL*j6}8dhpB8g)AB9#cD@(B!s5NKJq%g2X?mdeH53Ag8I$Llq#6%In z9KPqQ#W3%QbtIL4MbVl80yuqUfLxsOA_01ywE}E9jh0YhD)*sLW;l~QU(-2jCGB+0 zD+w_^I^YM+tCdB-#Cpk`=i)RoC|E1&6s?s%oJkky2d%A@y`b@HtoXFa>*89QzxNxK zrbg(La-1z#*A;qF01wAe&ZHIZydl$ZQj_}Qgl~iIjNw{#o$x)8r1s<4MzX5~G(lT0^$~6Nc`)?ca;ab_K@&e>q8 zO7}Jjpcm=Ro26@>Yu0$@Eu-xg?q{Vcube}B_TenLMdqJF6X$vD`Jfh1b)BpO*=p37OS6RPQKI+Y(d#+m0aXXuNK}EV?;}_F%H+-D73gyRTs9( z;|nOa&5>9f!(=E{+EUItB^4#OHpqyCt5sT40TL{&Ao2)BmYTgym zDtki z7?l$+JbVv`vMyLH_wk=GXElp1Vs-rIu|(t5-07NzJ~S7urd+seKha}LOejaK6oC#C zk<0c%cmN(-sAcdPx!&i>cdDIgRJ64@&L9TkElG73vgEDdp@j=w(~k4Uu^h%iLmbO} z@Osm7BhFyN^22`|ako3A#Euq;-%&+r`0+I2xty2BCR+mCs!VFbv(~Vc(rxJ&U#)RC z5)+zN%g{v>@Vo{FalMxF0V{bx!3V4d8W++nz+i){17-uGI=vQRFY>wuK37Cvs6*bY zh49Ryl72CZpMCP-#jgC>{-nf&J;<_xnQBoU0Rr&m@x0R(N(0?RR%AEkDMvBj=C{l2@l|QJo?Cg51UMA zAVhOa2u)B6e6u`tDT8MxPF8Q~?8mvsNR2fAG}CcnZVJhclMXMuJC4Ool zNv^+|qT6%<*CE}8lDTwAcBC6-hDL@+_5qvjmid=shEgy--jvb;+<<4j$2CPm@q%

YVqh}m~(ZfnP1j0y_2j#iLcKARP- zpdt#7HKrQ%kqYv+5f?3_g4VGkQbCIsQbG6pBA!~viFJQ*+kCBu2+Zano&1ZeqXdg+ zxLZrfKA-%uqV}LzuP9Hv*<1YK&Fkv#iZVMXTu=lY$ldB9URzS1Wn< zy=XP%xwKsCW&0{WaB1-dji+JiWD;77*$PTGjdRS#-e7Tf-Y<6=!0ZGh0oU-!riPuT&-xZxwi#(-1LC+_jQl}1Q zjx&CHqfe!eF@E!udXREP8ozl;-N|q1r1VWbq#lecgJ}>8J=)0lUV6fsAH}arwWL&& zi}KzqvohPrWrRakQul_+LmrOUHrHNb(0+pRl5c(xJD$+`#RY!g(BVI)RfW)X#BL`HG|6 zYWMWNo-Zg+ z%_C#V2Qh2m?zfZ_lGeO74w-!zA!h*JWPkWOj)lHu+Tw}9&XE$V&Mwhb7qOf>)QrC4 zO;#^LFw&gKD^|1gQZ{u(+#$GPjBgMXLK`*4P{(TSlYu}T)B2rE>ZTj&l&+$4sW#a9 z!d@|Q70iqX~V~+oJ&sGW=Ij6KAk%QHB6_h zsb?Q)yM7QKJVht=d@puOUjDsk{WN{WDrMFqvxlN}nZ@lV^v{f;7Uq)p7Rl;pFow=u(OqYY3-vhn+VONnP~Oq*G6DXAyDxy|gcl;k3xVC1)1 zONwIiV{7fn{C!vmY%Q6JK(m7Wd{~AI(kN-{GupI?f8+YIuQRE{p6je)JJDWae^^oa zY<05VV((VsZR+`J1QnE#sRTug*JF> zM2RyEifn$cX^CUp{gxFY4tZwCC*+TVLib*l1ZX zgsU$WTk6}NEiEsiRuzYPvt^g)U7?M-*x4&;LZoO;_qk5I(^Pb&QMA&#Wb^A3$;6xd z7F48IckdE;b5IuBevepDp$+RWkz(sP(~#*_Z*TE!1;_PZZ*kEp+7;Q?qDwLKx441xhKv0}mr45jx_L7x|9uJCP zuQJR36Wh|(;{SuKW!z;g!$-p}X={B@eE2G}=b!2NZj}1EpN8+$o%}k>Vw1j)f?~pJ z+I`m2pt$B^&R>dyV#UW=vgr9bD;@t4tep0`Ho=lTKrd}Q(%!$HMrnWNHu3qU(EB>bvzc^xewz6YEvhnDiapDQZ{qfB{n{HHD9 zX6Ad*_q0jhx9IVb*7Pb(lLs0;crW^Hn1~LZa4|aF2w4v4vNz0Lb3*iZQyY=}wr<1> znK<_}jF^j4oT1-pGUD}}V%eKG^`x$El+?#f%D;4K4o;!(5|h5iq*J85qC0hatW(aY zQ~hYr-y>%@m55Upy`_z~=0@F!Hqr=g&i$nk*Wwhbf%=<_m?MoK%_WVXEh@ZWZAwsV ze@h$YnxdCcFAd-h-Cvf$nO_-YD5f$TvJBE@>yGxvQTb4>QC{2*{WMB1zbEp%`KN7# zysVVZqK>Mr}*{H#3y3~ z;+jeP!X08*mDZ!ZJK78GqZd58Q_QMjfE}o7tVV?E&Q)u)LGeEM7{wv9UfP_JW_@*s=)G2ZExRic z()+jY#v6`Avw8YbYSjZq&~CN9QYY^CK)bqw&!X@k0mo;n#l3mexALIfO@uzsdXVCX zrpUwjay=zuT_nYMGG&RLQn*g*(AKB82bE}enO7$d>;pyBI%az>WruWcKj!LZA}04z z<#EVobEZa)A@WS5o-?zyCigC?69fIsdyLfe1-=s}K9#+}B+dXPm$L06TWoaF>cmRF zwlMyEX$FU<-|NI{|Ix-?>W_+B9fM=6;G?J9ynEB6;=s3&b3>m(-u4yIv0BdKdeZ*Rf|erof!F{HqP}b`D7q3l0|WU z!|+ZYUT7z#NH8~BO?h)o<-LR+Id8jOmc{AqLvl)uY4b>1a|~%dUptPRY#T}vSM2>2 z@$-kw2mX_t@)gZat8%ssI!`i+r>G|S@H1%@o! zPLu2wDa-yV>%>FrwdAqGrP1gb3b{-f63_Xy5ujA|HD6kgCncJv;yT!2TdUsU+*kQL zMz4>xHm!qPOq~C%NT_B8WBj+#)48eDTAKBy?eaW*fOxiAOSsrMB+?eFPT3-Ps}1YB zgXl5>9vQm$Ed!<~XO^5J1If9uevQB+I1d?cjnI!ybw`~zQq9SF1^(zK>ps4QDaL-p z$-0szUiyfW^%?>pYxV}|bo6BXFS|%wclY%BOh$dUU1V?IWW9&fgF*k=F6M90##o*e zeb+D$1_N3v@%{$wZp*^xj;SAOiM+lsl34JumS*`|bldl_HZS2g$|EbiIbhEJRt%}( zlCuqlHb=UT<8aM^=tbPb?eZdSWWvF3km(@LU^tk6BUT_|TgkrH?}+Pb`M22hK1=#7 zpJ>m<2iYlSNu3rk>^bfQKeVe&g4ptjcCpGc19M3HK$NWGZsWP1YUgBE@LPr_OIq}& z;Tfj)UHPTU=(S84LqHzZ#@1QcH{!!jwUOGxy1v2UZ+m#k#R@mewLb1k{|qio9t|GbTPHMFjzL3Nb- z_&s*JxZ!hc1VY{sC5zb^tQ9Lik7!|0@2%|kv{oFETCS23bff2)ABbq7RqWWtK7Pk- z7bCxjXmO4znNG%6YsLI8wCkfjZTo`x#RqFe>rL8}tIn5dFlI88y|1&;`!MDm;vpvv z7LgX|k*I!yea%x76n_?J&Fuy~BcggLq^V5Kb`$S!Vl~=Se#v_N328Zv?~PeJM_=<; zqBZ5QIrVyG@T%t(daY&tm>UsOYQ?yK)+50&I?^2Ev28h7?%vg=uP6#=15(_hOJvKI z{c|kAXi-uA(IxM(ud5hQ9qlrCaWao+{99|g$p2F7c(L~^+1fnTh!wU98)w_EVtK3u zzaSy=D2_2D>WeK#2O7+n<{5;^--r!gGCJIedHU$!u?EKo+h%QkJG)#)VySqJik~bx zZpIqVW^KIdNp#C7jgnr|8;o-G!@z$>iQ}m}%e=&7<74QNPjJ2RLi8|j`AdS|#Z6ynW6yVvjRqwcWweTT z4Fo5aeN6@b%?J*87s@tNz9W{mhH~+aHbcT#J=Vul1%HVlngNv|M>d&$x9^cYft9rRYP<>?%rDQ z#TIRPwh{@F=?M&A&VzMHm+ifx$ekDA;M zll|Mo=51WZX6i-kmLhkaMiF;nGH=&Dfn02@O_0AyyRwXC$DkrF-urG7^J}?|?W>ou zPL{#ckRf-b6ZR+)g8VN-sA(a=E@?t9Vc9&DQlc$b3u-p*NCO z*1AJZAyXZa&4;mTv2!rrcroeC{8~(^W3Fq6uCGR>Uv(P#uEI|A)gxz=EytG>`I|Jy z^R!f|vklYRvh_r43PyX#N_xmbSq|xP0`CR#G}UP%Za6_DDKx3&GLdN?L-8q{x*Vs5 zxTjZ{j0mAePWyC`Mlj;mk#4lFvtAV^wrKsb>-4fBhA{o}mt`^iQ%_mTOl57|B945= zNzl_@>D`9%R+A^T%cO12A=Am*$NFyRSK`Cn+E|V6 z{0wDx@mIpShk5{?|Wmb%toXDMH3Pwur5p#gXq>tUE;p_~hdHb2nE``$21MiT}G^ zPRA|cn!VJr*>cVq>si_*qZ+IBmd#?tUhQFP`dQIsidhXTQ+)Ny=(^IfFJsr0)-|xM zlzhgb#5CdfQJZP)|D{}+I80RksCB&1f1ZBkEnmkJU7WZK!(vO^ic+UM^Y$twzdalC z3MTr*;$6|J)i1vky?@e1_VJKcUac-*zxi(CS)@glm!^HGFJ1Kh%w*Q(?3VHVLl(;% z3`P5l+iH<-$=!GY9jR`UrFp z`hJt9$1Iv1@nz+s`{dHaDVyce#b?C+BU(GYzT%9UV-3cd6Sq}0gK?t6 zL9J_i2X@Gd){8fZVF!7~$H<84fx>%G>ky-wFTh1=)9{=1bKfBu>vu0hwX>Djdr-T2 z$W<}}*SPm`__VN4Oir;WEPDCmb8hFeU#@zxaG1U83o-u>-YSt95Fh@*V~1%0(eIEp zZqmD7(8P=xHeI#|*~qoE{@X_$c@*<9ILn!~MCq@d_VO2E#UZA*W^Std@Q^m&VhwE) zBSYGMV%$<%w{WYPyL}tc80%I$en(n^(z^1@!&<;{YVl02@v=?g4`Hw_E=C>IYBN2u zm&i}~us5K$tAI7yG6K!*ic36OR8u6s>?xC@ngR+fk=7L zIU0PqQQUJ(>pk)}(q;VTq9}Hj@MreN&OuyDx@-aiJ{Mmc)6VMQp|U*3ZSt$|<4XFn z4tfn4C}i|+pNrndIZS-MQCxGJZ`o|vC>9>qhQ#+lA?a^_{<(PVIO{gLZxkEYpOAr^ zjR_JedHT@L#fjtE8BE3}ozN!t@yxI)Z+Eeclk4t1ebZZ)xH~B&2S4N9LO-Qs>*r$O z39ZjWl4W~2hI-}xY45HiSsvlt7UgZ{14@a7S&M(%7ZsEHr3s4(Qdjwj5_vnoEw-QF z;rBhCi`HSSU&3x(k6c3X@kTKwtlc!Ba6(f!_q?WX$k7yTU|aI9{)2k{EJx*zu-4OB z+146A%p&fz#h+=3uWYo%-(nHJwTj>B8ly~}dj7;|O5TmPFStwLZ_AZU;i*@h-v83S z$X9iW^t$H#uKzAbncWmFp3@Xo^P0k4_%CPM4%75)`TPIZ|7aIVQ?G9dkLG_S|AqW7 z=YP=+P2v3frm&Cy1^n0Z@8Ms$u_^4mqbWST@c;IIDjC=RRnh9^U)C8qSH`tRj;#5IKv-cdP4iysmbXGooM-=q=dr7 zmdY2~$8SH&RlPYBp8D14{mZ=O{N~?Pf1*$3@&Czw%5|M~;iqflpBZp!S=Z@#ZYcOO zPhvfb-8N*TLFRuWYE|dPghlR*&1fh%6{|N_jypg8$}3zw?^l%T5*4NN=|f=$+i5Qx z3VYyqSPtu7JQS{lrR9ghiLBXb_wu1|7WBe&xC-XO{MV3!%hwzV*T{4jgsE!}g_Xq| zBw!Ns??n!-Z8#LpU97m2cE2177qcVn*F)hdn7jW_xB)Ks9f1cp-8xEvF#W`#a3Smx zJ{0!C5Uhc#t&GgjV`IpAP*DnK-dS)}Yg#cp2utDY4o%?zEQ5`3o}E#sm=%>t{hGo# z#fp*%3*c<%gZZ!#u7c_RA|n0C2LrGGI#U>)V9&Isupib!`$OnU#{if(mVB^iJO;o9 z4iA19n8YCkF3D^PC%Rbes+>&<=C5Q4Fi6H-+6We+Gjx zoISHCobiaFOudX_792eb&*3Uq3Z0kZ2+YiF3MV~EzAKu-4w%VN$5p^a5{HIT*Z}=7 zpQAy8{0$QyLm`8+1Ew=T7r@lH49Kt)*1*{e(y1N{oreL?Tfor-7Tm=k0v&gw53XH= z0h~R|<_MGlS1)dIg`IN8g9yMS58)Bac?88U?=g-Dk5kvMwiHDk@=+yeC8R^=;}}Tj z3!k6>*titML@s|BRRa^BAs-PcUO^;@fa1j{3a(v^XG@9HJG2qFsuDwCbro$1j(-mWxzJkh83n?9 z8z~UxeL)q%x=lC+XMTxeL~i3|A_+6MP<62OYto_X7#oTICgfWw5aw^gAh-mU!ypX6 zj9Nklr+!0$Pf;)|fYs0gdv3>5xE$8P0BnRQb>x4Vw)7p17TR~97nbhiY-2h7e=QsK z<)(w}#a%kU0h$yghH=d#>u^u8={5=K0E_*S6d^HUiDCK^{BN*6+$InpkuS5hc z*pFe*-H4+raOe-(0CYAH$rbefQa03Qsgn?`7zSYu3>`%Q%s7SuxB%9|jZpD&(gu@Y z-f?;d?82e46pn{Z3iQHSC=Z!g6zH*p!fvSALg51P`JvCnMp9fTocJ7;!wk5pRVeI) z^{^OrQA6Pd=!EJ@LJm`*s)fQ1c&vRW?1l9Sp>PfC*&!5egzXYT;hg8`t{q8-_D<-5 z^Pr=Q@}SGfMpkDmgSD_0gL1lZFrh%DTPR$JqJuCA!L?^#Ib79)bXe94gOKalhXUYK zSOp7U0H)e81a|3*gD()7eiRHH{X^k=SeU{wyp)Yq1F#&1U?VITgoiIGN_lE1oC|XX zqgeiiZfHL<6b`~dsJw(>&<Qc25367vtc6=(2zoB0 ziZNj7#Y6xuaj{X%#<6J#z?qj40l04ljfR2~XA=5X6lD?2fa5QtK-g{;1;Vwk6b3Hm zGzsQkNkOpw8Vp^9zU#;jm%>8W2uoqwO*jZ$sW(#~8{T<@?o|{mz#!=T2dxv%z5@^7 z_&bTfYy2+6FjxokVVAqe58coQ)rI7TTkfW9yiS!Z3Wd|*qJLrtZ0Dw`(3f&wDC~Ki z{=cdS&q;7BrT`y9=mUfnx}g(>U@=_&U?^M;8(|HcSxnWyGN`^m{)Z?CdLE`AShR#H zm3#y_xE2Or(xW&G-H#F3H(fLi521aNRt}wTX$gX`9G1dH=!dnBWBFTD4a|U}pCCVU zEF~Q#3PKNO!lc!V?XVWd(*8|>$X7juBcx|6N1pWMFxSP#qGzZZ*lq+8XTg2K~Q~jp8@xcCZT8z`WIj3>H)o%J-;K=zvu)ABLa@7QaiRVA6X;0A@gS z4H1Iruo&jTa_ELNupI7#0a&$${vTqaVGR*ji^pq;08EDkFc+4>Lg5tvnjBQW(7^21dy=>r<$r#J$Y&u|1fTpRI(jl|C>0Ir4>{qC zybgsh13ESlV)+{u!}I_lhGno8s$UXfKM{keungwFI_QDpHxntiC ze3-PJs)XsV9A>ST$A31Q>`46q&)_`hgQc(*?t@A-9`406m;!TP0W5??&;wV&Dj0wP zSPvUuQUj6vh)DcM=wZ8`2tCY!o{wBu#6}f6GJYmBa2`}Q(0E`v^ut_O58W_nAB_k$ zzyM77g;2sAnD{ZFhZ(R2I^jN82$f$c5Ke_vFdqh8Y!tE)f@RQNL*2j(*ls@xU^*;@ z`OpiO!Wviw8{s~f^a*XK5f5QH%!j406qZ9D+z4x7BUCL%oyFc_vC#!#3GYhck)A_VRBeaDZrEUR9S)bX;ZqNXYoSLw99F+1WY7*9VHV7ZKO8QAGus{xD__yt+Z_&P zz@qkt!}%~T;c&PChB_P$*KA>I??}F{84)`l4yVIa-4BPogDpy866r7vI&r|^Vxy3a z1<(V_VL5Dn^uVAmsB4%7d-lX2I3AY5+0YLc!CJTkHbOs4Cjxaa7lvRd zj>3L7Q#Zf9D3neSOe=}BMd?H z8|r*0k%EOV3zoqGSPx5~eHaD8eAoaNL1jCR!c>?uobp_3EM=n*Zh>C7I-L+hWdsF% z%K!t@p#$c^0_cWIVL9}{01UzqJO~r(=%yoa4CX>7EQH0d9D3nK=&E7kARCRa%P2zm z9c=-o!v!!G7Q+JQhox`}^uczc4~K)$4nr^(rtYB1paYh}d>DWpSP#qLv9oXx+Q%Gr zg&Wz(8AHK45rhs{4D;a@=z$He943y%Qm%cns#i#7qi?Y0v|+U=>^r z8(`e|$n9n5h8ZvqI$Yi!Fbif)BZSa*2_b~F&=2Eshy+Z9iTkKim;v)(4)nl67=T`=UP?Kz zCk(pSNM|DivtZ&c3>Yv2E`m9*8WzF^=!L1%Q2?jHAaueITmTb)rT4&8STKXShvm=> z>tHzy!2nF3N&gSAF_R7Zegt3^TmlPVEi8rmpbvJrjF7@CC|~uE2UFp4m;?Q=5Vo6z zp|B^cf}>#oPK6Dy6ej&fubV~xcd&7g9l5aGy5N2K6*SPETUHvDYV z!UlK@Dk19ZdOU==Fb8^IAuNL)SOv>r#tjqRBk77 zupWkB2quQSdnPO4OVHV816Axi6EQKkB z7zi_9EzE<8#iA^LNw5f}!&NXBF1m|4hHGIJR2C9hnE6i{rPZPoz;rnN9{RtNjVu=e zG67b>B`^q=!w{^2cAG`1gBdWRj?TDgFdJ%rqRJH*a+vrBo%|8 z1FnVnun~G-$^%3g9)v;YN`H_#(Wpb14$EOK3_v&RQjCW%4f>%MHo(pOk0A%&<)+N6qZ6C^uaB#7KWhGo(MdG!Eh$bY45^9Hr(v!@+h9dH0Xy8SSvHa zMpy=u5{L|Rz#z

SM^ma_ECKuvVtSMw#wGt^-vAv*1!#09V0c7aP@Vcwrr^g2!MG zrj^k8p%Ju0j9*5xiBD0-Fc+3XFATsM7=q)UM!q{$0yE$O z=!8YE5Uzq=ICVL4a2^ankBbd^5}v{=nEnin17^Zvm=Arh5Y|91Y=o^j=z;c?H1?kK|4cT5?8t>7SPbpG2pP!A;}^HU(qfyz+E6PN^D9yZe1D1%ur z@jrwTj)tW$2m0YW*Z`|w;xO6@Ooazw4ov!x-U8F08#-Y*OsS?|xCpAl8M0wI+z4}r z)Boc>LVz8qupG{Y0hqRdki&dvPp2`#4A=mju-(Ua2veaCX22Sl2OD7_%;i=5HjVa1jhaH!M7h zh<$-aa3c)BEwBNGVB#3s&?c%3+F=eH4_$?9%w)p@3t<&p8$b|NLuD+6eTg7UgAV9{ z`LGnap?xz2!(5n1fgYFvS3{>XME=gekgt$~3${=mEZriH|7@&fM-Yzwnn;|DXWQ@q zg{xr*)Lupo%9Zv7^F&I8LXA*un~6Ig(Kt93+*r;X2GS< z2~&4drLfM$hL4Tqdk}<;(0(r6ryc?5h6QjHtR;OPEai9N_ZSY-U;~^96DJT_m;uXR z4y=KNu<-|~2)5fxWMMuGL04J>b$cEPU=A#Vh0q7Ruo_muS{Q)2KN2AaBOy$JWj|pk zTnn9W3oL~Dpa-`58F`oj127YY;B1&Uk^VoAjns+M4RpZeFc&t!VyNuH5V;@Lz#7;n z)1f+v5%Cw=1k8lFFdw>MIV^?8pdWVml?cK#*a#g^o$O-3U?Y7p-3;c!)zA%tupBD; zu^cAB2ABqwOb$vg6|RO3SPgUGKIn!@BL+Y(tbu;m28?rd~kRz+89?7Qm{51^nV{4 zd4~v%%+Q2qSy*})L8u(TLg;|G&<*`C@i>uyjWF>-3=Y%i;6~+0*a;J@N5aK06?$PV ztb(O50DZ6lI&4Q=;lyl0XgdE{8=fhO!hEriFEPy_^6xP5h7=(2&1n0Fr z61HE&IH4X1XTd}bgWzmf3=5$bdSDf-)?6rHBR&2|Se?poA3BIcBP_tfc5Nvbj)v)^ z=fPaK2o}J#uox=sPz*C*4V(=d;R2{$jKR1 zS}{z8bub71Kep}%zR|iq9C$p+87`Fz&`E^~;V5?j3Pi1vVb!QrDin!YHF5=hyZa3|;YNz!sKd9vQe%hY% zUtceHf1l6u{r~65pW|r584uNmm|}@VR=CD>_MG`pz4>|-GsDia%p}J+&MM1nZ!&O> z3`<0_rh+Lp|BexIfJGkWOc;NxwPS%bmYH~gj-PF+*~bFsImy=MhwAejS7L(ad%y2LU&pQ*qN9-&Nfm>JG9&&0De#58Bv)oDb` zv&Lb@56aIp6VEj;ra8o}tIZ(utnkp)&i}eZNuaq`&zWJgOM`6VII}GC5UZSF^hSGy zDMp`XMwnuOeH`UD=Xiw6TxH}YGkA^m*m;ffpOF|8$Z?uQE^>xd&U2m1j9hDzv6am? ztAHsEGshVgS>X&8mk-`eSxXGO-81;!W*Gt%q$v6Ycm=n$LP%@ik?W8aNBIwEmMVvbX+Fn*IMW;^3|YJh2u zGs_v~InN>+Z&sddtgxF^_OZqlChl^-PsiEA0`nXhm6(;7WAs+LoC&Tob(`nFfaAvu z3(RwrMV2_pGUvF+3fH*Kwth4BN_&C{_OpwlEbwr@^FJxEE-=rQ+f5y_jJ(S0HItlS zhRe*e;pLW!O`Kr|7rDa7tJTM5M(!}>Ofbhz7Fpm7$L||?`gG{8od*u*khxX4-7*zsBee4UOm&5=Qgti%+DxXcop291!j zuhRhz3@P|}=bc?#d83grb&oy3qnu}E*b?#x<8Lr?W;o5+qK-28W*udQr8hYLjc?JA zKpWSYV|2)|`6DCckv~?DeWMC;oF#5B@fr`NKhXfY*vA!)viGfKfD^1TGNxWL+4ZOL zbCi9rb^bRb$|{WhnWyLV;o|M<6L2xtux9o z%^JHIe~Si~<{bOD&QW%KM8h25GDkKfB7fvK+^<1qKB_?`XEn$&OC0!^j)vD<=L(zu z*vLL^W|&}(X%<-IB#&{P@lSXzaFOv*_0MT<)cNm`$Ox=*oVmYJfNg)R0JDt$iDx#` zTwj_3u;o)m$Zi%{;0!0Z$Rn(AnTatCvWwZW8DXBITxOY(PaD99L{cL9rz&QO^)nn$_#X~Ic zC`Y->5;s|4@^fa08AiwL4W?LP7Z+II3P;)Sc^&68t1Pp|%ICw+|L-ux0%$LPE4jV~J@k21^FuV{~LBNF2h z<1BNMi`-z1sejh+yG5qG8duryRmVAyk4fhLRfBB(x&}G)4ISlS zRycC>n|Al42Ly9$`!6Hr;CD6r9#gfd0`@V_Jc}%Fk`tWg6qh;8b`D!aJy zeH~$ZO-Jr?{wF0W0v$h6kn2CSw(oVGH*}24%yaZ-W{Tm|-z@Nj*Rm5Uy(*VuUJ!}Y}bkHkT|RQ#{HX*I8uC6CbY6Fv~?AW^F{G`AHi5pbsAG z;wB4hXn)w>|1%Su;{YpMDeoQj{)Q9U?_Hc-kEOCVuCOS04em4Jwkw47nzdeM+*)Uz@o+uOUY1y3nTJ_rg*7HJX4KkuaESe( z8Xo63D=c#@GoqkG^qHpeFC7!6*uxwPEOLx9JiDX z+YGXuks0}z8N7^K^5?SV1vit#a(;Iv1GuxZTY( z+qyN#iR(1TGUvF?<&Tf(+4D`wCv3j!HN*x7tpPH{MdrA2qw_y1(QuQVGR0*cW#p53$|TosR)EcYHXHMt z;WQVy#u}rySc*@1O<z$TE*{k!=G;%q$b1_v*+l zmRR5tCt2e>n_sCxW*DFMU}Bn+?BhH~xxqO$zsk&nA2L%C>jGVj{++30g5&Js4Es3G zAue;A(O2s*bF6ZhHBK?{_wuugRTkJ#&|x-lj%hBBNc2iXzTk<*W*%jR$CzWw@0ntz zILThlbDXQ3WBjPCit(P5@I${x-!&k85G&JB(<|ARGptp+*6As*p4n+J`MJ*;wx z&Hw08%@o^Tr-STffdd@n80UD5RW`id%zn{>h$;3m$HCV-{{@Lrfl;n^IL8{78M(*#Uzdp9qlaHIbxd%M zU91k95k`OCapd%ybd1?Umh3@$<}EtHi9azSrpF9~-ApW4(zh$GgC&l0kuy9rZj*C; zL}FE<@f{jaFu^k0xyUirIK!+8k8+4rmKcAh4zZo<>}B(pZANA|%N&Zpo6=)O->1i4v*t{&muVK+$61bYnRBdhneq2q8g{UG z$=+d#Mdn5%#w7|YbCS6aSX1U%ONCkW{#UIa=fIY;e9T0jWsrYP)GmGbAVmU zvcOS}vdWQ?MB|@pkQuJChtaRw159y^ISzct%y5h|Y@XI2M_J=If(|puc@A-vM;QOMQ!?_83Q9~d$I2HK_%27uD z!wA{NWfmCuZw)ZXO=j6xwdQPPksX}mC@Y*|l~qQ+EB+lb!xFnjB(f*<`BnOVVUc!vhlw)xT;}7!kmN?Eb=efu=t}^*!1Nf0$&t^_D!*!Oq@W1kL>L=R!vHK$uNr_oz zc$hgZv&bqZxym`Nv%>g>CF0TvBVIQ{>|*sH9cAHRxx~zhjeuWh#c5T+z*}>+Y*rd#Gj(J8;QI4%FbC^}GG5S+8 z-LP3tu#H_mb^bFFeF6gtJ~H!KM=oME2J9A|X52AO7+Q;hyhgOA>< zr`XRN=UC)1&iu^z?}={K7X|WM&e(YfSG^?u7c7WPw?h zS!8oegW-KHa-6jhiD`*=O+!pF)2JYOImBtsu;DQZhWA^24sw+%jQ`xJ_#Nfg`dHp_w&y%0M zj6`-thL~jSeEHd(ke}n6;Sv{_-6#K}b~*nNNr_cv*>#~c=OLE3!U~&PodWi=d6x#* z#mq&U^#YezVq(AiJj@!`nLI_k2h`6)9O4Q~9BEGKk;DLNJj_JHu1M-)4RD+VE^v}f zm)K04;X0QYJ#|;4^HQ6Ti_A0LW(nEGGPA65fYIH%{NFXSvwN5S|CdBsp!qTdIn7BP z<2)mmTSK-o{^(ti4AacBkB2zQ!z}SA%S>IN9FMR$x+}8D44YHhVF$;fBYGq;Be2Y6 z_CG-nPty^mIL{o9vB+q<{A}eSbF6Wki9M#AU2J=@nd2BIS>Zg_xXS2L3}_@KqePlr z?Bf7OIm$WCvchs&LtJ9K(H^);Id(r)IhHue!z^)$6&_=i8?3RbLq{L8E7Hr6w8XGP zAICVvIhHujGMk>J0w!5w7Zax&In$hFALlv5Dob2vnH^78o}-NJl|N%<8F{AjpOa{P zwyEVHXE?z{uCT^rrv~Hhvx}qb;}nND%W=+ghKro%F)lOt9LMbp9bq%OnPT5_oc}I~ zf z*15>!^Ng5XOf*?jW?5sA&DY4!0+(4~^moh@6WnAM+po3xIKW9RaGssr2E-gAk9Gcs zB$5(y%yN}O+~hc0t}`O`u*xw;&o%>0vH$r_2amGIj_Y-hQ(RC<`q28X%9O-H%T#gQ=4uL3sRZVexAQ?ZMKEO3gGJj!`)a+OOjx0}y%j_=S>_A|!; z7C6XJPI8VVRye~d=QvW67z0f9Sf|~{BKP}PmS|i~6pb;?gIt7{GGN+kswKQ+g0K12*A$vH_ zUM{nr>l|hCMV=>2agtpuv5(m|YKKE35_91VE_0cY{d&eEmxiq=E8!azZg7s#qP67I zAD9`Y-z@(DYtAe;4w*?7-eM-X$O@NPWtBCKH2jgNNbZU>GR-DtxiP8&*50N9wv6eR zk##f4JS*adxXu!rFV+w|=!` zuCvPK%RC3})gTKju*gwPvcx%-xye;FO_;gM#hK&^vut>m_C_SyCC1sq8Rj|9S+24% zFhf_EAtu>AX@=OtAr5k!qnu&Gdz_l^K5HCiB4w|zi)9vA1#{2Y? zoh&fVNv^TN$ouVLCKzp(k0}TiC}8M>#VhF(*;s zG7rz%ENN5BB-0-=h3w-HODu7oWyU|QgG{oPae@_&9G0j` z9Ak~~IX%A0NSNdhGpsPrroXcG9OgV*{@O@cWb;$`HyY+L3v4*7VXk~qewIEZe;6-o zr^ESANTfR)JNB`UqpWa_t6b*Nr_IdMbl?FUV~$xCIm8mjS>_D8K4Vj|#>mqx$r0r^ z%nT1P_jKofOrjt#$4Qns$9Yy*VU@j~wFjP|AXA)WF7$Ku02evK#?Nb*!;EA+>6m1d z+0c0%X8!Li<%qRXV3m`M{-+T!!3sOL z&T%H5XNK6tzris3(NpBJjVPBMy%cc z(=&lAXPD>*?BY86*s|;A^--o+;t(sG;yNpAeyKge3=^mPyq;$#$Jx&^7r4q5 z`pdw+1O9nE$<~ISkJPggX@NY)IL=wl@E8|a<0>0ZRl&MwR`q+rXszlSpKd;Ac)DfoH$t)*0#ATKkzr@Ix zW|h5+-lU^Uaf&%Eu)s}DGI6N}*}+v#GJdo3KPQotSYVb_=9z3WmE7Pwn=dmnoM5ES z6tbCBW*EI(Iks_}9h_kg=Q+S-mKnXp>;Dxxe2eqnEYT&<%L26`)(U?E+s|R#{?= z6(;&^My8p3iVE1nQTDUMF;>`irE;t=ak~Mg4V3xcwWJ(pX+&aLqRgYLa+T4S+Y?ur zBDS)Noh-1QlN{qb=ef#N#_zCHPc=gvV~z_fva!R=Fu{4Yb7WZ}ClSeeW56WK%yN-= zuCmC;(=^O1=Q+z&ZZQ4|4Ln_WwlTwA<~Yg%k8+gjEHU#8=f5H`_6*03T^Un#r&I7u zBW9X?%y5WZ9OnSb9ONR0xynO~++}3X(h)8*$2ArhdA1HP*=cWa_Bqb~a+u*c3J&P` za~0$`vy5M@VHR29D9hn}E^?BqJi_=ZjgUz$FvBJ0Sm-i?oZ<}UIM2S3=NY-g3Y%Z$ zfxr~k*u@R@vH2Q3XM!arS!RlhJjxo^n0U3lbFK2su)uy!vc!32yS2-a1&QW@o-)N1 zcJUbd7`;xzjI+dMmYLupkFdsLO#Gfb@OZ$fY~c`FInFlDu;B%!`n5Lc3r#Vr%(JOSzA*k`BjgHK8GVWTgX&|FlgzTlp+VC8a!5SUYo^%AN|=x9oM-dvEfF)! z+^FLt5_yRt$2h|UF0#s1#&0r$H+ax6%?b9g<7P|4UY1y3nGLsijxfvUko-(>kvXoj z$lR^Y|D42tM1^Bq=PaAwXswuG;x;|yVUDx4Uqfu;BHOvj4o2>_tC?h;85Wr15DRR* z-JW3X4(ESfV&V=JaGCLYtPRs#&TE)muh1~FoMDdh?Bg;IF*0lbY~}=0oMIOTU#Vf1 z3L54y&NK0Q&i|@J(`z*R`=*#_R@leR*P3EZbB?pD@Gz@fX7o*#iV3bV&9T=h&pD2A zktIf6Z|2y>MOuFykeFb^W<16uQ*W@DSQ#>64&1E(2f4~&Mv6wxX3j9fIp$bqf%6>Y z?63jw(3{K{8;Uyq2hRVjL`tIT4;5t7pO|W<{>&6{kgHrB*U%q21xzvh4)<9LoCY0g znpEC(k_8qy$tkY0%;qGkl5Q!8=nd4y=xx^W+ah{RC zQ~^_ryiJ2_W}X>FKWwJh%u#l5F1*iWjxsW4Gcw7g4~OsnC89HW$|OtdW`zS>=Oml| z)RU1JR+(eRM|6}!oMDYsHs5b%SYh(d9OIALr0iy%JuI^Kqa)Tvq9`!WQ7&_w>zrit z?UrKJ46&Cv9%7MeoMHT98f3%AH8^fSpU@!V%(IzACOFAX&a-<&Vp*bx>+EIUJ3OQ3 zOd+d(WeOSnYxy|+H>U8NPRl1X#M-Ac#FnxdWQyY);GzzVGOFAZ6P#n3n=H#W()?*t zCehC5z1}D=#Zl%s#R8W($;bnG&IDJPrT+*hGQ=dunc*Dsta6+UpV1%_tg?gAcRBx) z5~+77z%DMakEWDqTO)hf&vl@K2`%JR!b7p`&9O4j5Jjx1}SmhdPZ1}v>66iQH zf%D%lkrS9o4#*bQp_o#J`??0&A`z*zRnPu-+bd>!p zae!rxf5rK)N=ypWSYrJBMzm;(IL|(={EG_M`&Flbm9Ob2m$}a9lIOz*Y^r~=rW{zd z`8dcTSHEFNxXyVle$(dV@;66}w4~s-^q8H@u$MWGvB;MH&|?-@<+1;?Bpz07)EOVsgQIFJDC9;hCh26_$4()ox?`rg9 zWR7brvg?#b>N8yBB8Q{O{iP+_^N3&B=!q74q@HEtV;-qjb)=0^^>?!r8|hh()Ym!i*hlJ#86#qvlk8)OL+ojhpS@h6ZR zHdAcqG*gUREk83Xv&bqp8J#ut*T~P>wK_Bs2Cg$D?0dcjICQ-cF!BN;_?Ql|@8dSt zi&PxiqhfBp*wS(Mr8@En<}_f&4l~7N=D5xRqc3~JZ^iUrVu>3Z>C!;-1`ROBQ4VpA z3tVQE>&ze2p|C-wxyUXJud%?!UISs8^X%m+3-lj|`t2C@2rJBTz4sBn|4*XtMm^#o zmO05qR#{`i%?kdNikM@G1uk-uHO{l8PlL=b^4A(-iYx45;uhstyj3|)-a2BW60QA4 z$WBK8Mu(W<^c@=H;k>Em3d?MKg$}ZVwJ^@)VKc!Do9?u>Y-5qVoZ&bZd6YGFj@+f8 zzg3Vqjt?ln_E##v9?moRDkJ0JS3gpZf703&ECJK6)ezfWr-N+g40Bv$A6Gfa_@~tO zdgWMTA4f(dh9riD6bx^0KD>UTg5fnIWm9>#j8bhio`( zt=Pz{hFh3tD|4SS)qkr&wtiAa*~Mj6${PB-2hV3T#47Vl95K+(dM#jbM4}>*Sp1xF8YppwO`kUa_OZr8Ow2nqOtU!e{P#)BNQ`p+ z3o86OBmM^?<06aP;0%}lQH5;$q6*o?#NT@^d`W)Ja4xKe6;@egjWxDBXynSZvnYS% zLFa!?qG`d%m}cY)ddgJV$C0t6_#8n36Baz$6c^Daa!%u=|G!vWIh= z_>qxvozVx)(2tFj(f>7*O#j55;=)hm=Nc<)*-(yMtUc)bACibKcoWGaBR?}@c5|6c z$2IU}4-BR_%N)}uG{9udjD1Cg|Id9MVvfm&jF_c|%@CLC^8K@!VKXbI)csA$5o;qc zuAv%d*w|37&$EwZ4GeOTo19Tm*Qxb-Mg_ghags&mch~*$No&dq#~)pyAs^?G#4ZfA-E zmlz2fFO{GDoZ~2$!|OI3`&S*hOvjkMT*tV;JbRv4uTL`mq`L3_!W&Pj*H^jrWHaz@ zrtnGyIQuLeWBh6rGuoviUpIA3vBn%bpJz(he~l5#H_UmCb1uxsD%000zijE4V&&Qq zQ!KI2Z4a>dIwNNXtDIzwN3*8v8&1Ou>VDUwM>YGHeW6Xn0>|0h5g!3nPyjJ})+P z`+czxnDzv1rdFHn9r$+Um@Jcv*Zj4E$PW!g6EoC$8KX zM3~1<7@rnz5-;=QPpiZc*Q2){ulq$}8r|wlaH1o2MljbJYuN3tBSv~}3m#~VU9!7L zhllS7z8|JLr3doCITyt)InyI7l7GeVdW)_`FFfcfcvUubPEat-d!}9Xyz+Q`I2v4j zZS24qr}*7>uRC7P2uIJ_%KPz)W9OaLAU^kob{L{j0`QhXB>UOC%-AVlZ@p?yC>Qh^#E>FhJ z+ub1EHWGYuf9#wyhoyT)j{AEW@@%b0@cye~`*-(>ANu31JbRa_qD~&-ZSO0 z>$DSoU0U#!>vhQGpu6M2@9WTMD=v?@oY=nHbeX#^y!*qeVrTCi-0ipDxtw~mZvFIz z;NfKKg1ys%J%4WUwI6-z!Qj%1V~^XrAULX(p>X&wJs7o+ck6L# zSleF&_g@^_w`Ws&a`t$A@YL|udAnP+aO|&whr)Z^(uu!4USHi6JYp;CU2t9flm^4P zKYT-Q>E#;S5FGrp3c_BTzuk+|TddmL$zD7)xU(&G$t9aIj>?z{r|aaDhG{=-{t3%0 z?m1DP*}b*Wd%9hZ$v^O@;Qei}$L<+$z5KxOdSUDO?5N9*BTidz<7H-d*5$OzLyroc zezm@~c?d;5XUO8wd$#w+X^ny%|9HGU9enJv*tx;t{#e6l?P6uIjo`A2&Gf9xOnhhl zUVB6Ew)WU1r;8QO*onQ(bE++N@$RF7Enf`oYm1$;`VUC+BSI z`PH~JXRR^+CC!7!>wfEEBzo|M;G>t>7d?Utf=glWw(T1C4hs$~9QRkx1dU5GkB=q3 zeB9qn6L|CXVxGAW<~kX?ck5)H{)E_L_il(Uiic|w{m>1;J(p{z)#hLO*X`$1^kIz) zp3x&%{M4xTPy)bsco+iO~)%c>}i_ZQtr(Dmix(;XX zNn4Kr&zN(9Oe)rJ=7O8q?|bxxH*Y(6^Ss^D;!{5e?oP$d*>hC7mz z?{Q=2#p>FF!Go#Tvmv%P*H>&fl$iS47iw_9*ybNdx8`o)96x!0MbLBX!G zPShJ6-stBK1`mfDX;!f1aXY)KesFu|iuIne6Fa*%xa)~Bws>4lox2mfqBnRr+~Q&@ zEjzKRw=?b@6KpvzxaQ*6<-zz9W6@ae`8zq@uv67$SXE*t`1ao5TThH#wrAynoxq2K z`<@WKI-Q}K3xn@JDYkF#gmh!;&i!D!meUsmyDvIX9}Q>f6Tw3Y?QJ+y%?EZeerBh+ z4#Ab=PVj5J!MW|R%VI5;>;!(WQ{Ajwy_fC;PYK@I9=m+cRNKz=xxt-JG~AZ6)O6WS z>`B2xVV;&NcCN48%CmP&p5D|>?6w<&yPj-tQ%~3l+_Rl&Gpy)|JF$Cj489d+YH8mI zd~`e0fS38+C-20*aAR=oQ@pR4dP?v>d+dpOSKM5=a_8nxZw$A>WxHB_H@M`DW034oNR}oT!H{WG8>Z^oIB` z@gC{uxi#*?QWF;D(&Z zAbjP#ILx!@vMsFXWW{0HPxvmdPN$zZ@bA}-F`6ii}yWC z>ne?2cysUr&Fvi%EC_DB44->*aIo70^N8Tg^G?*mH-gbCZVtZntk?wyCIm;H{hL$V z@Hqd&9r3MET&V`H3um+m&I^u(ZC!D*r|VR8pDH?$4ZhzIo^0tOFYrtX2lsH__PdcIg7b=PO~cu@1n<4l z*%QmZ@I<}OTb$?>w`@PW+RpV_aLZ1{1GjEJsQLw?x9tRRQZTFwi9 zh4hK~N*Mg{POww3vwvrrWBpru{mcQu9>G+&i%#he2l0zf8GEO~YF>MCB>mw#l*ezs z@fvie_2nn(-N9!a^4$|Ivo8bjRq~<+rPauy@Ew8 zY{(Ej`}XanIV9L~*NOUS7<|%Ba8|HsV5j%j-yXc}sj+iT7i$$;4>MjZKv&F{S`8f8zhF^Lw){`(duUAvJG4H*7`*gPn7GHVdS3WC- zkFhE7wKtro*TT%7x;=ak^Y|e1Z0|=0-ATPFoR)9z_kMKE<-{9z*6VAxZ#^F`UJz`R zr$6H77h8CHbJpVA@=UyDYM+d*{HmJh`@`<1?%DnjrF;9fKbHT}RBgzxDMRv6DhO1t z{V{Ptcw^W~ZofSb->U8H-sctQ_pMo&^^3P}zsVdHTz->>c^LfG$?{ju3a^ZqI(>-# zc&A?{hZ{C89&V#0`69)gIsKkB_t-n5@j|aof3VX~{bZe|cL;a=;m%mk3T}9om&<;! z#G7}@U;FZ%=aS&Kj9aJewwD`I_}X>afN=Vd@YYgXG3K)1a%*S*qHEhL7w(G&b3Nhy zgmm=nFAv`K+}H(YwhL|wZtc-P)sf)5i(>ot4u~Iq%Zd7InE4Yg|G!PNr_-I(ABCL> z-W0ws?RTC3qu{EmWBblLCf)G%6ZK=KDD~>C+QN6tyN`-zKN#G1wa;qZ7n#ZFoyXk| z!aV=?6Lz!7{Z03M7JK9gdNSp@<1e)*XY^Aq4-d>mkKLMTH+pAI)F;Cm|FP9r_%VK@ zalg;E?>teDgz>ZP_>~5lG_a)H)cwD?^*WVHOq{46mM41Kua*n9UcdW?-R}!`#y!7! z-}oYJ?r*&7#4bnUwLp+mRWHBnEP#Eoo{zPc;z!=XTM-dcyaQ? zuY9W&cKxt;<+sGcYUY0}9(MVd_@?;wo1N1d4p^S|obbQs4)@RQR+op~6Fl@hA16Dd zhuzxA*}rwmvE9n~iWQej?jC8-&0m|+u$@i!*Db|BIL!L54l}&plC*{&IkEjg{^8%e ze@yum_ZPRnp=gkO%nHqIz3Do0*k#K{ci!B6Dl8qmKkb!lT0A;?aszC|!`-&$ka+&% zo=J}iZhB7aK-A^ozxG56-gkBEz%?BgTc*F=*?*t^&A#-y-}K3y`=9yM`{Dj1?8^Msi_U3Ff{kDD7Gvv0^0W!XY%7 z(!!T_^1V9Dx3#u=JH%VQVhu&2L4Ipq_Ou9&nZUxX;71)k?#8e8DWy|zZ7DeCdQZ`Cclwk5-!$<$`_=vw}AQ2i@;?Kf5)xyC+;ud_A}`>wB;x z(p}$h(jT?;9od;3m)khs+D~Z2#`gCzNOB zx8K9e3eNqOYFoTtm_1qTwHDGRlruX87X-IH20Z)!_R4^G^5m-DlMk+alJ}irLsds8 z+&}j^1^euTLxS=D3a4i4^>f-~yUV_<%Zpo{;O(nw`omt=e{&U&$=4r_kq>51;sm6r@38MWXEFNs~ayH|4k2f>$mVo$i>XB($P z&JF*pB>b_zxAM*_zbM@hykb`{x764Y3u_1uWZ&9};KAm{TyW~9i-q71!s=S}toet* zJ6{~zziaS^!2>*{^1~CsQ*Vo1uzSkQjUNVkUgGB3mita!6FU}M@KR;Nuc11B6x{jZ z*uLH27w_Xg3hocHMt&T+Z}*s3;m5&4VQl%w!3|-|9|A?v>%lcI6`Ne&j9I|ivJ`yGw0sGPlBsL2Y(XW8XDgS-WuBfv*52oCr$+446XX| zBBzeJi74}}ZQ_{`S2hC+u{Y3DY?=)Vpdrh!h z4{i|LHNRDnNqe-{?|N{57;|r{Lt|pn4~fO*>b@HYm-1b=2AB5wldMjE(A?}Lqv0MO zA_W@TqP6YC?z{Du7Q0iHg=j5!@6C_7V0ZW>ch70TH+wbGv?sXcrf_D&hV}%P+$ffc z1uqO8iv@S{l#a$)@R=7|{od0oX=Csu!N!@#?6mVp-*!8D!cBEpj;_;#eK#q7^z^Xm z{ih`N?i6p^<1w)}xGxMYp9~HQw#9?*hrywEEx0ReXhHC3Jhyn;gERe8NvPQv3>D2>ESbK{+DNF=zBNq3NpFJ zH0=u?T}$pvpIO`fx<~2f?UY^PC>^Oo4Y=QrwHmjX!z!l8D#4hPZ7ocJ$KK^X7Y ziHGSh|Fd0(Q`5tqeZl<;+8LIf+!uU5Z0E4pkl2D)d0%kVZDPmv1#i7gtYxoh-b(Lp zTsYb3!ogiZV!(J7Z;M6GSr`8GrVc5#rr4jv_B|#1(s)gtunS>#uGUPL|EPHFx0GEG z-!Sxk8$M!%!!N@cKIIPt`ePTJGSONKo|+3cW84$dAKS{ctK1q~GNrS#VvDW8Ik$^t zFAA=DyIA=3aqmUJojb7y{xr7l)b2Ap`+{5UjGZ4OZuQn-(6v1F*S_6T()o*mJug>B ze1CAmKig|-Vy*jsbGL+FAgA{S_uZjfn{>ala!>4&_t!@|;QoO4Z_JcVh3XvJi6UQ#l^!ecK5oF>r46A<>%CX zOE0J0U*D?DmXcoEA6)ecJzo7SJ#GxYHr^lH9o~;0sMQlYBYy7Ah{Nxun-2sJxc{W2 z`>OlJmJZWn?zjG0Je;X%@x%eWe@XZ_*{n7Y_?=?=cq& zd?_rLI1ucqgli<0I}ond{!@l!+?tZ`+vC9l!JT)-Ej2{yZ^Y8RL5%xUn;imXu>+mXF7`<-$3D)hq;Nk0n2gG6% z;Z%CV(eT=A@Pk*yF1mKmbcOGe!bVTN26QMe8pgwnw`F&^mwMms_n-RA$2@-5=)Zq^ z>)ln@aKC(Gm)7bX4e~uB8ytMKKPei&!u*F1taGx#y|4CQ&!>V1UadRDCvL6My9@q| zEB&Ney%Lt1y*@ar;FV(W%38gu%7&TicLl@uG`0kN@|{~u|LTqjhuGv5MLan8A@3nN zT$Iwm{RIsyr-QHZak*=Mb)~~X)AIEM?|4=0!c!L{yTau8LHv)r8V$PcP$V9{a^3s< z;I7}(>6UEp&fg0=oedt~DU;dljlQ?V*SO=^+SYsHhAW;Qob?*Hk7k3bUSoEM3}3+{T2$>{#w+SVT%H+u78adcP8j?w*h( z-xKy{-`+5L@~O4@bXeEByMreU>eEC=ZR_24!yk4BcMa-7TAPy02iD(aDhkVR~yWua7mH zdd#hr?E;Payzp%o2){TD`@B_PkSWc%eogePlCJnZo= zzt;$N&|&elu>6Imu1Ky1e|L|n=6m#`!S{{T@cP2@+a#BF8V`@uH9P0BQ+)kJHm%o> zQ^T(-Yui;#NN#Lbl^F6YSbI@$$&g3hnmWSXgms*J_p&MP>WhLq!~1O(|JUz#=w{O9 zaDP`@&-NRFF|p2`;32WboHAXiY&fOMI*gjd%p1LX8Tu_%Z74RVs_>0c%SGN4*?(_T zZLKG`?|t4s42U%axBP(_uwfhahF?{-y?AG9AGkV*-EE^S32ZI!qp#jt;N6>Yt-m<9 z^FL!3HtY{)^Mh})MHWP>vTm){+n)PN3;gIoxmI7i{Stg?_*LMs?IPh9l*=cJoPDxL z_MTYuQPtpo-xND*cSHC+nx@`u0BzEmz3(0aVEA%${;-&ux4(`5rFEJRkGy2N#ob3- zY`!@7|8$*yKwH(>`1uhiFS%N@sFbFZwiFqSii)+Xc{fzvt;48wGG#PwsB~h@TveQ1 z8!c5-q->(aK9$CainG$FRhjE*HoJ;jSMzS2V_S#pyXsK8HuFVglhU|;KhM24N8R1Fhmp zS#t;FR&u2|a^(#pP=KP@ARf8kv+1*=s15XpX37fNw6ZBDKPH$On7uW=3~MyGHEeg_Zn#n=)LboQRc{#9mO^jLNMX2M*I4tib>D1%y{u8j_0Sf2p$|5O(d4pgwzxU<&JN-kt(V+Z zZm=L1|!L4`Ncg910^`Sd^%*#o8!g3AMxbK8Z9o%_cNd9 zz*BXVOb}V-(yQ$33 z`yOJ9rHIi_`1n;aM0lp-8{@L@Vq@-f4-k*lm|j_8Hm0m7FeV?|%WWcLs^&BU_O+8#t&x!E4SXqsTI)L^yp5K4Is+PX{6tZqnD)*^`#u6%OwsM}FVnacz1 z)RzmV2XmOn@HNQJ9HVrG#yf`UII06Ge(vYxa2xZMj;qbKKP`e%$JO?jJ%*?4YAJk7 z?_B3F@w-~r;MB|2i4kj~_YvN6wd^I_xr^{lwf_0Va`Zm#UIo|K-~C{Mmyd*GpKq_3SS*oVf3^y6mBXgl}#yhfRT>UG`* zuKA5pqgVVaZ08lZ&*k>fm^kOxXkK`x0Fl5u*K+2PKmk);gu

*~-|c`cdv zw#OhsjY&2&ol$s03hwwkRh7iGQ3R1!`v-A5Uaiz+%Bn|>|KV{gQ_kOLbUAMw{JlK& zedh@oc`Jln4_2@%tR0ac2Hh(p_Xif!9g*xPtYU@KD`U56Ui@}r2Tl3nBTIC9}ZDvO-Hybgf8CAAf*Lh}mJ1nz$h23ubKm>+>GaE6Q zhaoLA-TBZ6LWKL|rU#uf$_CVlNP#V)cN{GbpUu6v9jBg^v8jg<#oy^PGFGpUHJum^ zrZDXFFnC#p8`YV@a16uBO~V_`v$V0ilqDSUuz>>wNFhCvJyyH?0bV8$@{Wva8t z``^?p>XXY!-Hq^rNnFb>03TT)hp;i<^{uJ-^boFG4<zOa`*0T|*;JWklbbT<265*l$!NU&HZR7l^%&pJiC8w}yoJZj)3oKu z2VFckaD9^WWq4$SFrup$q+2l(PYnp!@x9o;34Py>5VvzCi{l?<-haL9%{Jy|;oN?`wJ{jN9ll-)A99waH_Goe zk?a^~^-5U@%IIBbO&=nvveHgg=4rZXIX63SK4XMm4k2jN`R#ScZ{7Afq+*jZ=d9IW zjeYV^F@jnvd~(WFCI)Zu>l~Ils^8quD)L^y${g9rJx665;cb4aNIP%`aif>H-_PTK zUmJ6ahJgo@B3H#R_?TbVHRD!tAx-Jq(k?`p#+7zm<%i{cJ27#Z&{nvS#I=8_jU0Fj zZpWMD8RGe?v-s2qv<{lwn;UIzw(>{IwUsZZ@!gmxsL{Ersj(EiItABk`AjZ*H*;64 zP14iwAmOz)O76qXQolDTT;m%iT>0d3Rz3!=P9bmn&s46((QC__qsqF^eL7s_WY?n6 zaHCbo0o<#wsxfHG(8aL2yWsvLu2$XfCU^^O$I&vokcXi=lG3Kq%{Dg+`IR!cp_@Vu ze`jhTd%i^5Pr++b@DdFBO)f*-6mox(o`#1A@BfYzKIfdj4reGyL~|Imd2%^BzD(Jr zkawlvn#X?ZsJvOukDfYtH}Cw7j!S+oc|Fb?89w05DQd*TE<`66wx%`!4}VAJ?4^bK zQ-p^JAN-E)IPkFOJF@qPbKa@OQf3G@C6;6*wtA6Oo~NVti>0z9=sfML7@(NI_(-V< zXvTo!=0pRUm=2T6ghsadX6b&O?l}w#+$=SZ(65_s=3aCYb9whyXv_#G+yQic&zLO- z9&zT(AHnS8JZdrJBYgnA8n@%J1>*dnbHTK-TgLUB5t+5-xS6u-hpGxmR&7;PxT*S& z5?O1iHcwLBg=*mlWU{Jernv^yW^1|{#2ssv+()_Z1#V5ucqOtv!j+pPH@8GfZh`sG zG5;cZ?02n_@ZhfduJmCfGxA+Z;%mC90WQ8xCV+*$+oq->qDr^Pk{%x2Xn1myGiW=t zNnBH30{5b)dyQ(ti_AVPzgOnTt3B*nj@)KHmqIXhn`W~#qhPgMpw~(c_v>}>T6yp> zR*!>gc}!Ysd@j57Vs0P-YyK3n+=Y*m^4>sV$}|O0!h->+Cp^7Jo`0G(g!>W`b%Qdt z2CSJ}z+#6~EF=$X<<=De5zM2ec|~Jp@Ko!@r3^FyS@Q&Hn=R{J3+)8WY$HKcBtl!Q zt_8JnI|$!yie~lVG$SjSj%zEz+Rhx`oWt|t)$G2tgn05crb1RSX1kWL9!X)d628Z> z>BTuBcg2mqTx1#D^rSOq<^WU+XY!r2AH{uE79uz!0a@}Sxnh%53&V98<2q#p zs>!)MvFT~9e1xas%{EVN)*W!i?J}WJlt}tEq8J7h-!3&jqFPFBx1RO7ziP5>Si0L1 z3xLXQmqVb!N>Y++IZSv3>QAAv%u+Efr{&!)Yd{&xY|B22?NwHHyFGt_HQp|TTVci> z)`TDiE51Wk!qUBRLWqQVYuQ4&Lw2edSKX*63c?!iNGumE;eL}#J>Z$SF=OvFoo4J2oMTq(%{WKn zv0r$~XR-4%ZJo4-bl->I9x~|o_+)uG#M?%oGtyRL?)>~t@4|mUc*^A}E9mpmZ zO_1>I>m_$PZ8o&t8c?IA&Qw{4k4CxP+~&w~;||L6KX%S2sy6XdaUZ;ss4+dOBURLd zx2`u=M)R_8w^*jmw;C;uF8BbV zJU2fzjC)s-j23V$JPhx_?bvpLT=W7h!+oczl;!>gqnfOLiQ7{(&XPOLK3e3*z3k4! zsgK6j3a`6UANtSB3gK?DR0nW2-l?PNygXHHMODQeFXr()Ss#myzGpbH^1n$*s78Jk zt^i4Rk*eF8A|5~C+wYVi!ZUVRhO@)419wV!KWz9;Yq!a0FxeWL=`oRMKG?xK$K~~7 zynBFq#7<27rlSc9!bk6v+#h3W44ZnsCu*^J*tN!8i969+?(VB;`0xVUYD;%Flvmq) za^0xg2QNUr&6aOKUgK_tx822*;tpf>rkB`u+j^I7S880I1)Jw-@L36!C`PTU(`k2eZSigikI9ZGUQ_H=dqf zIdzzvJI&ol;oWVeX<98FLp^$iC4eXAZaIXx4C8L=#7hKLU<*teo1~iUTA`}a{?pH- zv;DAwyJbk3>uw#<%BKy$mSI63b7n{J)ZH!hJ869_cTX)z_qXVPcS|?nnay@0vjads z=~CDfhY?`I-Lm9mpf3(x*U{-n6EK57?VMSDm`|?W&G6oevkqBvTPlPHnZhtdZiQz@ z&2Xs)eX8zhimPYW;w15UD=iA(ZY2Z76tgzT_+CyIyyI@Gn}%@*&6u+Xac(9up7LbH za7U~J<(CjXeQUJx_ed8G9AV_aJQ8IoPyXDw`Htk zaZ6Hx8C*?UKG;ACTg~uYmaPt);k#wRRx{6j4V!9G^9rU2<54n?Pj4`j+N~^dx9sNX z%)4jYd^^N(okKo)#d%s`2Vio#OGtMF#WvoD*+rpu$@&52942m z_ouMX3Liw~9z8^7$|qKW#y9{UNufIoKX8xK{DNeU++&tXk^9?>M=4~h;n92Sopn=2 zhEy+hkL=y;oOiqjmUpkcsjx^Uc00?9#$a`@dX8hY0mRTa><^ zre+rWmzH?rcW9_`<{n0!(N`Jr0&Oz!s`K>pUW@JGc}4aJGQl=Isl`j*$>a z_rW&l8z9}T`^=k6b_dLZTiL4nWKEtiZ_Y5R^S-G`9)oYb&l+m7T{o$awEuzmG|o1- z9uv!pBGiJinev_gPM3X8vqv3!jjiN;_et(AY1Vte`V2cCaRYI(QKldHKJ9wk+Wzh%r__+

wgx^q#wArJh91x+ug zc%yw}p!7((b!1@s>&_e_AM8cTkpUjQ+F6_(xDEY{a_Du^;@)UKw}Iha5@CA26pb>C zkhH{49viEv6?k&Gi^+1j8B)ml$vpPUsW^%Loakg10_u&l0lla|_ z(?30C>?m@4kFq8x*|rNF+$in;OSuIJ*O5Te8h_sABYbNLy=HjtMsw3XPi<^R#(cQ` z^1sq0(CBnY1qaHEYT8R379G!lW8c?7VjEv+z-i4SZ3fMyF~=N6(Pby zo22j!_L#yc^rM9DuuDec$-jfyV+uJpd^;tHos1pW(-YPK*zhJfq-=1Lc^jBE2#am9 zhoKmrF#>*%K$L=E0<_4x&J>u^+8b@2T+jjdIFVo@vqHvY?Ob+VD+Vd*HjyQR&Z3zC z8Bcg!TPxntLjRUC|3u$#<79W|&-QVatXlkDS^p>JjOkHqr=cB6M`OmQ{B4kRR$#N_ z{(;gQ+nhK&sM%q3M>b21h95`~?pn|7W3%3?N;CFsHrKCn{ID>x1?X#6iXZA}wYY5C zz^-Zt&khv+=sbN^_W@L?m`X810H=OfJ@1o8hO>9#-!iNy)!gNVG#dgy_b7mmxcS1B;~W1-mt9|TS|?3fF)_Tw?!h5E`?pBpeyVa1IO`T(posxXg0d1gf7cJE zMiwS~5BwkzJMN6iwgT#Z-+t=96+oMwcXJCF0D+fKVZrsiKtw+`X zGaQd;R#|Vt@*f*Fi+;KTPu^qW<`={q7ax|Rf2I*c9+P=PjDeMpCsv%c&M_2}Cl49M zJq$RH%Nq0+H$9O!7^$9@@Bq9Rw>E@$7j1;M!Zn8yD&X+#=n&_Xt9uhoX#49$w62$h zasdZGD&BPF)C?e{BPs?f^pzBiXap(8lT#BOvw3pD^Y5ig_L{qs^F6o=(A9d@M8?l? z*TUWKF4B1TYMx*mAoh&SPs*V;DeaOUjmt%+8goyLAQpM*)7`{k-O5%|jqu(d*+-O) z9+c(7tZ?_J)*p?z(>!fd!Bf=7az;MfIZv7M=d2FgUU~li(JcFME`7?nJq+XaJS8=M zp-Q>xS;{i^eN+k&SJ>%}AC?_Z6L51-cp)Ps`BZV%yXoTF>@2>-vw{0sU!t_e zQ2QUaKLytkX*IcZLLr3Pn`BdE225_stc&8VPLk1h9UT^*+_IFr;GPunl_|L9HiCVX z_o~gKBa^3!`g~EQ_c;GcA1@k(bxBq=rCnI9>(i%sy!wSZ(kJC_F;eeCwwUnAoi0ZB z{yterc*Z`i9PXXw{XTuCk8Pf&R;gf4r^Y4W>Zj+tFS<;xKr^z)4Z-DpU zcD(vlx`ac{;%Q;%K61CP;JA6&xcAsO%{Dq|VB2KP2-!EG4%t57u5Gdxn88&yA?Ac& zk)-&{)(KZdYZuP+=(5LDG$&x52e@-?lRlf7TN53y2$cwPriJV!@ymaeh41oOg&WYK zso(NfS^lo`w3=o>a?w^k$SnKS#Ac<%=7sx^ufna>9B(#_@YayL@h;7=;2G=8iiR&c z-fC98gfD$YPJEA)w>~RN^g8yOT*I}d^Z7)3X7y}jzL0`@;Rlkq7E>d9^=@nU?7;2c zEfX5Yj^}0GL9WI9`a%t-Y5V17y?S4gZoM}CM0Rt%re(*}GU)1JiVCl=^QuFxrY!{D z46m|z{Bh<0d{>ekP1~@^rRML>(wwrNT8|aoOX8Y{D17**Qh$iDtbSSUSy{^+Pv8T+>xJ6U8Z)y_gUg0bs~NkOT#~t3-nt2b6LsNi2dBE1;=$m zEUR?$e*0nO298&zR$8Obvf))$37I!&t+W8#4X?I%-lcZK?1I<5VosZ~!?>GXk@9q7 z{>3;OQ<#t0yx2CQa~w6FznM0dB(LS;Ho0_1$xQ|AQ(qblz&yL7)3D6e-S!aR2e$5(Ar)-fEgA1~-M(AO^*Xj&zN**CS7nV}Tg@v^ zd%D>gl=Y)bGg@(uy()$Ohy4)l;sJHj9|mOa`>+_yKOifWb(mqisJ?~9G9WvZjo5NQ znBz6c9feiBCTHn&)oW6(*Ur~WTUnkU(`z~5L)IvbI1gIR4xGhuwbFi^>@cfy80Tiw zneBLl)c(?ZCp+7X+u)m~A7FOruk>w`3>m>}D)!eG2c8OtGnX9aGLNS_9%q#NoBeS0#ox-&e>oQvIz|$6syT`v z$V*I1J|-o_BT_i-EI+m636zo5@c8(rcjYj$5qL9h$Fbk2(YZx_g!A5+YPc0{yrT!_ z=>xdk@2K(93nR!*HmvS3!uP+UN1=JcWSlolMiBCAEc1UO+afI0wks`u*QS{^Jpj${ zy(@>tNqy71)^1Lumjt~hOOC)i@0r{Avt3Ve+~~cjiL8WI%1smWSs%`2@99Y~-HQ3e zgmXroYPB7-_aI-5q)Ra9EL$`PZTS1tn|2i51fSfNG;@w0(OUm*9jJ2SZuz@(PtdY= z97=52mB^|M<>szux*cOtFIt_46Ju1%Vfg05Qht=2b{w`^yYUn;@GVBqeZ(x;mB2#al-GGZTS?(z>C^BXgipS0YnlRt?>j7q z2+!Dm*qUKRV8e%H$tUO>NMX}>nq?4aCVXZrg-tKv`SL)9F+aN*rz>hcuD>LRyEvLS zxzxh%hZm&a5qMq_*Cda?bE4LBAES>7L#7z6O+UW6E`b|SYj@v^n>6hFH|0kB)(h=H zU_n%Jj{%9qf>9ur>lLN}b(1D94AfjwC~1y+f5lqzQ6?#oV@@NzSu;6Dwg;S!MP1t{ zOj1&2rzAdU3Bfzy$<1s4-e%=uP84@*3K>U;#z8vt3G_pqMovag^r3EpS#DI{+bDYI zfRR(UAH4!Q&iE!%7kc}#txt}^xW}S;`z}pykP{4JMs^I;@K0F@GPa{WpgDW_HFB0| z6qvT$kU^xX|6zx|Ylm`Ux2CSG&k)5wtUF2wcmDfQm_gF=ct-GNy=B5y^Bo)B)XaXC zy_omyN4j1-f%j#n%5Hw&ewzZ;`@ZC6!m9pHUp;4!7shvP>S2Z9|C^dc_jB~8|C4SF z4~oXpBPZhjW`Fr0cKd``>~n$q3!pQkKrp)3!cRyjY{ zm@%yuXA9iCQ60#ls<(b9hqB1rfSn3$-SO>>Fw(;xN_nMg1U`vw|ux&Cb^87{{!#%54<-8*SNwamvX}>J$sDA zRl&4G;)~1};V$A&E~)$-w5^Zr4&uR+|FQI8#K=QfE6eeRm+gI)QG-rLFfYz9I(%%s zNH>g%8&NG7;`{U?8DsFJADiFindADYx~JY*E8z{qZJuQD;c5C<_8v#=_z|Am$TWjN z!W%!9+~bW>XCvV~Fvr@Ra^CUAg0lw!lXIqSV<-3R6oyLRdo;(orQ*f2iw}2kC^ZXb z_+xtq$-=qQX+JySvQgl6vJK4Os@pG%JTI%#)W~b$C?+IIbK!^g^T9CNhI#lSY_ak@ z?2;Bv2XKTjOgH&hPXm;$%O9WGY`lakFUDs4rv&8O#lt3V{Rz}rm89a^zSG<{a~XA|IV#EHHwA#R@Wik}e1KI`hp__k$P+ogx>UNTrV! z967dBmjyq0Np3mOSdfuZDBT)RTzJHqTHpMVyiS1AN5T6YNM8Pu996LS=(zb`AC7On zBnxMtTJni}b%s$|v-Ok22SHjSC9g2IOu;?ywj{14QVU=Gi8@ckQ-%@@OW!Qgg{MfDxifn1WEI)}7;;RUE5|9zfkUqUOX386S?R3Zl*UXsX zi1od;;a{-I$da0q3GB_1oAo+2O}h13{a>=1YvE?+ktxaR+D$P#CF2z2JjY2n*TTx< zj>KDNar^;G47sJp$x6bVX~!Soe^E%~{1;@)DaL}#+UcaCmX+&)Q;eL8_Dw%BrQvtI z$_@g&k;0*Lim!|}aCqfON2YYp0eHnpM`ZaVx=IaELq`soo{zU7=dCjx9rAv^*PAmsd$ zKCgR?S@OxUW+vs-mO|J|c<^M|NqA;RmGpRE5V-YZ$t|Ri2|TONI6ZTRMtdEBu3s{B zIa%5XbdF$=&diJ7&&kV$lrb{Ym7)Wo+7!kuv-T-RinVxQ>0#DE6_}#=U0p; zr%2xhWB&1kchaMyYI4D|^5!g>l(#@KTt?|x{dDBXja3`*AiBzvNBt-~R3P=}oqcd- zVtJa4e-BF!criA#@yAy;)o@24BTlV;rQK!Z%o;;#a;#b#tw_OT!#6p{8N!o>%B&;2 z7m9ma1MWt>VK(a88$Ou^I}^*URyr+=Gn4$4$XAmZ23^H-XbY1rmg#m5)-KP7De7y zB=v-6HWnR`qfgSDJrOFjNct3R1)BHw4q#7_OaPrhEUnfuE_+%Q&ZX)`=Frde3s=Vf zLW^b1T;lZ=%j0v6(+hobr{2#3$TiKCL&#+|%(d&UVjiul3F+i&89`d5bSNn@e#6}Z zp~+d-vMzyl&Xot}(KCAxe);=kB>>z`Jo8wQ?vnFMj2T&BP}p=94dUGKS?Y>)GhaRpQExH zKPMOHwW?fJevTH?zfijIXKr0+4g7gAgo6vMJF4T}9(#e$2cR59y?L@{g8Ug{>A}tb5_%g|ZX1%mJdeZe74#3nh1< z)~gMtMNLV%)V<7K{zNCS6PxY9)4NdmkS^R$%94k)0O9)=%Atkiw7@NeZmbqiEDNvU zMS>WC1(JS-F@IVKV>`tthqrKF_Ts6aOtocbU1~=&TM68Q&@8`mZe0hS288l#q4=V> z7hVT1uzCC)i*O3AjiuJ+UfhneANg!iT;%vOlgboT>w>RxOZ#c$rGw-+A7#qo2O6g( zMq8;SZEh}F?+wb)(~Q&7N8}f0>FtQH=xGe2-)5kQ;Tgd|a;Ec#IJ|qBEV+rhqX&1v z>C$&PoxnK#$dtuqfbdFqa{K6lSDbEDaGn}*Bcz#kT(!koWb$sMqiDnuODH-`PR!)8 z@(i6SqN(|!UOruOdfsFzO0qP(mhj0{qWS^Cy{F3|!ku2idti>W-7>3!C1e;dIlbzR zqOc={A;&OH&(24-8&BwT>8_v}6ly8X2>`dEIl1;V30)SqZcbr5J*P|gnP~Q)dH6?Y z8h=r9iD^;I5;zuRVG|wMi>LQ=*%{X~ho+zfbI-C9V%`9wrkd0%97dh#+idAM%g8w^ z=ZwTiG{d$3j}n0wGE_fq6xdcNNx29>heHeQAM#?0H zXW6;3vXYy3VDZ#gs}HcGT`Y&H48H4(yElbQE4*v54y^NvLb&&(kQspQS}bRsLm7-M zmU^z4IiEjbeN@`>7TNo}^l4zz=j9E(dX~rpSH3uT#QYy5M_-pLTx85Hi~*9fH->@O z61ip(irdeVcD?3(L0-^n?-yl=Yv#W5X=MiUmhjv3)${o?HDJY$D0Oq8@HckpexwV9 z`K34m7bM<{w7W&n>x6r9sP0oX%B$xZ3ucWyIkn!qFc5pvUI~Qpj6Nyli^)r64U6$i zv?m^v<%_v%c`rV4jB`n8j+q-}1E41D(!?szI`xfU;gYGm8Gay%YeVUP@4G}Mi1FG; zQn=cS5FSp!N8q6pJO&TKlM6ln9g~~wXnGi-PK08bn}0qaFMgi2i*K0>eV$Tox{RBT zZXAVC*>jncFQHzlFPE?CbzhyV(W~q0dgYarcbP7JUG^#)HLpdIcOJ9-)%8b?`Hs`l z>y-KD8RyIzemt=+mXJBed)%@fXZog3W;;>KNP9xM&!h0&*Bv?5e-aYUbjs_f7xt%6 z523#OaVhjL7)DZrM+x8axYQG#IZia%ho*;t<7y?g4uQjo@iSNLz>wV)5C@h#EuaydE8952qF?fvb=?qIyjs+4)7%)D(w7p#K5M ztpctFnlFDuf&C9iy~5Er^hCMCJt%#^!qx{9o4uwwKzQ?mIwJ9eCPjFd@Zf_|em>#* zQ-sF|-}4~W37L#$gy}h?G|Y%fy_(k+fQge$zQE z|3d~jl4I_Wd+-c)OW&8sB35L>_o(jCFAMmI&++!Na_TpT;MRuy57rlk7dKLwNc&6;G^}`#JxE5ms9w73i7-_|b zxy|JoW9t}U6_`Aou7r1}&^`1^AD%9Rl85MKi<`;G3aZCSZa>b>Ez*7+?X~JFwAURe zk~4BbY=BHgMvYHOASfF&t3^KI_Z z#<*v_eT=BsYvdROhTu&sd(_@EiQvh5RF+&qNmT;Pk3qIvLV9@3p!#(*I-3+zIOZ?@+jHM#YHQxBf} z$D|L<+QpA0u0yo+0)$t}H7bs*}NGcVVH4QJUC){P=7 zf~Q(;y4;vwHimQHiNu1eBrB?_++6IQhe18&R8;+MZYI5n(pu|2lgr+(lBPT+yUW=e zUlao7C(Vd8GXroJJUL^-@Pa3$=5mZwV#HjGyN@v|KzMRRYx>lPax;A=td*B9H%^<` z@uNgRO>>m%+p6YDGs8er!rkE&4S7u*BBD0fMUt*3lyV9NL|co|e-$ zwfw5#jy}qb6z4^WBMl*KmX4#hO*-d4t;?31MJ1gZ#xtHGl0kTJib$ex7m>Vq8z0lc zT@a7s%6J?-SCW2LpY&Zxd6Xe)4&NP_swWc)-F70ghk<2%Qd0-4RLE*J+wDkC8}5^C zg`+@yT9Oq2y5#Dsm<;sdERebCjF|K-ADg=)IP>Kf-_-rGuhXgWx7nK$H{5EyD3ImJ zO6MTVT$MO*1KqF@e?Ts4KsjJKO*>sUn=L!V_1I~S+j+Cuwi88y|Izx?PJTA&HSK)S ztxgmsw`_G+!}r5=hNCs9yLMVJ!!rMZ!6C=(x!p&rS`4&06oJVhw6bfM!MnY2V zBi2|vDNLTy@}H443iF?_2KjS+z=~%Qd!r_++2(n;wIt&2#CE{TP(C`$JP~&ZZXHDC z3|j$HHloJh#R!=jov#0)bvz^OSCIsT+Op^Pfuv`OW-HvV&1Z%18#RxfIbMr|^ z6p#BEss9ERHC^Uf#*=HpzBn|Wd369QkL}CQEk0&pRGJCf~OA8dDk2_pE0D?tif#Kcm`rx;x$Z51DGhblM>&8^Ag_rjO-+w zFMVjGXLo=)pOFbrW)}vvnzDw0Jyy~j)6>&7!_E44;|WrI*P_4Gs^$QwhsskFv`mIg z6)A7TWRI#2Q1b@&sX>wkbRHmSEhNqH`byc>Xq+~y?AgRVYnCwzCC}R0Av|@@@_$)q z`w=#^&s`}Otw6g!g?7ma>1o^1e)D-g`{2bhh|uI)sP@H1n-}BO8jBZG06zSz93r+% z^yG#coS&OE2#n#;srS`ZK4~52=`kl$oo1&y@n4Ho+jtt z%-zTQJ0G>9IWYf+XU281wuv3Uy6x=C=nO9XI@#7_%)ZF`eBvgA=Dj&TJ=mU+2e-?e*V7^!(5ui?f3iYe zyq=ATh8JXrfXs#$=%Ht_zfruB9lOC7j~vrKXms4aLe5@koR+clr*h3o^b2+}V|EZw zvqCnmq!=oHe&krM?sS~7LS6;bY~7XEK{Ul(CsWn0P30kYLlV~%55RrACgU;YO^f30 zc+K9hQ$r<0P@;RWfkxSI0~_$m2sP&|{!`M^s$Y|#8luDeH^1*csH(s3H*JP)kR^r9lzUHM}lGA^706yd#8(%%*r2LqJNV z@J68KTUXXqF<@&_3e|Fcp~W?|@nK$jp&IE#egL=Q#jEYbst@UsU&>xJUGht7^^qL{ zR{c^6zXPlSnmZdYpojjZaj4z+j${5TMgW91kf>}Ao;u!7`VN!ov0us%7HSLVY?Egb zY9NGM9(;1~Dj!I}HSs>1dvQA!HCXF5|0=_nRx5FnFp1LFOFmF)Zgpm=otk1t(vl)gFPA-v3_J+>KUYW$zXfM1ZA}6k9$zAdrS;FDZM`UAg}oqFy3 zy}Yeg*B^9WpEn}^AZO{d@sCok*XBR!p}l$2!|1O1BgawnMtA9z^5XZnpKX7W`GDTf zR$VE7`<`*yx{<#mHh)b`cma(Au3bpWKR%@ygpa3?kJ>z0-cd^G|KC*muFp8p5kY+4 ztN&)SES3TQw;tYZ!P;St?wo_A+5dUQ|VFfT1}!Th-Xy_p?-M7 zySin~N7Zq+y(={VBJM?YzozKAugTf~t61;fr^etdqtpCdcB(?vA*LFdQs>v?FbWy{ zhvdZDxxG}pFBjZS#cusTR&p)e^}*CRpXYOo#2-i>;hAF}SRFpQ1DM9!DhfM3WI22# zd%9J3klTYFCf17Pb`0sV3410I#Ip;bHcilNm&?XGNKgT9q};(6vG}8@ZKI<+JuP%3 zv1OY*0KWAIlP^7e8o^_HBumzjo8U)sjb6uib3}co050QOcWBa80aXbFU`yoQthFkn3*dKs&IKTzP{?_mdQJ z5)#9+Z$ehy%_L;m(Znb#F&8FWd7e%}9`;U}gfyQ?^N-n6sUV(UOmgp`wFhH~mvk)xj6DhoxGS2zL zniegJ0b|5iWgGi+T68vdm`|pbiW^?cdkh#cT!d@6Iv%NsPlxVh5GV#ut`bdWm#M~( zr@P5v)3%hi(WuH0PM+MvtT0rt z7Q)j)_U|M63eA2M0|wAcPH+A>Cbu5zdGIuUB7LgajHY=4s{`1QloritudS&wplK02 ztL+5vk7a7cp4PY)X^6D9+o>_1ANqlTPh<#~vHcUt*uZUlBqC zqVR*f1cF{>@xLkUM<{L2xr_?`)_ZrUbMe2qYw6A7PhaBLEsMZ|X%psbbX^#!Xxca0L}SO<>hs%8EUj0Nk4GbXHm?|8XdKjKvU zh~tNu{FmBI@$Y?V`W;JX+nEyy+ZM`Q@a7b}65g1^HJM&`EnMApT=J`?<4(R9zAQ;z z?RUVdQt)1QMG{w=VR&(-l;2NA3mg;226PYNCl|`{`ze;tvd&;?4&c6AnE+<&&y{(doPJL;CaiD%86K*`$-k)?r*rms{e#9F^8*kg=u{m~Gtlz9 zmH#5`G!~>gk`8`EN4E% z&VK$E81M6}zMSR3WAoa{Jn$Lsvbk>hW`#}uRu?8ma2^zOW*c8*zLO_wHc}-qOq(Z| ze89yg$X;MZ)d?EN_Y`1DPmsbcZVAgyn6Unk`*UAR-y}ThYv^K)*>Qrb)X+Wg(7$}a z3f-=ujuT}kp_yeTlK%Ut_h1!0=S0bUNGBa9P9zNXT0O&ruRc*~2+t(kJd~Cf0X zeA4*m|K@|n_wjjw@IySAZj-qWlebn1b(fsE8D|LRpxmT%5a&TzzuB0vD2j6g6Sc&l zJ^ylho$8>a6f?BAEZ(4R#%MZR@RAwQzKN_A5N<~Ozn;&c&Y9MXNW~1A?5O4oPty#^ z6$&pfLkc$;^A<&6o#<-U(l~YMsBXuF+|uBa(_+R6-$R_($UKN)J&>2DMuy`F`0;sm z0%F3m|1sj*jI2AKo~9>$q8O;kmwI4LZT{4V-3&R);FBZP1XaU3;K_yHgLmfhCuS5v zE8%7#JiTOcA@m~>B!06HhVcyMOU=U+!ohsA5H4~54}CdBTB_mWDbnJDSDuuZ79Fme z;fqg_HIKy)jPwG62xQ116WfTa0;^Mseq#k|?7#9bZn(T`9P>mP(6T(-uY|<|;F3Pq(o76(KaI5WAY1g^T1>%w*Kfl0%Qs>RV?`$VFf0JE;*=dS=Oz9|FTb z^BijsxP6wby7nB|_(N3FX3I{b4EO8_^K)K~3(rZH(JUi>)1!=4OK0=1V62@N7s--G zu~l0Xw^c*o71_2Pt(1+Aa^K;bQ$4&c(tJ^R+Q1w;B|$s~=16W2r5KwtaV((eKBbab z7?CgKb*@K@d3h?-Jl9UZU(dD@VD4#Fdnt^$R$t2UH0DV; zy&$uA-h?=BqyUVI*GbnzkFI3Vea{sU{)BGLYAul=kWpD;YqXyEnMRH=fJhZV zwN$D2hB3742};yoBK1#@n2r*;Q?Ca~q>pQ6!2)~0>bR8DEszNf^e*_Ub7zeZuw6cQ z%9t@dfOF4+3F`&#^DFcP@43@MKu77su?}rub1LMCUP`#3RQC3g?$!L=7U>QxOHcEc zO5u~BCPj0k;YlOsJRf?=9XkIqDg{1yxuWgUvSCMl?ip6(!x-Kgk9@`%^7|)=+;J*j z^CxevQzxwD^)M#$cu(v{V8wQ>7c0nTDY5UVkwF97~a=F1T^()HJCP z2i&iDfAcgeO+H{1&@7OjoFVk=)S^~>{fUn z4g*8FW@|oo6|7yvoEn)9R>&7pLHUxC=fx=PKU{&rcyAgy*G@?}z79PMk93E*&AjQ7KEd z8>LsLN`T=@oq!T}sswo8$qCS^s)gss)j!rM-_AHqfgIY-&7-VR3ZLh?tWs*8r=Xgx zf|}#LiYZl62GveAysOf#B0ruTrb6k=;S|Cl!uMN|ntzcph<~3MarrdIHyC0tWS-Ti z#8Z5ZH8{@k;mJQIv5qwAW_TV#=H5yWPtG}#`yvgY0C?U?oeTrZ&XIaxM)5hC!SZR< z-{ek?fEiCSo>h3v1CK#GO_=B>`<>^=60Wm$q=+}afhkZtUJstoInvipyy1Af9l*#r zG6BqRERuOY);CrbP0hg=a?2LkIdEM~!WKz8!kKkIJ&rQR4{S=I*$QurYliUn7D?et zX!?O>-ebVPB3TK{=wBoc>eX?s?9{90TzOls9p_5!Pq+@8D`#pZXucg61nyWOxj!ZEktK2#*TT)7 zsrBPnLF4ww%_`UX1?kpnTb1PgmC+ zL7XAW8O6yVt)H6Y?O!S5Sj+NXx zYWNE;8=9pv3`DZ#72rW6&C+q-K#|o*cO07SEdU&^kwXd{7fqNu%Ti?))2R4M|)L zx#8i9r5i&TgO|!~y;fW%hqz`gy^Q{I6RjbFP{U=iwN8tX;?b0+> zQR7KMn%NR~T?+1jFHPcVv=+Yja@jpV=678#hqz|$A`-KKM+gKic@4M^s2~5F9t1|P zWInmhJV7?TMuwZOm^e0Oj&*tRDj;L=*X0mu^F3crtPpb=eiL!R%_7^7Cujc>3&DE( zespV|Tnos^@k#qHNtMedFX*-TDjDLMx#uc6761NnZun-3{2Notbr3#!RU+4{M&Sog zUjBx2-Z{6>$&+NX_}uVF5?9@7c=#%L;a8fF1{va-x$Ihd=nNCM`C2L81MC2r&zL)a zE!SFI+wq;_C%yVNt+JUB969q@tq%{%dr>~C)0WrP8$TQuBz!A;a;w%9^}~Cwm6{We z<2|@vGpmc>`86qsYO*-}lkL8hQS@5r1{RJbSyl^v!i`25QYBX-<)Uw5cz`91*3!xG zs$u<2h`C)cLP#-U=EG#;yUf!XWzAl6bAWmZ?^GYqgYM+*Fs<(~G?fqFc1$hi|wm(^~=o*YR3V|i+}(MqwvXj z)%10x;93T5n|pCP{`p__D_#G~18d`3iB>c>V@SiTLwm08(UQK!Uy+gER^W#Fc(KzD z#53j2(FzaBFMh*ZB8anBKEOGxA7>A$<^%9yJmGIi&2M-BK6YJV8voFndTIY185vGWuqNI|`2G~8o8kNH(wG*+v&YKSylmV9xb+eIw5T0mp4q#DW=w!N zdV5Td^u0kgB0%&1wK{-%u9t~7Sn#-3PA$Aa!V6Z~H4wv-x01gt!-4@c=SSXkCfunI z3)=N(ZyIEKaT(@Xw0O_Uv`^^`BDxtmxszy_MNKaCgH%e0@GjN*ZASX0lR0bEgRP8$ z8>DZL-n-)l8A2*^sh@U#-Enh^!Y!EePc=Dca=G9S4A6t$mX%yHdu}8j`h^VddggsM z%1#Z8-6(H!Eo{4aYUcZqYrR?K{Smp=Tcn0-X5$R~3D_nb3N(U{^I{RH-C;4PoX^glRHlBywEk^45O8RAO-4Yy4k zOViP8&L?u$5Oa%))zUXa@ieTCPx|kncdwQSU`GC0nfE5w?Q5lmYi4w9yan7#ZLO7V zg@Zt=1pxQ0<=?-6d4YHf0OkZ_$uKYiG^diTHi{@9?F!Rw=f=ZoW04<-C*k~umUAmS z2cFz@f+m;TzfdBp2;Z)mo^@0n{pN8qC2-ntIn&0F7{&aC(~g^asp~!#40j~Xh17f{ zyfOv%!b_64mT@CI{|32pApF4XvX}ot%8KFk%4G*w z4wtmYo!MS>-l3~j4$!T$OFRfHUZ*Q_K1;K1!upunX`CPYD-W-lk+MpA1GDRO(vDO{ z+d6qcuMI6S#5HplN72le6v7DYX_4{+z&${-QyLv6T$2EO7Tg<$=F{yEaIi%R-$H#q z>gL9F44Ai`Khy#)UC%vSAJuxl&&aY~b^ciV**q{UO$z1^4h=M%(&j|CITE1b$*nHlpTiyU*@3|2HPD0xqa)pRhjf`PP{B z@c2oV)$!97W(&BVPQ77jO^4ye1}Pt59Lq@&9wU6bT~-pFS-gRQG#>{7JqT~sWSvAR zMvMjXd%vG(UB{dJPPT5~J8(PR`beDbkbc(>CXRXafXb^M$$5Z`#Sh3e?=TotY^1ko z!0jK&mUoPEGV(Ub8}CpLn>X`ESd?JTX8VXp=11~Pk6{fo8c*W`GzB|`fN8dAY&aQ%%K{bW( z4|(>Yy$qf_yo4<-3)!nX9=BSoRf|VQ<E71!hm84O>{TZslM7D8!|)wRTnn@oJ^&xU?U*$x z7yX?At?OnC)ekqgAL1_2E!}^o5EYuA$_fDe-Ev4_5NIy8BEV3$EI9-W0nIvaZDNJh zE$s?jTj+MoujlxIcoN2CO>HZ@1R*ny5FS3AQg|3m4^UsHnG*w6p_!che4#lbWKN}I-2q&-MJ5z31-||qM?{B#4Jpix!F^lgnkX%|g|C}%b#@`wrA74H zs2n?qI@uScPFN2NsZ>r-GXBA}Hz?&?GY5lqVvL8Ge+FfZ1}^Q9$GP&Qz!N^?6|iQ4 z4m>GugPezv2=2P%?V_LTKp&yjmb?!VS~(xy>{ITz6EzVH5ByYJkr2pWs! z7vy!?2+qoHv?f8O~4G3+A-vn{$GVS4ox|6>K*1=Pj%^ca%;@q`x~lsSI7_CE9D9Ek5X zQ=c8iIrx;6e~9KFn&yW#I)Dez9MH19|GhNxLmRU_KO`GZPwjoR@D@4$pVYe_XW(i6 z{R(TXPqX2o{VWXZd78h!0`36LTEX38)khTT;y!!GeDPg#$duqm94u()lRlO8_gNXq z?s$~8%x4vV>8s@VamumkHfL5A*w2R*#*kf&to31q9`5q|zay})a@*8-qMz`k+hju5^TsA36>a9^-#B$62Tv zp~T|Sq8lbWCy8sxjKLitDo$5Fu3pnfJ4P}wV!bfw2d2_&g{!7+t7eDr7$GS${;N2T z5-{>(IqN8cRNhNcf0U(c-7lnF{Y}4+7u4_AD{teU6@EQ&YeS>$e~Ks~cK7$;8AC|Z z=9u`4d{gi2`oB9_j;$26te>DCb;kIz#ppv195*Ao8XA4w+8Nvj&d86*P>d@7|LvW9 zd{ou7_lL>kg=9_$?=cx*fB+F9MvXDWs1f5W;!pzwjSwqhY$J|}5NpJ=iIUGP#oXQ? z(Z$u+rZ)G}T%6k2rb=U~h&ZMI1FEk47BtrERQ8rp@zR=bXXJB=>LrdFJy; z_FliW_S$Q&{l3pzZtt0>2lq6m0Kz4`lJR%kTSAWJC=>?t^~y#Civi75iSIwC2sFgH zr~Hb9hX3VkyM@iOA(fng8=mCOHu9d&3KSutvdXAfgfuk28M75tGEr2KOD zn|kE{{J2JxzLeyiH%Em!VC1|R-Q_hwFL=S5vSb*A4P)@#&$3H?Q?|m7+f5CdD~WOo zJOH@5i9{oZ0L`o!zA77Oy=lZ4xXyJx8#kw%)MGOI)0FcbFE`xIwl^Q&XwXT~6G=A*Hx^NVnu2$sA`~z#UwF9%oEW9E5lJj|?~Z z3TV$SS;!oe9plKZ{7|$a)3NZ&56J=e=lS7#Q64oWz^{@+@rL~(nr>*njEgrW#|Md4 z%GLUvC)acApUvom0O)!YY586I{v^Murn%MyxY@5%g$`MxY<>+y8Dd3tevzkDn!xME zurpxdk`YHa>fx&su=DJ@fJ5+G4)Jv?_$}~bn`zFkSXv(9>sSUeD@N!j9$y34EjuYp zViVCWaPu6m&?2lOh0ES{m>=&=2!ZAtmbETav>ay8TEpA?TU=aV;|0u9@iDN`io0eX=~sm|q(lBNI;tC(+fD<@doR3q`MGsU2;g)jW_0{ zc;B|KzD_$NkB&EHT;C7CWODYWc9s5?+8qP;gYS#MHT!z-_P6abn*c;0Mo5)*gEx9juDPKD&x|ODJ~>>Wak89 z@{Dexdyhr?O>+u@x5=v$jJZzNUit9^V_LjtuReKUrphB)KSnAac$Hj~W^mIl(Sc+1 zcitnrpcx{B{K#@@OHn-tSqE}|eN(QUcUI^Y0gKI^Ug4dwb zyd9thqB=%Ml{SG_j)4cju_&rnsM2omWkKn5^Fj3x@vfk(O{1_~WMp}u%LMl*xDU|0 zi0w8(yVG5DK;kAE^PE-h$-;@o{OkMQi_S*P3X|aA82FUm)A?d>H7f_a{XMg+b5;-! z#K@>lKX~&Pcs+PS46Ztx!E4@=9hVKHbM~H)9fWa? zk8R8S`$^vpOVnLDHgEkQ$CCZSPp0&LHS;zHhDdOf|Y=8RHmFi zvlX!A)6tdI1>XFrEKEnZ31M?3;qIojeJWcOYy{LVtIED~)&%XJ>cGMs7$@}st~oaZ zkgPa4x_Z08OUJ;2;KebxS$*JnC+%^-^MAPB6C{ z`jc{oFs?CVdnpLBH6+V30QV`Vw>ks>_lC|4_mkRn@2d`}dC2WeDE|X(^>aCZ==JTN zk1lL8{FX8B4)DepThD~Q*`$Y@#J|H+zq3_J_GJO)>th2Xx=Wltt$ z4WE+38af8$3}KvSFj8iOatCF(2QUn1PN+FOw8$^yNkAvxyXA%&?rsF@_(D#CT@?Ca zbcws*2V-!xq7S@RUY%jg%?}gpi4oC)O?e#`$KaYY2fPh4W?);^msU%ttpW6YIeMMe z1fC5ZyG{#$7lFsF)4IV+!DDZd3xZe2$g44f;0+jIF4H^*a0Z{ToQY*E=|k4WKZHa( zDR=8odCl+TqnWJP(!a9D&dYu;Kb>JrU8M!?CVA7D(LM}<*N=e@f>*`hYLoj7y4o4p zI!hPMF?`L(2ft(tyaK!^23LJG;JIhyB>J3#Lo&(B;NSXp`x&Q{F1g0b{5QyV0%62e z4bxopO=#_2BPnITF*MwpK*4|VlDy_ME=Z|K92)lM8)F`RNrp%lSLq(IuGp0KQcCxb z^_rC{Uy{|cjd__psY9b?kE}OYm81?y<`cY}*$2@vb+k|gc>B~LSy#yNxdEbos+^gP z;hWI7Pc3?=Qx?s^fL5fe+mil^O+8Ny&OxdHmD*%nwVn2n$s8kzH!04Z&sJ971C>~h zbR$X4O9KIjmZ_347YAsrx^_qm11g~hATzW6NTaot>IygVmXAX4eN$x*DKqxLAGygf zeQ)tks^+~Y(}R-uUIo>bxibfec8yVf_dz-jg~=jaFX_w@mIIR60R?fI_4=~_;6O~y zW^1%@wL&e{`>eFLsFFeCyVX6PzUa_*b$evfJR`}yeVPrwVZq*n!b2P&@Rh%LmzQH%_(ubmU zzG`~|a!KGLy{UNX7`T?H(8hgQrd2PPM=j!8V7N20Vzj6?Tt~Q!L-#h{ik1VhJ6)b! zKxb=4ICh}%!|wq1l2F|kx%H_YybFA!do|t+-jgoL**NEvW6`^*8eDLStS=;}{8RNVuKn zL{ZFhqO?Zti%RIVz$J?S>i~7<6Yu#GGq7ecH?dfw;O5DR9|8@>BEq_8Ozg5H7IA|@ z0`V%Ott0%S%p{qzHHRKgexv;9gI|ZY;Ky~4$b6BR2e1d>IxWrg=Q(`gMP>{7K+`8LggKFd_&&llj8;b@6*5M+p2vK+48e| zR96rsh4t2e28aT_a(FRz6abo|QxGuM);V%+8w6j5&?4?tn&tVxB%+37bx59tTic0p zh$5cMy#)1|((HBtz~Yg`fiAF%lc%ST^ZASy%g^ z5&j1sX}9L)F>%>(8My@(vQ%L<$@c@cBOE&|)`RzekE|GtH-q=_3~&KT!YDC!nIXWz zg|Zg#k^vGGA*i((Irh&v!BDbjboq~OAAf5m^t!ynYv`* zHyEDN5g%D=YGBynZ-k$sdA5MLhFj&SZ_qmG$V|J$4K@FlVFB()AF1z}Y+U1!iCp6W z@TxI#>jwARB}fQCR4$UWOYn^e>REo_$1L{wmZgFfNSarK8vr+{EsWtah$B5}p6LZg z+mg%egw~n+CnmTI?+5fRl4A9M+C9Xx(1&=u? zfgc2~);qFpdPZ(9)P2xmnud<|*F7V<0Nm*p4q0D@yXYB*G!(eK`85N~Ou3^+|0eLR z7+fnT03OJdj4L=7YK!5keIfX}V{lF9`jqJ`S2mN**?*BdsbSg0vR^~rC2~^3)=Om4 zm0WEZ$Q#`-PLRGo&sw1;xKFZR%ag4LI|uXS8N!TkL3ANB(<YJ$(i`D_^t+C{oX zy}ix&seE>oae=e^O35gq4BM}ir5g5KEgLl)Tq=)g*jg-|gc)_$MrWvs8$vX~Yvm05 zl;A%N4QJ~G?hl`qMOUM^_gk{|Y8Z|i>;d+Jr{&SBjd_Kc}- zZ8we1*Z)5>-<$ZJ8D1}17tPmV1>ondlZ;|x@x?jiLy=3JXWxT12!B}&uD*1iVjL;w z<7ep2y(L<&@_q2Vw@4@axQbg?%j(s$X29LINbjr&{=zu@{OCqg@xS0THr}gdF}U4l zzow}PJm=TZgI*pYIp8f=oMyfx_un+lsko=F{K*x(YHaDQLb>Fd#*CEeyM~6tIw~&z zH(B>hPCbh68SVd^zp_8R$25D+eB!w=GJ0SYA~!F1hvxQ&-SW{ljY~6{wv1NRjRKxg zxOf>|I8Y^P2{XE@qUE$PlbhjVBu-KoCP0JwgGv){+kv?m}ZReB$&Icw&wFp}nm0@1Uvdb)zN1K`_< zyYiZ3-3t1D(J!L~wN2-I#p0eXbF9GnvY!tPFVoI+aF@J60_Uby`3nr^vVWJ1Z(*&Q zTLd*MZTYNTE`3@T_9X^?0oxcSO3&k%d2fb6)z z7B<(xe!xuuIR<#%UJ9T#YR}N)BJHyQ_}nF-{^=&Fp3tM537W27<<I28 z*iRzY^v4_$=yiK%`NAyio{R4CnneY8_H*`Z+W?XKoSZ4aC%Fi#fa}qn)@{s1D~+U# z92<>TrY;{ORl#$zVWqJ+qY=JZtNh3<$Ay3AX!kkUvy$Srk(If6ZUF56RrG+NT`$YV z8?-nbjgq;Fu9w5e;!ShropihuN6#mv;lghtx$7U)n^bE5g0*zhC=7G0H^p{&i)YPl`t85`X zcT8wDHA!+Q9@(oYZ)G7^Qp(9+H~Q-kcTFc(&L*sLr7VZj;eLVE`W(WA>vxUO1epNQyWGs$r+|O*PZw~dvIUODQrISR?f&Du7&Y9o=TmRb7aGMVN|M{p) zE@Ln_+9ONKs42$*2EZEDk9B1XKCU;SJCo+qL2?gxi5h&(qw=gKFYJ}WWsDjAK5^bm z7ioWwE`k8w&2`d8v;aYu(-C-ImfwsmJ@3nA!qx5lqc>>9@!0%TbQ9DXDF+XLkGxyO zEI4}G&~p?SSK}J+xB_9qASEz+2eoKMJLc$bKDxpX1Wvb-xxw! z;FZVav9*{T{75?2QoQ1U(aM^T%Nr2qI_l@(82mo?`vznw{FKnAL&H98kxy)wE$i@K zQb?X$hyNN*$pKa1{`2SzniHK4uE8ajQ%ya8!)jf?hX7q)MhmO6T-=SHG#rgdxEC2693wrn*VH3RZXwfZGS!LW zD$jT)1IFk~^K87^R&uYsB~&HdU$92iTHW$PdF>Xe89!L>0$lS$dF4a5bvJ)28vI|f z>f|K?3B3@NU&@ki^ZM;43kF%r7S(}@aosLugkmOsjxe%MR zJ0*qyDY*Gy|BMu;qa6EvmYumPu~R*q1Kv2y$IM8W&P}uC<((QpB|f{=m{)she0Y?r zyAV*^YnNJGr>^b;KRt$g$i_8Cb#-J0b@9eAS8}v|?Ig{}H#)<^#VmduuHV(muJyRD zH7;zquciKL_f?@{nJaAFz|#y-?2_c$D2*dNY`tqW1n7>JwSWoUc#Mv-)?m%Iu?9;@ zl1>;YfuykYh)B&g`Rq0_OQRU-EZ5E3tOpBnH?Zo-8!t;XPzSj-S4WJ9E8VG1N5yzP zTt?=h@s=wS$^k>;<$!{@6EKtKZW9B5MG$6{_dztcW#JtLFMygrt8s_zYtj%wHyilCV0Way6Kx| z+F&-0oHQpAVQt-WW)Lr#5H_F7(h{w)8;2jfX@VT9U@+M|Nt|~O@^)8DUF>X`ENh|T z_D(i^&kdh<;Gd4kvgZyXKi)I-ti9noj43H)(54;!TFLwlcH~S8TVsBBB6&}fjo-nm zzG~yqv!sasv@x+@w@)u+;FPIVCP_@B# z!&h8$(}u0@%~jv4jw0|p9X7xDeOX;elPaD?8`H|j|Go@!1;D&dJ8z29(e4dL%@b;c z54^=Iot5~dc?^C7{06U_fgcB7hNd!n1Oby~%kn#Mj(c{rQnO#d52I|mTCuQ3cHPOA ztaMJapypmNm5wwgEbFGQ8)|?E#0aUjR`BLIGHD}ocwjEgS@+Fh!2Y?iaii8#mOKX2 z*)mV|E8R9Bm$+lZ7O7y3m?3%_z4IaAz?gP&Q*9_Iek-JVq;LE^ug{t+x0?(@+ z*K~%{7t7$#G`UYF{3M=z^3}Uscgt$OG1cihUpD%w%98V~VPQfqseI>$ ztv6XNeo$WXGx4^aFDL!%JzMg_QEPh5rZ}D205`W;f2fwr@21Il7vgEH>}RUwE`YeS zMGQ<_NlEaX=X7K(lFqxSmzG6xTti>JB;Uhe*poxAaFOb756I>Bu);f-dvC0pWDUi;4HJ1W9?S3{39>A=Eu(fPofVNPxJ9|PY zs2|j=c?>-u*Kb16vTs=9P-2b;F2qx}y640bul$DW--J(!u8@<2afMe=G5X*@FU<8< z@eK-?Jy*#F!i=P%uzBOMHpIK_YR{WNuPKse?xO>wT_=a{GxD8IXzezR_W_FiF8=|$F=Vb*@hQHG}5ZG76rML2%X?uFW+POuJRAE*}xtvio%Wjc5 z_Y($hQS&%xy;U~fk5dY6lV>!{^ULA;jr_|ywnVoJ?Oz?USzUvV>}zJ90?*wP9zKnX z>%Pr$&G%^RrvZ8uDBb+^`XFl#-QqsGbUujP_etmXC~}vAyuvtH^|it{y4jk9`-rD) zu_`Dr43Q0?Q}y_)xwI>+v1j7I1I%peq0O1iai6^L04*x7%AVN*NS9SfMl}tjv}*Ls z7J|Q<6Ds)5<_F{v!VUiF(IZ`H79$sUC3foAQD%>He(;0fUJL*F_6zW%;2jq3y$gA* zvS#qA2l?_9BXIYFqw@)BI`C{;U*wtSLGS@^uZ>3*dpyhKI0ZhkFKa$oHa=*{N5;Cy zc2!aN)q}?PjIOQWs52E!TtVWVt#TM6=N3H_tz0Wgl`DRNxa*aBBy%gn(;$EsKzmAL z6(2${{E)2OigyD)(Aj=Ye&KwuAB-+}DR^3Kbjj5iKR9nxIEIdlBKWZ-4Zts|m5hhT zqu^m#N|;ji2&(}dVYc2aTOPu=;%%c77B66`*e1W$gv++cv4`je{%w+6L)f=Xmed&e zwV`@@a?^tG8*bkDNL`&HuAZ*X2@gHZ{AomMtYSR>mbv)&I$^mIH4s4!mGHBD)=pHZ zL?c8&gcGzmRmyR2`&gdIspWqWlqT{kYdgf*M0(?!ayBXF)JRT2qQ$9JPCJBd$JQ&+ z1K}pjRw86`vLMEVA@s1%{1tF+eBE!94S`OdzA1( zXqs+_+Htv1%Tz>v)ev67R+Zar6D>;YwTWgWj@ra-B~Fh_lMdnqG}9E=gqfzyCd@R| zHqqfF;yA%SHRv?qI4{O)E#(r9%QobX|7>Ku`0&HVCl^iX5vyXq4qx2*8{=?@o8vCO_UwXF6MD^H6@kNF>~$XO523izep5HZq{ICb3OTNGXAN-Mp$&V=acGjJsQMXK!lR`N`# zEJ;n97?~L(;a>R>X_6xoYTE^}za%w(Vr1Tpgbo?Mk{lz`b0l=gbqdE0qF(tC@T4?* zx{HKfzN@`5b@8O!L2JH^gl$ht@~YIu6OZn+=HEz|E^j8JW=h4X)G3or*}O>T*(U#$ zkeacp!I>n1RjKZYX;WE8@r#5>^7<-lNWa(gvLh1K`^|KcwK{d`cza%U^vlxKsh35_ zw0?PH1j)i?{|K^(bxtY5_F7`uC9)JU?NVz=P<^Sj6ljzmm5x~DB;{Lhy1cG%WC7tV twBTwPzXo{s6_%3SS6HxDu3JM+5%M= 20 and plant.rk.frame%100 <= 25: + cruise_buttons = CruiseButtons.RES_ACCEL + else: + cruise_buttons = 0 + + md = messaging.new_message() + md.init('model') + md.model.frameId = 0 + for x in [md.model.path, md.model.leftLane, md.model.rightLane]: + x.points = [0.0]*50 + x.prob = 0.0 + x.std = 1.0 + + car_pts = map(pt_to_car, control_pts) + + print car_pts + + car_poly = np.polyfit([x[0] for x in car_pts], [x[1] for x in car_pts], 3) + md.model.path.points = np.polyval(car_poly, np.arange(0, 50)).tolist() + md.model.path.prob = 1.0 + Plant.model.send(md.to_bytes()) + + plant.step(cruise_buttons = cruise_buttons, v_lead = 2.0, publish_model = False) + + display.fill((10,10,10)) + + carx += plant.speed * plant.ts * math.cos(heading) + cary += plant.speed * plant.ts * math.sin(heading) + + # positive steering angle = steering right + print plant.angle_steer + heading += plant.angle_steer * plant.ts + print heading + + # draw my car + display.blit(pygame.transform.rotate(car, 90-math.degrees(heading)), (carx*METER, cary*METER)) + + # draw control pts + for x,y in control_pts: + pygame.draw.circle(display, (255,255,0), (int(x * METER),int(y * METER)), 2) + + # draw path + path_pts = zip(np.arange(0, 50), md.model.path.points) + + for x,y in path_pts: + x,y = pt_from_car((x,y)) + pygame.draw.circle(display, (0,255,0), (int(x * METER),int(y * METER)), 1) + + """ + # draw lead car + dl = (plant.distance_lead - plant.distance) + 4.5 + lx = carx + dl * math.cos(heading) + ly = cary + dl * math.sin(heading) + + display.blit(pygame.transform.rotate(leadcar, 90-math.degrees(heading)), (lx*METER, ly*METER)) + """ + + pygame.display.flip() + + diff --git a/selfdrive/test/plant/runtest.sh b/selfdrive/test/plant/runtest.sh deleted file mode 100755 index a955d9f9369ace..00000000000000 --- a/selfdrive/test/plant/runtest.sh +++ /dev/null @@ -1,14 +0,0 @@ -#!/bin/bash - -export OPTEST=1 -export OLD_CAN=1 - -pushd ../../controls -./controlsd.py & -pid1=$! -./radard.py & -pid2=$! -trap "trap - SIGTERM && kill $pid1 && kill $pid2" SIGINT SIGTERM EXIT -popd -mkdir -p out -MPLBACKEND=svg ./runtracks.py out diff --git a/selfdrive/test/plant/runtracks.py b/selfdrive/test/plant/runtracks.py deleted file mode 100755 index 7647e2f58a2ce9..00000000000000 --- a/selfdrive/test/plant/runtracks.py +++ /dev/null @@ -1,207 +0,0 @@ -#!/usr/bin/env python -import sys -import time, json - -from selfdrive.test.plant import plant -from selfdrive.config import Conversions as CV, CruiseButtons as CB -from maneuver import * - -maneuvers = [ - Maneuver( - 'while cruising at 40 mph, change cruise speed to 50mph', - duration=30., - initial_speed = 40. * CV.MPH_TO_MS, - cruise_button_presses = [(CB.DECEL_SET, 2.), (0, 2.3), - (CB.RES_ACCEL, 10.), (0, 10.1), - (CB.RES_ACCEL, 10.2), (0, 10.3)] - ), - Maneuver( - 'while cruising at 60 mph, change cruise speed to 50mph', - duration=30., - initial_speed=60. * CV.MPH_TO_MS, - cruise_button_presses = [(CB.DECEL_SET, 2.), (0, 2.3), - (CB.DECEL_SET, 10.), (0, 10.1), - (CB.DECEL_SET, 10.2), (0, 10.3)] - ), - Maneuver( - 'while cruising at 20mph, grade change +10%', - duration=25., - initial_speed=20. * CV.MPH_TO_MS, - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)], - grade_values = [0., 0., 1.0], - grade_breakpoints = [0., 10., 11.] - ), - Maneuver( - 'while cruising at 20mph, grade change -10%', - duration=25., - initial_speed=20. * CV.MPH_TO_MS, - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)], - grade_values = [0., 0., -1.0], - grade_breakpoints = [0., 10., 11.] - ), - Maneuver( - 'approaching a 40mph car while cruising at 60mph from 100m away', - duration=30., - initial_speed = 60. * CV.MPH_TO_MS, - lead_relevancy=True, - initial_distance_lead=100., - speed_lead_values = [40.*CV.MPH_TO_MS, 40.*CV.MPH_TO_MS], - speed_lead_breakpoints = [0., 100.], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] - ), - Maneuver( - 'approaching a 0mph car while cruising at 40mph from 150m away', - duration=30., - initial_speed = 40. * CV.MPH_TO_MS, - lead_relevancy=True, - initial_distance_lead=150., - speed_lead_values = [0.*CV.MPH_TO_MS, 0.*CV.MPH_TO_MS], - speed_lead_breakpoints = [0., 100.], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] - ), - Maneuver( - 'steady state following a car at 20m/s, then lead decel to 0mph at 1m/s^2', - duration=50., - initial_speed = 20., - lead_relevancy=True, - initial_distance_lead=35., - speed_lead_values = [20.*CV.MPH_TO_MS, 20.*CV.MPH_TO_MS, 0.*CV.MPH_TO_MS], - speed_lead_breakpoints = [0., 15., 35.0], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] - ), - Maneuver( - 'steady state following a car at 20m/s, then lead decel to 0mph at 2m/s^2', - duration=50., - initial_speed = 20., - lead_relevancy=True, - initial_distance_lead=35., - speed_lead_values = [20.*CV.MPH_TO_MS, 20.*CV.MPH_TO_MS, 0.*CV.MPH_TO_MS], - speed_lead_breakpoints = [0., 15., 25.0], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] - ), - Maneuver( - 'starting at 0mph, approaching a stopped car 100m away', - duration=30., - initial_speed = 0., - lead_relevancy=True, - initial_distance_lead=100., - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), - (CB.RES_ACCEL, 1.4), (0.0, 1.5), - (CB.RES_ACCEL, 1.6), (0.0, 1.7), - (CB.RES_ACCEL, 1.8), (0.0, 1.9)] - ), - Maneuver( - "following a car at 60mph, lead accel and decel at 0.5m/s^2 every 2s", - duration=25., - initial_speed=30., - lead_relevancy=True, - initial_distance_lead=49., - speed_lead_values=[30.,30.,29.,31.,29.,31.,29.], - speed_lead_breakpoints=[0., 6., 8., 12.,16.,20.,24.], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), - (CB.RES_ACCEL, 1.4), (0.0, 1.5), - (CB.RES_ACCEL, 1.6), (0.0, 1.7)] - ), - Maneuver( - "following a car at 10mph, stop and go at 1m/s2 lead dece1 and accel", - duration=70., - initial_speed=10., - lead_relevancy=True, - initial_distance_lead=20., - speed_lead_values=[10., 0., 0., 10., 0.,10.], - speed_lead_breakpoints=[10., 20., 30., 40., 50., 60.], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), - (CB.RES_ACCEL, 1.4), (0.0, 1.5), - (CB.RES_ACCEL, 1.6), (0.0, 1.7)] - ), - Maneuver( - "green light: stopped behind lead car, lead car accelerates at 1.5 m/s", - duration=30., - initial_speed=0., - lead_relevancy=True, - initial_distance_lead=4., - speed_lead_values=[0, 0 , 45], - speed_lead_breakpoints=[0, 10., 40.], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), - (CB.RES_ACCEL, 1.4), (0.0, 1.5), - (CB.RES_ACCEL, 1.6), (0.0, 1.7), - (CB.RES_ACCEL, 1.8), (0.0, 1.9), - (CB.RES_ACCEL, 2.0), (0.0, 2.1), - (CB.RES_ACCEL, 2.2), (0.0, 2.3)] - ), - Maneuver( - "stop and go with 1m/s2 lead decel and accel, with full stops", - duration=70., - initial_speed=0., - lead_relevancy=True, - initial_distance_lead=20., - speed_lead_values=[10., 0., 0., 10., 0., 0.] , - speed_lead_breakpoints=[10., 20., 30., 40., 50., 60.], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), - (CB.RES_ACCEL, 1.4), (0.0, 1.5), - (CB.RES_ACCEL, 1.6), (0.0, 1.7)] - ), - Maneuver( - "accelerate from 20 while lead vehicle decelerates from 40 to 20 at 1m/s2", - duration=30., - initial_speed=10., - lead_relevancy=True, - initial_distance_lead=10., - speed_lead_values=[20., 10.], - speed_lead_breakpoints=[1., 11.], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), - (CB.RES_ACCEL, 1.4), (0.0, 1.5), - (CB.RES_ACCEL, 1.6), (0.0, 1.7), - (CB.RES_ACCEL, 1.8), (0.0, 1.9), - (CB.RES_ACCEL, 2.0), (0.0, 2.1), - (CB.RES_ACCEL, 2.2), (0.0, 2.3)] - ), - Maneuver( - "accelerate from 20 while lead vehicle decelerates from 40 to 0 at 2m/s2", - duration=30., - initial_speed=10., - lead_relevancy=True, - initial_distance_lead=10., - speed_lead_values=[20., 0.], - speed_lead_breakpoints=[1., 11.], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), - (CB.RES_ACCEL, 1.4), (0.0, 1.5), - (CB.RES_ACCEL, 1.6), (0.0, 1.7), - (CB.RES_ACCEL, 1.8), (0.0, 1.9), - (CB.RES_ACCEL, 2.0), (0.0, 2.1), - (CB.RES_ACCEL, 2.2), (0.0, 2.3)] - ) -] - -css_style = """ -.maneuver_title { - font-size: 24px; - text-align: center; -} -.maneuver_graph { - width: 100%; -} -""" - -def main(output_dir): - view_html = "" % (css_style,) - for i, man in enumerate(maneuvers): - view_html += "" % (man.title,) - for c in ['distance.svg', 'speeds.svg', 'acceleration.svg', 'pedals.svg', 'pid.svg']: - view_html += "" % (os.path.join("maneuver" + str(i+1).zfill(2), c), ) - view_html += "" - - with open(os.path.join(output_dir, "index.html"), "w") as f: - f.write(view_html) - - for i, man in enumerate(maneuvers): - score, plot = man.evaluate() - plot.write_plot(output_dir, "maneuver" + str(i+1).zfill(2)) - -if __name__ == "__main__": - if len(sys.argv) <= 1: - print "Usage:", sys.argv[0], "" - exit(1) - - main(sys.argv[1]) - diff --git a/selfdrive/test/test_openpilot.py b/selfdrive/test/test_openpilot.py index 732df0cfa9ace2..2fcce2acbc0915 100644 --- a/selfdrive/test/test_openpilot.py +++ b/selfdrive/test/test_openpilot.py @@ -42,25 +42,25 @@ def wrap(): return wrap return wrapper -@phone_only -@with_processes(['controlsd', 'radard']) -def test_controls(): - from selfdrive.test.plant.plant import Plant - - # start the fake car for 2 seconds - plant = Plant(100) - for i in range(200): - if plant.rk.frame >= 20 and plant.rk.frame <= 25: - cruise_buttons = CruiseButtons.RES_ACCEL - # rolling forward - assert plant.speed > 0 - else: - cruise_buttons = 0 - plant.step(cruise_buttons = cruise_buttons) - plant.close() - - # assert that we stopped - assert plant.speed == 0.0 +#@phone_only +#@with_processes(['controlsd', 'radard']) +#def test_controls(): +# from selfdrive.test.plant.plant import Plant +# +# # start the fake car for 2 seconds +# plant = Plant(100) +# for i in range(200): +# if plant.rk.frame >= 20 and plant.rk.frame <= 25: +# cruise_buttons = CruiseButtons.RES_ACCEL +# # rolling forward +# assert plant.speed > 0 +# else: +# cruise_buttons = 0 +# plant.step(cruise_buttons = cruise_buttons) +# plant.close() +# +# # assert that we stopped +# assert plant.speed == 0.0 @phone_only @with_processes(['loggerd', 'logmessaged', 'tombstoned', 'proclogd', 'logcatd']) diff --git a/selfdrive/test/tests/plant/__init__.py b/selfdrive/test/tests/plant/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/test/tests/plant/test_longitudinal.py b/selfdrive/test/tests/plant/test_longitudinal.py new file mode 100755 index 00000000000000..3c8286b775e3b7 --- /dev/null +++ b/selfdrive/test/tests/plant/test_longitudinal.py @@ -0,0 +1,255 @@ +#!/usr/bin/env python +import os +os.environ['OLD_CAN'] = '1' +os.environ['NOCRASH'] = '1' + +import time +import unittest +import shutil + +import matplotlib +matplotlib.use('svg') + +from selfdrive.config import Conversions as CV, CruiseButtons as CB +from selfdrive.test.plant.maneuver import Maneuver +import selfdrive.manager as manager + +def create_dir(path): + try: + os.makedirs(path) + except OSError: + pass + +maneuvers = [ + Maneuver( + 'while cruising at 40 mph, change cruise speed to 50mph', + duration=30., + initial_speed = 40. * CV.MPH_TO_MS, + cruise_button_presses = [(CB.DECEL_SET, 2.), (0, 2.3), + (CB.RES_ACCEL, 10.), (0, 10.1), + (CB.RES_ACCEL, 10.2), (0, 10.3)] + ), + Maneuver( + 'while cruising at 60 mph, change cruise speed to 50mph', + duration=30., + initial_speed=60. * CV.MPH_TO_MS, + cruise_button_presses = [(CB.DECEL_SET, 2.), (0, 2.3), + (CB.DECEL_SET, 10.), (0, 10.1), + (CB.DECEL_SET, 10.2), (0, 10.3)] + ), + Maneuver( + 'while cruising at 20mph, grade change +10%', + duration=25., + initial_speed=20. * CV.MPH_TO_MS, + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)], + grade_values = [0., 0., 1.0], + grade_breakpoints = [0., 10., 11.] + ), + Maneuver( + 'while cruising at 20mph, grade change -10%', + duration=25., + initial_speed=20. * CV.MPH_TO_MS, + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)], + grade_values = [0., 0., -1.0], + grade_breakpoints = [0., 10., 11.] + ), + Maneuver( + 'approaching a 40mph car while cruising at 60mph from 100m away', + duration=30., + initial_speed = 60. * CV.MPH_TO_MS, + lead_relevancy=True, + initial_distance_lead=100., + speed_lead_values = [40.*CV.MPH_TO_MS, 40.*CV.MPH_TO_MS], + speed_lead_breakpoints = [0., 100.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] + ), + Maneuver( + 'approaching a 0mph car while cruising at 40mph from 150m away', + duration=30., + initial_speed = 40. * CV.MPH_TO_MS, + lead_relevancy=True, + initial_distance_lead=150., + speed_lead_values = [0.*CV.MPH_TO_MS, 0.*CV.MPH_TO_MS], + speed_lead_breakpoints = [0., 100.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] + ), + Maneuver( + 'steady state following a car at 20m/s, then lead decel to 0mph at 1m/s^2', + duration=50., + initial_speed = 20., + lead_relevancy=True, + initial_distance_lead=35., + speed_lead_values = [20.*CV.MPH_TO_MS, 20.*CV.MPH_TO_MS, 0.*CV.MPH_TO_MS], + speed_lead_breakpoints = [0., 15., 35.0], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] + ), + Maneuver( + 'steady state following a car at 20m/s, then lead decel to 0mph at 2m/s^2', + duration=50., + initial_speed = 20., + lead_relevancy=True, + initial_distance_lead=35., + speed_lead_values = [20.*CV.MPH_TO_MS, 20.*CV.MPH_TO_MS, 0.*CV.MPH_TO_MS], + speed_lead_breakpoints = [0., 15., 25.0], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] + ), + Maneuver( + 'starting at 0mph, approaching a stopped car 100m away', + duration=30., + initial_speed = 0., + lead_relevancy=True, + initial_distance_lead=100., + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7), + (CB.RES_ACCEL, 1.8), (0.0, 1.9)] + ), + Maneuver( + "following a car at 60mph, lead accel and decel at 0.5m/s^2 every 2s", + duration=25., + initial_speed=30., + lead_relevancy=True, + initial_distance_lead=49., + speed_lead_values=[30.,30.,29.,31.,29.,31.,29.], + speed_lead_breakpoints=[0., 6., 8., 12.,16.,20.,24.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)] + ), + Maneuver( + "following a car at 10mph, stop and go at 1m/s2 lead dece1 and accel", + duration=70., + initial_speed=10., + lead_relevancy=True, + initial_distance_lead=20., + speed_lead_values=[10., 0., 0., 10., 0.,10.], + speed_lead_breakpoints=[10., 20., 30., 40., 50., 60.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)] + ), + Maneuver( + "green light: stopped behind lead car, lead car accelerates at 1.5 m/s", + duration=30., + initial_speed=0., + lead_relevancy=True, + initial_distance_lead=4., + speed_lead_values=[0, 0 , 45], + speed_lead_breakpoints=[0, 10., 40.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7), + (CB.RES_ACCEL, 1.8), (0.0, 1.9), + (CB.RES_ACCEL, 2.0), (0.0, 2.1), + (CB.RES_ACCEL, 2.2), (0.0, 2.3)] + ), + Maneuver( + "stop and go with 1m/s2 lead decel and accel, with full stops", + duration=70., + initial_speed=0., + lead_relevancy=True, + initial_distance_lead=20., + speed_lead_values=[10., 0., 0., 10., 0., 0.] , + speed_lead_breakpoints=[10., 20., 30., 40., 50., 60.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)] + ), + Maneuver( + "accelerate from 20 while lead vehicle decelerates from 40 to 20 at 1m/s2", + duration=30., + initial_speed=10., + lead_relevancy=True, + initial_distance_lead=10., + speed_lead_values=[20., 10.], + speed_lead_breakpoints=[1., 11.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7), + (CB.RES_ACCEL, 1.8), (0.0, 1.9), + (CB.RES_ACCEL, 2.0), (0.0, 2.1), + (CB.RES_ACCEL, 2.2), (0.0, 2.3)] + ), + Maneuver( + "accelerate from 20 while lead vehicle decelerates from 40 to 0 at 2m/s2", + duration=30., + initial_speed=10., + lead_relevancy=True, + initial_distance_lead=10., + speed_lead_values=[20., 0.], + speed_lead_breakpoints=[1., 11.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7), + (CB.RES_ACCEL, 1.8), (0.0, 1.9), + (CB.RES_ACCEL, 2.0), (0.0, 2.1), + (CB.RES_ACCEL, 2.2), (0.0, 2.3)] + ) +] + +def setup_output(): + output_dir = os.path.join(os.getcwd(), 'out/longitudinal') + if not os.path.exists(os.path.join(output_dir, "index.html")): + # write test output header + + css_style = """ + .maneuver_title { + font-size: 24px; + text-align: center; + } + .maneuver_graph { + width: 100%; + } + """ + + view_html = "
%s
" % (css_style,) + for i, man in enumerate(maneuvers): + view_html += "" % (man.title,) + for c in ['distance.svg', 'speeds.svg', 'acceleration.svg', 'pedals.svg', 'pid.svg']: + view_html += "" % (os.path.join("maneuver" + str(i+1).zfill(2), c), ) + view_html += "" + + create_dir(output_dir) + with open(os.path.join(output_dir, "index.html"), "w") as f: + f.write(view_html) + +class LongitudinalControl(unittest.TestCase): + @classmethod + def setUpClass(cls): + + setup_output() + + shutil.rmtree('/data/params', ignore_errors=True) + + manager.gctx = {} + manager.prepare_managed_process('radard') + manager.prepare_managed_process('controlsd') + + manager.start_managed_process('radard') + manager.start_managed_process('controlsd') + + @classmethod + def tearDownClass(cls): + manager.kill_managed_process('radard') + manager.kill_managed_process('controlsd') + time.sleep(5) + + # hack + def test_longitudinal_setup(self): + pass + +WORKERS = 8 +def run_maneuver_worker(k): + output_dir = os.path.join(os.getcwd(), 'out/longitudinal') + for i, man in enumerate(maneuvers[k::WORKERS]): + score, plot = man.evaluate() + plot.write_plot(output_dir, "maneuver" + str(WORKERS * i + k+1).zfill(2)) + +for k in xrange(WORKERS): + setattr(LongitudinalControl, + "test_longitudinal_maneuvers_%d" % (k+1), + lambda self, k=k: run_maneuver_worker(k)) + +if __name__ == "__main__": + unittest.main() + diff --git a/selfdrive/ui/Makefile b/selfdrive/ui/Makefile index d2289228e344d4..d0a3778e21e5b8 100644 --- a/selfdrive/ui/Makefile +++ b/selfdrive/ui/Makefile @@ -55,9 +55,10 @@ ui: $(OBJS) $(OPENGL_LIBS) \ -lcutils -lm -llog -../common/framebuffer.o: ../common/framebuffer.cc +%.o: %.cc @echo "[ CXX ] $@" $(CXX) $(CXXFLAGS) -MMD \ + -Iinclude -I.. -I../.. \ -I$(PHONELIBS)/android_frameworks_native/include \ -I$(PHONELIBS)/android_system_core/include \ -I$(PHONELIBS)/android_hardware_libhardware/include \ diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c index fc5c16a9421b45..68d979ec9923b5 100644 --- a/selfdrive/ui/ui.c +++ b/selfdrive/ui/ui.c @@ -38,16 +38,18 @@ typedef struct UIScene { int frontview; uint8_t *bgr_ptr; - int big_box_x, big_box_y, big_box_width, big_box_height; int transformed_width, transformed_height; uint64_t model_ts; ModelData model; + float mpc_x[50]; + float mpc_y[50]; + bool world_objects_visible; // TODO(mgraczyk): Remove and use full frame for everything. - mat3 warp_matrix; // transformed box -> big_box. + mat3 warp_matrix; // transformed box -> frame. mat4 extrinsic_matrix; // Last row is 0 so we can use mat4. float v_cruise; @@ -88,14 +90,16 @@ typedef struct UIState { void *livecalibration_sock_raw; zsock_t *live20_sock; void *live20_sock_raw; + zsock_t *livempc_sock; + void *livempc_sock_raw; // vision state bool vision_connected; bool vision_connect_firstrun; int ipc_fd; - VisionBuf bufs[UI_BUF_COUNT]; - VisionBuf front_bufs[UI_BUF_COUNT]; + VIPCBuf bufs[UI_BUF_COUNT]; + VIPCBuf front_bufs[UI_BUF_COUNT]; int cur_vision_idx; int cur_vision_front_idx; @@ -228,6 +232,11 @@ static void ui_init(UIState *s) { assert(s->live20_sock); s->live20_sock_raw = zsock_resolve(s->live20_sock); + s->livempc_sock = zsock_new_sub(">tcp://127.0.0.1:8035", ""); + assert(s->livempc_sock); + s->livempc_sock_raw = zsock_resolve(s->livempc_sock); + + s->ipc_fd = -1; // init display @@ -271,8 +280,7 @@ static void ui_init(UIState *s) { // intrinsic_matrix and returns true. Otherwise returns false. static bool try_load_intrinsics(mat3 *intrinsic_matrix) { char *value; - const int result = - read_db_value("/data/params", "CloudCalibration", &value, NULL); + const int result = read_db_value(NULL, "CloudCalibration", &value, NULL); if (result == 0) { JsonNode* calibration_json = json_decode(value); @@ -309,18 +317,14 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, assert(num_back_fds == UI_BUF_COUNT); assert(num_front_fds == UI_BUF_COUNT); - visionbufs_load(s->bufs, &back_bufs, num_back_fds, back_fds); - visionbufs_load(s->front_bufs, &front_bufs, num_front_fds, front_fds); + vipc_bufs_load(s->bufs, &back_bufs, num_back_fds, back_fds); + vipc_bufs_load(s->front_bufs, &front_bufs, num_front_fds, front_fds); s->cur_vision_idx = -1; s->cur_vision_front_idx = -1; s->scene = (UIScene){ .frontview = 0, - .big_box_x = ui_info.big_box_x, - .big_box_y = ui_info.big_box_y, - .big_box_width = ui_info.big_box_width, - .big_box_height = ui_info.big_box_height, .transformed_width = ui_info.transformed_width, .transformed_height = ui_info.transformed_height, .front_box_x = ui_info.front_box_x, @@ -344,7 +348,7 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, }}; char *value; - const int result = read_db_value("/data/params", "IsMetric", &value, NULL); + const int result = read_db_value(NULL, "IsMetric", &value, NULL); if (result == 0) { s->is_metric = value[0] == '1'; free(value); @@ -392,9 +396,8 @@ static void ui_draw_transformed_box(UIState *s, uint32_t color) { }; for (int i=0; ibig_box_x + verts[i].pos.v[0] / verts[i].pos.v[2]; - verts[i].pos.v[1] = s->rgb_height - (scene->big_box_y + - verts[i].pos.v[1] / verts[i].pos.v[2]); + verts[i].pos.v[0] = verts[i].pos.v[0] / verts[i].pos.v[2]; + verts[i].pos.v[1] = s->rgb_height - verts[i].pos.v[1] / verts[i].pos.v[2]; } glUseProgram(s->line_program); @@ -469,6 +472,51 @@ static void draw_cross(UIState *s, float x_in, float y_in, float sz, NVGcolor co nvgRestore(s->vg); } +static void draw_x_y(UIState *s, const float *x_coords, const float *y_coords, size_t num_points, + NVGcolor color) { + const UIScene *scene = &s->scene; + + nvgSave(s->vg); + + // path coords are worked out in rgb-box space + nvgTranslate(s->vg, 240.0f, 0.0); + + // zooom in 2x + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + nvgScale(s->vg, 2.0, 2.0); + + nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + + nvgBeginPath(s->vg); + nvgStrokeColor(s->vg, color); + nvgStrokeWidth(s->vg, 2); + bool started = false; + + for (int i=0; ivg, x, y); + started = true; + } else { + nvgLineTo(s->vg, x, y); + } + } + + nvgStroke(s->vg); + + nvgRestore(s->vg); +} + static void draw_path(UIState *s, const float *points, float off, NVGcolor color) { const UIScene *scene = &s->scene; @@ -669,6 +717,8 @@ static void ui_draw_world(UIState *s) { draw_model_path( s, scene->model.right_lane, nvgRGBA(0, (int)(255 * scene->model.right_lane.prob), 0, 128)); + + draw_x_y(s, scene->mpc_x, scene->mpc_y, 50, nvgRGBA(255, 0, 0, 255)); } if (scene->lead_status) { @@ -939,7 +989,7 @@ static void ui_update(UIState *s) { // poll for events while (true) { - zmq_pollitem_t polls[5] = {{0}}; + zmq_pollitem_t polls[6] = {{0}}; polls[0].socket = s->live100_sock_raw; polls[0].events = ZMQ_POLLIN; polls[1].socket = s->livecalibration_sock_raw; @@ -948,15 +998,19 @@ static void ui_update(UIState *s) { polls[2].events = ZMQ_POLLIN; polls[3].socket = s->live20_sock_raw; polls[3].events = ZMQ_POLLIN; - - int num_polls = 4; + polls[4].socket = s->livempc_sock_raw; + polls[4].events = ZMQ_POLLIN; + + int num_polls = 5; if (s->vision_connected) { assert(s->ipc_fd >= 0); - polls[4].fd = s->ipc_fd; - polls[4].events = ZMQ_POLLIN; + polls[5].fd = s->ipc_fd; + polls[5].events = ZMQ_POLLIN; num_polls++; } + + int ret = zmq_poll(polls, num_polls, 0); if (ret < 0) { LOGW("poll failed (%d)", ret); @@ -969,7 +1023,7 @@ static void ui_update(UIState *s) { // awake on any activity set_awake(s, true); - if (s->vision_connected && polls[4].revents) { + if (s->vision_connected && polls[5].revents) { // vision ipc event VisionPacket rp; err = vipc_recv(s->ipc_fd, &rp); @@ -1021,7 +1075,7 @@ static void ui_update(UIState *s) { } else { // zmq messages void* which = NULL; - for (int i=0; i<4; i++) { + for (int i=0; i<5; i++) { if (polls[i].revents) { which = polls[i].socket; break; @@ -1085,7 +1139,7 @@ static void ui_update(UIState *s) { cereal_read_LiveCalibrationData(&datad, eventd.liveCalibration); // should we still even have this? - capn_list32 warpl = datad.warpMatrix; + capn_list32 warpl = datad.warpMatrix2; capn_resolve(&warpl.p); // is this a bug? for (int i = 0; i < 3 * 3; i++) { s->scene.warp_matrix.v[i] = capn_to_f32(capn_get32(warpl, i)); @@ -1100,6 +1154,23 @@ static void ui_update(UIState *s) { } else if (eventd.which == cereal_Event_model) { s->scene.model_ts = eventd.logMonoTime; s->scene.model = read_model(eventd.model); + } else if (eventd.which == cereal_Event_liveMpc) { + struct cereal_LiveMpcData datad; + cereal_read_LiveMpcData(&datad, eventd.liveMpc); + + capn_list32 x_list = datad.x; + capn_resolve(&x_list.p); + + for (int i = 0; i < 50; i++){ + s->scene.mpc_x[i] = capn_to_f32(capn_get32(x_list, i)); + } + + capn_list32 y_list = datad.y; + capn_resolve(&y_list.p); + + for (int i = 0; i < 50; i++){ + s->scene.mpc_y[i] = capn_to_f32(capn_get32(y_list, i)); + } } capn_free(&ctx); diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond index 23e6505bf2c3e40c840496a9c3404e6cad6427e4..17f8c32bdfbb2a4712cc86f6a0004c5e50e6df53 100755 GIT binary patch delta 1738261 zcmZ^s3tUvy_Q%heP*G6_Q5o`u4+>v3m>Q-P2q-A(2xw>~prB9)C}>pHjDbq2iH&)v ztf;K0EYYl}tgx);O=UMKZ_&-VR95unmev2a_F4y-{rR`+u+RCfwby>F{W#~$jCId^ z)uZ;ihq_n0!rWEe4GMAUuVG}@zqWJSectS?s}!(f!!Xq~{iOsp&)%9ZdK|}%TA{A% zLkm@Gr*q&+r7JFA{o>05V^ToK=GZ^q3=Jzeb*W-qVt=U_HL^;$9uG<6G7d@fKW#4a z_6RbJW*ij8BW{D~790m~?mvS${e1;&v|NvY>?2rt7}v+ae?feY*tiDQ=izz{;{S?1 zrQZbobD%Q|{3Na~W&M%H5RxK129N-u9i*7XBmU2ZhI!YBd6HJbY&DMe#rz<|^W}WA zBrnAEJve_+EH0P01jQH)TYrn*E}ZuVdlm8GE_nol*7F za!m=k;kW}C??C(x3Usd&;yuK@q5CF|oyh18$nVtBz8r9k{BQ13q74uZ!}UQii1aFK z1v^XFFF5}TN&|H&>e$gCHRFnPC@@V@EXLI(ciW0&Q*TC@kkbe&OlaTF2e6)*BmDsVSkf3GsJ`^KguW zg7+RI&d2e!Xg`X?7vM++D@A-aIE|&=NYEfU<=}6T48|I833_%3 z4SE!g;0T4xf}Iw`uYjjHQ2%ILT#1WX#7#KIOHz>@19*`ul;48cE z@i0*a+3iRd4%th%rm$Z0bNJHmL-sDtpM&02I4Haeo!O#K*C8|p20++|<0%Nffx>(- zL<)z%uLZwT5|!cl85~PQ=S-achZGT#kl~gt#)&-v`Pahw;Cw6C2)T~Ic@z2IMAAg4 zgV9tNp->8?gGjIxaewfKaJ~`8OE}H|dlT$=oZm0{--BI`>)AM-WD~|nuyu028Ry$^ zJcDBtblQ>bF`Rdffe`=;0Cpk%490(l>?A25(8N3y@u!F>tmUZluNww;;GpmV(j0;f zH{y9Xo&_(KbR?&RfWpm?eTL)0ArMAG$&Ex5d^mp$@o)%llZ0;j{(5ISEX-s(T# z4)-p{)gz+e!8wKf68Dr8t0gAc1vvklP7t<0?;E2M3|BXrD7fL}Tsc|(4I(rbO2T_pyfKN%rnG!#V_-PzDkgbK0tHi?FU_oMZ zGGuMwFM?eRHW$~o;TVqd4%odx^kN{tLe7sv{+65f6lX z8shUMh9p=3osjib$XNX0%3m29uod7t3 z6y2ehg?J?N+>rIeF(2n&f|cR864ys@eId>%TrTlzV*hE#b0Gf){2R#k(&9oP9B>GZ zKOyLe*bdc5V249;(hi*tF-*uI`oBQ;dK^x<{!4WJ1)cslj{?tx{C`rINbsM|K>m*a zj1>5&B>EQD6;OT-*FWNj#&sC3FG3t78B7KLFW7G|^rEE0sgVkHE{>i!?}ej=Ai|l@ zIe_#FAuC5rVJvwIg~tJJMEso?8i)AyE=EZw6W6uSqwq0~OK{yPhVByn7Op=Kc8A!e zp+_MCI{)cn^IdT7clh%f6h9FItcuNnC|)5(28fYia=jAz{h%CzgEsar2>%z-odeyI zIPL|zSojgdH{h5F`4q%AGWQyPz|bzqJPGg&IUfY06Xkp^_+}i-VRQ(NGRWpZ_9o(W z;4T~#HiP9OgG&)#1-;jC-i){d*ApP00lhk0o4BUXBMALJ1WFVZi4nfS6sTQ4hlG%ww((r594AeU>M>DVdyTzGsM9C5>Esh zAjT-;_rO!Z(xHD7;z5wzE4sZ9?*?;0_6~G6`bSI%^ZtRWS)df^B{q=ieq39Uax!!% z43_wR;LAmpf!GJx1*9P1R@nIhJRWuu!B!)FMD$6eMDnSl9n=#dSOEBMIk#~B78J)K z!6_F3yV(Q}__ZZWh@oT+hMz6v>?Aufyish(~~( z5dHvky5sm2X`M9nBtU6emqedZ0vz{2X(*1tIC?<-5fb#mc`%NDi+&Q=JX}-o5|i_N znA8V*pM~@a92A~~^mCj?A`WL{+=QH$AVnyS`*9RWY7&P*cSVbTUvmFlY?Ev~ zY}vsNy}M|0a~2fN#c>`Id?kqnOH9gRaXu1991=W;qY=7e!3%Moi-W>tT{8I%=iMd! zbi{e0a}D_OxUPl%msBYnADm&muy^-uR_!CZqpj+a-Mh@W)`Dp@SyuLe-9xPU1G|IF z!Pdr--Nlygsog==sfu5Ntv~yzXn-LpW5w=xDY&x z5+O|E$XJSawf`M6JoI*)r3$6zCm&j$J+eDIVv-;`dPPo>t@yt>!n)my%j1;Zikn*F z^tYNJV|t+CTWocS|A*KCz5($RVdMSJy2I&a+;|TL!YtpR-9sWC5FtfpA%Pt_sNUyV z)#ubqvf4k|9TfV#Es;2iY}`CPXoSrd<78YH3n6ko!M|X_a4Y*_wAS2Le+`~+wj}ts zoe=RV=uX2C(Ix#QI3I{i1`oUvXDho%GI5?x+4sCuYz(#DJh1ybEArLdLH=E5JA3v8 zPlHw_X^lA#SGROYPl@iNKM13`@av&{wi&7{f6HRy3ECR@8_x>Terc0_TNNP1A zTPydA-I3j%h3q_4-~4$s(PP)+awm@4MEzEr7j((ckLy2i+-q9bJ+XV3`Is_S-?lp_ zz`2xeR6soh~CNM(;Cje^QUxV{p{o5C#BJtY%QyI~t7y`k|Z;xHUP;kW=PbFKJ; zyTh#M!)t;^q<}5JaW@VM4+~rx#O)6?|k4harA>I9`S4(i#S#1-!XEw z3_2g-d=rj-(6hs6@Itu`mn>}A7jp8V#2?rK#63;y8n@wO1rl9?r8|7!T$s5=Ol^_4 zoBzo8u&LKVCk{t6^eaSiAI=+aexY3B(x}IAj})Q>{Cw+?i8bNgCY(m%m;})mqCQCC zM6fbBClg8Z2jN;Aelev0{;b0F5n(>WGr?jc?UNEuk@zrV4bXYgp;mhArNl~aDBL7Q z2;GVEJzcJedBg~vSJEGZn>jMR7v0^^S%>qtsO=_*Aj>z>3IB$e5g~eb~g+G9J42~XJW)s1jI2Lx{m8Pmc8%cxU zIx)xucUDM1;YW_t->uLo7bCBN+|ngY9yr~|z68Es(oVqjZd}JA?grg7oL3>9P1!>4l#udbPeUta8P&w*Bc;T!I#DwH4k~7+#P(uqd=o1nMjSF zx?FFAi3jES0-QJ6N`_?~s~O~tf!V&`??C5696#W=Nc4|`AAr0Z*H4-&O<5&cpW5PlakHPilh%c8!<0X9? z-KO{;JO$wb9N9RZiI_qulrF>h-(VE}C;VTMcrLDg#4!ukzp{!^iR&nlM{0b9xj);W7+U z(x0?1MO_b3f6-WIkrBuxe?Ki3yvv}t5)Xbz-?yLja|t3$f zV2aYLlRgd;eW$!ew|5u&{qftvBcdSXp5tnGB$xaAYu4Z{RHbzp)xKkj2aB|i|Fiw! zDKjMP$b`kvdk8?uG}#ys7qnZ*KnRz@KRzOTH< z&xUAYP2oIn%D8R;>nDqT0yz0g{kL`{{a4Q)=67BkT4#XxQc zw>&+(qmXYK$YcX{e|bee(K%n~m8id1nrMU%y-}nkf3vp?k>3CJAQXpgWg{$TP(_-K z2UcVNxw`i$N#A~Py0Tj)>0c8*`fRS|QOWgv;gL^r>20_DkMO;ZaVa?!-V1_L?y)xp z=I$Pl!lL50I71M+XIb#2p)<@Tul$X?!RVf zRR317GJa>OD)w>1|Ju@F=9~U^io#R=D@I~>2O4n=C zjNtnV{JpcIV)6mVJA*zCG_YBC;ctO%@-{iqm|Y^B?&DPUWKhTEjRw1^{5d(pBR&-E z_HS6bMGE=5KYn?5#E+7urXjGXn`y9nFOUV}zbX3p+6;FW)>$VUv-Z)~MU$g$BiPQI*hJoXR*BdJftr>t@o(N z3L1Pkut1lIA>?J-+CTbDA?o#?}DRz=|=gzff@82$u-TqBGAxaaH>%3wm|(kqMv-3t?wUOFf8R# zU@B+u&8aHG0g~@>Wu~{0`$`6LDgOuJXD1fUR)lMZ$N%K-W^aG|E#cm^p=@*fqbW)! zS<-HmybkT-v0~S;P8F@UQS!&7tSMzUsLB8*(wyRRvE$jvzPnHKH(<9$zIb+KsP`{r zGt6k$mdxIm7pQs4wdR=yuKG*c!^{_M$hg9+tHM&T6J5{E=@xz`>wEE1dx}E#{Qig} zh}AY*lSgxbT8;!7nhUN*#N~E>aSnN+pTCj0Pcpt+^lP5W2SEcjiXeriQ-9p}Ab(lW z06YrC7>)Tzdg%BQDM~9ybRQMtZ4U$%<|bNXy(dK4VX-t?Qbj~jQC&v+e)e74+9+^p z>*yB(txW@`w%%s3_f(3VgW_Asvgx(Q#$07TY=}|6lnvQ}#bRj4o)G_vHBk}ytY}pK zC$NBHsQ57(L_52iIIXzNR+TE;sGH2ik6y*)IZAsnD>KS;ncvdsn7vROfqD+u^#*H5 zMVlqt2765VA1od2{aCV#-p1M4PdC03KHv!+1vOH8$64GeCD*Y2bm9GlNAF}_EqpXM zIY{%vfvtN1^RY(N3*-q{`y@fK7;13v?(&q>Ka3WT_$)}(yrHeMJA{`%9+=JRiuX2J zU*ZWO#Q)B^;of%1>(J-MNGpUlp43jihbZ5?Je@7*SMf*J|drpPvU#HFBqN zneE+6oaj5V0`#maj#~oLzC(UCszXw>4d%Mow*?_%xQ;*13-SMP&4qr?2A7#f z^@te^32j1sGCrjPjLG0s#;QY{k39vKQT@DLkv3_Qk0rcrKc_-*R5&cW?Rw^R+h07E zbLqG_P(R=1HwE$^x^X{Wk{LR!M(Knb)iFG?*xvdyxaw#7HeJf_rtsLp0{`pRMR`Az zJZhc`%;P(7@`s;ya~sx3`ZLC{U8g+}39ojtzOO1pkrUYUQgDfW^QCOxuJc*ous_yl z{gpE?;Jg&3LqJVlen((|Hqjd6-KWfj8*Xin^t)u=eidiGs~1~)TC#7<3(WpC&fX~3 z_Mjiwxob|@YrLxV3?r^Q&`=}IMN3{DShQ!cBM&!s(17>1Z*iFu)UDNgXj3CJ z_T=H)DB~(etaNm46uBa0;HojJ0?Ty2*lB&ew^A&Wia#U#5N(|irk|lA<7MXkjZ=4U z0(%=cj*1!cktFk_1g;?83NN`mMA_k02QRtQ#&eAozt9Z#I?j>y)XF#soa&l-E8mRU z197r++UU*PX=rv8-f+?Fh0Ac>!JQ`9ND@0or4X4S=;%rI4gZyELWeGtGBjw@-$C+f zdT`*6+vYNBsIqf6i@jaPxhYbm?d}pA$q#T_+f&)l7G9u`B7sAn2y(#jNJDWfhUcn>?5?f>}XM^X5+d)b7sH!4M0 z7|@sVd_uBJ*7jk)iTgE3PZi%w$&#{91he`*SMKqqgArrZhZU3IF47JO;HAHyTWn7tE z(k*V`qu=Ao*mKuR;X$%>N|a(boos*C5$+uN6f=dTtl!^w<5SL{R$;u*P&=jd5K|jB zX%qI6{%kIzmCe}?=BN5cRJq6-A~O21#-2LXXcxPA^lUeMpV)1AHn5f6HtpDPp#%#Q^2Wy`A={;-2OGU z4)?AVnyKwx`h~LfLMM09QYqaQWgU~nuZx+;WOy?;d2Z`tTpN1#OyN=CqerHzYrB+1 z;iPZ)KPU?IKBH`g8Fkvz?^h&ky|x4R44i5bt4-d{NmAxk&SkI45ik0Md%oZn-6Q-0 z=2+xDkfxSG&+>=v2%ok9Vw!dLXty!T74L0i&RnPr(MRrbRoO{)!QOYKI^!{>gfMXIzHBhwYf415l+AojGiNVst> z^Y)&c%@yF3OSCpK-zD59uP>sdR4vTM8Xek_@QWm9&|Xu#NgWtE8V`4rpBB&NGbPy+H>XEDphYIs3}9$1sSPOD*C$$ zxU|*6ZxCL!gL$nq@e{OTj<{2#^~+g$Ldtn9)iLLwNXHN3Mf-%PPKWBqQORY`!+UB(7`7^0x%Mz~SNiLP~8og-F zxlg2tAuP?7Lcb)1sK1jdZ#&9cTnJ;*XwKau-Sd&?w>PqWi{x?eNwgO=yhGPZK6V^X3!z^Mk&+QW<&gqLeiYJUaqL*GcCb{%pz`>efVeGU^7?cN$gdMHE3#oT=~vBV6LRKbJUTAcWZ8=M@~`9Akv zgQQBM=JY0uG+1-vCE!%m%t}t>lT;OwOJOB9O`PyOqTlu?>qiSeB0Tmf=5FD?upO__ z(9D&z_kypAtGmS2$4i1<)3{L@`^&5$)f)j$_Y4iaE@4gCgH9Ix7VS0YHre7GSL-E| zsz-9VnUbI~o@-`1)*|86qj=wgPEeu1e`I@jOpTL^)!dUu<~EToLn^g*%i(%s2&u3| zEx&6->RS~ktpKN1@6g^dKcV!oEXQ7|ti(-ZYi}!kJR+}tgMn<2{{SZsYW$fS*M6Jc zbGkTQ$m{HQ$(+m>q26kq2Qeip{DGTbmq>R>o9*q(m9#7KKlC!`8$(&&9$hnGhbmuk zIA2+?_0xsBwMNNR#R}_hL_ZnmCHv?FSIQn18x7h!xfXEBK6w~V9QN$@mGE5c+43}+ zfz8*c-y(h&onZ0fT&e0lH8J$MkSgFZ%C+s$5OB&dznSxb5f#o8KD`e+XS+;F$-*17 z*Vrq;)#%cmrP7$i-qZie_R#nTByG?{&dc_@CnT-wzQDFR;?gEF|7VAXr*uG@x*}M6 zm(v3~3#v(pyfC%vKS+3k_Au~1>WPR^B5l#$H~dbmmNE%adUBksJ&=r-RFV4w`^f`N zt&l9+D0q_!50JH(25~yi7b%L`ZvqO%TD|rOn3L+E=thyAxPd)?lJvwmGEOHQVr#aq z+$Lqn)E=cA2d8#3v^DR0vER~enL2XG=|f~2ad;2PQQSK@^)-OSdGiGG^!OwIeRQVZe=NU6=E zHP3UZ#kEe-zVX}$W$h52u2bkv(?iTNBHcTd*B^U&Xac9Us?pYvg*4t$S|nA_MlNSL zn>4-xr;?Q4!+vb{epDQ{UTy(<3#UTsku~pBNGY#I?G`FtQng+XI9k%cDVK&_fw^oH z{Zx5$vB%(WjrhsW@<7h+g~6ERsDIBd2<>(O`GDGzWcp+FgnM_2E#HlSJ#jBMm91^7cOLdxA^Gm!h>H4ToPNwPRaR~8x-u8nmv%q^xyrV-tVBJT2rg%(0Fdmx~f3$ zITxJt+a3vQmkiNQ{)qMMN2IGozeDS-2U*{1IOQ2_HkAK8n?R_LkSy(D|szu+W9)fuB{cRDvAqf)i;~Lnzr&dW&uDx06k-!-= z-om|cT6!bEskKNVX z86fbQY!S3ltBxs#nA#&&%Vwu!Q)1;SeV^ZaZ@71_(2nc454A+S#-7Kys3Z=@3(!xb3c%V!fl* zb&nX$*LLrDYFoHY(l%=Ey*Ep$Sj{00iGHT`804t%cDuo(3?G0~(@g5lt`ICdBSMvV ztWly(pfhEuER;=mt|aJ3Pe4*WRoR3ZCGtC6wz=;l`&N0rmMy9NC)w|lPl&kBU_l=B zzQ6uou2FqvaRF<4@Kj*PR4@cwHR`eg|KJazyyxOtO%1mPI`EUiW3`7{p9*(rk8JxS zv)yv7kIxeBxhr24F}pjL^jzj%qeJVVX%MIaX`h067@S(%xrjIP!O|3uiN5RkzzQ_k zcC^*yLoA8-UxNRWe0(AeHmfIM6 zK3gU{=sR}xYUz(eOe(ZU<59FZLOlgqCz?$utT{=F>IDzQJ4gGs-0TLJ>g1AC%NvIv z(cdX{GF@!P-h|Z(uiwV5yG=^+I5-*}J+iq#nTQrc|7C%Ze?4=b@R5?SXCD+0==+Wo zz7<}wg}J?&ndmrbvQtvAIHip*M}bq1w@)#;?rQ8|d z4zP82%ou2^rnog<>G?!^x>#9S-J6NzQK%k#&J}5MIZH=7Sm{>vS*To*p7e4FJYusP zoa$MwjZ*qvz4`#$wl`Q)ym1V;>ig+D9bp+%VY<@CLZ!W1jO#`EhJV)QW4y(ZHt4-% zm1c;P-z#Ywv^G5``n%5Sq4epljKWLc^oii0pDt%0f4@<7dK-te2MiffhW#f(BL>dp zwyn};tG{WZWUf&IcLa1)n`~j1v)wpd(za+*OM&7pqfWbHFSG4vQ}X39u7XeSxY{7) zUy2^1w!$5FL7nh6m0Njs0FMa6ucoRB=52&>o1>7YJ30XfMys z1*f{5+>ad#LYw-FUnH{mUoeQkWyOz6fTNAZ8s+ld)6RIUB=AkgNtXoQt2>qIP|l|9 zqZB2rRDbc?Vsx{cbGT~6gI^9Q3h(Vq;~b5?3;ehL6qPbuu3P_N7q6By zmzkJ#e0M{K`|e!YB~&nI@e;nqvF{tJPn8VU|qT4F@+!5$RBUPC6b0N?x- zkC%a!B)n#(c$fInLgB}YnA`7QW2t&E`66|0=4zx$stw>YdYd~xrN`y{O3j_yB~^Vg z+q6HkdYSrs>TN15zG|>LUnTN!Qe&T_I;!2|t|zBXd0J96{)ZdFcF(sYRZ|>0L9&#v zO?ccqF2f z6x~j3<-G%%y4*^$x6!zc-+Qb&kF(6csH2vweT>_LYlI(CBCqo|{ppHHMM}~L+QF@v zDgBx!dAF?PvL;I%{-pK6Y7fEZn~rWDV7{d0nXU9-)?7;qXihm2QrA`Yx;$b}Obb1Wtt?){_F%E(`3oe^CLttsa45)1$?l4@J+dJ?Q*eaV&h=M&}pF zuTFjw*eP4jev70tWuA>zrNOToSfQqQu31kN9d&jnw^p6(hU!FVv`UQkOEqs;(;Q}$ zcb-^_-NmK1tsRrD)<3~{E%d1y3T4Y1Cx*9+o$@;a?VN#!9i*Q-10xKuWUIgUT?yeK2WDD>gUqOy^8jd;c}JUNF2|fkUD>F;eeFT>OT?My za;kc*fxo6P95YMV3^O9NTcM@GefC~X3e{hY{L3Mw5#`brho6d-!Vc^S2VU&fbT4;Mp%ZCioBB>vBmh9oquC{Z@K+6LUbM zwc1u8MP}RTL>_d_lGXLkS zou6~DXSadiWG6a5P=6%r_cvO$bAo!AVqT*m8n^dEGE2*4X51)nUoyu_d`ZSdbr^V0BfYS)B z(Z*t;;%HoLa$F#GJpW+}wo`i9Tl*Wkv;|{^+HDp{vV84H^_k>gIai9bA&ZUL3-c;z z(8G^%gH}lcRY9M6-YqvYwu6N%Wk>R83wACI=l(CtKx>!%bFg782{q5pMj|p+u03N- z1E&_-r%kNOMZe=PyNf*0IRIH3in-Ff*!K zr?2flEiZlcX770G0Yqualh;TU-Ng;&4YO^edA-)U}?C$|K^6H-+H3(v6M0P zt^(`!0hquCUnZ5`&V{yDn>oTWwMy<(>-9u(wFs~1#A+WJc%NE3=NXaKX%^lS-crdq z+I_cZ88<|v_BbdXoVp>lk!L&mb#OPzCB+9RbzYP9eUk=B6{5X-e^uqu-)PgGTt`wT znJ>~!x3@*oR?80;ES0YMLh=ee7}&u>v$zcTj|K7-!aKB2+wB0S>8?4Mr%k&B_Ati> zcK#jMG><_*O^`g4chD!eGmRsXL9DzEvperk;mOYi7HD8L7c^4)lENk7WZw?{Pl|eZ z$3c~{Y?Tibw8<{vB5?YER9t*drB6StMPXq!>o3*D_bPDeAD6Z_+8{jmb1q^VY*4s8 zTiLn5I9kKqZQq$3WPx$=K0IbYh?Y)y37j&By@?G)Tk%89;qku!Qya%=FU*5;m{;AA zPgV?{`iq}@0w*&K_t<94Vdn7O3k8?oP+*N4W=5G0S}}c1mrHQ0wjKXSJzi_1hoPZI zphGQ~87b4Wb$6sW+>D~9KE2-);nB+8*0>R7)Z&u@rqkzK5Hh7)zY5=#GeVKb?kqTC zIa}W&UzoG?BZQCtlyj}Mrj9hv?>z;WnxlMafpyJD^TL>90IF|?_VDi-;m%Fm4z_RN z@oG`H_mr4vI>N2jD5dPRf~{2@;Z*jNxIm^M=W8iSGugojMv8u{wsO~iQ=1*0%cZXr z`#%gIj<*iC^jG8bby`!*KWP>+6N&VG5GiRH^ZAZh)6O!ZBAymg^`{mnBLjli7Cy+k zCfqzoT@>-M6r)^wY1B@YjrdM1#9hdv&R%CrEi)d!s_F}~f~@h;=75xNUiu7=?9<|; z)ID;!HccnFHuf8hGllQfKA#*$+s&b4A*G&4)_Ne-32W*j5xr@aN_j-|8nlmj{}{!& zZg`vrP>q!4CCRlinoDz3_+e^At6`k!8v3rNoRDolE8^D!&zGz%_juFguiqDRnHqB1 zM)o3Uhokh81L36P&^M1uRQWX<+$DSjxU!>trqkgMJ?6@`g_=uU4o;q2BcIe@N5oHe zi++c;i902{{B9Z8l6jGGn_;xr!r@%sgjjRV!QIy+04h_BOr6o9o+W#SVA+X`7QRFb z)M#HfzEwOwQC=#I7yTCMMPzvDB_0vBTLz!L`|_@ZO`2mf64CAmL6Y`MNgH&8({2;~ zx0EeezJ6ktZ6oZ^n6MuX*miDE9AjVGB{_Rh+0+Mcytj*vyNH|3o(CQQr}FO|$b*7@ zgpI-vc76AA+3dVt5j(YCvK_lUPl_FC#;e?n9Bh_<@US|#42 z&0tr7Qwfhg%KmTfC3lK`gLY$dMDz~@agBmxj{2DOu~pDMikz$-E7A|xQ?aVFPu)%u zUZ>qOEC#2?ifxl#S5>te;uG1;@00g+_AK+FboSC-JeUrf+(J*QL562Z^FwEp!zNWV zS)Qryl}5Z-c-biKj6~u0fm4|~IyZaPLsQIQz26u8=spXqZ>C_C8%0$#539L$7Iu8< zgJC(Xq89lDkK;pP_AlYbbEYa{kMDlyavG{08LE+@KOCHjQLgQaKBK2Vp>rUmN*%Lv zv0|oT-CXI9f6C<*S@t3B+ab~@KH-O!rm8$PNKUk)r<@wJ8RlitPrQix{IKXB2d5Ip zmf-}!_WIvsgoW;to0}?0fKp*0YNIJM<~zwOR-1vAVV6gRXp=3FTheY)%h&7bdEk2J zP^EX}antUxb%eK1XMRE|YzcSPazlg&e+Zl^(4;*(X%zj|Pgvi6|6AE*xZSO`?eB|b z^0k~}vXrDvEVo@A*fhU`E1%LnTr=ScuF>dwI7fRJW~y4Js++2S~OdcVBubHDq+6%{_Sya8j-QugZ_8n6EqFZ+7>#a zQR(zHIUb+SwPfb=`HHj%-{#`F(65NJixW2-PEk_(*W|vjHulG= zj{ES?`z2eC{Z)1AhZ*MZX$^vxZsF3{?-<^ZTwQsA{r8#h#%J@bj}y!bE@;u7 z;0CQ0uI-~Q0H^AE?7Io;okZOErV38fo*%hsq8htYq`6n~7TRv(%fYE_sya()^_po; z3B5sP*rOjvdsv^%#6%NA&KL77hCY>G`s@(ZSh!T-5lIv&PSzj`-CWv}MO-OGsC|(e z%Dz`UKr5N$OEz68J47WmKUEpD=lfdWr+RaS$7NwXDBO2+gwnU4DgCV8{=6ts=b60A z<+S)2R&c6wIn9^|KJ^#B4NK!LyehzM z1=i=Y%?m>oD@B*liYIK=_&Mh2F@+%1j-xN&0aBTFJ^fGRGXA;urPQx3~fA zudLL8t64^SM)RrN9q)4=?v-(6&@7YlFFTd?fTDk~lv^7`Gr*~^`)=UE9+Se-K8bkd zV}YY_75SYvUdm7=TSI%bO_y9^wa-PYlU!=UIhO{>rNYi#zAu4CH7e|~`3Tl`%Upjq z+sC`-&D@6eWbm#e2r39{^9eM;Tkea@ApWNdVjh>0`ySxdvzOB^*s@V8&k1bj$J1bZ z7JH3s^Y<+0c~(Y%kz2y8RHc3KakcQH@^aYzT*L-&dPlHVdy{vc=m%*&-N3xRQT=|P zbNsD7Eb@jVJ0ahcIVsKeF1bR)Cn_@x2<>fmI(_-o+iwj!MEPBTEjb^YI{xQ9fgQg> z^y{?OcXx@tA^Qs36%GnNe4KlvM#}a&^WH{zLLY@{%qK5cXfEs9KdETVy1aFHm#i%) z%bT%o<;uLZPu{Y^%nFLjSy5bSfip)!_yNk>-t(S_- zcq_8lJf~mUtQnK1OwK4?xG1go%B%!y%@#AtYJIU{v2|TfM^9_utjZZyrY&+N(;+jMBU{S!HYU^0LaVD#Jb%A)gP zvtp)XB^aLhsVNDIQ|8T_Pg%v>VUDyW%&ZKzvdYYXBj6JM|^HBm1ADg{CP%tNnt@5SJ}F8of$J=Mqyr2uBR}k zh_XknDrxhKEdzVUC#7fQ6{*r%yVjfTASEhUwQ1Pk+=&HQNeP~{1?zLl^5*1SWuzA` z&nx80K6<5D5)waSR$6EE(Xx}Q{YNSm_E}z(Rd!{uF=Jj2TGRUB3H)0xf6b{J=}b?KpE!9+R>s<# zqSBScYgb$Qyk=x@!NlCG%*pPl)}uc20jpr6nK@{6-irJ()td?H))r>1Kpzzruds#> zbVOU(EoQeNDMe*@YfFj?(Fk_lMtbJFqzvk?@2*G1HojvHv$lU+5n^q*(9yqVeEPhY zta%GlQ?22f&2z2x3bWfF$}}r2Y0>;SNr^~DjZ?aAxwWIx9Ba+nWDd3JHks3`KQ@_} zVeAnL7RIM4uUHB9vD!DAS=QPuX07!?`i%n}$oQ^ybCk8S$~@ajJKqthnziHxvmZ6< zNb9Yg6=8i>l&s4tC|X&Z#l2mhT{*xSxYhJn)m!1}&%R(rTkTuTprNWRDXLU~qlH|_ z`f!^W6>4+k=?ceeH>X<%x0`P3$Jfo#R&`3H%bIhO8RaCWnUypzDJ?!VYhL`^Bg39qPkyq?j4-W- zcAJwURgc8aTTCra{ylHviuF^_nd$3Rr{w1*C0TD;=D1O+kK$8j%}*n}u7h>bjN)=N zTzUS8d#NI|4|~hnJa(5mZi5S;Jw{p2Z>ezhk55QQN>9&9OiE8kOYvl+pdsN4XIuSl zfV)0&yBU7=>KsgXs$2^*X2zyxq@~Q8#l@q-oxd={h6$|Qu{U%+3U+JFka{b5B9Yv?`Zz<#RaDf2RtW+hQ;SqtwmM~x`OoLQQe zwK}Ja=exvY^x4Xsb%kYFtMkh8i*v2|4QK@4g^nK9haXi8v$m) zF1OPTnir}o&4E_dUi>pt`}Sf!$28I3a^Gi;oT$3ybmgZ^!i=_p2JhvoOY(}=8>(wo zmX&0w@)Q=7%EbEIE;G_Pa6hd6aK9PWJt-k;PSRrQ?JH5HVO15O*3}P~eaFh2KAXn6 z-H1jx4d0aog?U+p#l=^wD^Xsw`?ZQ;R_{8L@8Bj(+kb7U7|=H(HGO>yO{iJ9Slz7m z>ag4le-I-e?LmyZ!iUUB;o5v+=V6_E$h_EEo`6a1qK#-4tV+S*olaVilw@S(q9$1@ z&~w(fedf>*n#}BV%384xwJ3ZL|5n$o9TjI=QIDAM&Z}3Hm3JL*)-8{i$<~NR%_-J3 zkD@zAZAP(|q1eG{ox&1j`S#=AF8F%CdAuLBL(JsKSUc4KwI&?E1bxo{#|Z0NTA$2= zX3}J|peHS5QG7-c8d43K(+iJUh-BoJ=B+KrDJ-};PmNtQNuwisSxu>xuAXYxsafu> zLzoS}IAo5q(jG^vKJvJEp_3c5OOsywggJsodE<_XapV<~oN4LtrQHOkQ|3h>G)M7ZUzo{D#yP2#Bds@{!uUvJo~y6Hx00cJPQx5Z8t}D zKQAf06w}VZXVK-#ua}_!19NzIE%X@pfh8*@H+sdd9USOnk1`nUTf>;dp+q&4tm_ZlF0goeY;WVJUo|$xN9*U68(RdD+^W6=inQ zaz|zqcWz`l8%fP8{b+Vttmc*1%<0kd7R7L5VFTD{VQ${qRe4$q-~2izM=WDW=dM_v zmRFdUQ<|5qW{$ZzW!Q}t7iO(xYLK6;TaF17yCEuW#GB^4n823iNmW&grs?GP$uSd8 z*Ib-|9CzhgrgJnZIdPKR8*0QPrlefwXam9(S|pertt`C`@3dw5N)ZfcP2X` ztWDc1hJ{jlt6ieqR95bL=B2b58)3~wPi3nP$tx+yu@#K2%RKd-VehW864Fu)8f4@{ zo`o~ul?mgZ(nxYOzVMOrBP(Pe%u@!)@AG5>0Ouq+kDSj@QHa2XItO9a^Qd~5(-N4^VXIc z$|esK-W_Bgtw^;V`qUiC+S$}i%{^|6;Faxp>;Sw;i#%B#nlfqd@_OpxYA+cJ7#QlTzlTU@WGk#V^jvQa2&#cE==0c{1jwC1tJ3D~rimv9_>OH8AZf zCb|>WmnB$@n=rlB|Hm9V!Zxh#Mf9yv8CD&>CHd}i^PHh-%}<)Qa4t4?8N7|99_J3W z{y1UI=G`amq9Q}cT`+yBWz@>~5^L_3FU{z%#S0f>PzG+~)ty7uixmrLQ##bDXfxCL zDR-ZVeS2D7PHx^>>+UwpC)HnJd3*gUbE-A`Yph{v`Fiea(`ohl#vIfOeZPutw5T5@ zS^bVwN%L@ zUjEKZgLtrD|7-Te7T@LfQwaQYK|);BF6FMKy(3Gk-E8qq@unYO|(v64CbL zJPXs~XC=`Dfz@b$_4m)HGc8HGu_9URznFugWOnK5T57YHU_fGT6s_z8$Jy4iVUF-n zb${1odQGs7{AOnMp-!fiUJYbxS%+DEZq^d=rdZmgrl%)OOftI6tMFFZi*+56R?+`3 z#rB_oHF5Uu=3Lr?g$+^D9W@~BG4);R@;}UT`Ub8`R{QJdJ}33Zo0A>AtyfRsj%oFu z=7e$jOm7cdwLWS)(2M>yQ>_Dkn}crY;}~K&#ybYyvdD3!^1RTPf}(;l-l*jAoYZ_% z#khX#v#J%<0{}ldS8{a1`|5z05@Gozadk z>zVD?X*F)eO(Q&HwAH_xW2}|c4SVnByQ4hVu#dDpsjBG9v)A7C$uD zfONB&kusMYK}`j`XX7QVOL3cc1vtXX0J|clMC-X;j(Y~v_HWhNoRWOrw<~u{z#K`= zb+R|yBPzskOSl^U*ze8Dh@X*~)OpKdJ=@1|u}sLzaF2;4<1A}Ft;M%uEgqJIM-QvY z^3}f8xMK18btzNaF$u**rFi&Lh7Tgl!2RkSO%=oW?r8_zAgLYEMf0#FQ+L*L<<9y{ z>(W7ZD&SmJ8Dw1%>Zphe@Uzm@WhF-7^ui;!8TY2cyAB1_Zdq9~F^k%hsI_Z=5usg& zj#@{o&mtYSSa;rn8MNm}hjWA)>wNDmYX;q|XC=+cNL$Pk&^MzT(SdeoYiQNRqfl;| zV@lnQ0akW4dgG1Jj+@!B5?`x0ldG{m3ODD&&vLjf=-gFdKQ%AW$SuywD<@|q&rOM+ z-04V6IvtFhk2b$OJJ%+wcG8v+18K^bwKhjJ9(N@@2dke|In%-|f3WrRCOiRrw4%ak z%^B-h&f{l)B3xa$)lIb1zjPe#vTDXThSLOargh$UM?x>!ugDaKT!%Z+(6I^Y=N9L# zE6hurn6%#7J;8CI+Sdo$^NV%QIcRTn^M}Q>+vNC(t7&+q8nEamC}f+{Q?sLk=j zr=hJgl6cRnrjuscG^icgHExHqZ*orI%9(}5Icn>hU^T>`&A*Rv3>siNIITCG#mJZl zv04rLZo+Nsp@|MxKWx1MwyIyB=g8@$2Fwa|ul4LC$Cxl#qyvn_O?J3=+t&x%KALJ1 z7v`0OpA#3{ij@0S0O*}n^8eN_$suoj^ zjY{*^mE~epHs)s}C#5M@g?oHI72DUu3mmg#aUS6qcz!^;E7w<6cuu2x7*BkPdcc#v zI%h>z$raei)58gRPBqG+ZnREKa}2XCo{nkn`srA)+V6%_tvrsM3B10$16v~BJLYh! z56uC1-Z#U^Q*xIXck4xtQECHZyQy{jB1fdvu&ibViqD{VKVM>oD0Z!rUOrmW;=pR*j(Zm z2=iocXBxC-UgGH6lS@ZgnhVg%uGx-|2xe3eyS!XIhqY#=V{o6-0!l`vxR5hp^Q}2p zp2ky+K1o8(eJ{b~sre`fmBDglK;T=9v&K1&por6@SB>16n_(S5>suvr9KFmltk32; z!Uo!Ts^UXYb%eDe4Qg*?prw(=Nb92cFkhR-e}a2(nlr4JIjGpYnP?KUUI;Ai%tW$f znT}xkhlgQ|ayP8IQyoK1!y1w5I9HVx^`vTZjt=WUCiTdC)TezuGJGoq**v-ke}>J2 zDlQ3UMGGN~TY{x*nFrDa>R6TRum{bsEZNZu|AMY+Pb()~dLcoTK>Cu~+%6Zl z3|(<=bp6YzMBn-z9!0&p07g}h8`hCosQI20l@ioXOB{D)3UsB*?TmtTXyG1Z+Q;~1;Oys5pA{;%0Mk5+@5m*}r zl=T-zkag1I2p+0(Lk5&D7u_}rU>%r)7D}e^0T&5@v#Of1vnJChdX1XKZj{p&NX>2t z&VhA^VS=)bWWeszRIr&dF#_#A?`}Oe2aOKL#6JtHW-hB_u_M@f8{PvuQJzQ~EBbW9 z-!qI>ywIdT#r;v_bj@-{r@UM~et(9%JofmylbYevc%|?vjT_f@_o@Wdnqd0%Y^X-# z<-%(7ZThH)H(`B~vJ8P#c5dQO@oPkT@4Sz9@)_DGpY{#wfx*>6@ps^bFjvmT_I89I} zJXzx>gnKl8GM5XKt#O|eC|~3CBUHX#qeK$~kK_WCYy7ZqpT-l%vVN7$M=`I~_`b85 z*C_6Vze`h(mkesP1TB(5y~dlQW(^vz&)^IiHQpw?sVhhRMtv41XznTicV;th(RhjQ zR*fGM-lp-`9JbT0@jc*_ztN!yPDuh|d*JBEUe1PsHGWjMQ{$sou)a&?dQFfof(DIm z6W*xt2H{N_Zx-IH@iyTt%)Om`@BWQT)T$-eCA?kZ)l#z#jqm%A?HD%&I`0YL&H#@7 zuN6bC00I7CZ%GiT@ukAu8m|{Su^Qjg!Uc-c_%Y(-e;!THB!)6I9{f8S%GUUC;UyX` z{~z~#xyIveh)1qirool}+cRLf2&%ONHGi_98jZUxE>Nw;%Y@fyJU?iL%DCY)=kZrB z88n_2D8&K)CFkEHQp@Tt#Nk<>&I!lp&u70S>w@DS>GevYxn(L z5oBr!PF%nVvNc{mjd{MtJ#oy-HQq3W3*-yrUL$g8qH3b5K!Gtji+Q!i_pW4KqjBR3 z=CvAcxSe^O#y!eD{I6aUER_rzG+t87h8i{ga}o0Od!Tm9c(s7p}%%zSPXwML>PBZyP6w)Og)^?#pP62mi(T zZjB!k9;u_)JsQvG&idIJ&z!&o&DZ#$KCE9-t?mDPeOXYh zC73jjxliLKgjZ=iWDx6DYy6Ec=CwAr_y28D(mGoZq#D537QqSXHU5V128|yb%KD8O zZ;xc&tZ}b#4mVMYCg>Q#30gItC>gYA+|IaN<95cz&Om33=6tOn7cI|Cl!uW9R6nyzoSu{AWlo*lnjzJUM<|CaXaH|jpxURGj`?V{|(ig zaYxBC>KHkszRT}?U^s6;K0QzeD)oKEtl(bIcb&^57#@mE9Xgqm0 z7pPI=Ww$bK-l^^XYb4_qEy0FcI6YbcbO3 zMESMMt2FM3nx*tQG;VBV{a}Bfow!R`->LC@?;IBRG(mfnWUTQj$)H-})xv8uUL(9# z<8^0Wsw&{E(**UBpkCt*!W%T+B)n1M&BB{B-Xgr2`RV(s;MRD#@K~MS$og>_FA<)s@qESMe;!ScEeSF;?vsqOHC}IV#`zj=5MHA3 zM&aee$^Y%9ZWe)0OVBF3O5<(9t2N#syjJ7*cSqEys_Vkl_zM<6eHQ^~I)yiA+$FqG zx`S#XSC7HGxNJ(5CTB;q4mF7T%%peBp-t1g726CBlPuYy1Cl5jeF3 zKH)BnR|${Qc(w3ojn@cw+uYv&*NPz47Rdg;PI#QgqieY@lQn*#k@piGjSqQ~d8Wp_ zdn7@=CTMw%6O?GY{blCm8sGN@bDzc!J;A){|L0z#Rue3h1dST^(GS8Qv}nBP2hN~X zl>*J}yv8aMm{Z`Qb7<93bLJjy=Q(aCxKF9$+rwcereTiqU?Um zgEijVow-Zno<7VYH9jPmd9=nWy&`aHf&s!~|ABinp5KErDA9Pe)VNCH%~D}+wI;|A zLp2(&k^Dw(@uW`FY8_pL;e&I0g0=LGaM>3Dq__hh)5(KYdl)?^Z$YSz?J{oHQO+l4b^H1;-toP8n&392PQ^q#;PM83rtxHVp1&oz$K_@RT$<21hX0CNv<@_*YK8$?j0B`}27X}sla zE>OM3TZK1hyj^%>7p}%%hX|Uw2&nUdn>mAKjobPy8h46*tHxcz+cX~CEc^d zTc}p!b_>;M+-{+IjY|vRXHqqR-9(KVw_B)5<8})*{{wH)xZOf+io^eHC$gK!d1t=z z0h>Eli%;l$9&`6U@VI~Ap01q6U;R=xl-*U(g_ryT_x%H}{s&(B|8O<_>or01|9IFm zXuMT;qsD_9Siec*?V{hTapQN^Z@E+3|2sv{swIdN-lp+b;q4kv7T%$8yP&~$*O@eh@h0KT8gCVD+#Q&4qj0yzTZCsbKfV8N7eTd_z!R z{@1Jt;v_-4#ydXenmHc~sDaT&{{RGnTjM?%t{#oMPOyFnaq@qActne!T1!y-EPH#s z#ywKdW{p>ge!IpqMc?_*=?bXvmn{N!7Xj5MU${r(9cOV3vNi5Jn|YPS+r}`j)_CHT zsXYE`G(p|ERLb9|)p$rb^E!=hThF{+SU@C%UyHClqvTR1_j#+!xLX?%$AdX1L}Z|us+|2xL9b9HnT zfXBwnCEvp5@B&+?-pxE#h@dZvj{SZ_j|8HLm}M8f(0>#v1RevBvFT9DADc__O;s`LsYeq20$GjoW>k zsd2lHt2A!6=>O4m|MB;m^Zoe4%7V@gvx(`)!a7SS-@|I(gMJ7)Qo2g%ETt^yhm_im zt=rD5Bq+kCEa*th2rCOS3px%u!l1P0_`>Jp@&XHTnQxPe{C@p8RJiI9;sQST@wl^q9e1`Qmls}<%Nt7v zAJ)IzeplfF8Fi3%mXpg16y)*(HTn5?a+?Dm_n*8#b5I!epS(azE-%oL%O|J5Z8FE& z@k{YUXXIBr;Sa_BH>hyw<3tCO{8mpCZj+z;r@|fb{sQBB#3h&c-rMN>FE6m74#(gE z5xKlTOfD~wkjwl+x;+11feWl<0pI`23zX#Y0u{NuKui7wOhHE;$_s3%ATOX@GM!6# z0h9cyKNFAIBA5Ada^#2Ff(r5i9{KsW1D{-8ARw1Fuq2oH$>{z1liTkDPZ4*JQU`f~ zj9gwICzlr}$j`!}t`2=z|HtCd)rW=N<%Kuo^1=dN zY4;O_ZdVxJ8=8v_`rD_E)P0a>Z<05*@CCX12f|%)GsJ}hD$H?b5xIMk2+GONxk5bB zg8VG_n*4NlxS_%^9}z(f`K{nB`B8BF9n&XtB78=E0^AV3KmQ+#!h$+nfRWnd=ffTH zbKwE`De&dQ`}sc!h1H~>X(zx_@;AXV@{8d)`GxR`{JPA&=fPrewbWq&H{Lb9fCsP1EqHY4w7q7Ff6JEbUF^Tu6BjP_ zg>nB?X9!=DH}I0YgIDC*BSlV4K6_*+3L7ez=+KZa;4Qfe@5lrAmOO@Q;eSjYQHp|2 zp2KJ472F_i;3m2DC~?CUe0TmgQJ7PQ1$;s7z-@95?vMv?cj}?GLcyCBv;^*x=kS1h z4PTO1@D=%H^nU$CRA|v5Cf~vna{Wy4NK3hLm)YjO+!hGau- zKSm6wAwTc(Q^#G^9{9Nb>JN)TcTgBw9)FqeEx8HT-ZNdi&4)yLojgGM8TqX)J5}s| ziwZtE%*ikPPjP_-x%E-uHo1o!hy3XGi}vn&==^^nf;{T*rYl4TpIpZU0&)izSd!cD zm2`Rjw{d|;7I6MwphHG}ek}%+lOJ`J@Phmlv@glSQ$8s=)KqxoCxkcT7kpfJM}F1E zgxl|(u8B1+?2y}6j_v#Z{)YW z4k>jw=d;2y@(aEsJSUHkQ;=V=5$(%EAJ+dRC{%}q-W_;N9(+**ZOCo3Z^&0z6D|4G z{Xob4*HIzG9c;ihI1z!;t(B3z_<1JpvI=S&D;??VsAM-VllaU`AqEJ)e ztgnj>8}jDAg*W79AxC@vbf9m7&&acHi=5D;!mYj~3NHBtt#F@Q|Az1tdHNmUDY^Xp zfK2%Q{J(gtcyu{+IQ|9?9jBroKmSMK0&DVG6YWd#71~!5@8|z$bf_nV{@)AyLR?@& zehz{f^3@MT`<8qO@5qC}hxNCm!kOqW|Ig`MUb7V!SdgEN_BQzyKNsyC@>9^>?R{MT z@(sBCsp#NQhZ0lZlh-d3Qx=eK;4yg%PxdbMUxz}rFN|{@JwsfeAlF|md`&)sSLDw{ z&W3#ca-9DgDl8Dxk-rc@+6SgnBY!tUCyyL4P=oyMkz<8akiYdZCr|Dof^71CM375v z;|4s12k_nb|8)pjQ3n@65xECX$lr{djNCX`+(16{{?GqGVLdHq??6yRzQl!V@(A9L zm&obJ)3JTO{#SIkU?Iey-8ld=j5M2jy?FW{^j;-(ZQh((mnD|A}Ap5 zkh3J;!lMHp_ur=wlpGX>{iox%;8OM!b4k8I&YE2NjQGPQN^&E8q}cy86+VxkhTOu1 zTk<)4Oa3L~=$B2W(n0&#W#P2oqF_>ouOMhn9-#e#ds_Mz#N zNuQD52(NaNyhe^SdcXeU_LGGLb+|c#9P$o9uEKrtTO((A=)?NgFB02nbyzs?nA}8A z%8r~&;RX3|ea^W5N-9_gsuaEs#Y(Ng?)b$5l~{nvjtj3A%fM^Hc>z*poaBPS+bhUkz`A%Yj=34BeS!7K7p zap4Vlf%aiTg%Snr!_z6K;W~K(x5zvAoO}znh40V*XJDi*bBAB!97$QMKVVf}5XU?WJsd^!bBK#)Q1p}k2S zz-{ss-06K>|MCqOqu^18C*#5ad5ZQ+@(do4{{?cAy^H;qqeHqcjN5MwUz1nxQsFiE z3Kwq3>sO%AUaue)-IhE;d;KHRscA5vnZix-=ObqxQelgrg~A>3mmtU^*Z)D>fUoc+ ze0To;2Lwgb!9Y-~@Ra;wy8xZ4};;za2SSa&OET*54J= zxfF%|Pro65FM>?+B?e?Ed_i6z#~FOMzTAEZf?Vp5!F}?NBWOupqWy}zhQ|j!?!OI! z(u2aV|2lNY$hB9B#Z{0u$SKJUw6DmmSK|ENQelA(9k~OaeUzpQZjcA?1^EhYf0WMu zF$z9)kpGQGKpx|t?^on4oOMe=0QSFju%ueiIR-x#TT!Jn}6(7`c;p@0`@;9yEE7}Xl3Q?}JVeft+(G-*-o^g&QHb}2ar-?BK`D8J_8EB$FUX&R zoRU1rLUCsm6;cGXjTq3HdY(GlYEQ@wcuH=;*W?R$DSdbTN1>4goc}#|tMD!PJ8@_Fr>0ZT;-3p< zL+Ae%cQ*UX^pQH~V37N8i~I-3S&&C) zZ|{7(|NeJCQE+#K@%^J+iy)soM*BeFEAs1*6O$()f)XlZ@QnPIo+;+CATQB=OEvZ%uX9p>Z?+$R5R z+Iti4=RZIpm=rYa&InqOCukp$XYhpl9>~eatD*g{{&Fg85VR)0FM=xaE!x-Q+UvxW zHRLBFr|W%O|MCrJqQjOtSaAKb(>Z=Pf(&v8?M-qQKHt08e~(6xy)TUWZ;1{Lc?9>! zpMaczJVW~>dGR`&|061#ji7|QLQqP+f#>AsAZJb9qJ0@sp+li2|1$(Nyelz&6{^g^Vg_b%L2-=d{2+}@3 z-Img4-Y0tBrT9+Q6o14_wP z$jKC5e4ft#-#}1F9byDk3g3`_A2}^~ikwcmJpapr_J!$O{uDto@*F{i!Y%Tno+aKB z3-WM{Ae#!(UGkeF$S1Fm6DWK|Zit+I|5KqxP@?dR{0N@6HI? zP=^LVjlw(f6Of~QaXOV9a`ZzV_g^mN#yBkW+wVjKS>y)V&&e&gO@0z`Tym#xFZMqb zJOr)C19(Kff+yss;KCVsg7*0r>HMFeu%-@wgrJIijrKKp1#ie7gPd;XEum49dxc;T-Ts{#&2D$zQF_k8{0iTmELj>7WSfGPLZo@tDry(aGUmh!d^>V53 zFrvb<5tNX7xNxfQocy`SS(69IDTVLP|FTe1hvy@xAzvb>Rrr=XL5}|A!>R1&e}$mg zq@ZaD+$4WFg68A}+AkFDkiUA!8P=aig*AeF@(R8r|7Q#+BHy5WOy0uN-pBPX-+=#y zpqx5v(V-yM-Y8akO|HW?S`{X5ZmgGycUxkW7Onw=HQt}moGKCl9S0bl`@6P`bf-33| z!#CugMo>$hpna!s?JJY147D#KXf`eMfA%AODk|I}|0Z%4`-U!BaQru~Z;sIG8>{CA#>^S?y}13`0z+vIZ$$Yn>4r|{sb;q(sfji42Ea1azJ zJRyG|ax!usIk|Ls{+ETdEa3b9(-2gVM+mAF-jJV(oQ^!q5VWO&bp5}kPw0sVGRRBh zmM(ngSkT)% zy~y#drt^P-AfGx&Uy@&rpoqLcPOR{B=i~ir+NThd?+U~H_kT1Cf(nI~58TqxyG083DgqEVPAiu%+;=&HOgCJMoKKaqeSqeWm z|08Hc9Rheverp7!I`J$xQ?W3SW_*ft+~nV*l9)O7?|u z`$^Bp&q7c^?jvWd@QVD;&d2$GLxl)Ijlw(fr(rOjWAxBrZ5mMnf2(rja1kDw0 zlPAb=$s6Q&@ZI@e76R(<4+vV3YyTz|QKayM{PoDmrXFe*g7Rr$=WFt}AgCgDkW(wX zA-{CY>DOOJg#bZYh3oBfjz5F}8RRi?Ooh(}AJ)IzexE>)O&tmZISTj4zlfZGyhhIQ zz{mY33(-Mg*ncg867nsAQibQ_KS0i!+$?bZFRx!1_kT_Pa|AWyb|DsHtMD!PO`ap# z>))jFzlWgNH>Yzf-6X#ig68BaCp;VbfYh6swO;2cduYE_cvw;43IuJ)0|Ye+@5n!i z9POIvR4$RD3*VprWx=2hpF@yEzCzGk;WqhKkmF9gpZ^F!-lVYifV@S}iabV6r0|6N zyF<>f{xT{g2+9?{CchQ~s>oC1)CzBUAJ@Np1O5y_9d*bMv{ktN-_toh>bYVU800x} z%)N{KCkyj^VcdT=Ly%2gAjna;M}AA>1mx?t;{3n7UP0VJM1C6tCFC^*lqx(Yzddr+ zAr)E#l?t!Pk3&#HuDwm%K&$XAe0To88-n!jOy|--&`jYb`8|;{C%2HZn0kNyN5PpE zwEH2*BVVAsuka=L$;gSw-7%+MfAJ9u{qF^lpN62EJiveog_q=KAg3ODSpRbStq`=K z4$@ol$0BG;o+3y4?sO`p&klUte`h1eJSYtNZ;c>J;S2JoBF7=Gk>g(9#s2rH@HYrr zl6MGNDLf{BCUR18?Gmv&vhULQUlt1L@O%W70 z9ff=3w?Ix9P$5OoQsEK#Z4i`@7syE!o(tcf|8I|=HFc;ER4TkCKMpw!d4rsG;{E)~ z!gf;7w7Vfl|G{)Fw+Nak+$6sza^~d5+xs;!tiQ#P3cWkz_d}3Jz8He~zkG!+$xlX3 z)cd&pBwe2WWg(FTod3Uvpp1Nupj_c=@*g9oA`cw|)l`t)kl!E{Pog9Dk+W5}{-fy> z-$dl}|Nn0)tPo@>d`^A~49F%=kmD%a8@*rua{Ju|K>>Bh5wuizM1FhZB;+M>(nBBi zpDg5uh2D=t(3*UMpi<#A`Q4DykavB~xc}QD6o&o3CBG+v^zC#m^>>OjF;lonem~^Q zw{-qD5wxHV(jD@X5#*82k>e|Tx%2V;JMs@>K-y2IQ?N#ku5cry!p9M0k=F>CE8HgkEOK1( z200#lcm9`!fI55yK`ZhOL6O1}@^2z1n|i3}?-tu5pB8q$CjTCSDslrkwZa?nACEcx z`s=7*A!w^`{krKK-{AS;1`Ki=IVQOapASB)f4Ti`f*_kZ1nA(9FX0~fEsztCuh4#Z z;N$*FP>2o+!~VMsf)etzJjsyf$jQm?fSfh?`rY#Pf2dF*s3yNNf*SG~?OXB|z9l~a zIr`7&{I6e%lg!Vib3B8aXhuFqdxPAD zTjVc9&SK}|{rA6Wg%0+vFuecz|1=ZslD`;1K6!xl0r?8PBLDjkK`|9#bV$e(ct(B^ zatiVk?bqZvJglhjj|ke3uhF3)FX0{eYmlR9XOB-(?y?H)b>aK-zbqKk;dKbI$ZG`6 z$s4#${s!c@6YuB0LkDkC=m-5Cv26nKHzR08K12J6+<+(K?-+81^_Nj06R$=sC$|u^ zCVw9WRFON!i5sXD-t|7Ne>pdETwqHbT)2LN>0EvU7dFV3Xm2WfzIU{%r&`%#Z>Oj|Jr-SVws^J*MtE#$*)DwoP2@y3vw6kOuhg90YToh(Eooy#ejVB z6?{p49daUaxeMYWdcXd1Dx|nTL7u})@?YS>HTfFtHwteDAJ)Ho)JMHQ-0_w=R0z_3 zX}bNS&&Y3v9Fx37j&CC>k=>leoTACuo6 zK`FUWiYJ#TydXagIpr^f(?@C{sG<(iH{^FiP)oi*PN#6~C|p;b|L=*QnJmcjKY|Q} zTjcjc&Vt-Sj!hoQf=h*y5#*EWCyPfND11eJ8ggRtKny6<5-Kb)(u~|gP(dD}{hEAx z7ctO^{IST{jNY$*x&2ZEHPm5^ppN`W2-0peT|+r?bn-RaIP_uv{RM)o!$R*BI?Ty8 zaGU%*L!QDt@^>RAAkWc$Nxp`M5fwgwpoF|ahm^d5=j0zn&YFCS_NDOs`G59)@u+L+ zP$Q@zx6r;Nci>y{&mc$t<-@7$=RZJ)*`(0_V>#R;{}O`c6`uA!u7CLk{3e2O>X0L-P?+(R|25<+Ln`S1 zDK5NHcual_f>Lq=Ihn!>`0o6FM+BABVS%7Z;T!Tfa$0f+Io;GlO%}A9Oy}}m2%3?5 z2r?9Ik)MQ|1-U=w^y|+)Vxj*|i2PIp`Q%FsC{Xx{+(S-0_^|%v_FEw+p$^hB^2Z^l zAdiu=R(N&bVp7H45*@{|Y(UO{Y_tBS*i!i~Vm+v)Zsz|t;kyhMG8;IUxl1Zx;+1D9}xRKmj#^vrLW0z1XbiSAkGw`s zK<=Uaa`b-v$?Yc#5q0<+f)a8cL8-!X@~e@vKJ;PzFA-E877n~7{|id!knRe@`>+2KkPwuUuMt!zyd=L9a%%D_M9_u{@Rs}p1Z~MTXs`XsbSkCK$nS%k z(4<0(AWPv3atA>Ux%NS^CR~O4!uRL@haqT59Sj7m6dseGiJX+&LQXdEe*R^lm=rYa z2?#357YM2pz9C;CrzLlXoMHWSM=A`f@8;9Fd>VpgLA@Ee-VOw@(4MB!dH72`!7XMye|y*uO$dd6rPd47C8lZhMe{F9OwUv3U5NthP*&f zqwtRW?a0x7bvl(La`aG9FxU}fk#7(*SGY}nIdWY1?)={($fFL@1M;g7v?A9o6Z<|= zcrx`+`x1h(X+fJIC|CHJyhTn$ZXu^WqW9~sp~CkO)REf=+A3V1P3QPJ&k6inZSQEa&m*kH?PDCCW2#Tp7Jtg-Ml#^S?DHL9kKS|_-T1|yHf;I|o$2EArPPCnlexeL`-BC}dQ~5mb=7Xul@+ z;T8G6AZJ6qLi?~$6gu)ZBS^c|bP8ew=?XW<-+~-V`2PH#B4|z>a=1-?34&bm674;O z2NUn-{~ZWgO$z<5-ytYcctZXzRImcn^Xq@(w|@!W;7UBc~(RJ}egX zw)b)U%Qv7b=)XRl*dd=5bk`4T~`!nfpKLXQ3$)2WP+GlTEW|FU3G zhp!@NPM#rXp>T)%>&Wq@9%^d@`P0JAm*n3Z(;fur#EXm!=x2E%dgrJH#NZ*j( z96>F4ikwd2nt`d5=l@$GXeJ9d{}%`{6mF6K267hU6>@CyP!?P&{3e2Y@&-YH!dK+C zLrzTIiJboTe~w(xGV(hhs36xrA{N(L;T8EEk+T`SU;lFZnFwmAgY=I4P6*O&Gu@U8 z~vcSVqOSm@nF&|Kj*`Q4G@k_X7~j^N||52*0_2wIUx2#OS*klzbA8F`AF z{5Ev{mxVQTxDSFV@&ZA%!W;7YBd6Q>c>nz`4j^c|D~#`-o$J3jo#O{0$RKZ!V=8=3 z{@@TnHWjuAaun{7pNgD-e0Bw1y$TN_Dm)B93Au%!RN*=KBapKuw~COKSfYZ9cly>3NOk3962?4i=55g#r~6pc3&9x-(MkUORjxX ztZMC;!@2Ccz-Q!7Lyk#4`>6c=pX(LG1s3GbK#)Uj;li%Mee!1^XBkq#M$k&(G5K>5 zl#+YM$rN6|cjx~XAgH7cO9WL4-;louIW2jNoNnr&CJWmCn$G1*5Hust5M(IaB7Yfj z7Ub(Or(b{e5exl~U-DNV$S1Ecpg`d(@>d}z9(-8;a{ILiN~nYMjQq6-D#*1f#o}En zygKl4|GgeTn}foz{|p2*3h&6@h#c*9)2W;zN58&{{clj=%?Pr{Z3N8~Zj-+iIWD<} z9Pf5?{+ES-I=mf0EAjwAk-`)5cOfT}F3h_kXBxIf88R20@O(J@PA&6OeC_vmCu&e{%cDLPQ-t zfuMwZ_A#-|QibQ_pGMC5(1-PJA*eho9C%IsIRrK2HgZ~pZ^^&Z=ZyPLH>Y#yA!w#> zll-d~(42gUoQ1+2lg|HNN03JyVg&gLUy^?dIT3k=oOtKr{iDf3x+@ItKTZ1%f^zaT zf(nI~F=L5KJ|9u3l$P?s53QwjUYWG4= zHZ5ocf^vng$?t=lio8NjeMIlqUqglaBd8;95VTdee(ZFPABY@-e2W}&@L~PS?I#O! z>hNF$+2qD2#O`nu?vbC0oZ!I6{bwO)c~BU(-vS8vEg*i9)lqLccxw-Xr^$J{PD<{lb6U@NSEh-S#V?l=l=jf z9{C1AzQUK}PeD#Z9(D+dsUSTi|8oT83{!+3MPU!3UA5J!+^Hr z3*=~boKB?+pN-zHf4Tjhi6E0Y1n6Lquiy*v=OM=-Pte{y^kM(yDENnk-d~8IC3%VV zEAkCICVwe%Qu3~EKkomG3i?%;OY(~lRFa!$UnzV;{%Yj3cck^Zy1NbWzxCOX&vr2M}bDcgUHO zZ{hC5hxz}MSnb}VplLJsirj=p`&sZM`2wDhJMfg; zgRjYhPviVwQelM-4S5W2$y2y~r|A>Q;WP3zd>&GvLSaF^fqUdF+$Z0{BXa#SVhUpT z?)*PPA*Bvq#bU|HO|&l*UXp(eIrY^0@Ba|AnHF~5lD7!jk}r^>-FZ3%4tz%b-7%+M zeP(_Su1t z`)`XvaZnic-%SxzlE){D3smGOd_#Uqr}+Fhnosc*(7(f|3sM=odv`6Cfzk((k&n=9NV ze-v`u(fjo;x8EE=9(9l&kUs`NEAj<$B84Z1KI}gqLD^xUcN;;u!q?=FM@~iVBd0!s zkNdx&!jloykp~FcDqO$obdJwOjzPXej(Jx)|I5OhIy@agHu(xcj>0|i=OQQA`FQ{R z{{s?1%Uxl3|Lr{@e-VNb@)S9#!gKPMg$PC^*#N?FjP7TeSBTz9fGSa-xa%^S?z@op~^UXouqjlx^U%mmqgdmeTED&TV zd_n$oi zsuaE?3)&qK6q8qIpC~*dzcX?Q^39mjufO#X3;pkelFt#eA#X9DM&TX#J&>c_ zy`Rcq{mbpQMUXxej^GCQy%1!P>z@;gYp!tnz{mY}Uj(@ag<${&f;@!>9#MQ$M{ zy1tA3pHSgs1ZCt41my}}lb?#5irhg?eRn$l%R)mP9*&@n+(Xb-;rj1Qr_w`?AzhyT z0|c3}Aiw{I&&eN+Ae(%J_Kw0m^6+s83aAhxXsPgs{E5g($W!E`NA^(5sc;U0*5o;Y zN`=?tPeo2czD7^I;U@XtB4>W+!}{MKXmMCLaEClX zkVoDk$5;50{5gHjxc?$5Y!MVIJSBet29%TQpT|#8g_kGL`Ty?_R8t27K^uj)|ku2tg+K0zsC-7v!%(jzjK*2y(dq_sRbWK}&KE?NpYK@0L6LAJtO^7kRfCohMbVf_V1D)hc0zYIY!`33_@6rPcP1UW_TL9%$uMxB%*S{e4eWUPh?_&Rb3PIZcKb=bxLAt^X^3Ng1B3~e9em%$e-=@Ns z5#*A)2=WvjkYA0Q6?uT1C{z>@@^2z2BaaZ2D|}7<9pqH--T6O7P)!}AH{?G+P)A-M zXG>nf^~Ge0Lv4#7V_MKQ=wOn!@HzQ)$g#<_FN($JkQ<}->(8UYFAx-vFA%gOci;)R z3s1>?_)WL+$?mc~^3%Eh< z!Y%TL<4G?Leb|2iI@pJW-Xpk6{wM_bKe+ERs-WB@i-~V+k zf->?9?Q`-1z9xSfaw_sNM2DIRHM}8z7J@qR2JN@x9bEt4(op78zo{}l)dsDq6TOL7+;k-ru>3AvB<>BRf_U!jms3Yzvt1g*&v zv@gjscuoE`pg$v=RcdGF);mv6u=IxMJz zbcg&31bO7fe~C5ZD}1?kvHw1UplDwhcAqv!P^|Ej{Hw^x$!+8m*Yi+}w4}nf5mb}A z2-+yTCI2CEw&Xr?wD7*uxs-(&`Ogq!lCKbCDSSbG)Jw$;JMi84KS7X79i;o@H$%{p zJV(w-;qlZ%?bi^LP77LzpiJQf`E8L?l5dbx9nt&sx1qvsBd8_s5Y#DLv!_#eXXMPt zHT(vJG5E0l<@S>Wi#q%sf)?a61lbCA$?uIE|G>xnXCf##C=AS8F_>DIl2Bd@xob?|EZBEJYZ3HhdPKkonZ2!;Oo+M2w@1xoTQye5A&F5HmMzAn~8 zdw)9rTPSR)!|M>FKVZ5oZM2_}dvKHdUyw83`FQ{R@A;#{VpkaMzyJLoxI_LH1bO5c z+WQJ$lD{KFP(+0aL9xP9^7kMoCvTBcC_F5w@IeIC9+hCa%SW%a*Vx;{U;07 zzA$dTqb?K|UXVu!vK8)<-wZiEdDi0mA6%~>F1#YYC4yq|3Ij?Mo{`@MIYmf?4nb>$ zSL7ywHsr=P#SJtH@8G-h|L-D5d*E~~Z3O8GH^}db9E&_a&V1^jCJXkopxpyOE_s3= zPvHUiiO5-zug9Ez{Y6JC^#Ah-@&_O&Bi~>^xx&}v4@OQk_^|%v_S3#4=B%a;(i`&A z5Y&-d$k{4ff6#u4$NlFa$T%nr`_Dy?sqi`ZpCHF3kC5YB-^Kp-sPF^?1>^;SmI{x^ zpMso(yh2X;AUglcLQWmdMbMhOK~Smin*48((@2-+|1E-AS-|;U`j-4z2-2PXTn>&yk6+Vri1$m72w!&TV z&mzYs&yf=bio%Ng3kZtI*9b}!o{@hUIfd~3`M*NYnmS0Y$iIr94S9>4M&aGW`}zMG zg0zQB=TiTUSk=114e}N_7P*0(`H_5Be>N4qjUbnNjv!Cr0r_{3vm$qp6ZJl>fB6QK zg@ihM4?!8ZkDy%PYw{l=r`o&Ne=7vl`@*>Wq&MV0LQqGZAZM#^{gmkx|KviP{|zb> z2r?BuC;u4+WRtIv<0#wWOAN>( zH<9Bjd^z~A{^j=jbp%D!!A4N5@RZy@PEPJ2r#SF&|H(pmP#E^#Z4p$HFA=m+cuRge z+8w6zvFUaqLoRYjlPDLKd!iEZS1hwQ_1a%769y*=M-$TxfT<^vy z4mE=cGf~hM7Va+s{E^MI9c5pqSi4`$XXxxr?0Q(1-oE zM9})M(0c^0$j?B~hCD(0hCG9JW{9L07mz{$vcuBCn7$C*Qzrm(Ks^ zBFLo^~GmI{xA@6Z3QLr_8; zas;L1B|IlDkh3P=pnW;PbPzV6EpqDzIR7uG@G%5AA33iruBjhrR9gPc{UD8%Gn zMo>!bAt+OLLEa*#gzwJ(0fH*(AbmsrJp{GnE97(v*G`{IWvKlGL9=N=ixFff+#>&_ zmx(p8AWxBFAJO~u=ThNl1o`ASf&zuF$bTI78Km)lPkGU{+U1Qp~Jg4PPJ z$bT0(n*$&B-v&X=L1EZ`(mV1wg0w%H%%#>MM_0H(e$SWT{BKcVi=er}ZSwnLKrXrd zL$M}2g$I8`=l_QwXhj_i1V!W)JRv_FIT`r^?Q`k!{4Wb@S-|=K(Fm%@eFW7CZ^)m3 zoQ^z<5wxX(bo~+2IX(wL26=%TQ{i*+KNmTnW>aBHIGX5p^h!dekr;EhfJLo{-<_MxuR6zCrtJ z=i~kNe*`-U`K~ZtPrDjkkROi=tjVuK`;y#5`-audLQX(_6?{p4@!-SyTT$TzTp%J}!ejDlaDjw;3s1?9LQdBE zxc=oEaE3xj9RmAF<94XYTYPTFlbeXeyCpyAZ4VuDj5Bs?OYFb-{lx_q`@-1JznKVf z$%Ffe_DgaT?PK!b*6x^>lQ;JZMbMfG`Xj{%EAsfY;)hB@UgHKj@)bU7$dgZ6<`^Lr zCZ2iRuh1=`2t3$)M4 zW&4smc+iu?{;#Q!JzCsRLvH*pF$Egx^2wd@6S2Q__Wu!Xl5a53`J?IlAEBX59TvE- zN8UY9JfRi&3hfi}?uTMPg>-rTKL;bNWdY~^=0V~D9r+p;&>u6Md(RQ=E%FrYZSpWe z2cHV@?Zl&Ak62)V z60VbXzrdOpy_+(1Jf;B!ar_c`PK)BWkAD={F8Ji>)-a{nRX27K}q?N{V8v`>9H|Ci`c zP=^zLO+31qJorO#;f6fJ=Z?I6xp*b(kCitp-apy~BQkb{aSdt>24s=XOffY!`TSHo z3Gx-%ugIGacaT!SLx+NViwo4`1=@GyGgk~qdz`#uabxaj!b6h^778}G{@db?J@WFQ zB4|aP-a)ia$XCcOgzwM)OLVBH!xDGUl5fynd;IjymKcyp?xOvC;{E*lzavJvm=yZo z{enB>OSnrO!F}=s9*}2)59@D5g#sNS@(P}iH}I6agXiSh9mNe7y^rf(z5xvsO6o9& zSL6@CsC7^Xy1`%Xs0B@ZhUIx5ugEqMdi&YnKG4z81HpA=I$BcBQHfB%OH zCOVkp7Th9Vz~|%+d_nHP?a}-7C%0dKfDh!=%RzQ6@y@-4h1Z*bu)`5Zn! zhtB^gf`W6VBi+C=@(R8t*Kq?IatrNePm%fJ{iFF9k+UoG&!_)u36IEg_?p~+cjPNv z*!oj>VUZt)=-^XfjSeY!iS{+Qwh@a<|Fh`@YP7e>b$A$1A;RYsxq}NNL3Tyk;?%Y%jq4@@!29za0B+l`}w~LBXTAMO}iTID%>O2 zo-gj$C;#CKga_o^kUy-ygbMNwGV&OAP?38#diXd6HTnD~;SKpQXus`!T>tV7=waLF zPn|we6Q2$86#sGgoIJa|xUfsEJyyI|{Jo3)7yY@o;BsFW@5s6xzCtB;juRKi$!pxe zn%qZzMQ+^=zyH%vVdjgGcH}F3)(|M4T=X5W{S5LF16`1teZ_!8%J^AYjJ@BJvg5XY8GLLhAz`_g{q$n}foz|H|)+4jsAqL@}V*Urz6A z_CKP%N$$ff^40&~{J)?=f(|x$26xE|xJO>W1M&@g`ImJ5?@)-SgMO{JvzXj~r{oqq zBe&s&bb0=FQCQ0Y&i_8VA`jp-`3l~U$MBXsOi`Hq)pRah%)LRLqrFA$qy3z`Kzo}! ze&hIR4>gAh*$>2{_Q=-=^2saslHA8vFDvpI?c>q=^)I(ygF-?bT6jj@!E6E3&nUUvklYIChbKL(H6(T&k1-bkt(HOayXh|L9H<=N+{3bIdmtSP2LtMC}g8b&wSWV}6b+&l*F39z*SadFVbB<`gB+t-3 zjHxhxis+D&$LLUyZ+|Q66PZ{!qWh`t@f}p?TX-&@_v@_^j|bdDjZJ$&Wp$8gm@-^B*qU8+=&* za{I}GPaTeajOef=7kAMA`$KYh12MV0f#kr){U`4rJ17i8|H9WUAMYS1kAEtBO@2%z zoS(I+>*!Fi3@b(&P+TZ?dj7wKJS&nb@KkgrZaKlkO(&z@!fH(OKkj`z^@NGsS>xa=EtLLm$?^+~3||p?7&_0XtUvl3ZRmCx7KP z^l>T+@{4;P_urZdZ$gKX{1SLYeighXzf~(PydnP~+BeUj^M8d7Ep@o`w401~(2;-O zUczbHNiKmGCa7i7k6Gb5=H~+WrgxrFs`#zIk9M9(6{A1|4$ptKlX2 zu_ue1iu`zZO>VDea5>Kum*WqjOqv7Sw#rsE_p-}A#!~3tF z8hA~947?@RJTah-T!(MTPYO}c&Yv#2SHg969HD09@=a%u%c(TUFGhZ7Q9;h-oLtW3 zf?Up}O)j^kL;faQ*cHA%|Ig15k1n7N@{umd-{_CW8_5*D4yn-Kb4ecj=!7w-BG2x0^U-T^=OMo`dP|`0o6le^Jb>_T1?loA|7g%K^>Evse7;cmaca1GlCgYRL!0i00FRCI@7b`}pjT z%K^FMC;p=tkVk&*=>7T&s8C`+OL94&h&;pRm|PAhA;0?7VnFHO!}^!o@0d&!a_Z1w zKn1xRP)Xk4b44x(R3G@b|IT}@xbWtnFihel@Rr>CAQln19FX=rT0{7(llKD>`+r6S z=VCD+gFJ#;M4sVuOfCnMkRSWzUll+9Q!1R<7lyxb@(2Se$mM`a@&=zPayg(nrt`m9 zU=dLV58jd&7*Izp2c$ip)(}4HI~VUCO^#@`D~u07yW}lcMC8}NE%HXLA#yn&o7@ip z4i)5pT=L^D!6G6*3m%ZqKO`3Ql3WfbjHr;|b4)G=l#n<7E(Vm68*dk$lSdd(A$))S zmm?~vLxay1xg1bU9=}6ectc*o+llw{Ut>hwq|mQ^c_MlNEh2o@$>o4%ms7|@bj4k#ke@Hr-z z14{NT_TLHrAugQm3*-Jf2cDCc7*Ihj2ULz`89Bhe2xLl$>o4-`0o7g103og2jsH9Uku12 z&)@;Mj{z;G9`3eTG%aWuKF8#8KneMU|A{q3eg!-yPsRcD>#v}Kd_*OAgU=PY98gWZ z{UFv5`TR2B?cl@um)ozDi-uXE+TR{ zAe-FBXNO!4$R+nK|5dU7Jt`!Zi;)K8=H>WlMlJ^wk!ScElgj}m7ts0N{iwKbN*!W& zPVQnr1-TqhN#5XdC0(BX<%nuo!1@20E5(2|pvEr_dc$F`Kaf^i2A<@>L3SHk~jEVk;?(q4WfI4zHAT6O65kBkWazHck^KKB%#tRu#xa0=HE%F2dnv=@`+2lSxJLGaeZb${| zM&iOA`RO+l9*~z9(2`sZC?e1BImX|2=YKh(ggTs{iwmdZJ_eeTcXADp%K?>B@BjQi zKs7DwzLKfQ?VE`KZOG5TKwEP2O0lRraxtJ`{k@nL5kBkW@(InzPr11mkU_q}KrM0? z1DX#$TwiWK`G{=l;N!DHE(heY-$D$?BR?Ml4Gw(Ve-TEsJSYs?LJlY*&+s`Wmjg=3 z&%YJc5P5csnb`k16$%WfAeRFw$s2sG$mM`)^6b`FLocTD|D_mdOC1`yh{)xDw3pBt z!e^aa4rnG_p8qfXe{|h(yc>O0;Qs*%Pk;g=^m)hw1p^caSTI1DeiqH@ z-F1Mv8{PigsNFScaUxzIXw?BKM(9e!s!&9n;l->)koxFr<8Bi(MmW6LN+ zAbO}45&VWG+JXm~P#bOub>Rcqj=dfNmQVuU^KdO9cwZA8!rPiq3b%yDg=h6=({HXj zPB6d{n!-nq)FOf()*Eg>I%;xSr7@TDeNg-^4DiuqSV zz!D1Jk#0BOmQV=4c2H{weohl@y#(ujZz@&Y#sEvG3m@oq4{ix1@SU30kaOuj-u}l) zVCVvQ|I22p#UD~c0<0d*Z-DLhynY)RT65#k87eW_}FR)ZV7d_JbV5F zh2B;m`&@v%HG|*$Hc6-tKdOli;Y+I_c#%+Ee`5sZx;=qgLR0wFCueW;wJpYQ*`~`LZGV&wc(af7e3JK9^4X2;HSPz66(hYT+vL2@Kh5@;g--CKG*FD z+!C6qyY>Hxr%FaM47i|~F5q)3BDf{wy%aU1+of%f-8A#J1K!TlB%w0=oF-a@`ybR5 z5!@0A;8C%i)n5YvyG0@V=+m``;Ab?^7Cg{|+Hgy#n|ogWHvI;=V-Eu?p#*;Td$ow* zyPD__-qwWD4KL=OWi;LhN|ThTuDzX!ZB7{-0VAVSptRz$4vmz%8K=e&eXtkh!h@k7%YX3+Vda`;e}P z;FeGqKG5wR+!9LQ@zo#FB0}Kc4~h@rHBBgmTS8;_T(>81O(^!J2<-b|Iq?jBRDA)D zG@&Kj67u?}A>A$&U$gqN>1Vgd$AIxMNvI58saN3xO{fO9gzB4~*Z;BC$O#&ofy}F~ z6%XMzUnd^Hrx(Oq@N;hv@4!1FUta%v2ps)u8IZs$7sUtg8*dgL!Y6MPAHmPQO?=YF z`oDdL1g02pmDjyb);K@hCTX1hC-hp5Ef_N8x?5pB&4}m>*`-bAm6ZqwO ziud8?eDMMN-~+{n@KX;FABnHm|5qL^fe8jQ4~b9VM;hXDxc8sM7x2p`#8+FMJ^usG zkwEEXRushz@Gd@2+=rh{#4GT_XT_`Vo9D#q@bj<9Jg>h70=>F8>p*b; zYspjizSqi$XYixy3;0wMTEd5)(AR(O<=fA`qT40-p>uL#A6~vgybKT3tMH{JRErU? zTNJ<}-EP2-4CTZj{PRcu?!nLgot!v7 zNev9Q171xNO5v8!7(UnS3B36)a^fj`^@ZHC`kNt8yCDM>@Tn%Wgj+)1S=5kjm*7|L z`hcRi{oM2Vx9N9kj|9pXa6!EakM_tTtHCXy03PXfW5bL2ci{nY;&3C7r+DmE@h1GV zdJDePgxYXRs0$yQ)z|+X0?h+*;sm~Wq<9}*dzAPP-o3jvBDf_qK8yALTz8yc!0M2k zU<&VltN08)RbRmUdq_e{b6fvgM&AEM5$Sdbe(i{y*oW_ak9Zk=QN0R}6V0fGfF%^b zBi(Mmn?E8a4&kd~;!Sw%8HH!>{}J$R(MANfgu3v7Zuj8JXUd5ac=BxVe&JdD+w_}g zV2A;2O(=z1LSy(`wn~N_WZjVXl(_u-wV)$+Hgy#3m@oq4?g^qoH&6uu4SIrUmt;P z9?1R;;r_j~h~Spc7(UnS3H<0k$?>O|7xix)@cKVXV1@w)mf{O|s0l6MmXJ3<4e54i z?K1!Tf0YyX>p*b_(yxk_;S2RDJkf+|a7!qFNA}mL8VKCD%f2Fk5Ps%v;!XHv^%i`p z3AN#tP&Y33KIEevRDLT$Ju)P)apy9c*~k_|8B-||sfL>qy;{Hu=^AHowWBDf_q zhR=0-0`FbkC-Z-bfd76u@eJNjU%&^qOI0u7mXP;K)R1nMUKwu(4nOyS#k}`1pz$F| zs0{C_SK(t#s0I(t%lQIxTmMH24GZY^|1F^qzUL#7P!oPwy#@CkBzLF{k1eAv0t4Od z!7ZT#KA1^DefUg$2oEHo*h?AETQr8xb$bH0gr@Y5YYo9qsxJ!9>d&TMS8vf01MCiY zf3#gI72PhuEg>I%`4d`0o1WMIp1+kqbu*CpSQDzjEujD&>2?Ed35D>BpWG*}|4jsL zWP$u&3+_EwiwJHBb>Rcu?!hggXE#Y>DymP3bSfPY~CFH}WpOJ*h@X|uO3Lk4iHMk`d2M9#E z-GEy{Aw2p=IdK!-S8u_+{aQof>-E27)Wv{Qw|np%ZPf`pyeOsl04Bz)S@e14$t-}LNG=OJ`>ikEbtJ_VuB^tr6 z9+HGw@O|GR-iBMEy+6hJzpI%h7+|+_0H5mi5Ps^goH&JFQXiSy`oH=eGGJ^0UH_lf z7pEC~tclLyk-j)B;gzA(!U`UbzFSW0=?+$m-qXZO@Z;(}+!C$Ay>EO*QKU7vCYt^J zF9L1dZop4}uOt-0uc$ZS^@i*p!7b5F;aUCJ6$hGW7X$2;Ch)Ot_u07#!Oy9CdO*8#mS`D1 z)qJz)z?*;8XPwZi%*>OaICK*6K5gDs8(!vFTZ+U3jY7 zJ^20~l|&QxarHiY5^G?9fMq&@2b$;@Zi!Ce-k-~}pTYP1gd`fz5jd)W1w2(>!Y$E~ zp2%vVtBLw>OSB@sUjK)>V-*9IKPj2k;Pptn4nM0Nz%9|{mS@j@teHkzf$aBxwUxHv z1KsYxcb_c@b>WxQd+^%vZ2!Fe5(F&MA>4b|Gm5HA;g;wap1fERn%s#`GcW4jp4oCF z17;Y|`V;Xv+)l87citoWFX2Z&DenD+TbRiF+y4a#l-7abO3i(EwD-0mUWV^{O^#E6 z+i|M!;}44EKs5vwj}Z^xk#0BOH(w?Dhw!tn5pTk;sJCJSf+swqxUx3fzLVL72U?^( z_+fi@3=hTdmSE1VPqY{@l(M|z+M+?G}|xE1Mq+hcE6546}0cs=zM+-65fuiT2a zt=m3){$hEHSBCq)n|oG&6$BbZAp7n&JQ~P>YVcF%#Ov_+1@Q(v{2_V7&D`_)cUPc+ z76v5h9eAqVgHLrkf!97+E^4d4;l=zLUy;CIBarWT^26dI_;OdSU+`~80e>=rHI{;TDgui(pj$O$}++iW^>i+Bm%D2bN~&+6X>jP(&z zFu)S3!9(4y!;jueP7uJC>Wxj$=ij+|%Yf!)AoHar6u~W_HayYo4t#hYIer&@^uD*t z>wgac?|w3%53f95s(Jvogi`oaw@2_(z8ru2YOMb&-yner23%2}!9z`G4!4AsaQ`)0 zL(Yr-m;D!P`{cx)?qD^Ms+Zu$Zh=g;dWf803_q_v zfkzLO{byUAJ%9fNQq}XVK>lZWrC645Kh+|F@2SWMJdIlo4b@BVorh)n=k-@cAkc&= zbWNxRk94~ZpFdm@3gEks5N~8&)W2m~KOlh+18hy#g10r%HayfsyYN)Edux~ZSAV^n zI9UgZSF7Dei}&I6s`vnIiH_i@COU?P=k@h}ih%c8dB!vN?l;Ma=kV%5@df;<`Vwx5 zmSR1TJ%XiX>cj1pR_MB2g(sIJp&GnW6R)eg_5T$O1Q=kMHsQ6N%$f*piMHVb-R^9A z>>WNN8FjY<-dw#0Kl3fJe*(8ehw!#0n!+W~tp3IbEOmPV?=0lRQ}~U#_zXULviKZs ziLP?b>))Pzs+oGPlj1YCTk69D-7drH-ytWiz^|%TH@ujC$#=?t+D0Isf0k(jzSKlR zxFs6F6WwmX$E(|A{9YS6Ziz0;ZT;WYOqUkW^}l86{UvHbw@YyA`98ezy^>HF9$(Qw1p&*n4)=aT zZfO9Iw8J&wsa{wFugP}owg2OQ*MZxWb>XM~lU!L39{jj?0=Ekr6rRMfmb1~Rv2zk&~Re@_#(3z+JDWq7FjSK!NR z|6=~t{)0e1|LbtO69Igrcc=kB@vCwtLb% zoH&>M<9V-_XWw^${Q9%s3rOTZ1Ne~_i4Wl`^%QO=p1`N^Z_0F5|9rToE1L>D)a@$VElSre^Y73*B-8pj zP@Hg~9>6WpCOpwZBY3EZw&8;}=<9z60kQfz1S*FwP7`EB_A&&r8A@TqziZYS=;6TL%& z-1GXkTWW7SQVf{u_6Tn4{4spBltd@+^Pd-=Zg?^OEYrnCAfJCz&2$M5bdlCdk zs0HtTO}q`aM0@a16HUx*{cmqP1{Tou|5Ue!@KxzS#Vt+Y;XTDi@N?>8cx*pTn<0>B zrgL~?-xY&b-YB)Of|u?i33(c~T8YGCuY|w_9pJ+)(JFkbiPqqjXaH~PcBA;3)xTv_ z{szf3+{V*XDM zsQivhrzzYLox}aVmS?|!pDjzGOZW}-)f=(?Z``iMq6f4`W4E*n4>i#W+!C$Pb-V7o zxc=-{F!sxd0~aV}m$#$dfT!vq+!AfUyP9Yl9>w;pQUp@n?!os}B+&$ZLcI?ks}JCo zXgoq7)lA25yQNdO_a=GvGr0c;H=ySYm)>TGA6)P0Te>A8v_O;Gu3; zw>*3PokvNgwXHz*>Ze|ZA9%FZ3fvNH!u>>MQv@#(&Fim?z(BV<@Jo-C6L;bJze&6Y zZ>uM8OLUldQU7*J1I;wW0K27Q_)@ng@Jo-Agr@NQj~Ab!_5wc*Fr zJMfWu7jB96)!q7ks+kTjz%otYbKM@n_rwn_9^Duos86;%_WBx_ZU?+m&yxc!;Ddoo zrzPCJW8%GeyC!P7U4rix$It4|M_{ZcF2l>umxL>j z6+U={oVaFg>;J17s9QkS|Az)LpaG9Gp%88fMewd}x8SjTP_T`_vGa1`4*axw51wd3 z2|UmR&Hz4^?d<>mL%|(B~*hSd99qd4nL*dfG@Lziuo5JUtlLAlC6vO$3v%L-bLl@`PXiMd$opUR z_y0AaDclm8!@aTA5Zn@4!uP~)kc?Ic99A#s0j-EaO~{8^LKV7hSK*dWTtnc@Ur9oB z_+|A5ysZg^a7!qHcXhiZU)Sq@%czY3$KNOkb>L^!d+@|+2yO`twmf_OQ-$GHAp5(Z zZ;}(I@JM|GAE}Swjd#d#X7DsmG_Suo0`{`Igje1s#kGR(PUHlh#;sPy>LqyjU9!KQ zc~Sp1;MfNxP{n|$-qIS}5)I&O-EP2l^!VZ0W&ZUw&|C+K>9|nk92_(BVd`%;r`pTvA|b)f+hUWXXV5z z_-S=dkLT9^H@_$Y${MhmsA;AZxFuSHN4i~y@A;A(KiKx{_y07|*baDo^$;9rP zTJTU4ZPV>LEbz40&g!p+z(h}w!1vruPTYs@s1M-D{bc_Uyse3jbIC%%BcP>!Gd{11WO(i5-XI>7TT$!xGk_9ETC1g|{*5k*2id{@0( zcvgRQp#E>lfC>gQ67eeh*zbzh;AdYdUWfPk;*Cwu>wo8E5(qZ~ncEdK;k&Pp{Ui9H zbK))dl|L76!w;Q*guMQD5U9Ue2K3+uQt<>{z98O*Pe$SccC zc#p;(mw=Bz{}bY6`0|tD75MQ_iC5vXYvMI{@M-b5j=-gVkU#@|cp)Cb4}Dg=2|xIc z;t_oDIq{bGdi{U?^Ac!dfL%ccKK+91--F-$vUmc&u@diZdG`FTe? z#p{_D^=}<;XP*Qb7;x$~@en>Pi#OqW9xNWgk3U4bwRV|*SHDpL?RB8Im4_cL-huBP z5bwb+K1w`+?|F=PAAa-h_{SEcdMbA_U4iGN1+TM&fPw;@RRI zc;#ord+_rA5KnT?>))o|>gOcT$AD`m#Ru@|FN+W1X;(ajU;cIR(S{fE?{H57rOEcQ z@8AEC#WeKchaMnahELTi@RR#w|0=wE>mz0U*ATdPs|={aquazA@Zsm=0>V4-CVc0g zW&db`^}hvL7*P4V3~1kpci`9lMfUH(hd0C%b6fvgpl^Xa#hv$dz9a(%cj7~MWhMKk zcj6;>eC;bTV1mH#tK!o;@frNczsdgdJMjg4`L$yIZ2kWq2fP*hoF~t|^sen9ZQfPf zho9XeUWU)_Azmpwt3R85!968V#emVh#cS~LeZ}kW$QN(G&;LZVc&6c|=k-6qQ9{*Iiu15aO6mDm3+0*78A1A6caXT%eD{iWi4_|EdN#T5_W$38DU zd>7XLSN}xu6S)6n@tJe!Ki>6MKCZ}g?gGW8*ZmXm1^n=z zi!b4`SBbCSS6(aby?eWOFUA)nP(on$4dP|^(UEuse(}xXRrt;w;x+hWA|BTf=)X?_ z0lf4f@do_pN5q@(jDS^d1#Z<_gy!&2#{U0LWsv5rEsv2Igs)ir`V=Zd9E9%Qw|GTQj09Vy;SJiM=)NohS=C=NK zRsG)W1%kEY65Lfa+*)!Oe&a9XPE_Ert7-(!otFVMxT|V-_$t{yfV-lGUz7c_zyFIs zHI)N3;TK*b9>HBz!(CCsT~QaF)xS+YSJfDhT2;ecRl~dQ(^d_4MZM|y{Ht13Zw4|y zXjKirs&{AtcU28{MGeo3x|siS1YA|aT~)(fRl{9T>m9K>?TY$+SpU1K#sF8`uE@9V6hX8t$qZ?y4H@iW=^UTHUSxT~%Yi z?uWEj!(COwU8{z>qTcrG=l}K{knMoysv7R98t$qZ?ur^76-AxZUxI*D^$^~?Dpj4r zgV*ZM3E|_v5g)_-Pl-=*&+FfcVtGvhQw+HL8SxqXz~{y1@S6Gpe&&9)Vpc6TyqJH- zA1Hy5!~)v3vPF=4YxbjF}L-<-MX#?bp1bilstkS{E~VCkA|{;AHJ(T zfX7ok&=7%9T@IAOcfVhJ1mAhN_!xfmocI(zedLq!5{tbV0+%0E1iU%?(4)l{@bl^` z_`a&_U;4;)@t#(%7M|6gRkimR8PLFhj(QKiP@lk0JXVe~gI`sjZ+c$;wVGbpW+3zA zN#aZR`MS9G(d{eScUatq*Pbd~gYSL%ljQY3M4K;$`R3f4t!bBv5gIB6083 z$Hc4f@bAQH@Z+Bqufsc^7Z2c#_$v}p9k)m!kvj_lutAN|kb zaR-5w2D|G`KCDF&?6NAPpcl>Nu>E9w*Y-e<}F zvn|h_{}Bz$w*uL><)1AB7VzupOL+gd?7xB^|0!|rW7|c#%ssEa5(20Hs|+Z^!~Z5; zfgf&(SK%jrTD%6Y|BQG&^P>K(176cWfC26QE(02H|AcrGK2eY0mH$unZ>?SCUsnU| zb)cyJ#?Q)t4!rz7#JliI>OJ^QTlVk6Z?FpQ$h4$*;-&OL*{H@zsVG^KYdA@8jFg zzWeJkpaeg)D_(}To+n;`m!B_Qg-@UVB$@v;1iCMf0d;u2Cmz7Z>J51MLfO9wPkuu@ z`Z(7A!EZ{Sg#jz|Hhg$m_V2)>-xBY_7wSE8TmN7BZ5hzFfUf^f|Bmm;EF7T)&ysDLkt`JCOGR`RHXA1MGc&0#9|j54S%$HGuEFOcEMydS3q* zH89!?WM27mNoWkWzwtDMFLiqcw}j^KotNwSe}TZ6ERg?O!2?am`^0viu!MYgTer*b zW50B$IDX|5SpPRQ(7^!j^>QbAa654Vw=3?$PkdQUoI02O<5lzoV;3kA^p?6kftM!V zTI?`|UwD`J41QgG4nH4Xk^u_@PP|8a1)po8-rsINf}=0}wj!Yt{8(SyhqqrQ9+wg5 zo|Qla-v0yfDm)m7*WgG0P&|O2c%^tle7*kPJtu(>1IB+M-h|JG;t~A7Ux;_%XU~iG zwmf_OyRVi&vK7dFE|7}%;nC~F2k>JT#E0-3uNP0@=_vEO{w4?ve@zBV;a8q3K7;Ss z6`#XTK2LlJKlglb?~_>n@9jyTk_GaA))^Zw6c6C(Z-{r{^WPL7!yCUPK3TiWzr(Mr z7bl#q1I70BKNFw9&%9QA4!`nO;tTk`w}>y{C*BcDV1+>QvUq8}eJAE068G=K%ka(> z*}rlpUX2mB@(~$OgWsHq*WvY#i#OosJ|P~$Pkc(esqWVQ2R|c$2m?yj#ar;nQoIds ze^I;xzy1~R-nPfy&etT6YzMrRdLMq~>$3j7WFV-zj^|n-&gkU!_WKT19y~4qs*4GXMU5``HZc^G{a^YU3Dhy*>O?$%r|%JOz<1v#9>Sv!h&P?f^?Qe|NFZ{7 z;s$u7kBYb8S3f4+hF??fz%N{t{k!m9{7DJ)5NLi%Jb@qlw0IxxEyM@#EB`1ygbzO_ z9;XPLT1sF955FKjh9CHn_yoRMiBI8|zbZZxU$6gX8kl3iX)Ue={F?5+g4e#kSvPFA@siJ9{$E>#u>p!CPcN z2)}tx@h1H8UhxQi_I~0m_=)?Aw=*y5-)_-DudIUsZ5_~qKT~gMA0Da?;9cDwtzG8d zRAIah6t`^hUIRTgj(?Hzb+?e!-HM%F5LeIxdT0QxBkEJJQ5y{GTIG`$IX<0^U+z!P|NQPruq7 zo&2#JrvyLpC*uBRu>K!E<#2xCUKs=YZx*k@?Zh>BNl#FRpH&acZT)Xo*0g}G|HEID zXB@$$db4j*!E3sI4<7!LJmNk)wr4X!psNQO!|lXV_*}PV@N0jnj}o5B@w4y$BVawe zw2+MLS&ntvhYwyYCn&>Dy+*tOzo1?%JgYxD!L`@QfEotWUMC*F=epg1U;ZoEKZIWx zi8nVrum8cDBoJ)|GGD5<;D;~D{vG&Gx4ZE6t7QKk{AA`b{}G5zNzqNs9d7$Iwmf_O1BGxa;CcH# zDhF!9ZNC=0{j2)y;UnGd!3X*NdHp2_*nlB?tS3m}w*MGD*ZrsPpD)SV`&s5i{o6Ea z$8rU84EPoG1-z%eqW}N$%su^T$6s8RJ6c-1%)b*F@YjK2`i<1f@QHc_K2xv3L*1^! z=l`bb`2c~VUz1E5@N1vdnt->va_3s`zHTS*ME4)W2prQu3ZLut2yVA@3?J(SOyGOJ zE*CIWckBPF8kk|gX-`%@3;0+QUBY|1?OorV_Z8hPZF}t9e1M$5-wt@TV->#C6W8F@ za02*)$MW5;2KMum#?fRF@oA56`SDtYMe?@ViYwzt`{)g@M8YiGn;J$^7+^PXL*Km_=zXT2^R3N z`VxNfiL(C+9v(U@^WXd2cCj4L0X{s@gv#(^-zq1l(7#Q*3SX$#K8N-Ho|+7(W584g zG~lTw6vB@`UXIg*->8d6=C=Od^JEFMEMV(@^)`H^2kOG7notjZLK8~h@l8EJAA$0> zOF{#<-Jv1e)BQ(qd*d;NAD4Gpu{S}Wqi?~caC>VugWFrP1w7SvJWKfSuw2-x@T~r9 z`d!q3rvuIRe1{Au!Ts+PFT(@fuE4D(s+*qIe@mZDeKU}`U0DO3JWm=?6P~I^a7(BS z?`PY^{OcfK#nOeht%%@O69f2E6B@yn>f?XH`ajPo|2M?|Ppf(cw_7@gpVUN`aJ!== zJ>K2+X#eq_FSpcpfg%qt&;wN9p>9{@l7)3{B`rJlft+xHJD z@S1K{w>*3P2c9Y?sBZeW4 zzYITlyLbhDRlOD?P!vU$NF9DkpM3xysyE;#^aLUNih5Jst^Wfpq80{Bb$bB!_eiy; z@X5c(ogBmMIJ0e!y{aB)u^sUGdZ4;~wMR45?Ka%MyCl?s+x|Uxwb(zazXSn0@c$6k`%)|`4A@oobfE2@{-o?*g4?|J;ggrk{^boX z=AX^`%0?i|%d>f3h1iW<^D;S57e0N3cmi+UTb_L%KG8>;n%nxnt}hZJ3+Vd)@*Cv@V|en{ z;uE;l#1w8dF@wkUVlYR*YGMJmnpnb5UXp}X@TIzUW4ptict^2+?3EC>_D(sF58rv0 zco}Z51r@lx7F6N(T2L!It3R7gRupv%u$lQ&!MetO&+s>u`cmsv53uN~{`;f?ryax3Nt zOui)3WdUD2;HgDoOL($Rd&XN7m4DE1Gv3LG~m_`Lb&yV=9XvA-x@-+74W=sdh1&7xq2IJ{h$N)Z?zKSXU*#(Tm35%F1A9AiC#rC(-Wq)J@}L-3hgJ8ym zy-m0kZv?mEZNaU0+c5&R!s);xy%Sxyt#Ep9dofGk_F~pock6#!;S4a~+%L%;8p02r z5>Me5)JO3B&yoGd+a7y!4NSHJ-u_>e0aJKWeFndvzJQPQ0+#R_g=h7*LZI}^a$;}g zsw?fVEQZU$>{9wbByYTB#4WPFjXr zC#@8o)t?oGwbCjESSzi;t(Df{)=2}nb<)PB=k;%`G~5hiZmqNlw^ka#t&_Ik)=As& zyptC5uY-WK(k^_g#npp*@0FrU;EOBbefY6=iVyx3>;EGkl)w-JR(gUIZY_2MPu?NN z8N)~F6X()@JZrI27s&fx_J2cOk^{}))_Uh~YrRXjP2&~(RIInu(|K;iI8yiFcAzr+ zr0!pVr|MO>wf4A%fc5q|+-B&3Vo==j76#aBK^tzb1s%A( z7WClZtxCDcH?O}b0S z|IhrPoM4CnJFgH=;e$UCAHkEe;$!$oeX{MbSN`8JV7eXf<~m>ocdZxhS})wD@e1B3 z?p$7fI?rtu?CLG`;dY=hJkb3s@KfqlxV7F|?)mxc#IE&XfNQ;U-45Y(J#iC$Qa#%6 zV*a_-yAjB%&9z>*YrSySdg0z}+Ir!OyZ(&K{{aHa2g-mUJk{+H+%L=iQ+WC{X=F3_ zrF%)uWuO1s?sVtxErA6F*tgY}@R{zvf?EssGy!|W*1}8Xw*I$oqxlxl^}qG-GTeH2 z1#T_83b)mB4IWz$uOnbRJb+jC${lLJt%ZkhYvE0}w(!`C5U?KJg4>T;+VB&aP#2!+ zb`O3|A6Zg(R)6+vrW)vDz>)jO6%XLkdp|9oB;F8S+bceTS8kUgoosqu|MsSHwi(F0 zeczwSkDvV|gzX|7=z;vNZ~MZN{mbxE-!2zWfggX$cgyR46#-kZ)Zq4Bu@1Lt58zhq z4Y(~>!mnffZ`Iz!0IT*0Zq?p`TeY|0R_q<;(tkXw_O1&QciyuVOAl_{Zef199j?;x7)BSsy7xizqI?+Ia0k&f4 z!)?JbfZKv4gxH}43wNy-?piP0wO)0%{&%ex16=Ec zyVeVLtrzZE@3zP5*1H{8w_dnwy>Qoh;jZ<fyyVeW0);rBT zuYW5d*LpF)wO+Vuy>NT4xP;qJLRK4I%)f@d$Mdv`Eumxj)~p1#_liE;-Yb^j_Fl09 z&)zG_{I4QlZx(BCd#_lB+k3?T?piP0-YYim8vn=hIKqHkov$tUSiJ+ce$a)V(*1kp zw*DV!AhCe1|6S{ayVeVLtrutrzZEFWj|WxV~4+e*YJN)`PY6 z!d>gV8y?vnZN2adf3B?;e(W!_^%kDhpH;hSy%^wHFWj|WxNE&|*LpWSuYcEiHv^fw z)(dy77w%dw+_heKzUVFHUl#$l>V>=33wNy-?piP0-r^1Krtkml5xCZi0j~AJUF(Ir z)(dy7*SYi`_rvCy3luNso@>2u*LvZJ7S|H)S}*)k{3@wNPpjDO#G&)zCHO%1_vyNS z8NSf{EARuamgC1&1deK;26wAo_(|PAfVz{u2;jZ<O${JeSnjS=W*LKC=ay>Qoh;jZ<%{utc#K2tycA0l9_w+Xk_8^Nvhw&2!!+i?4SLnlVST5lI_t+xla)|5!_nu7;de1vhA^Jz0>W0YrQkLwca^A(&AdctFM!yTf)P? z%ss2W6#`dufTz`Mv*TbfAp7q+;GVh5+>Xeti~-hqCva=MQ@FL>8Qfa$!ra#XQ*FIV3+VdaTCaD@cI%y$WV-~v z@dl|0pZ-_kWq53@w}ODR-YVQ$Zw+p(w+^?~8^CqZ8+#1|to4R)YrRdlwcZGBt+xfY z*4r*TtACq*)_OY_V6C?cx7OQ(TkB2W)_VJ!p3gsPy@Sm_=GJM}jw(6b2t@X~}wUHFp9B!-L1w4JT?7zGP>;Lm_l)wrD+B(3~s<%gW{Y|oe z3BJ_*efX{(zwErY{_LaH8mPEH-v6>c&2AsbgwOSgYjA75b-1^@BG2njWVEujp~&E&|qidvI&L3EW!m0B#8l;a4@GRD8YuFKb3446xQahFj~M zz^(O8;nsTRTb@1t^dYk9U2Fx`p9}Ktx!ro}d$sk#EANwH^x=tm8D9KMIj_G80(%b} zDT=QOcdZv*smlI!xcy8yfNSgZ8kraMZ_~-OUJP)p7w%dw+_he~YrSii`FHi8TtR0Y zDDHr3y>Qoh;jZ<dZ!y+%s-poqm4j5|7?Db;Wob~aGT## zxUH;a@N9a^{GTIW^Lqie`MreO{9eIrW#!#_yQpntRk}CU|F*R9F~F8qWwN(t6^#X3KI$k1R zy?O<=rI>f0?N(~7x&*gY?Zd5Am&MoXf9us146t5ZgY&+GYOPJf5xt#jH4_w{!+?t1sYooF)9A z?!SV!?jFmn^R$uJov>bAf?KQh;nu1va7(BPKcETKVgw=$)Zz9nIDlKLZosWohj44v zk-A&|H!9MrTNq%iw*z15{$05JMr0q}xu5in!M4X<|AF!dhT8$}bXh!w+efiS@R9C6 zhFhziz@=4Z^*2Sp-ZszRwyd7RtyM4J(X)c0h?j6{)vMg|`nRI9UhV0vGPhn`f|qWW zJLJQyRhQw`sw*2_%s=bZ)r~-&y7lTB+&+q3hac618gP5|A$+&|G@btlr1~r)__YVi z6}RB_X0#2rk79S>^M^~ZC-=kp-#&^xz<{t^fo=O ze_OF6n}N)2#nOk{f@J`=1 zXQyTVxsUb#RUNRvfS#UU2|ug8g4=?{)9Gf9_*!#WI3-A1$qS47UZ#44ytfTkn=<&wufy zyVeVLt#|D*|6J=`2a3#H>xH}43wNy-?piN=|8w;7{|N%F^}=22g}c@ZcdZw`tF<+X z5wKs68N=?U*V2=!>LyXYh*pT-~kz?N2EzFu;C0W(l|7j#(%LIwPn8@ zQ`+|I=l}X{*WV7TTQA(^aTOluEv>;%sRwX5PF8;n1nN2fyyVeW0*4xQF zuYbEmc4b`*sOgD&@Du6@+_he~YrPv@%sm9=9T3c!1S^eAevsLd11LO~dW$OgEeVc9qU%o_&cM89xKHKzs z{_Q&>1Lm87%unio1>C+(w}e~kUBS=laXg)dcENe)E#`j-0bBK!;Wm#e@UwbLtMHk6 z9d5@7ZpHflj1FjEz*IeiTkCDYt@TE5YrSpf#r0>u1E$b%fxQ2D-f2B?7d}z%!L9Ws zaBIDN`1x4B$vi;7T5k&PYU>@rZPh!04<0C;ZwmK*S86VvA#g?mbGWtM1>9Qi5^k+` z1-I7g-Bu*FUjJL`ElI#lOKZJ8+*)rLZmqWhx7J(T^6dFr>#c1CJok%YrPTNT5k((t+x%g*4u&G_ZzyI7xixq!CG&R1GGpJxV7Fs+*
?a;`xP4A=0k_t>gxlu?R~uf;Kl_P?SC)(|A#1%Q zxV2s%ZmqWrx7J&MXPsB(e-!~+_156_Il(&IT5kZi*4u#FqBksK{co+ei2?Q#j|g5m zC(p74x6cW-;r2Pfj=8P>?Sq0{3+VdaJ}B6uYpo>k^RJYI`f&T4;1C{Lm8J-!dV&%B zn)(=SpA($G?ME|HxPDGB`}@BLSV9ZRxxc^`|a20;z_v8`O;Df$+ebe*$x209E8OYq0Rt>n#?+|WFt0vr5RuMd( z-o^ZDAz<^n4Ue7`WNBsp=``HtcNcCes~+5@cXB({|F*R1V}Q-?0o>;I5N`83h1>KV zIhX$9eg$Lf0>y>8U%{BbZD}=y+tO+Vx0Tf#zTejW3j}OwwS?Q!Y6ZWl#pUUXjuo}7 ztV;0KA4oCAJ_47{N}voM>3|CSw0ae8-%qT;FZ{k7zb?LB|F>Q)fdB(+Y1M!yx_=0_ zrBxGdE34L)XV2f}aeFI}tqb&)cHmdkdvH5W0#9`RKKyd-dHoF#u%*=yZcD2aZcD2% z+!C6=dz#QR^P>K(ST1Q`h5@#;n!{~rwSe3A6PIvXS$Wzyv-8UQ8|%`lvGAhWoMpzp4jHF`%pm8o{kqkKxv;Cva=kGjm)2 zTSjvW==%SPCbWS2n$Qw%t$GEwR_$pgw3>^pSCy6;{F1S^AR)2OY>|Jmh1FZFS;MRJ(@aS1V zK6$(z+*)t4>3RKI>+Np_GPl+{fZMy^A>3MT3b)ofg6EyLn15pgY?(ZP+q>W?{P0`k zkNcfpH?VEu3Jf|nRz?}AtGzSfHO(CwByEg#9BfLDUsyWp~O=|7%TX~hMK z@!pP}pbAgaYjArPT!-7c-~c{~_1EP>1T3K@{Ft6Ng7?&0aC;ZrhTFT~xPySb3+}@0 zU2p>L>iq7*d#{z67{LA4i4Vos>wjBXr5q3i#j_Z}ZGMm8wzQhSZDlpx^6dHB{GM$E z)_;C$4!8NefZP0D!fkr5;KlSV>hBx3tJjuRCAiIRA8zxz47Zh41#Z*3nt5@4>wvbj zs$qaFt?F=FS_N=>7uHei{kG;bh@V5i*Kc6bYZE013+tR8=*X=rd zRWzuq{sIIJX+jOSEv-VhEv=exTUkYLTUoVp&+FfA(M*?C9SpE{!9Dm=_fO#VS8oPz zTcQm&yqJHTw@DGD8-aZO9nyCyBe=EdG2Gq-PvF+7r|_&*%lw}qV7+<{w^qG?+fr-^ zkDe9e*Ws<;)~daS#oMjddUfex+ipuSA8xI>47XNYfm^Gtn!ELXwie6()hwXvf9utC zxV7p4Zmqfjw^kj(W9!vT1guv_aBI~qxV7pw+*)-9uJ3|luZw`a3+}=D`X)7juimY# z7k=QQ;sf}l4~P#7&+5;npS=rCF~HshkKpz$cnr5zJ%QW1;OVC4^>4j;wi(FWdi4Ts z^LPnAsMB=?Z>g8`Et*|$ewtk?gp^-91^ zOV@hguJyuQ>xH}4yXD#Qw`Fo|E3p3Uw>sRlUbt($aMya_Md!`yuZe(by>Qoh;jZ<< zUF(H6w6?mL7xixq!G2iO!+^72lwwTaht&IY{TR*wZXd%Lu3hGz{jexq2a4jckKv5q z*Ypa;aMya_do|H1yx~6ogMe$jaGS?V_#RDY1rO9qI{)oX+j0CDft%V7%J8}#r~-Gb z7w%dw+_heHxBj<`8W?ax6AIxqO{fWXtrzZE@3zP5*1H{WA3pEGTaVM$3%AzWhqoUk zt#<&w@TI({v-%q%F#WPrdkVKz?+9+KcMP}IJAqs4o#vj`zZHeG-Wdj1>z%``^)BGn zdY5o(y{io`=AX4*?~!t=EFo*XCAhU-A8xI;47b)>foGjp=6@9dTlLo9)_Uu3YrO&7 zT5khxi{9{&SpQq=ZE}Eq0y2VI>utfU^|s-AS5jLYb6fvg>+M=V*Z-G2`A%jJe(a_k zD1i@k|32LRy6iuI$8#MpL?HQB8IZz9>La+d-Z6ae6*RlwKnV;n zz<&0V!tG~2Be=ERG2DLkGjT5c$E!ax$ZmM{w;)`g*j#^a7;de14v(G{6ayD&O0=J+2 z^x^iip8>r11Y}-+DFT+z2)fegXe)coR0Q=d`5?*?u z^aHQDy>76-qT$2suV_@(F7vOa{|9`q4iwX<_82*E1HS(|<=Kbu>UW7Z;nqJQ__6Pb zWk3r7Yang7t=&3s>mOaXE!}!>>mNysfHjal+#1LLZcDcz-1 zU=3sfw+1qWTmP8Bt$)n7J@yU+@(32&0dI0dd3(xAW zjKEk=T!Hr+a^fny`UB#1`1p{_jt1OjM>F@l{_P5EdUP;gsoP_CP?r--;dY!k+>W!_ z@M8Wo^+5h(x973|8)dx`UP;Cehs)yzYuQI zuL-y57d;m1f17?S46y0fhTHV(z-{_<;f=S*9qO6e`roEsVu3wH1N3bA_2D-C25_5x zL%2=96dvz+t7J4npsqfK*WM=kPvKT8Gx$}li8;I^cOv!{2-Nh%OL$dJyrREd5-Mr2 z+H8uxU1moaZqu(?cvgQlz@|+D0~Wd+!bjKS#7+2te-Mx0J6{rSZF*k+tEB|mn}N*j zuUB>8*FPiscj2e6i}&E+P4NVN{)BYbh zUc0Aw6W)w9&_-aT+bKNwPPu|Hy!1G^qAA=GUBH`qoOp?Vo!HX@+UywU03SY5ufP-C zuEP)ADt96fU$6hKX`q1tdvB8g5j_1axf5;pP`A5qOQ^r)+4G<1fd*TFY+CA_N#W%{ z9|8UG@(7mjmF~ZSd-?u({grf}-D>}-asnS-*6j*B(EV$0|GVWlb$FoLjqGbt|90Z4 z4hS*8P8`9*ZNBow2fQolb-JE7fFIWrH{dtboAB^R zK0C7dYaw6@gbv)+2YvWLx5x0#QMnTnc%nYdJ+FUvt2HpkfL=omw1g+$BlEjdlWAzj zY3jBQ_kTo=Q{M1m{_SX>vJuGVUst_K|1mjG4Q^Llhuakg@a~U4UFLrSfyIx@2|~Et zi3lEipWKNS+#XFAKGp4B4eS3|OHQ0%K>4S|`|!i+1NcIH2)8?wn%nx{ZqdjBd-4a6 z{cuWaVhk^xkc1|1yF)Yh;``+e&Ec`#q7?#-CrD9w`qhf-;xEXFOYnUs#eH~Py$s*? zKa2fiuY!QxqAJ|(Pz}ELUvlC){G56Kw>uOTp4FdSS>=c27Bw-z?ob=v(fvDcTQ~IJ zjZluCYxx?CU{%zrxMtl^z9jecw9WPQ=AT`E zSDrjM+;{r4Z{K&sBl3&Zh+Dg7A5bN1U)Y`2|M`XtuxY^bd^xiUxj8e3JUO%Ezbd&o zvHHyA`D2+gYt4dmyk(BGOKuKyKyGfyh&=b1M!Lf>dE|Xmf(ZpKd`ezgFWX1tl~0J5 zUz5Gm)oaCV@*&)-QqaB`T|jOwb)DQ?>IS*F)I)Or{j&d&_}^ZYCI$oBdD7)BPv)SAA{v3@SaG0lAr= zPHrY>kk3wl+`;}wv8VNKo`7b8F%2*iOvudy)jhK(F!>oyfZXiAK6mLqGeKh>r0rrR z7?Mvh!HC>UFeW$qpOClC_wb;2UG@wbJG>=5fExMeRpNE>J<8%uaWJ5nm=rbg!(|{XsC7R?L;4b+S@HTnxKMzZRFlXE$H)q@>H)rgVn==l`al)R}qrjYTNN&!!Pj1e5NN&z} zOm0qil6qW!rYOuATYG1V#k5V1JbDC0MBZ}5i{z%uN{gP<|KuhaP+kmTZ(~Ol@&Ve< zAB$5u%9}4(%xzRH7F=xM@{lBcGMy_&x1C33H#}g``C}aH?9Alz?lU!z{ZYx zG!1i91f+B)CxtX{@Ze#lT#J|^$OC*;;4 zvi+3YsfkA(1(m}kDD0c93HLbhB6;};@e=u_x_Fs}uHn7%XK!5nGRP}@gn5v$Vo2rh;&&3H?`(0>7q#?%l>$@MHF8tcb#hbH4RTY|O>$Gz z?tZlXH&xxD0j8?k0UJQ=}1j z?N~WbYyWIbc&18o6qqW_lba$fkeebclA9tek)udGt4x8ZQk&cqX@%SrsY7mxv`TJ@ zw3d2Yf2RG+qt~SY=F!_CH$~beH$~bZH$~cA^rZexmHLZ8?50Wsa#N%|a#N&3a#M^W z@}wBk{wq|nMUnGmFteeJih;?h^Cn!{{9cnApgefnVB;#ked^* z$;}y8$kXkU`m0mW!Vef4}ma*C!iTHq5=N5rOn3V zW_#=g>IeU990Uz)r0Uk?My^B`?IGoVVoZMmA}HF68yBya30+q>k`mwOVlD2Php zZSvYq;vMpJMe#2ArftQ2@<+dLWO@QUkAhA?28_sC+e*J$Z^~Zk+Ff#Ma^&vm@~AG6 z``AwvK3o6y5!7ga*-?wUa=c97lMk?;0r?0%&AK;hzrsP;Gb?W=XIvq7;0^LByhC1x zhvd!FiXlp1gq_6%WrIXcO*`x8YUtq%G6_Yf{j`0GHhKahJS{?fc|Dd_o?;^KYT` zzZqb^C3|M(9@okH*ioB&x`W*N9(nyG;-i_%^T!GhjAub|{o{Y>08d7%nmwQ{w$G7| zPLc;#nY@SX>*Re8L7RdJyhCmds7D@Q`}`5v18u(Qi1b7Xc?UiwAMYsp&mEZ_=zRU(M^Khv)|M{3O+Gk4&Y(lSYG3g_d44CEc#`q>{+lDp zAC)$*9&82J7fQQ~Bm((S%?I#|P+ql$2at9vG9sP&b@8U7pBh8!Fb@C#-NnVD#{ z`?20CCoo_CBgi8#H8DC>HY||)r->KIbEk`!$eZwT*5ma*0y`U6l`~{V74iV?kmuLP z_Eqxk@!~b|W_n_A{naV3j*|fm^47b=o8%L?OCFvg+qcL&?-6e&p47j&)O|eDJ2aqx z3A*Hc^t(?UG-QH+Ji^4i1yB30f&t+|ki2SCPmmq;$@}jXACTAJL-Ow1W&06%?dl1{9bF%Y?jx1I^=} zngcCkKQ_4oual3&jcr-|F-1MI)D=t=*XOI=?KVjp8bgWPQ2CJ(UvfIR;} zIiMlAAA8#W1@yT&1M_aTLSB27T)Hm#RaeLaK6&j@OibRuexeg-{oh1TJTcn^r60+} z4!I3)lABLNU2^kzVt3~0`Nw~P317kTXF>A(i~lq$J_GKP7k-bfA#XONRwm>_e84#+ zcRWl`ct`e({j+69Hu>z*VH2G|0_~d2I^Jhr=CmGoVLqu3SiNwjYt3D=`+I zum8;etDe0Qee+>5x!Jx%Zhm-GCZGK&j04RUipO>(n+ zcka@Eqd!PH_2)s_e*NFbN3Ij{DLj92_RMEjZ)iyf882j|EMRLNV|zD8ce_AY$3{-3Q_Xh0h~8jyG3Q}O{k zA~!Euh1HoW5r6+51B%%o{`1#zW)*T9+dJfDf(CgN+jq#@)1>C&`U@%Oq(S`hOKuhp zIV{Ib*O+xfjl6oD{Oq_+9$hQmPdurAv!iYQO@aXpcyfby39DA#zD)k`7iIenx!HfT z;A#KWZ4Iec66WKE-~jc$aJr)NEff zZr1;1K*t35{681TrS6iOY9EsO_s9W_$St^yciZNGJTss|ff?YFo9zQ~vwaS4&&>p8 z`#d?e_pBxbW`Ij>CK!>M?Z@P1`wBi6-~)0}kL%9_WyiV@ica*&T_bD&~N@r%f z!}#E=tgk$LrbFeP_#vVBAzu9xktv$F>p z{kwQ>=JNcpqAMiG&w})Xtm>=f(iO-jSmzhXi+S0;L>}EK`!AD+-g-F$n}WilGN3}f zZu+eB$Q<$}UM;KSc`RaUa}u31M=>{;=PQ=_doiW>?q6x@t^A7$yWQ0JIe{= z$cuN%f#zdR>)$+BZoEyty;h(B_J?HRBKbuhkO@lU5C4yxK$$%JwCu;8yY$}x_r5X@ z(tEz^HLKG9>yX=@kR4UYH*d=U)yVD7%Jy|~_aj*UHz;U)O$Ic{H@#4b(IsE=s7%}< zcfTO}X_MzZFW&Je*!&UMQI~wpU*(eeo?>j6mN+I}}u}!Pn`?r+BgP$z7aTK>iS3zI)`>0f(d~5S~lx|58t`M4tv+ zwb`EOfC0IUg~pJ4bdT(3MBc;Cj>pE$`oHl3889&c*8knRrRb*QlbdAwh&=kFxOHB( z3#PY94duwa(l=y4o`S1BDOFk^?;S7O7sd zyP&*E4m3A&dHz`WcgTSJEJ$n3a*o=8QinrLW7H^Yxc9Zt* zh|kym1-!@W(f}LZ-SEk~cgq9;`IDcJE7T*;<2ey#Jih2|3`K-Aa_3_ z+YiahSO<*A`|pzN$K-CZQcCJ?!U2kCN?vhgM-jRGVR7sHY_;cqAt#U{587L%MV*g5 zt$*_bY`jNyRGA=df88zyoA-TJ$LCp=VTe+%!Bj@`_GWJsgg%n zu++%yw(O@)KE7WbI1TdKPxW?4Cu&l#=`%9GC2t)fkJuJ@^V4#vJLE17s7t=;Q~1co zqu^fbC?F5CwH(u7?9UblPffW&({A1yuTmQfDLb!Gn-x;zv%w+>>^g%h&JbC3T@d9~>SJ5JQ{u44`i9KD!#`RaG zz`a%`u*vthQ7(0beEOu^ONZROOZHPGZ#_$jx|VoS|EB$N>!r==G~mXa4oNRrgWSRT zph>>&g>uVW@)6p*wcu(0?fBSX=>+YCAb|)Eq7L~(hsp$9@<*?gE98?;@nj6hBOmMk z9tF9*pOGF=NFL&2x<0x2BQ*o^$xjbW_cJ7KpCBhNa%ug)IQ${~q7Rq{YS2lT8O1wFiK)yZu<0UP9N#&RW^ zT(Nui$U!E$K_EPl1Erj^vP{>$AG+zNA-|=8h_g+?f(%4)~n@_JSH#Ui8di`;iK3o zd4wlvL>}T3SL*^=|37Nh=NF(o&;|7^_){&Tt9LfoV z`{lt^$hv2(`JE)#Uf3!jss z_7^*3!f=P7t#8E^c=aD*88*7?*BtPM_xZ)JWt;Kpd3(v{P@dc`=W8P z{;#39N+!U{r-XZ4Chy@@&L)50Zh6_Qkl*<7t0(;{@A@1$ zgE9?>@PVRDKDbfNtU`WnS0-@Ct9a*Bow=O9wPBMyGHbIStu-r;B~+c<$My~OQ{;e} z4~nmwQvT`XrXCf|S;p$U12k6fqZU)e^MTv5j3 z`)}jtcow}DOn)tBmLo6Y9_Ps$STh#L`}o;Xk=#yheNulV3Tk+B$^SUb6j#Wm?f2MH zinl`E#1qhAzf!JrHTJar%@c5p4;=Wn;x?EcnbMB@t)yM~TeM}on{Lwf5x)Pk@Tr^h zpN$U$S~Q?=H@bk_#VzZQSFe{d>yk&f1wQ+FPbLT`$R8^&Ha+sf*Jb;VJTk8Z?3Yx!=SF;*<0Ut!v$z8m2YLMT)lU&gz`BhI7cN0(Q-?X3qDXHET4LH6d2h=7X zy5b%3C-A1WOYY*!D*l3}{kP3k52P<1!9tM0rhTNpd*n8LF3>06{6Qz(&wxC{6&jMS zd(BqT|04=E|Faa~n0zDNL{7-t=$MrXBKfI`fG+_8_`H4rL+`-3g1M&$z4Ih#}ajX1WGowXM>i>y< z$Rl>V7{u=42NDzV);{t?i^y}hW!5EBym;f0Bk%UH{x47v;me~%atlAfD3OoNTyisY87yc&uZ_ZqvKUM{wP`I-o zeUMo_e4oEX?tVk6x=mhMe{edmLvH;^imprE^$wE2r{LlDhzI2P%j67t;I$ilZ}W5Y{Gjv z>x0><-u2()O617f@0J72laD_oSE7*d`2LTk5)?CmW!3P(VTpWGC`eu?Y;6=t3lqyVzo)`Un$QIH}B`;!88j-iK4zRqn*{Uw!NtYup?Iqjg z$s>I0r9j@st7wtDkGJt9_-y?j;+$#h zKP`{US~jrEzX4e%@8TOw4f5b)GC`BP)Q|&p$wwbfwvX$tML~ojYLnZ(?5IONK}~eY z!_Ua}K6%OfY$@@i{!ROZ_@Z%-23&>T@d(LX98jNp^+j?e2IP6%n&E<{{kQQF`GMnT zAxQeKi>e-zM|d7g$g97UiKpZZd}tMshws>0`ro=V+XZDT8gt}T^K2(~@hMt?d;^{n zMe=B)+?vv*y#D{Z1Z5gfj${pJlMm05?JMNf&&ngYN^V~-+t-Yn^}qXJ3F;=m`oD%F zZIIje-H#@DfbCuK5q<*NBKL}T)7hrL?n~cy$p`q(r%%2$epVEaPw;_5kGvzlgckq) zKLt6wv+0vJZj&oCAdm3HgdzFRk(wHjhd-75j8l*6&$OSjoxEyIXn>6mnWyB=f5?s^ z@*=*tXkC^q>M?%hGPmeS{a4=bjHKJF{9+LQ@8i)n1@Z!3MvLURN92G?GsU={8@LB{Mf8B3)1bZ_4qP*mweZs%fvppd%T=+Kpx?P zh#q;~yHo~*6b$Z>MPr}5eUEHEAh+?NH6-77m>lScyoE=*H>RMsNfw6_au*-bPRT3# zO4mf>gC}HS>+)|# z{@YmjR5F2Ot^JMc$RW4!?UpJ#ZcUBc{8O%V@+es!B=y&zz`a54ag)4&-`#Y{yLb?_ z*zrp$ZStcJd|g`Io!Ha*H%~zSmiyD7O9LXj?E2*8_sD?;X`iY%{@HxDVX4!O;hqVzW)=E2Uyct?QFGA z_K+)@Bj1pI_#8j-JqjFrYE>XV_oauVSENWDVck$BFX2;fo4oj#6m1PxlcI$n(COS&w{x_kJPy_-C?xKk=mgP5U|Tmk9_zb7Tj+IiIylTE5Kz<6#%H$!6*CyX^g&a_Yyms5O^sQz4RRM(wD}=g|8IVp3~12+A8)DJ%n*33GIkivj;wL8qcD(N&l0WIKmkCA`1o-fIOm5-TZ$iHDVYzZs za`%n$Wc2ZCx2D*)ep)d(Kg$a!*ym}*#H}9rnx_>LwnFmtPb(&D^~oQ2S}|d3K)&f| z#e}V)_t+&+X~6OD3HepCg807*`5L%Gz8+pBe*j)5-vn>Op4Pu9ie0ymiJLUw zc(_Y`6}&~h5#A<$0^XUs^xw8y%EbOWNG^c23LcPO1n-e=fQRG{!~5i0Z{^9v0}A%p zN_E>#t2g{#`PlL++d^?voGB5D&=nYs7oxr8C9D#FP3r_jv2GCFs+D zJAZyksXU`ER=5Y5#=?qJ<#YF!xd!VBuY?Indj86wi}Cv6Fa_ zeErVi74nBlJEikmbqdzLTn6~$kG?{DOup`w;^ytPInay#`tsyFtSN0@{$KHE4{!0s zApR=G-z2c`=QPZY)^8Hek+1%Tc%D4?t}HT(?Dvb8jGOg;@PGtm6KtLyxD|Xy+-Cot zc!hl^?y!Gfyh`o`KajwspxnmSaL8YP-(2dFZx1(rzQ@E&!*soFO*AHA>SSDkRJxGlD`dJBVPlr z?|HxUzqti2f(8w^8r~$o7VeS<@D@3W&T7wG=C@4Ib!LII-&e7tF8R0MKDjBnfZQBV zkNh|f_a>y^N0^{bZi;R|Zi;J2{&(zWL~d%!8&hD4YeN2vf0de;lAEH7$X|@@t=DC{ zz!YOne7^oKV?dq;nBppszY*IP$xnip$W0BEGaldn3o*dX1aVu!E9AGp9rCZktK?&N zjr{M4C-qmS;9p)Om%2gz3V4%zAGk|?9K1!o2HuW6t$)*g=OF0NfVJ>0`N!ct`3>-Z z{7!gp?$Un)1mQeL`|sEAKKWDd0r_jTl`A(SKN>zFKXY4828=1V5CbOUSHq{|*TN(6 z9^A6CU9b_J^C&;(_A5#FP3r?Pty)R0i}FA1FQ~ ze?G3$1WErL3ZIa_13o2xA3P$z8gA{C?E-(hw@Ux#DClEAp8O$rf&6iJ zk^CR<61jO5E$>C^|L1HkMQ781J>V5`2kwxc0I!mt53d;G#I)J=f({|)d4`9^q? z{JU_M{Fm?+x%YbnZ3;Gjv0RA`c^=*+e+k?teA(v#b}xJLIo}cgf!d_sP$L2jm~~5cDXx4IYv|0PmCk z7(O6>=1b+ohUBJ(yb%SvV!)Vu6?{T|3Vcd_F+3vw6x@1!+6D9V|CbQtB$&13ci?&Q z$KeI?XYVLyTqNHeUdniU|Bppb&IFcaUXE?WD~dacSC@HGf3;;n>~-=pai9(ItKd!Y z&%<5v0lXD^TL0z=_&9<#4KP=tqj;D6DeT85-)kqiHNo7a{|-RVn+HkvS#O4iJpvkIBD^#p;Coo0woq{xCcue++JU`z*W|#Ah5K$dNz) zWpY4y@*Uv?@(R32egeD%pRNB-Lr|sxAA#HC8{if4ufiSj0lb=Z&l)4BWdrMP@H+W( zca|&BAb$h>xaKY35dj!E~AxPS93Lld{1)q>VyCk<}O1>>TBHz7)^}n@mwhK)u?K|XV`!4w{*xo0{_MR0`@HGtRk(&uZ@;_qx zK6wNmkemGsQ;+N4wBP10mwP#)0Vl%8cgdqX7{DLz(wqWDztNPNEjHNF8yaF4(379 zeY0EBQ#@3>ulQhvWBor|5lCB(6dx--QGBX+lisTYv*$PzLlA4;Ak# zK3MRy|IED~E(DA1H&T48_(bvPN|*kRRtCxZmh}du3lz^QUQoRF25;IbKb;TQsH_1J7?_COvw-j$H-ch`}+&#-*9$10mJ;g)C`-%@zkL!=y zZ>S6yDLz(wqWE;tllnK8I$8`C+&W-+k>(W7D_&UQY5x_M1WEUm6fY}oD_&9DIY3$e zSCs)Z#p{YU6mQO4oX>;CyGzSSFZmfWq|cYr3)0#D_+QWeE&`R6*IxyONy5jw-v7}^Q8WqWkKv!#cPV! z6>lisj6JP?egeA6fR^HI#XE|3=PvzcZh=1!lJ1+`nn3ZM;-TXG6^`})U_~J7|Doa| z#m9o*3Yh9|jM|PlWf#Plt!(EqFim zxc*H0U4vji1MY?o$^RQZBH#Koa>irwSHdTYp45L0!E`Z*eKkBHzYuO6lj9d z-y=7*6|!S{uTR0n2nOT2=B?Xu zzn{YgY zygu{v`4@lCfS@r8(hFeib)Xzjll)Y;Oa2LXi~L*gHu?W~2s#w}>zicaF8SVYpZsm` zfZT)k$ZvpqAq77`&?o;Jd_Z10NDg#J{#N*i+$=!G;`8;t2`0*bsp661)|<0kuoefD z%XobMzltEA2`uZ!@B;Z(2g?~3$#;X7$jynBmw8fuHU&pwM-}of!X5J4;8pUC@EZAd z;Pu$k`ZrI&pCM?_fT!S1@}eVG!X-D~l5dg!=F75ud+ySI@4${a^C0cNweT+aN8mpB zE%1Q+d+;9lPaRK=D5PMsL&W>!uYnK9_lFP3FM^NAZ-$RO3hqKMA^#41O8yu;B7gd! zast+>Y#00sJO`hx|My3brvV4S3*<+_i{xj*OXN4g%USoVFCnnAf%Oe|h5W~GhkOjL zlK%=`BmZ;iasAaPcnSj=a2XB$L#p8efi-J#LK!^Mr@Gkl9 z;6C}TRk;!Y`O)xR>T&&>_A~cBqyfhJiVqYYDn45Dr2otWw$FOfg((Yq6*GZ=Qh1BdF7WE8z|DyWmaoU&CGU!jW=ft+`A8 zy%9ls9;8>`ba;o{+_EnDXRy6behWMx|LT!g|Mw{P76ydmKZ5tk%>fM*A1Xfblwhp* zg#1@Hpegy*N6Dp*$X^Jzs?r6s_5Y3tatKUK>;})19||v!9}6#%pA0W$eg64>IUCH{ z(k4F#JF1Z126xCGfmg{lJ36^SasAaO*dYz#_XXq?c!T^M@Fuyb30Lt};z|9ROKk?U zX~5-}phND%yX1Gkee&%|tpCluFPnhA z|6?m&QQT3yNN^m%C@RmIqc_@s8qM#eKzt)Z_Z+_UkDFLdE;! zH=wu%Psq2ZNwrVOcZWyh=f|G*zjb7`+BafAj(mr= z$pm@wcfkwfpNAL8O>LEqRM!7xWq_@CMR7;*>dfW*XD>FjS&%&c=6zpRyrFngahKh! z|63evA(y(Xct`QB;=bZupaea|L&f`w4-_AY&)5H^C`QVFvEmcOr;0}zkMF;k*g7iP z1;%rV=M^s~UR>r${gsvlv6mIM6|X4nC|->{t$%(3)|3Ht#T$w@6?f+@{bw$9YaS%s zH@h`$#XE|3757&-*8jnZK-#aTc&K<^@qyw)PYFhfj}@ONK2e3*7U!Zth@rL3}#ofe{`sem*DFfPycNFg` z?k{-Sf9Bo?3&CRh^%M^k?<+o7>C*qhl|eGUHBx-6_(bt3`6F1EL`T#5|LJd+zPFCa zcEOwAIr8)1dGed!1@iB~i^k3R|IY|YCcygtb;rp8mB~+m+vFF)E95u89dd7opi04S z;5G8?kCy|glfMz(Aio6OB>%FwXSoz?eS%ETB0mD&Ccg&WA-@&gCI2DZPd%N zMHGAm6IjP)yTBA(j@%Sip8Of_kSkXpH?>tfme&8KxJoo&N9?FfZi>z(KN;Is$W1Xi zGneO&bvXu9XF>Y>u}pE*$Twj7I{9zm4RTXMP4Ydxx?Cccf^*<4@~^<#v8VNKo`5fTmmF!82AK6hP4T+o4aJ*tm;N&oxbq%RJ^bFz*B;u;v>b!icb`u!dI;SBV~Y9%XWdeH95ue;kw@?{`5vdpEwjl_g;&TwoO)b;4h28OfGTcC>3LlX_=X5!sG5IUu6Y?|Q(;BV+??e#MfQRAM+p=9y zIzuMTkslAwldpppjGOiUeF%ys!217LYh;2F`A+aM`LS@D{A_rI-1|2K4h7$aSIM`2 zw;WK7{EhHB`Kj;*`Ss$S)uiA@7~qmm;Vtswd*p!H@RG}#6$9f;3M)jd`$jz_=NmVv8Vk%rC_JC zWa5bYB)IkVY!|fPIr0%aPi|_c@OE1N7tWT6i!|Ukc!|6NFOz=_Zj=8OUYU7%{+9L3 zb7W#?79`KV_%9%%=&Iz0V*48TN8xqyhv5zKqIa%L+@#;K&mOlg1vkI3H#w~o(t!585<^4s9~tb5i*1chv1eG^_J z{~o+V{v&vq{FiW>{LiV!^;e-_^Y^0*$n)?j`F8Lc`QGq4`9bhT;z|9R_IoRWCJku7 zUGlTwE%FQCZSoJpI}4unpO2us5G4I~Kint(Ej%FqKX{M)85heH4ar|{G1mWm3SNT& z1M&mmL-J$bBl1(=V{-GFGC7{s|L0@Clm=W4kH|j(z}w_qcqjF^{!RNmj-X2ew!1_o_Q}tL2jr%>dgPa4`*6{d{<{M~ ze=&&t&+q~Hi$5p_G$cP9J|e#uJ|@38_O$;e6pS%oO1{lnnK&Xp2yUI2?Sl8gbL2O` z^C!~!|2qf@G~f|>B69BD-v;3!^Iyry`4?$Uo|;>J8k zx^H%Cnu@!Mw-j%$aJ*`DRs_<1UB!LH1I2rahn^Dj6(1-*RD7iP7(QG7n_DnZ222%? z6u0V17i4|@{hxd`nBDt=;zh+vikFvqTz~e`Abww5unu@!M zw-j$Lc-nvF-gg#)#rEqe?kgTB-dpL?|KZ9YncwOwK2Ut9_(<__-CJIz6J@|u@knv& zq~-h188_>Ha|`k&pzr?|6fY`XQoKw)`~JU8fjOXx;*R1~#cRvmv+BzOtD$(4{0yuC zUGfgRMScgooqAkveE@7)B4{WX}ma*C!o0! zwlbiixTAPg@!H&_|IEbod60D9?AA0CZz}F8-df>U|F>5J(taJqyNdgY2a5MRB?uMo zD?U(ssQ3uJV*Ni>222#6Djq3rtG39C|*(A zQM{^nE%BuOx&7+OfQI5t#a+c)3!e6$X}|VDu-JYb#k-38iU%uQ`oFg_NanXf#ruj6 z6dx)+TCJ@A$I5_-;#0*V#jSUt3wZsXGXbst^NJS~FDhOlpRNDP6quT@6|X4nC|+Ie zo>f~OSaro4iZ>N^6>p^;*B`fETN%(%ysNmcc(CY6{hLeOTMQOFRJ^bFK=I)cPy27Q zBuLtCtoTInsp661)+x&RKX*#zMPhb^@`@J}FDhP|xjcVn6O?B`a{lvMV=G=!+)=#B zZr1-b4zT{OE8bANskp1S*HVJE;vL1iiu;NO;w#txJ!L?scwg~>;=_!`_usVNC=<+m ztoTInsp8QxPwVg0<<*{3Jg;~`@uK3T*wgv>30PJJ*os#acNDMAUHZ@5g4#UDv|nBE zhT=`d-4%}Ye``e`>;Jam9mTtf`-%si67&=g74IuPP<#kqvHl+^1ICI^6rU;{WqrQ> zw;Dfc=IU@=(mp5me6eZ>b$Jng^Xk|627k>X>;CyGxMk4{t8|JLbB7bu=ryr6h-=JNcR z-Gb6ANX~zLYs!k-idPhO*vz|*1C1pTa zaa-|<;?CTq|I96@&V%IqXSb%NcwO;^;>{I~^}o9!koA8{@wVa}#k-38o)QF#_Y@Bm z?<+oluUP*Nl>sBg$BIuBpJsi&{*SW3?A}{zlrB&_uXtgp$MsiS8pQ7l6fY}oD_&9D zNj#~4ZojHBpr&|T@rL5f1yB3Ww4b{WEVf@u@wVa}#k(tA`rls}B=cK=;yuMf#ruj6 z)+p=$p)z2k_*n6Y;#1?i{*O#RpZ{C$R=Pm(yy6A&+4{dofvJg-;$_8c#VgC*vz+CD zRaLyEcwO;^;?30K`s4Osfq+lqG-?=E^$|K?Kri@|~iiuV)`74I+cwEqT6f~5V1 zijNc@D?U+t`fg?YA1MQ@_b6SUcwX_s%;otry9LErkevVg)|3=4D{d=ZVK?i4hXbtt ztBThYuPfeA+-oXBYA1Xdle609n znJ4u(T^7V1DQ=yqbb;b|#S5{g_0LbhqB5YQcv*2<@ygt#|I96L=0VbZvs+VDyry_v z@x}_r`oFm%koCW-cuVoN;vL1io)Y+q2a5L;4;AmjSFHaB%7CHbBgMyxPqIE=|4*~Q z?A}L;TTP`46wfd9xc&-DgZO=c;w8n)irb1;5>M)%+s{!3R28o&URS)a;A#Jv_G>N# zi|yws-cr1+cxRKK)I?G7lHz5>?d9%SmF0ouC|*^(rg&ZPM(T0>ar-ru0j}aL#oLN^ z7CotdbE&(F!GimW2a5L;50`k_fBhvv(tZQQhl-CBA1gjNOIiOw3B*4auID4w6W zJbz}lpfC%P^Pk_EqT(gR%Zl6VX8m8`0PBB8@v7oA#p{ZD4JBwQ?ke6=ysdageC7JT zs|@fJ4;1ey9%ekg|EB%=nPBb%#fOTI6dy11r2Zz$g4m~uM~YkLC|#g%g0AAe z;(_8l#Y6at^?zR(Fi?D`_(<__*5~X0Nj8|>`>EoQ;?}uJ7cBL-{_;zM_S_PwL;a-L1Q6E+HVAJl5ced z-W`)~2XB!d2yc_0a|QnXPltjJV?dYu9=K2bI6NTV_d{}^J@Rwm;kmT_|09Av4LImZ z+0lUfL+~Ma03VS*1RonW>;FF>n3w?T{})~*6Hm$agGb~i!>#kOU0{kXNA8)T%Tv(8 zjtb=0!i(gl=t|_~fXd{kEzhzkxC0YZ$W75X*S~2$Q(O%i z@Otd1Np6bHC4V2bZ;_i~Y%hA!f7f9^XEBJ~6jzu0o7mnb-|T8R=kCc>A>f zLkhl#9relo4j+(j_Ys+RNPY%*a;e~n;51D@MK7m&Xe9+6)Tx89rWg0H}H zGf&UovK~N?p9RVDFaFz*@B;ac*T?}C$@hbo$j^qC$v^2KuqpTryh6U+M`dD%d>y<> z{s_EAzRSmCKVF@JgAp{y&xbe3KMHrrH^N)wzks*J=j;D1*2xidXuwP1U2+%hlbf|< zpm;Ci@%=Xg!b~vtzTyM&+i*Zb^1I+8@^s#${>ICK*e8ll6^|6R&d+v%IpJLFY5kig zpb7HIfP&&h#Y>8p=PvzcCbs86(tWdAQ&HSeyh?r_Zb6Owc^}96zfQpsAD3cmkY53B zl79#8l0WkkvY!_D9`LqDL4cq`{u6kYd=uO!-}RF+aX@|?ya%7H|Ib1Y(tvy5eex&a z1M=5*W#S>Z2OnkKv+hPP&IZ=6;S=&*J|z=O$sKq^ej(g)vt96s)Z_ZgQP9VLJo#hr z0{OGAl>;i0?+P!GUjQ#Bp47i-zX<}H25kRnnV>>`9^4_n4PGVxBfPfYY5%=?y-ZMF z2$J@@4BjBW5#A*K3EU;$>NB$c7WqD(!TP^V!D$%KA@9SxmaO-{9 zF7S4`K_*A`71vw`!A8##XYM`!Sxtmlm8rEA>ZuZWCDl$6nK@~ z)KD$;xc*K1-GTvi8t@dnLB8LOGI5jqEVxVl1$b-Glm2@EL3=TXeVfn81RZh*-X-tC zee&PH1M1RU5>s|K`i$4f10#L6iJ*aF_fpcuRb~{(s)h zGC`XLya(PPzYN|b|32I&FW(~j4>BI#|1%KuGJ$111`o+^K16oZCqM93@d5dFu>Fwy zm}L8;{zep>g&mE_uZB;^zXP9={}>*TA9<)8sC6N&|Nnpixj0DvGf&1FF(6NF{*+pQ z-25fABDwiXYNfeL|Cv9fR-Omx0hm9fW|NygrB)%gdU9qC`7_{E@*f}S$$%OK&%=N^ z`50HCLH;XvlYD#Z$0dI?yya2w6n4}muV6rj{H^dV`Jb^LpZr{GAHZkp|4R|{XuuZ_ zmMavJ-v;lKe**g%kbeO_%zFIy{}GI`f%Pl+nEVBJ5KYK;hEK^~3y;X(n0iuw7iFt` z?>EaC=g4<~=gCjS1O;*zUL?N)UP?Tf-?Z6!1Z5gVl{J zS3*!*2$KHW7hWen65b#`72YJj2=0$o?a8?(Ej$lLs z{s147m;Xa1n2?_hpOTv^7tK69|M>@v*2UQ_FavUm=gA+y#0Bz4;6?H+y}RWMN)+q@ zFDq`7ufg^e@-M+1^84Xlm4e?QsFAvEuV^4G%~9laa-|<;?4^9q=>330&)KLLCt|`e>YtF zdm`HRj9pKexTSbo@s8qM#eMi}{coOJ0Sz!ut{(Z8cus`mA4FUB$;|_8kaf>8Pp)A$ zu*{QdL~fp3V{-H0nvk0Z*OXiyTygzH6nq0`V70QZ1zUbYY9dE&9$b0yJ+Xa({3q~Y z;z|8;`;};bDY~-aw&E4Vodr+(&rDEV2o~F~rg&ZPhT_eYF8%MW43hb+mf~&2JBoJ| z_q8?)lmR{Ri@qr}5t82k?~~sT9~d|5|EJ$8I~tk*>;KooN94!A$K+?iC**g*r{vxi z-;#+V3f=^_K9KE#OW`^4>*0BFQ(J}Q?pej*TMsef~c+{IwQTZ*?8?yiZhl=+VAAEq;|K>^zl>sBg$BIuB zpUzyKKeJm9&4T3o=eNeXB-;h%Ky!-c6)&)x@BbG$*h1Q}qlis6rZpE%_Vh}0WHPbigy(6W<0+CW@0}R%so)Nr+BD%f0-xsH&_ZN)1q9P58)MIh~0RlKHn zUGawEO-~72#aoKE74InCh0oUi<`($MfI#t{;-TXGtk1vyKgb5Ndp{(9_I+||M&!H0 z$K;p6C*(g!J+8kg1^I7dMMPeKTWhmja0)y}em6W%{y4mlcvAnS{r(3*kp^r(z-s~d zLGUtp9d46f4X-SC+JFC!z*z{A_S@|Lp$o|OgxAQ|!RzD?!5ic+|4)4W-=yH6|CEVc z^7q19lHz5>ZN)38$MtX8&zymy45%tzQ@l=I zykCmCvFJ(vosOWn7{vZ3xJ!QE1G1wQ`L*yi`QP9j@}s|l&;Pp=Y>b2CKcBqxUGaeY zba;>a7I;Wr{GRNme<`j1n+OIp;Jff4d0{9!8j&9lACun;pUgac{#n+)eqVMpodxLy zu)6SwdU`oF0Ra20PU-d4Pm@%a9mOVrH-bN3Yw6z?e>F7u@R`pbgY2Z|3BA1OXo zd=h(F|NI1;(tzzAl46X=-wC%a&vwBV;5qVN!}D{O{(JQgWrD&yNc-=6c#-@@c!_+o zAIW~od$W`{%Rv-whv0%57%X^GaaZw{;_W4#_Frd7kn~?yabNL3@t)%06}0|0SE8>B7$`ne ze5Ckz=JNcR-Ga$1NX~zLYo>}v9y_zk!#? z4;;(>%jEBZdo~3F1QqiAe<3?^$d83r$$tW`kstX>*-u@3zWzTOL4yYP@Fw}s;4b;g zACU=KEIJV@K` zcklxFX}^*KEs}3N5igOO=Sq2ndosXY5r|h5cNDKGUQ@j8DM3T=rsA&REydgL+4|o+ zxjHn!Jh{5$XX8@)0`L$f?FdJAOhxf??_<;P+@FDr(zmffq$S+Sl zuD>w_|DUpVfp4lv|No~6m!#!Vpg;j>)1VNFLMb3cK|?^PuxgDcU0pSlT`AzDh?gSj z2`wv;DmG9^S6q$7OR2Z2sI6|b)cv|$cUOz&NSrSMqs3^E`8(GiP!dl8zV-QHlRT@Ggn361-dD_Y2M*?K=x91-Eg|$G z$>Gm}r%Qb3e~p4VB<>L0CGqKk=Mb*Xzo&#Dj~Mv;`$llL#7_vGFY)pJXB4PF;+F|t zC~^EXjWPdylEM6QnqrBYf7MbV@#{qfr4la^+%NG`!2^#<=l|wkyHrXJ=3l#1OMHh2 z6qfjlg4asi{5yhrlbid0^Dh+|OoMd(->l%R3f`vR?Go=j|BpxpbIFV!?s z?<^4UHD*g}V5th8uHX&@cPV&|&N2SX>1X~#Ql8{+SoEb^;^r?W3f6K2O2j3ZAdv1qxnh@c91U%-E-JC|2+i1us=_e;$eeSix%(aX$X)6B)o86ueo%TNS)b!P~+0@o%nxW=ljA4p9Z~Qt)mCXOH*J z0%QJ}8QbCpKKpvRCRM@H72KiVuCut<|L2@#Fs4VIg1Z$wU%?9$yiijZd13Xc37Q zi$GC{KP-5c#9tM>TjJtZw$T5E*>JYC|?2=0*hKLmH_9Qm8m zY*4q6agOA0wcvRYe@Jk*#PmToe_Fe<8f1F1YJgVSb3f?Vq z^Z9?at?w)_Tf(N`sS2L1;0^`XTna;ug6Ao?Tfy@cyujdR@Ba%G4n74hR`3!9FYUw8 z|7KJB`xxRppx~7XUajEaM4XSm+C&EMdIfJ#@MZ;XRq!@&ef*m%pxF}b3Wtb-M-{wF z!Mo$!n15!*Y`bC>D0r%Zrz^PQEH3u{uCol{TA<*03hq|$d<8Gi6ox_t_bGU>f|p4A zHgORu6})%nGIyj9}g>m1{+O)^~jqYG3Ip^cw zoPH}=Ar$^q^_>N$1h+~2sw5+Qs>ELvJYC|`p2VJqm%>tE3+#Fk_RnqzYkbXuD{E~w? z=mHWq2Un%U-w<)CC2o$bu*uE+zd5*SO@r9~|5pU6m$*6T8YEub->5*d#LdCjDsgS} z0K=h8GMIy_UE=xIftllq2z@g6B#6wiF}1TjD1K&!?P^|GYtlLjg5_ zKQ4Ho#O;HP^gfB-BzUpJ_X}Pk@o_^6jq87@WC*~(|M?|;Oz?oj9~o+-uax-6RD)Mb z{5HYEJEZ-8t1#3`4w=J@K=l&;h2RYme_!xsiH{p@#A)s2#`?q72}4`2L2rQGyRH}lfE4b!R7+eaTqu_Z8?pE-8gP*PP!C9#9EVv}yNN*({42qWC4S{OM*I@Nd-wmJ2t%pl zaKU)P!7uR|!2=SvWEklyCB9Pd>b_iKZwo`XuYu)e8i8sh{wu-jCH}GC4HEC?Fyb^z ze5uYc{#qr&Z-qmf#LYq1E^$YekwHY_w+bGW`1^u)an8rTIsGO&jX>R!L!scTy6-G_ zUT~Yl$4oHdq)Pl2!P5!X=ii6I;2;J*|8mYX0=Xn!DR_>=j|rY9@e9v0;6LG1ru7ra*Du`bDAUXHsJoc*TnEHKmC6g*YI({+yVXHGvekVA6# zlc<49;+I@t)GSBh+Xc^)_>Y3SDd*$=&Z$PAd};tU3sj)sg$nLd@ZtnqpMNC@41E5V zD!5<40}5WL;MKp8_W$NXsA0*$dN!)yTK1br_)AM-}uMlzE29NLm$ILV`$d??<$L9+q z{;)`2DDig%_etD*dcL?1NB^6T&zJNuFlIhJUn+6)@p-?*&8O!B5;vcouavm{^gJJb z)sn${d_F93^YQswiJMQ)*Gs%hv_yl%OJ^A^-3+dee|ZILl^o24s7=A!6+EKg(Kt8e zpP4~d+@McClXojP+tqg#nCWc_o_ZD+=l|(v8I0R+hl0B#ZZ2Fo5;qsFJc*wcUEtOv z!|fM}Ss?Lkf)_~qq~L`TziYM;$0zZvf)@+kyZ=8T3?-67QJxW~RN^lR?w9y&bBy!> zi60cavM*%?-<*D@g`rDwxM-e{LAS)sg^NAecNUlnmrdg4!j($6 zKL0j~4AO~#&%d35J0$*|;4X=q3s;WB&4nvZ;<0&R|L>LzGcGY|oGI_&29ty)cwW4h@3)CEhG}K;o@}S4-SXAEunozc%4ePYvMhf;UJ!B6zFB&Gc;& zkBamWiSriH=YLc(bP0!UiE{`2-&1}2xLfd4iL=*@^yw0}3GRAI+W(slIg&%FaBxf9 zOrJ0DbdkPL;%0hZFW2kOm_s;}^cswcnhvEBcZu`?iJL7{De)YUJ}mKoCYr8RGPs39 zgT&1YnkAku(zi+6Oy4f?LXlpJN(R%ROX5D^z@F~g_hx#V#7ji_bcvhk9R`o@|4W5K zj=~{N<|2KG#0%dw23@JdeS-V@aP)t%Fa-J-7%LIHQsSk8S4-S4cv#{A!D}U6$vGc? z^^&1lI5bE+EO@iTYXxtWc)j3l5^oT^9b6y(<_g#>3=zqpRq&|9+XU~Dc)Q@;5|0R8 zvZr?p8S}3#>*xA>D~%g;-7dIa;t|0sC0==%5vN+>e!;^MFS$%J9BL&)fpDmoxLfcB zi5CjqEb)B7TP5xjyiJn~#lp}o@qpkFiI)lGWGPnURu;EujrW39qa*w?`7PZ%}uNxUFtaKFTTT?Vg~c+PhQ4@*4q zE$0}24U)li(_+2mtrB;5ZqRv`%m?47^Yj<{wp{Ja1v+<2Jo*b`r&P!}AOGg`v)y%# z?%EN1`()P;%y>*tHh&%MBE3uEIfCa)+(TY;O#OOHH%2RQlyVcT&ooZ z_Hy5rsQ%9A0-MAO%C6N1X{y9qHyhj~@pHErJV)ZqMjVY5NQO3%aiPQml}4aqi5CV9 zULtY#QKJHt67RRoNMEgUj6ZYw6$pn0g+sH%eIk8C;${X>iI<4H{*N+JdoKIe@Pb|5G zy3bF{Z5JfwwF;g-b+s}7?!5tNf3iRdp{Xa2^!hH?BJfh%^M->?;csLF9> z;9&)i^m5dnX6$%ck%5AT6+EKgj<6KpSpU#OvVpf7{)H7hqTr5aqzsHO%%|X5SYe1L zxT8jqfr5t>JYsNT|KFzzb}KSa@UVhM6x{JFjgR&>S2|xGL!8$uID3u;il;A7@Ngo| z`@buZ0o?t3;tVPkJfh$^FC>oR2iM1+yaKi<92~WY1C=Ovvx2AY>5U`p|Ko-})3RQ{ zSzT|SKIsb-JbV@x^UwEU;z0E;CFX4k?tVFOdY^)~X$nK?D~SUYD0roUw<&n)t492@ z_WuRKAdiVk1#eUE)cV8~@b%^K{eOL5L+`X?uO$vtpx|Kz?@Gwg|L)flXHco&5e3hA zBXOJp1#jb=k3YGoyA%$odlP5Stl$v^XK%*i^x6N{69Zk6*;{c3$_o@ctl(W|b7TIc zzMVLON(GN7cuqs&IDQ3hYtRxqI2sf45(RHo@YHt_$MKn5-v8H|25JA#-c1~+K*7Tb z-X-zg{lEKni8H8F@Q8xvG$oGXPs}yeoY=tFdx-Jmc)U43SO_^?1RK{{C`&PzbN+q z{*M(7pD1{ng6~)GPfd>c(-qDCnQ4&tUla3^eO!r;HA#Q=}XTA=i~3JX*MyjLxgmOsTfA=+*mB>->JOy_vcz$Az^*^zJ6)Lz-!HX3a0u>vW$M z%2#mzcZtVPK*1}&Bl~|^14gdXl-m?MRl(C0+|kQXf0}`-*U*<2D0rcQ`xLyD>?ibm z&Hitb4Wj?s6+EKgQ3dZ(a4m8wai8UMC+3Vi-9lT=rr@axo^Ehs|4#!|lBZrMuU7D| zg4Zf|eIIVNKbqS|F0VA>fPz;lc(sCu6LFq@0l7}ojN27FqTu!9u^k$xLBZR>_4>;z zU^Q6*Cy>i!nDG0sYMTE_$SoVggRABpRROt*QeGWj50F1`$Rpco%3Dvy2P5SUGPo$O z|1oj;QnL9p(u@9&PFk&3hPMO_ltTs!tS51LmK5)rczT|{HIV^d%ZXbgJ|^N0_cFxSJLHkkOVc~Z;H5l31}Wv;XLF?x`g#RV-zX}EwT7l|&eh^IzMrggZMkv&SHjthICl_kBm7n}{Za{^P12{EobUhd zB@PbL0RA>{a1s7GNgr^N0`bL5{0n;$^Hz!X&cE)<5<8?WO3YiYNX)yJB<7BvCFB|_ zzB-|SH7Iy(VdC^{3Z8yL;`GHjNB#NqbC9O1R5&|W>IPZV+UmG8=N;B5-7m0T0gmrVU>gFDZ2>AsIhNGOkweJTmBL`Y4&ky`1Nt`m1=x zy$0}RlEDL{@1um@P735B8B<=GACFJD4}(#!Kc9Zo5Fmk;lZ#C|;cl`Jg-I7s-axvN z^0xS_(HJ$PlIcNto`Sb4c&ayEV;ZOUTA7RfPbZ_4Iy5MF=}I|}(LWIdFCbk|L|V?K z#hZdrLn~PiC{HI>#Xg)&SIWD79xo{6;a?bB-~UqsBlDQ@*5!!0#)Tx#BvOIA0u+eXpHDw(aFKtNfWIneOXPKdJW+LGVd$N3dqQ;IiGZaOToiek^TPiPe#pCb z{K+d5+nai1Pqm=D$J(j}U&RMl#4JYxU!VyU7j7 z^@N8BZzbGzW4xe;&C=jKKzLAaz5nYI7`VMsTqJl4eNAeXPwsf?L?HfFNceq(SCVVN zwWJG5eo6NK_mCPm$d2d`$v8mxRV00vf*0NzZwZ>dxtF8hC`;<&?eB!hawe)S z$PvGC!TX-_Hj+Mzq<7yR&v-lGt_^X%k8rmU-`M|CLmqMXkT?_*{t4mL55zO*Pr4@X zV4UX?o=+;4Ycbm&P1xX%J2Vl8u8nbihVay~IJb}`)=hW{;f3Y#^b1VR^Y;_OV$%Tb zA|<6f|JU(AFOu|?gf|kNvpJrAD4BkFh_Bb5_c1lN0&xd7ad15n=j#YB-4f^T5MEFC z?+NdYbB%pM4Cy;XAQb3-$fz!yW&C6UFX&(KGQVKx7C%DA`RAl-(kqNO7Q`kE!5oAq z>+wbZyNF>B$vB7b;e_WAK7w#J;c0~D6P`hMfkq4tVkjisNw|;jiG&vuK8f%W!lx5n zD!9g*D3=)g#9;>E0m5ezUP*W!;njrCB|J>{g82G}|LuYpE+Y>0gy$39K=@+9n+ab+ zcq`#o_j2@q8!;608u0Ubgp2=-MYl!>H+~VwaEcOs6N%GB_$`EYbI!*f?}FvTz#ff{ z-j#&g2rni)mGD)BrxU)8a0lVqgT&w>hK+>h5MD-j9^nDP-Go;Wo=^A=gB$a&fEacX zheE=CL%5IdX9zDQd^h1Ggg;Ms>7!!*&%59SV(=4(TEYW_zeso`;cpOLP59e{hfU6Z z|EGx9(Vd}t$vHsa7u_OE#5w-|FJky-+`!ml@mcV1!fk{fBs`VyuL(~l{9D2uI!FC^-**#(i#U8wcn;w| z5}rqR58-aYEx16L|MCg%PtX4gh+zP6C?uTj>3oFSNcv*JhZ0^w_;A7X{x2nlF~q@7 zINbvV2tS9UuOxgt;njqnM|k)#vH#~?Fo_syiNghi*AqUC@CL$j2yZ5QI^nIo9QDs5 zhPGY$RfMM!ejVZI zgclO7If&us#NZ_MR>kO4F5+A z1%w|bypZs2!hM9t2rnl52f|AP*Z2QPGMBf zVi-ppY6*7`UQf7_@CL%qCA^vNNxdBX-%1QqdJWhS5k8&pcEahwLWJ-cBz=_dIfQp{ z&c`30eoKgbuaIIE1$f&#*AgkM8=D&bzj(+StEB?bpEEF;`Scp>3Ag#VK8Ji=EJ z?k4;WgB$ZNpBPGrLjmD;5nf36{e=4ne~9p6!s&@?NhR6;ml20j;_w*Ze!{mB9w5Am z@JhmW5MFI^zW;xQ7{aCjyoT^v!uJqfPxvc@HxT|B;mw5a1sCfdW&tt0MI71){~h7& zgnvMIgz*0%JWBY7agP80ix~bKH?VHPKPH?7my2+t$@OTyiRAEKi%pBSRVp@8rsgclOtMYxafql6a|eoSz^|4WGB z2jWmlI6dL?6W))UuLTJ2Pk1Ha0|~DVlKnqDDh(5dRN_!e_*la02_H{*1L2v3H}`VX z-$@Luy#~f665dAmWWw7CpF((q@acp{3D4!+oPS-!kVhQ437x>BKOf7#xIq2zL?Qdy0*U+pyq)kJghvQ}g79dZYwSs4=!zTI zZwc=vyoPYLJw6MbBiu&#^Mt1oUaND_|LMd~M;si4)2~`wgug=4=MerH;dz9=PPkhm zhP}j)Pk0mI1%$sxcp>3`B-}^%r-T;^uJ8XpCx#N@&`x+M;r}4qPx${59w7W*gjW*& zg|&D6!z>_%{}6{T;Rgt>CHyPG>k0pw@CL#=dpY{QnHUcD8n7cG{Qn4VBm5ZQ?SvmE zJVN*h!lRt?@yDm%Nn+?C4yOq3COk$stBTKp9|*S*ewy%9!nGfXA)OeKP$=`CgYf=@ zy9gghcn;w5txrt#gamXi}enDA4cq&O>Ncc#?eT0uCyts<&|IZeTEZ6)UQhT!!W#&`3|y>#m<7ae zIdNzud5C zg!>5JEV$nP#l-LkaVR1DQNl|Je~fTH;g1s@AiR?B${l3?znvJWiNg-U!-Vf7yq54M z2(Ksnw}dzJa@4Efu0xQX>G%v2XOX+wqbS99-?1?E+YDM=rW?;g03O@ z9q1OK--GTTx&_)YRTMx&?LP!?ngIGEXb;gJLl+VKDRddppF`IW{ZHr?qQ8LdAi4wE zGR-J}#+&~u0H*+4ABOf2{S9;x(MO@nh&~BjL-hC1Ekyqa-9fbFaugs(FM!ei0|1-` z(EB(U+C%gZ=pv$rLzfXf3c7~qvCu6LNA8)5PcPN5z$`gGNP}Ct|9sc z=oX@HhVCG`2--3u=+MjzZv}7yn0hs|hv++?i-^7px{T<1p=*e~AG(F;hoC!%E`zqr z3~Id@J`CWT885&VXb;g_p^J##23+5x{TL zh@J{vM07568POL)*ARUXbPLg!Kz9)B(EuzL#S3sbw3Fz?&>o_%f-WN33tdL^_0Tm$ z-vHf0^v%#6L~BI=mW$&BxE0z-^lE4i(RV->5q%eQ8PWGb*ARU_bPLfBL3hNpHmnT5 zGB;j;hoPNBZ-Mp@y%oBM=xxwty}EwbPUsq z(RI)sqF;e7BKmdcGNRvtt|9sz=oX^igYGc3#_ET)09Y=G7vMu^C($24dx-uRx`^mc zq05N=9J+?+e?qqq{RMP~(768B59E4_1G+=k;`;9d zuq4F`FcI2GbT+hy=&8^}MCU@65q%+a4bc}tw-9{^bO+bw_1^;stmZ+DY^lXb;g_p^J##23+5x{Tdx*XY zx`=2mbQ#gtL)Q>}19S_~+RXqR1QbDAQsM=;71~MkYG@D9cR&{reHU~Y(f2~v5Pd&% zOI&Ni9s=lygJEURmO=3XJPhq5dJD9N=&jI2L~nyGBYG!v4be|PxAbb<|33xL(F@v! z)j(SY#|!X0w3FyMXb;h^Ko=4HI&>M)Z$Z}({SI`Csrmi?djK6KfNp`d42c)uLue<_ zA3=MF{usK5=ue@`i2fY9hUkAnw+OA@|9=6{K@xO8TZYC9@D;R^=)=$+qQ8MIBKjzF z8PO-9Yl!|Hy2a4O_5VkJ4wAs)K>=*qNhR^5uFQNM)ZZyHAG(o-NLnb{l5gDgCy`kTZYFA za5=P-=*7?;qOXE3BH9aGM)dX2HALS4-2&Zv{l6KYgCr<|wv31u;8tiS(W{|7MBf2j zMD$(IWklZ#T|@N!&@Cg#_5UG&4w9e@+L9J8z{Ai^qPIYMh~5faMD#Z3GNN}v*AV># zbW0k!{yzoKK@!wJTSmqU@I17W=sIW*(XT)k5&b%J8PRV+*AV>gI4twFEs>!S}Voj>6^7IRyuv+R4 zSkvleo*r7olGxtOuyNht>lb{vXK0nLD0|KT=J(=HuG2Q^ek1F$!u^6PdxnN?xzoP- z65RT*Zg=eYO$%dxVD4CiUHbVwPIvGbY)kerwzmR4zKuD-uIZ^&;qO^&AmZ5I<43ja zbLNKzme_AknjN~Q#C~zw!$^B91%Ayr!802^s9l$mnilfy*)THnj}rR?>%zYc4fT}R zFRsyp1dsPNnIG*h;&&w&Q)%UKYu7mK21_&c!B zf7aUVV-jZOm>bkWNq5=P`XkKb$3jz=-7szXnVzN3Okn%Vf9MGv>ggHHqu99_IpEvr zIz-%`$?QkM7PeI9kA=Rl49Xmq#Fidd!Gd?fEn*!}_gyUXahH8msQE6tP3w&HgpLi( z=svR{Y0nwdXgg}U&NDa26W;rMPY8c7SgE%J`jxlDnGN&z9DwcEKu`B2r+Y@9<$Jl| zyYm0Xcbeg=_071jL!J4hN ze181u_x6xVb*-~7y;Af0#Mb)O>iE?ywRV(@Iv=~0b*(FN=+3!)oDE-Iu+w_evfKmK z%kwm#L5}VeFzM_0-dR+xnHF5<@Q3Bdk-L)L{Atslhqr zENGj4PVk1$<^&@XSgmJ;JM|n~>*^({|lG3*E(nUwJ7)st|8#X=|9fxUxTG(E@G#H&E_(oTdmsscf&g-p7 zbOMXrfjpBiSdpg|%eu|eCsWPLbXGi5J;;6pN2XB}mN$v*x0lCw^YF~EGF93REsXKZ zk*3~u4Y-kcn{7TmBhzbWMUO8Kd1^*Yi_A

62-jEo)HUOdHWcB2!)v+ZFT8OxtWh zq%|__vhB0$na+&YG?wMZGRv1}(YlxMJo(_THTB7~%Qh@i&y?3nujyqdEzR`J1!ksQ zwk(I9sVyBX@ZA7C)6q23<9)l-Wmfcrk!LX9?!Y_(+@#M~bfiu5mF^m6Ge!V&m z^$D}Q3;CrclEvyR&ACD6FZ%OqRV`o7R-QK^^mM7+xeNvW3a>+W^+Q3=Y-rk(#Ecjp zb}x$UUcrLTJ-aBj>93xcXVZe%^Fvwexe+Y(EQa|XyL&^m+i-O-^4aEg{?GK}$ z9*YN%(|*8O`RQg>6+wK>5)8mOGkZE(&vwUVZ=uyz5wWJ%{bCRjAm}qIlJ?hpkhK5( z^0D1r2;>-%+UUEF%?g*_&>cm95eHb1XO0Vb?z6j-_8&w~yd%;%M7jfax?>&4(2atA zi&p39pDRz=j|yq}L^_CCe~DKy99<&{8YAmiEdO3M>lB*&lyhP14b)`a#CgF8TIf)+ zJ9cpR{K>324H>89KL5Mo&-i3)L{p#m?8-en4Yxgp3h|~l^$P)3_15ukKONQoe~#XJ z`Kw3o-MtadZ)>AI;d+`2eBor%i3jJI@C=@jGPp;|;BjPNVexqVc|0eN zwFVIq8AMgA*QT zM1)kd* zc!a)3ew_#2z+#d6#K=B9H&}x~6vcqj$Bc$c*00#C$cDc5h-oi3?9mZ7$M#@6IiC4o z-j=mmz#IL5HQLVjK8yZ=HAbgA(0Cl9Ix@vS&wj4o8~qd5j0YN1#`wK2O@RJ{H3n9% z&Raag@5KVQ)|T)0UXk?3*e$pEy%k9nV;^<-z4=Lju^-LxdpoC%nrxr6*}FLD(XoS^ zo4tOEy#h0>E;?oOYw{oY3&8C(^a;f(o~v%R*` zfHz>VRYWgku}7Z*pY6nTa$CXhMXw$oGcyRlH#!?vm7I7cJpQqZS!~VO1=Hds zTZ58Kk2~2HiGsa>g1w4@y=WBd2D4yGM8U2|P%y73*yiyu_Z#o)Eu|OiY833McpkQW z8cH^U#V$L$WT+)-^><|c88ZK5>pU}%?do^{`_GL+@)nzE7VIWbup1K;%qI%=i71$c zKGaJ#1tlwp2iBWx8jEEnD%cSe>=+96Eedvo6zrO~zkQ`qu$?H_5K%C5EF4Dn+170K z+E;D%Y87jZQu6+6L0@jSq*NRpm=WuoP&j$D#XaXFHe=mOSnP+#S>uTXEOwZ&nfPPu zwUeKFWUM{|o(qhf{9w`u8(y8;Ga4uNx2Hry8I6aBj?O)enPhv=K8`);-p&VWz?xja zcNw;Sm3zx^oxy8Cb zW{i)`^Qx@&iq8;3AGm)iHwNw>%f0?JWZ^$IMlyj7A9mKzHZx`B5~3c7)JjctAA zaJ^fSQc|LCWH!1UwCUXtoisjIG`-&P+L0GC8#`akY>a$1G**TF*QooKp&fq4h4 zfq5N0o9FFBx7=bD>VzoNv9k-+Ic{ujGw;)BslA2LyOiH$SmJr`E?v@FC@sE3Rv)zL zUE%rC?1J>V=n@2*fWl;=FyjLAJ~@|F{pN!K!KD6vZ^SyL?qhTZf6tkSfxG?Y#?H{q zji<22N4EFJk;6reeDvG;+fvM#lD4YM%O0G+eO$22+d1^2#)xJeAM1}jS;Tr%>=eGw zt#Y#925czx5s&q}+?rOwOPq-kcZxMVU>#k-2T}4f*+KhF{bSfx&Ew0meR*~;3!m*- z*+B>1ZCBtN#5%45yYJZHq4zf)Nx8pq^@GXdZ2Ph+T>ZhIwIeXxf`PO6xh-QCWAH3~ zFl8LodSW|^^*Ej19r(UyX))G>;vsD2k0|8+93%9hcwqEJ2GbDH9dJ^Mpd>W!&9MYO@-OH8D4;xYZBnBj1x9T z#wi%TwoS~Kj`sy2t!XTrPG#q1q-W=3q$2Hf_-u2Xn=xk!(zzUXzbNA!_2K6|UPfxRhJ-NuI{U(m<9KDcre~DGmkYyvi!uDpz|km+kE$PToI#pQ$pYK!2^b#VsYa%Z_N zM4{(oeCV2imbfruZ}uD%at6{(LP2tnZbC*{)_~xFDVC-$r&*f5nqg`BZnmZA_{El{ zj!P{~hZb0xzFuT$iY&1-Y4|~|G#>PkuFYPys&lS=`G6pI<^$-FZw$ugdVWZ2j4rY0 zi_Q;A+_BRO+%cPVllK^W@5kojAolbT>)1N{O-1g&3|4h`;7zedo$f~e0Qbu_jCT9@ za&H#~^x!Q4Z!yxZ!i7mcygs58#A0_kV_RW}u5-pZ?{mghufCvRF}7rboUHM{wLy&T z;JnqVr#2)bU<4!o07iSq)$Z8P3ha*XvR4MYwtYFESR)sq_{ zi-PkGEC|k|HlQf(fEmq#xR!OXYgXSOZ6>SO{w2|!Dei=ra5Dg zQH=i~ZzbOudm`ETjm1IKnD67RK84$`QEV2sd%}6a@Cw}h2wOgEY_x8x_k>-+FgB{D zjqfkr!rr0b4#!iBrraFR_i*9eN&9*5JQ|>RPB8pIJiv6=90<;9`|L2j0FA7B8VeJ@ zZTqeMKBle%3sPiSQHrH;qx-Z~;^Q()3KJ;ftCO<z- z-zT_ZJNbL2J66Tt$GKzM`1@#gtdhTvaL2at_o43Cqx{`Es%{H^$GL3)?|h&iL#5KN zLi#NuD$3KGtZE&WUClD#yNx|POC#&tvAa&7hQrycp3&|gZq0+Cw!251qw!I~FVwsF zNWn(kQ-5)AMf=>~fpow3H11_o_W8JTIQ|p%q_KYQe}BS$AZ1+cm)$*@I)iik-hU+u zkctA{c5yHZcNBl^Yj4vlPoI6p-3?Qe!us3 zKM~*n?0bL0zHtNYt$xCu^?={|to9QLHa_V0KKT>&1F%>9gnju#e($3{VLt%7w&^Dl z%-8(h2jcd&-Z7FhNN>Wd@qX{!u$#+HC)P-N5^LnAOg#(w?LU2I%AW664%*Xw%iujH zmkq&D*HE0Kr|vmp?H9zsP#wmW*2aE^fdd_UThf75q3w822+Lj@zQ@SUD#W)d2U)OX zu;2SS(j5?=ajcd-7Sq9(rm9R7JP0`JA*>&Il|D@zq@;h}sP8&%iI(;YO@)tTuqxp}%R zyZ{+Pc)}6cZ^OtJYksfH7u=R5e(xQ>9vqso#XfPkD8S(r_|B&+;2rdEAhcqOeZKYP zu|q;HY_Xp={7QJ^kNC1L9?(6TXZ!Mr&=*_mqbBo+=(M(H@$y^zUJGvPc@8VwNx@Bf zEy2|z_*yb9`<~GF3j4WQ>d@fbIF;OBV~y*5Y)%*jbXbjwT!S2VgG9S~X70o{Ml^D7 z#1ad>IPrVSF7ta2S#8-%5WNCv(NlbhY5QOzPDA+;gWOlRvxECC_j}*Pns3^*-tol~ zV2bX$!tZ^9B#`Y{XrveW+KnZE`==)bvoLga_q7{KfQY|wf#16;ZXXjL;3B~RB-oAw zp_0pHOx4cY&%Ybf$K7B12N}lf^0Ebc4$hc>Z~HRq9>?&Bev)sT@fG62f*SKyV*eUo zTz;4Ny`z7Pi^ht6F?S)`JN}8mRkRf&xFOYBk_`xMau4J;BHorlzqe~R)^`j^n}!QJ z4v`z9SF>5RJ2!iicWm~q!IO-9*Ky=&7UOrk=;-<=?oNs=$rXceeB#evbSAoz>y(PY zxI2w5C&NDt@?JwFpB#1&78+cqayFbR{mO54pG7Mvkf&ht|>t zvgwY2_!_gnJ2s|2wpmZRW6>9`zrFJf7PAj?H+J5V)My`x_Z#s(2Jg#~8b^+IH--^E zy38HxMjmMOIo%8 zGsw@84~2F-ZXc>ezcaFFwz8R{Ei4T~sFKeM-spVt)!ZPaI3GrVfx%lae0Y1|v^V<` z)TuKG`(hOTS0}HE@$7l%r1kf9^CI)3>aS3pukmjAM`<_DI%;LHr_rvwYCbp9uv($9 zVHl;kxA(^iVFqvD4YtS~JC$Oz$;lNs<-uQ!{na^o7e9(_<2yRhQC1%CZTA^dM=IEv z$h**+*_oX<;s1fR73{}%;Y+DoHNY5 zXQCb3Rn!`P-M4ntv*lyY!(C(a77WYpuZk`I9-W1SwL`;Au^l_|udV&FJ5z9oYGsWt zk4oyT*78hx6hnQAL4A7mR8;Kv4AdAk zorJ5H&$+%SiXG$XQR|ylja}cgCS!e*7I~XB-7#@})9u;on{J!BzUj`~^-aYWu5TKN zG0GkP&Bupz-~F2ef?yl%8l%$SSUt$1~U_s46CJtyM`Ua5FRaWnmC zN*3<;Tp53}XJtHtS9{928UME9))X)Oo)|Xfa^ZGWb7g#yGAZLf_DLBp;N``wBy(kD z96*AlQ+R@NGk%Hp9e8~Rhb-K7R%Oq_ZRI7n=e-ncQpTk085!5$_LAWiGz+(zW!aPA zcOKGYXFQiZ1!;0JzTR$Y`YvQ^itMsA9eCQ-)Un&vbnpdR)0f(dwx&a`+M2$4!`5^y z@9WK2N+w)+dlWnO!z=JCM*H%cv+!cJV%$Wp%6Q~zzn8g|XI!6U-}TEo);C7qz!d^r zavYn0@WTsV=7aA5reVh|SeCA}HAc}Thd$uX2&C18A5MBX?HpFcyQvIu_yE+d;{7Y8 z(F{=l9<*lb!k3XCC>MZd&YcgyIXc1C$j3#^5ccw1#5sW5kAoN!U&4=P*kK)){pYb5 zkjN0}_3ys^ID2qabisrmXLrpWtl^0SN07~Gp2z0+=Vh_5x7ONkf24dua6a?jHSmW) zReNtN+4H9Lnr>dmXUeVnlTk?CLba3b+Jj$8$o*(ITfcbS3*Kb+Z|<_4m%OXh!eV=u z&DgVCk7eB-USQpiz1&^LzaLb!XTsfk>a5pwk6XniAHh^k>5oPD2Z+~t z8<#w|;4}LbQyNxn!{_yuYxU1N@wtC;%9;nQhJFJ2o+RV*Q~0deiLqvW4-Ju-OR+`&}`-uA?z?|Ndsua?Iw z-#z#lKW?~b#1Ne?=Z|Z=?};6Rz2{v^tmkb@Z07~Z>DqzvYi>VSQE>aA?N{Ia^{%UK zH~ZX!fwuy$O?W+r*N1q0jh8tXJs6ZLFeo?S{W-jUi1)AY&I^@{ak9jO^l143A{9xL+ z#r@eei<458@F!mOJmlWCIBDdP_mTF9)n4~sYjXA!eEWOBpKi;0wEx9y*qZ)q|H~&H z`fTf(+Z#Ua&xUPXb3wzDo}M>t_`EnN4d;@h)=c@aXKCF-qsAd%T_=L#6!6-L(8gW% zaoT~=xYmroY)vZ4V7BEM%w3dm^8gHdTyOZQ9OO6kVv=2hGIu@XVh8+vB)O!y`+Vx17Ixzq2>EkiG${5|F8g@#T|zCinZxxO2$w_Sy14(wgY@ioph7m`vI;kD*Hy*-&Nc5gUhjveWPyz zV^7U9NE;a32m6b#U(yc?7X~-qGUKNr<$)aPIX`*K`TT?!zi@%CmsuKqXEKc^=40m6 zg}mA$>LTCvgz$d^RsDD9=+ir==1$axnOpFB_Geo#2}d7%3%>iar2TvgUWtm=eo)xJ zZx3rT^sm|5PJM*OQ7}Af$6(id3||gS4tQTirD;Ayk z?cR^d$F{-!#FhL_h$NdT7Yjw&`VKVjD5N8*ng*8c01ogTK_Vae}$TT3+fyG zAicpc5_?EoQFxm89`fRfWpTT0R&nwzjjM*-68hjb_DLa2zvSVe@Z7Ca$KChG6tb4o*CI<#$ zM}l%cZDDKqtwmr68@49{L-w_*vG0SO^Ppvf>$M$Y&3PWOoU^31JiXx#)bnZU=;3P) z_hUCR%cR(pRz-;_fK1Bvz)@L$@{8)5(C zo#af-#vifaH>LIL+~nXX-;IN-_#`{Fo5kM9V0-(dJ)PWp z=&}N7ok+`P(ut>8>^h|7$FT!<@`*VTTh|fTEo9b>xppN0ZXVr85JS(*!NG|O=LEQ_ z&y0M~FBpIwPq|dC!*OcFimSoBd@C}dZkHc^2m1w`_Zd3GwZ72Vf+4>jq*< zeqaq=pEjh*k154VzJCWUx~LWB{J3ZbY~c}@s?h($XWUiP*?Jayrj6{6b1D7)ZX~KY zvd(;#XVVpftMJ21dVmk%paY35+I_8?*%l{Hb6dl0c440gy&4Jri_O(-4-Oiq zJ7pVAw_$Ttfo%fcTy2@k*_wtexpNv_tBM;saq$aWIHxg+B@4T}IlN`g=Usxnb@Q%T zgYS2+RL{r8>foL3*ex2{gL~l6<2lJ=HFV8tbj`hd(={D4r`;2?;h}3>nZ<4XC=7v- zc${lw-61ppOS<%PKG18w?!k8qZv1?*f4C2WozIw&U&qJm#v?sTXW|gdk0*`!jKsaV zaY4>Y4zBopO7NL=e(ytAqBS!?Ie#RXpOWzexMI&of_ss`wD$?X54kW^?@-y7rUW;_ zeyhq}n-WaA%kRDUXpb*(2GNw@@_YQ=>k(i8#uUF`f1Sjt@N?8vqw$$vw6TxD*Zd1& zymk3nq(9QCXyvQX%7f6#_@SA!HpKV@FYfdI(&~IoU;lsj_6EKo-~W!u(1z|GgPy{p zgRwLlPHuP$S6PF*aGT9PV=b&N$;bNK~x z)%~*?n4L97P-_eGZ{vIFewctbEy=c}ch8PayL`P38?xxtm#@#qdD?+;oDQNDuOGsy zGW)T$Q_|Ve=ZE+c44j00>2avN~NfV0fT zTHIt@F*?2C#Eq=cmBr?~kH;%;Ha^KmPX_J^Aq zaZcLkvR)nI$CFXqJ4SawkG{Dv`ZV6J#`|u(Z^ruzcz^#Ke0Y&HJ~AFhE7(!tCz;YR zhqASQ`nG3j=Y-IEyY1JHsY}7o!l9A_Eye9ol%6lTt3ww&YoDOGMFXNc-n|vWAD!zug1zT`R!kzJehUb=%LORQzmz!oRi=9MXVF$wBy9D6Xop0 zekc3a3mR5$a5dl_D46*S`>q_{`_=M#;yVo2g3DsOU0ik+OGi;$o3GZ+ZiErH7>)3_ z)CkkSc_XaEJ8y)i@y;9J?|4TW*hioZu(``e26kjnYhk&($8i6;)HSUjHhIeYJx8#c zJs%aoe;u?Z1@Bj$(NMB!sgpZr44Zs-_VCFEFj4pr_$`Kj?Z}4DezC@tmx|i+HM|2Y z#e=iKID!S^Ej9-&#!mpNt+;k$_+UurBjV?LL|}|ZcPBNTcrmH5`_-gIJ_>Z>Uk++6;px({mmytk z`O-XF5}R3Ty)KVW$S^Lm-;9e-#)(75^F-H+M9V~?W!;B*6BTy%A0K+?dHblP|LSEo zbe~3R@RnNiUt?|J_lx{1Bd6Q%{qe!URs8#^nflYtX?3^qB?FsdzGh}FXLBaPN8e^y zhl=li&$_H&bz6~+Z3v$9+<{$%%D((UzxOefJqP}Ie($eUcEsP9>-Rp`)pM0HgZVT4 z-g}e*l7jQm;kU#7UGASSc!v(-$UcN z(B{N-f#r-2dhkUfHgUoC5ab!~tWBda5?SyLXk5*+eJ$`EXB=wZjb(Z-{BaXf$sgdZ z#Wf-6MDsjc*}FRN0C&XFJkJ{Xd98iWfXZRP75>qoHMRCJ+Iu)u^EvJM-tKkWpV{ze z#ohR;SKIWNLCYq-!t>MM%KN5%gc$T*^ipRDiW&7r4#f&VlkazitP-G)G z;$>i;nN}A_W-&h=X1UjCYg|5j^^84E6&?9^7 zGX~ZnTlZwo+aK()Z%nd$b|iH9i?}{s%x4ICxfoNG_dc%l`q!mdPmT_*IA>yT)7=yG zFEv|+8B4$yp&c*UPgyn|32l7|?w$GtsMoz7?)q0Ty8EBw?w&Nm{n60BU$R#Xz;Frw zW?|^Qm+jd@@cEhFE^K-X?={aX488iYz36;IF(a{kIHu+=UZB5@4sJR(J*b~6Ik5Ck zXt`}>Xx=OKys;QH0YqTWEo|cNgD&u#;qUh8p3vj3;13l4g9IDD@ici5%5C#y*wDbq z_>4ODW|h?}vbj4wxas#sHcqGC>l^>#Ri5#6SJ{)X{2lc)xwCG|!2c(3k(>IZBBWj%G z9vO^$kQcOEztMXN@6W-Wl-}Ttc36U)_#4~#|JV{5T5liYO-9$@sjlokEx;SOa#C

|5lSx4s{vX0Jv#g6^%rQNfO@AA!Q?Wd2F$}EN(#NEk8MtFa?Gc@Eid-m!hXlY)c zgmE7*;uigk4~LQ2k0b8i`gLE(D}*(qzMOX<%HTm6_}#%qr0YRB5vww*8GkB6@>_1? zr+xTS`3;(^*TaG@l6iisk>8Fv-Lv%u%p0pW;6&cY7YbHwuq-g2g*7^6chBZeM7@pI zn@^1no*FVH$iHdabnZB#eQNxdV4>xA$D`|h!2P}#8I)pWTS5A6~alpY>IgSJ>T{G_}E-)V}4e z4%Fou8f>W%%<_CZSa;}xH|*ms_0VLG8p+B?vQ8UzG^tZFc$2X4wO1wKbu<3dcXTfP z2&g6{wD}Et)(!8V!K3Kh*o+~K(aeD{-wg{JlhPWzS$bLWf=*E! z1#^rF{?;fHzY_cbndyTBk6-cG@@!|wve%w#33Y}p+-uLs>N(OA;xTmpcEjIO8TWtw z?R)mx7bICO>0Q>r6sVJK2HBtW``p(1Vulsw{DOo+QZ&_5NzrcFSCkWGmE2d-VVC3sFq|w#-&W$CKjAIZY}I!A!=A((3a}YK zZ>czM&inL}6Fd%>w^T`9*g^&ND_~SAlQ(>)68^&pwsnUve&Ah@f7FGxQa3^uJ+d^l zy(@A3<*w8?i&}@oZHx^f>k}ciAPdpjI?HVeT9K(8?KJI$<)un0%vz|SKS!N7pp0|e zCsrGv^lFn#z!~66t4yI~%xS0f1N-O`A#q^R&2s8cqN#G*qt!Bgr;so%#FzSj0gAlw zLEDU+{%fE`E0wHNa2p@Mb`;CmDGZAL3nI2=a_g`b^{v(Jm-q#9rf}0pwQ{?IeXvuA zQ9XW=?cXVA%}0S}n9@4z$;Jq)`&O~qq&HOSpwwtgNtM0>4E0@x`Y!XS?=o3*>j`Ahoq|)miT-31RL!flXBUzPZ0aS|fF2q`iC-bdkIOdZw-a~>ktfnd zA>W@Z*(D52v--w}%TQW)PJ4u@*EC(u7rZpxH{y3n#C1LqUD)@@e+d@YsLzr}V-9_=(jNL-lnO&5~$=HDPjg*f_zaf%58M9!P+0+}e(uA}f zzhe@D$QnLY5(Pswsf>44>zX#VA&UJ~BXsZmtuKLv3V~!8DSOj-0tCp*iY8|S8?#5y`P~NT#AbXd z#Ob#9M*T{Oy4NS_4EEnWLRUb91hs-W&IZAab6ZvRZ^ znb`s<-G=s+g4VdK9qmnI@42E`+X<(n%P@tHmbb&#uq~en6FPklGWq8-M{Ehev8_X# zbfl4m?h}UIUW;%{1IvIX^xUvO<1JSSfz=`|X;Nc@A9;;Nz2j0}vCw@h;lmqxOhcaio zZUUJ-uwm;%pe+H)V3J-cyw8%o_(t%zVJHpwf*ZjH_m=n>mh3qWo`iDgfXE zZv>|T0Io`Pu*nC6lw>q->Yh$guf%SC=%rnPUpX$vocD&40 ze=8^(L}Up4M=xvu{bis{qQQ2xAibgqEl=vp4XG@?rzxoNTM1!)xM{r;h`x)6CN#zT4G{4LqWy|BF@&D&?) zq>>BWB&<@t6$bFf+01W+Y*k$Y+w`qqRPAnHm%bI!%qPP+OjIkgyChj28v!Nam@MvG z&UyDVFr;ixhv`>!3--efeCHl4JD6)vZDU(1o{gR4YDF#kHdIuv0FUPM-kiy~d8WHE zOx99uMcZ(rb~uK3m1Oh;%z8Y8ZL1ST!{5c(A|)YZ?5I5ecHzoKFjSo9 zla@V(9xYu+;jE|3y!Ae0#pH*5<^-4pfG$nu3W2jOj|+w8A1!QNwA-_RWMHmC*wa4W zB&%+1*e?EvgV|c6nzqi!+$m9ixB+Wm(6QFe+`e!+XEk3{;o+_MJyfZ#C1bJUkY&Ay zT~L%smbE@DUdH*2mW*RZ%k~^PKTGyK9b4QBH_HfnfH2huK^}~~1Wf)?4tmT)z}>Z~ z`qo*2);PKH1S?gV#%-*=bhic-skV_5#um6-B4Z`j64C0yAyI70{;M*dMP+hsRrTfo zGq+h6Rf z_Qb8~8Lgu5#p}0J3Twac3*iaUB^Ke#w^LqkvvJoZhp=Erl++#+s64z|B8 zOt}S{J`-`?aDo-Jb8R!6m7Adq&EOaDe$lYqO6`Fht9fA~D)rHioYxG=>}=3`BV(sqkNYRjqdWhp4$4 z@Ml%=%}lEPz}5;pI!L~Iv7!y2>4uJ@=>;5&0Vg+J_SICTn?^Mv85BuWJ zR$x<~=FFHZ#M<5mu%RcnQ6^RvCr7*m5o-`}pKrucC87~9>Naos!roS3qX4UfaK&D~ z{vi^UflCTVMWKo?xa8w0wDqdNHY=?DKUi$`Da8SWKyR6NobCHXoNUsz$e-J6LaCac zqD13tZzG&)U?G~vgpFiM3>i;rf>L3#I$`)JKD2xxZ7?H)e<1@@C_3Aq>~uq-0#2~m zh;NTTn~;r?3GKzfvD@5Z?9z{d_SOpIm={U&>? zlTTrzFnT{sC()$`)BCC4*yN)^yp|GeYwCGw$@m$}P+HYe0}k~~XkyPF74$K0BMo`i z7?vM2B431=CDs$gFlDA$ykGbe2wZbOi^$F#Uib zOaNEC0O8am(<3|^`@~Y%Hl)M+*+{p+^G;3p5}Lb4W~mtclfSZ<2IOPRZ)|*n@NlPY zpd)XIde|oEH@3Gy$W;aY%6c>klU4s5V^83}&wHRjtn&x(eOV_2-zIDgtEsHC3R2?~ zfXNUM%?kbz0{`6-KAbxfT=lP(dLQ+00n@k`nAP40J`ZQcV=dW}8aG z+5ZyQf8DQaN0acF>bYN8zvDtt`~XiG9=oOtFa65CJTCOixVA}G;?PcAfK=ES%OFJk zS6&HzTcA{#V9EZ~&ief>7-LF)fqGC+hS5<_sbH*x#ov9uu;+ir_WdBxpsMo9(2Idt zt&@Lo$F_uZX}vH-g()g;%YoUIZefgc>2COmUZS?TYB}kn-`H=z3o$(ssi~kod=_bt zeuCZ~L$NPG6^SOn=n-S#3@M zKNMjkTwnHlZ{_HlG7NzXx`eY$4vW=)gKsi6enMsGbeM~39rgs*I+T!;kN^?cf0S)H zi3P5=R{ln3uOENvC!1ei97?4T%HWY#iL*a|$0!HhfLz<`@ z_Mt<#C3+PNA@X2PhdM}44d>G=IHHF?6n`jFWFc2s=>a@HGMLkApyY7_9^ z*YiFa|71W*;YxGGH0$6MzZ6yK{jLaTBe{CP9r0^U3;q$%cr~DMdLgun+$bw5V@N z*2}$AhG|Gv=H7PHj+X?q=N6X)q@-kVk^xaDg}py@%x4SoxeH-zz<}T=w(?J*^Bic1 zIZe1kN4XjxRTe@0*ns*bBjt$NF!^u@)xWozyj`XchoTyemt+(7P)ELC4TBqInp48i z8S%Vz(1_enP6B^pp?|?NI0~B`=BkuklSv8ZZ0{d_yXg88`NuC*|y0CL?}^K=iFL>RSiU z6=?0QYb?oDG8}E&2{;ivhJOTX4$pb|PLe=00eq&WINayh^}Za1fVpAPMTY3t{B_<@>L0uHpdeP1CmC^Ns-vI9~8iC{tgM3uQoXIld<{9q{g5~ z_QrXkGnI4FDz@XiaL`la(92UuI8kT$;BUeE8hUz6+v~|;-q%MQvLKWD^95n3x*9d~ z*OwzZv$6|;`@F!aN~$5_BDN1;`=`e{15tm4d1UQ@Q{l_ zpi26Q#awJ_3X(u9+&$4hB21BNORgh=PrF_1d=dbg@^W{7r zAqcV3L*zi4*sACUmfIqXPB{Go#%Hu1G5g(kceINq_DPG7?8!d~dAjbTA&-;lesr^D zFuo7!%_LcJ7ANgQ6iRh8Qt*|yB*{h~tpD5xV%eLmf;j#cVEzDxXaUP&f@O1nC23wl zBL#6C5A7&XI^^jlw4Hz>3AXIE?`4&bfm7ol7CZO-~0pt7`AxUKI=<4?QNPQXImeEjo?IGcW6MSqSf?B3Hac)Nq4q(9pTh8?4+s9Hs{o zE?lRTw6|gC!n^8}VxMd~f`!u0S&BR=ikIgA;Br*bD+q9B^@WPk z=gdOj*jAcJ)<7phrOzXQ)-7H#ayU{#Cqgk^^+v{S1g``<5vpqcYuxh}su)^Cr$C(3h6@)sr-Wh0+TJg{^;)`lO z>`kb_v??$vu7zmA?J_AL(zknp%d2YXtg@;h2C7mZ>I_(97C)D+D=tZI40%tO`5r3SmJ~$tLYk z%HA4T9fN-M?f2;Xpry0pHX8_1!q3G*jqodt&~H}YR3PG*W7c!hXI^9kdXew;A{PZn zoJlPs$E5I5wHFs*UfkP&ON{3&$Z_?)jNjd#wHGKUMAFs3|6%b9>3s3?>8j#o>FVOr z^y7m{hGqQTza--f*$g0OnoQEhM%i9Fft<>w0i5(4stWsBP&tD+dw&M^;GbnQ^<Utb$su6jn6;Zl=4H;%MjZV4$*A;i|2;Bq&J zpcg|>DO;VF?lxkd4F{|q+Q-6FVqf);UxV2gmDoA{HZaE#C~S^>$(`eI2Gx;8TMAg@ zZDNn9M7?U-CibRE%ra*M)mxJc)g*>#T3Gt@1n2WhCpcfgt>ep+Y4QP z@e|{s768BjKq=a??%H0gN{7FZ%R=WdshWhUYf_bw+fr?(J{Lp`2)~xPc`5+*L}Ukp zI3^|4bmFZD;}%U0a%O=W@&7V#URgI#VuuDxYm$dc<&TY$L`?jOj8tjSw#ab`-ZH`~ zijvr-SZR$aK`PJIO09XE#HFaEBAg5*c6$}wi01PuC>Ie|Z7ctded8}aZ7#)d!-vS{ z(>8KA9;S*gx@aSc!;v)md;G4Ny#_kNwh?x-8&gM&-9?k-VELYk zSfScw2{6pw#dk*S`DXZK0%W#jI8{zORcr7hjy|v}NKQOeI|^YYpTudBTmF42r3|<{Or<5D2&5gaEIzWRC-!!%i~B zk*JGdU7-!aCWT@crl5TTo#e#{{HH|3Y&3-4q1A*>eTmy zWFMeyObF_GE;hLDg}{)$O_8B};Wc&Ffz^iA5-{xVYGuM?rd=E2TCay%H?+C~A)rhN z+z>ijRT-MuN^K}d%A+}l!sWjB-GOh9=Z07#!OSq`N>pS5t<&5LqfK=~oKy#nv&5I;In!TAJw1l2ZfWvQ z#SWP4GH87hhdEZFe#Rk;$hca7!j<`fHm&JS9B4tfr7c_;!J8s^X)3~Nyx~|b(7d53 z%gjrY0N~&@MIoeB03bA$67Yo6x_~Ai>r?pp(UgD}A8P@bP!lH&rv$v=n1jj_lgIh` zG@_5%QRsJ7@DFoRAEJM&2SBSSFQFckfG0dt4p*jBNt6J>Ppuz62a3tG;}}<{IUMiu z)*RFVGXw`knbp8b0+t3&d{4n;Gkl6zJJiu2UJ`-Ro+VEa)V$<}aDyl125%iilS}b)kh-%0H{9XI!cl2h>Zyjik?u7SoXG5JjMQ-lWGy3 z`D$+HSK^0JjAxbjN zQ>1t$^w_JhJb@IyF1!Ko=Whm&<;=LW_QnJ%66L=xukK6>l2k-}P0_O!B0GfFd zgdD6_r{4s=2k^-^fs@6>_?y5p%|IA^6NEy*hu#EECL8^30Wp1 z33$v+;0=I>-UP0Lx+vhraI;hhgsWH$+>nU?zjPD0F4U6!=S|=_fSz2r6O+2%4mG(7W->Gl zrvW4a!ma`Wk_L|$8u8L_kdWOTCdNj^Ba))wO|+c^+H`1knI%k&BfAv2#}-qMejh#h z7xd`xXsBPbX)ArQ(g8jZaCMiok{iLFqWE3Yp81|#3d2fyH;WDz`>VPgX5+)fkv;yE zf9^}mOBdV zC_T}pX{G62gMaleNSv*V5PS6~1KMBE>;J15ePVFqOpMfkju!Ym`#D04SM5B+E=7ow zrWYWK|HAi6kn&6kQYP5?cQn^^;qNC%Ie`BPc!xW}QN;2?Y)vO|`e-9)``(I9#b1o# zBirP6J}p04HR35x)jjG{b#!t0pgPtsQq=bdM^!BB$5ofh>;ttTM&ZcApaBiPavxum zE$lE`8Yya%Bfq;&S+=9>c9b3L_~Li$(?~H!HSQ2Q5-Fx7U-|Yr_)$2!+;UZw6 z2VZ}P8KcCJ#$(sRKa08oekQD;?!I1K5&W0VQX$||Krc#+3Gqi+7frHM?@s0xEN2Z- zVr(uAT~%-zYkY?6W}|HRu&;dnD(Twk#OZk1*z>?Q!PX~Wyt(CDH{0sjD*hAIqe0O= zo~&7GvU#dCS3RPc4nQ>WQX}9*uj*SiGg^$%{;Mf#P+Y$_Nf!r=x{^IreLb^9i=+8c zb}CwYJZdVqidyUN8Wnj)8-abTa`se=n3NU^;th#3{ff5L{7>Z^15Aa56Kzw`Mm3GH zZravW&P1ebijs-Z|H=f6h4Z>}mMXiz+ce@`7yeb8R0u1s9fz4VR*V-P^%Sh2o*84s zndZKz6w7FMSVw%y!&^oCh$w{7doIyLS9=QIzTGqU|7g#W>*d9#J)Z&GvleFWju1ms zY4xmMoVYZU3c%e)?yI8oe|^h##EEID{ok-Z4v!}fF*M@_cCJcBSS2ui|v zj$P31CSfuNfx}v$x*UNuhdY@&m+}v;&O!}50lZ@{yAOh3eg&%KSO}BNDiu~KY{Ti2h3#&+b5V?sL{YjgWiwE2Jw?;d)sn zIEtLp4?23lx!DH!<|wWYHYQo$E@BElm)+3?I`Ce|yd}+0&A^nfs41svPn4?|zF5CT zo*@iK<6MraJ_aAbw_+!opz@$B~jvMi$Dtd)u@3ax5`Mh9^lqE%kOee~A zX@As+L!f0JI<7j5(m>}60Bnm&b%(TD6@E_VA?mwR*Mgn8eP6p{8`L3?tcm*N_4LlA z)!?5FIM8;W*H-*V6w!N#VNGkoKyxIv#cD-)8Q7fN;GeW#P4_{PU zAXB%HSM@OLX7EF#zwu9<>2cK%X#%|LIM&Z}l2_4N1a7cJZ`f5RW~CP6?s1szq!*Jz07T+Tk zovu9r@8do1iFi-*yr_>^jBR zUby0BN<49}4U>9cw|K zCXlPYTcT9L=_EUj4J2a@+Y{CQF7TV-nc3YxA@x?^o8YkiHvAXhc?1tMiY^N|ut%-Z z)lUx8qCJIkRY+MbVH&RO&KxeqHt>=e>q}S7D+t8d=y+Z&O@s$+w>i{$Y8E2l3`50lp8b?q2!CPEe?xavGr@Sn>{1j zN_DaQ0HiDG1X~1FzR#e~YhVR_#mqSq`@*?3yu|o6iv?;)6;@<&^YluVO77_)=<8p}rIt7_vFsk)Ec*xV0vnK6+vyni2S>>$vZgX!MxqQv zbi%o7gry?P@zyLSUC`rrFVSf~{9;BMeoh8~g%j^qv1 z>HY?1?3@Dm=9>mwtjd9{PN_{UN1(~2BtWg5fE~$rn4QPKjd-l>M>y;!bL=Z-R663& zmaxviN$0>Wm!Y3&L2b3HOP8>&8+sykY=I-ltD3y_lr8iJA9xQV{r9kzdjJQ1nuB zHh0c(Qnjh-wb#ziS$bftqvu=ksjjTUlgx;m`n9-r4myyAkI`d;YG}(WgY(i+^kTR` zwWpM2T!hD8*osMwcr@^EZNyn98YXbW#kL7PcS$aBg`cN4M4DV@hnZZBFV|!=#hP3v z5;I-rMwwiZWqYP{Dyy6FdxFVzvUjFShl12-=4($3%XEd`8D2XjJG_2M;~106ukg!s zX6Yp+nR}z`FNN=&qI&i4tjvJ8nOxc7S;n}zS~Z>|T*ty0af(fing%08W3l%8c7R0IbUWky4L5tg6`_7w)#8C+9#@$YA}437Y#1^DEzO*|1kW&H?6=v2>&h5?6SXw%}6A` zaX9S+`zDfp3F!A!cNDJ4L_GmU@?a18oc*D?4Ex-&3@=>AVX)c*9E&*shodcz-31eX zmZK);KgUeY%S|TuWbbTiXRSc#F0huP8Eo{I$vFwq?BU3c7c%8Tuio-^lJjy)lH7ol zi5xkRKqL|fa|Fv{=}6-rb&m7$KPG33+vLp8;-t&wARPt{Jl>oaY9PrpD3x*%QxOb$ zoZ#mX>(iwxP_;JnuE{uyn|Rb^k7%jW?N#M!XLngYSs#{F9S}YbTd;GrI={G?DZ*^6 zAD&aOIZh+EAON@a=m49b$-`F0Z0xzr$5!e?TC)zD#6{R7{tST+;h!5mTRRcAJo%R` z)%N7MUCFof+Bp$7J<&$8zwm%IiN0~$(>wUa%_Mi$f?#(F!;Me6;d$Dg^o|Rkl00x3 z|Jg1HggfSzUfU<)E&>fMdZO>SDcn8MB;4{u0NRD_h1;HX^dDfYs>PjFYQK6}8x7q{ zCTgLfcw#{nu5U;klU3ccVnP9B==Yb$7d(vdo4nti7=*j;-ooq!nKrzZ#g6tCN8zrN z*gj%c@!iZ^EnR+4m&r!=5&H?}@STn4Wwxk~m|}M0FF1u0d%LyVW2d2hPmNd} ze+o-aM*ug%%WBaizCFT)8cb8ElG14yy3gcnxZ5OOMrH3W-w&uC`$tH*6LW3~zkuC0 z8WrrbOwK0Yy6;PJy6;Z%-j%=t`-+_~wUt@+9i%~mZQ{Fs9LoQ>=6qEM_AL!BoX>|W z(YPia7I1&3=4)Xsmd9HhM=>wrx$IIkH_U-vtfG#77!!R=amvV# z$>Uf+V7#fmglS6E$L_(DKr39PzKU}s-bvkmFSkz`UW1Tuyg1XD4;jc6&T4%Y%OJ-K z^7lMBU@-#h?`Ap;Kv)fA` F1--whyqD5@vGV>L-XDjl-{bLJC3}jWv={SjI_r`( z1D#&&CpCJ$$H?Ef6AHDA1q9s-)epav=XABk>HxyUeRV+C#?P9eGv0 zd&*3%L6U)}$3IaG#nTfH%~`1JyW!#SP)goT(-a<3j`J*0QHa+C|M7Ta{-NtHFl8cK zd3t=^sT1Zi9GIG?{hlst?ErKX%%g^fg_M)yt!;byBG|nilqt}7PatC|(Uh%wY^%rdBed0)! z`HO9@-zP5RRf%7)`1{4=_WmN4BU^FA7*eagMX@P%VubCPm{w}F&xM0$L6n@;Xfpg zlh%ChX7E-UOJ#f)|Fi_UUi=#913mE{$rF1dSrE^T`K$_QUVA#gwGZ0IBz16-nR@Xu ztnkUo@e8P)O7UJ5#|?&E&j_=TYt1j>BdX%#hT)Fmh+c7VLm{k5yR(sN9U>XKjFt|e z#@C`WZ{S&C9_M`HMT7G)CS;3%^Aw&Dc#rQ^{@9l6o>JToeWcFcl|43&S_y-Pk%xDQ ze3fBDehfDRY`GC^xslWfd!h9vyP>?#;94=Mj}!o3j`t#Sm!QU?3_9R*BMF2#5bK3r zdPLPZ=$I;gZVD_qdylBdCY)QAB;FY`|JBFF@IiB*E?gF`!A&Dyp!#s2rhX^p2!d-? zsotOc_H)q4klS!c6tQ>`s_aqLpqdaB9HNB8A!IK5$O(%89HgTT9gdJR6oB$-!3=dB zMls536C6*JwDy%ghxZ$jF7r;KsX>$8%~-oY%^`g?n=3a!37n5GNERoBVI3~5&%=@f z?tJ`l6vIom5gRaVbW8h5IUj*A`TX(p?Tys0b*=rRDmd$;$aI#m1rsZ!uOu`lVbh5U z`-{`p`7>!Wod=J;0hLk zrJoz%)hx!Q5il*my;46y+?Tp%mEs1NJC?b{QaHsKLc>xiT<^+ZYRvI)!3r@%EA$pJ zbATy`IatNTpy)B^Pu@IM;zk-e`Q-iP&q6thNt_9Z(9)g~{NZ%q&{4$q;FvX}*sTNK zJ^(4S(aSQjBqLVo(_7X?<$`_gL~YT2SqFYSFjS&Ad0!2eDp9?)UtmuXCwHj!NGs{h zMG~Y8)!Z{o*CR7_Ab~U}A^rD~S+^tl9^Bz`0TnqILZVczNL@;B-$-oC?5C=WYOA_m z82`7>o6UGYjOgZD2}sVj5=@?k+sXF)V@yaQrprVhzP4USHM;vV^y9kYLA|?j8$7-)kFWm&VwK>;^XGt5gQo)hff`en z-XAyP^7ZT1^Yu+0yh?nZ1kP5%!?h!mWJC)PYk}Cr*Z<^2#P_d2dLK^}ZhP~}N9q$7 z+WLfYc-12#jbp`riC#RV<%MS5U^E4|;T6>8mZjs^i(|11jLeb5BhK+kJue5HM*8T; zX>fm(ivJPb0xJdK>fiL{4+U9=ye*dVcQ0vSs+BaOn+pfZN<5zm;OfhK;+e}4NuF$h zm2&W&7|t!I%=GRkC)!F7HVY4kx=^$7HY#q6E5Db*peKbAOAdP)-*-_M6s}~JM69_8 z-%}|pjPR5#*!lRrmBOHdg&og?Y(kuifbkRv4X%8217Q#1JCnj95eD55;ZX+DDJ+o) z;$#NGX5f2R9=kdY+a=V})PPhW>$&=DpMp*Ynzx)Oc&BnUjBGC_C9lIn$_Z~dDfuoG z21SOqoRoYlh24rUPdSI-yAvKWyhgSaGz|eEgb1w%87xs=`{G+eVbG9x%h?OxY6_cz zFi$xtgI9AAb|2AG%Be+|lfs})Au}tY*BN0KC=8kxm{^(Rz$gU%MS*v6t{e|y7{X2? ztV#{`n8mrg?2(hqO{>V_>yH6uz!=tn#q#)i71bc%)K>yP<9otGUunauRr*vb#;uC1 zU?3vk3Xl%xvNtD)+7P8bVD1lz_XX3Pz^PKxp?m$9eS$dWE^02!Y`x93PbQ)y_62Bo zn`;f;skt)s?aftl61a#Cr^n91rRWdmy*V8{Y!S>Mbs__q)9dn|h0A3MfZ!FJH~R=^k7Z z`f>4$*2f{p+rvuOmy^Vp0FT(1dH;AiIeQi}&__(SC$iLA#n{kTh~eqDrptpf`BqFT zJ@4PlnC``2y3^1G;8$d3y7I^^`zA_HZDUT0n&*+2LP zC7u;nI}}R4D)A~2a)M=Enj97E33&}6XBhuRW|Y~k;7AB@gEjnM>@c<)-VPSgyqQ~+2P6d>%re1)CS*p9eAkmE4Zcf5UASEe!E>vCgw${6y~+E zfon%ZvZTpk7pi?K?IZnf*D}*&G0q#Xbh0>9HL{j%oh>7wtZ@~d^ z7JiR7fTiCd{>L|@4?A#&I92?;#?3rAk=;IARGRgUz3kp>G0ohV=XHIN2z9t1AAg#R z$&^KLie+=m_37%rgel}L!DF*thQ4PN; zr_49td-^{}|0hgSAQxnIR3?P|^^b>LvuGG6cKocre3zUK@RWTp+JR?7 zn&E9h=U;>LkE~|mH1R!8+B>F+JvwcqVxkyn?KLR3B{|Mm&q;6YVfwp7tt!5TUCkGl zt3Iq{%jaMLJfN2CpM!Pnk=-oxVexUIh!y+N1!c0!hrcj~ zhgzUBAJ?oZE`7aWFWWm$oTR#nTou4*?DM^B=9J(Rc6))iR>k(R(*@%6*2&oNkUIH`#OlsjigR7$ z4YLX>FAwwmwl}EX04k{0;_Ver^&SMBBcCd?IAnlup2zpsFj8RlA0v~^fw*a%9Q|-M zEK{90P*ku&WvRBR)%A{9RoOc1nuy#}T8n5b=!gG%as2xa%z?u2{uk`&AAL3~;T*z@ zz|(UPD+a*D!U(8hZUcM@AHU*Dz^aDzN_~G+YU+pPA=VGgL#?~b!>k)08jk-F)@C!h z!dqD4OyyU+o~RO=&try}J-*YOq#Zl2?v!>`E!zHw<*QeLP}t~@wb?3--hhP8VVmYd zb!_WjeE30{!2FrWS8u`v$e~>PiZm=7M&TgaU%a@&5y@AdN#LtD29B`)Y3_t4(&{!x zSA6U`cGsf!pIMPb@5LcoG_l1e&nEsY+**nhp1h+AJD;%M+y_{5K z&atHuhJ~|gnD9Sj0gDY7uxcItyCpx zm^I;IV!d{R3RhfZSz+AMY=RGnf8dk!AIy^SUmV+-4_%Wt6IY;uTaS#`5x)VoR)O~~ zhH`gMCf+E*X@gTsxau#GxjSBg9o(h0T=hS9a>!J4>Z$vUsHcjMf&U*{dSgVqn zvQ*OXT3-6y4Bg#{6ka+BrgD=jSX|Y-rHGeHw)}&!);_%E;KRIl@GUfnE}Wa@g!7Lv zyrww^JI7dc+eU&xm1YDS{H~(gYQB=bWoC=Ib7G5WtEN30y#;K;vGqb zZ|kt-%}q}Cv?tLAoqrjvSFowdk{+0z6m{a1Q0{&iHVW_xn+QFJBQ~>|&Gkc%hD31#7~Uct~IV&*N(AnkS}r zi&}Go9Hw@{!d%IuMowGf$zy>`athnl;>bRW)$X1Py_E#x4v11eN~-pO5c4SV7#@kDZm zhUnEDBkWMw*IxP`Jz9Z6cf60hT?eeOyxeP2iyqwsvT_lQt^`x^>|G(LA$s0GmCGj%vpZ* z4y**PJQ`%Z{7^8Czl7izOel`Sguw}6IJ^V`4z*?2L>~%v@p7wO+>erK!Oj>K^GV|-E zq+D(Dpg?Og0yR9zFoQD{&s;oBYO-s9m4G^y45ajqo*L`v{(`lUtf2S8i-Pb1^rVUU zr+1)>y`WPO$kac0Mz2AB6tQvNs8AQ<_eskB2SM#-D@D!XA% z()(8BeIdQul=lUAC!Iil)GM?_FuzLF-{QwbjN#RD_h8m1=nU2Lo{RT~HDAQvvPwvp zBTu^%^*9n>J|gV8->Hd4tHUZTk>{K3!`_OQkD%5n-qvOB>Qe-8jp9+Ayq8cWDWQo- zC=tYY47;VtWS^{_yAFEqIhq6Uy;f-wP>{idHy>iM^wayD%VG@9Uc3hBL^kI_THDp; zL_Km7WkKr~qv9Jdfo}xcJ#`t=yq}S&kk)OlHU>y*Fj)}hzL0$yRurx4IcsZ*%1XOk zv{--*iR~4Yu)^(DTTf%SjaA`3E$nAB0KQJGSVq6*&y|;My59*U@;R8gPh0lE{my1s zBb_m$nonazQsAH2x)P2RZ-0(!ec$cgk{Y5}aT?>%tq6yfzrHuZs}N2bCDc5$0sapp zC}q+S*t$&w2M7f(WH)2@K7&l2zD_0?W%5I{^$arkCphgAXqn|)HgV_!v9|e?%N;(s z+)BBOv7Na|CcpeYGI`K1pujg;x;46xg;5fYm68jgJxxv%^Vl{U^5NCb`Ek!C}^HR<_B&>CtL!Gs0 zH_V*B1e?8r$$r(PC5IiIxGlJP-{QG* ztKM1p`Ua=@B{SG32<-DGGWQp_=Bzr%cJ4VtYdFl^>%k!#!66^;K`StkKi3y{^Upnd zxIZ7hA{>w1e^2^c0sA(5D3kz&>EPFC$B>R5cn5*EoDVseintoy9JHc0h)x3A1%W6w zL$>7iFjzw)gcY}Nty{kd#`Rnh<0h1=@fD381|J1@a!MCx_!C zZG5@N%xQ*6M%>bvcYK&snPSPdfnDxULj`#)s~s5J#%dSPBo)BxfCHtl@fm1{1`m*O zuzy213^*pt9NM%@T`*2-a4(i!E$QIb066is)j%481fds{P0L{yvDs2ItJR-nri+p0 zmQNJ+{dybbH&Z@^XoP292mp7j28&3I&4Ix+6_yWftg|?wCc|wGw~|>BytX(we@h0> z8#dT`s;%zce%4c2SfLabrW0NR{OH(wiU<#~+Tly*v^&K5vVYt#N39?B^&#mX?fTRH zrlaR9>*-p9^UPmxP#=`(O!XI5^n+Xt0Uu39jTg=-xU!cwxJ-B;y`)sY$X1NzeH!3k z%iCp{lYb?1@tiBUz>%Gi#N}#D0Tfxmb3!g^LRQ9teU$wCK;@#Y-(WHZ6n%|gg^x>1luFq3G>z$zqz23}Ku zC1cfg%$fTXW{<%?ISaL5fq^Oh=J)WO-_PKDvIq9$i@HmTrmL-Uk~s`uv5GbH2ETLg zQ$Otqy}?QG`+MRaP{kf}t74iBfgEE4#Sx0AGJU7&T&c#d~6(+MGJbUx6CjCbOY3{-En66qa9r7U*AyTwzDo$*e|{jhc0 z{|1Qxy!mtNgSv}_YumDYo=v@}1irjIy(t5|ARokh1^fH*Yy>_Fw?dy=tggR^W$=Y5 z!RR3&=pkxcNWqgyy{!;BK9VvvJFU%S7Mc>O~K8 zPU33QgPhB?=C>x3mzqQXQ5O`_`;MRlnNzN zt0gKCl`Ovq;vKF-gb>3^ry!;CMfUnrVzM~{89zlChLuL)Iu7SNIEf}59IV?jzdm-m zs&G$w3N##xpsV42$$7*8V_)hG&4Ucs&NsLk`lH*SFnPdHX>zqGWCse<-`sdwTGwP` z0pp6whi zmUTKnvs5g2y%T}Ys@cpDVvqP8*Mx7yH%$;$ZeeeZ5VKWpRkP7HoW#u8#>A20c*M}bJvm`fE5GQF_(jG~P4LS+j*bk|8$U z>&?G6?=;i#rX`0Z#Y$8*?2KQ3j*Jl}$9F>9g&0&zuReR&5zK9Q1*cjn zjGXk{mTjXAus$2Q6@t;Vo1He$PFD=aGZ@VIPunmg0r7bEI2>K;CeiJY{8;?CloxHJHBACk!g#?m;LvuV9&_5 z7K;PSK?SDq!3FaJLJIOGhZf{M&5^3qSsp}-k4Ufa%(|z?@0w1hh)}q<3_nJ0v(6sS(u-pFZXs*m<|ue z9w-qr;%;ljEnI2t-cXD8?qcPRbB}(B<9c(j8Brp>$)98Yc}`4>&WYfrS(0lq3UgIb z1=g(gA8-j5TlJjSG?V<6CH2DD3aUa_4&`1@S@EypNf&6laU) zvw~7FcI@X@u8|h+Lt2!mKo+_&*gwaD?6ot1=RG86eB@@Q!{V;6jWIgfTp{m;F*7Dv zw?AmG-h-*gYcZ|c7RR=3L#x)Q7EN%`zk0FqPZu?*o}J)QW608=b@Q+^&Fht~?S<}= z3z(Y2Atp>$Reg;vbdx$A;7NrOTzP2CydRZ|o@lspK*b{j8D3hp?SW-()K>2VK#gy3pq^Cmt|b#7@5e(=IS%^Dv26E; z5h3Q&ffKL%OYldf;dVi^+1WJNPr@@Gg7%QtbZFBujz+3{%v3!i)x!S+K2L$ScOP04 zeh13~=%?gG;cNwgMjmAtA*T3jL>p7gxHf@nm};5_?ulO}Gu>>MCU}_cwj09DiXvs~ z4G|Q0`u_nRtian#NL=gajq8mR?(E}*xZuV4Rw;LgN;9V4W#~SkKHpD9( zn&_Gu3cf*nv$x;*T}$AaHogLRbF&04{2%Z$3cO2<=ta&LlFA`~rA! zEAFttQ`pL0e@*=0ULC@GdrVjQ_USF1>D#BbMANrVZ;8OSZ*K{~H_7X!_i2h7!?wRJ zZuaXN0Q=SXYefsmwHx+FLxUAK#qY=go(Artz&Co}b(~|2 zWPBBU@C{C?9AwGv2Kb|Ih@GRPjg-eI+e7c;Flfq-f-6vZu#GE&VnzkZNB?PW$`WsI z(QbP$>`{4LxpPT#wC_V5Wzk}6+yj9QMScOaNq>_%fbDrxOcCiG58=5ftzQPROK*rh z?wSMbaE1Ek^ySHZQZokcGmvqAKp?eXL(u`fio+~e-B_!+u~*uBRJ5L+g)n!p^~|;q zD>i$b_VX{MpIRSbbeFaSYVN2o0 zH(#Bj+E(z-f=0I%nJ>KUx=~&c`~pv>o)y8ujqcvalQM6p!oW?M?3Mfe^OId9M8CPsT zv5g3IVO5cU3!q{_;f<)!04j(JAOc09-`BZIa+4J1?+>AaIcs4?sM zM(pqO5u?v7K{fh)2g`a>{1mcG7OC=@Z}$#%e1B{s)@@tt(q`Hnm8=K7Kt)IY937wt zok;zb9zA+j>wnmVZLwd{o(JZYimgEbzLDUY#0Nr6BQ>YJmL|rx*UAE4SAvh_@wcXg z-Fhqb3#tXxR#X?%c-3~$Yl#DO2EK!?s(K@l{f_iTqDN4A7d%r>iYpO!giPy>?XEMv zL;JzHTDQ0zOv}9KGf^rt=*`6XcPMPPXTQ1eJ*uA(AJwlXym+R#xu+PXH5JqAiBvY@ z?btrlL&H^qj1S(v?i2OIyPt!e^~LPBxACt+TmNS1+heE1u9Ml+Vzy~}>>}NazgeAk zVn31nROWO0@SZ-md$zMb--)e@@34gJ5FbD*wT#>wt|>1gl-{5I`qNJ zDuD>~HV6@m_3%Hb92H!O$KNT>b__ zm$%vatXNA5bK~D_F%FCI&ZR)7*){*qXT*0d4;72=snR~UF8b9!sDoZ+M83VJ&Ihqu zBPL=MA$Q2K;Du}g%7FX)I)X->UgFfDuZdlORuOODD;e@CBGSF5&fZv?4sHuu#zYKo zxrsvR7+oR;A8ji8YkzE_Z883*OZOXnaXv*nTM+MJD(Y(ra!cN@8s58v0M zFCqNh4~vDBntj7N;=A4*ubsSHf}d7-zVycQXI7}ro=$Qf>V*G#K;B)JB=P01SD^of zNOWf*AAL7c(U;i~AJ$x%eD~y)F-LE#>hsZ!%R0@mn8%;Hq0`13qrpy}UGIc4e7nCw zQSv~Lk~Vl&bPSMn9Bmk=V>9XK<=4^3rvs;jQq3B4WV(-H)6&+FAP!Md3ajZ8l;nht zESuz>A-TqWx%(XgYj(E-TTODaNDg1DQ}q22BzL6)J5F-rNv^(M?#CdxGaXo+k0CdJ z*^nDp5_eBRbhUB`CTxY-B{vf&C9oWl|vo(htwTPmx1acLs7J3uU1FrvavgFy5 zH?DLqy3ry+b8NuI!hi-!qOw}~%X%?L$3|JlQPR;u)^U0h>0sRt#Kzd7NC7_dSBzL0 zq#$3VphQ+s^0}zM*Gq1qq3}O3J{=2!bmXdZ#I%x)*eU9;`IKBFB@g;8xslRe zttur)p`;ky_2}k6Lr#(oyvv+2*@ShfCgV~(eV0Z$c{&wy4&G1E*&r3sL$n>u7$e5L zbJs*rdAml{9?Tba}A0 z<7Ir(5>vX2*}jTR?DV$+vGgwh?4&KS9J)}|@+*qmR82+y!EDY!e7JXBNt=ekkoS1Q(%-Ty#l z5u#KIq7um#k)DwzTSWzg8*ioUhotbTtV|ZDXndHq3X-BrGCL?`#*tifh%%i{o#_5a zX5})wOhy=C1oljd%y;ViW2q80r51_quhj|w6EFG;rUE`wak0&l>-w5}f#RVjBoB$a zi=WR?_&gOK2c9bTna31?rz8QfefKW2u%fcqgt&PM#eS|}5X(FiYp_jM(rlWF7N~Qm z2A{0RSEx6lBmbUI(-kq>9dGDRdaPwFWVTX8ah-1t+2c*J3UFM3$5f1b@0(E6igSS~A; zS|5e0T7R%w!Bc_8_f_WyJB5#9m0m}N_f+%lrV4XC8ud?0E&M0eF*IQ9hzOSlvTk2s zT>Yn{Aqc=-9qoex3v8k?h8P)K->UXjeRq9XhP;IyRc3tA-=n@#^dpFnev$9>@pkS{ z6#+yMpTHTPfcqnbBcc=!WCuQtHN+iN(hx}c4`jbl+5sgELF4iOv2wLPP|^@IiU(*r zW-;?;_{zxJN;2X^0g|U+yo=opV_x0eT#6hjdd z{HUwEtX2ScD$QRo@#j@MxK(>Ao?j>F;abG$nbBreZph!?ka+BKI7Mft(#9 zT^Zrz0h8`30sD7Wb_va>3KuKnBAfh^<9S&Jd9%EoY}3nAQovTJ08wC^o zYF%%u?MiZIs&%pJ?Syz+CsmTat)!;<^$ocbAEv4+QV0W6!ZAj&T)1Zp?BEK(G#k)UN>;F=1Z@hc= z>ymu%2gwL$Uj z*(!Z@FtJQ4mFaKAM`W3Us8BgxoQgwWuhhj875#rp`o->>^NQGgFGQrUm0!iyh)Yw1 zZX?k5WlO$6II63p{fjOq8ylyjRiXlY;Jv>CjqRj3h&&7S54ynCLw;l12Jx+1{LX7G zvqo}WDJFyax=&&&w?U<#ynbL!zu77e^aw2(JhKdy_)$r#uB|BU!!}Xc2_;R?R`l;9 zwZai4t){l31ywA<9IytswppIlWF}TDi;k6)TH$gK-*Rko#mpe-+|^xMJ2F6{L=&xQ>#-i^ybjZlc_fHR5%Qrsq` zfW}e*)Q4MQwI1{2vfQP*A_~E4#Bi)yxerqEG}l%X^p=*EC6JAIa&0cjQXZXH5u5a~ zq?eMR6}k^HkjEqeiPO)1by8&7X)7*gp_?=|OMN^o#y<_p6)Bgw-}CYAF*4IYKjqz; z731{c5N>hHKTPp}45g6{0bf6fcW0{f0x-o znQhg@`bO~2GAoyvID(DfzLrUJ|ES6@Iz`no>m*zHVapxf;8zuchmpZBaFBWwCAvTL z6~Nr5Fls-PpQ$opfyqi&NOC`}=o%^M3e}evD>7p-K&ZTt>hj{mOxNKU|TYj0gZ@FZaV6l>ybz zMN}E^Z-W_1244YFQGiM6B5F>fxx1ot8ax0Q`viG3Ux@XM<|%R|>@xRx!G;=6P--Z{ ztvbQiXGY2FpvEFKcw>9P#fFtC~GxqncMm?!C{W)i*Lo{jXi(}jqdKDYm>WOxcO2ns2~Dr%>i)+`zTLfRTRJv*mJNz=`F?}9C}}HYgK@g4Kc*(SkE!(8!KALB4`>CC zEJGC%%S^5(zphPo=PLTwNcw$FeNuEP+xoxQ+Vz(xLeC-aX3F!O==o*roB!cMH=mXb z&;kK+*;4#0vNB?*Kh02-Fa%=A*w@IepQ87!t850qEO5~%>_e+&A1hK@DyHbv>%=r|Cvzb*$G zT@9aWyD1)$x!<*TRi@NXW?R#0D6Y+DEi-&!T+}Oi)(o!ltgW$1L2$4B4*O@Z#yi8; z;G!b)zFdKwfxTQ%>9>Q4MmWewG1ky3FVU@&h42q|LG4t}{k~Gb9;pCoCeiIj{mrC~ zHJ>Q*A0pO3AIZl=qnQHal~_|N!C$~9D4>TFY}|^H!{}5!;J!U_k3ZyZmJ_eY!A9o( zX2IB&nO$awFZi3~u*`~NCVE60r*4*3?)@qS!Ob#DG42b$!Hbl%FJ*(j2yBKeDt&e^ zsV|^VRmguymdSx(!NF#rqW>F7zt5{N%W1H%-ajJP(CZwrzkG{e(_Q8I0nf81enhbG zY55}IFiwfN_1!wfxbsp4)WN2=oUaJF#eAyu?@eq_FR!Fva}h%c0*e1) z9(g`wu+b<5{fb~C%eRcdjH!}W2OFsX=)Vg6-9iVOt2WUJ2>peQ10nlGWuH>h=h`}o zhh*+|ZM<7hYACaFFX{JrwaEs5u%VYmVz8;JtGL`na{VfCgxIBE9-rZ8A0B$HWs)Ef~ zY^cQ=HkK-&4mS1Wd_~YL=JR#p6!%wRJ__Z!bylz%FyYYw^u_nH9-w z>y+BQUj3uY4$6!?8}9)3^=kZx+_x$PqKob*JK?(SWr}f~!`EPgBGX;2KxcI?k9U8l z(r*V7jqs3>zF-sYeoq#n8V0sgJ@-_lfL>Ao)J&q=@B5oc9c-RZnJNXr%~D@6ZkXTTbR})1Z1AwaX0WLA*}wro&&|g%0m|4;mMt~OTwROWN-boTf5GQ^TSlzn1{sQO(BfBG{l0f= zRSM|9PSF)|zdlA;tIY z`io8RKiX@PoLR$@#9v4;_Oe@!LcdA=PJ1x-rlw|iINWTqTlR6d2mD=n_Y|%Gv)OJb z;VA%jakx3lZh48rJ>bsQY~gEY?rpcM;wb=kaJadT-LjCwJ>YX~907A*yJZH4d%&$6 zZqBw_9^!BhxNQVSz}(Mn8NlIQa5INn``ayDIo#VHr)xjJ5wH%x55sY|7u?9<)`50Q zJr4H{wAn4SIRe%}c1sM0d%?9FZXIm5&b_4=JcmbyayoAGz7Q_J#cY(hYmfLzb zjUy2V!V2_oy1?meShyM*MAr5f31Ki5t z#%YKHLENTZ^SK}}B1k~ZjnfeaINSwp=5XT-#DPF=3s`izAn-t-Kma$+L>%C77r2qb zjk6F3z#HK^)M@y;*wltICR8qVL7;YkKp;0hjyS;KE^sY}8)qX9;5C5H09(_*0$dQd zt`-R5#yN-s9PR@5a=7^k!~qqzVO<~K0S^RDs04z!`ANh94)=h2INUrJalp@QXoDaF zAn>kVpb9tVA`Wo42i(Qs=6Q$%K5nB<5M%%ZoIZi7+?l9h_kdeD-1-#afXr>uFbMR37Xl-A3Z6zB;BYUvnZvCM5eFo0lgDA8 z0op}~0~`eo@Rl5|U5q%u;STV6B1ij&@__Lf!~u>17kCVZ8=plS;BXgs1$N?%sQp74 zumo{{1j29^_!SN}Vq@dwa2NRZ;I?oDnC*xI90eZmqa1E_AP#W22Yla4mA0@oG%rOQ z;3)tv;c#<4;sA$xz+ZX^`~Pqrur5O!;3)8dui|j)a>M}+_ku69aRjU@5C=G1yApAL z!yVvO4%Zf7|Njt2zyW~~9By2NIKbg9a5IM+S7ZO*l_TIO>sia4)zgJhwTm&m$0o7jSyP-{o+}2E+jl*KR}{2+OhmcR=8!umU}t+7}Q9 zINSxkio=bY5C_6>+W)&CurQneZO<9v0EfH4XK=XrMZ|$HT-^VAAn;Ha0ownYUqT$< za1ZzZ4mZDyI1rjk`+pAvx`q}I_y6Ws5C=Hi1KyIut*;^ugyi!6-wT0yAqAxUzx6f5 z0S@@`(zsupqHxLIn+ym~a!d3f!^P7kRRRsL|e-F5m z!_C_e2RPgV?g-}U{lEDw#DQP|)#lU#K9|GI#fSqO?gh67@qqomwFGe>NI<U?Ix%oZB0S@Kto`TO12RPgTUc%wV&k+Y+koNx}4RAr=C7yyW z5C=Hi1-^>I%|{RiY#ad(1Qv3*`6%K5hkL+haJcyx_WxFnfCmB(ak%+Q!~qWXfDhns z>sQ$Sn>hmBuMh_~-0?Ny0EcUjBMxx5B&90Eauk2ZZLc#QnYYCoBj;3y9nS-j&0R z=MV=t+y&lpBbzf%7+S5~b2$0d%614sr)sgdFUn!}=Ls3r{#%bP%uQyU@^Jqr?i)>J zbMhc_9`~k6%$+BsSNj(C2Pd+#c|zN2pOef)7B?UF`*3f6n6<3|c{lEhCa@)x{u=Hz z6WHb&Lffc9+~+X!d?A5V%oiG0b5Nd#SX>`)Rm0jbp3nemw4r#qA6Vfat4s7CS!mM@jF8mj+dEXv5*$m65QTj)6ucXT(LZh4P7i4 z;ya-OHA0%t(#?`Gp*9Kk69GHFSZEm^iG=cO$q=#F-LmPo*TQr)_*@3R0TlJsbSzd3 zJuZPdKLKa}d^I@7G82WyaY)YT1N+XxzT70%D?w;j=O^j~Nc0(afo-lWG_FIky;aFK zCyPB%M@S>xc-1Rj$>f&rirfMW_wtJBbV3BP^F%IgTp)mp*6gWcI?n~+3no-i|Jbo3ExQ!?9J0@`s_xyoLoWs3; zViM=^n)Nblt2hGM>zKrO{01g*4mbXdNu0-TVy!%bC-4s@aSk`%!X(b&*4voGIoxpv zYvlnP0apbkaSr#~#U#$*-hVNPbGX)a53@K&z<3{vc@8&MVlmI*R*l0_o5O7mtpf*H zgdfK)ox`H#a8HE8Qb99Dm^k5$bXcy3=lHH{HHYO&cmb!ey2Ik-aBH-~@;!%ZV;q(f zVL8^y+E|C>XjlP!R3$hp9u7C_9hQ9@Zmr?4yc>?wTG-#uH~@2 z#N)Lc7H1ePu9dBI9F|pK1jMy+yu;$)a94uEvXH|)i4M!$&|Lbg%$ww}%m^(Yt(EIK zELI**c32+ba92HtWkg7BlV&?lio-G>q=3Y|^&J*7hie-;EL}O=XmD5_2*qp2)2#;r zEuWKq17V3lXeQX!RI)DkKNTD{&UPAvj@7&3q3fP{d#)OUHzREavGlskaBlKQoaTnZ zXpQtgdwX&0@kly@CeckxRgsTXaXL0x<}WIIf{N3z$ucig_+*J+9A>Hz&oC-oX1O#{ z$7(haqI9pXV@XYfblt{vEUSsoR#&i&6WZxFEZVijVX2YU@}^Gt@nP9m}R` zH0s_Ab-%xsy-e4eYuTY@@WIu!?3ZTnL3{zL)*R2V1uVTeo^=ImU~?hG@b5~=Cyj8v zX!&CGv2{uAn=9E;`I=ZzSEa{^9tlcE{k7|y8)D!(c2fo1% z>(;XS&0*^+Ygw}vu<7thmfb=~o3vlfqk&FQ{zZSiXJJ)I9m|A{7p?HUem+&<=y*PU z#?L3LWuLczzoxHcH|RQXEi<%)4I|gG?3Q@$zn10Fb0+-Q5;i@ylI?E^zfD}p&e8Me zmF#{?^n;-*SxP#t{Z_J0>EM|w*?4;HypkrjL<6@%+gj*4Ifw4p==Gikq%pbTEh&ja6P$(4QvIQkE~(2^!)J}wwa#aU&B6c1)G0Z!G384 z8&9rav90lZYz0eijkZ6$LT-DUC};{eSvAT1(F!)DHQN4twG8@)y6v~i%tZOYk{YYe z2u*Uoq2f~i$A6xR{lC6@^cr@qHEf)^hE;1L7z}IF#QY$;@P-Pf>f(5IWaf_;wXN#o@_8rUe>&_%H!(Jd%`rejJKKF-f06i&yKD*S0b z|93UZZVP`$!|!yxx0-Ek3ma~(W{2o{bv65it`}Cb*mkff7JhGsXYC3$l%6Y=vpMb1 zXKpNKtLb`mIon43!g6+uo_|=*eu3PiZ-Z^`nakNd8^r!_ORWtnyshng4Jw)d)P30H9JSwM^-c41Gr9D&6+&`oAZ~mY0i-DO>SCA&XZ#il$6 ze|uK3^>p36itR@p-8(4bLHPC5GIpP?UoT^Z4(JP?FJs+0K&YtQxM*A{m=_sT% zdrBn}?C%yz{o~nLvaRzfwwv@$R^>6p2cC&GZW+4)y@p{bneqn%{i|8UGCINDnyc8D zPO!K0GPVHEhPHAZJM5(ck41aVNPawDz;<`S+<&!z{X$nfCv}F7(*>*>UGL?yNu6Qi zt$enKu7BmTO-OI{OTOesJB~{$Zzb!zBk5$Ax5fDUATv;&Z3XOZXTi|yxGIn7K^&`r z^+SBn>3^T)v&=5={ptcXvkUCOdf{cd<`%GHU0~0Q0`@1alX8?Y2H}_woN86xT(+T4 ziWnnJ3Lhr%e^A!eL;iCV?XoQgk=HZ~ZFs?d3gNq>Tuu5tM+r8@#dbwvk`j53Xc!H4|k;c4=jr8^qs z_EM=)=$tCC9JxWt@oRO(vazPA>})qwX3t8tyE`g*eknVRyoS?qUb~W4?jYs(N!67r zSyB(!wgC$ay5f0357@S3C3~5!Z!TpAdO+vqrR*$S*-~~3>CM(FI&pqdusyvLdls`L zlm`of@jYSBf~9OxPuMeC&YPp;O~&y#;^dd?HegZF6LzGpWWUiB&ncO(BXK3m#MRJ4 z&TGO6L?#@GrVdmcm$D_9D6j2O_A<#fRmy>EInD%won_*gU?}VK3U(Hw6a2Tw!4{ZMuN`uJJIV;Oxt@FS z3bxw>n`dERLsvW}nPK0U6|5UwpLMWFX834CGNfbmEAbV4LbHHhsbj zl&9GWcGnDhhB{bE7VPOO=gm>_s@n6`ayC8-cIZ~H)pW)4e&o^pv7DWwya{q%6ApPX z;nXR0d)9C;LvNH<&B40$hU`7N9N-}<+Bi<>Hx1l7ma|2WHT)&Z6e%*Q_AFY?-s=q; zwl8NFaE&X%BqX*cow(FRYEQPDb?O8A4%pfFKG3&E(T77%Oh2GKb^Zg5O6}}<$fm!g zk_qoh9`}y;jKi?I=PXUo_UTn)eDy{)*D#6cP+ob01+ z(4TGWKtC9H&c@D?>?v864&4ZD&=t#AN`ExK7qU!|BBN^1r!gb@n17TmaWo!{$+t}FVf$&i? z8{1FUR2w^u^kzwl&JI-@^b1TNVuSW$lPJ&WeAaCc?76>$jUNPi{#haq93`*Mhso}3 z`RwIEu;aaac8sogzKcA%*YcTRF!FvX=QTYDf8p>He|zFk_9bi*PW903UcwfU>^n+1 zkfqZ@)NMK`pY4Zi%ImUB5y=QxX=3));eGudOW2=-g~s#^B}}ws_|T(J6Pe=7`apWk z;~HeQ%ttjfVYqp)-7=fQJ>ZXWxOs@(G7;Pst^f}NM)MR5wOfX8xCgv1hnt7lEj{z` zsY_S`AkdMgV7T4VhQmGJO*z~=!ft7pk6s1?O3?(RTj_HrRTFq1kSHk#$;}qKr3Qz4 zz@s?aJkoBtXTy9P)&L0n!{OFZ=tdmw1^=1Dt)uY`rJpzgUI?7xaO)VmEm+%Q@U? zn_#y*%MtK`&*yN*!-xYMuAPWDz~MFr1SWC>w384AINSw3gu{)K5eLF^o6`k>p5Xr7@lzKU1bzx5K%cr8A444Aa1Z#`9B!V5I1rl4|Dgndk3$QH zpSqZ*BMxx52mBolH_t#E2+5UCT_EsUNC9a&HqS&H;BXK4Iu19_LL3OiZSs8Yfxxq& z1Y~Z09C3idJ>auB+&mj`AOyE53l0wiCWa7DxOooZ0Ec_Qhj6&{3B-Y_9RHyt*U$@r zo>c{W-1;Qq0Ec_Q+iw7G}_RRsLp0iMX=+Iffr9PR>-3g$M|g2R}H zIDoB4xH#Yf|A)hk^AQI)+y(w~5VxsUJjMlx13?06?gBr>;l`&B2RPgX{#hWm1uVIY zPa_Tl3IuQ$_%04NE<_yQa2NQS0URe3sB36kgg6i&5XfENFL1bVG2#G+d%%~gIsQW_ zzyR|zhy!YYAnpO5&*A205eGQj1OBLr+k#iU<|T*&DuH0`0UyobW~``&aJaW|YDQl_ zw^dno)6ob${Q^}u9gWbD!|7;*HXKezBQ*7K{D)d_4e4lvhCYF++ykD-;dC@Y4G#B$ zM=2cpzbXdM(FpfA8xuMj;U5mCqY?h#a5@^{XPMhV?R*?75C=F4=x79bmk};d(a{KB zb2uH1@R`JIA-7g82z<;@Ku06&;&3_|;T;ag(Fm3|MUM6l6|xN$Aw0C8&nPzHD)@GM6G9gQ%b!|7;**&J?Ok2nBM`~T1eKwu(I!E=ZM9PR-h z!r|sZtOsn;{y(GvbTmRwjsiLwp(BUW(FkogoK8k)N^icxd4P^aXejYQG*KbqM45W7 zpra8IIh>A0sKMcMGD4JWK*$2A0n9t$X&4>dWZu3ImQI3H1b;JP<_kxe+aBC6b zKzMF*dLhs^ynxf{LLA_5IvSxPhg-qhgyppVhd|S?0{91^t%w60?gdZeaO)e01L3&% zA4(923MYW=xAjfLfoH?_VlVhV9B$o)I1q-5`+qM4ehwobe(Ulr!~qW179$RDxC8v_ z&|KR8YfG>o2rVG)|6Sl8bGXrsIKbg9@OMITdH-*G8*w0{fc!ch{51|YZbuy8a2NQx zP+Zyn8{a`32qmDr9{_)r!_7Mo2RPgVK05^W?f=a?5eGsD__pWZ6FJ;kia5aGUhpAR zxqts}eHU?{s(^3*?*;G4;nw#M2RPgd-lhsy?fxYN~0URe3s15K!;LQMmKyLjAae%|U z;4g5v^<%^VHOKxx&;ST5R|^Dj>jA_84)=o3=Wxd-hyyB4`~N@#s@KhUR3#A19S0Ey zI9%&N9N=&l_z*w0RasUW42RPgXKA*#lWrzddwEqun00bW8C@`Nu9N=&d z_-GC{pF|v3TxkoxH-kW5jsokqhyxt%1@Fk=*6$Dp7IXIJUI;YhDL92V0A7w)v={J) zNLd;%mw+d7xb-x>AK(ahArQskj{hMJEDCRc_6*_xhr7USe{ckh-y;rixC{Iz4mX}f z9N=)*S?vG6<_H*nKpfz37x>21(Iow)~IKbgHF9c?D1gu`f0S@vOYkTT zH(o{@SQtJIxWNAj!_#ShZ@z*BK^Otz9`K(RiU)k?PUW!!^Mr1?&-2*bc|s@M-aM9p zgFJNZJT@~A>96FmZ8*R~_go%3jl({4OY>Old|c<}vCR44kL9sN^!!jB+d#upp2l_0Jl2V>?s;q`U0<8WHq*6m9y>|b{CTX}LR=TjW8LUFV;-AB*N5k^Ep#0= zkDXp9qzlROaSnrYCDcv)ALH=$l-28bEg_m&HDV>#kguN!Q|BmP^-Ha@n?LU_o&n)(O&S z66~7(t}}Ak9J)T7%eK&U7!=br3yPP(f?;{A(-J(V=dzh}ZJ5h8 z<0{mGMH=xShkEQAoB^SWfMOd2Zp~%g=z3)?n`485Tl3h(Tb6OS=O4S}86Ll7x8yCrS|ywTp4)cI;~WLv zJ9f(>9Im}-?@#((XWQ8u2ye|F1Y9=~U|^x<&xeY>Rxk5^)?(t#&{;{{rCxD}@h zG~sXuP8Vpv;jRdW&62J%@Xv9F|B9*Wz@6{}61#HL)?;=CIu42$*ra!0#Mx z#pwcmAF7R+TE`C z9@d=rThLVejepB4k6_JK3URt_8(F87LR!)}$Xu>z+D9x}r|DRfKlu(8RdZGfb$iOw z)J0r12b(&xE;V&d9o5WfjIvwKAX`9)Q8;|(0x!#BhgJ$1wupI>oF=cC)7x9)oG=&9 z5ee=A8qG%fFG13w*$##y9!7~Q(VY(6TC~rFh=h!b$V2j%@H4O1u+R|Y_02_H{UL9S zTB?$Z7v**+a{Zf+6$LXP=nWzGh9da1q_6|Yp-}qQ+l!5+ z%Z?QYscq;>RrW+@j7F0Hg!=?%HRWED=!{VA%MzUz=dq+!LRK9&RGHxBf2x}*=va#_ zbJ@&Q_@9%_xoq_+q5ee4<@6GuP;`0!I%03|3Jo)c`(1u505AT4eYlyLbLIo!u7?6C+?+Er$=ZymZJ$; z!EXB3oGnu|C#ba*Kl}_|yfFtynH_Gp*QC{SP-^A#YdOrLFp*%lY{LqEt&pnJAXvl< z5r$nsMNBIDY^~5PdkyR^%CEoIUI(Ks;-Nc2WhJYCP4nT)o4Arcb8&x1yiamJf%^ho z@|tL^W=%>BYLgWAjwe~SbvRU|4D}=*Wc{AbW~~z%#x9|X;~!MZa@q6iu=YNj%RXO+ zeH6AEw~#^CW)3r~M|ycKv#b}=>zsm9as)U7jowJF`QV`^+4}WDn(YYE59&1?ZzCO* zFD1tdlEX_c!Z6X{=s=3YTcBJo|cg`wQ2|7FrCdTF(m&BKy-_ zd)#TKvmwt5sgakf8#36Flu*ppJufuU38`%7^T>k(9iatxx`+nsFG^{lBP|<93*EKH z9ckHsS{1O_bb$)G9AWR!!9?SQ#_8V?TK8BvFoM6oXdXVL#W+PbH8w~< zdLqVZ0>)~*``+U;Mibp*VM%2~E&L*RR>{p_=92%$9xkS(g)&57U0EHmkKc?(yiayo zjdn}7x$Nu<2sU|zEN+uvhW!}8)Zf}($-EjYUfVZ zYDQgwOv?w1&K3)c_folyR(u(tc~QzJD(RxSzoZp~#Po+%_ct~E^ku611mAtB=F?t^OsQs+>RzL|eEcg+Ms=U8x-aYOmszH|Z;gAK+=nzpo%}-mRrhx~`qMY6?whFY&vfw16sqn` zs{2b1`elmz_cl!f|AVG9!!I;kb${&vfBG`jeOY^d`f$~Kg6jU&c7B;Is{6}rDcvTH zAkB2~LAtM{x&ii_O!JYdHf3?_ua|{is=>IH+9dYFE0{FW=CHf3 z2xD~mIn44Z-c;Y8%~roE7^)W|E=SjkVmn_I8dfjB*Px@9_oRn6|#rXfn!hW&gQ^WZeU^*q>YAs`E2N z<$XEI{|Ebc%6H1jU60dggek0etB|8RFoVUuAvCW8z5n8`qI!dj@!zy_E{;#$)B6qK zGp#NY0^5Xsf%6kQ{ApX~)SGRc+BNtz=Km=8k6BVnou{i@0cj;B>%lB;e%@}02-%YD zoKv4^=ZvAH+P|p5zie(rOkH+uo6zDxbgI&5Pd#VM!jio$w9(=O=)jK9xU8pBTxS)T zx~{^a`8UY5tQX}Rhz>aDEn!j`o{byZVuHsZ1W}reU7BkOE0D&jX=*3uCpf!qZOguV zOK|E+rn5=KLaTI=-z&*4hx{FM=B~(dSIJYUb9P0(@yPdnu~4F$fqW%G?|8~r&{o_4 zi<^S&ZJo^ime7Eel?YLff(CTjE^sLVo%LC}r31B<%zdsR4p-6gr8PLOts`ZZ-jS>IeG}djqkfn1?V@tLR zOLUHD?EZFPif;NeHsu{~%QUwC9iiJ}Jj3)erM_@~hQET+ng@MhV;j){^nJ>tR)#+1n+q)-zSLY^ff z5JH}q!N!y#{zS}R3vivn%kzkwXAG_sHk6P-JJ$KrDw!ryW4n$GScKiB3+IsdKc?7(|MDtqWXp?M~{aUr^SAzHamb1*PA z$53ww#pT$nok@zatLhkKl;V4T9E(qd2J0YBI>5_ku&nomPKINTNsXgN~ybc&?L zNkZc!x<8!GHbI6K!GX3GlOChfJOCTjP~{NMNpo7kcYyO6XT@~MxliMIYwX9^J>ccf zVqFP!oPsoZ@u*`H-WM7g*2{*L;TmkHZ8}@=K`2A_rb&hlv|AR1GL$$O3ZDCa7&=fk zvR@byXzUAdCf0qI(55=IYF2b(_QWosW19HzWK-u{O!o8QG#`l1 zd5saRlJU|b-aYwI_W3R$Tgqf_!s2%eFWE$)$6GqvA=87^G7cDBOv0t}uFQF7Xy zCeCI^qt4j^*Kg5wV&2Fm&PH;28m{q5y1tn+1u5A15;o{$ zf&R^%aU`HTpK0!l#WNMC$8{u(5evlozDPWOiwGk=|A#kvat&`hf=SynRG-W??h*Ry z{&|$0+khZS zPasP^qib*%9o`y4p|#V6edZN(?J8Wg{P0d=nI8(Lb$cG!lk}1Bo=$gbDm!*S$kg4R z!eT$csXarcu(r4kg)yZRG!N1nr=Xy@>ru&=w{We@*Pie|=H{?Sas6a$M3bZjyW=Rl z*wo?`rN%k?F}C>=;lpZldfKv{Z1O>&Z`yP#){5qy&KRw!Vg}xJMMs$`rdPw6tZ?&D zIHKh`cJ7eSmR<7*(Y7dj%BOx?DrN5FjJ|h1xa zHXeksL#T`Ks*!TX8IBawl+ z@yk}p7=lXZ{~j+c|G(5o_xXHw*CPzn&9buWL&CtutSlJf3>a6THx?ann^fWf=Q=y6OTn=0GDH6Yu6E9KX{+vCrp9$5p zHpOU-hnh^9FKONo=ZpLPN@=`R`8#TE)&}Gk^}3`MB3;uX6Y%UbIt% zcm^Gk4SG^lp_o8>gkXcZg)?Y@%AnUn7-Y#~$G#BSW~&W4qV!=@VlDE|gCpim>E&z` zsp-%q$fy}~=N4{PVhAUiAZMoZ~U^ zRQi{~%&B6;?h)lI!smcqydJ$25t07OT+)}_{!-{$jS@DlXUCiBm$A>k66z=e_x@dT zYLpb;=4>#v)8DQfMf%foD%pPaZb^@X7&#>kH`7v_y>g;1tZ+ zwVvH?qhFx2;FqJ03;o(+dt)5e)mgq(;`CcXU(o%%-Mc)X6#8(Kl+p{mf5yryC_ROIl$B7GIs{8>pArc&JJ$EUEu6T&Fn`5gAk387sgwHCEDCMl)0 zvnR3ilR~EyF^|e|Z-vwc$TK}!`?4)YwxI#p z%*a-~B-)?t7i7cc@>&*kXSwoUPNeRvbGq<+0c|-IYS5j_vdZCfq+i5Gz0{qLK3vJr zB}%C~?^@Eg;_@I(#qKE@T0K=@rY|!_qUODI&MbV~P$!4Y{7x7~&524L_)bX84l4Bp zDz!HTkz8sUrPNouLyLb9Z3rxtH9jR|%4#1wCD4#5O@40A>Qh3Jw)y|?a2uBWi0iA* znJUJh<9!dyc46~=I;*Gi4y^4us2ls@v~X?&>`^>GU4aJt1(Zbto(8jz!BamXy(mI= zf^6N=TX!N4V~w6KqV32t7w~D~4-?q2a>1}C;f!!XJ6f$kR&EKSd~lHROBj*lesuv^ zA9ZsMoWQ!B71rxMf0!LRD~yRMMLsh=U&=~IxQti<(~6POv$C>ov{7^7Rp!WziDx-K z2px1A9%h?<5E_T-xj#){$A1vE>0W=BE%;GrERMC`{T(<9wy1~qQ+UIn8s5IKR{p$i zjKp0XpOQUPt4R>MM0>xk^dMc6!|8g?r)y69;1o9MC!viV4Z3kX7J_LS=SJq4I5L^N z`4fI|O_kh%)&AX#mp?xVEvZjzT))R~4htC?&V`6XK2s0cMD>N}mYL^;?5g}3AKx63 zFZA*I=Y_257~5qCZmeIqFpxfeSC6dX@qzuugb4vnTblJ?CCXQ1uEOOJ->7Kx>6ef;na%w@Ga=@xRJe0I+k8>z7PS;4j(KbJPl)+TB8$eeyBCF_ zbsqzv`HU9g#S!D~$X$RvL5Y9<_lgBXz;;SB1xQx#L*M?}9}) zaU7fTyKpk81-LgAUphezzS|_#;H@!i%pXE$^4;zA>{zOP6KnCOpih2c4Dkf_J7Xoe zS$M8Qm)mqKKAAo8r_jIMUVMUk{;i&Gpv25F4LPpX8^xWxFOkE2!nvOZK_)=7Fjq}QA_UB*1>ZG9|m}fLw ze@&Q~)HVcjjb?Gzh0LUSA=ui{YzkQ1#?h5*1OA@JpK~{xAm zGgf>rTbsB-Y zFzW;CBJeB+W%suuSxN=o@}3#VGVTaz)#RE?8r#Lto!&dm7n-5lQGvj@!bBYJFi~Xlk9Bn6&cW1-l^ifhi*1*Ph(V=1gZ%NRu`GN4Uj(RGNc#bmqH#(>kf4Yo@HDOgaRW-Dpi^XFx%Y&j z-LX(AG+vWdy%%8N9rWkmF*VB~b=m3YvMLMNzxRX(6#Ywv#~+7Zh8NE8vEa|mH2=+Vk}!xi7&k9MzQ^sc)xgd z1iM=)ETBq|HFAfdTe(Bgt=yr++X`%s??@dg16F^^MsyyWproWDof--X+X^%>e|9onKm4%BuE)JWH$Eh!Eb zpi_Cpcd!Z03sa@<^g0k+BlKC#-B3C(u}=kNgu+{p*$;<3tTlD5tFb@7>lppo1wPws zoWbfw>dm_2quKaKy&-Aa!l1&S)H9r|kJKmWdXHw?BK1RcvqrI7k@`uxk)zm{D7`_~ zZX{a}rBBl}8_8a#Yr~Q30IsnK@OnAkC`3oHB~khmoq(Tzt_H3f$L0>^1TR z$wjlcYLNTY!Zr~`hhz4NOrfnevWSaNH#NC-%V#5$+pq;$&u^=U9BUTAx1C8 z3u@)K{=+Fk((Qq|L)z*8Mh}H&qRqNO%(GMD9M#09Mf_$4{_|h0= zo{m#7e(|06L}>$GXnYcKy*1(n{%N?0WN4-$9?*BDYEqpoprlIY*(!COl94P<&}S%P zdh_@$hVj82@;Mk6pcHv^p>)DX>gD+~`p~}8XsCBJ=U^qpd(oMKzU?HjqSzm)9dZdy z`35?xBi@H{*by+Qu(*k7ta0Wj4vUti&BoHc$o=_HHc+omGaMZnzRm+jvel4L>O5($ z$)Mb;+C8pgRy+MJG$m@=8qM_kodmT6Ph69m3zK+-`px&=`Wd4z1rzZrF^lF zaxllk*$MjJq!b-eMu@Kh66KV;sM!!{nkEm?)X;*u8;ZRG#DIdsTX!g-(AAthP*Y!* zY%fJlF{*uqEWW6Q$fUGEd7?NklH4R=fPr0$(>G8uW;xG z>Kwz^xtdaZB<=TW>O1LX4P%{Z>6>E&QPSqOvklB%OW#m_##Yn74%X5emeLe>xQ@PO{mUGI z`tkaX^}pi?%!=1{)qOIYZHq?$+CH4!pzBM+S!RMh!zQ{A(YhrfbgCnDZ=%C+CuT-R z(QdEQ9ZFlOc!J0~bonC$Q|JBU|KM+cV^_icO3)9{Jp^MC^-0xbN3jWs`g*+-%Ra;_ zlKJ?4%tx3<$jZIA?!n(a{M|)tTAbg>xoc^J^VOYE&SVzlyuCUK-?@om?e!EhvFb@e@U?+*)Xp1l=p$Kivi|Yt+k-3XmSc;-iY7EnVD0PaKgz=HqmVwQG+yfF zgqy``ZimZXIBP2TM3;265eEDRFpH*;jd9hS#Trd##Y^;^7}rqNHbvjIj+wr*)h9~S zaSLClb`E88QuL{@*yrX!RrK5}wzHK!iR_|%Z!7&4?KC#KwZ5*-I+)F=ub&c^0Edw! zQ4 z%`qggMV4PsY)Ll`LRU@^w_5?PXsvOYQF(A#9=@`H9V@-p!mF#Lae1g&aN4|Triyux z!~VTc>X_@D$IPguUo@Zt~13+Pq#jvv1P$ z+2};Fj<@Jm`RMD9{w%YJzOC@?fJ!E6b(+}Dw)&=NKf!+LRq@bg0HhY^KUhjT-oKJ1 zPQ*_k>$BVRM<2#FUeUq^i~}vYNwoVHw7@?DFbmVS32@b*m9OJ^jdks+?_4(*>J$@K z!^9Gusq4V&S9K!L2tPRW?W79D@P<}g?ofX ztmvi?$r`lK57)gkh|OuCAFo?Fh#hO8Z-r0&O0(K`VgI(!KboBfGmc1es~9z~1+Abt zc2yls#XzgZiI<@j=YOtbEu@$2;wOnT5La!{iJ!mAjg2pcq_eV?dc97MU!QJ?6?of0 z_{Cs-hVI>gY-l=m8AU7EoOFGPdCLU+@73gwN`k+@Q~+OZkm5?ky~7%(4c(RoQ31M& zzx$dh=CiL;^()!%R{9o^|Btlyj*Iem{=o0yOu?1~zr#@N!7MDh2YeV#iGFyGJb_xk<8i`m(k z+1c6I+1Y*eo@Zd2S6*!VyWaI!exzuN$n>N}Wa18w$fOBw!^XZLdM5gU!)og0{a;h} z--Xquu1KxL#E5Tr>9UU;QgDeVFT$BzIYKpyi545O@My6|TWko`4jC`$mo%E<%z(t8tbn0dlRMzg z8EYBV-lF88$j1dbAnAejV`_g1fT~}~J zQQmQf;NgZj%)^W? zzD6tR;#Mh+H3DHd9BR={AslMaO)gH2NzHE~Aj9Eh<;lqsR^TG~H49N0pF%F#_cQ!I zl3M*V>ThHtG*^B`D?~F2^?TlAotldg8qYRtMsu;1#;y%J)Lcw%4C$p>8(9m|fR;_O z2IdnLq-;INp=3>1ltD}${1MuvrSes-%J?g_r!2A5F3B|ajF#8`>fJHOCH*=ovdmX! zly+!ql7)l1o9ONokUaSR*-ZFQAS_xl})1E@g>NmX!BCfs;Mg)I=ZCs}Ut3UH*t zHXJwBP@zHR5Hg{5ikA^C|50BZttXFGM*B}xS=*NeYUSg}VdNd@HtFGaA zx9z?t4~BF$e$FsYwz0L?s_qX!X`MZnVb8s7gd;*o{lsm7YKI5KNXe0Fl(t*JG>PI{ zc85TBGl`8&6jQLM65OKk8~9kx6j zIm`CB_*SZztodLryPhr%tlvx_rR@-X2WGM&VuOMYMfvR>lwx8pmLb|C_fD!lvCVqX z%xlelZHq<2FNF^dMha!q90J0Os6Xw7tu9P5}Kbr9cG>qf$9_)9QggtwB}(oSN1jW(I>?Idp3TuWjD zJL6#JJpW&p9q24x6cSsB?EG*soPF6vbQT6vsf*amc71bkbtWsz#=7p;RTPDy<|2#i zDkj)2;1v^Qp(3ZNSjXnK7UF7_c|%Nfn}?d4Lh??^T5bxeokPI#I9K!*rUKA+6MMR4 z)u2d5#mf0&sIa4j$ToBn8wo`TiZ)%IL7VST(sze8I=RtlXtd}Vv}G1CbApd#fCy>h|>1}kOH7}4>8T{QnTuM9RexW>l^_43Nc(LA?6-XaAytDcTvF= zd=@9NaXq2wLjVsd#9&r54jaHPdqSDt<3$#I7HQsdD!D`FqYp8l&3lQiLPrQ_-%AYE z4}#=;;cC1V6IqMj|IO?rCJ8RE_R(I@UJc+?FL8iyAKZg_19J($1_HhXaHBW6`gc>2 zxxESCK7b4Yt^$}zz-xQ|{YXC&{LFZq@imV?2Tfn}IfOP=A=p(ij76GvD3(QOa z1_H(b7*4=Wa4`Z30GuFT4S;6^ECCSK4^6nDiB0{)KEl6EpmRSlP3YbdzzngWeiQC- z(k~lmBQP0An8AmA++PgS?`k5h&ao>_F!w%t1hmeE-RuXTi{k)f5HJY9A_6)CI6**b zq8SJvnrH|JBpL$rL_@$UG-W>sz+(Uz1l$0yXb=p14!~)`90A~z3CvCaoiow;<;Eh* z%|ulmFeRB{mM|4SSQcpB0x&uYRlNZ0AWRy7$64YqAre6E!LXtM?69;yD;^9-?Ey5* z9pH*xc%k6+JagW$_i0l{Q%dxgm-(MsVh#%7v77H2foP=m^B8#5CZA}SVce` z03`&70RA9A1t4T7fIs2U-3hn{AeVrv06rT^9suAjVM+ja4Fl$L0PTkn7hG^A0GstR zQ-f}a9_-jKv5Bw@1kZ?a4uHtFKsgaWzqf!H24Lk|Vn?AXfE#b2yD^PGGaRGt4Peo5 zjQRvP1mZ@VunNGdabkk~=bJQTXJTO95n_ZL_E+TQe4tlj&U`ik_M9Iln*JCePEZSB zKn))yjuaxn@c3&nj>UA7oP{Ky14l!ZW}xgmS`1eUze4=Xw=p~=(a_~>sPHL(mSdoT zjlnu})u$4LuEEjOL)SZ?=b@`Duc!)LMes^Fbfu%lI&_7Bg@=fi0C?yMtwCXj3LY88 zVH&I)2cx}%P=qiL#SWH;PQqH0V3j1{d=%7LBL=Xn@uHtL8utm*o<>hLcLZYD`{Us| zYoYg!@vzQ901pV50w8h%I+#nmc~V1`KS6v$SOYXS&JqBxCcsLw0Ypy(;Q$a$oe0~c z0~qckHDfWGMOz)-kzt;X>){3C-WQ{+amB#FV!o_Xd&!P{IZAXFUNl5+CW$v$ox7s5 zeZKHvd??yj^p4nXuo`dGK$X z>64RC?km$|dV(IazuaEtD;IJSb`g)hI3cqx=$!CBASZzpe~oVDLWS0o#Xamf6mpYi z%t!H=jx=*Vj4y`&c})>pGtWz+mzxiSLYYiY{D&f28eu@YOcDKE>&mTV2H-zhTL&&O zlt&DjEy$g-6YCRHrJob3c1kR1iI^dHqg^K_DU4m8Av&|ZQ$?LH0kIB|Et0LJ(khh3 z6^qS;^KZZtr;2-o!vI!I!`K%AI57?Jdo}$$rCHuEeNshaS&n!cPu@ zM1Kc!XZ$SK?Ih3}W?{W6jI8d=OF;H)7P5Rri2gj5ybjcv*;w+%*P!kS>gZn})On6r zPZ$g`cy|cvI|mlngPQTGn&uyBO2^%KR$!T^+(jfUBEXT<>I5^m!b0UMTPi$Ovt z37-e6{Sl5JlM74qg~;q&ae&*e;nll*8Weo~-T-i8BSK!#e6hdVS2f5sp_Wf#5rRzf z5$BxH?4UQLXm&Y3augaWN(duK-U>0?l)pf%rxs#RJh4#xSa{d~gLF)+Yg)2Mv{&1B zz`Iybn&iQ@Ef#ZywWy6=0)?{yEL(zMzJRE~yH^2#+pZa^^lB-ctyn4s3iHt5?xpY} zfzZpa;Pi)wOkE~sxjhK0-o-Ovh!)Glo`OGkQkIL8-9D>9u^JS+k0Mq1ZMhgPJjS?2 zu0TwGh`tWGj09!-3ei!}LlN$8?ZZS9x|ptpoA3;Ue68tOguQLK1E1f+R3GW7s>sj1 z7N0q9Zu}CY`QZtkuC3KE6NX^-z8F^|v<(xd8z+OmP3~nvB1HqlEaE~0EINhNk8#`A__gGfH_AK?5XX!f-J0w6duo>BsPB?=( zdw!r4!@kIt9E3+Gy)t4tMuG@YtP`92o_JTd7Rr4w0X`tvm_A)4+Ngys!0{Ql5`caU zhUP8|9XMEu5iKFpfrJl7c-)2XEu?}FalD1uJo>fB2AyC_!&*$me?dESEu33TWJ<`^ zGG`{%vvG@pS0F0+u^voxwy~!oUxsHhvAs}U4=DDFgzbi` z=pk~;6qGi6j@dB>w0GYZaaS0C(+A>$%=}zU*-e}U<_j#|9GfWv8Bve&&P(z4a&cEd z&`|u2$ecGH*~!Itir<;@a^rby4pU-tNKQgO@RUa*CeK?KUmi*S7sRu~D|j@mQYRkH zoWU-CAcm-aXO;LT%u^j?Ie}8J##O^I)``Jxk;GkXH3(#0v!r0R0IHynKW|w)5Bc+! zvfb-o+Ec2-%;tdDRJb34OzuOZDqR}DM#ZBsZ##Y{X7r|xZA1t2g%5b=@`d-|g4meSGkXr)t;SR>|r6JL%_X3jevUye?OV1^+=dHT=5h81^*$tNA! zdb_r^)lS%C_Q~JbqYp)2^*rYIk?3phnjGigfh&+j-K78oMEKvom||Fo{n_F<$X*_! zgtW=i{uD&v{FHq(M{46SJEXQVUtmw)#**_E`U@`%W4neU8(8u&@`fV_a&WpR9mdAI zc9&DYB)|3t{lD4LTvpmsTFjg`h$n@@y1W}opv~VZE@#F0V!6;2_)P_Hs}=xW6^Jd^ zY)VVsL*%MTQud)#BLR34jQMaE!>FlCj&mK3V_EoF3Myj$3RcFKyhoSASNTlGoCF>c zV8D?oRZ|`g@U(h_Mjgk>eWYM@I*Zzbhm3XA?A0JC*!?>aLcTz00xkbY5%}_NvlTV$ z$tcX0!h6V$bePKeOGuwC-4pd*8UzOOKy6dn8L3HPk2hhbv0}IAfQ#UCN z*G}VT^1UJ4#?0i&(sXq3nNjNFF&ItNOa@jnm;PApkUlvJhu|WZe9SsF=Ne+7Xq-O+a1hqUMTegfF_@zsW-?ZwAyx}sD-RUztmrz zMdqe?!qFdN5V=nrU^4`@lx+C3ZTlcO2YBS}o~&%2*xt7fDy?(q7ATv=@RWmwa>#yh zvU@}gN+%MFbi>0Ht4N{X_dFBHB_(?i;K(jV1L2>G24Ny%9kgx8@;*l_T#XWsh3Eay z+Y&K?*_uRO;UY>QCd`%70D2Q}1i&%^_5e6az$XCyFroib0iXkQ*?|A%u`_E7sO{Ezhp>8WmAI_253h|J)>L4r} zN`eof1x$X~!W#haeCCQThi$K2Wdot;;*j?C**+Z~!|rhyJQbcVhh0<(u_*E6{+xI1 z`P`nT4IZY~R4rq{Ys3b!_WEktH$tg~_G7%cm!%0)0C2@e0^o}G2f!6?1OV>T*2YK< zU8U{<%(p6ar=!Hjgt%K6 zM;x@x@IEP?5IUoD`y>R#68c*R%7YU?P@J$AKvfR&&DW%oz0r1Sy2K6`-2&Z^v$t(pt4`#z3pv9}6+-kvW=sB^0@H^0a7xSHG^(pWf z$nKuQg+WCK4=LH8Zh0QNm`ydP=YyI@j)UjLNZ})pb$%#@>Tg-?h$$S_+!0Hpb9J|E z3rQUNRvv}h#o$+ z>h2>aCP98!z)k#FWKUGH8!IIr^Vx;CPc};e^=3&my7AyJLB6jp^WMg|#!SeHwjZObfbYe~47G2und8LC3ev|>D z@SlLgARA$rd||zkp?$1u*|Bve8bos^#1HC|7D++_ya1Pygi&9yUEhg85o+XY{BR+n zJW$Emd~;xhujBdt9yuOa=}*jJo)-G_MTX@eCv7CIjal5pBo;j%V-U1j@_-$5`RMsu z?D`6rV-#CITJ-fE3r?5UaDK(Me=kO>zhala$I3bWD>1<3WIUZ%WX?MgPiF`Pn65m` z7+{W?X~PMg(0K&CrYeISYbVuX9?!61PQ$u@=@`!V@%B2D`0@5n?sQ@`!E(HP&mAk( zGsMIz0Qm8C5deO??FB9P@wO8He!N`(=4xvNNaeKx06*SdM$B})J-G&HFI4bF<0t|L zKi=LCfFEy{{y+&3mI0x4fZyh#sT zBwzu6ahI??_kn~jE+OU!0K6_kW@qYs0wD5= z_|j$w)g^ufrN7-I>TOP8*75TqHvK9_2iFYwmVgyp6)y-8V48UiZMgxsa1CvZCJ&&{ zwt{R=hZEnrKtSG7(NAaqvwU_PJNIoa%3|&eX;=+B+1Xi=JwIlQ+yHXxp~~Uq#GO`Q zC88iVVdqU+0dHVSKeYzKn-Ihui>=5ev;wE7#N_^p#!2S3> zJmYU2#QX}+=!CK6qcENp0Xn|>6jdw#5kvX$U7_{y-DGG=3!lw=9U9{Y0f!&pJboSU zeC3+~ytS9~qgH+sL+#CC_|jJ&B>h84&iF0DAJK$CH&PzKO?CmuC1Aa$XexO`XMBBty6_k%TJXG{h!sM(gz05@ z7LpD$JqvNG@hqeTO*SOdek|`PVoMarX#dR)J{6A&&!NuD-!avH1F++F@s98b!ojLP zVB{459{&L&-y!?c^s`5-;jW&7svUpgObfp@kli{EK+C_xJ~lJqHnK;%h}F&cyA$O7 z1$qAh;LePnA6GN@H>lX~x7byv2Pfo@CBxBlRorfm5|7)9z-S$}KL8_-+sjD;J(kR( zHt4bBN%#zp+vJQqZg;EEY7>z1xSauj$L)Axrnp_d2B|$Nco-NDVLWcX1pslokuVy; zD)1kQQ2_W{JLM>v;EBgHg0~}|Y{Bfz3dzru_fj085tcf@a<5?KNe<$g-cp)y+F8U# zHBNYlzH|Nv2hoJg(-1yI@^MVQVzSu499on@`DmHNg(Y9;(;$D82C83s1XQEDI<(Alky zQkL)y>Tp2cN7xMj4>{5Vdx+$x=HUSN(flw}p|cUJqbT`02D+#w;Ks(mWDPr)E!J%? z#7@a@a9qJp9qe)vUe0WbSF*Li{U!M&&2wM9>Osp#9hUQsXyd*f0fLS}=!7F*xEB8y z7c|)TNr?E7XbPdLE|aE7f$r4QJY3SEgs40hH*N5MfyGFYpF6$ttU#%uREZKDmT8py z?CC7-9gGR3(;kk{t!7p+M?UlX!qCL~=an#u!Qx2zoqUmT|yvEJuybT2A$Kd$lQa#B@Ekvo1>4!orF7mOI`Vcz~ z9)r*o!S>ge^xV;?%Qoj;Ibk&q1EWirWN$CnRXVZOOqy+aKT7)3R+#_7iLGo3Ib#68 zGs9S?_eH&{V-CLVQT1T#IIO~D4`>G2cTwUhhkys!O@QfmGij3`bo|$ejgEsc>HaD z`jr!fs0hN}w!(J>p66@J!HD6FVAq;S^|F(^EXQOHQeqtaTIoLAafB{04!L=g5js^I zKhOi+5*(*3L9QMSx^Q)%t9E*TE8cq!+W(?K{dE8Tlcs;T8U)k*{!gNCHR`AP{tp^o z*I#{ex@pypj%KCUlVV&mE*FNcXQe-jb=I21pzM@qPMF8n;tK^$nS2heYAny`tMWNG zLIIz%}_i ziR|5x*q2OUx?b>r8LTo0+mkuWCm5x9tW~h&8@W(*m@_C_Jnb-t?tu+emPak>@WjJe zOJy2X^pofzyo=4@)rDf6NL3>o(Z8oUOo~|^$YR?|TN(3%0ou;|@VAqkm2U+=&#>4{ zcr+VYM|$C7-lYYm*-uD8=;Avyc!q<-j<`!+f`l{G(g{)!i@Ae1i333!7Sl)cc2l0w zX7UZ+y7UJAMhe%+MG&Qt&uR^gBo8A@?Xd%J_*@kUH$z}#s z@*J_Ot<*#qj!IHqc=0DjuN}g{9RN6dNfQzfuy~3R)EWL_S zin3rr&^pmUN^|Q7M(eCK3KDrblMJ9`M=4w|02ofd8vs^y#4f_K2G6rUpcmZ-%Y@XB zPEx4Q3qX4UIsll|37U3A07imS?Ie8?aOk@)<0t96ASJM~6k$Fo!YNlHVG1H?ZfEJC zT4;*uNnH`je+AcPU8N-9`R`EGatB2R%9L)>2WsIdX2y-~QbXZGQ1Z-wCMbLNfZ2xv z_^b!a{w0lwWg~hA>mtB_mtE^=~Im99XyFe;x(Q%=q=?58-eQlvH2nR zGL(+KFEwW!--HX?Mqjat#tF7&ami1eOt=h?rWT$&kwtBd?F+$Qq13V;^w|M`3-CXS zjjR9xJW~z@z!#k?)bmVv1OUDPOdwXuls~{A$eD8Vlj=k03=*CxdjsH^vQUHK=f_Sw zQ?|h%^BrFpzOsY#Bm-*=wtaEJNC1?WIc$FH#1DVU*`A-_JN*Yqe-g%sCqiogaMOSH2&Nw_ zO&0b6;9FeeL2s}Q^QA<$t&ik6Z{B4t28n5iw8m|Ajf#P&zSCID_q ze^ene@Mg1yNkKyRBPY{_VbWx^Q1sA=c@2k3F26gO1`VeaY6wuK5m2`S0Jo8-`vk7f z)%^wlS64t4)J`U= z@cR&syre=q+p+sd9Rzr&xB%Q&;Pv!A53LI>+2V&$EO9t)sm9b$-3496c|vfe19WQ* z-RMFBi5-O_PP|yE!a=#_KzQoQXrw~z9aI%s=oAQj2v5z7!msTdB~?WOs6uL(@gvQa z>oP{H>%w1vXF1*+ZSdNt>JQqn z%F}aH%e5<{Dm*<=R(@Lb_Ye;~cg1xpz5~MZS5~@C^y^4JxS@;PbSvsbuBzhYOxJBM zb8U?C!67f`c$Xi30!f>ed;zDs{23jNz?IWo$}RGRb@2~=qXpyUMbXV)CV4+Thn9WH ztB@bi@_&PqxLi_5%5l=0LpQi6jiO8eC%u>lkdg!vUy@SpgetnrMO~pwU+BsS%n7W8 zUJiC;FFJeTmD*lx_cAdA-zFgH{!rU`IZA-l_;S=004+z^>7d9LF2@&^AS1-)kIwYz zc{bga;5Q?%2?IAYHvE5h*UptI7B>3_yUf~wt7d&F73!yW^G zFR|ZDk$i-0q!(?orKwVodIgJ`Dn$vKfgChds&9U}v}`Jt&K_{&F9;ZpTJv_fp0q+W z;T{sp)@iDzK^hhyf&C!D*SKj|1O|a+_cX+~WUxG#h6ol3AY(d~M`|7aku6EgY9uR12W4Xkkb-;^D)GAln;_z!suGq$yAAz_kTNv=P22Tm* zGT-WeCw#VTciQd{A8m~++n)c6XL?}w>~M8}6_c_L`X5ZR9ja+Hn3cbYaUWw}EixU(@eGo=gG5A8}b~0WM4ZfdBL3@vc+RU5nSnA09CZo5xx2iJ@+L z<)@04CyIMMF@5tM}CT}ATkq26Kf?D_6_)i6J zzm0FI*T!cePoc+2&6Ba4#eFrISHL2G;ErL>7uG0GURPsyamNiVz@MLD_&b6Zx9L6U z8R#m}SF<;XeX$A;!J6iaF2NHaPpWz#8kpu>H5W0$4#726#ipyeghG1 z)dYmJKp882W^??<0F+}@v>3c3v4V`vp1dW-dQASg_C#JK@8Ji&rm7KL?h0eGvatvL zoU&!h)zOP6@ukG$XY7x%rOm>F+sOBo8_Z3Z`&{fEF5Rx4^&SGr@VU}{x2-iQ7Na71 zp0rH9r1}f;@2Zxx=9bbxw0or#%=+g_sm}B;-!dcW;(R4%mEB%2AJ*Zkd20ZC2xi^lJ0ku7v%4?|CBBRE zTZGF=y=!zf7PWXhX>^OKQK3f#e;_$vv6LZ9#ssK39AQ+l9FBZ{lTyv9!;w2T(L9}r zTm--mM@|Faha>r%wCZrg9_xtp;mE&;6q&5*aO5#2J3ky*07mO<^esr_+2{-a{BUF( z0Dd?!6aYUQ=~RO!8WsF-L-;D;mg39}q3FTo6=lYJLooB>zuCUy{-5~X|P zP-wYyN7w~m_X+?j0kC(GV@(6_$GcJs>mP`eBJYB@YG*CK17|j#@}rR`61Gw@X8+gK zn1FIx^s3z@jW9n@;ftR6@Kp)d6bxLzQ$12+cY`$Bvb!-KzS5R}mJA`sBf*B4C{)+H zRw`V&!QE)do0K&FubV1Ch#eGPDb;`Ny%b8aDR9xo2D-X~UcO|iMfl*CMDQ-`TBnO` z22xaj2!GAi~*0SJr=(G*sx1lKH$OhQ0B<=)zVU5r?=X)ev15 zbURi{X9WiUydzogzp9SpqQu1)U#p66Y3zfwc#tytnv)4}ELbgcM&*$A;drqC=;(?b zT-3!I_skhr9!!Zj%O7ZjSmE~qk0;mB!H#9t8P{J!?2Qku%H!6Cp0{UtGCiJU`+kW@ zS(w}Zd47t#SZ*v4%IIg@`HhQN-~iD(`*Xqdd4XU=Vzes$Q%>CLc{!FCzP(DZGmfC& zJz%?Z4=vDdAILLq3K;oGvgiH%y{h8o@SKG5aXASef&bpK#0vf_r7rm3nUu1bPt->! zSCjF=mbekPo{VQL>Lx5_oivO6yij!3^3(fHh@CkL#o+9Xs_E3&y%OwcQ}DGq%4qt@ zjq=Q{cTU18bh&&8(b#~-21+BLp?mv-l;2(<XU(}) z<#Q$kfNsR(R-7=RE?FQfK&8fTP#l=IGM+sdhR128KZHp_(_IzQWTy<>#UI;Igm#dFWN(m*J{J&7X&s0`L2=^c4$Dlbr24 zVYR2n7f-$xJ+e3AS2DJ;TjUEiW#kgK1bmwU{!7Nl7xIw(;g=3@4W0#d&q*jl%-~kW zX%4x^Edj35Suq~mB6A*cG`I!7=$4X`aNI&Ky9Q;K<*j9U?h={vPATanlDsB42?s3< zvRly4FRK6a;*63Ep61EmP7A&45)@*qU;8_!T>CrAul*G$^cY=yydzh3iE_QH5uWAp z10R(d{sULYoOhmI*ISLaNja~^CyD9vF=zov?8XX=e%&OtVKj|8UShQs|09xEHq}QZ zv6ZQ)Zw&gkQEr~ZoEGDMizGI#2>)9pv7;A7AIIb*{-o)Z;K2If=g%HjFV~LrCs@L8 zF~j5dYpTAZ^wgc*-!6%!n;WD_qV5!Kw6;^HRGh~D(QVoGE7A=1_-$)8$qZcgw97X~XeecvOcwWc*jFdD?C1 zvSurigDQbyaBvdhIGj^^>I?{J=6@Q-gAhdm5o6VA|^{}Tk&!yM4 zS)}!s+r%IiwewcmY@5c$9g@DGfz>|bj+PfbCY5bCEO`X-PM66I)f%L4(@oLEQaTM% zQ9BRCToW**4oQc-8oj{xKJb}2KFmG2kLQK=Oq0bH(jwkd_6uvV9KSh@#HOkB+dTLQI@+7AN3)*ob+H?#WqxiA6C@m$o;j|<@jyM)^csrcn?uPWhMx+Zkgl^?F`UuN5VASms&DIcn@rl`IIKFrYUdLt;^Ip&h=*<%e}q8)1JLb+)Qz zR9Ao&H~hrbpOunZR04lQ)}V+qD7RM~M4;MkV`)j&gx=(4t;vgv%;%g`S9A9=YjsYF zv_o^Mhjwh-IVsAA-~@a6R_5wNq=iRI0uQvwM2tMvnwic?ahfd`+3)A1UiJflyk63p zbv`eJ+F^i8wSVC|VA3rb>{6}OVDrIGViQZHd30B_lmh?1rINR$fXH8$C6q}{@>NnP z(bTz2vbB@zdnU1d7o?YgoO7q*dTv!Qm*YdznC}(*Xe95V^o}fK0G7#1(%ArBy+oO= z)!CkC=Q5uwk`HsfY~~8Z>!8YT&9?Be)Pq`lq77D}W=&SxRBCZ9P4rS)B{9)UM?X!W z1?#WYyiqKQO*Yv>+>9j^RamOS!`j%86o4ApzHV4imW1SPpsJHb+SrU zp0?}%3t4&EJISWbk1VqGSPg)+tTE~TrPp{$q1t6-kn@GJ#3xdJEu1EA^!+qET>b{T zjG!MRE&KY3^a=I6NSl@@Ya3XV?QlG_jr7!cv;3#hNA_^+qILzz7MYH0%I{J-8L~** zH5IqXr9RB>59v)=6hi9DAN9z%C7t+eIWC$ka-J*4F}9w8CN+p(X{GsX$klEJT1K!_Z8wr ze1&vBfELc3n3Obtl)YAYJ<_dYmhz7@kt>P};ER8xn{qqe3WHU~$lGa~BI{WCuk<$W ztF|oNbR|fatY$AOWsUQ+;c0T0%U?>LQ0UClUSmrur8zPKYN1@2T)@hkU5aV<;+6EK z-C~MJFPZL@v~8O#Z!l523hH*yzO-BU&H*?6O_pDvVj@X!?#-xKY9 z#f8YlmGR_!M(*NE%M95(a1>ffs^FklV zAyif|nGLC zSW=n^#vY(1Z^ZYkO}G4Y3%SP>X`d#V#s%tz@lvTaE{z;NSYrTT5lZ|c6w@Byi!9he z-HSv6P^%DIEna`NDm&!mgk;tvM7Kn4(>9Gk)OwaxPgg`KyVf?j0^KeOM|Kbxsyp7D zvru;6ix(5-eq@>Z93KkNz?*kCpZ_ZFaCjX#7*?2CJl@I7H(b|HN5ff5LU|vQNTveva3VQbvf7TEcck=mOdOFrD}s9S^hO20HEkCq-Z0 z|No$9mt&-8U(K+iY)d$F>~fTJ-0m2vs29!E8?13GX0DOCQJTj`*qlgR3r+bEb_o9i z%8nqXrVlZx1>-hhz;isLJ{YWaTy_gn=+qJB`i5?xX73R;@eN%k&HAIPQ8iRxr4hK66tI(^*&&3GtWb_&m)CPpB6~aX( zya^uC-Z8OJZQ;Y22iT#ux``UBk5TP($(qI{cB;M3hb?ahy#h?krvr!_IZ+GNp*zNfSS36FchCHJK)MsH1L*Ci!#LxD!UZ z@#o~aVQgn-U7#k&#LjirHD3Pp#Wpcu6ep8^EMo7NQR3Pq1zx-Oc~eQZlF^u^VhLZwi= z-5Yw8f5r~=hOtUNv(n?pK3R`<-UP+^&)8RQg5q6kidhQ9tUjRV{~0^g2NWHwDOxBL z^ZSCr=QH+QUr;z&Q#}7nZe@8tP+Z*0F82e)$-P#3e6CQe?vK8#*~@!PIF;QVR(A+0|1PqU{qr8V z^{YeBy^jZ%xszh`EkJ zA0u|N_ePqd=rBVm_lWAAjA&-Wv@kys(R1AB`~Z&2CorZQu)cv2||)zh)Qv z_Cx-MJaQf&RO&O zE{a`s+4v}(GkcP%!{=GX>Dp+%+sS?(hd_LMC#ydmt$enVjU5jyHtu43$0JZL+{x-r z(Dl-c-$~j{*!`$SW=o&7x%I)1U8b(*F7O0#r3bDfQK zW9D|5X~Ygvqd6;`jisX9cGHZxy2fhF%WZ7eJShM3Hnu%mcTQ8Zjm^jbSHU)!>)q`# zSL|GHjo+qlg(zH(oaq4uvU4jyScem~VD5_`rDCg0eGmT^=&rMAi-FAFDsvdO${e!`NpuUAvjmj` z6^@Py$InZFv{g9%-Xe3{+A4GWwhWaeTjVzO;y<;~Wd)F;Jo!Xsx&8?Q%Xe(`YH0JpC)9|-w)7LZr74@`mOfeoir$~F>uX@v^iSB>_jN~D z`C1_DI9m(NvrRI`?N8V)hE9CFNhbbm6A@QxCT)`YFjS%I0wHA3rt2W2kwP5AiI1>p z9|BpvQRXPyC`&$!NFcq0dwm^E#Uj?rUf*2vV6o|4dwmlp zI$hNsb2goD)i+XWN*9>^ann26YF6Z$?7a2(0-{Z>DZ*FJ>_L~OzLR7+QCGiTXRoDW zfvgNuZX1n3#`{_f~nvbTifBNhD z+5=le=eYd_=)ElkevbR`0DW&wsI0CRC-aa`Diw9H6HI6NetLh>x2WAn^rcE))BJ(@ zRJG>bWOizhzP|l^P|%@3;81;6S=MIk>v6hi>AHUs8+|XXa8jC>&rHw?nYztSG~KX+UaSmb(X%7+_AsXS>P~z8XJEY&pwN@^z}61 zlT5#4=^Zti>+i7NhnV#onQEnH95&xodKPK-WRRY5tazxto-EcQgFP6kZ%Bnw?PP3Y zhv_G45+<6~4$~)VG(S%=T^_FAYSRurp*j|1REOYxGhofZU?cq(8ip8KPpU*pJ>bAe zdgMU;UjkbO;t&h=q$eF5cPzPrTXAkWJN>raKSXX0PEwOFAzdc?76<2J^bLs+hsM~} zRwvBU{-sECNHz5vqj%9X0VN*h$|tyZYT!;f1=^}66wt*xl0r`b-7JGvq@9hYN#pcA ziLprgF`B^hl-DwLtTx(sMw80I#_Jo(j6K1KBfHl!P6s27jVvzrG}W|dyxv8feJ@1y zgxj-aPB(%z(?g8(pX^yNp_)DML=jS|_r6H`0UmXuzv0)?D()+Fbb|BKKRCg$!6A6n zc;smhzgVPg$OX_da~3kuZ0G5{rWvl6E2&uT8e&AyweU#lq|$3{)l zH`hMI@b2`-Gk~1FdcU;`^fv6wVtwq|>G~LQdN@+L$uM2-V%r`AP)dUm9L)!%RC73# z2Bnk+Pf1X`gaa<%OS3V!P+*<4kAfAPmcXS%5KAyyRY3;z6@t zo}_4Z31(EhgqI!COkQ*Koz!g=ebgC>K51bVeZCn}r4MIn1|e4ZaNJ=y2RX@)rd{*& zgEd|pnI&sNCgo)*-4wP!KV7Z)XC&LWP#;#mpg#YMt77va?aeoMnQTt?SHFeI;c02? z@k0HNnrkE2H;eRJG)G6Xv5R5rv#8v;C!@NpN62=boMdXbL?0mehv3N`#gZ<(TSc0O z^{87#!h%rawTG6FgwzCdJr3XNdJ|ErXVP%8>jJq!$Pxa5bN}X{&E#fU4s@&OXpaWg|ntGM$PsnB`i?&s0HaE4AUK(VYW3k4Ay^+q8KG(Uk zqAPm*p7pYRiYn)KfB#xq2p zGAQ!33|Tc9y2cxeyRmhT^o;`xDLhfaL=XDuk&u#2a6Gb!2aoiR?1%;#(2d7>A2a;w zvAz}WKe8H2|EFa;s3y?o)T*gFT`|Rqc-a(vS{WPshbgjZ(!vz}|A#5&)}W6SU<()7 z7Oyo$K@A20rmzJ)%YUTzGkx+@e@|l>!?}wU#do%n75}TXF}^E}%Yf$?!+qABEU=#M4Qt8KfJCc11w$91q{OL>9cCm!_p7Cn11<7|DC=4t%0g1 z$%(e?=u7=%ulp#3&$TuFivR77*%}|<|7f+HsePs1Tdlu`k`}d`>X@x*(kp#)wH>BT zxKXu#x3kVpf!FMIp3740olEVPVSyN3kz@+lVz5;UW7}7nBDWem)NVV#^lP;0;C4He zi^^6tZb-94*1gbBX8$QF7UHQ^4wauWapWQ)v=*7(4{~?TF2(cmx}`%kZ%}azREVQ#nL}Hrm3U16(5K zmvO{DGo#XUcekOBCi3U>+8j543*uT-aa>NXG>zVC7-=IorB<>FpBu`8eoBE8MI&kW z1HX+{&+T^a8Qn8*+nx&iG74Q!esc+6znBcYS{6Xd;9?DKBH5JP8scm;LMItV7m}Tg zw?dqa%gwkpxcn>tcUx~<1l-gEhDP>lVC4OC(oDM#7((?z>()@=gkitk5~TRy`1-YP zQh*s=|DZz^{NCU|R&mm>(za7#B|F2iq&Dv2^jAF!a@A$&z?@`Bz&K8mF|B|({jFiA za2+#r<|#v5J1!nyVWSVe(MS1k0Utkj!2>dC)(Wr2hrtSkF3)S?6K}ujp{RIdm}8)= ztnHC`i3Aow@u;53(T+Fd=F8Bj?9&E++iwAs^3UBnK9{SG0dw@UVF1}NFSuSyV}6RJ zY~v73*$2toj(Ndv1{vwcg&Q|%%2u0kup|9wc;jtN*-GGgpMf1$q1{RN%=XGNhD*Zr zq)ImWtYNYZiDf^ZHH2#XicL=E3@`14R`He0=_f-tnUyqE^ygre{*Qi2iWYa%hx%-d znuJO=jUB_++QnTm<{!v-hq>%Xa`#d&zXLNK-*2a1O-^bF7by~x{dmz2e-d&hZ=8{gc`?TAov&zwKtY;0xmbyILeG8za0Wx zN~m!daIY>}+1qf*FjtoLwF5l99z4FDv9XzxqzS;?4ly<~<49Ubi1F5@5Mu-2{O)C zIBr4UhPWHw0j{LnO1Xc_4NGKcJ@jbQ4UM`PTbnt#1%VUXj4jMKZb4Uc!qwOexT80% zlzWDPqTFJL%XLAcF2*hTJwZqmY?LA#=lRgIc3m z9mO`@G1PS$Ew5G;umU@O$B-pqO5}yFz)LfNRb@+9)-MKp*Yy{J4b6MtnJ&C752pmr z`Nd#?&-HFYQ;3svjmLK>C`QbS55caw%3m2Bl* zgTHVbz-|H#12_-Bc0YitY{Cce?vB1P@lIg$_dv5bw$c=R&u~z~OGX_s{ zHU82amPE<1eF%fqI~zLS@te zpd#6^QElBt1yckJEP6b{-J_mNQwU5*g~f&gKkQ4+Mdn=Jw@P_kWqTi%_uSwoECBuP z=Wv(V0L}x@O$N~SxkbXRtzFC#0xGJy+3I$NrJJq3Os#^4^|QdcDh$nS4G?#d8NbeO zV=pQ&=+P*D&9WZ%b!Yzn80>AsP%fr=ca}iqK$QEiEL|ISHh{`rDEDM@sXUv?dX&4$ z<&UXskMd1+%%-h7J51$Q7_MuqfXdgX{0!wwa``2dAEWFd>*Mz?^tp?&q_qDp>TjUz zz>UlXQ27GNTe*qZY$~5ed6QiKG0M6VC~uGrUJ5JI_u)N`%46|4s{Y3E4e#Mq#eAX@ z*y=0900P#Z8A#S8@VY}we0TE&R9XtY^=z(lqPuuNmNXBTBg`c+&RyIiV`c!elw%zC z%b1D4{QJVtvmI~FD&4vnjWo=ZT2T{^3Ekt~(c1W+uV3|0R9^Se(5Y)pzJey;^R3M{ zw;}K$wek61nB~dS_*?e0TSvS;t@3E$!6^jo<+HJUVguG3h>fWwb8Z-TBWv?!1p(irHop8ri_BJU^$lQM z)UOd5Tp!FKwat0Vj~c6u&u12)=OB~aL0Pgk^b_c$k$eg(|DU3^>z0AZN5xg2;zEGa-(cw zo9h^Gt*Zod8qqh3<=ez+bqi4uUq#$XiJN5BbEZ^tP^h$#gEpb(^y_75T=!@D0M_)& zL>KY6+;&%p3uSYUw{RCv%9ysmq_Cvqcz2I78IuIef+}5fI|iGZ!9ZF>pPNwCOegfw z+~4&(@Zm^IWm>O9NV?3oDxwnWY=C(#N2n7r&5M{y)`CswAL}ljkuiS)GnmaiZE*J} zl`+2olT)QpfPIx3>vyC_NxvzYe+RndvaD}p&QriN=CZ_7GUh8_x^N3H|9KhqwueyO z#BTnW<}O~8DfR+$jAfk!M$u?HFax=bM5U#Tz$~zmvW`n>^o?&2o2`wFq%5c?IN#lv zKLlIFTus>&L|u-10o*3wN;G8?%s6B}`L}@+gtE7R>wGK8gFV;A`q@v%{E5p>Gx<8i zZWhE5*js766De%uu`^<_rU?M-jY1w+%}O z0q>qxfH~`1MRRu;qApt=MeabIcSJNV0A@Zg(S=?7#aRISVRPD4vP3C1$n?TF_I-`e z`He~wbBlFQi#@Qjr&`B1!616PV;6YPp}9dWo$(*N#MEW-J9E{g5-NPp;=dNTXk7H3fN|Pu*_p!8!`{i*gskp z(9e_RyCdtDH*43U`Do+?ulB+o3b>FU<0UhWXZ^t44mAD%T#8q0Bl}5cj5c*My<(H9 zq}>j{RwKZ;$IMC6HUXC#VEojKBWXi`O9?P;1@4)(wCFmq9jm0J_(KnW<6JW*NfUs( z?Pr{2#*wrVY#TTE8K(kgs$-?w<2uj{K9(2U!3TO^Bbn=K>|y34X+wZZ@ilff<49Tv zaDuO~9dM()t)y-8j%`+@o8SXIyp0iNPLfuFedZ=_W2hNN(sF?t;%y89&dtY4T6>>Z zzLm=hz6#xjU^kjl$M^sq#`Ps>A;1ZBjK7$1B<;2r?CWK`37pg)Z2UZt^s41?8WD_jan|W19>75Km(P@GlHW6&z2JQ-BZgG=2zt zm>(o#eEFt*h+k|YnmKv!taW~|-CDzQ^0?=OU^9yi?caj9eJHprEntIt3!Bz z6L1hFlwHGA;`%nIi-R!WHVI`H%{WNQF9GhhQ1(4=8G%;PvIAqAbtg_-G&kPDU$9@O zQI#2POim0p?olLI>L6VeggRBYaeK`=w4y3+U`#GX2DT50ZEGW32}A4)iwzgrAUc(V#U=?yfw6B8+enB2reycRvQ%Xm8Nb$d;CvK zPBfV!V!H~OIU&q3D)u}4H(ig4O}4d}gB>@k*EIGccY zb`SvvL0QBN1#x$}M_~X_K^Ax84x&+`aYYgeP{rc#8H%ek_z;S;V zgB5yDAI#q}?ln2pLeGz|($^PZ{V2;Eu9NmV%F!wBjj(1-UThVaVMCuyw94%4XRxT* z&SLUig})%&s^6H$Rnw4O;cnj643oe7T5hB z3Ol-=-p16pBF~m&#FrMt5fENAA+@CI6N{F#-?6Wv#1`F$k!kG1gpfZS`Ze}=hiSTq zd%0xm_^d8(7 zNJppW!<;?^;mjgnYKq>QTZ#1C6n$%_MIgFLkwp$5hif*{ce$oJI}$CL+iL;S`v|ko z9B}SaUDHAIk+OJBU&Qzm0U0Ir{tFp021qX!B6PLnRX0>#IIZcJt}LNqx($qWljV8H z-$;djJAH5~( zV-Q_IwD=1I{XXQ@E;*{xA_I7ji=&qj* z)JLjx7xK_?No`Xc-59x{#xw5M*X>GXSC8@~vzGC=7hn(`bnT6g(?iirwW6v{z~52h zNB>d^AYTsBC#&?8qSD*B!O!i>$;6J$c5a9Y5B;x2pD?%~eLZ1^L2XA^B=7_^o>OJf zcNY3o4$U z$O3^p9nwJEbGsqm7InTVy6v$|jTfA^=)2y%KgRJyJ+?Q7Hqh$Q-q$p>1}ubz-g;Aw zYtC6T2M^OH54Nv)F5UO*sm`aR`eN011|FnY&6!tS<4N!ceN$Yf+<;rF=vG(Tv1+%5 z0FPGV1=y#M-FiKR$596djgDl>@CGzz(k;M8V^o@@jj(^!c;!)x=ARFb3S4`)pA+4H zr4#+V=C$MnHegx7YtqIlBV)&6>{!d@cvXy1;GNneg*>apiyT=(UZ&7-R#~P{T3Mz@ zQho+M$T&|?~pVrvLm z%;txqI(qIt%>G8|}AL#!TsXV4FA7W|$3bY+0@(!y!r8~N0c66s3;MAmV zk>&nqeG8|rK%8Ma;c|t)01`b0tW6-CN!-&kX%~d%S_5PzWi12oA;}%n*Utm{Rg|>= z2v4-1#`*c5V#quoBUmHR;-wv_NV)jw;C)PT>FfJ%nDj&-TiKo%cI~OgF+h%zhoiC1 zJj9TpK(4V}GC4$3fV^P2%9uUqdDT_SS8`Hq9I$E^afyOaZDlTaK6ep61~xatM%(@jJP}LUPC(mMXV~E^W+^$T zwk%)?&f+))quRoOan9mMV9}X2+9qe}$9iKg>;XQAeV~ajn!}=uzJp}DNK`(Lv&Cn7P@T8W9AiXpJixmwJE=%8iz-vG%y_?iL^KDWSg-0dH#E(Ky zIlQo}=ESq$TijR1p>mvfQo*Q+dBCzb@kd~JSvDpf%+g<@oly#uiTdF7jF#u8EPRh< z9={0JB@A*iyD!>RSJyp|)A%tN(|;%GuWOaeKflU)HC1#Ew5P2iS5on+-q+_#2PH4l zf1612-@wVNH`A=6CR@~)=1G}m)sn8p*qpa6Zmir9-d)xpJ3ujI8$|4zAU*>zcb5KJr-?9PKgp#ZE4@wkIvpy; zP_sxOMdmPMD3DzYp&v9sCI!eTmPx)tbO|E<$Suy?IzoAjdt*aI|#w4E-)!ApmT3Q$Ymkc^0{ zvBxugfR9(>Ml2|0o9T;QvS<$0EB2Xl{gF9bow>>rcn39J@TWy-?HsJE?DduUA>V!6 zS3(_UW4xpfXNKD28muZM3=>8l1E#;X^}SR|wK^!BtIn*Y#^?+i%=;zefP zjq&rBbtD4mfU;zJV#@mjyEVdIm7MnK9v|&-i)C&P(O6ah7XQ?MmOwg_uwDb3k>T&_ zKjb#})|#%qufMJ3LO>n=K>wtXb7Eucn_v^EEKh$;%X#=<++Cm#bLT+NC%;l}j5GiO zo;R-5DVL`_K^}Sqz)yimcZ`YhlHz`20-xxiN}g4XUR0^bdhbBpvz zbjB+RJ7K{5iBHkO!^KfbZmN|7R^3t@reIWKSxZbYEyaPrhAhT((iPh9KEkwQvHqbn zx#x!+5|A|tStG^LCXz4mB_qosku_30q+nEC9WxUs*;mx z%LA4bAx=~n`y{04D`dRu%*A#)!qh_O7z=+MQMU60O=%1ubA$3$dH5 z!crmXs0{FoEyO5$9yK}?JWUI+4S4^qu{w$jSgT)Lzmx;L;hHeGCQQ7I9$c^bQgeWp zgHJ5&d6H|uGlq#*!D~xUN>4Ngeed%Q(SN~8K}VK4bA|!-_Jnj#ktmuJ9xWvlJWWqA z-=0THsq6vkdWeg`o4L+f7t;|Ww7zKcqGyJv;yb5i71z0Up{FvDpbh%>>X(mBr>PX6 zM-Xeg|lWGZ`Q4sHdcXI>EN1vu|iA+5=>f@yH^PdKFWaU?PE_N~Z zAxl2h=MD+O!phQK)XN#opr@HQ8hYySr22!WX(kS}=SlSsfZYLNDtO~JF)!1%Yo@)M z^rF@q9WDPht$THk;^Z%Ikl7af8XA`Q(rB0^U}zA;ZJw-5DJ;W*af0}nf}xDcY92!a zFKz-BQh;$w53KMS zKgf|ag3{1aXb{98PmH+UT`o)ENuds2PK>zHo=3~d0M8gBE&*@ycAG{pA)(c|VTtq9 zJ-YarcXaWs<3+_!e4~q#FT@kwPW@N)10j-jw@$F3llZq=1NAKcFQ=3EUwfWp19-+x z;tlY0yI=!;miYjqADO&MpXlBm6QD~Rjvf`em`uC$T5XUE*w5w$6}!9_SL2R(=y`Tf z@n49PY4}y=`P~?n5ryTJ2&K*`=#Ij>i>a(|D~~!S13Y7Qv9CRk8Wswkrn?vm9{CD} z>1fF??B-YcIB#m$=S}**KZP2n?LvC)(bssp!k(uan-@Rd(!4l=k0-Hv^}ILrq7=$y zU5k^WaNb>GK8Sp_S0B$TRhmj_#;$N-SMdv1$%W;W3QuZA@N&9}o9%g$3&AsX6$yAf zi>#KK78dDo9v!TD5P=Eg$Uc2{FN-y!yA&tCM;yM^zgFL4zs6$W;(>*WhsY^qDU%$v zLjzu=yZF*Ywo&0xJC3^J-KV?w1iT|(+t}f~Uq9B#mlpl(U{fiSo*rphocvY1Df3>4qQDCwWpAD_=IBB&CP&oY~Du<7W%+ zkYG}D2+x@eC*L2^e@WjS7HKZ`A(KmBnvyV;=sQyfSZ7uI5<`>YfK{D?*s76KNh^;! zzzANbgV@5JM;)L6uTm>E1Ke5Tshxo$pzkjBU&4BlL z%1+q=r}*?CtB&X=S$(og_Q_uOq(waOKB~{9s*0qT>IzkH_N z;pnc3__cAVer)|J(pbxhL=_{&zD^BQ5xmeyG1i_ZRS~?(4x%2s{iUpp%jvky{h$xi zdPTsK=o&?#%YNt`Cz38@`eduI`@0n<*Wj#xWBNeyMVWp?eWU0Yf*0fQcnQA6u>qs- zVmw~cR$OP#qefM>LC0w$ir}UH2%|8D;Ota z2$FFoh*&Yj{*!FaGAxP_^}_wqCrzc=?u5R;o658G7+7 zc%x6T&@ZCviCw2qZ8s%glc$oOPwQVbP)~92IC?+7;im;RX()kOAj>i$4L=NPWY@c4<9ULH5Xec7}b^lEWEiG0!()n z+R#SSSdxBLU*U`yCg0_!c+&QqelZ<9^CNHqgXx@p0S%gb$$@hbG*LL=cMBqUQn`MJ zHJlD&z0v}MJmplC>lbpvYt3X@g}y~X8i;v+*Xdlf#$suU4cC9gYBjT$?lntaEA|Ed zJ@9D()Ll>i?O6P*t|OayIdtXjiR4s;eo*};8-tZbs3Th5QPgRrCbKpRjhIRfJ%bY) z+w*9X;kt?V98PovZ{{!7CL>3F(MQpdvnXPj>7QTp*Bw}M&BD+6^18#B-Ni@^D@tmv z1YqIa#kLAY9n1l%?k2Vb=6=z}!3h^Fs>$0I^)WV@+dy+0@llqb})#>9mobT!PbHFQF4E2|Tz3k^f%Ox2Nlf{Aa7Mj_969 z*Ae;8iM)<*!kMSP>L+>8mVbH>llc)$=Kf^!uX@2602?uvSM^~-nf9{2r+XA^UZM>d z{8dF4l5kl+h)%Tf5RK0Er|GlH`p+D>ZDzBn-*tVBr@;`*4MM&~~Kx!E-LE}jc}y3nN&G`K*6eeR3T)VXyUKlk!yX49&B z`k%Pi_D{@&{=W0k{UH3-GpMGdG4A+{!UUZaRGgfeSi`h;5pQhP%>BNuUjJ&%TV4tN zg}147Qg5inw~A$f;zrOIIuH7q0v{Z1)rqr| ztkUQOEK4U&Q!uJ70a&iv@6gB<#!PqDLJV&4p?<(QLA87TUlq+r?dF- zshMnjVbx~3`T`G3R9!jqBEE*?nu^mP2CRsA5#KwO`HQbAnB+xZdH!N1FmE$cCr$GG z%(55D!z3@_7kFEnh@MJT$&0|Unusn6CV3H9coUHWwy>6YQCh1Vsnth~mqJzf0o`$} z>b;2Ig}Vr71?Zp{j*l8SAMrPIDQgArTj#RI;w1%>DgZ36vG@zH0d+Pd=GC!w!@}0| zU7dcEgBSV`8$5PledkGn9r$sy_Y_6^*^lHo@bA$OE|2(|IB@)jRG4)*cL+BlXITc=Ksg zI$xSuIn1nB>*FD5kS_(FtdiF(=P^utC9Tr}O=lYOTcp|*N&e^9=h6!vNVSvq9YavN z5HUx=q}lwEqPfax+vP-UgV=hO@*h~CJy%G6TOQ5Fq60O5=pMD zm)=h2VnV-^^BINr*|rs*D#2uy-fG(W$g0$Ev%MNure?UEn%l&O=Y7}mRxNJ4RZB&^kEwsAF~CLm+^da?yoAA)9H5*8_A$}y#DO^LVBjV z0)$Y+*WDwFLB9Z+o4~h7{27GLdG+(4#{?$$1Nfc|@KaVZ{`cT-A)Sr9ujlDi4Eh?- zMhPN~`|vJKJCR25^ar^cn8as5exVW;WCM`1OlCckSqbE4rX?R*`hS9S|BGrv@19`t zAA;Yf0seHE|33Ie@JT0szPY8@xkPIdk|BwFs#AZ+5i*;)uM5*`1hR@bR7UhbR!B(p zR3_62NWTW$bb1Qow*x<+0e*_i4+THA0si!DEPnv_`U~pXr{4XN2{eX4w*~~J%X}B` zJ2k-HozL=X!2ggniHtn2G?V$PNmekK2SD(-9NL;3O5e**k&4e+PS{G;G^0w04XdIFmsPWG_OcH~As-jj|h7Um98 zfnyMS_T$t8TX?YqlTQ6D!vPU+q5&OnX%8D`L*oR55GMxX00f1k=N~B2_dweh+8<-k zE_I=R$-pFQp`()c9@#0V)bVn)(@qC4r}P28tO0(C%eS`r_4W-8o;CpbVZlKc+KqQudFoEzt2qFQI2%90LEF?Oo zz@S+Jt(x8+Xw|gYhE7Xib+qK2N@l0QxXa8q3%r;N8jf#6i&CsAzeiSDM`|2C-<3kc zA|D~i``ols|)}Q>|)dfTj^#N`*Dmc4}Y^U{Y?Q=8BD)T6;CHhN`(? zrv}zgH5qAEYhFvUTC+S29NXN4DA(}pdw1K8^AVoUw>|{dv4B1E1W}4oMG**c;-C`i`?7t1^pMI_1 z$|nhJWuMb_mD(Y}|7YXZb1~NLRLu!HH4zfLc97LIZiDz9P8l$y5$XKnC_fMPm(ryB z3XoA`_Fznmkuo$8&~OPF?lI+GNvc1f-dELqf9Yh#H-gVM!1s{(dhol0FUK1_x}{z% z*!dAYtLd|a4;4Q{!lS9CbKLX{oNzIM56C|I8}?NGQv1lm$X;3;10VM;sa|T_ z{f1THF!-N0P{rvo|2yyt8sOjEFXeZv*aHFgR}ddxg6IIE^=1%{@2HDR@na^f1%C^v z8ba5_z6@FpXd{DCWawi+M1nd@uVPa30lC~)E52LF_-})M2NpQZ0O85hE!8sKtAJc( zb&(7j2PmT<*K}a~;owgjiJGN>SOOxkFC}iO4M=&&2DTXR7dF5@EgR7Te0RB;GSm@} zGlNcRSh;NgaTN0N2w+GskRO;(qzp9$bXXE{(=j10AWKH^aXqDYvHkFs{>;k#l^T0o z>jm7`f}6O}ysOr&^A*e^Y(oae_TY4oF?`284u0>{ny+e|_-cz@@aAa3pL zM?y?JLrkMG__wuQy^uS-R_YPRK(1%KakQ&dxFMVWvURnG&mA)`H=p(o$+0MSggV47{jfdhi z6ItJPS^P1TzA6s-vefzFzJb1JYPon~1@A_GN7BP2|_B6lc0Z@rY!Vp>fxs zc)S`vy2GLvjtnPGukzk1rG<^4bngI_(%dUhYEt8sUs#lmdzJ5^(kIovXNpQ+=_Tlk zRpXk^Ec&iAq%TYh``W7Q&|ZMPXf+I2uS5jAjR?SDnTfz}yo*+e1@Y`%zPqYqEp>WOx~gO?9lpcW zc&MkPPTN_MlwbG*b(z*B)c+Tx+!Vte5IfY<)lCWb3r#8$xL zfIqjzb6mw>;0ECTFr0Aj;hc@M_j$KL_CC%1gVs#leM*0(HB;k9Ii+UuW+w@I7rPQ3 z&Kf^SwXz3F9=?w~mCE)~;9$+}97S3a(#p*TJ*g(zX5%@|3SWxc$L0VItRB^<43C$eWu^%^D$ag181H@##L%V3iklVIV1KB zpL0P`Naok#IEIgM_yBI$pLnp%!SI|8LK;D7_r~v_=e*^*dgW96Odt3;2skHzxaEzD zxbWme+;aJGG#qKP%*e$q6{A^HCy}aLM0F8GDUdiRtRP~CZ0X4Uu z%KqFf!1L6&@h3~Y-uSQqeVK=mFF_hG>oss;A@BieJm;uIpIaWErc`rW9_w|~?%MIA z0?DU&d_d3&ydt)^Eyq{<_D$E-zdWhaEe3urkN0=W10g%=o{a|jTjzRC+d*dMpwAEd z$m*R@A6ZMB54xUwk|ghQ!p_M_#-^TWeMex?atulB$mp zK2udSqcF)>$hXVh0DTs(S2hukzTvw18jb{7ZHtHciQfai1bn$Ie$-F=26zSVMYec` zySNAVDc~R4;`njGcHln&|A66S)jNC_!Y|_8)js~;4CHjfm- zx9&?X)k@pgMnGkY`8lfE#jQuFyNt8bA7x#hSDZalxeE6TY!ZY2jLAen;I8 zGd~2Lt;RLE7NsvfX~1RL)yQ{5a!rx#gjkvl{J0u7&Xe>NpA12hI|5K5z(F><=6Z_4EYeq7Upvl zp^T6Zm(pIkly!Dm^j}L^m!P!QGS($5^0!G9-aL?_Lvauq+K$TnJQOFz$@D$YWZg18 zKmq<5W@UN}2lF|YPLZ(WDLc5MklEG>h&$;F``diZkmf+bFn(EjSAmDRQxVrPRZiCdh4Q(yA&isTFMqw}#z zx(P%&CDwqLNr`13R#0LAh`p4U2jUzh=76{l!s~SqAHhYkxn~!r1iFpGD-ES;qO~C# zYNW>QOYbr}$WKx#-hQPuXBucaDq2Fom2_T-QE{`SAQnk@%StZ>C|Zenna{w~ zl`!=Qi2IcI8-({N5PyP*ro=T6>6EwtVkRZdfLH;->n9NFEN&x~AzU%<`YJn<5S1l( zQM}B~q>~a%jH~(P^=e@A^2)Yi)|Xe-*ru=JWp_%i;D6ivfVSEE%c^xlj71m&Q z8;V*Lvw*q6+@1mix8|UWdR${jA0RiSIBObN$)H|J9;^SpT7&!^9zs|Jg&&Ko<9Ud77%`-VgugoS-jbCot2(%Gf1c!d&4^T?gMDP zN(z(pzBnC;`Qe)%uff$Q+eeu3l<2sw443Z)AnyiPmU4!!%(B7d(aHJJ3-fH|%iWX5kmJo|vi z2BB0x@XVNCaugy?FHYf&A{ms=`!&DAEd2+_E0)q(k6KJRZ^T#|y3sl|x8KOTmXC2a zZ6h3W4*7bpn-?~1#Eb0XNT*5$l0zHmi*KYSvh;5>Z9*CY8NHdoOy&0?Ei!)dPr=`Y z^ft!t{V86AZ$Vm%tq(LQ%4Bv$SWn<5vpz+2mP6}s1kI&U0WOI9aHM`9apkxMBb9Q4kiJYr zGz)p1rhSpVPvYp^D9dQt9cd@#tlgX8EDq`MH0?*uQ2xI^o5`zW-^L6-@;6OCLiz)C zO@`+dr0*bolI4%wg8bD;-(=|&n!bv38IymV%AZI2GP|2)8BL!;8aI?sd%mLSGNj*O z*La+v>4QjzlB(%w+`nmhKhizeH6ES?Nbf>=8O`rYA`4L7R;0JG@>0Qf*@$#8?tURf zr3uYV?-uZjoayh#%fm7{;Kvg9El z8OaA?B$+jX4dm!<-X(dl-A;O;KNf?NjWsH~3GkU}yb{-oNwTP6&EUSVi{@j45hs4y z=hxEwxRqChdjrRvi!yE^U-6T)ZgYMz6GbbQo+P7byps>=Q+3Qt*5kutnYU*Y4hxpu zJIUhSapQ444MWd*B(dXckoQ~Ujbk3X%e?ayknxh2-RS8!kof{gbP?aeeG`Zz6f_y{ z>qZpuQ5{y{R>LXr8GJi`P0#K4V0;JucH(ar{#@cxOFAT`mLw&mmb{jlO7<4L67NB&CG>w~h{mj`>SLx#I}S@Nq5ms` zH0IDhnVeEsr4Dj`_c5p3?qjBUq`bb6d&u&-j!i9z8kt&B>8;_+#wTRPK3?E{MvL#- zhfU$5AkOdOqXxuL)95)W)U;5oI2dMS0;B0lU#*yiv{FZx%+!*INvS1wJH$m1_~0=P z?!w_+JDyB?G?ZBZ3GtYm5_u9q^%q#w7~BtHWiBxO}k!UR?1t9~ENJHWk`l zPc2!C(x7SQ6KJ{EL_@AZ3%4KA&inZ`4p1AtpI_`OxoUPQIkKM@4N{MO7kzar`e2?$ zTzW$8<&S}70ZY(`3mH}}_55&PoJRZ**pWkgQ&RX1ALP6WaY28Ywq?Y`7&%6yd-+(n zNcRdda@?EoJ-Bp);rN zP3dh2LEJweqkrw$gLF3W;ccnMU9?@r8xER>G<+h&u3|Io+6_mLrhaXwU9-W+r;@oQ zzFGJpY*@J@Ce&yG!h$Q`(UiF0SF`js>QguiY#mCY$9R}bd}r=`SaipP#l#yR+z;^0 zxM?8T9^iXR?W43!*lK5SA!35InbJ04`L5!J3@fjc+lIE&JYZW6@MBvlM$C2Ah%VZk z;%v_4&YdT9L%SiU^V@=B?U_I3TBJkJk}n_jpH+NBTxF zKd+Ij?(8qA!D}lMU7C1-K^>j{Lqm>E+h&X=e}9h|>k%5_0_i+xd_WVZzk}3CITofP zr{M@TKZYITJNUx+MK;bag7e9$gM9Cte2c&D zz<+^$v3if2`0Y*)@uI*J?hwB|d>;CS;>jw`f9HENEqk#FXGhOL8c{x*R;?VfjqE9j zq?b*~Xv)N{jbM2KERW_V22$EU=|STI=?bJPtr4jz=KB%jVZNK9%;F~(@Ts3ZDV6+0 zwaWoXNvog!hBvH!`V%R|Pp={;{4{JdbrFqC>ZT(J%?<=1Hn%5?JU~4}W0l6KfEW$I z1;xAlG(*>;2Gn!7BBdr^g|SBVR=ElCFP($Ce0$7OytvX^d=A?IEK2GKZ-?F8CL0XLoR=7xTW>ZCgSoy){>)s z9yqF+R&gGXwbI3>9{(_84v>{hMn+x-vYb5JlpfF&IVK_XsT{<#{6CLiOYA2;iY^T5 zZDMB9!Hf-B_3&Ien1x7#Sv@@CC2nqI#$xvOq={JTw#QL7IxWltvF~vQ<;@CTJzrA0L+I zhc)k5=7)MNvY8+1;WqO_JzSn2XkXj&S9+T!NhplA*(nqxyV}OHo4<(Z!F7a4?1(`v zxHcfR44>_|96g=oFq3Q=nq&DLyJ_(J%PmFa7Wi^IYu?bAm>! zQ{*H1$nwq4K>lWlne;pZ`S6D2^IiOL-pm<3Ny~i*(Nkw3dbr|$sQyzDg(-c?p}Ga+ z$CpEXWW)0LE@D5~lwT_#f8Y@IyelC87`w9#n!Z@kKm9!9hd_SedC0G5SU%sScR$m) z^VIZv2hAkt0z}(4EL!B^qj+)kMW|j3`Mnn*{}cBA>Y0)tdwo-aDf$Y}Ye}bHA>R`6 z1Ac}4xQ6BPT|E2A@~1CD{^0j`Lc0w4XV@WYP(Qp5{e!gJP>AMTg=l^QqEj%ZyYyB} zal8iAe;4Cv;u;?n7-278rm2wR&8BqWK{U1+qJ`Mo zXwZt1zSIh+-u(wubC5s&2jpY_m;AMUChtF~>OvES>i@zY*YK>@pz3|HKMvi5=2(bd zx(Us5|Cjj4L{rEus`=V?i0|7FZT7!JFC@rDpZ*J~=R*GGUywK9dALDKnxQ4{P}R*K zI`b|>hczr(?(&7=>fio`YSXv)GU0E?KRWq8RA(ldV((Ga!yuY{AEIKzqUA0Z6xDYh zK=q?w)#u<-RTI9JRY49SS{spCu&BtPeX__$wY;BJxBP3XmL;-C z(mt~Z232WwjcvG|GWS#w`kq#}raQmSnzbBSsrKbyZgdbX=+@aV*T~EvU@qi@3f(vx z=4hGOtjKJd=_uTG&}}ZV>fMMeRPV^W;5rLV4mzC;*H7mDvd3&%;wt>9)veoW&AVnV z%R2*Ut*)yLx0B4h_m$ZcA;IqK8MMvRliN_XG~wJijHt?uAXYcU6qnHKZ*4(2h_=OM!9T3t&U zkq}wr+IF)EP95o>`*?>{K^`(v1##fQp_g$~oDJ7m=Kiz|Pa3U-Gug?QL@*rZ>s~QV z4RA3QCl|)oU=XMo1N;%^u=6pe-H8WD{!^}RO~`qN+3UGaHr#U5bng#-wYR3&1@d!| ze<~glU&CJrj%b>K|64ds@!TQU+pXzijxhHzCuBv>Hge> zIFjC0@OMvw&}$UW62NirIze!ZLC?2KU$xe_?v}4;~eY?;eYjl)Dp)JQ%m-`8f)_LH%)7-Ig7u< zd8s8n^Ng!r>+Q4gRGiPo<(@gFkO-j#LUEhbir-PX6pCMBHcb)ANYf5NQ(xJ4<;^rX z#qF?Dle9RM#C8zA<=%nOSNjPeu52UbbtFR~g)nX+i0J-83z88jWb}mj<+ETO{XYR! zp#MEv8K-8UDwKA1F_uh(*_1{#%O~ZgmK>XxYI+tacxrWzzOuV7b2q{4oQA|%*S;qA z?m{!I?#|~{+i!i&Z2xkrYAbkZeB!Lb81?W68FE ziIimfCJ^HdLTMw(_SvR3y#z09BgyvJCZV^`UaPzMnbq`PKVzn^EtE~KjDhK2*hqXP zOJp#KLh?9P2yjlq{#!&`DDgE4yspnUP0_37BZF^a;~~ru#~W)Fz41|FjVa40glToY zHp&{y%FY(BDU9@r7dq)(ke{|&wu5H2pU;*J*^Zjo18};$#?e@U_AQFSW(WOW*;P}b zK}2=LRw+%B&*Ozj$+KlHU^ctCV2EAUUIndZ|l@uF5r>2^QBnX?d z+)*^rqdr0u_YH{fM4>ge6U2Z-VTbNnfz@@7Q3o2aUvH7dv!BU@zJjhRRfl*iqA^J6 zq)k%iEoxuL(gVI=Y1-i;cchl2ew9i>`U%C{eE1g~E`oa#1iD&~XJoLZ9kxQT4LTJN zI^D8tS9mG{p2AQ!J3{u9J2uAAw~8v@CHnuDeeC~vID@7&9~q+@{^%1G7-__@VL8SB zK|iH9mme49v@Sl%`DjAag>O?!f(Et@p6STB-y5qb`U@>NAXFnpVng@uwwf+yQD)P| zJxqoqI)Q(_#p;DZ)Sh}_{AM|T4h=v6&9IS}CQC$YHk%Op==bnTK75par>&;uL6G*V zcE!@bV;YhwOmg5phWx>Fbi;WdZcySa5Zpkax7$PzAsWr>6F-pJEC>U`QV$!6uCm0#jo4QhCRB~UkeTlS_rF$=TH=0r+u&Q?nwnb)4kC44 zhi2>Fpbn&tqv=;Y9n+M-FX@aFVEK`ku~YsO`P?-%Qyy#^oYZ6O8>txG`wbVud}&SZ z#A<48ZglwSVVU-;B^OdnbB7D_95~oS{(S{bj{*@g5=1Ky2_rFD`hm!!h&u>0j6XRv z5^i@u>eNVK-++ePKCQ84D0MA$D|P#9{HfggW1pxd2+k|l5QM*{mh_5AH60&C11)Z& z)rB!|3=OoG>zNBp{l^NOINk6KR*@kan267MvuQ8FXpK|HZe6&mY2Z3Nw9!4qq-uA7dz=&M=66w|fW zgsWOzUt(35K$t@9TC9ks3r?Iad##oG0dmvggf&cy30e{ybO+X0MZN`#ioCg6QUHtm zXA7sasr&GxdP{)3t45= z)f_r#p;tt+3A#Sfnx4!Td>wRMR$67Ep@ho(oiE93;sO#yD>q(bTunZHCUW%49?eY; zJ`(zH0h9BsG84h08d|Q9We8+inU*dRLOI>y6;{EIAwUKDEXRAOWx~g%q@}_DtgH3|uBDm|@c93t3uSkc~)yEOK!v4r~;ug2H811)GtP zDi{N9)+*toRu^HzZ6kC4SYkFMtfAa}ORahLEMSD+vn6_*A`h7TtP=eQRuG%nvm6>b7B;}`@`kC@~3OP=? zSsz;!ybc~!&|!hu)V4^Njf*cZ^n~@n{*>9un z(te@DkxO5Ix*QM^xifiY(~Sc{lmoXf4^zQGp#`@CQ1n48O&Z4ms(i;-W7KHAi2+R> z%!tEX>xTqKhoEmhG?R-HG~((Bnu@pT>b~`N(tJ~iH$8iR2OSZ@8o9E~^cX+fekRl7 z{QFzzJrD3XoA==3 z*#kdf8cWE<*4~doca`=qs^w0cN=sZL;E&XJ4sQFAwWr;24d(X4W0QXpx_c#|gfjdb zT4v5zW>8+tbR39FeV9}4-Hq)?LXQb9UTq-08ZTC4@%fu$qCFlk=lFv)kG+$@`%UUD zPat2ChyRSHm)bkQWqXeaiCRM#9vj1Y;VyeD9O#>=t%w;3`y3d@-cD^+FdC#~T71W% z71slcK7kV|$2<)9=Y=S($B7Tj0h6nS_ zgnlRSCi?mf2j4pd8qH9uGN-QYn=oj30qG9NMZYi@hT`Z8o~v`sq$TFty28w6q}P(c zQ^?&5!a#1$2WC_3MIp(78;lG~e#P3Z3X*$&6>^8rv8>Y9DE^MWFh6?AejpC%4HO4M zB|@m&!o$Ta8Y6h2f#Lvr-UD2rt^u#Inb-%syvqVk*+(kCu`Fo-sgl1#jjRn^KNk5oTv^NA0HUiYtB&muR%u{c)KZycO6w z2Tg>_2LVAR8fm)2k|Il;UcwTi4t3IrC*kgTJZgysyvnBH5B5B2$T;fs{F2*`*W>0g`3=P5m4*36x%f7+w z<3D=C6GMv^{sy$ZvY`-n`27$;KD;5+w)Fwl1vLr9A1!qmms32mHsO3|@X_9JAC~rZ z_^7mZ_@YwNwo2?!ap~`2)U6UCoN19RRbk{=mC$`eJ!?C)M(g^Zb$!IgsA&`X+R&PY zg0Jxr-R*g_rj?Cxrg~%15xl(LS!77i!&=~(Uxz;>7=vs4I z7gxhVVTScCGY$xjO7Nri}yHxVmM29*KB(B zr;w?2c7aFe(TU@43VimJcW`V;ZqDGxx>hx}f?Cz2Icof*>MA#Le1z)arvdRf9^x}p z_bKPtejoZ|JsDc%49FNg#GUp$TIEpiG#=ts@RT#StD*l7XCu+w5_&uPp|R=xoTG0E zsaaB3DWywcg?m9N-EftH>(2kq&FQUJG0VOrDa70mVs7G8d!7_x;AOap6Tox74W}uk zj=wEz;)>tLXmndRIhn>$&2el5oYNHF&(_rZ)m67+8{+BjnZ{yY@RWFJBga!ljIpE> zVrdX!=@-OO*F~khW5A2R-$Pt^{txH2^UDt!2koBMIOwlu^S?ehq+dz9Yj~@92c-t} zo`dgj(eK=w7o_F1*qycj@rRuG5mhZrH}46{wA=_Z&^r$Vp6d@{%Wi|e>BIw}03WSE z%4MEw&<^~$WBf}S)UU)XUL!`#o4+cfw~;J-EVOWsgiwu>MqGgc_dXVGYjw$Qnu!|< zqn&*fG%AJdeTr>j?gN+;@*Gdn&z}jcxYt=~AGh>P%qP!<-r7dDBc*RYXB@&M!i-#A zh-CvK$Gs4GaPDtG#lFGP?U5YlSkUzL$bV7r&-iFr*09`&&x#do-}kl9Uf(5Bb#xIo zV>GV!gb1b6=oPs#y}1k*PcnFZc1EDv$C!L%R>y5a6xQYzSV@Jx6at(+L&={@UxRz# zm#_5NzYRbNNU6yC`9EUFN+6#y>u7O*?VMmK?(otS3w`#bV4)9RNXO^*+9Vti%#6X! z%JrEU|BUkUjLg8?j53F!gj)8o@M5#z&C!O~Xcjtiy+NEa3lUCTKzzu)(tg0KY7YcQ zITqpq-}?+{3FLk0lWLDvOm85NFjD$jlAo81&{4?;Xm+g-(X-(w;ZWYupVZlcmCJ7RKn>SRrNA*yCYgz=x=DOjaYv0G^|k2hIAT<^8}?agU|oZ~ z>6{^zyF3d61ZRj+6(rp%-gcC#pj=u|v>MOBf>k!WqdR_D*v--4*VDeuN?RfGXm#dN z`1Dqm1t-~#h8BVAVH%xfp5z7A+*%k|<7e%%d$tX<^qS>yslle_j)nlOW6?}J=Y_uL z)pDqZIItZ)H(IE6a9nc~wL*<&1^_2&yb>Rk$@Pl4*RNyK(`Q*1(!hgn;z3B}oo!_3 z;dLJt&%?@9#>S1X8H+MUbZol&1j~B?a`D!@_wvUp15igtYnIJ}dPV!6VL84=j#sTY zX1G~LjrmblU!=JhdN{3s>>TNyY_iG4;Ow*z>D44IzLy^%ghZFd$>B3hxcZWv#z3Rv)lLl6wlj zN4mg}UO={6g|EB9;ts&xAXOI<@k2=_6%GUkTykTZIXhGYA>kx_v)=RuWBUSm1|`?< zfc+c(>bwo>Npp9@1G-Mhr|T474?}O~&>47YRoD+aY}hwF!QS;ceyxOOPAT_~UN-E5 z-eC6tdmf%b!CovafF#8$e84K5PD4}9IlYNZ&MaTBQ@~z@CuT{p5l=f7vwHf2eQBDR z1S@R6rZ#MM9oQ4V-jQuKrR!|Vy%7M`->>1wTs$2}iVroj$+&Xm&Lskvb02& zssAg>us(KK=5|JwV-s=q-~Y-osh?ezJ6(|FHDuX`MZBG1tS;Xs*ku{r4W98rmSM=U zrJJFdGuE^DTk%2Sk#2@42ZI)=u;;C@!RUz(eLclLX@gO0Xd7%W0?YFhD-{fj=E^K! z37+CrVE1z;_>*2e4b7b|!IyLwW_(WrE_R{W54FXfjtBO1Jj8uUcB+yCR_!kCRxqlv z%pH3=?&3CJTNXp5hu*5v6s}%c&ploE~!12 z(9b6X%pnYGCu6}~x?8Z;V$+fDJg*DZ%nozX43%u0(hi%W&e$Av7P~3-P#Y6~g*%JU z3ihC-2Mh;T-AHT?@D6Y2?0f-LrdJ?`3kH4!E4Hm%Y)F>?eD(0Io95dH6fYHpho;JE zCwSONbWqev9tM`@B$^SrlAPpWUGobK(VHSTj5blbnm6jBVw_a$q4vN&aMt0nUX=de;qEVlez^kVJok%B|RM%X1Jv zQnFK(S-=t;#B2qlD#L+s4&wX3>hebTlcT*@dr2E{)x8XH&L^PXWpRS3LvKTz)US%r zOL4Nk!QY_~`W>B)4qqFfOpMFjGc4qP<1D08ibAGcx5x&2SY$U(PQ?+UOxvE{Esp?u z;xOyl1OsL z^z|e2;xWH^BOPbPiIJ?><^L}mgKt{uT4)c zDJ{ek#jQMb=3M$@vP6xCVht}V-Px}pBdIaz>dM8@XMz!Gya0R0vOc=-BN_b-ofw@fb63M_)(svcDlxrCEC9xTDq}nfpkMhvK&ovgWh@X7zCF zn}Jn%evBd1bUMj!RO>is9MafT^!GtD9UE^Zo3Ug@h9dej`68WmXiDyRa#|O|imoOh?bipIHDeg3>e+w`h2fR}RSOEcETO93GPz?Qx#vcokynNahKw zK!0S&I3U6GdeLwoaxbE)q+UdcU~x!C&*}0I(hEXUNN(cr09w0lNG-LNUYm+xCmdLz zw4(N>j}njy0`j_53Ogdv9_5VX2G)nnF1mh(umg}UrBTaQw*3YCxenQX#1jdAS??Q6 z9MTPaxz8XtAl=X`Xd?)XyV1-(I@uB!qH&zvtka^vHNdme4gTDU@n#cAHw<#-z8{O3 zYd8jzuR*wvFfJ=yw|8v&?rbaleD{rrX**Q!O`GL z0hsL)YLrU8eT)Q##8GvN13f5@T4l$hRymC_n~qE}bxJb34L+9H``F`*=PsrBjY;9D}7{hhrS9)-wTm>lZ@W(rhUw^~Z0OnaJ55 zLwY#<1`+A^ob*NDe~=iz)i8lvSYe1wp9y1Wo6=UIznk4I2N`XRDU>I-l7iFLm_Tv4 zl@y!?-x%Oo`G!ooy2+PXNp6jqgQOP94_h50Dy{JvFtkuPT`(0SpoOxyib=rg^0EB- z7RF!Gp;X)^bLkU(}mRr!f_*0 z@w~FmP^t~NmGZxHSEb;waDxHw9M*%HxzR958xpI?%brk5YlqVG;63`(P#EIfwfgz(IXk}>q(Uter*3f zLplQag_Hu($w(U@XK|7%eV4bbKVqxMBfiBjbcX&~x7FLZAv9w0>%A+LB5bG%XAvev zUOjm^!l-TdMOZ68ZN z?{yF%pQDvt1!17Xcn~8#H%u}h1|HbP%4~R6ik~8_C03>bgItkqtV{-mSZPKYe_;rq z0h3PyCi)A*9F7|R1L!V2$=_pe;S!Y8Z`+YFD5;`723M2Q4jL?}{qdB(+i+RSUF>I@ z^Q@dQLDo^rE$nADnf4myX}Pvw^xTJvg@72b&u}vQZeQ$R$fM`fW2>Z*)diy`jnj4r zia+{dZ2#I|cJOEgNgBn`GQm&>xZo;ny%|Z=e{cX3B@&}8$UyOlN=iFCfI~VvzM+?Xh@}~2A`qN?QtbE z>~R_zvZZopoI#QFZE`w_lR47Q1z8=W(D)i6a%k+Nr zJkHbLb!?ONk2#;6qu^QaAB1gp6bq`s$0$CGVfj)VU_}26(f4EVkX4LPeGQ7G zaj>G;(A$GFo@8{=T6|hg-AjE+iRH5gb@bf5feq))<7gjyxXj>3rXDkRb4`$*d(03O z&G#|${?f3X>AQOP(u zoL@0Ae~v*hlC1n|X!h_U4d+K7Vj0d&NR0nuP*)Oo!tmt)c#O@Dvd11{etgL_YG1=S zwtvcTJExmQ$~$pER8DppjZ+ zjZ}%GUZsTO)s(f&t1i9qN`e&rGb)H2y@;My+Y8@2Tr_m%9)hU5Xz+KOX@Dzpjt&SO z>QK@6F(Nc?F!fK7+Mh#IIP<6E=X&z8KP9uMKYv7FG(P*HEZK57KB%Hxr^|EmG#Dubvu_hCgt=f0@k_~h}jVXBtfBjDq=D~4;0xIh#+ ztqLnfUl18?^;c_j#pnrqOBGg(&IXJuRfaG}u9i2OuKsE0?!*=8&BXVPVJ!Dn5A2NJ zFqs}N0)9zw5IRr$8mwMgii;*WqkDsC6rK8n}?)b{^p23H6Zrc;T`r~}b zxv*aTrhyL)?>agD&>d}19@ZTl{4=N z@E!!F1uKNgwD1maXrY!PKghUVE8K5}V6cj@&`hbsY~H z7_I)o#HV1w1f$Jg=o*I`YH!@1wR||XlVE>Chn!g35d1w5qFZ&uOw(XsL(k@#q9Jp5GW9!whye?g| zx_*e5Nt1_9#;^6UrQwIuI~cp_`=RTjr6k{UFm?zUmZ2%2BOq4h#7aR=8{7JgM_1eN zDXH_*#?4LUp{Q|4zk~ll1Jd?4#p3^-=Tpj;A$=P!weQpkXcbcJ)#%SJMM-s%jLB6a z>tS%i`|8-J++L#^fE7u`*;!-JWoQ=Wo9MsR#{cV<@&Ced{{K-!jV^VjkgNPw%YVC7PG8p8@^M|egQbVwe6&%^3;0|qK+6l* ztrVc+1?*P}Kr^X;d^x>Q$AABo@_QZs{ZZ*_qp@*P2K9-UL|iNPiO=EA$qI&>0k*a4 z(N7){3P%EC`6!Al0Venq4guE0WNb+mp+^iU(`1|$3WeJz`f93|reW#5HaIB$g`Uz? z6TE9bD0b0o?5T&%?68-kwZ%94*^{Q;Z$Dv7%JNpB8f~rR%$tdE;!szJI3hJe`c*pUdUYZhiZ+%Fv5o!6iCmxvBrK8cN16)s@HyLsu zC^%Zlv|7)WsZf5rjBV$e6kRU8DOIOWnc8vFc>ZY(WR5f&&(eW1(gaBOGsd>5)MJ&# zV82WFn%b5`%@pdgf+q8C!w)gXJ)2`^*{vbR7xIWvI9+ihL zv>6Bc-ixBwpESQ5yq4E`9f+3AL5Io6??B2C@X2?_JdT>p+{46AemRaje@X_NtQXvj zBZq;EmeyfOOJGxu>;v+BKjUy=ENh+}fBTV6UD7uX1D^5KFr8 zD0#KjBk*g0o&-y&z43Ll=HX#Qd~L~N@@lHFd7CtxX`5lp7BtP!ePkHRee;^)j5ld^ zzxJ^Ma;n=R3ImqX;&AV>wb)=ti^IKfLoMJ574agxmY3^Xv^6s!klwcAE{{Ya^vX0w z=>mgMt(-ybz^Q$!&*6kQ-c&5@P6#{Ae-;f@?%~}tjj zHnB5^gIAE7?~bgI>jl%omK!gyFTY$Lj@Sb)8=${``7D97>kDNi^<>_4r&2 zY2#XX*DDrdF}vK+wFGZSp8~g=fxhd_;_X^Bj=YQ;c1Oj4;eMPcbGZvbL(m;C#H)DLvVx ztO8ye_-Pj|-JfFoyuy!X)4H9RT`T-}HeSNeH*MrX9VIUs=W2!8H4zQIWPCf&5|3q! zTsy1d**k}Sp)>3dX%}L_ZBzwu+;MX+kRkcreh3jhg&7apPp`ffep}BLwY+5m40|Z>}Tt({FI6lfZ;WC zHwB~O@Jjm9dS6>7U|BOzTn7|~Gsql{8OG&|lI-2>z?sGX#>4{9Pi7*CG80LZnaI%C zWEz2caUK#fYrnBIy%XI@d46<|4K%jHRvSJ zTebT~&^y#SNZp=g98C=Jn9<0m6=8=&Vu~kDo$E0dE-lV7Zmsy^aH3yw#UEqc9lbM@ z3w2D*Hcr#}?5TzhF8x;j`ckzy#$kcQ2#i<;bg`U-|5aU}U_uymp}3>s>IgMB6X|!1 ziRs^^`;ra|aLvM*NNc8m90Brxzsjag8Au+GMx2S~IPwLMOPsC5MC7pp36=WJ8jkbm z>vi*Oo~kJfKo1mOcU>>Tw6t=X)4e13Zw~O!h^D8lX7H~-bX+7~s9Nsm{)VxWpWYgR zMP!J;PwokfaqN1>ILBAtpbFl3A%?VAjmb&LDABMq(KW-9jY=67(VjicT*?t_GZl>Z zn90w*eHqwZEBM$3VFA{HJ8oNzJ3wz*W&H*=2OYvOXX`b#`_Q^lTu~0NOpWa?1*76p zfyH5yIIxTFqPW&5jvj==NS!t%ArVql+UNy28lj4OzEKs7!4V zAH9z?aX&+)>otW>;auC4wm|SV2tN9e9#_?T)>AMjZIfo=8ezOpd7GNjjbG1W?UlP!~qjDwg`$#F z9sR&q$Hm2~9~e6@u2^vk2YO&9nH)j2W6MwoWf7C<+(^Ceo6yS=7H9G!3pItafGp-) zx7bE4P2tNx=1YCElG`S0Y|FkxM2OQ?p<<6HG=rXJaoVakKAZNLg}ZQR#fQdbl64hK zvMPX?_v>Wa~ zY3sQnKLalrrZKt{xn03jirfs0okyr$%N5Bsc#tAD4qI#d*UD^<_IN6@1rSeV#slHX zl!kn03?yp*zv{6pu($ueRADZ3tybYWq?rnrLm(Aq*2Rj|4aVU#;@b^p^tPfBY-T*9 zwUJ9O6`q3%*8|JZ+Qusw>k@&bYHg!|J>I~(MADuk@gqE6QJ3{(1JgsIbd8+o9B$+_ zK5EF_&JRFd;iqX|=N@<*$V<|cLSq~0=tg5u<(f-$G0k<}FJqv^g-eewTAE4iH-Uk- z{r;u;dZKEz`Z^)a)MtV~>eD0io@6(6m0~v=yQp-?9~AxIKum}8Owb{)9Gy+8U`&U= zQgt>bxG_oUT}#@%*-b;o+0Di(I==uOGme-khtb!wWdUzR+xZUAmrEn09jmYfGWIj0 zk8e+;hp25E;U zPiji9Bb`|swGn!q%Q_XwWH;)4*C0KeJ%rVuE)lJffQ*CQGVpi?z1eu6$!Nz_mJVJ* zWmdx`vrA<|6-=eFXMrugYpx~r-2s)=M9XMv7F5>Ov1y0#jP}3iZ98s9t+$Oxd+Kcs z5a=!0vTq+cJ}jQ{*3-Y#p9K9ibKLpNC~5;Y3jachT2!o7VwsP(5^n(^CGJIZ{J3j! zJx3#lF$;S^Sj=vL2V=$MAs^ezusmbmXEuxX(#G6#KarpDGpU1Tb-IE}3Vu&i5YwWR8MV4YA{hgOob z-ea^eLKk2tn)tPAain>+OKko;dvK%-Y@<9y$nr*cE+S-a=bH*W@_1ePZa;XIgtRJJ zUyo@rAU{Y`uxv57n0gUyVG|&Me7J6Q0KbVt+K&y_f!NqiIqCozc)&Qg8!TO*_K0GN z*CoaPPn_cQH5KtZEGJ-PAj&?_qqbD7e|sM(;-Il9`JhJ$8B_w|nF=^fry!n@amUPq z#=g41d<~-y(+DP0!sIEVW;$>gbdal@^>$Ah`6(CMA26sUNdoI48M3TLYyV742BE$4d9cGKnlTxK_PoV{9qEP0 z9(v&}(l@@wRDri83=~<$xh&xtT#_lgY2w1AG2a+(1x7!1QYT4OM?b|DN|DHR@dV$4 zdeM~GsA#L(SR?-Kl)z4r#-+))^d1`vrKlMr^+98irpfSDc+Q-3!q`?yKWa3(6$s^B zg2Fn0wM>C_0iF-{JEXC-0p?QRdL9xb0NdVeXf5g5QQlz|&|qElTf9o4zS7PWNDs(N zeUxT%xpFMH3%9mFZrtf)z3(=p=keIggtYK6(vu2}9V}n%LU)O{kCmw!Rx(JDF%@w( zN;h=j(&a+Li3P_oN`F_*v`Hj(cuti zjHahn=x<6AQwecTR$VD*!7zV(#Y9$J3C9X(j#r5$F956Bu6LN!;w0}N?KIXvb!{E< zP8wtXmHtLQ^3>mOq}BQxfHd^S2xwP#KK}>3l?A@${I4pz2(5an>;y1US@72oNM%+w zZO{&j#ZG*0eB>w0{@dv|`HK;+%E#f+qxU)ETz=94KD2R(KDL2pUrj7FE^Dx<88-r@ z78EJhdiY^Cc>s2k2iQjOYj)Q)C|R=>*YK6wp}5xYJSH(QT3G2>c=~x`hkhO<4bo#~ z)gLpf{EWwmH<=4B zdrFM6sy4#!*ZKJODh|yy8Lp)`(tb7G)isn$EvL_UWYd9~{^O(lBgREj!T)*al<0rN zeW#Rp+4z)j0mA&t#u>sv2>McEq3{lbv!%ut9wecg|QEu_ySq7qf^bmR({9!cF5NcJk*g(OirEl4lCSJiN^$KYf@mP#)EH7?QJ3LyN zchzX`=KbT@czszKRPo2`fcMafcsi!B!n{%H*Mc?Plfd%<19s^jLeNYS9b zoay?fSouv2MkBU&P{h@95TbC@d=0@!Kl}*uB(JAL;%gY)k=V&c8XBEZW-1VT?FMJJ zRHZXgfFuD~g<7O^yQ#6{cilLI4)nO`TDw5bgw;nW*?ODb-^`iZFCOrP4^29*iF(`P zGIq`C`W-n_EUszvwg=HD{rYK7;4Cf+vg4+(~!gZKrr zIq`LOjB|phjuMnz52Rmw$9SHR-ii`2br;h(-HY@?pbH{>@NK8Gya{`4AVJyGa-*EuP%Iwp8}O*gdf1FQ=q%gLe3HTd*DeT%@=Dft$IqO?RBq$ueV< zZ(9gGr0Sm}*9@d>G_XT6AXWbcS-p9cj9IAC8(k`pHG|GBx?d5`{>#Oy6Lot>OP~F1 zoENwiPdX^LfZUD_AK)Te%K8Vd{|N4|7h?ts4$z`JAX_z%ipQYuQu#AcMfvCvxrL9vHQl=S2ML0!e2z)>EmDCcaOb|Zp_|BzW^+z zrpXrG1ws*CMyoHT0{aFR{i!UJW0UN8PuF(58fH467ks}qx|``EgIePB^Y|+|46|qE>p5jxQM(1>zSei{KzrA zo+&Iq-}iT?^gg~p-s}#B-F}4S2UJ^0vJ{bOb%p+aZG-MMR1#{u?+-6M5&-HDWRuT&6%C=SYt7Lg%yoOPAO}uX`SSs zVloN|sA5gAsfpvo6w}i};9tnz;wS3|DW@E}I+>d5^f12Ne|fT$kZ3BD_H{8ii2+tM z16tw68D__!fieS{0V_sPEJn}d42TED7!cfzGoXNCNMe8_{+>*WoGVkhngh2k${e@? zLCt|;q``qsWPZ=k+--gjTxEX3$^6Zv((b0?f%*%K19mqDNMsx!fpH)M)u}l!80p0! z=I93aPZX$w;ja=3SQ!PNOGbesJ&6Jn&La%Ku)zA)4==bWumH`0s(DG(~5fE5%dP$+OQohWeRoJ@hk&wv6NR59`;Q&&fiex@@*%qK|F;{JK6 zttuk60E|5p^U4NXOC4xRj#=`gOxR(v0N2(JG-U`=A?OF0GKfT0|J`YhNrOz^X_FW+ zR9#4QsEuKox-J3*bBsUa$pq2^V+67e;RLd~2$Wr>CXmZwR#;3;pn|h9fsQ~>6DSX9 z>O|ff#`_SD$e6u9;eCh)t|AfPl4ThBkl%l1{Gpm4(bRx#1(*ZvU)Sb>*G?ihm#JM>0 z6URJ;okC#X3_eJTA{Dy$kuG5j>}4_tB(R-K98=TfgVQoy-i4s1%R5LDT`ZdxVJZc$ z)>wg+3_ISqLKzw7{Z7Xh(C^rPbV~owEXJEaRIBEVj@n1O`THl%o5Ki6ygMEg%EzA3 zDUQbz5f|#iP}MNxWR&UtlbbSKPz?1se#pQm^9KyeDB}d8rpyDR8D*|QsDv^Fpp4a% zGE;tFlsPZt{@`?gEpvVSn3;P@2rN!X`(EW%_83||MT1~vSQINq<)LLOuzatfWfL$y zw7iC%0j72hEoABf#ndForY2Es>M7sLrXB}DZR!l9Ew5u}VFgug;sW(^w93SU%R|fS zF!5W3%*0P>4l{A_DNhssj5ITGAq46gRv;31qKSLT;l+_G>Kgtma7wL_o!PnGDYubC`eh^KpDbO!WojVVGflCM9&=6Y83*imQ^z#XngLx;$_z+`pk_b^q%SVy46v&$t&9t- zcoj2L450j+0rM7t0VBU-45+*@%>KJic-nsl(#-z35Xk;h5e8IZe;!+u%l02@CHo&f z?v#R%o!S5I@7(skk7khlKSzegHq+cD5^TfPA)c(A%icrD(Pb`WT=CyJMKEluYY%)X`i0 z3)6T<-(>|izeh*E821hH7Z^nM+JSdCW>-g-bAe^8k~NOfvY$`IOo7itHFWijxr8BsacE#2fp=W!7ij33${TZ z7QBM7+?xe&V*q0TLLoklx0X8kqeq-lHRNOjczo1N04Lf&1lWTNBkdr-N-%*FATpP| zbd(9OjWTAs39uRIsyje{RS>d5_~XXdd;D?Z6Z8cjfGbqE@u8_uE5xFX#GR(sCGjKE zSRoKM@X1G};ez>y(-HKs>1UY(ojS@-7`c^j;4l1$bpdDao>LwMu5rwR1Es+DFz^ZQ z0^CF(<-q6{UXn+A_Ce!{BmRzWWFq83P!nMt(v~gg1Xw{TXIDA_Z(JdOjLXBo77*Z@ zubk39G=~wufa=sEeI&JuM*8XyhyZ61Dm{?^P$qxG*hbwzQ`9#V*%=E)eeGt!$gepI zqL6{H;4w^984IdYMimRHAkA2yflvtx3cvzo^q0VbYf_(2O}`2`hZz%o6JEg25Flm< zYk`0S-5lS2X4lKRT5&q5l`033heZ*8{iDdV}}FVcM0B>S23bM-BqXyosu?jAX~u}>ArK?lA_l625q8!kK&gxo>HCQhZ{|Ct?+~~V zBO>;F>1M=kG=%zv>Bu16JYudV)jnt%(qt$IQrYnE0%cbX595$ta}d45FbI|K!oEcn zEwJIC=X%pv$L>5+D8Bxfhe0796IH=G^Z2}S+4|bKk~lZCo^;`RQ!U3UhfR}Zj`U1% z-1wRvCBX%cfN=_x0SxD8xW6|%0oXdPfN=~k#*b=8IX?>2{CJWf)ck0HMlycHLs0W0 z7HJwXr0j3;ED3UWkl^2v3PKnw)*kd^#rsGzR#+hrD~2E{ zdLk=&rf^mqKTfRpWWQ7T3t=8(MezYQD=wfJ#EO;3AWhyew4U_l39up?B&m!Q?^1RZ zD;6QmSTP$yC9JT56-vj3Qc#k!9VPy&@uZN7a<%V#D|OvcK;o6 ze=+DZ`U_@fRq!|;YG54cQp?p}ya^2XJc7sBz!slD^nk9yuBJlex>pmS8yd%mkODzX zgr|{avBRLLu8zX4?hsU5@W53a1>wA-c;gpz6zO{yA*?X}qU;nEAqZiF*t6G@5T7E= z2(cLg5#lApNtF46)NzVNdpQ!SY$dc4BqW@U{bP~FAWJ+*O0K`GB>eD zfcOe-jF~+)+GXOY9Pglof{&}?A&RR%g)v( z*x3VD*_m)|=Yl_A=bpQq(l|Lfu`)Z)`bZ93n3Xp=JgvM2X=Y^!0$Di&k&w5QsX&jx z!2Tz>{imNhr7}cw%+#g3+@}5wjUZF6M+Rog9ArW$I-}GgHrlP>HDvU}_~E zaPS$(5EROu4Y%CF1X5?DVDDr{)4xnkLHGm7CihH{LJ8qZlfvTSOJZI*hlKYLIy5gy zhuZvzYgzY9*M#K|Cf&yr(pcQBf3ZAoz2yNXjz=uf4!UCfKq(Gcl%vX)9P@}JngV0Q zah8ENQ`ND=6KtfW&E1_cZLUF3)8;p%6CNU>L?H#0(Zw5A=py5sE@vKsEE!~={j zAAjnm%X&0|=#qg9j4qvEimKJkwQA4>6bTx~PUwadJ7Fi! z-`t=0f;Y9DdF=UTfSHXY92aNH>7-VLAaStdkogKF6 z^@ZD~DXr$qN84q-tb(BC%QB=V1)CXP>`&l}2d?4^;hZlKRm{f&_ikl;sjMlCFJY)k z&6g_FCh(aHAGZlhTMb8AyDS|84Ea2whT6cGr90OCf3S4PC$go_LQq@!d!*Tba%&VH zP(T~&6D;n5t1M19w|Hz_SiCHkS=_4h5F||e(%nP!LzQZacc->d50MIiEM5h%+Y>Dg zWl|5ZE1E1m0#$v4pnzF?>1MaZZJW8pdm{szb!-iLGK+VjD=Ld8Bh4({27BF4qYGA46(u#u+dBa1GK^ zl7FJvDNN<5+LEEYIZ=2T`G>YQcNM5{c=GKeH_k|n%Ug$+XBbZ_X&mpDk)1crOpP0a z>}$~Dvc@g?(A~KCAM(a^U56%F%#CzDkAO%;zu}~)o5|)ce7;qZj=U6eHLXv!lBUbP z(zR5yGz~v)*wJhd{LoUn|1w9fG;;%8-09U$DH>x)C2h2`v16J1+_|qSwQ&-%??Ug$ z+W65LcN;%k!`qmS3~1v~N8KLg=d?aG*P@|xu8*{`r+J^x1>|xit2y52W%kkfyz2rt z^oG3$t#&#}dYc`bNE1E{&Pko_yTI5juo zvz6}V?pVp2I|&)2qBD3vjUH)!)?poJexMbuufQU#!RFD}152vvBr`5=D7E0)a;MY= z{n-;+&?&`X8E!@dJ{LKU!$DZ(dp~ej{>2Bp@|Tf;RqjCL&*+3ZNTc2;hc(08A0I$p zuKEcs5kFskpY^qIQgo(yyzngUVt%H1n$QQAh3Cw_3AG?xea;-E9|!+xv@X_Bb+j4N zwKJAu;&zO=nO10q3^C)(ErTaW{1N?jTwtygJFmDhjqGH)CwY!mcMYsUFj?4SYg%@R(aQm zn5FJ|>!LoY_m_83FPk=5Gz0bSL319?FwYQnF2S;%SIwQYLI!?*aHcs--vzyxe}=(v zcBVPfFF4i4)p;kbs#~405x?5pbrd5D)v?BkI@a#)*+7~#$NV253sqm9gL|84!{VJB zvq>A%1UXBDx|``6iGK;!kCla z%HzQGB7Ib=cvMG|1=D}fERCmUx~Ed48}FLKve*x*x32Jm2>AzNlpkzOE*pizr>L;% z^0jn+&F=qsO4(5PTA+Mwu=2YBX=VL!Egh8Bywbr|nxnB5qjqN>PRpU~^q&^GGb@grF)3mhw;u3R*te+S0n~GQ35!R_JPHx93 z`IUHRHE`C4t|cXw0D!sKg*re)pxTmseUISU%h6goNvY04{y!4`1ELbNaqY%m?O9b=XL&ZR0W0Y67#L8IAU5xia*vn4u>!T>QY?K_Io% zSpgvd!oU^gwn-ROt?E&AOe%9ntASc5d*c`AqR?uqdQja7j18*iR`5a9O5XUG%D(pw zn7IgbU zu>i>fa%hdY15wuFG2KAJ&=}?)9(X=&UYJx7&qjW^UF@^Y&#g7Ls8DEfh-+-~D3onZ z<71l#o`r_Bf)BX8Z?5T60~e&5scEs& zmUZSqhMn`U(Mc=rZtSb+8>rRnwrDj|7Tn}2h)34hEO-c`lLDZWSRhmR7)Q2YV;l(= z+C0;mEaQjkd~0hPl=S4uE(5BTbKsBR3)i@N>@b%EJpI;Q1byPSo)2YoaD!El%Z|w zHHGtl9HVe4Tv|II#iwdE(%+!1w5dZ2y`0=&ZdAciZ0{3~LOd)&rvbC$IK1exmPaAf zBAi#AK;SfUK^%`4>f>Ga+11wWxGXYzZi@xP)G;;{T{?obU zwxMHDn*Z#!HuN!8IPREkX=C`qf6O%Gf0sFu;7ug4{xyV9J+O(6Y zEu06v^x+}r6^>*B>A`o#ZpBvO;8&3DBAZD{-(+qh#cnk}2;Vl>$v!S!Bws4R!_$>F zoj6{>Tt(ZB)vpRdiv^gAHh@zLRJfMRNZXOU@N66w_>cEMpA(nLx1068+uwA`M}|pN z-t40H-H3Dn>sxSWgIOQ62I()+$Z>ca?`=1CO-iOI=vQ#Afc$LsDh$tzX~nq$nJ{pw z);0|o%g2HuU@-h-U?U6r){?H+5fp`?#k6HRXoopp8`J@n(3x`w@&ELv=xY~1J)t`> zTQvj1$ennu9RlI(PVY%Sj+KJ9T!M#a;Pg!KEB#!(&_l4zt$6-W zc@Nmdm_D_n!d*~&P1Hx@-#4Zq&7@d|x$ZwJ6rBz(m-!G8ny;0~o zT(%>rbVe<4gXoM5Qj0Gt(WufRd23GTk-Ty0kz{o}GW2Lr<4x2=>h!NvjUgc;6Mc|_ z9Zz0I$b^`1CNWH^7TGn}F=)5BCQj#~&WJkm%usMO)aDEIFzgP#A{Pft2(@X{YAmUN zKnGs{2RAqFL1$DK8eECP=PvFsZ`G6b3fx@v#BE4)0KFB+UKW96od;IX$104Ak z$Y1>MRv9@5q~9U)0ODbR+R-!U1Eph9h;JVFY&wf#QboK7$G^!fTU0V6+EMMW`M6Ga zJqt|u+B{onG`<|9>_k*PqZ=NWm+h1`!Qo41O6Dk2tn|k><`F*QF_$Ern>I4SSHk79 z6wc7MQ5I)A9d8{mkJHf{Q-S}wHjew>B1L^ffgzm^3aN|Ey{@gx97f9m!xzAEfMwRT zrE-kVf20D7t7|g@Tk#!q9D!hx&dmM(J9Aqf3oFiu0}bMMS8^>#Qx*kPF`SAl0n-m@ zY!MveMao_h3hZQTdYClq6r#USluJu4vQC+sRe^%+jTVY!{sv9q+fwnu4xx_Yr_7~3 zq#j)08>qR+Hc)esZJ_2N+d$353tw3hg4x$WwT0H#oYLP?{*g{~eCI)Ym483!q&z+V zd6}I}Dh(g}tlsw(q%G{g%HWMW$7CQ$>`=>EGBOrOBEINGLw)JS&XVQhN=u~#}J=PksqC~;Du+<1O%P1;DzVmb50Dy%AX77=0ZLmv2I*2x2#aG zfeKiXTA_esM0uqvD&pz*%#>X4g%N=XVaNGx9(mO%jY1SGUy{dKEA-CJDWTROwEol5 zTw42GXPgwRE&K?-SP5pzzhK7<0bUAtt~BKg+i|@BiEV874W?NPTz&({S}EgPb%XR% zk$F6E({9)&;3GP^!b_PtTc6h%k?e*EIQAhG4>fT*TX&A}#|QyfiPqK`*vw*ZGZIas z!zXtZL+!*BYN)FDvi}oGUm~HSe2X(Rw$(G7(r`ZbV00$rJs^YG02MAHi+~J}BZ8{0 zz~$JdYT|T-_7-@|O|57&)|+;(h*NKhZPE`|>r?@Q+?%qtJ?z_{#&f8Udeh&hvq6b) zc~Bzp#N)p0gs#Z)SeF*LEcO{6AsLB-znRZ-Esn+cV27Zc^*USGOj(OYESAgxmZ`Jd z;TYFqD%b1{U?;zP2Ir3aj=`uFlt;&cR=sS-$({eGN(@B&ROAv(VOOXIo9O?gAafiDBhwtDwS*SHZW)~OgeWR9ojv#f;9N}I%)8~x0I$q(bAr{El&-0 z0^+Gb6Ofa)pg~q@B^va`6%ER`qxWB=!L*nD4;oxI&0B-Zfsh7+Z4gLN z?fRO+MYyeJ_*1!zya}Y2968s+;l#6$?j{vqF&m|TGILPnY8)t*RjS63F5J<*jMO;q z#s7mEFHQAU<1auM5l=xNHLgTBbFoQkq_py(xthMTFNzZGMbv(& zL}ObAA~5VQutOMX*K2GmIaa`!nFB0SW0Qd4aV<>h;RG}9H`cI^txj^9-xk`T)`w1W zq)!3_sn2(oNO)2K^_$$ONR*w5M1=9}d{dEi2cLdk=xf2TUPy1{Q`j$5LAo{4xl+Dg zYWx7i1p^wRhs4|iwCNck(Wrz+CvSWmJyPM($s4C0l3{3tJ~ggwiKZ|B6|L2YWg@ ze%N6X!ux)Y%^kQ2W~5YZf?SZFnc%e=E)#6vn1>1003#DDYie;>U|Da=+kzR@F#{w* z_?HIgj;v|}q#~_0KoZh!0}OBUKQlmeRHPW-6qKwO;3Q-+z}LID0p?HsM+00(cDDh3 zM~VzUk1nkR3o}50f6LU$4X^{w%nVTEKG$~($2<(M5g7A~;yqy!(Bpff6DCa^&G zmnP_ktZEZ}Oh5)>FzBSAhK5hf@wL`1qwu#aPQ^+@0V#!PTLh?{`D8MqMy6FiFw znF)GBP)uM)KPis{B+4TJiEJduL{_y4h9a#tK|iG3CYaX1Wdgf8@SE)(2|RGsNZ^6X zBLQoLJQ6fQMT!ajfSMH(T!u_0xUiF(VEqfs1oTsRBp}f>68NDQw+SBM$7F&dcvAg7 zgqy(Xzuessd6?iR9Fdv8SjT08!yNN4!9ifm1Y4@AOmMO)OfUi!G7}7h@Gnj9JhG}y zkcqU~1VfQ_o8a}Q{%0m=iHZ~x`~@{DCb$8aOz``s+ytLY_(v0jpcuCa{E#9O6ku{= zXAQ*!`Rn51Ukry2_8e`WP*EkZi2nz|Iq}|_^I0jwU8nc6wShWv)bGQ zcK=+_H5_|*K{0%WnIHmNA?4xt9LGFNa2gmhL617z1oTZBX;K}S;AOOynP3tG#ROLL zl=4_WqC6Im$i{*kWL2ABCemsXOhwvlf@SqwCa^wXEbzcpV}S=Qj|Hq1@>tLn6)7eN zgshlA51CBxXgfE-p>fOv^iz2(Akj4zG(dK@38IlA6O>}Isb93>1+(2=U{?>vSKu=+ zf!)xizRLu^a?Gk8jxPdZCTJR?GC}Vcm|zwN!b~t7!oM`Zd}LLdAO~r+31%YgHo+>x z|I7q^QITST8juweRE10?@RLn&Z0tXppgFR;P0#=-GQrK)oQ~G@EYo!Uf%th}Ou^E} z?PG(EV#ek7a7|gG4rz|F^({Z@{JV_7R08I;q&^>}hWWjUm+H9meM8G=o&MwhIHhZt zfV4EW7$VM%aWAp_8NZ<=mJ%}X*^EVvEe(WkP?ZCDg#!@IHnuF&2VnXqcJv{~^d^?y zbi%69n73(e2@@`27HE2Niy{2Pf82#0Lt#|t+sL)Oxuui75RafOzwYRG*xWK$7apU^ zT362c%X2JiwBzlTmNB~US4O)_n}$-TwAOMK30bB&K4@e4OB+%6oIBqMT&H{sGI1-D zTUsKdKB<;$hcVGoqz!MT%Gg-WSUL(Xi#l1BIgWI&bkv6L$aI&r4P{VS6OiSi$zqT? zCRyV3r!YJ53~pm;l4XD{T&K$a82Kpw{tTxB`IqU!2aa-=)?dC_BZHMDIqD@_9%&=C zWVo~B;t~}wCS7j41C3ADh5M`W_{w<>jdVKD?w_^c3)0;syp3N{327s7j@=|nRM2<$ zBu@caTn#P0m}a@F(;r7_!B-s}XS-SMY9qvv?jM`*Bl_{f;ix`#c642bPfyF_fQZw> z+Y8`G^8t)u-o%LKph`OmsD&U=<;>^y+omqEWnCR52IOQBA`6{)Sbr@b#)e$z(u z7~uY4SNwqPN#9>-?+-6oRt7|zdB&aR$7gt+C4J>Q67FfZLz`u35)d)2k2~Xk`tXeP zd#i5jxISWBFIApia-N>9JXXsveZx(SHP-anc)xSBW0^m`Su$3qVRJZHJ#aK*2%pb+ z4RVQOG4y*<<`-0%$3v!mCBvp!T0S#5m*hLWzufd(4|iiSSe}}jW4gmr4_YFn$?sc& z^=r`-&EbxYocAsJbwV3l+xtUi2cZ*MoV5b(ZiKLA>xiz>pDQf;guhY7Co3(6&|468 zhD6Svj+rM~Az;D}FRrvq5ejf2Ca&|`w4xX+HIA)eD@6fIx>a24KM%bX)4_}s4;|b@ zUPTAjAjhnR4xW_xf-3V_$aLSQ7JKU8$8K&NoML%uZnkzsb9Y%9Irgo#RP%A$qh+c` zTlONG(v~kE-~Lc-53kI*s>~llrnanFZhfhD>c4v(U3GFjQdgXO8Y zd0HpDY}#gNrq4n5k_m@tz1`AC=WbKJr?tXW)zpNXvqRk`ugt!x%sN(I=;pF_Jlo{# zecWxC;c2Y%$fg+U7s$`=Qn$q`^D$NCBalfy2jBK=%a{&h5igcQe*N9=KO-2D7PGW~(amLda|OTEZgUN_E%! z20+q5N{WiHg4XfpKFb*uRc3ptVn1>#s@Mbh>H)PXyfS~H%Df3OsbbAro~rmT#oeSe zEDsK=OlG{@s!J-4!J9OE6MSun79W(>6-L2u40|6~oUZW0R9#_&f-UgFC*6SM=n6xD z-8h98NyERi)X_^|96gz2eQ7DCvpx#cYi-CzN|DNnze5U!B8%ei3PjM@4gkA&3`OoZ zgd&%sNLp(Xe%#Vl-v~oMBW)8$)x+>LzqfG-j{zqJ;>)I74C#vxR&(+CB$qgARu2Uo zG02q{s}0)uHc56$FY?1__lI}ICrpr@$lgB%(}oDVW2ggUJb#1o!q<3X5{k4he}l4+ z(m_aT+4U;)(G&ba08;))dUV3lPP+NE1!sy-i`4J_s^hf@78H8p#q?Gc=T^$Nl<(8Ca)yYD9GH z;D@~ZuZx^OkIgu|f-7^x@Xm?`C!S4jF10vn@edh=eAx){n*uhN(#UH!w!h{BKnxE&0}xPbB5v8C(zY|&h8iw* zdgAoG0nSdsrKu;u&J4t!w4x^5q_FdgyDoNm{v1nbHsvsOdg7Q--ju`G>46vF9ipr} zbA#mClC`u?aP0|bH1%!Qjr{+g_%CPLHiUULQ!8g8i6@3VOT;B{(cbO}ic_0V&ID;k zY)V9RsHQDa^tB(wR#n~>uEAhf2veK1_Z#Gd)0P=rdrj$xa=a@) zq_yn=d71Y7X}LJC9Ib7Kf{_nq0!!7}wgAI-^6-_d)0mQ30@cv6w2|j6Z5@5iSemi{ zf@-c@ham~0+UW7U8=?^Ri}GrH^+G(gDk~WuPsZYR$XE_fpUIo?izTRntFQxsu!6OM zKIuzF*as)${4;r_zgUh3rajFpYjwAZiE~6UGKo0PfqkfP9dsyf@Mj-tT#hvR1dj~@ zZSWt82e!A)Sw@rg3JfakjRq+hW_N2ZUBOh^8w!kR&v>3|kIvU|KzkWXaZhfdthkGG zD=NjEMp{waNyxI|_Fv?Rv#R?TmEt^bb|3;*9O0z6vcP-o|E13QpjNfcx**NI!6QN- zodwdvEp18Yq-{*SR%>6)=NJI2>L}$YkeI2jk9%K2tb(ZqfI7f>`}C+KnJ!^WSqAIT zzJ!sNEU#0a|77h=97&6mHHBw7U`;rWJcgg?uJ_MxkrCp%| zwjQ{k#Nto>>!~(cVa)>y4_sLf?46%xV&z7%9SW;a6FF|IThp@R(tT_j&?Qla9Bhli zObA#F+)k?Uo2519UTHAa0SZ_LDA@YIVVLqZVI6QPHax`%w(bf>$`gQKgP6m*TXxJUEK0EdsC-jcu=jQCkjSbYHKr?E*$UN^4P0Eu!mK%yKCkhuCFMlkkqVQrxg+H#03fmIM^B9;|O zwnKv>Xbt=wr1tW!Kwl<0X$$`ZlEeoy8Tl1RB3}Z?K0d51JO`w;RQyAa`qGT6mY{Cq zD4tP8uFOB57t6eH+TgoM==Z=IrwzUg!$^G9(yKywT3QB+1w`JzGtg^hdVaMkP~b@0`pUJ$oSJHG55K^HnB)%)Sdc8=m}ma19{Xl1`E=o%aBRc&k6<3Z?< zuCN3)Cfra8tOS@K6kbp;&~0s;fQKld@MmBNH$eTVXb+87V{TZ!5}FZu(_#{$AWVWl zu4OkktAnQaq~v-Z+cc#tlwXtsEYrs}S;2_TsleiVY|jJheXJ|CzlV!H@7=OQ=wCub z6rsl4!koY&xL96P9wyVpFrV#s=#wVgvP3>RJKuCPMAP>#A!hS$`1>|c)Ax>0tMP>9 zso&d?iS~#|__7iEaM7Fjrmj2Qt{oU4z8n9#HuQ=v@Yt0^O<91iruq)#jS&K#FT$6- zV&BPkoV{f^8YoDupi6@o8El0>A0T?Eo(2a+{uNr^4+bcJQ68;h10adl_qiS;COTZ` zh<9C&aI==VGOz{X^u;ZhsC{dvbV|yvCe~!%-~!SD$O)+!h}83&o_gPSq`zg~2H!A8;qLS~{garIshV z#=Z9#oin>7mCxkUn%E_b%LQs*%BLV{f)XK0bmxj6{6Tn{C6HfO6+aeM3@Nhx8m$pYkVb_7P%j;V>XCO1D<^ zX4m^8wNhF)J3Uk~_7a;pOf|(&oEJ*d669r>e7fO!8|GzL^c(8(yekSuUM73qufW!X z?(CYUoY%!iG<1O5Sie~3ad&5P8j}@R)6fTD8-prRK`HGQM zZ9r5GB*jFC(;UHmVnl#&zZv%;;U0Q7_C!`XJ?)0pTJEQy@I9CN>kMp&<#?#mJfy zA&_6w0#5Sn3r!Jci4Rj6^!Ks7{+s{O()o<$b~XLkLTBz4p19jBJaCFx zq*hcHGsq)6GG@3v!V`CUga=T5U;uu}^RVC+>*uW)|**{=bI*%qQRvOSmu4 z4`g2;QT7EAWnUnXeHd2$K3A3_4$vm8qbUiMAM|K}6VC`UhPnJ8O~F)tkOGYP!MZT+2W+l_`N8r8*$>`^!2Ey} zs2XyLa6zd=@q@Dprt*WIfGK`Zmz<4NqPT!n?e`2|31nZNtC_;A&c058G@Sq7m+?lIZi{kNWw`7 zkBR-?$II+L4nfU+BhrlhQeb^CkoakR0`Wa@H}O4infUBhi1>@C0oBF9Qc-=8jW!;+ zRqXe~-R$?kW%e_bxY$1gRS@gXHRS()!GACI(+_0!lPI&FM4A00s@WfpGCkQJ3&hR- z2&6pOUkwP@|CD1>1F=1Gfdb|Nau>g;31er0VNkd$xLU7Zcq43bd9{pw$pxh@?Tm%m)QK^N1K0RY{Ur%y86iBDT=^Y{qY-LCwS{UE5^G^k(93 zdSP6Bkh-lHDU52?+QNXR(4Vw}8)zXMB%utoTqNNZgvaf~r-aK88YV(G521IW*jBh02iqr#hVY*t zT){C{++9L9w=rmPI{`bGC^qZHn&}-lAwa5tlcTJ!i05IGzkI7Ka4Pzb=u6*MU5;jq zY%dO|P=OLVc~_vsPTn~Aid?~?_F{wPV^A;!Ojqjh|CjOq4sD;11E)q>y^RJ7`8Owi zaOr>bIhUp%{pJ!8IJNU_jY8$932kqJ6pxyuW>1TFKY=uhndr-?b&%j8lVifuVi)Ej zJX(@nWM>2BB347wNSBLjQ!tf_bkO%hphVu0V1#!(hKZSXT!)}|2M?5F@93nI zh4K~e5EV@29ZA48n&2J%p|GT*SEP`7U+BBl0?1f*TQ(GUsl z8}vAFTzJ`la{zmbJ%v#ahV~W*B+UkI48d3co{26z)yMW3E->s*eAO-vnBZgEu3$vw z63ks45^S4+#nA3cZ67g)JjPD*rVaauxqdOhb$KXocYRoH(aA1lF`AlJ^E8_NBG#Vx z;@XX8#b!h~x}$9ctm7qdQAtOB${YJU{9$ypncBi5$X{QYeJrtNu#DsZiItM?^{P4K z5YO`kkh<9aOOI(q+r_fG-zVqBXu__pmFvu_^W^sImapA8>0eg*y?+^5D;`+uL1Hp> zl@-ih`WEYRJ@9-w!(nknT*bEogTw~4rlX!$)CcCs(Q^riW-p_U^$Io^TL(E-4 z*nAF|m`NYtsQFA>OZBsz=2(G&Od1DF@UxwwQpX`gcy1`3;b2k<5gc!g6N`0@=SGO> ze!}7iM4c~UP@M8ag0)aKo3+q6akuQsVg#{3HzAO$W7qRo6P7fE*+isuMl-)*n ze^02g`DbKe*Uw-DdK|6`dfN{Q#(F)t$RR)5Nnn;OL&Bs9(?y)B3B4l9bu6APW@vqG zL~9D9JFkdsb;~TZ1PHCFLq&5i@->DqbdK1;5BE|)oZ|)}ksbNPQN=)2t4!E{ zo-IyS_y>L$E8QB}zGjGwP-}~UT5{k&ry-2Vfw?YJQ_Ph-M+^`DNlxBRfd91S{?iHA z!5nU`f(ov48B2|+5h^n>bKR(jujS^VwudZ%xt5|4d8$rLzD3zwlnvclJKtB3O=T<`eolBQKf2j{>5)x$t$6ur}*IrzjB0h zmT;?U?HX~q!Ud3{WIk32LNFRI#31Fpk3qv*m$PZmz>|tMzK(`-Z1ncVX%0eeUSe&n|ih_|Q1^!I#4{YiO7!z8fUV2*jhO=#Ytbm`ONE-X4Nh`!=Rd8Qc_t`f2!#adY z`&NkY{PZI_L@Je^Cb5whTVSB71Yjjv+lLB9RUN|H$Msss~W$v0>& zR5%u6p|-H2v~iu-m*{|cr3>Ov>h?+O)w8c6hO}WPXfQN3SwVYsOj1O8OBjf=kctJZ z?Op)f&6pmkr^Iz678mx944}mCNL*#-CIuhmc`pFzEKM2KzGmcwSY>4?ZcM&eV=)TlzBf7zpz!pk|M}2To;zrR&_y+0i`?`lo`!GozZHylj1kHcSZao7E^zjfXJ3gn3OEgd^Q5&P=MOYN-pl>Ivf z+-F#yrY`@ktzgV`@F2F{#})?6vJI{ihRA~!T1?-D7(9T7cbm6~AMlcEHgoyyhC9n0yq2>)Fevl@qk zmB*g%Sbhg@OaB&P8kga(s4DUmcf_X_#b&%c9h>q$;-nKTJI8nj9vtR78(bK z>y}cx?qU?4gEJguHBJ256%d7uVy7?>fcknJAV?*?}oha`?Px+|cG#wtR;H zCsioif`*Ler*X;11|a`o9S1v>3VBunVaHPOa(mTb1ine##KXbOCHohmzwaF6`H~;p z_60BbRUnT?52ziD5?+M72R+0tAI)c@vR+?8v(d%ayb+9B4BaiZ^c{%||6vDwNyB$z zVr(GNY3xZWa1$@CH;}h>i?(j;_EkNLftJ}O;gBL~oeF0?3wj7|oO%{nh3Hu<0}ctc zwtLYNjH#HFP0OH%@Ghd5re)AWc;nQ`$VF2pBX!s-22pzpDzpppo!&S*gbY2TH%{FP z!|+JDS8P!G5Tixt=1w}^wWQ*|e4WBL7`XtJnV8;F5u-QsXk8sfScM9Odzx(SpESU6KEMVE{(^facs3%FnT6JMgd_xOoSg&Ly%(q z%jEsy0&*TJ>n2M0(}%&2IWvOd1UNXb96wuK1taIl1eWS&3kQ~X0L~MRn_^pJ4`3YU z&EaR%U6E|lpT#(SfW~pEWi3jSJEP0Ks#@e=LJwbfpW)>WH~g-z&Mve0GtkBZ*> z_@PuXUo1!WVh#AMqtx&#aj>uezt8y!u09LG-mkoogaXn#7Zu2R<5nCGai!6|}Y<9VP4guP#jZK<_&t8{khvy1 zwh_oNAot~IkZ(kN$RVU}!@CupOk@x3R60BCaThNq7rC~vasof)$T}dFBWToe2qTX` zvn!!DYG&k82=qL0Hw(`bIsAD-0Cr7UckF3{^v4l|7_2&#!)xWqQg7UVH^>xvc;o3< znV~fKC_)VH>+2|#z?6$O&d!OxSP{>|GFrL3MPgEIDYl2`8^+esY71N84%a<)sfZmY z$5p+$cORU*tSyW{4z@xmvYNKA+7q+m5i}u?-Z$eX_n?rG=euC_t+wzwB8rw_-qtfDl2^!nWz_6%3Oe#2zSR4Z&y-5E5X#4K?D5~%6-As~Ag9J!O zBV`FKKnT4 zY->q=FWXv@i)^OQez1^bEc)}FQ+<@zU;_CckVjYzrncEO$mDks=^pCoBkjUNu7XMbJO>KFYd$Pxmjr8Nt(mys*KQFR0E~*Gpy5KOXh-{cntxvzZ{J(_% zg7B$xSiQhl&Sbq15;2R8>H?-#2x}CX0B5oC%j|>%L=iZG^{o4-Ulox#O?!Z?)N&U zEBM|rK$?Bm=}0pq*roSj$20fm;zu5nvaf6CoNmBL8ItXjB6dQ$)f7TuT@dUk|?~F#QUc)RVV3B z6y7ilQfHn)dps7YX_R^vDZffc#k0ngI{yq>L%~Ro;tsum(h|}=n9HjNkd~ZxoQ|Vs zEN!q$HkqSyw;{APX^~8B=!sLK>CMvkbi_RIN(0YXIydwF9b40MmU*CuzSC3;F1c{W zsdE;iF=)pv=6CeYqI8oeN;iq3bTc$LBQ*k3rB7Q!?d9$`)h#?)(xqJo+tpLAH_q@4 zq>FcNJJnbCG*|30NXQK!Jz2{ogt|aLE(3X%H%~5bW6O)i3-K_<48S<2fT-2 z6*cT@Tf92yyrm_1a6awPn|l^>4J6;9O-|uK&$d9Ii$tJ{w11#s&fbT`vr)n5!%LbMeVV?+W;{~@i$N3AE z4cHu$T)8Wq>rftsl(#$K1Pmi}Nx-D?_CGX?)SWG7KT}Z7{u{7E7j^D!x`dkcJuuJ; zLK;d|zMN9fhW;xJ_Pu|8LiZ|8Fnz{~g-#|CyZ%)OD9Ezx`_^KV7z5;q3di z1~;fa@(lKR{AKdZ^n%&IvJCcQ4Wk#d0!uR3s{xa);st+CW>at-t*%otXI3Q zli55k8&a#)3gaGUsn$q+$?v9q5Pshn$Y*TuG(sSCf$X_g68Uc|WHsO({)DSHovIJ7 z0R{34ko$aNZL!t%Ng#jn*4I(~tM7qq?9o3?ItXFqqY%D;uK< zJEibgT4h*)Ta78vcj zG>i&)9O=FfFT)3lEi3PjShWzGK z*_{tE$F(gop84eeoMKyK^-5}{Ng9YW_M(j`k86)WrtN4G(ed2)7^bk!H_H1dI%1E0 z_ZbsGD6GKp&0&~cmIacmM!O%!a?C_r5-`bVHvk*-l3ZC`<0HqK{=h5Jhl>3^@^B-C z$Op5hH}@sH+bmY+2GQ66jGP1{;eKWe9i;XgzkP`)V|kYr3epV;Ev6N-zXo zVk^W_OXF+>N;4O(rp}a8)LcLLo1kUa9zy3Xf4QmO@7JATjaU$kL%^6zK(IC#oF+7Oq#PXh%l{P@%<;ylt3filh`&BpCt zqf5h%1l@Mc8F_=IX`q?C6{gZa-8kH!4sMFBUwp9q9v@Xb-BjHlEGJ7nanG$_IZo;V zAu>enXR3#G3)ug5{rLa( z1Ni?ALmV%J%N32Z+c8^3t+j*Nf=A|m>wVyBf$+6JdkbJ@DC52cObWC&238OuvznNF z%5g@>Ddc7OD46vs%MJT{eA%h)_VFE~P`flXp`k&Fm>XcM)MX6DHC<1&VsSv0Pmxi3 z>c`lbJ{wq`Ptjelr#&^d0N7cdqFcZmm32?OR@wd3mhGFz^Rm+sBjXtLKXX>H7vdM} zecl09fPv#Y$-ZBwxi}kGmSq0|*yKo^=1q}q&A&v-1En;)PlqVEos@Ff=~x&gFJU2x zUiV;?jCgwW9LN|kZCd`&C8zoxkJN;*76=I<(35yDrladO_wgIQJp5)Hn>3^j@a<*t zdlPB2Yp-;OqH?zgsa3oedzd@_Tp(}pj=_d1vdJ$S=|6bK;Q-RoWTdAZ%8WKqNg0d8 ztt#>Ws+m0+^Jc1nQ(0~4fg5pxhN$j6@LY5n#G9^&liQZkXAGz1WRFlY!Q*$Q@lA+! zF%988l&_xthsw9k5mooiwzb~a%fRoZD5C9dNg8bRk;dPq^z%!R8=0zHO>w|6%5ZW zknH#2*P2G{bL$-qgT~@4+-H^SH-NFvt;h5#omJ(LTxA$G?iXWFUuZvvk=kd~y&6U; z3s7O@8SOiOdK}HVEwjH2Sj*_C?w+Nm~{$tHHiN!$?~aFv(z_ z18j6PowoO@$xF0yIrUR~HzB`5DXicwuJsOeaTUXpi!olpZ#ns6dl!5VeyM4>n#&p= zqy<|WxZqJgxo_|GY$q2U-$-%E2Wy~^U%TK`4SXR9otBbhEIJPa(?V#jpg>Lmxy{#q z($@O8=O~b#tdXZqsfnU}2h{bn9*)Z}9$sKpa4pvbYfPEx%_Y zkk|MlPjcjaAlF%2Q%#?RCdx{rOQv>>34ulx@&&Z(MyqzePG)sMEjg%EsXvWqK_5xV zEV%fL>W$-bn-)b*{xTTfWeoNuE76)TmA-WqsmA!2w~8V3(-Z*{oVHk4g@T1s# zB3Wkr5s$!uh7_V(=_qByk7+jrZ>2PnCzP)EdazYZuPq0cB4GwK6)`;M{o^5Gc+eZC zkvvW5g~2sq?w{u)c+-F3|EJ==xZd`Qc1cE5tFdm!J?P&m-v2A!Uf*@NOM;1s{Oey` zHMfo&Q2q-jY>$W{?z%7G*Ft8skA~Nw+6VV`B-FZ)D85DY^19)C)G|ko(u#Bq1u&j?fBubKyKBQr}RX;DJ(Ww>}T+2&JDI3 zEP-|dWs+1_)>C%MGl*V!~S@Z!6_o=wrDPjJ8uTR%}o^DtwA%(J(Aa4HI$cipf(&mW8BnQZ(e|n2H2Pkdw%U{xDzPsNra6Uk<58vs%6phqo|1-YLup*cRJ2Cl{*=e+TlX66oU`4 zmDiq;qSnetTcp^zJRQBZ4bmCSnJmg32sFgH5V zH8*-Xt_K)j>Tzo_zTV&qPVq_$u18$5)ZlZcC*XQg3wfgS>ltR#0ci__(Jke6nlIM7 z>>8HQi32~j;B?GZvPGJ}@2{**Y$bP*c0=Fp^^ZrZ#jWH3zpY3uQth2B;pJb$;9oGj zX>f>r1JKacvbm}aKfN%>a_3R0%G|NY*;_sVbHBr;1IcKD!utym#@}d-FkZIYQi{dz zkG7VFN=682ZRC;C&!N80=<(kt)s`POvuAkDkZ#s5rn?nvILu6nswHT4AU z?aJ)d^Rc!n?rL zL$Yj+x8eP%#9UZuz|L&bdtAsf-094t5b-_gPkb@t)ZfQIx|*rTRs16G&Kb01KeDox zharIIwYhmqMqvRC{}p}JP@iAcx{~YG-|)m~u3KFb9K+NWR`7cYSKsB8=KxB7kMvU3 z5-X3@o!a9L09|O6dsDH-MgZkqgAwnaV?{XMYzcMsz2DX_*7)Fk@3(*@*m$unqzKf< zCXX@JngqQl&)1DVDD=5E-)Dp6o}t!|cuUma_&Rhg3!_n0a=WRPeQ7ajP<#2J=8QU` z27cd6dwX^U58DL7Q1orFQ*FsxnF9G5NK+P*gV?qZhN4e_Z0{h;rSeqkrF-Y;4054n z?mT6^^uZm`OaJwxQ{}m#&qSSV+6FjQJk!0IOMnlOZ2y}^5U7iO4}%^ho#Z*3>tgUK z28iw>&l&%=Foad`ie};+4I{46WTXM28^AC?6rmpLjK=K`@C!PS%-LCXer{nEZw!J&6w%(dkvVV*rqhbk1GAez1sfm&Q2q zz!`TKEMhib51eb=I;W^N(!t%!Cm44Rwv2OUEIJ92Id^Q316F(w1oXw0GZr0$NCdu) zL6|=IEo!LSGUQ6JsM2y0@x5#{{$E7ZA(gY-qj^u39~AX`24dDx{H#x=JX6{N;Z!E7 z!?`D&j#=F?8$TfIIIf}dO+zMC)lYiK4I?pZkWDz)%eK8fkH=fS862-{u&7dR zIhkkK6V>fnhrBoPlx10XJ$tT%Pbo=KQKk#4$+nkyJ4-6+0<0vbRfPItZ=PlOlw~V> z%jE(n%W~XVMxw|v5-H1qb|6Cvj78OcLd~)0@t6R}RUq@Ji9wi}NLRyuayrHil!qF_ z+y1~qWihy-kl7Mxc9xtPI2a8#_B>tGq$#zlrCztaahg)QTIyX2H(>WYVe`Pja*c`$ zf8-6e3V4jb@Bhi_G(jWs3+u1AKy2QQr7&CQBBQxQts>fDZ26Mv!|1)I?6vKzrxxeIcDUBHc&Ge zq#!qP%++e3Q1OA97c?xqCJI#m3RQr846sAP5UhRz^^=hirs4AEMiUw#*DV_?j_;n9 zXZZWC;f>3I@$ISYxuQ;c{uPClp-*@TY5Bbq`*c*Wv~r#o zW=x-s_S4abG&SWr-nfwl*)b#`a7XG``758Gt>2;A{0oc3HaKBNoN7JZ7pG~~dB&mu zAc?G;R}|;q8h}&;{a>Rsy8i`vW-B9&ZFR(ChCCi$z5(kD3r}{%{CzGAG$!$w|0yuU z{0KF7Je+z9tfP4p>Pr}^yFFg6W_%EZv}p}(B-Qb-Q=QA3%(T$}5DO4K_!`2(l%c3O zkZd;Ks#cjK2b5w_i{subYH?iPe6)4;B*daY-!di(shq_lQ%OMXQYLE=d>hDiM{tw$ zA<`^_uYo`jXe|0ByW4h%RxK~eqI(@HZUTwHM)r zpso;711PBdC(+OwYAQM$lKQk|Dpnf((9?Yq_P4n8h zt3|>W8CAV7w^UG7QNwgpl>>&MeK%F`vVISwN^`J9cnMDjn+wF#!Loq}2fO|ByKT zcQSGAuqIa9TIUlO4es*Iy&Ag~m2c6o7aO|vUC0N9MdcAHrjt}LZAFU;-;vbd#qwTK znQxxZ1fzQB^`7;ykJNq+mBj`4&X?z7AEseYS)2_l%g3GtY;@blBh)HObSl%9z)W;$ z^8MruSbqUhQyPCk* zB_2<{h0*gmu;W*}zW7nwD>%{ncg{=2$PukECH=Vhrs) z*{t?jEgufL_ysGTWZtfe9pW|P>us~S;WCa_sLK_BpYP5{ZkCFux+(R9xN2=DNDJDd4Ep99Ioyq!6s$vJ?vk9I|- zr-rb-!i`1ia0egCZ%Cu)cy=C;8z?Iy(Y(Kj5D|k=@hA9d4Ly{;jcfEj4%ndeGB)!i z<+@hNX*Mj~^R_om-?=Dgc;i%>g@GskXcn{dVxV6|wr8}l=vmlOjJ5Rt``oDpZ;(?; zJ!>zGpMQsqZoO<^GogPfjTawrJ&Q71&D|i^Dy4J?O%22Vptn+XHv0ReaYKC|pG z8=Ve`2a)kGemuw$@5Vl_3Ymrl{e`?@7Iui{`9srYB1AC%AL#Ao{x#c$lix)(13xm` zSab|`J;FN*?67KMQ6Z2C{M!u8FMu6i0$I%Op#c^kdw?`&GfZ%%t+D81B*g?1p(Otc zr$fq@he!dBeTI4(-8$B@b}ZN=-}j3w`jl59?}jy9CFl+vG3&B75vD zeajLw{#NdmcP5-h_kLx0!x*;oA*q7hClK2YM6Qha19HQ?PRHau7^^gWMPuAJGwFPR zd?Zl%d?%Xf2hjV!goam#gNT*Tf|Xn}$D6l7PvDUZ+uXp_q&lWy6w8u$cjr4`gRb?& zfdPlmq*75c)4tc!4q<);Wl2881lseOiwB3HZ$TJaV1UV*)KZssVKkZdcm&b{$Y}bk z5Gyr+SW<-6J5#1B7g`h48`oOz0_UywcfLhSs_zc;5gu$3YfHhLkHC#*3w|vStp)!! zWNJ{2pym)YNS{3{_btWVs6B$c^^IKY4c9Oodrtrx-L5_MH9P|L7Q;AdkhVI40gJz4 z5Br5T^*fK((YHQNA&u52>Q?nYzs@GVqexHZoy6RuXv2FG^>+z8brc`a?|<@e?(z&p zM6tddnu#=PhjxTOv{giVblneV;9*cIzw_Sas`Ceo`ElpN)Yd%yakm7S&M*rmie>SS zyMJofIhs7iKknWHw);m^q=Gs1){k;J5yz?`?sgWE*_p{d_+-0+<`rb+i$X$VAGblqhbLRY}&9qt4g zroR?|gH8gf8P@EP27OO|QQMu7v%x^X515Tz#`Q2zz3cxbXaPMLB{%4($+i_n!j(I^@ z=%iSE>{sBqnl^1r`htd$FP=ppEWkd~z)F6=h5&JAc~NF6)6U96xXQZj=|>-HKZk+Z z^rKB0Mk=$>49k-29{~I5tj@qn=P*@+6^vS#h*f|>kY}*Jr2Ue#WdqAH*r#Y1X|n=L zGT0{oTR9O1es#`mpySdx>ii0i#Ihw;k&+j78|`X?E%*g(FmcO@@sDdQws_fn_euBN z_Z2t%!TkQ(-2=}JW?KS%^|4dk$)=D7iHXR2f$Tny7S}ciTg2?8Z}BzxL!{fXQMwSS zYO{<*Yk=^t8xaCo1*9not1yr4w9U)EsN?Bf*mQ21A_Wyw@q=78ts#UaLjZXJ$Z|gQ zK_H`mysi#8+cDPfNr;~24g^BxN{>Kz=2zZi^XTW%%!k$4y{T#DiHjKq-Z;&C5cac~ z4`&VbUZW9if=h>wAvEg=laRetu$d3BrE!}1AXKxN4|`ruuchv|C}Y!kFXPNKBM;vx zO5rqvA)_=-(;tN9@|R@n1y0Q=ePAR@Cu5^nZ=9Ng*`;xs`M~Z)XZ=+B8ZkQ^JTRth z<^S8@zjl2a>(^hW$i7F6K%)()wfjabV@^kxsR_ttWFebpLLoLpxZE~e9dNFrsr(eA zv*0;GDce_+Y{mMV%cx$na5sgd7V&XC z$t`(&Tmw1vnj9hJLFjNz-q2+{T@?{_9LYk%7?OpCQ6viu&yZZ3Ya0fcB72Q3SO|yC zW7>7u9NB-XdzNcIaYH0-IP^(Sg1Yp&{5TK36C_u-d>jFqh0BlqP)+kW-UEQ`#rICL zE?o8nb}e>5gxc{pblb;)cxw4P^P9ZJ*EA1p)#=ztF!m2Qy3smBcbdpB7!w`VL#Fhv zqYc}ND`DaVCOXW)C;UG{4R=~%Qbuto?!$zKr~Z)BeWavKm=}6mPLU!ZoWCtE^A{P$ zc9Q2=y7&m^$h6eWPW3qJ`-KRkCXi#QefXnMm2f=)sl)g9pik~csE+bO zl*AtLGbpt91jrtvFAB754@JuxXKe%&EpMFK2*OmH$5Nx>P1sLugz-uPAbxw&qo^x0$$koKiMHyfm z9s`!gn;36$jB%(nF_r>D6QlBy?h3Xo=i|*w#wz#H*pEYS(uU+)L~9VQWEk#PbxO72 zskS<$+VE5hU>l7}6VnS&NR#<58I@m+(qs8p1SlzX?6Qusrj1FNG4rTByp>^R`IwX$ zR?8eK)W)PJ=UW5I^HUm_o`&Mi`10|SpRz>D@lS%4s+zpQ-z|UAD=0=S_E!?iUC(!_ z;+JZ&xF(WIRx3k8<6B!0xv|+K)9OETI;=^K31G^NU<0mOl>8^1yDbUTyz;q08 z2~WGfI+Nz%!PCTa8tp>)Aj|{R+>s{n33=CkR=bgFP6|>K$%wbw9i*83ZsWC{V$1GB z*7GoR9Y_{mnlF$GKnAgW*0kko#XvTwGy1o8EnhnZWDUPZENCkP@-87P$9&c0!AeNQ zF92Rdg^OIx$NKaA=LlhPc@;!<@W}{H^3VeCuXpztaPH%iLKFu=>U8{4J z7`1gdr9Q1GMQ+z20i4L}rHW%4O+FT^3 zP%Ycr`{A2v+vhsPtA$Y=!_>iJGXwl8fPq!45324Q)WakNBE7P_(x8-;L&(Z!N?XZ# zp<_$qxtOOZjJkR$Fh*@0s?_y627Vu>y?~-Bfc-+GXrh$3O$0`Ijq+c#NDaBo^JpvX z`piA9kKcU&WUD%3etMi*J4{h1=oFf7AfhE999n&fW+K=!EFaS$MPF(<$MRVRVe zs^!ayZ^Y;m+gYCH3foy;WDp%n!o_+A#GPz(P)zCHv4I+pG&x9{%(@wf!dVd$_SXYx z%f}0;MVMqPdI!ijK3*u0@~}9$uEWQ+t^=5hfrBb?Y9smD1 z{)^|8?e}a0c~0wsNtuoO!AWK4VA~5oE)SV+FQ6?g^9Qo=(=IV|=l%7Vo%9~|sVc6l zbmU%f4D-P9(6G$*v44+p!hEbb4%QJqR>Uz6ANvMaNp_zIbwZ@V8k=mG?afG~jZtcg zr~MSAm`$&uVW~8*IHYJL#i+TAXy>p}&6|oOvZf-NUS}+lU}0-9>=vV#{G8yUIrjiD z{p5Ebjn%y^JJ(bbW0jYifvp^UJYy3vc@BHvr|HxrOh*>?s|y<{DQZ9!rEgG`wT$x| zDx`EO67TSeh8UqMEZ9^e4_#Y4dbir3cP2ZNWfW3ql~E69{?;C*kSCGOL(#8~VKnvn z80t=aL4EcJx2FJ5UQSs|DblonEB2v!oRLztF;OA!!uCnz`zg})NMJhFO` z-syfi#uWsP9RcFiUWrP$ba4$j;fYW`6F=RUhylGR5cq;m6V)!yBY7=RiIzUaoxx^2 z_{Q_bQ=0Vp!BSq9+G9+NJn+L=j#GGG{ z`@jSbz$DxcEHnu`puxumfuC2BSGR#!FdoYZ6QV01v9a(Rq<^(A#cMwiBA+8+{gc)dN+f*2u~ zZhN*vd_)Q!Qx|_6;|;H5)qWDM0KH4iPdHLTo)CBOqke1JVz|MnXD3xJ5`~2-Z{}RUynx z1riG3XsU9A%4&{bb(AQpktnN`YsU{{Wi`jla)y`H(Qv(0+Au^CFRM=jLs^Yj+5i

=$IQt=&1F^=`ZR-K-M87E;7W3)sR-Y=}S_0O4geh{`PPNd}V8P-)SO zY1P%dX4+@!8n*VPN9b{C?A>zV6#r)ijef_e3bWAetWl23yhwK9MKbLDEZ+)`p}6X= ziQ+o1ky0)2vv>LG#}0h<0Q%!(-*%u!8!1CNd)r|oJ5UI{aWfT86hd!25!0pkqcJ}z zFtr7J1%>{Xpnn2LrFca{`3lnGkk(=t?FrZh*l0KL3(kqrz4A?zrhbEPaUa_avm(tc zfyzEWw&8X&Mq)=dQRYwq%`qR3Mghe<*X%%hRg`0f*plJDDN7{Ckpj>KLg{oG~d-5U&UtPyKr?~nsP5FXchB`2OG$C z?!&SUdiWD>Q(uD`0c__!ApLsJOMHjyvAdsL7ko+9iuLlmG-R|YkjNW zlLrb<0mgJdKf@-(fpK8j*o=i^g{)za#S2~nu#9KgM5uKYl(K$!Rhs9Wp(t03e@!f# zR!ln%CK-#S<0YTuA^OU09PB#*Y1H>Im2mA@$TT2JuJzkW*lg*IzE-_Z%oM}x(garRUypnf~SN)I7`AGD-h?qLMVo? zh=i{pTwC5YVrjZ!kv1bS?Txk(j=t$ib7NXAdX0uXiFPaqa<#MGeI#Hp$SE`vIdCcZ zp!Emn1eVX-$_gyWVE+x+p>Dj;QiEPKW$=nG-(6Bk6eX3RR8mER-UCZKWA?{DJY#k~ z5Ghk>M{bm_FP}rmjWAEW6izKFUT!_^--GhZ?!_RA7%cHs^E1(Q5-27~#H+=b7(@_2 z+p8VwmFtRHnYbSYJDRDhehmx{6Sc`;Ak+d3V==rEb<=TQAD}ydnh^cf>D84)DGW$j zx#nhdb9d!4Y3XwQIa^)c16@sT<4=oLl{aprm*Qo{Y-7{!dnuhXV#_uayPY)k>x1VX;<1s@ zY$(bAvY(0p_D$}s_=a{snhrdnNb}{JoXj4>d-1se-n>y;NK~92ys=nQ2A?9A0DR*SuJ=L9kT+-{`E>$ zcrZL;29>;1_c_OSfy&~Yx;?-a^#N^^ zi?Wpii`d5Yv@1~_29;oO1gok;#QF*%s{&v5E08@v3LaDDlN;vf%hq1nDttT(#UA)+ znw>VSG;Tqi$aG*_ZRlfF)gAqnj#48SZ5p5?8-rFaW9*TMI%_e7CN)HqrC?a{B|oJq zs8ZE^gY=X#)7R8vsZ(8se(1tylvU)^*V#-fF<`M6+7a4v%$t+o!2FBZLSXDZ-50Z0 zfh8PHk5H$NKrPx>v{hH$?-A$NGeRje`X}=yDm!+7i`dZJy*@|Xd3UhM?-EQA)o99S z48os9nyOJ+dh!$GfocO|&(=z|kNtK!|C+_r>YAlS${u{p^2W`SJsB?CadfmY(in7h zu~YpE!@7OhzNuduJa;CmYt)@mPm^C0q{lPwQBNQpoPzXl6uMhzrKKKGqSgA(;gdiu zREYsMZED(cikT`{5Qrl*@_3{OK&CS+0E?coc%+bkxkwd};{NNX$gVtIS^e-ie4%Ls z+GzIhwXjZY#aF?y*c>=kX)5hsf+BZkV4PF{fo2j(+aa9#Qc3A^qAQOFr5K`yJ{r>A zxJ(Uf!~<`fDjC9tRmQcSE$XRnlX>cKNGupilV3#=?t3yI%EF^ozIh9MCV8ddOC+9O?0NB7ksLYHHJBkS-oG!`ndY> zL?x5^rU9$Qgm1Qh{SEhk`O}a-g!Gqcg>6b|+V##ZatrlAn8pQ!uX^CCXi$>-D&gw1Z5WiS z_M(y*6!{wS$wI_gQD{hHA&7)gsn({_7(BS-MU<7{5JuaTxZoiW-UWMg&^spfXos%k zpW9;$!a79#ati2UwCL!IK{Q}kf2=MM^hI!tx1E!CBOnYIqi^_BP9LqnRt0?zvXasF z6W&Bm-*-ss>D!OApzm_0|A4;6(?MS)`@`uQi3c4! z?Oo*MKOpdV;JUy^I1hYJ%maC*1&q9WcikrqK+ zPI6H@PF=tPPF6_%1LH>TUyL)P1$| zA5m8@&y%|CNb9NFgtVaUu=PKnZt?4&&iU%YsOyc#GV0PHFzVVtAnHO_>ZofXVqNn$ z%AoE({FG5Q-Pc9k9gcZWcLNxs?uR!@Qrs?c{c@p9anJr z^7ZlVPxvb6D>Sdi)J5TWH#wH0k9XIBG5UU8!Rce`KSeX|K~^&Qw!;nd^ld^~Pv1JE z1%2Ph{{elQb3xzlvmZ`hIv&jEYX^bR*9HR7XTpFFtqTkEDGH=6{s2WSS*5I!zQOgp zx0M!r#0>kQX?=}f;kJy$C`@e=ES}?-2aBhGrM*vG>pUfj`oWCFj65Zsh7}$}Bio0C z#`Cg_MXTW#C7s*E`Q<|33u@E@pR_Ugy^i!3ytA>*^6zO}`Yu>3p7qx(?ot~0!={#G z(~C+B$qgZI4DS~gTpI#$c?07-hdxo_OpHmpRo(cJGE`mvo;L2NWAPNcm$8^bbD4M) z{E=fGEFJ*{7IBoJAh5)NamT+P5TlNbXeZZ|@CrWgs18_-4w{NIA9iFrwJt<5beqy3 zEkEtw6R1{O0|t-2@-POQN)7PXgb&bLONIbHWV=(FArpO9O?cD->e3JRP@LE8qsgzUxbCzcl`tIefegc_Z@`8GWw!$Mx~(dD`4LAeFlt`;pH1qhW{yt z3*ZoX4qri9$Kg~Yi9_{nz7o*Po2Y+8;II!t;1@4HoWMjplMxsNK_f5>G7f!Qrzu?t1|BL>Ek))?qguy z+-(BJxGQ%2e{eSij-co6d8BpRjYJaMwfHwKHzjDxOAlu(6i;G|nILG4m4Iqu>?;f= zX^dS@J|UuA-|alw<>-s+7C0zq%Q5HUtGJ*o9~fvW)Hht#0VCR$?%=Gk;VCWR6(YJJ zuuu078k(ra~BJ&I|Z!%8+1DUMp#|Er49`ku10)Nx2KOr6N64pVQfCgHpXXjGKu)C4?)joEu@Lh z|6v4*98|R&RD6ll97bwNX;MMfb+gVx12}=e+=I{($MW?x42v)1p_>nK5B>Yh?uWnd zubU9~*G&lg>t>Vx17@4p#MjM2`nvhz!|ClucCoLU5cKqRLYjTu1ikoJY<|r5Mu{4L zG7)fExiju1>{NiVKMZAmw!fibEk8pO#%?j~zQ@ad4TLg=ox|z#qWqgV=D}_iVApn9 zqt({m{!?~;h5s;iPeTB^@je86#{+AUPhLMA;Pq3~ zPaw75Bt~kE7VSw8(VoPs*Og{I;GJ>04uYQ3Jfw-!ku;Ec9PW9c7Pd$6>)>+FLbI-T zPe*(JS=Y^pm{%r>_hgRc=!54Az!-stk8=Xqh?rI_J;+d2Em>g@BamE$5!eUz&4}uD+qcj_aaSH&c&cAbI&z! zPe$hw+k@QGgWVM@Ehz*zI5ZPuU#;8yUOgGmPEt5T>10nq*KV z`fpkN70$yddkiTsR%@LBt4k(4oYiY!p0Ro!f}Yh=NE54TFvyy5R*Rnvf zEJt=x{PcsMr}7^1fvDVvkydih;48ng+C3-0{s20EMA2h(HjZ-9d4yvgbQS_*bdEUx zPw9LMMlm|cOBkK=AuPP`Uwb45YM4hh{}nVAz3^}v>ySM}V-f^Cjj>1*jX%?f>qVt{ zA6BD}Z1=ay_-zz7#^|tE7o)#(%!ARZz!;-9E_yPm(06e!tI{<`s%1MC$7-^4y_L0V;>cO$zEgQAsU%4UIm%I z!$kV5kLu_lWc~m*VPulOFfzY_u<{yw)0-5nt?7;bEfO)n!+f*jb+B0OZ?X6kSwt)j zf}m%y57NY<83Wp*e}i|j8tAm;LEh;>Xk$bScxR#c7$!RlLQ{cx6IvS>^G@IY{Ubte z;oTUaZ8OxC7;ui}QU*)m=AN>$kY64KX#tqnNI^V@Nf{eYH9 zatFi?M)DJwDk?};fO(VL1{g@j`FL)ATc}}wDo^}flK+P{(35--X-4uH2t;xZ-#YMQ zY(EB$3iWYT$Fm2n({I5uTVX{k zFUDm(%kz-dSk6yAB3KRusj=0T^@ToO|4r zY5A49@g8?&GD_4BB#Ii0M7Jy7h5dS#Zy?QBz6^o6vZaK(vIk}Vmf}yLU86V~vPSWA z$Qs2{AQQ!{#*|6%3S8DxycB7T;=<%RR_@5rK+B}~F+>?g@nUQzD=2;hm^a1Ufn^v` zKH$iVT?C32>K>z&Ir873*dHe7DZY>QVHE!XfjM$i^8bw^e}e~TEYF9mvHU7zjpbR8 ziRE_BmdWyJT-LLki?qgae)3Hblaqk%j1b=aXNI}T|^b_9gc<+(rSKcMdOz;$(>2QKP9dMvB^E`d0W zlGi}iNPZ78k^IES2avoEH|R;;jkKHO6jA#rK((OZLGnx#Rz~tS?!98C1M?<%GB8H+ zo-iHBr^2kPA@_Iqtq&9Q{MJI6@ta7tQA6(8idNQ;^B_%E`+4Ahm*hV{oJO((vPSY| z$QsEXLMD<&k9Yvd-{J;6$zLO_k({5LV&P#U9cY=Jyb#3|Bf|^Df95&)Xpr z&l8_{0MEy9gP!NZNNYUjBySNlU>~4m^1KWsmGL|eTa5~y7X$O=c_A?7%+E&YoOxl? z-*;vkOwjY(8fnIJV+hQd6J!1loH+>EHIny(M2+MxA!{Um4w*>Ke)<6<|AHIzB%ef@ zk^B`6a|{p>V+c?dF+kpReOP`6#T6vynD<~(sUUeJFx2 zmsjB)o#PJ6B#N+1qB|^Szz#jr9gt>Br;&lwH5pRX<I_B0SUMS$K}X z12nR~2bmh#-$B;ME`&^EFBs0qrr)wIAPKAv{0%qg$^I2-H`##-j~pX_GLQBq`va6J zMz$|)PRaY(Yk+x^{SGijc9leLvd1Op&0EbYa5-|GOk7 zK(R)0F-X)%J^@)H`A5h^^6SGMK(Z4z=t=$^X?NK8P>}or&@w%G8%h-;xjD8M6eMp3 z=1uZOV2tGJNjj24tMRZwSuWZbB$nySPrw8{zx|PB{PrT-s1D4n&clWWng5pL+R(0% zdjG7}ullZ)XG7qwa~>kjEMe%{5uy}8m^2%CbU=Z-fRHWy2gYg6&d$Ykpn=~G;on{1sEnuw~> zkXX_F15~^Wa}HGTVr#aw zcHCKl8>9iaA)$^nC3VVE&dA$1JNvYcrG-I?nTrkF)=nUOKGBzQ4YW5E{W=;4UPrEN zj~`90V>MT51A!RY>=QZH0)yw^2OH~Hs|Ulz9I|mZY{c?~XcG&bSdv{*$NFI_<~h2h zTH|mR!{tm!*3raO6(f@82LIAgz|pTz(ZJN%Sm zZ0$l5Sf*dQkb<;s?SfPt>C}4G7R{KVGNw9vu2a?~kf)NtZUDyeZ%tdCe}yzAujOAM&p#Tt61hhR z%f0=Nd*)sN(z@L9+m5tYd2&1&)t!muOQF8H)8-?xx6$RVE+6TBK4pEJ#fr6dLs({( zZ5GSQ0eCE1chVaI%gS^Jl$DVfswpEY`3SYPl>V5^bHo#UQL*-q+BL+TE!$xSW$?to zD2>y{g;#NeSgqHiDKB%FYiRoF4uES^e9ZmJ(8u^M5A<_7Rt~TZHwL+WW9Hv*nh&y$ zD+L}O1U*ka>eiF>DA!|#9yrEnWAGZ6TZ%80gCEDcc%YBNyO#HJD_Pc$E9ui0)x-d6 zv?C|WdRJ#rcW%*+p?Zr1IQU6e^m$*mvQMFeIGNsuD^sB?&Jp;O^_0#wEKFu!0-}cN zZPU;l!=dwPAGgj+&_z1eJmPeuK5d<^(}Xp;Ow;9O^qMp@X9P60&}nKaG~MVeUbV_d zYkeQ0hi5g`tul2lj^^q-(Zpw=uJi{#mPR^d)s_{vc~zweNG* zak}K)=b&IkZ?}Rs@k4sEe!ZNI(POR2I#aNik(u)4^LkS>bi@nL^l2}*rro``rYSvz zN4Z}LYx|g{2@~|1G_=Y@XsWE!R7q$m>fv-OoM_!*406$PQ|&g{`i5IGmc22}Q7=MA zpPp`OdiCViRO}&me&w1N&H84_25g^m!fjJ>wbfK*>5tbSnjT0LtT(<{YB~nRfi&MmD@kvs(B{l z1cPDBoPw1x2?pOW!z9Z`f%WIaSoT(pU-NXW<{e92pT@2yit83!A3w)hUA_IX)h1O( zDs3j}>^KO6W?G}A$`J6Z2sLM>)mI8dN}Xw)B3*-JkG+D4cJ*Je){;*0)NnVSSbKEn z73(rL;bLOZ>$4Df#%H=;aU5QaUa?_@?iDMm9cNn$rFu{sI|oM8gwSjb%u0aJhlEH7 zFng$U55GS}$V~_(bn{gRv9Cfn524wsFm@jVW^CcB)@qW2r{dJ`xz?^^F{fXfu#+Bj4W*24GqL)Rz+<$&w6T59cUrmhY{}<%b0-rvttH>)76t&OsFQV4HwsH z>GNb#tqE01UDxFau7~4#_I&Gb=?)%!Z9ZP*e-MHfSfdjzK`867vn9jCbGTOWniYGK zEU=E2K1C{YA#x~pku^ZQyug|$eaNAa^wK%Zd$svA>lbqO^+YpsKt-o+ZYtV?0;0k< zolzmHzIJQzASY07n=El_yAc&P%D9#cIuhg7;Ck|e%Vl1l_K_iOHM@Qe*R8K1pTDLX ztHKZWyk_-nRZzyyNagIa2@`gdagEF&inibyD4HoPf}pWeP0Hq}IQ85jYo?nW%|A8P=WT6%|k0gygl6Is4mLprL~aneklYA225LY!Ldb!#toED_Tu zR=BCXR>tts_3 zQh2xF(kuwq+S#Jj!Z#5rrfD}_eiM|8*HR(Nks7U~>MqC2bmgh)>X*x{Risut6{prB z=Z$;I+RB|F+JuJLZ{Zc3o!zf+yEA`=Udh>#^5p}ZgzkDTJycBB5g{E|! zrp`iB05omNwQev5xqc%;ea_nmVcR;nAC8AIml)R(A*}vK6%rlQ@~nN0zQ^JW`Ht!D zSa(Xs?;LGcTSI;EzuS82MoQn`Xg%mlx(oHy$lc8_C%&CqcWgVZ`v)t++}5->$Gk1p zkO0$cM6G}&?fGOiBMtlLW>Yq5kJDrctJcWX)u{*Ube!j6r(|H5ZPCEA2v$%ld1ap` z+G73>wMGw4=*SP8-}MsCaN-!72=s>{rdnKuz@}RK0)b7n2>8>)n#J@|`ev~RtAusYNFW53~vW;g3`_#^}f+09FF-R=( zPHcmiMvJ_oAm|r)haoK%c{jM>%9?zA)@VHz_MkF)ECS~}mc*mzvGi@l@}X?AumX*( z@&2eaOcHCn*FvT>-ZkHbK>d~xsD;YN1YY%k)IrCr%c!8b0G2DYen75NYVFRIFsP$k zIoMK^jE{e?_6iIhu9bVfE~L8J`Yej;f)?%{&TYYe*r_>+tED8WisPHJ)?7qcJTky2 zCeX98qAOEV@!AX<(Z*G#CUT4qxr)pj2aL^NI(~s?W{$34KGW8)+(0a}X}QGZT;EK}~y9*kx2hZd6@x8SUKq&D>d%0&SF+mzp@$r9UUe zIFu{a9>##9C{aJ+&$0Zf_2occN~+avTVH3AW6y2tF&`2O)#Xm>3BRocZMtuFOucLU zgQJcKCDt%Me#1OpTURa}_qAnmslJ~ric4MnY|~A!FFzR;vmFPT``d7UY#hZ^_r48x z8!;cqH(zjXS#t~6Uaz?NKVYmtpYyjxnZ|+*@&T+O?JNQ*J0F6_GLX&VthS7FM}4%n z`FRj**MZGQ>(=zGN0P1SJ8+(tXrfi`8(N9>#?0vG8O0m)J)5+ZF0YEZbXp)?e!v~b%bbji1Zl*>V}zSKi#DHP9$JQoU{c3Oo)>>FAzXeih4QOmZ;8-!DBxGbSVbrZ-QWog?;NF)FdGff}5rV zNP(slwQC()lv*5Xt0g@L2!z4pDz?>9OQbGU!S5PE2#&KwC)9zU=aKch;?{Lr9b{-x z4cDx3VC!lfVZeC^%z#r6m;py2zlB`Snqa^aQ=Gb|G<%b_3frn~Q80WiIMB z0P0u+rcv9_0zuz4Y>u>O8}>WFYZ9hZ*9O#T5^r3qNd(SolIaamlT5FMU7i2RG_8I3 zV|AD%+K1mlX6?hTAy9R)7|kB<>I7N~S$6>J?rvmTM&9NESo?5xV?_H_)!p9K9O}s1 z{zyU*r=AmUAL55R2x{wJmbZnQZmsJ6;ijtmhhxlI`><}BZJsYZlK&FJ0_>3&tOyOI z(0Mi(($ehK*9>~dkedm3X`AgU$p;TunQk*ncW?zA<~Zp$2%+sE{0bqpz3oG32L#pw zpH3qJlUh#L3_$9DAFYE>lZ3Y+BxKlnOY_9N>bwjD6L(k`4SeBDTV*w+qwTCzAF0tj zY!Sg)EU2Xc777j+bVw9{`fO*LZ^$qVIz$1vj1O|^vpo=N=5?}tBb`j-YUri_>3gIm zcZM+sAgmI#wN|Y-H@Ve8Dv^6ORy4v$Ne(Mx7%@rhhuZ_HxNrBX!f!8#aXR+(vt99( z`ap6Fw6*XHnh=dIW96gfE*+>IY%?&v|8xXA`Y_uUzmagwyD-;6h!|W0$K#xk?`R9Z z>C5h5+&egipL{%kB; ze$r$iO?xWX>TVrsvltW3;WAYc9Yx!W+7ztZJ>97J30xcWB#Pz{2-8S70Ab~mwiIbE zghPaEgK+Ih)D|Ccp|U?3BkLg7e9AUPS^(kAr)({xX%LPAY3(w9emf5W`bW75=tr^_ z0llJ15#Xhvy-tHwXdnVCko5$#CQU?uBWyS^P>ky?2E=GKk35Yg{D5ntpT=tzL0Cw_ zR}eNn4F+~XI7P@72qjO0fe*Mq3`~3;(3~_e8WKl>2I)AimyAM;)ZYCtfb3BS zGy5UDPr|1V_K&hPkhbu9&C+@M#4TJ__qaI{E8?}+XHrW>8u#B-S z_i<;>P0wOFKEiF#IFh{#8XciCh-Z(Nh9No)1BC`M=rPE8gZd!N44OC2_OZ^O-)tTX zy%p{@=nay+3|bOi${;Tdvve9>78=N)8Ibh`O$oWt`X@sEfWW?8giS)*{+dXcX2UfuAkk{#em% z%TbcOZ27jLu!TZ)nHoORY1k_?kS)6)>uvdjG!5RJ7Ul4rX4|ZDh7?pJV)qdGok6GX zUWL*Y-L9Zxr;zdMrQss|N>oGVg$B}m4zk{&Vx-{=?HsSaWNU7ersKh`7TfAcjVDY1 z@Ow5w#%KtUFGF||LaUb%JNiKwO-LpL`eb6l#wQayx)N{<3liVGY?~;VA!N+7wUH`7 zKttqtw_|MaESOiq+=gEy*()=C4%59l&kQdOM|Bzw3k~$@MUeHcejp5==3lW5)j7rh zPsd2nX{s$WO@}7ZLN##p(zbYMh}3Ba7aGWx3Xt`-lp|Z_*!D78a#)52DjqKJNT{2a zo+Nwm(k)cSOPLxhIt^`v2C}6kWW6m-k!AraY`(3vj+_rY4SKV@+o0D;_A+Qud7VK# zqr5cC)M5{VA%%yx4^nAvNbR@K`ExQo3a<#2KXla*K-P`7b5)yJ2WnmoseZHngxVT_N2*Z0U>DY=XC2F-^*xU^BH=kbgl(y*Y`{@ zo_zu5!g=HD45yl~a@ zMX1-8*jAf{p@(ib-N~_XsV&YZ&BV3csx3mAR?g`-s@i54O{>9gxfvG6pk=mgjO~2$ zJlZK42MAex?2jTdz-+$x2DXVw;)e?L)-YoGEOMp5XwL+e(HVyd4SUO0g(%M<%ICgi zOCicJR`1yLmhBZI2s*|R$df?UB7?d4DkGcpOzqqwRULV?gUPQe?l7{Ws6yyyJN(85dW{8#E!C>{6x|HuZZ$rD|9>9;#S>j`Oee^xIqSRnRlqAA!w=TEX}Nk4Y`m3c zGnLm6H%Bvu8j+_8wTT=CDi_$_ceHkAraRMq4sBR?fg5oPNqh9X&QBE_O7js=TmZn z?FK`6yHZ@vE_-XDr|c^Hry(Nl_p?aH2D`&C@~={?<3>b!5;E42Z7?R|7|TjLFHB^b8d zh&0@}5Nx>fYfZzQ3< z+tzEp`5?}vYS+aMuKVh3v*GYQUyPcnAC|PNq`tV#7T}kG^zW3$Y3D0jnEW~*eT}Dg zZbRLWhIFL5s$9o#^#rAxAzewGLFs!)OQ}ekKCumuA|VVa*AYjg8H++8*H>k_>8($2 zlL_hfKe3rL0}p;;d&Lxv&gSA6i~87h+X=c*h%kybUtpBdeb9~HX-h8O5cJ%*R}#su zsyN>^HE0Kd5guX2rLncbud6RW}zCa!h5$mKy-N*MI!OqA6crE~DAJ4tq~)qGRtUyI6N0EK zA|(a|1u-ik3IYkSfPjEl$RhB(&&=G-W*0x--}5}b=Z}5unfIMJGjrz5nLgu-C%^0F zN3RAalnZIR1c@zxp#DI6{cyd&CWY|pV<1`f+pGf89U`Y2CnmD*_T)Yk+!g~PndL(- z;$e=vYA{x<6=;i;dbD zU{^jtgV_{GrXy7CD|5%Drx@`DHze?Y4YwVk7ZLbUZr!su2hrbX=$6#XFw=+zqFQNw zdo$_pZr$Io9JaeMw^>w}{4h~`s0xhCWascGqSBd3(fm!#h_x?g7&+x=;7Rz?B!$d*RSXU3c0 znemu*pMPk6!Ck6F=0F+pP^K_X+R^#pBVoN&8}WAm!<1U%CEf> z`s#jS9HRIU>GF847RV1kCWm zmLl;mD@M931-%k)JQHR`CNu1=!Ex;VE`_F+c+Zv!XanM;?rn#gF4hhbZHr$U{G|Wo z3x?_0I(aZ8kpex<9g*Hiyo^*U(FlOgigp*-FT=^9J}xH+`!02lx9+ztyY698&gE^FiRb61 z`Wx8jy}2>e*Xn$6O_gtdHE zehAV(JeAGH<3q;V^23cBX@|42+=iq=8j^+hr!sm~`n@9jmIQXrVcWjU9hHGKiz>t8 z4Gqb@54a(zvXJgbL(&vY3iPSULb@Xj2{kh?Bu&`FL%H!}P58stuqNGfsZSS{gbF}f z5+ccxu)!_yw8&{BOV|YYDj1H%2qO$fFpcKH zWg(E=Rk_RLWwp6(HGv}whqFD0Rxj!m7*If?t;oOIf$|z)i{x`YH0xw^4v7VUv zV0*NFagNj@xdBFVfAqTPmErVnbJzNrue)3<7n44<-{rnP{#oe7*^tEB1LtNwKcJ?O z)}(FFD~p;Kh9#kXr=W*bNP2U=xqDWH3&R|bZdOBo7Dbr{q?5Qk>$MZP=5Q764ze}dUx$K!qn~B?)OW@H0Um)z z)3va^F(~nD()cV5W_7&%(=3flZmC=2o4_NmICz^;7P+;4>ID`<4Ywhj@JG6p zGr6z%nV0^B^20zke_`Jg_QkKcn=?=#B^Li?u&t5kq(y3fDxvKvP_P`&1YR3~IkE`t zV;$pdII!Xf%>m4D4sH0A)_kvw{8w&E<E;hH_}cQHPW_Saj`-gwNP4ffTc9jHtQIrRRLBTs;vih(QM^e=etc?2Uh@VYDeLA1#{12k|NO@n zU5*jK)<%9&J>latdY?R@l`&dZe0ea`8W|ZCbq*?m%jjs*IRf;Vi?|u&f#7(@y9w4i zB4aBNvl(V^QIH|>Y>uJs*9=2l(cWA~Qkqq3AMkl=-WRzs&YGyx$2@4l8wo$66LXf; zjI%}s-|1(F228bI4+`3G&v@&zin$zR9)S|LHpyyI%%yM{5TALn^-e!!<@YW&V~W)h zv=qd73=vMUiYeA;_RbV*i1Gxm9r&m`3gXlhYl1Qp#7z)kQ$gH*8V}9LNR0#d!QqvI z(%9TPt!7gmzAJ1Pv3iZ%D%@qPW(1m)kMFbwDj9I^yVGhNz!`X$#+qj64<}{U`QS}} zxAw&g!VDv2B7#TvN@NfH$J)V%X<;k^t64rw3!{MN`Qphi4wC8elQs+?>^=Qc27KpY zMQ3it(nW(byuaHYR|J6G1UwmCfo%M@zsuUKhj-E|C`%iCW2vE3ZFA!ec9->GWANo~ zT};OP+wYh@5(54$DVr+ z2hx=fVQ31Okaj?f{NliI4s3Ki+U<=?UZW)F&Yi-gu-9nAc$Tq07FfcGOD-O6A$Hw6L z0T`UqFfz~T7*%8#oYQ4N+Ec*huR}%t03!Jo&AelswL)+!ZSQW9vh|RgI%=h5Xr?L^ zXI~uyx6)c*iodfbu#9(XF>L>OYjZctbL*|61j{q9ip7}YC^BjhdhlvoAe;j%#i)ho z7`HUQY7JTdusIu$z->q%O$~3`086u86yVPrtgV!-`_Wz5XnjYC*@uqcMr%UUSP=W? zHHnY3Eag(*B(icG9CTlY#`*Rn&cawE->=qz~&_m*#cN4OM=fGgjlO2 zDKxg++A*UyBB{oW6XyZYXs36YGD2A37=Gi#)z*gXW6XxgPVl#J+auG?C`q>m=0$fg zAl0W3hLv0UD)IPuwA|WXiAF9{wpz8=`9KWG_atueNZ_wX$$_ob{*=I~z`40B{$1-+ z8I&x;_qo>#jYX@elU7}3(rPMAn(MBB7pn397yaY@k53R8C3Fw}kKeEh|7W7`nA)D+ z@ebF!)>c?(60BJ3_pFxa$#`!5RQLc#_WUb)^W;Jn5d|atb={x zH^w2JoGhRCYhr*8^u-roT1Lhnc4HtqTUUGdv;7}gBYZfM1z%S@?5cOpvS7if+vkn% z!BUsxjLG^$mbt@fkAALFM5F12l(E`pU z!c0@=7f5p;9Yp8%8-YXvDPs!{^oR~UC6G`cS6ShHYjl&-0`UhDhJ+qE;$mOow|kd$ zYr2toMiKO)n^<7o3&rQyL11zMXt$1$4XcF>t2AmK0lWGA;3lkMw>94U0&@8R3|Z}N z>%-|4&B1aIUZKF!%xNsgJPWTJ!%9;%mS#?4Ip!%H`xqFOW=It#COU zd#ww(y&(m`;9S?BAp?WC)!;fd;SL=>dCXQ1e`f7&y12*19^#r1dxPSaf#C`{|BHxWEyb`O2InOZ`5;Uh2pgL@ zp=WexmGH9|$P-*2gC(*M$ZqodD2T^c)?Y)SgB`;2OdvPu(^L>2vWlGa=wPhNP;Lr= zWPEPjN;SXAb4-k`!N@bGxb13)ldbv17q7;`kW>Q9;v}*$U!X(i&2%kw$uR5cgHtaP zE9BmICRT?e)5I>>iCy%P=G!u`#fnP$3`+fO^!clmzzth>!_q)2Y6=5hSdO~+{@1YB z2dtebAq{41C?V^LN0I$%h-1xcUGW`0cr|*a-0w2BdO&s}8@k@+&ptjNven^kg94n=p`C-d)0<_6GM#d-wm=d5(1eWAPw-1J*oD9Wi zr?pVB+jJY)!Dba3wBMoN_3VJ<7_fOEN;A0gzr{GtTbEX@KNa3)4 z;)90+$CR1G9Sn@dao4_9^!hy`dNqVE5Ogv|#6tS;vra zms=jE_cqba=NPrGp#B^?2rLDdV${CSG1A6bXk#TdL;;(B9NPFYhB4#NZaa=!7b}@N zT#lR{tdANM6Y{zHg!KfqyCsm>t~-NCe4L~+`GWlI+bs7C-x(yVjp+8s`Mhc%EqMPp zRwCa4Nrv>uypG+Dj8r|4mB^N#vIdi$m3TG}d@8jyFaHKOpGr;h#c3*4rWG6BT0|S2 zn-LjFt`j1XUnWho=}GTbZSAf+4=>pC7LTdaB}87dc8o_MmGDx;l9gvE_JxO2)uI${ z=^<6d7k~3cgHmksQGF@4Q87+HME_EZyWvF^ql3r>#fTL`&tjYk4{2vSi_y!& zI2oUMy=p z<3WeZ5%nt-;|fHV^j_Z>$EI`E7mWc^#fX-lT$h8}1KiGCqQ(Jln1srb>xbn1F3i3} zx&!%*_w)3!Oa=0*EXytL%d*5q)S=U{#DNW`JTlLrC@pcIUV7ttz4XSZUdjZ^dg+fC zsX(7bZ1PL0){p8XrJvW!vmdw%w1&uw*1oYTKd6`ga{%ci*HEy)vG$IRJr}Ky8&g_> zb3sstM8lrj5^1`_0(Yi#{{?pf-1(QSZz@+1-u%0DX6(1`*E2l~X2eu`&*fP0yR}X+ z-;FLS`u%LhU)Hf?X-g~%@RS6sCyi--1~ZN&cgBnoup)z2qhnOKIlxj3+7H0OBgQph zz5d3?>tW=QwziJ{+xn+sM>0lSwGR95C3+})R2SM8^q=?iC22PJn~`SIB)B~`rNGA> zK<=%x_8Q<_2o~Dxgl@4no<&(Pa-ZzM4O4>m1i~m0I^(y2m8Ny zc$+69YQxb{0WWxN|6aSTzC>5cq)tE**`A;6sqDFH)>h$XFyLK`;a=$3oShw8W;*s= zvwo?>GZg>kpyb2_%590pz;=m-K&(tOO-s~(Z@G!V(&G1Bj<0T77b?m+Xvhe~rWut3 zvOUQAnB%Ui_5XYY@2Gt>_5T=+nPbaZ4t4_9)1&~-{YIH z#1dqC%BZZ|!u__5-Mpoqc4sT3?9hfZM)pC zMcK2dKHi<&PxOX48)52GZEaaZtZhtA4dy(rk|CoWUagqP`9m>n*o*R@ZYCEDRV-fX?=C%Z77>E_k zp_ko2+-z=}s3d^MPr#=b5c3o8sSfG8m|&YqCW|^0vJoP3xoCulq!o9p7iETHpTP)I zV6D+vw*k8b`0y@zKROXWC?A)A{)CdrU<*I(9i6mKe7S-zKl3k98+ys6=|AgHg)>L> zOl0GdY{6vU8uSWzZ?OkAWDRiMDq)YAw|{BiD6N~5Y^@saKy*|@eG!e!nQW7Ib`IOR zqKjAxPdEM4xB#U7MbK!L64-)d+Y8EW1j~45QZJ!jH@DJF)iDpH zn*vN%I)B!@r41JXA>lNWm)_F0Qu$$>%ds)dR^!LsYh(LHX^eQ6w6!%;LO{IT7V@}= z6oj<5b!PTZDHVQQF(c0mg4@|IC&9n5)@Zji((*HLPSCK7> z@~3kROaJ$`>P!D3_Y=M09V83(hnIedr`frR(n0B$SnkIoMAGD3(J_zG{|y)~{Y$AZ zIU|r}D)^{06#ReQ;syV{qP&XO_@U#>psD;Gh8HBjUhHC<5I762UzPX`t7hN|hKR1V zp~?h30Ka|!w+)PR2k43bJsJe)W*hn6Rbw8VVvwrQ9T^@h=AEQQq*BT7c@$koS^=?2 z9eKN~UPtT`{@>`xKW~Tvn}@jmRYz*zN!O9@K{wP9Y&Z1OktOi(b`MV-@$&GvjB@JP zhC1@d8}&N!Aoml!p)-;d-qW_2ECkmPea`(cXd=f3_2OHOPAiJ`u#S1BIK`K8R|c)OSFDSzcGB1r3Ji&1JpsQqj+mCx{PM?c#rg$lNctag=q zrd`%~Liv2ed#KoDMrX+DSV-qn(d?aUo7tqm{VI#xm=(>wggfHeS{Hi}JNao4`*L$gs1}YuTrv}~;*%#n z?D+s*AkEuXSztu+vtdi~Y=Nc&tFf7u7gq!wxhOI^D}h`J+0(a}b;i0x zl0+$K+vS(JviN$vhTL@eIWL(-47CLg;4ylX5$_xbQ(o>_rrcx;Q{DiVWk>1byYiMJ zIx4vcL?d$}OOCwoU3m|}i+fkzy>RGdCz|7@8kSuGJme3vS?nm>TY3nSFy+ zt}jXx_Y=LL@>OKMy2Zp~c4nAuBo$?q=Y-%dkXHmso#T7yswGiuAv(tErI-{90ES6H zTzowowj1SHPUX36ILhQEaC`z}1e_4u@Dqe~c z5hs=6sh4;u5-v-TleD)o8(!R{*c*<9rHD<|o;LM75}h(h)Id>+ULH=sL;fVxz@snM z7uz=gsRllWWQZELVUnnU<(@T=itQBi4aHV&Da9*kvIZX0F^?K}1XxDCsDXSgcUC@1 z%>J^=ky2n=_&=4HYlOSR{_~=Xtzrvl^$w??s18m7GH@zNY$OOOv8A%azF8%!-0+9< zP+pi2@-7#TTGyalJZfD7+`GKmB1S5&jfjc!_ARe4cyX6k035u$+UWhH&JEkZ4;dC< z?m>C|n}_xAkajQ1tBlo`S1CX$uSrP8s`ol2v&ZkXjZ{%AqU9^{bDl2t(`d*-mgx^A zbi;a-FfX?I=*~>BO#g`yx?NNY~ci3H0wXx7OuPu_xRbiZq1j1Ap7|fgm@k~ zaQ!11yWrDxY16DS01-b6x=p}TTxdmwsh4d>mi9-3NWRsHc`ij zTWuGlw~ICgSeLmT-0q!g>nqcSjjxrrBOSME-Sv>ftr%F*?OJCYBW^jsQf}8e0IMZ# z-H|rhFBd=0R-?R+QoT9P)>&BxqRV{SL~032EVIEsr8832S^G-~Z?|J5mu88DOS2PF z*Gc<8$G9|s6?f9M0{dz{;^>ArFkk5~FR+aY4Vkz?lx_TSY&%PQuRcrdR6=qawseiHsc9da|1ja0MNFZtaU3BHc{q4GB(*2}g@vYjk#6AmFu>VcEmAP(38LRTl#*3fIg!#w|OrlyJ=t*pkg2+$uNQ1`BS1O<~8wV8_F>9~RfA zt-2P6Au1bbM|F(baA3uaw6B4M54j_T6>LFoUMA2{yv4TDF9fAib>@I!d)o>t8~Cnm zuGx;p0>^sTSMS=cD|Ju7`fsyYluJ*!99Op4V*HeQK!to@Yh+Yffr@w7+A0Bh5oclx zt)!=a1a*`25QVGTC8$`xdvHu%D8$KO?k%~yCe$m$w0!bVMSf|!Eu|0iq*a5{LSI6$ zqMNn97#ob4HUO8dNMsL?eQYKnFA6^&0;v=T?Z`!_av-%lRIo(W0huu%GcFKcOFVTUpyJ-Cp>viW!i3BNpXIsEzsYw zQ1k#3M=H)Sz3F__(5v2Q&WfjrjbT2x1^a*ac`Pa+kGxmIe2MtjJ-ckJLP8-V>IN=f z=yJTW%l4D8T{L11GG=b)jkeLSJ;P|2dGK!`09Nrhq-!e9M!cb0ip@=i3)zY6R;+KmzMoudaaUNe7l7%*gk`R~I0klF?{p z_H(v}qlOt@#Z*zpPi*Fp6u57~rd^<}>L<1es*)v^gH$C&SHAj5UL{K``*FIU76a@` zqjp@!c$EZJY}CF5w&hx86E>{UhGVlxKl+xA2P2-oWdu4VaL*D4>rcQPG9T`#D1rXZV*z!)?R%s7*?BJJ z#Q0##7q*t^S+qY72f#|pjM%x0eSeTP7x2*Lu(L+zX~j?bS;u-}o3j*f4Y2S7u$D3C zRnnTedcbBSZsq(qStaH)$_(00_*zKQTi~WI(|@RA#4SfG({BSd|IVQ??1uxemO9Iu z2W&4<$&^ForhmrUMk4zybdypi36(lYB){Q91j7v8_agVP4r ztL*ac`P|hHt{2(X*9x(V93Q*GIgW403#OJ1NGgz|_Xgqq7lX4E=;18u@xiT!_wSDJ zH;yauRC-j%h4Qi}Z(P4D${VN4qGV2gdt{uAoj-)Zp|>X^KXo~VtU|eG?WYX}>x#$v z;MEu$N~Zn3vbBmkih?JrFm|r^AB}(cT`E3FFLfxcYY@^4n?0_3*j9vkT~uNEjFp`( z0T4nd;P3_G5=<|G*uu7cGO#JZC2%GEn%|DSQ)LUO*9YhVZP$DNHG}KJLx~v20Ymvu z(=pPA6kv)$yBk=Z{~(+|c8aRXPq?>t+9sOUqxQGGY-TH*w!UuVpyTc$$+Fr~O8KQ> zWa4TK&gMwgc5ZWmB@zuJZPd`X#`qcvdMmO>-KS-bhLSbkqGa_`#$JWM zXI8Lf(z|eIgf4{~Rywd%9_3(oav9@4v?gpLzaW47Brls@Xv#~$7$RDNQ zuZ`7%gJpFJFvVXRsbjqUD=@H%mIrL~5!8R3+lnK$VeSN0SHd)x`DtzRki@MRSdpKW zqGP=N155GK5`o2k>%ncrx1QD{Ma-JIQ1A5Y>RT!Q)G^{#CbaAlu*06*LXKiYH5UTU zJ8EkdfZZpTk}Dk3kJ?rlW5a>oJwH0$P}yb)9nLz9`Vss%I$7V_I`U?LG-(K(8<2&y zdLuu+#B0h|19i2#alhLp@k0jE^P$hIZXemAqgDcb%V)Yf`iTR1kBrbE_wxppNZJlh z5fXi_p3UsMe}ApE=vWV}GW637cc=I~I#5?Ko5 z)XqW8f{5vpa6Bmb>|cujj|0*8DqN^U9s;sV_;Ct9_W@Zf5L_)qe5L^To?RY~a|{xh z0OSat9*g)$_!$YriD}FkY}o6#tNrB@*iXPS>R~)BG?0CUSEU96+!`9Bt?}_*tkK$L>7ubl32~qAxCuI~8WwxvU&E z_LL15@_3EH7vj_wtz~)R^u`jMS@6cCaVMsmPrlDMc0mcM?l5^xs#6&*|cWZ>OK_iV&Q{#5sgke5R*XUmhVg;EycEQxlz0)kPPmJ zb?i3OtaO6=+J&r^?9%qJ0W9^jEtpJC3GaGHBhVO@6UL&-GLjA&h^D5Ij*+oQ5lu}X zu=x+;Y}Vq_Xll^);5SrmJZ-yEuYj^`q@2svg-E{IS%*xP8Jq_o>-}Q)HQ#Dya8?4@ z%QxS#FKcb)@Evf|);m5xpDi!4IMK=7#5B-zK6xMRt4AJ9OauS2iJ?^S>qa$1M(unQ zB9bZ~n;2etZ}#i1JOVHL!qMqOe3yPZ>-&=}+%3dX#ou`vr$q$k$6YRH1 zv+EeQ-@sB#S`M&heiCD6+H2z2{gdsbAoC)~Kk%~Ik$=(F-_PyZa@p3>=yo0d-48TVXIt@s>!H;H#T!@4*FwVu#{2MnQCy1R zZ1*4yQwlGRiw>2@Z9vX2ZLb>D^n4%TDGtz&b)v*xnJI>B38QKiXP;Yozz^>ofc_Hn zikr61bhuhv<4_5uMg=H;n3r3LrHaZ8Sdl^7sAIg`fTb9;w}4#(1M?q{5=KKSyQr7{ zn-uxp4Z35s5*=tn{wDAD1;W)2uC=^|Hlgk|knTWUlPd4HAH)8jahBm@+KT?Nw=lTy zut(M#=PHjqvfj9d@WL()YSlOtk?{d9BD$sIkf6(uDkO(TPe3FoDlYG$k>rzfegmDF z97X%&At|==bbbSvqG&sHjKo%p?n z=pl()F|Z<|wnE2vAplD;YR>|@*WZI%nZMeLM!8j%b(D?}q$5O|Dngc93XDhx4)j+B zYg0VAl>sXb*7AYHnmoAW!BL;nVjTM~3eqw?x#a*$3DVL%xhcSE1GVnJc6f5TVp6*i zH!KtRAsslhT4~mrcycQPR&3THJ-HPD%Q0)Az={Iu)8=?3K+W_#fcDy)fO(x#&7 z@hEs!(Fd*c*QN-p#6p5A16J&>c(A{Vj(n+_iL2qE4?qgjz)4p_zBM zLA1qjZ0MMt{<^Q;QJ9yNp(jPDt#tZX4}7x+of=|y`(Hl2z)e3k29vjvPrqojx9PcQ z=xy;^MnmVIaugYz&jLBl?-`Ae$P+-0Ub`79!%bg2&dnqBY7aNPdR#qk_vvmuvKt`*VMu*N5$kqG!1T!v8)sag;E(kw!g`YD( zFbx+5Kaz7bkf&JTa@y5Yqx_v^L=TT+p*IoG8Tq9}@2XKYYK$ct!g%1@;U( zmUyXoHU<`S5%0PMo(Oz~FJ6ji22t{2GBSv59e`V1%A2YWnYtkU=B&b+XJG@Hslfxh z(6c|&#TPex>5hl5A<5y}TBz4(%y-Hp4EcN@T>^yLjkyh= z9vojBlAl+v$E7ipF&spvQL2P*G*`Qa6@gP#J*U;fFt01W&+9nUO%Dmg$W-E3n(A)q zfp9;IlS_w1#Y_XTil0Jb35lvXtTo*K)N@WW3!_A-z~BHA!m@AQ2>wFFJQ@m#44(F zwt0_{QZIXqT*^4h#lE!QuK09Bl+7%Qv3h%f++E=A$F|mm;L6(DRI}0^?%3PZJ6oGz z_4Iy2jnZ_35$;07uJ;?L@%raJm!s@9HPTN>xf?6IE!0LzaL!%4*TNI`>a=5=w3=W4s!hmb)01TIle)p(_Pp?BgjeL;)ZWY(n&dtqbY-L zB5jXx`Rd4PKpx=|4n`#Lfl^w zupD5>NGh-ufA))UTiq4S3 z5oClmXYA{&T8$A~?{u-*{GNiQ8#aSx)qDCRvp!wa^8r#0sa?^#ko2x2d2y`N*xz3V zHW>RSvKP9l2g92qFkN+#31-be&*-LJw!B*8+j`&kmMHN^ceRxwKK|t1YR};dF zAlhKE<$o@TZ$!wGQ!v-dVE^Jx--2At4=ctQR+RI@>|YRd;`-I z47G~h{*$rhEtz@>gI-)X_%M#f_eL&H)eFqyDF&mnExyrH3^F`_ieXtoKXX`9e4wWo zJX({Xj`AZNt*WocM9PXxBp+DQy#}=g zXXD8(Hi(-ee$xSvU?6s}I7U-BK>UF0$W|}+;9NbVUqSC^peyB#*U<4vbfqNDYID@5 zg5wHspWA;+*6PfmT>=r^Ly*gE)_K&>rsTR0E^%386d6|_Q-G8~+^HCvuqxAlCTzG> z9Uvqa+7Tl|SOQpxUMK-B!I7zuDlk}xt~y2%gta&g3y}tlZ{j^~Rhyf?5u<9HsZ$e- z|6Ppy`I>3tCz?%rk+qk3!x(x+r14`QtHgB?314KGmG|I2^{kqjU2N2j#G-;ExusKQ zC^R^e3_<7UhECcTdP`}hxp7uxhcsQ2+|rbaOeNcI)c7>EY<{*mY$77uFLaVV@LIjh zn1NSR@IlD4v6N>n5RzvY#%4SEs}qGJFF|TWLXvUNT%n(x+>(sZF%L;b0D~l(u&D#o zc(){%3{WjxlI2K;Y*~nu3P~hi_94lY8JutA(=KS*vBH)WVkqz`+$+VEeZLDIF96Y4 z&9iC;lIHtO+|n%fv5NV8@H0+C* zrBLY;7wX*c=w5Wd2M;AhHd+87q5ekmP(n$EKuNP`W%UP$QHr(>y3DaYx4T9AhmLuO z_98H$q(g*~(sGa^JWnbqrRLV6tyj_~p)n1W^l>1bO8OAox{|Jp`M(ou(J(0KM-%={ zqC!a%5TUm`xsrzBLqjF?2SV~ZgxR7Mr|?c>)o|4=#7UZ322F)B9D^!zaaKc|Qp87e zjKrBD>_8PToWX#mju4v4#kpj}|CXjsfxdWZ>IAqOYU)TJTvO9B9*%}QMdfawj$BRa z)zNJXxSHau1&o1*n%)65eR=%92~}6q>kzxQSh<>>#|ICwLQQ`JLSo%K!^P4^tA+Iv zmD1Y|J?0WE!O2-Ez4vs?LqWFy!_68^*oD!MC^}lS!@vi)dFle(K!B;z&a z>^(l-lmXIHsy*Od>8|Z#qWvNV4xM!Ee#9OAv` zVA|`1Pg!GJj@?t$wZc3ejx%;ItYODHT#S1}>2=1V6`~`) zx;?JgktB715Z^PS-5nsf=ELQoZ9rxLA#KaT@aW=wqSBUI%6mbxu;Z~fOdEv4hRn(> z-vKKEmJ_C_I>ybQ*cq7(Y{@jp>;oi#cE(pu)46@q8%9m2X3UhY`XfWG3jHtuv@bHeVhiwt66n{k?PJn;J&6LZTR+BFP3({ zIx#@Xg|FI6Ix!OKo{~=eYM`55-G2}^T0-ynC771e2 z-c9pmdxEu$mV}#hV-; z-{sSU!L%nGAGZK8FHkMY0~p`7U!Zm#z?0-T_N3{Aud?cVa2oj^^~D$9N;R3SNfmjw zvHc4$o!}kVLIc`+eFIzQ-k%43aRcsZluUQE7(|o4H{xM%NTi9~aqF89DQ&oIvWeOm zi-zOl@B)Ci1%+{$)JaeLGiDYb%V1hkRhz*B{eOh zS0MUvd6~YYM`Pg8zBum=W2QkC7$3E*dIsINNqO!n5oX7Yg+k&q4%U0a6+=ZgP71t! z&{mEQ9t|rJxDE(4tPfxy%Lf^mi^L$K#Nsi?n1@=&r984Pq$h^RkLnmnG(`+D9s-t> zi`#R*TZAzi8pSGV6t69!F`G=xttHB@B$LD8AS4OR!TLVYd};xSGy)N$Hr}fOQU@7e z+}4Y_Csm$(I(={foCXm-gA0k1G@lC27{Vo4jv|$kB+^rouOlAn5c6Q3!(R;_8cK38 z5R&8wOdX9MGCYxex>TK&ZlTeyp`ZIS$S~+G$691SYT_2rK{`f~tVL5*Y0^|+vzDP} z;Xp?4u#IEOGIgaX`=2~qy1M~@?=B64|CRBa-79VbH8aUy@~$PFuzt9K6+H_8vNoOPkOWrfY&UFe49dm!fB9!m6aW?GEgcs3TF?yUc`t5;@Ps9Ynl zk$}?!-8HxbDJEOUALYR(Cq9Wf%;#Bwd=7-_@begxvZbrlglvmpW->-L zTsGff^G6vvVyI{DKrcBq8&8B60Yg1or(=UmsM^33gH{G?#)ZjESi-BKiQ$V<8Lz5+ zskTvqqzH+WEeuB=%T21?77GPQ4bb-cJk zY&fdmbp*|LLw!j(1mgG`YJcT8GSK=>^h3V}G4M_GPUS-o+ul?kR$d0t{w>uKr4iDk z{+_ZE2%P_x+SbkbW5jkSS}w8Q>kzQac0V<&*JkP(aekt_MpB^L#L_G`C7U?00TdmmdRjgygtxW9q zng{HabspRfuTzH!ZdKqWCss!5A&FZK8fi4t!*z_fDPmQ6FtGgf9^BY^?6Bjx3T%XQ zh>5VadPw3{CMLpK=ooP;5))xbz+yLeaLe1E4i?U2JOHDxP3mGZC8ElL7tr-d=cOoGj!~9mfAAR{qeRI5;1j@>yr*_EKaUv^>Rj)8 zPwmwxB{K`>?G`Q={%04zx-&ie>Z(T!s7o?LpW95hMGnrRA1r}&E|fJ zNQc1PlXDF}->N=VE8s1kBGx`2hKod=CI4OE9xTE)`b-T8YX`TzJ{A1Q6Cr#L635$m zn*!kTS-!O`4BOxI>|M`<)%^?+{Q+Wu*w+@cPYqGd!M$ed@Mf&jJ~hyE8m4a-3xE6~{8?-r>)Z z_hZ=W?X!?LAMoXDq-zTf`{J4C7fQ~@c8-f<<@?n>!@QX;#DQ3vQ1-^N=%@%Ll)dpx z9N`d5^=mNJUdQ3yp`WWQd=pIj&5C?^Sm>gGdwp>OCItjNtZa$?8WECMZ_(|Az@voODQ9mx41>%&G+-!BZ_?2uPSzG#0-j9 z^_$hdkskJOggwg^el@fyyKoSD(H?~R{d!(F?2^hleTj-(h!1~>{bD;0p<<4KJ6v>_ zAN>*)GY{?$>I2H!ND-qprbeE}1eG3VS9q-y!>b@-)gJC2#DYjixWjIP`$j!0_YJI( zgFG@F0Z%`RKray!Gu(;dj0mMqxzP`|-X2oF_m6)S!Vikf+};b*FXJE2e7;v+Q|+wT zupKkrZ1-U`s|Q+$5`D{oC8DWTifXQRplg(78(xK*`;i?*3tA2atj9O%qk75kM+HPF z@1jQq1erQ2y9=GYakyL%5D81^pkztdVxP z(^iXKOl5#JLdS?(8L;92Z3wXO-+OR-{(C*AoAB&&F(xUBOj?p2lG2s~EXAb7=@@ZS zfT0%@11#g12e(;FgGLTIK`DOPc6j9&B~SrYYt-J;F=APXd8;y`wgp(y zt2lIj;W&mPD31~6p>oeAWQGy5S>ViKoaMRK$4z5z9*?a_kIqW^mH$Qg>HKF zU4z~9=F|0l=mH$w|K_)`r&fkNG>6ah5X*kGYIo&uFAUDNjE=|s1_y}b_q?%pYGJ=B z;ogD$Z!#obPm(lWPtrNkG0>%NP+i2;83jNjfE%3p)> zb1nk1g~uHFzVNdE$VTBuBC~8i-7fsx59Biznb|8k^h1H%4dfHyM)?f9D+KF1} z2D}&2k%1`Q8aKfCn?Lcs_#PZ3kRljxMjhb8&qzlNX8EScLZ@Np`{K!X`b+XVc`JUr zTa)7(u7c+E2KwR)a94@sH*dt?I98A~*q@c0RXb3JsX-1c)L{zu9e$6ZcOp~AAFq@2jgQ#gL2Af-w8(_2 z@d$!vWcO*pA2xw|I@}j{XGrV}_H+IR$jbT%!p00vV(a(y3lCXJD{u%h3La)$z&!O} z5NpNJ0$TsWCo7O$9MSKL=?f$PT>(8U=QGkmY4Zd;cfhAFco!-L9VCaxEV$BWGvcFG<0PKEl+1j(G&wKGH3&IjH1Z_mSWJXz~*1BkH+D+ ztTw_+H9{FTZ|92%q?d>GxJ#QqeJp*3F@K*FV%DKKzWd4y*cBFeBaMfn`H)e)ScP;o6iI&5h1c zNHO(jk9HCNNANFWT)s!{2^sPVU$R|&aFQ;|8#jm2!v(Dnc>Y@hadV8(nF!j!#S<(= z*aXOyPX@*X;AGW{viYSNHScrdwEyh?ve$1-uhPMLU> z{s^#)zo88eLVmO$HS2F|!{s4oW7$gHfVNQ&N!)V84QOxa7;#g8)rM(nfrVf7;HF+h z2a|LAk=E424QLPPA&Fa=xB+d3juE#aU^$Jndw`wuN*AzCW1<8>Zsj&kW~F2Fq`W#XW$Q4dMnio^ip zAJllBH{vD-7=HtExIDOBbg55K+R811aBqr&AxCYXRw+W3^U|pl1B_idM%;?U0Ao9_ zE!PCMDk_~{uBn>x`t6vj{s%L|k@&pkACX$ziAVRch@-QUbY7HNIpi3tW5iz$IYt7@ zx$eP#&UJN~IS8q3i_@+bud7Y`wgoct4fVBn4mz7@Z600s;jh>~6=)1v5@f)l@76%J z`-a+Ter>4s7-rWAqwj5NLba!jhUj3p>);-+HClTB-^qPey653L7tI3Px=@KR3OZBY zL#;VRNiP=Tn{RZClAa^RH(vpxMcRtE1&wK;mc4p@WFWimCWazVWiG50H`R{$sCiX- zhbrhv-@8Z?aiJ)WuMeG`#tg9HudUPLqcqftQBj$WQ5wp`sAx5?85jD;tn6fW$GUQa zy(1Y@M7r{6yQPiDyd_)<^vpcm(VoJoXuR?(dq@98SP@udv^P!PgjxD0-n3n>USim3 z$eNtEyPaWXf8&DT1K^=i-^`ulu}j6uI3u3V3QSH;%rs?QKi$P}o!%86VYJUwPIboK z9;5v=<=$?1TFB2{>K7=)UeTC^o9x4KD28IhK-`I&XAGf;p$EA8d2rttU>HXJrsBQv z+IYit1u>PG>`y75b;4pqfPKA^*VW}X8emT_Di=Gs9Dkeb-Tb5==pqw&cv?t?@x#-S z#^Gt+7lOpt^s(4ACGmczLfkYzR4wt%9{x|h=wAD#Gu7<=5W78X73zl}b8@0F0`H6A zX{bPC!;r9Uh#mM9Oo-990zU{A*xw!LvTS=xWoIf(SE#)&#a@n-V0@;}awOvQY8}S- zte%#gIP%`_&hc&>uU)4F-z9nlg=w&_jqC}^SP=O{3+Q(QbcIM_tDHNJ?5f9A7kp`(Q$ zN`QQbd$W2+H9D9pphbXE2#OAs$O0fqZ0jop(V^+W&ukz+h}$`ixedgn74y?eo%^^U;>4w9b!lDnGdCW{-5 zpC-7yd=Yc2VrYSA&iO`DLj%t%zPJH{G8yHhCbudEy2cb!3Es&rBvIkSqc>iFgVlnc zUJO|$Fc^;5kr~LMW9=P$_r7yAVyOpt6i}k;ta;NXc=r$NdGiF$XW!MS07|GuAXI6o7!W;O7P*i`VabOl=#x6 zw5+PBy{YLDczR9TOZK@)!gL^3@pd}D5DkM-Ad{JM`5?MXbP^mJ#OOl~A@2aPPYfaX zlka}cAwXu-$2=rHD>dYx%wb=A`>Gl2ZZ{C6^`7{SSedeKySGt=iW=U^PA4 z);HSXdiwiCdZ# zB+_eE2DtaYUD}K#wzfB6<*n?2p1}r(*R;W|9QYvLCqc)zwp%=XSlE=-_735DJiP4$ zy{5IjBkjz%WXZ(Nj4}+=i?O!}f^z4k2v`pGHt87UCIy&+y-mPQbtu5zrZ)C?>im|_ zNFk$*eIiw<5>yHP@}D4wY`_SVFn$vEG>X3#*RmlA(c&boL<)dJ@X{7e7Q_9~h);e#beNCwrynm!ZNfLZK^7mu+dIg) z^s=kbU~!}*tZ4z4UMapWlSh#8b|GA1Yg{ltGHY~}07(iN7sFocV1FomEqdgZH*j`a ziNwG%LYvr*>r9m;vn@tc7~*4?KSsy?0agsGC_)4=$g1dV;imQ<++FbrcV8b@W8A#n!ipj zY@?ZUx}uF1pwq^-%-qHPs1gdf7k9CLE_OI|g-j|jjezNeWzaR$BO#MwU`36zMLI^g z$N`qpNGk^ROji$??Cxr}`B_q#xtqN$T{|UYgQ(P9A=r_?f&MoEiog! zFq94KZqM?+fPAr%?)C(~x?IPW?)GLTGlYGKUk{&d@2s3paXFMecB`UHwqO@o20R?S zP4D)yxfynx0)cy*yzmI_uzhfE!I%N@SHVvF=FFt#hsYbIQ98N$ET04Lr-+yd;wBMOK_q3N=_~|s4(l~C`ovmZg?Kfg z*!X$vH83mS+Yesr#7d1sx&!%>uhhh@7JgEJTn0PZsktQ?hK4^~6|N2a9>(BQRvnMV z!>ZI!fA|+)d@Y?(yy%N3V?J0W_1SEDV(8ahF~&q(izu!=*Lx(6jMUmvTv6FRaTU^* zk@#ESv__KRi)Z4V92wX2p@XoiCdVG=Kba!pyE*R3u?G+E&JSO2+2)(>3d+w8Uwi?M zmB=`D<)F7A=}8}ECa%i0`}=pH=t_nRNE{ieee)giHOrR=-xEIH7tf*_RG;z1OVKHn z@jRAmZ`F7aRFy_t!H7%ZWI|bWE_z3g;A4TXpIrMcPtbKT@r^;LP41(MBcK}-;4QP> z+l`;xN_yxnxhopJvf*n4yZp@9rh#zvhHEC@_8ud-+zzB~Jr}+p$TU z?X=K~;!^}ZJtFSeq3z}H9B9EcJ~sRJeo<3UJAZ=FHnhpCTUeca{q=ux9V`0VxAHGl z_)_BWh2cwE$K!+S6a18y6J3tuL+p!<{yh><1f^GT|M}dZ_B5p>K5Q9kf6C}z*qcYK-@JF&>2k|mGY-5q=PuzrvIYt&s_9tAxuwssvh=*fZYZSVkwBNjT zxV^2BW&SnDgri2NmEt@Cub1VR>Y}#4%-~!~Y2$4_>-z&Pa(NPNkCq=k9tWbg{MX~* zySnL6%dl^tNoG7u<~_=k*Jpd<`j%>MTsF-}kht4)I3goW`UVkkzc5#SiJ?RTIJ~(t{UGbQ!-Z(APNT$=r*;~bhAl;-J%i_fU68y{WhrZ$M7?kur5b!X2n0(t3Cdm&Yfk3Z>lQ8%#S02jx86v^ zD__*{_s8`yDMGi_=oo2()GbthHvh+=O<2|hbn>BKeB4qrK`0n!sVmqlJvgzH3ig1G zc_`R4U{J8mRK@v@?%0X;nWS4K$f49NBBgE-DRqlTsar%!-6Hbjr&xadQz%AbWPAfZ zIK!5$&NG{W;eJb8Omo7o&}{O9`*m^3NNSl2MR4(p-dqQN2VKa&hDt^I705)PXpO#h zD_VoGf`_6t#HovqQ$sv+9<9ApG@f!&v>)TTv7P%Rt_Z3$^&SSdv0C=DwImJck;sHOrtIRTPujRKHEfAmCa-5}+|IPAqd zZf&95hngDpxYcb`@=*5FC#)XjJ`fK~v9?t%#zJAHS(~wiQ>@i%_eRQCJv}j~dP-vE z5liBWsPt|XHrJLZ*2zIiJ{UHcW^K`W5C~e^F+>}7(&B~@dnZ5Pn>ZF@*m(dSVu;Du zY24}931uq^I@68KpN4&vIFZ|!kbe}Q_crMKAon5sVintqt4+oAv_bAqfr$H{#r3p7 z?oWW6nr@w8dIZzqogzHwjHj#-_JI1NR$k1~=2%lm%VgOh9#;{PeVYeGKrtY?hMkm?AZP-tCb zRJt_8jPO}&3#!R7eT`L6O+LVD%m?Q+**Xx<#cb&xOSr#?#R+4MnaoBdpbDf<+pLxiRwIxqQG zkB_?Ls;ycxjnvVV=*700oDi{!<&UHA*ue4Pt|c#9EsAm=0*e95t(Jc-8*i<&Qiz=6 ztIbTn?Af7O~3q6CHCa{al& zTFt2R3BSc6R$&35Cx{1DVacNdo{d^X?|*?`zOfoxy2>FlCQobV{aT?|URaCwqd-Kg zLsuCTddt;m9Ym+RhF{KIZ><)hyk&x7mRM^Tm5U~HwA=B1If&BDD9;xl{@iT+U0DX= z*MD1IP=wEqo2mA1It6eDr%CkNIB6%Npd;((FJ}iaL0pZwhU8HnV@L~I{ zJ4)rW+Hq??rKb^o_{XiSXr&MV{t*JI5=Lfekh&TVI5wa?6c|`x zkou;Eji%r|z_Nl=222EJD1+e{3+B+E5qO=xw&e)t#27?e~c3T8Da4J4)2f~$sy`*5rzjlRHm`RUs%u38hTOaw>@2( zPQd(7if(&cQ@*lR3knGnZD>v_+&m{p+**oDOE~R1cG9}us670qht2%f+DdzwU;ZUt zPMMG8S88r#xJLXNDqU=JH~hQ&q)K{rtS`$UHJ~f`_HGW(Uh$Zdp_k#4rITVX4>do z{omh%(>*d<9L|YnNzM$D2ycNXyZAObg(08MnF(1IL6-bZFgcC5(lv#xTJJQ~fGD59 z`^&4|r|2F0kUbvd;n5tH6P1N)!Hn)9NR2v!MwbI(?iuSq;r&n3ru-oH+l9FH?+zCJ z$m(p_$$OVoV-16EvqMv9AeK>JI-0V~yW`;!v!U`=;|w?1bb!dYvlE-8zhl8rWQP=P}b^!!1%ma$ae!c!^uTxJfNFoMu+}I9!7|=5uw>{XwtcD=yKrLjc49giKAA zJ)~|DD|;x{!p>A!+i8r`zZ@#6u`W)S(fdhwpXMiT-}Eq<`HJUxo+-n%8l~GDMY&|- z;q^S9zm@)57~=W5G2&NvJmO}?*l_NzYjl4LWK^ZKzR3+jzb}b1{y@ItuDs!VhtcTX z3uHH5j`|n`1*(yy;n&fK+@sodOO3oLzH=qsnk3emMx3{rLmATf^xa8^do=C$aY@Ls zwTS!0dFa|#9{ff5%}K;ik7J6+Z%*>VbF122VqE+9SAMWYD%Wp7tA4OH3v69jxZrn3 z`7v2dw#%@<)>ZJAw{=~;92U>s{J|Ql)zh38L>7O(36$xifj^;+=3H&(WC7FJ1~l3f&gYJh7`kT6=cNq*(}^2`|PTPhqrr z0?m%M2Ww}H17a`en1)e%NEUlR2Z2qxfF=-wQqiX4nhVx3o%k;w>w+NwyF-=L)VH)> z61P&ZC-bU?5w}9IC$kh-uZucvb1zzLg4<`{mXCdxtVngD_DkX>_hQCr7;%$(F{6Pg zmvr1ZT|)EZWowF%FQstdgllIf?U%%@5LkY=nxSK_G>o|A1Ise0>w#U?b4$KrZPmmB)=Qx=w=hl{Lvs@=+8J(B1bsvG#}di& zle{~p*gLbCSFDYA)|z=?$qrI~N;P<RG{OTBD2=kzvzP|0y}lZI$1Etf?p-6FUl)a+`EAc<~|Z}htQ~ixPS~m zHzj|!cv6m+$KuI3iJ=0AZ^xd9ZuQvU->eNyDt?k9Tv8;H7l8EU7vqJKlM2|*``zQ( z{hPHza3?Bxkg?8qlwAD)Q$N_q>npjPoUp$4_r_)A$uVm7PUAAFk>64?KK{K^#>anP znG3byYVEQ1FwrNK;Y;V-u|A>EhyK+*o>jkVjjVa;KceFwf8E36iz#=p=cD~-;Xp6F z{z05*lla*MblHqxoZf@(au76+cqeHd@lMj>avJfDxSU4N;&K{6>n^7efViB7)637= z(oEw~)_rU>u6AK9j5f0=AL&n7#bdTu)*I=lVMy<~#p{ATn1|1o`B#O{mjH#&*9v{i z2 zH-yM4P;dZJ=2LY@C$g^i-3$2L%3vEdbwTU~5j6wEPF!a%f0FLOX&G6xv3S&3cyUT3 z7f5@y_fcCcznT(-9SlTVO&KnmMmCT_ldXfDbJUI1^DG!nUAWtY3aZD+i*9!yUVy_? zvQ*(VXn#_Otz`gHek1thz#kiFqWo(hPB9K7)7L|6_5gm|r4PHE{)OZxyOspv6xl%X zOEKSrUml;Z2mX$qdutMiuY#c?`5n95HJ+U|-{YhCVSj7``xkOAZB3U3;szKvlIg^7 z8+=zo@4<96RRi|Q{h9JFzY&O&i6xnmiB-K&-tRz0>9wnv&hYz&!c}!m$g+!$z~5Jp zWcuF&r?Yay0&%jsWPaT0S`}uC)f9c=QP@~Q|0jMzH{=L9>O)-3DoB2Zjv%=UqkIG6 zNQ*LG^N2fiBnMqf6?f_kkdfO0T7%^&?M2u(@ckf zon<+Da2++?C`IZ|9@4V5{LOYC#opg&{)E*dZJ|-?@yHCjSh7o0`=^F~C31QVk48nJ z?W!P3y+3E^Nh4C@$SOx(1$ac~0p-t+MWQs5fL#}(BP|2rtw(@V7fxUDccXxu;vR%- zL^Yc^bP&?Fz=xF_LV*2(YPR4(^cfd1GOtCfnXnNCHRF1z4gqJZ@4i zVv1}Ar z9K$;XA6(m<_J4nsP;)8=kN5Q{_>+ov|CtZJgr7YUp_Pxv`&xrnWIU^tRIG2>#j)Yl zZK1(g*FBiuecm9J?4uIPXSiLjSWG6VJLcF}L`j2;$ZK$xhLM~gBk~%Y4$M_uCnp3$ zOP8{_x0ps!EVS+@29NpG83d2{)dqwX^K07`54+pJd0)=EXsOuG_ZI=bxDl>){`mh? zWZ}q*M79w5a2|mo`vuaJBD(;Ri>z~uEi(AUYY^GB_d3M8{uN_;+9(9~IKrcqLLkMs zMI3FH3vL;(LSXp@HDAL@%w7c>39P}o4z*aTI9r1G29$!rLiUfdePH}&HS1FwE$28& zK21#4Xc}8-aPJ55gjn3&S=(lg-i`D`G*|K>%D4<6(@mHa#Skb~d;A6Gy$RD#H@QGz z3HraU(?Nc}_;O@M0T0))>gpSK-RIer=BgnH&kWVoW&Y0~VgsUgblVfHF2b`>4Q)1> z#n8OcwW*EvA`1AJJz;9MRblEU{?90v0zAtNQ@7yR{wBIyYB#mv+EjcQ z8hlhUVapLc=f`%5)da3N1LpnMF2?nEGu!({#q%T7?g3jP<&mE}u3jL5lrexNwXj)~ zFE4pqOF;xFCw}m_T&cF%M&-hJRMkv)G7oNLdravIe19w3W~1qgA3Q9ZWl}JM7odPx z8#n~S$*wQz6dNazPk~tBG)V7RRx8Ne(Y3#W?Nd`wMGeF1l<0;J8A>WqCqG~g{A@u8>t(Zb z@dM3lsm<2g4-8?y*lc-zpqY)b+eY|-A?$Dkrv7;thP_?jLi8Htwa}H-Qb$yHn9sA{TA|;1c2~pC+wmPhAq%Bl==8VU6YNV}$qICM!!)iZlYo)w*+T(IOjP|0m{l?=;{TGb} zwv%XGkJuI|n@@UNUB}Wu(B>PgFvxS1T|_6)9FVx`JWe7Ffn3Bg1ZuDdoylU8lRA4M z`nVwTO9a1OAYYb5Qy(7_3}IW6|Qg|J<+x!kSP_i*cMPoKGJLm z#LGYQGR538k!1w+4Q2}`VXX51%y|?S=VTy<)ieU13&aiBVU?eMXDaTOl{639Eu0{BKFt(FV*Jf3=z=oD_Y*n>;?~yYE!WMcNytwRUgH-O8MzMqx(BNLZHIWacUaZ zRMOb}1&{>3-6MW{$oI!Qh_sY0h0|+6A>K>y4xB0f6&{;J4(;Hw7D!)YX?n;|RyE9p zsYe-xp$2U5R9kEeJ);4*>UlVuJJr@DLVNITK?F;E(pHz1PqlT|q16Z-Vh+XcL+4dv zOP;ii(>;w8zo|FPHkJ0Gu35ebRaX^a2e&xL{TG@Z$DHA~mAko$&)p}SnA;IgJ< z#r+>(OPmkIvGQrQdgc%Dz3{+xDbsDul>YR4@8H}%0^^M6kZKUCwTyt$*8i*I$soF~u5V=bKQcQtuoU+>O zam_8TEi#%nm!Sjy!oy;ou_21NSXr9W2%gJ=T+xL0)n({sS3F}IYWk0xR;amK-7Zn% zKLPoTdoP4b=5Cl>Wyo)m*y^ZKfbIl{g6{KKvX8ovtVX z3e&>X=6TyJTrDATmOU)bnWE7PlysQ2Sb(+fV*KhuemI}?Mp}6TX~Zo^K=_-bWgge` z1-5NQ<@)!Szr1K`OU>A4kvEg<;N!e+@xi$tnCOdq@T4ug8B=NK6pL2KJ`ZFjvQ;m3 z2o9cp3?pjwaA)FxAa|YlAhim%0R+>)_O8=;qY4Jp#VH%8_%=^nLhfG zt?`3Lj*EGAALQlV2V7Y%s-qO|48YPS&jSk^Bl;(@@|SFNlz-#FpD)=|Wf6!a3vKi0 z8;G@R*+hEJpP(fVz-zkmCqSIXF+p5piwmNrP-Ul%tp;_+lsh9@-HMv`c~%yMc`}|E zqSX)lpHWjNM^o4nrM`z}e=b2&K#QX@4=zWMZL-lfn{T3FaKhkORZUIxXGPf*;8|`p zwWoLjAY@Gx~~EVxeLKo?XEFg!&DB zsHWXAGR_X8zFf;~ZK>}ov3!Y`qm^Qxwvpszft0j;+9VAFUu~Z@0a%k)u$CwJvQe+t zZd1QgLj8_m+|<8bKZ+SWPq*V~4?6MXN70ioTV{~iM(SjVa_xW3wl_#wameF(=}nt4 zNKp?$-&WY-!fGFaa~a}c{L0ifZB1NXuCQI>t-T1EC+OxlW*do^G`1of&O z`IOM_kzi6PB5+9LAt1X&1P&gP!|3h<-Uq+cS=qezdx1mfk`;ga7$u|nZzE9@1Y zAM@>!ErCDgAwaeV;)Z=*rX$}Gwxth0BZU;48~8hJbIuRMllFS~&8e5yfYp81)-~YE zIa6%K`Aft?#um2X{BdbpQVmkvAGYURbZ{LZ*HiD>ehxo$3dXyrNzFc_H>G{Ze9q8d@@hXtSDi-j-Ni)p{hBkpEDb4wHE|9x?H;0{Bi?MDx z(oJ|#!lkt~35a=}4d;~O;dSFAUlcf87aP^)hk373WNC>w!G*$EyNQNTYtItS+V=r# z@Iy`jPQqZT)Dagsr#5A)c+U_jt5ZNmA5iLDJF;>r#E7+4RnS51Y?- zZM1_GZvts>2gktj4en*2=d#J}&TZJb_iYjFI8(jWlM5p}ul@0PZCN)7H$@Rj!opLdD;8%Uz?)g}eNJL`d@?zGvuem*N?*~OV&IeFv8 z^3d;vf%rU{RKDcJ+2MV#yvnxH>hSVXRMm&J+2K23n*O7hd1)_+k{tic0}p+=C6&G9 zg0k*My0a)fjx|$RcLPabtG{-}xz4(5@x}mAKa3jTqFxAhN-63Q8m1HVU|V?f;pqTjJY&W!)5rudI`RkZ!Yu`)r~Aw*q%TvA;Dc5xb?Vj~sxkTc7w}$hyZK zUs-oSTF5$FDt6mF9@j4iZHO6UjMVg^Doy94&~zg8 zn*Ig8+E?C(favA@DbhmT?AAG3ICU>Yf1~6+xK7ClcR|U=7?mR*N&P-h0sa2%2p9F= z7nSRG2uk29>N_9nMg0d-4rUpK;0f_p(1RyciXObkGPW)}FCcFvSbYuk!R0+59y2`= zU38g-k-UpVbkQZiD7q+n?0l8HT}#f}jK=8C2O6$bEy9JmR{mhS&UO3mKY${quxb~v z-m(E-o_ZY%n8hIKR~e_p2KO64CS6DWz3QUqzkLMB4U@UNxA4LFfQevmvO-+vE~5Vq ze*QxkX}Qm|Z^+7jf`m6>vNcW^pgbOxAQvA-AQ?e=EfbVuk4x*oBQKyM0rC+L-Eaw{ z1V{=OwhO|BZDJ%dP$%gAs4b2St_tJYN5gc2wgH2nTbZAfW*}tTgI)RAwu9uXUkr7* zu9BSp@iVIAJO%>bavlM~SIz^0K+ZYsI4iwPO*RQc?2l_AmNra&HGmN$AQn36y?p#igVx6)v>%XswL6v&X2P*)Lr z#9R`H^Uj2Mah9OiTez;>Lcbk+|G!ZY1Wr<1EUaiz>PxG!M7y-G7|sgyS9NO{*tQhC2U(?yO93he~VuF@sNYB^lJi< z(hmnIq|d$$vPVz@DEk|^``|jc6YhfC#~6cSOEi(M4Ym&s?~LgRXZYVl-e&|d(SdZ1$*i!|F2 z9~vJ@6ZKTHeT#kD{0h z4Q{4kIt^|JjQ1jSq99XfFt_|VMcL<(OpD$vsK!d8>^sc|kibrpYksu-1uo#f{}3Jt zQFap!e6=(=ZZ{ufHf15*RLqc%*07sHJ0aZ=AHv7AS8CedBq^8p=r48zE{cA`2d^NX zAkl9S?mAHu`WxQ({r@6m-md5nSF+Jv@ByvX(6Sc$IW^m?Jcab6E9vo3c=kBx@hDhF zSjG`?b`L3S3GX7L(l&rva4Z9y?Rq--Ny7i!sI zL-TL;HZecF;1Sv=WJ{sZJsF>;3*rJ~91wBUG{0IJNFI=`b%nnANKB`%KDbU_xg>Yj zC4C*Yo=dW*N?(bT`by-S1bdpPbc3d>>}Z1BY}$^rP*wIb(h*ybCPkeMTla2){V0jC zh)=(Zg;6#E3cxYveb7^2S&BMV!?>OTQxr8Hn7Ka0I2A@JZCG@zZ=W3fu8-Lk?%G{n zcC3G2Y%-Cu})1ZVQIz_|2WUYu0Z6Q1#|hy7F0q)xv6o+dk? zlP@DpIvM#Q2ol=>%+y%td~1ESx263!EdpJ$aN&t&-WfH{v3DAIn|V78(>3!4fgNrI z;q^!1skc-fgi>0OfGy?f|Db&`!WsR&Bza$X6_U(1x>w-KbZQ6W6(AGDY6^{`Ko$cT z#}zSCQ9l?Svh3m`Uio;nPHXD-lqZ_H#F^3-^4wPZ-{hHQibk%ofiJ3$s3>Nnu^^8I z{*G+mn28-vgAV$O@e|ZN#}+pBigBBU>BLw9>_j_=aUf(xIvCO3{_{Udj(ZdA{43XN zs)0g?h;*#Qq;6&<4Czft-Ec>a!EFS+yQ6(C>0H^pxkcK(T%91J(6_ma$}ota zIZ!An*%%1XdclVwNPRCj6lvZI_5(p0R}WLZu0@>@xVMXatJwS@h08)0mmH*4gI+>X zWtQPhyu)*-hLNPCO{oCmHszb?=n4nmvoN^0cBk9(xVY|J#;DYXX=`OZzT*YqCv>}d zj#-(Dbn4tp+%;ryPX|3u?Df>ogjwz{7_L+>9{q7HFc^=Tz(!?4U@KPr4+M5|wXeXg zAOTYm-BYv_!NX5p6}bAHwuP&01L{)J~xFLT!ySgxZWH^?`W< zbtBu)D?zTFLb5)%PO^lPWIf>>-{M03yAnyUE`#WO#kvrPCe~*`lUQjYxjh?(A_P~$ z4aHJ%oG2Yy%&{T_aV!+ai8^Q)2{Q{=vO#SF4A-&MV&CRKH8G5Eqx;Vs`v{#J&93}@ z_G(-;|E|U+d`Nb?3B3xZ^K7PG>c58Xp{$57W?cJ1%?%I=_s z>16jAu-!Gf)ncy=(#dZ7ARpOY2|;T64EqS>>M}6jYL9cZeA<2_NNJ1Y-C4+@8Hm)` z_TEYyh`F=DDHOz(+4dRArKRvfpF>5ws=|Nfc`!c1O-a|_YXmpfQaiTUBU$%t_FN@GLM}j~jmrDad04UwAFvukUm{)sF_Vaw zK&)}$OJ;(&K*V?uO+G^ALqUxH2#6iThL7yCmHVIbxE}Zz^G@Z!v#6m@P}ChDDv2lo z5wjh{J0P;Qx1*HvkUGBIZc`>|aLXNlha9=8$_u8PkFNL*yAs)B2bx1H7*rd97Vo050O#` zxe6j-ABucJ5cOT}?6WU0D&vq$Jz%$l}{0{ z5OWVgVJ;p((|b@$B^|UkRFbvS@Pl|3CsLD@n+5zQ7FX;cdsCzGE|Ogj+v_WDffz-^ za(aP?MIcrlMv)6ZoH&dkPX(bI0rCilc1P?j!iIq$A&h04KeE?l&mXb(Q_>4?(Bz1H zpfTj)T==jmY|b%zE#^FC4-Gj7;8GL;@#Z=$UyT16>6ypyMMpubJccjY4PrOTiep!f zq12m^iaw4;|F#C_9tXS(sk_JR7WU3@`(WkCxgHl%J&X?|13wUi=qB)4G#DRFq^eE? zb}TapbRZs64*94xS&o-dKqOS4SB?iUz5+-Xh)osvoQqF;T&=&in~chPPs8cE(!N@m4dPrSG-5J{ z==1hg)klLUh|btq5tXr%M9q@UqoM`_opK(-NhWw4KX3o4N5sK~hHHlm86P*B(aW{z ze#ekn5eFI?N)7@E1rn3#7|4+#dIt!*Jkim{wPui`L+yyQ4Gm=yb^)%D+9{JfG72a( z5lkeQPL@7!j3ew-3Ihc!%b?cNuw`(dO9rMG)Y`!2j&Rmuy;nFA%pWy06xBgkwn-}- zEn?RW!7|ZayfVbFE-uHoE~bV7yUpEk13BKp$UE`=Y!SOIy`v=fvbzVx9M#-;`+|SqCYf+$AAV-0eVqB&JqkU}XBXQph+p*FSYF=7*O}7TCF$J7ePYHmbx0mN+cW#=q@&Aw+)7#8})QC@LZG zKDa0flAjC{V zDqaH|cvSH)5WZ2xjX-!*agP->_?}~&P=Tqn5pEH;B9t24#~f0jP6MkHHzgbt7+0uO z$vCW&g=^n{6|R9oZACd~C4BoD$LuO@SvbCvuee{^HY{NRR-iCtGB2?u%M{gssE3#PO z8dEA%|4TG8j^VqtiQREv7Ft52hLj~#{}8abE4#r3rL{T zN#D>Rk^Q#8F`Bg;o=w+k>>|$?@r-ZMBTfyiu|9)}{hqJegj0Y&AWs8H9he2;7Ou5gb;Gttjdt7Yx2Z+(w7q1@?pB+=j}D1^t^>Kd5!WYN0&%~H1&Jf_RD=p3 z(O(Qms9|t_3-UgchC0`wJupxrAO>5w2`!VCPv5DAVv_^2Sbuykg=IvG^2d|lq%Obl z>?X&3!EL~ul|*){KQLKwe|6im?BbNbA7#RoZmrVqra!YhenhB$0G^8tL754^wddNx z;U-zhD=s?|HD%aUf&%>29R=8PxJS~Ew@kRlE_^g zhq=ToL)+uV?9GmP)q6v*3+1SFjB?Hm%SmE8Hs3?CM(keFr5gV1jd1l|TR0>Dr(sNF z%cB16XdID@tf;Sg7uj_Ex1(-UJb?aHT03$C&WXuZ@%pF-!$<`Tcx4RVSdNpMTsKia z6r@0MPMIgwug?pT7&(gTC1Mn%vNKA5v*`$aF-~kw|3@g+XF!$+*AP1Rh8;btw4U=;^-~>6DjPh?8}PK8S=JYFUT8;_9b9i+h0|TKCd*${XDRlThW!ghHpYN zKDK46ql4&4A{F!yV$FAqj+?e6o2%odt@#cE*5FO7w{_lzo~ z51CEdkk&aX;EfM}h&T|8cGFFy4GqO;Oy2T%<1HXbe8i3;Z+Rfgfz+$2^S|%jxW_4e z@C1IK+ZzS)D3HNo6MxZbPP6G@qz5o}P52+ZsPw${FkrrhE|3FfHyQEjtzf^+AEQZw>#2I zyYb_x!ZqQ{b{vIvA+3s9qjwOwHl>B$#{@u)X5Dt zEy9CE%yK8YP6%Fm4yjE$9BoPK%k-D%Jc6ErH^HfBT*<<=eOO>+dfRpcum(G!^~+Fn zGDQaMbd2$G(+2ofdTxbiFZl+wxt?2=7~q=#yFuJu0XMRgQ+GMGQ5)itq7jh@K4ube zY?3x+lJ(9yJw{q#~0Q+oZ^YmIEu+|2=+N zju?X}Kel^8cC9!af2ny~G;|G9ca)PxhJ6|0|7Z9wWf-V-=--7@H48QlzvdQfH4wfQ ztO*FWU~gw)LiVX+NGGl$=b<9Ss6bTg*XRd0))ZmUP|4I;x&%qc)G#xS zJynYSSJRz0N*zyXwJm!k`Y3615y_3NMW4aw!Y$zJGqEoJ0i|(UINKw7q@Pc9Ge^%v zdIuT+nK*xS74ye_Z{381&4Ciuf~fgRUYk<-<8myf67jfmImnD8egYXuNz37vUg2@) z((sB5qLu=(>o=VqWL@?-+6fW9AM73c6itM6Ox`%`chF2BRxUy<4!eh%?mk`1yMTn? z);t7f_=92ao7L~cFRxj^O^bZ|m5y7vjC@=Mtp9!;x0jF*+!i8u8}1JHUI|e*>$%Aj zweRb>Nk@q_z;5Wdr5?aw%@w1ZLczfq4Gw9~>$znCOAc1&>A5MuDiw7Wu;K%{vYk5M z=#oZC^GCG7gHFfO0TYFekk40hGL~XZQ60*u`Gw_fDV zt8fy8p-D~x_n`$%X03MMP@+WQflOc)a?!&$LGRQAGLB7tt#fQ7h8IG@fwW|+FNMWM zngkLAq&a`5k3?=kW16CLABN!8rKhKTbRhU<8p)}=5`AuIkZO6;to}glxftofAhklN zyS{?b`ABC`I)42bq#GP|Om0moQl5qV*<_aeyhtXX_{KtWac++tb*$-r}n1pHkSlMw$9n*(+@F|;DJtH>!Bk|*nK<@y;|LrxB|_N{`zGRLYG{@Ifx!jX|wH-uYHsGk#Y5$^qmT5#@y67m$VY=RA}N z`}xUHW~CF-C*6(?G_mv9o~)oqt}pSf&vNoes|gaK%C;;$}%T@=}6I3J}SJMSDpC{_1bsM z_A2qQT(6cNb0R{zd}Cz&s)my|g0J6k75xge-WP4H1-I@PzXhrn(spKiIh*TaSEL?c z#-c6>rgk8o7gIBN%~2{4vltcYe~nSH3DON&-cl$3X#=D(#TYsQPnFt8Kk~I0*2^r^ zQ=_AxVf`9fJs*D-gnEbd%K|Im)?l(2)_(-nw<)evtZ@=+lQ7~aeg$iN(lJ5%PC2a8 zx5;6hNbY(xds%n0X$|UWpIC9Eh2UbWF9P{g1oIs6jl&$xklrN+_Bx&9!2a>C-htgm z7jy%=53U>7eQ-IjQ<*mY)VFcX3CN7PyI(qbyE{3s(<>|J#?yXyh2MBeDz-Z~rwRM? zTgUx0*p*oZhk4ib8fhYY2Uw+8+e^}kP@4}Y0BiD{80<>OpdR&|ql@5{fp9%pVr|cZ zX3cXTZiT>#758rf;}x>16j-I={)L)9al@pvgcjhUPdUPH3V5gaF z%LP`XuiqkID?jQG$Htx(3vlE$>U!z4qXkY%i8WDNX~UJe2=eJOiR(I%i+@C50r|>` z=?_!yPHyY2oDWs0_ z=WN0`===$!FNrR45z@+Gq|bfTgZpTeg02utcXZALzupc+cV-UA79hfbJ)B(HfouR$ zyWG)*x{)HE832wN$u%7xd>-!-`I?RoUVu1Rno!CeeFFGVAac1d=JPva)xww$z6Wz@ z$?xpkA&IdI(XCN|hoHcu#;4k&7vwiM7F9TKnAorQ6|@p2ro29Exud<9@)FLDS2#T3 z&w!WA3xOrH3O!a&^kY=HJT{Q_dGmP>$m^WqN|f~@R(lb7XBVyxy z2z4*lj!N*(G~r~|`(cc@Ymx3EW@gmQfy*i&VPe%ou4}yt1XoLteMajbc&7+R1KzXL zl#aFwfOJFN{hU~(KJUm8&Eg7LSw7aB3WMBvXwkf>436-c;=={Tn}ueI4+7Ti2hqxC znVU`eL72M;BONJB@#N}invPq!QXN)VwAxC?t-KUhz!XQT&4E?wxh4E4Oz{%S=xS)P zxB{jyO0A~nmJci|N)6R>O9rMysS2?9U_d2q zmclUA(mqOM8iRabS-`;HWsO0yxZ8yoECM#_BDNbuZn(^)(yUr;MyaDU2Bo-?1(O6g zKZYCU7qN+m!M=_j*UZa~4n|X9I|Kn|*PqJ84k@hJnMm#vvEP5bf?jM2(l@R+1}Y=k zd0c&ecC<2@ssl=6n>`WU8AvFQ2btxC4zb~KPGSI3devc}FD%kRqF7$7p6(ZW!~?LgX!j(MLzwg73xGG`A-Fl_+& zthmji#WnQG#Yh*hMSnWBN4#Gu-kuET?ltUPj01sdnHN07t&}{Z9^=0ZKPp}v0%X*6 zyqE)GF&9d>TRgG>S$W;jjDH`szH$XuAyr1IDf0VB@a3hr_^3EiZ6?2uzN@?tSbn71 zu!F~?{Krv&Lk?o`d_{eXT#}CZ4bvD&k35gaXOiC79pjbu4x$ff^orjci!~Y(886PK zO!9r2GO<^GcPub9ZR=rQ^B``KPm8Zf0`djhi(6APqz;f{B0A@6@lJIhmw0r}NQs03 z`GLO^Jxjb}08)W?o$T73;Z3VunIq8uwBZ+|Ag*VmM1BHtjb#D}m%P3Q(&>id1LZ>y zmv1;aC~MkyTup8|mK$4T0-{l+^ufRgY)%=4u|3||k11EE#o+G1R)5y9HVeLmZ>Z-TIh0f9z(WVj3n&Q#Kp9}NgV76R!a5NSU@3&bS0 zHss};vw+0#!6%vq7W`@|5DJ9E3ikJE&WbK&2KQU`6D?E^xQQw*)7u9XSOcf2kw302 zVEf~AAqvMZn8x&qXUlFoTH5_z%A*BzrJKhe&!p9F%#ZwWx)nt-#T`L?0{HEvEx+TL z0sL0e_kYuYD^RG}ZSx6PMR?K5bfrr*lO8k)?*Z zc@9V;F?FKraZR(4?xvgZJo%t!`7h3arcuCm2m|5|@ykI#N|^hH^g3*w(b=FA^@Enk z)?VAaJ(?8tmzJVL`V-BDNC9@r=xk-428qyYC??1`P;kp`MMGd$zlem0_z)$0&3jm2RoPl zy*7+|L#{rjKU!7&d{Q9Qf&wA4J#VLnnp&W$r;DaYdmNPpcOxKEc$4P49zf~?nFRHa zKc1sX?sJxN1C?teE$h*|0k7X`>76$q^&h0fydjc0FCaewIVkqf$*ctOJ&*=lo%K!M zf#}C)rE#?9iAP@m=~I{D|#+XK0;J{B8|WTUqAI{p&;` zwGyck^p}&^yb~G8xD3b{8qh#1&@1p$$HY^&55UcL?4V;?eg}7dZr^fZdx$7{lKP2>$q(~LU5x^g<@fNuhnzQ2bLA27VEhs15<+36~HEa zJ}Qp2td8Ca-6=0%|LV>T9cLl&CZ;g8@Y%KTR|nG-5AGCr1N#AAuQ01O>^0Ro*b_*@ zN;_dA@E_GlRVUjik+PiC4((`LL z>nC?Y@ybil3l`JjdhPY?C|!tjKBeodZ;kZ+8qRIX=H}R7tLdDeEN_9e+nUZ9q*;{d z#29Denuh_BZuZ7o65m+lT@PHbp6evNJ#vs3NQu@4Rid>)m2;GXDt{kw$F-dLY|GWw z*VEtUi!uC{KOuT#Xq>Z-X)Fry9=EF_=`t(~q`5%eW-zi7OoKtL5KGK09_?*5Wh0$0 z7Nw7fm#sj=y>tAgNBlek$T0DaWY`|aN)dDWg!olUAh>k(&CJ+1i8KYm&>2cOTpf~| zW~vQLoQ16??YL+l)WB$`k0iI`0S~(kBeq*I+fhq&pCvxsBsn4=Mjhv>>n6DoChR4j z_j9q%xQU(%@a!MXhfuLS@1_rT*!@73P;bT-yoA7_pjrP5h=ckY||MFsE*&VSQ_pVcTk2 ziX?xaLad1vbF)@j z7=+N}&E!N-k!(;GKo_f=2nZ{L#*ubHRkjH^66>}Adj0GZHtl(rz z@8kk`iB){*Y{aoqSf{^E>W@AjWK8 zoD{MFS4baR4!gu}PS2di@ikChYMo1)iT^78OZmz%mtH;gc}Hy}amA658VT2g2hH@+ z-`~%D6Y7Rh;yWa&{1XWI0toyQ>hgCFApswSX6&;D&LkRiN-PZ#P_r0Z3JvNSbQ&C6 z1}tAF!P^2W;>!VGM~(__0c(&X)U1dM?yk@DZo!^Sa<aO~9F?y$)O@o}wb!fKX`ekPwMiq(ee5$WeoGTCwx@Ib(&Wa^qkpp!J~zevc;0 zMfD{xv_=|>&j?J2suHV1rAGA|V6BsNZD>3af?GZK^_D`Q#Rm0b9XD-w+^Xl6h4+#T z>Ly?(_1vNxI-k>I{=aOIeHx)Z>kEaOCHgP9uG|aAQ+%y}N2Mr+moAX0ym7KKjnJdD zLwXUfGIpENsYvUNdz+ddjX*tjvYW8%#$u@PX#{lEllBArt7|p)2nuYRx<*JILH!z* z3y&cG-y3OkfJcx&Zh=<;dFA@!y2hA(yl3P1Z=e>W9z&am|AXXdQwHoABPJ}C&B zk%q2-E7WH!FT%dEAF}X#y*R@YKRaV- zQm;G2r-S$dXHNkQ)elILao+G)n zL(Qp=`BWr4s zo7EPby8jO=xVQ1Z0EW~llYfi<`{h`!k{KOq>rBxUSQB7ezOAS69NN3Iu*!1NFQo8bw^3GGlBUAcV{GZX99t= z0ivA=+;$(jXF5$*8`1ZiNs#L~qw~%L0~cPCOSBJNWipVxC6Fp(+jTKY)B9);A?`708D|yXePI zU*R{*E0Pc%^iM8q9mdPug|Q`(QXnF#RV+odLKfSBbOuA3x971Maov*po%vSSJG|h! zzKXl?z~1r4xj77b#~zDj3@SXqX% zIW_q*{bb65g-JRh zntBf#VUFsB^olC!at-7^zttl((jx@c0`KhOLgk0nz@-t8)Nam2!ph#03jZLO2Khnm z>riU0g-04;W(}-3$bCg%Tnn{pzb*i~(M_j?saej?g%&Po44sA-5sbEC9k=pi?6)gs zb%l;wc_lWwOGDJxfTeZ^x8aZ<*5lYC-JLH4==5kkw?d)Qqx9Uegia3y2A#%6a1YUy zaK+B=;T+=q-10&+u>2skm7Zl5u;d`Mxt^s03=OXdup2$}pWD+pxr$pU?9O77dK0Z& z6JB{CuzZvHtH4AP&Js53RbZ!jf*b6rGP0{;dci)0mBvp}XhC}S>A6)3n{}_ATd}ZN zcK|Eyr7PR1UYPJm)eLNHbefT!v0_p(9eO1$5n#6|Jqc-Xg#fE>bDE6TFd*4 zpz(%u>ueaem57{kXMl!oY*f`E&VJ`z0_S%U$-hmqdQ-G12zlrBX&QmjcGrSx{BLxs)sGtyC8kPa3Zm!SBGx5ets7krzN5bk({ z+Zw5qMR<85tC7(mHWHVQ5wZZtdTx?wNCA-dyw1M#&Qn0DoP7y-97s8TCl=1Wgp373 z&c4+5nOH@895L_H+Zmn%0hj1Ip1pJkNpyTZxUS>#!87Xfjt?Iq&L-N}^?to^HnDY{ zsV**5qO8-YFz5vL)aRWbeKWr>>1J=y@%iwppxY?7@Q%+Hr~5Cr2jb;$faBkQ)$Be_ zd%*Y1qYIO;MdkmUd2|m;|3Ewgj&p*a_C1+rB4WbVR@ESk_e9pc?>)+HlySfP^WxiN z^8@oLz&frh`zL*!X<=IvJ!~{Gax%*pr-j95JHu&U@R7qjl$$QA3&8ni)Sv*o90Q5W z11DG0!sa87R>-3Pb7vrrWB1C#LbACKSYA3%x3-WQwmxN&gAY~g(}Usv+&RY?8eUn? zTiX*Wyvly{xV9WjcRGF;OGEs)5() z@)0faj6lMG{3sUmG33)bMj-8~SjpCRwI7yeEECyfwB=uN1a64 zT=i2POG5T6`|v1P%cJjOcq#)ej)HNV7tGAVe1(nMxzokvwqp%p#{rmF*;Tg9`C40blfZ=VwZDtn$jNG zr*;@!Uuj81&Zzp)O+g&Q_fQY8El^TD;XK!4p^C5#Wsn;W=y zQ1#T{3y_PfVwe|nVvd`)q#1G@@DxadyJ*B_4RV$QNNPDc4lXGJMMM{pq8<{MkEC7# z#-{+Y2kRuYa(qXUzV9FPfj{P}ItOFIHLQ{r2AN6w9R=}Rtan^3Scv8n%3#$A$uoJ_bc2kw(Geiqv{n*Ie;NFOjS8uBb;5T$|kL_WIZ=&g(d2_p>2L& zY*gz4OC6~z+an{LW4zonxA&jXXuL8k6mIVq1tw%zD%{>Hftg3?%GPyMl?;!4$@@PN z=Ze!-GJA;J^*y>mBF>INZ?pmRJVp2&wa7(pRE)GZP0D&B9rXs%qeO2+zqxvj_lZRE zV;@iv&dSa0BqHfF2qn`LF^+*BpFC;vB1q;sS}VEuGDcd)^H3Ea>&*` zfu_P#qKQj0Qo|1lzMi`H`UAMY5qVq(efME!+Xnmxx;Yy+T|~E41e1oXOwRE+wYmzX zfF_W9Y<%wrBWhx{I=qQdo|;`^8K~emX&IXKBt8rhKks}#k4zD<&g6shyQ#%GlMgOU z3gUm~=b`azK_6!$_QGhfLgw?P=4TV|Wwe1Tj2NHySHW1*#5NjXC?q}cXjfcYGsfAR ztRbHt@DUs?EB-j0Mp~=%55UVYj}=UXHMEZ9+-MiWO2#8m~F*F=tc#97-^hC08W89n{@0geMm_2Np({krfedw@)+QcAenz>5l)B9<6r z16TtjNzAFcj71||iFD7ZU+t>hJC*%B93Bgc@!)ac70BZoKacc=vCes-znO|FD2jz~ zFc6(N?{EGBCi}u{f${#PT=sa20&W-3_rorrp_iX{`d|uz zE5{=9Nf*1-H${Rt#EV~xCj9vZcQBBB_yDpIo~wl{9(6VgXlJ^ijcPNnoe6V*%ie-^ z_8n@CYHv6gHj^vmHF%kJjUL@D7*FL$<^nls5oA{DG3Udb^0du|QmiIa2DzU>KLODc zS!OlB#typOWW_xj*j~B0L0vXQ7kUcVmdDT)w?kgE&UN`Q?9*%9%JVTX&k9lp=(uUC zW_@+s$}7blqaE1z3EO}% zK#bxYiHrquTX@;f2!LPZ0?~~LKn4TBm~bUMwmSJZ1IY#w1HEg`SLN9IlVO$eBI~+c z3!Tcu%+w#xByVIa$@$~tFepF!&SdA%0DgJoXozdV{eMT{Ht3pge>@2@DamieP|R}n z9LR|u5TrIeicz9#VD_2V1)vo?e>R!4ve!2dFGs79?6qhfr{hG!85t`Z5dLc==$5I~ zd!OENT|26ccPHxDtDRF=^~!8h4G8xGu$cKXiH>yE}7=EiL!m!20d#yI)QNYCv-Sk*~*iFDdFl5z`WclaaO1lClrCj zOb53#a3hy$$8_gx!EHcWI2vG6wK!DWsOMG)EI(9Tr{|UhEICwt2bl5{xM}Ub(^JmX zf*biiSBe$8ae8jWV#RK>o?AY!EJYm!to95Yx4tvrP0hawn*`bxX;(crMXXJB)N?Bp zR&iTkyY<{|%n%lPk%ip7i^V7vtLK&vEX$xq>$xQZQw(Z2u<=i$Y;7Pn@?|N0T3GBw zmiG8kxzc$Njo(`fa;38pn70-bu{(bjSi($jL&wfHF#6AQ=5^w44MVy!R!92Tf}+4(>PCYr;OAgPpHSATBO%H88qf>6S^RkbM>!rPpvmf!S z=w`cMtw?utze)d>j@L8jmCVTYq&Eh_-5O*iv>M(%md8Mdx`FiZszPy}0{Nlo@F~!8 z*yw4OQtgP`@BR|M`IGa|cEFDSxgjDc$Q|&{fcz>JVBZ&?zXQm_VgXhnTY-!e?`#n7 zybok3M_9G@AI6p3NWU&_tzRnMcoWDg{MP!&mj$v6$jkhe`pBIESqS8!cVU-&V4nq2 zwXjRbEFk4#7yk|MtEoV~VtK9}v5~I}N?auq-1ugh^MXI>*IcJ|7|L3b|p%N#L{P8@wY3+~iX{zzl z7GAH{w8pR`XND=Zi3nyAM;{MEl10-eyH_GU>+8>Bjnto29#~!Ml^Iavd5vl44a5tQ zwXE6I=P`}q{P0;ZUe%?>!v@U9ny-Ie7Rn2EYWU+77T}n&`QxjwC@%RQnhz%i|L3b4 z;&*T=@W=BKfn#0VA2*=dB)^dh{=V#=Ex1S7jY;5%iL5`*)ualT$ok_+I0zy0>iEJv z%07?Eh%iY0zq8OGb@(~^#1_DQVw ziulss-GOJ?b#X6>u?;Z?9;|r=|46iT{VT?~bpk*xEiP zJB=hHfg}(TQVyY)gkB6KA=1y@J2VARk{A$>uA&qvF`}T9Y$;=*1ftRe!WE4uC5Q@2 zODtf8gy;pNUr_^6zGuzMK9%de@ArP+ANgg?b7rqSd(E0PYucLnT+xW+d+cQntc#K9 zB$y)Du*^mF=+Kqm@|u$i*2}oQQl@RS92^nZ#sMFz?ch!)LRrIwU1|l%ee*fs)?=|f zE_67EWiD*(+{hExC5tg5-^0D^ldO*<*Stu9Mq!eY@!KcVxyAZ523aYm)OTeCgvKL1 z$jKE;-^n#w%1ur+@!MnKH1BD_$PdWx;uz+a0=W%29$$j4^mh=O#qj_dXW*@ufcS`+ zCOTUMc~6MZy=F?#eA!_(D&*a+AK$Bw##J$+ZHE*x~wdmJx>iJF+(h9kAPZ;& z7fpATRwC6;IQnr2_NaV^bk;I^oKg;A?lMf|@RGT72DH6Yb`r&|od<0%m7RnePTNc6 z*CB?_{jB?PVXoaW(KaS&Lfvq_w^W!=H(ZXC==<+%u{Vx+4yC1T!8b(w_rZVp(n+yW zW_vsFu@OCk^HA+*SoAO+qs^r! zAHZ-tmD_zc4*WEM=%?LrI!*9jDA~nepgG`x1^d8+5KiPH^D^n zNQaQe9xy?qL#|%$fp#7yAZcv{g2Mzc{-ECi4Ru>gY9Y2V9}u%(Q(@Jh7R9z|n`0Ji zg1`#+qE3dG1senG&s8v97_t`dz?Q2qSTebpvtV6axS6wHom{w?vtVt39bPR=VF8&! zWsQBJliLB9y&{X@>&h)3Sgysmi*|$Z^0HNA086qMH-Vjg7_FdmjZj(6vTBWeE2%6A zOqxO>VG3#bQW`=oSvt8ZGs^idg89MSDJ#4BQR6K@^(2e^Wppqb$O0hE`DAC5MCJi$ zEDQiWA4>L>zfss%BDsB~Q(s{42(r7x=>aknh=|j}_(iiS(oNkOKrbNf4WJtkJI@m& zn?wg7SJnw*Ti|L`X~IiRP`TkW;Uy=i+;BPJMdjZ1W?B!nX}$25+%oMacV0|Ox#5*$ z*~PS!8!jz4F}<@Mr*yd7U3vsQ`zB`P+@2#hU(U+8;nH{$KXaOEe+|*3G6Kc_bo`gq z%k4Mi9ofV&$B#{`9Yf#1Gqi11=1XoO>u%2OG=3d-9)5p>i#dwUfuXWy0Ga1}g5TOG zr?bZ5C+xSzOegCWjoS#bk#^b_osAkZKKS5^Im+Os*1(r7 z)`Sxe*wS9Pkzi?CIP>XSU!xHDZ`)fbhd{jhw%w-e199?gdk19)h_DUzR$k4q95%#J zG}#=F2+XZH9t8Hx1~hKWmGM>D?ci2ZNY)&S8T;;wUN}c8*cki;Sh@5!2zUipDWB2nG%r{WTndH`};$Y#uNu()|06qyBC1;Wo zfhf)jlU!(zG2_#c{`h@`=v-(e5mkIAz&xoLB9T9UbY|;RM2W7q&oNKyrjXpFL4&A4 zlkP5xEl$ilSnY{ZgWwoE37nW=?`%Oo=9$S#tqHBd6Sq-6hPi4_oLYrs%3YcbC^xw@ z%^+U--vs~V@9~X#(x~7n8ijTN=l*^d-~JMw*ur%7OjHWX-eh_G_!F3yjDr;8Rt7ODB`)VHws?N`uR2&c;$)iwd$NQw_ zJ_5|~z6{ZkP}6L;1MiE#`)KFF_#Ievmmj=lhdn;Pe9wU$c3izDe;GN5D`fXc-AqZ6 zR)w5^+^P`G&F===Dkkf`5y)3SHt~T;ltc~#c?$y@$x2Es2EygYv4<>ex(Bv*@T_<(4%zHqkAZ44)ll?RQdZ|ls4O`oZFiBZJ^vz zu%d>m76z@}4eby1R=oXWrthJsm0)x)MJ;qHDh7d=&b!k+r1n635NYXGc$<`niF=l5xbl$*|J?&!Qh2)+3nK6g`>H`8z(vP(Pt8L zTfwb6!1xiZejlR4kP2Qh{zE$=A414wX#b%{aFR;Wa~3+LWhZUNE_>hIm^fRD3K0W9 z_Q-B5`Z1)%JvnSP(xFR{eqK}n@jJE@y(kgda7iSOcWl_jl9D-*yJVV!mej5-^^8F=2I2lEcHv^Ke*WQ85 zYniKUHdmlMadU&3Cr;OQNI9+9ixug+K0;yhtXyH~lcmBEd1}Q_9Hjay-ItYJu>02d z8JWL=kUpXl{)ue(K6q80FR0{4eg;x|bSr2jwNvc3@Wg2rN)~9_KFmUS{w~@#?|j_& z<;d;-p83;6v!v1^GD8e|xD>NcvG_XH+L|6&n}k__&zRw?YZrY<&Xl!{k+E6Db5b%> zLU6*Lo*acIndoQ{s)&$>f$XF(_H}DeatM-nVjIMzBTzFt(rZ|~)|qYCXZ!8V+r~mF zvnbx*%q@eyMb~l@fiiC42De>pS3eP570ZKUPoANPP=szmDu z#4Fl6VqX(t0U}~wkA!dusmAxW1j~MZ&iU%(}pDKb_Dvdi;%J}$z1gD0K`z8e+Zqq~(uwrqNzcEsKwC>s3vvksF*Kdm`}`I=cMf;{0v z%`o&yr0Il@clOZFx}=22wmclUb_z!Yt|WcRKp=CEVwVdkzb(9} zIp9;?RA9xtBdh|ZDCJ4O!cO(A!{Uyi>w;z!lV1b?l6uf8sP+Mi@huvYSqyVU`YVC)Vwg?f z7;kh|qjFYUTWaG~MHV*xxZOsYUrd_6>^MShNa^q;R7szrB~(dYj&g*;xlHkIB+QpS zCC!&UCC#;zYDC&CPWtsoF{5D)NA=B}G#r5>LA2uG{DbHdbFJn5fUGUIH%fwKVdh*l z*`XBv9iqKaQ2iE2pDnj<^$W%mJ%!!fO0nh?q`Qkr4;ue~=U=z0*?nSUdx>)VhO|p0 zW8}C1ghw*27i2B3LgFagT9&xCOB@^imAz9<@m*pV__?@us`Rkkk1cLIBB1tu(-{ZgD!xXH8_$QSQPY~F7p@TgfES)Ex>er7F4$x0EJbS~ubsa6>%Sb| z?5Ol@-(cB=Ge>LvleTtEmM9F-t$n zidAZWTzdks_V&|Y3?8o8HGPfd$<=?6^HTET0u$<=AqGcZ0OPZ4^G?Fr!_DQ$Kyc=(kB9&bxuMP@?o`5Vo5PDq@JP`Vl@9mSE z0+aTl63v1OED<-67eP4r7UM^Ox!H@8z&iaP{C7TOI{62CImxO3W#Y0TLduHBB|pOI z&V?Rqm9yeMqKQ3&^d@R@byxmm_YI$nkNE_NYeu&jD{^8L30@wbCi%sag z8_vZh^xh4ZVx!{hy_234m4torcqK{hAYLa+FC|C0j@=#D&L6p&BNuKRt;aI!4f0hQ zAeHiMr>K(5Q}#jx&>#uHK^uuCpTknju1b4Y zz(zEWz`QO95iT4L`o?=z7AE}o%-}6Z1p`Xj)`%XECQ7aY5j7YkCsQs0*(6%*zhjsD z)BT*?=g8V#3~}T<@qQp;o|s2(#|w4=Ib9{354Xy58OONcF5?(CycEugsgFNn9J3UR zsitdH->ar^y0~pk`oO1SHpL18iZbJL6{a4!8mKC3e+na&968guEp2x?hA}#I5C8R^!A^jh8 zkKZc_Z6jwb9NF7)A0R{`fk2!~AC$)eq&cgsvbSJYe-)B)c}5py<4TC>E>E14kYa^; z;-rM~Wn2mC;^k~!U}jV;lxPuNNJ=O(j5JF#@@B8LeAxN~G6*#c!Ob7^5sw3rirD&+ zeF7;A_C3O89e^z=vKU>^7jf(ebTA)SuEl5%EYF+=%>b5UF;ak?yo8?QI;2GAD(teo zTfhS33e35WEY+iI_`mEC{$|;CW0pn8bICgFD3qc_mk7UXge}GUn*YP1-qOr ze26!ZM7!cG_mF5uWi2vr?}mX8-pzIUOcE!b@HBODBpNptr#;yr&f&m3#W@5RcL#_4 z4kPvlbc|MoXZ>#f^zYU1@`-ezhLFx(l(kqmtkhEi`4h-H+?3am$Q2-TTADn>DZdE` z4yyHzn11FT>eAr<7i!6c_$gjSLhOSV-BXC0k%0?wJqXi93}sWQ?b%LAR-x4%uox52 z`ne=4Aju+N`4(dgFoz^_fn`{XM}Y<3fMS|L%(!7c`u9S_sz6&-a1-V~80FX|P6BPc z3G=TYy;+Rmjv^iY7rx|eDZXd_<@6Whwg`Xmo)Uz==!u*DBJeU-|57&WGMHu4Uo6Kf zNr;2-I-VU46d6m(V|t74BahQt+=dkQ787sTpW@ykpFA?X#Z{?>3E^zhfi)oOfgEzUj?Yt@=Bj9VjpNb0xbpl6g-U`dLLDCym{6W7;Wg#} zgV*R(#Xf%OdtRz&bLA#gvA!!esfu-h35U^NtxryXsgLP(523(bs%ZRoswmu+O%Re( z9m#E32SlplPnby!eGTdVsE*u;ggO#~r}03Ha3Uo#2?+Ko4Coda1f`@rj{#{>L+#*I z{r?ZNk@$B7f6~Uim%X)-TOs7JArD!h0D7Pv5>U!EUIpU%D7;8FJtcjVUZflT@AYxo zJ<4M0BNgG>E3W!TNEr~RkMJNP**n4N5K^Nu8(FjiuvA4BqYw>`V~g52y6iUuR?O{V z2J%6bRsu^6fl@+)ipiqQ3Wr5|D?|;eOD)Aijf$I9ay5FNEv%(--?A7jOqw+!rCB4A z?|#AZ&bkAZ^5!VA*ycwIK7=#?A~yQfp}nO*Vt~+9(A25FaY=USUEg+e>cy^I3|9!u z{Gi>t;oLl7^MfZYyCfZA!z;6*$y?~iB`nCWSLgB;w`JPHDy<_s?puR$~8 zBF=2<5bV`=B2KT{3!m#H-8NmRzxW?Xx5!f76eX0KC>Q78Byb|qF0w_A zXdtF+U%Mz>&Vt&)?z;)_e<4`zEnS8{Nw8D!7B9heRKCK`+*djbBJ1aY?bsI)YI4d= zR3pwu-RO$dyA>G1ti&IKnf(jX_SIOm+l^Jc_a2KiPSlAr{#@CEHHlPvDILIKa-`af zde?uihTI0BKc=bbad<-99A(~Sn*&6I1U09~hf~3#)MiON$ynqHcdSyWv$;E^(PGFC zpiubtAx)dDOZG>pW2|N&lIyCCgMYxslMo)c0A6*~4(5+=c}T@@X1k-`yU25hcgd`q z)gBm%q#5|5B_2zPRuOfJ8nva1BiPw<&>4;u13Q3)kSd?@*#hGlXC7Ie4(#1%Xk0ZU zL+c_JqSX$9Tj_mRAVQU>9x`xxg~&8yc_?^<20utEY|=+@4Q0 zDl%eWNMa3}D>nsLRg6*JmD_fGPEii@>Ug+YNjv9i5JiRr?XQV%xXimRlE3)-?{APeN`LNx+o4 z#>WCH;Ks134kS{?*aK{BtoTyCckX1Ys*18*w?J;V-tIuS!Cbi&0m~0JUUB7?3oIkt zSPU$yKDfb$=W~>-zF7+mak;p>;%%ZUw+w`#LnykjuG|oo?o5@xkqay!&V^f#II|Ys zL>!4KoL@YED8#PZih$)K3b8AR>&@<{nn+Ylq_NPITU7);EW&u+m0J<8{0L(%FqQ~zP;*{g z#}n07HDL`3oRPxvz6_3F^=)cXQH{@Ap|H4-Fe%K?UEiVrs|q#xyT0WB?iwr#HF^P? zYr|X6Ll#gESzx#a@OsA)vIa!UfH)HEW1^=SZZrc%sppr$K@ z=c?I(2BJQTZ54EJTWtujw($+jf;bkWdaj|Re)91G7bY9ljI_bwMptXWOg75 zvwtR1_RmD}LANxFPn@UuWYTi*`*hZR?3oOIOs4p4trkErg=(@l-3Oc#5x=U~i z3@|Dbv8Cb!ETuy{2ZZNSE-)dUd|Bl3E423W zHG$1mYy_8bJmx~rnVTIG^a56pcwaJMFpZ8O9VJvEHBUvPC%l83>8rm=vV}h za3BLko+kwo2xNu0WbX-qSb!M(lD#O2RG+QJ?S*`h$yKDevuL;wDc=8cF>QFPB{rQz z)<~@t^0DCb4W0`Vx2LQgIU+zgiuBSJYMkGvAOiS-sh~+B>mDG-@ssi%h$|pMw}O~} zmrCY0dqHNB?v59k^oLC|9rR@?n3>0;U?!f-vQU*@KjdoyOHTEUVN?2cb^y3dHii{{ zxsK7nXi0DGk~J;GS-Acw z&is>HXl>TO1oqbX8sQ;B#e4SRJ=oK6_r8dl6D0ILpp9(D8`+T|Lqw)+K;C4P6Z%Dl zj1tJ(K;p&4j=2I^10+UV>?o0yKJ-#Ub!ZBdRZzmO+L!e(*p@Sd|seD5Sw9z=SnQxFuhz2?Q`LXhv{w>QO!aEWXKQYb{bOjazARU(fx3u}NB zh)SC(@~i~1NK~3cmH=5GZtUDF^1J{<<+0xp+L9ZkIY17#$M~L$#bu6mT{leQVA$q~ zSGEV9ZrE%;+@_DJXnSoZ(D2NYrXNb4(_}cvNrZEIKA=kg%4b02x*r41bXa8DU}hc5RJ;(jQ{xw+mC zTdDG2^u`l$L|qE;*Dm+?=o}LM1#hKZM-~2?H$JbPgWsI{?!m8;gq7kgd>f)Coa^L` zS0HMFEZ??Y9*$uxQ^iNSO<3jJhlfjeVchUaV!F>8Peb@MFfD`s!>w&;s<5^MbdN+d z+jFUEOVUp_Zu_ZTs?tgK-SE5?z%O{?bStZT%gC<6jM597Q9tC5e5akH`A$1YU+ya8 z=k_wLY&e$2^SBr#D}CyN-gq|FEhWGBC~SmY)lCgizNmy-^Je!1_C+@}$m=`P={vW3 ze@}XI;3eMpJlxJ^zM{LDOx*~V?7*(P8zK6RZ|8UxQavENj(w-Fu6|V*y&_(TnR$$w zz`pCQ)(yRW2Gaq~AMSKVr&9&&AhSJ^6YKW_$jLk=NE8A&lk@l$5DMgMa&qlH>D}l) zlk2>*O=RAM%uhHo^LQ}wLB5+&(zKhAWu~doQ7iGlQ;r9`PJfvn`+Az%G4xsFo$JVp zGn*>+dr%1R9Q+mez_NBSFAElJ*~~G&+sX4{WBjR7TDelaBMMd0W61R)+j!0k=SC~7}#IEFhD$s zmPV(_+VxiF3vSWzjw=KHg%*b4Cg)aBgh*TYfyO0ZCbx=QU>SkNIbgr_cH!2d52iWH zvQ@}gp3hvl$yuKLuG|hFid2!mu^U)X9~W*v^if-x3KQB_-A2RW0^5{846?i$ZE9WHSQ~ZoE!2awD&fnszX`V2ppO~S-;29Cg5TEo+m16X9<#qrO!HN{4rz^L7 zV7ZFX4cOX#F5FJ`!&gH#S8X)8BM1AjuH58czm6-nDzREt3z**D<*Q%puTB$RdKG0m zAO`!DXjYCI$rpqDAAvb)Bm-EI#W)G9(*VJZ$3vJrK%Gc3EJj1ureKUO>G*cI6j##6 z=o$b?Cx;=ZuE?GY%WJ}Gq(vq+{3a%ueXlb+#d0^ZkBkyy0?NMa>O=B^rX&O>JYDU2 zK@*U^KyY9f7c|jX^E9MJ^GlmUvjOSr!nhq0#a;`fo46|B5z4`k z?jo$kL6KuAkPdXliwo{Wq;xSev4`@{MS6gUF#Ng5{|t~mBAO&ctU)Oz197?g704JM z;_lb*!y-=>kP+C%eu`PoW!l)Jfoc$W_QkG?RQqk{-Rtt+-5rO6NHOj`^OxeD10grF zQ=F>7voCC^`m&0FYD=#d(#fid`MD2w8H86&UwPCB+WT>t`COWn=>1+W`nVo@0l}?N>}Aw>O8vIK={RO zZ={>Pg;>~}!D4Xc_InP6nA+~mFCAYiU0ApL6vII96H>sDgMVU@7?*uF8k*#5e7+n@ zj!$~Ct3*_-bF;kh{ZYX4y>U9kEsOp7uMkM-5VgIREO;5Qj_fHT8-^^OBI`vUboH5J!*6qT zvUFIBk-`0vS?RfS9$w>fJX6T5bM4U-tYkk@`yRw>;VuyGIa$$tc&4#A7UQ(86bFiB z55x4yN<4rdCGd8lCQNb2}PW*3(|NI#YK~KuMzWgtQe-jmq$SLh=LF#kx7zIy}S@}(WlIHPKkYyCIi1;b& z=zEdLKEOWwv*M z9d16EE{+9;INbbN0)u-C*S`u)Pf^N4faN}l#_}D$fR>QocvMZF`x-v;oWEt@Yd)4; z2{kQK4_R;*F@2&f%xGHP^kwVlv`xNP{()1^V<+MI)Xnn-!P!*e+x`J-Fz-=8(_y-Q zA>9|jOPcyscjP6Ct|@{I!!`d3znP^puZ=zSV|65fyqFd6)9Kz=GKZ6MU5dFOS6wGQ zIM)W1q=3rMOBKj^AnBbNxBKkfLEPs>>w~t1_LhvV7fm;R^;gWoeQLfw+VDQbe zT)7>9uU=#|9s<^4v_)%LSHUG1|FuOCph3jAURxxN?hl zOx85j@kv`d=s1;nB#bqE@5!6ac19^E_z4GzHNh8 zZ{i$pIP6aMDksOiA$(9kIe0`^S+2cf$+CS*t}AzLsT0h#mX8N=)fqg{FBj>Hyqjc~ z3i<~4jX>I89IYhNg(n6B@evz$7bEPi-vFfVa1J5l>>@`7kgg(}g4rM+DNpiqQvdL8A8t1NkS<5l-F! z5CsT%1IwA!2g_t-kE`{)Z00%&eEE#G&B-AbYOXh)4WDw8SaO_`i|N_S@t8y8fQunc zr>inxh&^#Dxlk~~o;bOalIi1HG8?mt<1s1knTcP4g;SiKIFFZwQ=Fc71tum1Q{hvd z7mJ1SCa4X)3Y>!wrxbqGlZTaGkdf)dn=HNH%`Q(+H7|bq>E;etcu#)o=-4?dyeCc; zUh?aH8Vh4-Ph^I~^g1cb`@wI-|4;E>W{Pi@N!I-;w44Wrmhj~W-m4Rgco6aa5{7T* z$Q^`nwS?zHI&vp(#;{t#6y=jG8V5J+{0Y)+a?_%)Ka@185(r)KC$sXqhYQQI#jF>8 zYs2=x)+d@4#1A1gK#X@~pw3bt$62jc`o#Ku0P=zuF{&MK;czk1SUtzh02D%mUbGR2 z!rENx$C(u(6~}*P>ZSAmM;WHV(ttntEw$#8fqo6;Dxp0|r1U<85K=qbX{a zfGW6oxz9(keN)votmRa-sp|taN8bFYY6sW66Df|mh)h%@>|_+W9$4aHTVg0?O@y5c z2bNCx&~cf5Sun7<(-7`!_7iGsz)qBfcBia;LhTStMV;$oxj{GIo_<2@W{P`c8w7R| zRXH+gkT^LtDQi%B^s9$Z;UA0rxj3n`E*JNc01@}6)}h-{fqVeuL(~Xu(d_aypYXP^ z@TcG%@j7y8l;(zAPn_@1yoXK}I(3p?@3jPPqJ0nHc#Eumt)(pRdQ;e#G8i)1J~){)i1upos9o~5-yO&-?v>)P-|+Y* zAYJ$_n;?pY0AwAI9?xROIHX?Y>fh&)HO5?xC%%sSaLmf&kuE0U z7Y^rI%HRI78W#@Ju>(4iNoH*g5Mlc2NMt3Dy|SU!g;21vXB+gvLNUVfl&XuZbE_Q} zTjz#LTSq13wr&DmMzwIc%v1Wjr4Gc;vZeL|$xR)X*ZmO=8MZQIxC&S<mjWAx z@8ANvvEcuYz_#LLB(Riw3+xsAECu!w$hiXswql2#S3}6Oam_PL+jtm0F3HZ&#w20d z9s}mkJZai;$Ux4A=Di2~qRE*)^RZ>w;CdW7 z27Ue_YBku~=aK~wNRKxNDifpCeYjGv-`AewTV5)R^?#_c*R=$iWHn?)UT^@(IM6iFgAt^*LYF2hnoFw;+2obDQ9TlMb z<2VX|TUeFNAgG;&tq1X`Y?Vp)blxgIdBM>ti`_aXI$|e=5pKAP8FRy>8KW|AGd3MB zBU#@(%4JMAciD*GhU^h!knM6Pm2k1zD;09MY8w{iFl6n7Y_8f?0h97d7Fe-sXV47T zmBpenC?>bJ$r80yz=y+djO2iYjX*-#hH|{TM4cVD1Vn`rxtS&2j|=Jky(IaD=9}+XZuoy8&5^lT zjcdPzmyk3=?jcQnaB?y-@Pm_MK;WQkUDn-D+X{iE)p5k7ydM^j3;6?JxtQ_F_bKlo zFfLGY0sKB-TMP&k?prarZ&e1SaKw{!ao9vDr={R%7jEWu?+6!e75QQ*I2723S6sL) zdj-cb1UCfP%7v}X@G;J#)tF^7?eEV56O}FP?`dFI3XWnemx9d|`w?bY+<#jPQHF_ANsJ-^J%roUT8Ysng76Chaa)Tw!;Kly;ZMHT}53Ad)YQ z%I1j`5Co&D)jz;*IBKn-I7CX81}C$M7gax6cRP>Y65hbNTP27lLR|~!3%m0s zK;)!1pnwPQb6e+`1U$J9$WWnxmxa2O0C`dYIGGPN2^N$)~Ky~Lf-wnngv>)8}wUJjZG{u zt5zb}1o}wX^>UKBULr)-`(!@^X{FWc`;W|>_+C%S04}B=e8?VHn<3qK*ap??E zQA2AEY8=xVWuVvo1Fxk2#rQ8jkN4F4oB9vx=of*E<-F>G_<#uWy+HK$yGND0vtG4Z z$?TTdTH|V)BAC;Bi?JSB$+2+UO_B>N!(yy9F;t8>W%Vksu(Y9dSid*L_@e-QcggrS z)hO%V3HsPu(6AH;PISV7xt8)KNWCgnXlV!vBmqdDx79qq=MLiYSexX`BzE;};ZwSa zu@W&|q@&}8TOmd{U+RXJLI!`M1w7_FxeX{oDI{9N?LNERd{ltn2S}H3^I2PtEJ@}c zqq=8ec`1WcT*tv~rL+Z{7s5^_;r1qNo5far2mKzida~NLp8&1;x!Qgq8$IXw8(rmV9lxPSmTdf%=5KWH{0&93B;q%Vzps&u zAAi`S4kV|7pMY$)SuJ<1Xc!|X9gIf&%{8(_H_eeK6G~OJ8D$IT+(~_U6jdE z8esG+3@~gc>+~gu1+;S+B-bGy#Kr9&fXwX<3xUE$9e z!7OtJc3evlKC}bNTaumw+Ko*OzTYLNyMqlwmIU_84s~fjGpYhxgOXYQP`|M%?|cG} zVW+w}w)y}HjDJdWV-d7uiHUjYp z?gNyipw5Y9_Dm0tIbjlmIz;Tj=UDLlO4u+LrzmDg_=@iR; zlJ~>u2(WtYX>UC3pAM$UAE>?Kiy+7gP^`ebd4ry|E!tF#6|-OQCtpm_)`K!J_bJnt zMM^rv zHJ$&b^Zt`zk?{Ft=(UbL$k&pH3?0ZN;eqbGb061p4|vHQ^cOuK>fPK@u%Gs*!8JM} z{R?`%5?1NcCo&S7&DIsc1;+Qbl)vm?wuM~~6lX7b@FZXl@SIHDs|G7ENRQYH1rG<2 zzgIO#as}qGYuk{<266fx3d`{#u@Tn>34UW@Sna2y*JO3dfDPWKo)=6qu+J77&ur%e zlLGSrMeM&NCNG=V0SvH;6wc%YUBkhsZepdU z6B@CBpQ>485=d0In-%94KUGJW0B%N&Ve?8-Lz1KSqotpwRvvkw6f&Y#o+O!Zmjw)$ z?c)kcoY1Vzc`0oG&bP`JxWKMe6n_x)@&mYi!5cN3co35P66sk7)kd`sfuIW7C#(js zN3?jjq6gK$(D(7i=>5Z^~+Enfj-@*#CN zHRv)|pQ@5iBn_$d#I0}=D2%TsPCk_^L+IH~xSZnCkwJ-Qir`P;`FXGSe+K`*a29t> zHlIyL;D?luo1%>O;|bv!a32e$?h53q&s8Jf4Lp1X6CC5eKw=sayT7b1Q4XsUt*JJe zFWK0{;VC@-aW&)E!_IKob4`qzs%*Y9fpIUP^az?N!x#V_aY@w?b+&KNkGpww7DL{9 zM+ccB%)QU?nJ_|W1~}+jVLv*eI9XMF;6j6Ezl0wKu@$?Dp4?d}VmF-JSsEvL<}Zbl#W5I$FR}OWw>?7E)9@O49j!me z-yv@~J4Wv831oD4XO96Pca{}?rQR=u`X(YB=ZblW4X6k%)TW3;nWNoUPlVB_#M#=D>inPsVQ3`sFpxAp3gIh) z$TI{;SC(EmJl4++@?nvk=49~W{Xm9^K?}E3mh!GZzWPb+MvcR5(2-8NS1|eDh0|sa zQN3>YE6|vDUX1-~>G5p(DYZ4}j9aF4H2HujdM_NV5>1mxoSi`po92G*Pqe5i&8@O~re)}9e`>JHHQ34%?><>RN{fG-79}nBb8Dl^a)x6|I!BW?}Ps9Uur#N zJBZVhG=!h~O-)c%BbD`=x<{D^0&Hf)Y9JExvu-6=EK?U8SR0dI@tqpedO=KI;9!lrN_B!kA(BU4K?>tGvYiRE%R-}&C&}J)@ z#ds)4tEYTV#Ist%#M@<{sDPgDp?7?a-?j&7y_6CVCc6-JwT9-)=KZE-mb7l5{jRX1 zH`Tf&)5Ek+e3kTfs!MuAYL5gdN4KC%@!Dc#6Nr=qymLK>0STH-c@4y5LS6y!asrAw z7sN+4Esk~VsHL%jJrRklu)P+-vJKPOGhqeH-lGNsVHC+iR~XU6H!dXc+o{*YW<{ z@tTdTF3?)DajUiH21?egX#7sE4@^vRR!ce+VPQ-y{I;}%W=ja9OeE8LWU}J7;~ntL zm*0XC?d%p+(z>HoKS=4e4mFad%~yI9A%t(5HnCF@i0pv0J-?$DqgqcudZtgkmxn5r zX4%1Md$=Z0o-k*gI!Mn-*V-sGKx|Lf)+rV1;Z*k2rZxE(L^euJ?Dm1~p!8^#t)$)F zO*jfm_%6^_dTOndt?R2x5;C;+;*}p>#qc#!vjzX!z-(&KOnFpWp&WZ11F}c88G+kD z;B&jNiZL2)cR^*m1*Au=)+X>(`YFuyrzP}MF1~*jh_kucPf7+Mk7}b?%h6h-e?z4D z2C(iqdVM$^n!geQ0KDQ@Vvb(huR(lGq}Ptt8Yv1rm#cMPxA2^D^)=3JCR_ZNmaBY# z)bVk8N7ihNHdtAK)Z8(6N+)Ucl`oM3lLl<-BrRC^45^PM zq4DjZ+>nYkOMMsKFfi39+f`43ao>n8UD^e)QZMJHP7Ok{L z3f2pOLyp_CkY?pdvaG8n{* z&!S*`LEsa4!CES9kuuA4M7gmH@|vwJR8D}HH3v#|1O#;;Tt5Q$A;mRq-W+J!dq~}# zqYYFFK?o)_U=G9Q!0;zd)ShA&=W2H4G5jcsI8PfDct3G~ePQ+Upna)GaoLgfC@DzQ z&4cze27w->IUAh^#i@-H=U$kHFaGuwZs+TZmcvP)jb!fgcr0t7XF-OXKy|as5c;VA5OLtlm>tX%*Vsg zAi%C3TQnap3PGxG7}MtCMLwXxcA#>};2bNJoglInk{xlY0L3mqB|iw_nFZP}N*oBVTjBp_0dZm@UxMyl1PvAqSg)6~ z2;~$~BVIzqegy(gH)8L+q;*z4Lh9^GX!!Xcc*hvMS{uk}CZHho-q6AV9|oSr?Z6_` zh{29&xOJTEVmJUcJZrYnb#dUpxxZ665q z-SO2F>Y{Me0R^Tg0@d{}D z1}wpgNWrCuXWzV`r7Ba9;$?$h5yIN9(n^(1fXt5!VbGT8f#Jk~bmZ!4=!id3ocj-} zQF}LEM!{D@QLcjEjNeMo!bn@1D&GU*+~=*KZ$-+<7%Jo9EwP{0qTiWGyw*a4rh*77 z)S3l81_EWj&91J6@;ri6Rw3G1Ul7h>zq%CuK+Pg;0DFEN+Hfd-oLr>kuvNP*9^MzcUH2q^9H z2l-ak2Jw~}iSdce5TgZt)>HWH0XRnsSosRH!ih*Gya~pSfdJ!f$^#(4bHCCEM31+$ z`85;}*;QH3{>}!j*CGOMEfnq*oA)A$@H-vWcnAY$JJgHs?zyshn0wu7j4(*^aOEuqxPv1 zPQ(Vtv3iph-sxWpxWN+Mq|4V{1n%Zly8QMFe(SLruFYu>VBU<)+pL8vWk}%-kF(pG zwE@a{qy}u!X7_jwgy~?K#hwk!bTmzDI^~lNr-?lYEZ`k9kbNF3lpOOf0CF|XbkLb{)160{8xCRQ5Yc7=Dc>lYOMk`kqc{U zSTg2U?Q^Tr^l4~!!~Qll>uECU5&7bK60C`i5uNbcE4e+K=W7_Q3=6J3B% zO!fLn*77!>qcJ$8siz6}ui~#76)}MAuWL^ll$ngJ3K+oix4AA$(CQ-w@SZqdeSFXx zPs9qs-KAI3 z?|PQZy`tq=!xlge3-K3di#D2JtQ~euvr!Epzy!h^%X#e~Gk6UZ+g9Nk139m)n;5Sl z5n!S}u+z;jIGuM5HFOhfG0R_4bWOYD;~V}I+|TgkT@%^P>;I`%XhU}p9W*MkmN%P* zp0i*$?hLb*+d%jD1N})o5Ltg{c{M(H5eGw16Q|k0v_VNMXgOqv8w`>V>Mxz zeLaH^AhS)3A>X`N-lsUZb~4YpCA%=KI#B<6J|b7 zJTrhL`58ebMm!Z@IAG`pZ0=1Bkx9Xhc7T=K)E1^zV#$WryljVM&>p;@z((9;J3MS+ z#7)kPeg+J4qgb5y3nc{0GGh7eU)sQ6Xjj?BptM(-*%C{_ZfS2>m4j1}d16mn$+x$) zAqb_6446Gyl7_>0lI91GBpv#GFKW1y<#IumNgi8)%ZUZb_e{ymYn++q7>>-RP7O$| z+44)&Se2!G$rIIV3E#&QQZA4efV?EmyGdjYkQdn03e1b*iKmfL#F;vZuK{Ed5SREG zKpq3~mk3?)wa7CP$ZB!v_g4aW0LW|n*m;aZG$1Rm9!N%oZb_^&A0uC@-i>s)%vFbT zXdV!U$h>gcob;|YKJOcDMo4HlWgpMdeDu~{Oe^VOEdF>hr6tpIXT9;#G6&OBj|`4y z-}>k+y_n`;on9J3_bRf({4_c0V*`yk_a~RW`Cgx&He+RbDUq?t>d@3zB{OPafDCWoVApAlGvOA-?=9~BV zmZTe#%`Hj%sC=%q{2CBHu}UTn!kwRtxu9UZgS8VRRP3s5c{D>TOr{&o&ln1mNjQ5s zM86&Mpn;8D{0K<1;~ z{+Wj^Ez+Q2dv}^?DC90YYcI|46Xxx*lxdtJAme2!+T#2aCNN z?_YsGM5y14`=*<3s`4qnfqga0Uuti>=bvEI&BG+HkdlHTrTA93l}HFDKZ64!FMFhgYQV1$2Bt9G)_;h zxd>5MNVZmd~ivvoOb{@#q*d&-2@~dQa|60 zs=Xo!oulG!*q-WOjGThC!76lY2mFjm?EQX-(nUz;Q#xw%14ySv=`+NG`B-Srr3Ls7 zMmx%wAr|E6!4yg>Vj-R$Y=QLID1EAUunLao0R*)k)zJu|j73Q2`|vmVQ#w~Tuk@e~ z(o28uUWcu#qdzE~&cHHa5^fy%v6*oO8eX9wT}77*L~cGs=>uZ@i=O@->7{M@)G0}? ztLxUV%nA58DaeQ#ag&`}md>`9-WSV0jMh(>RZr*J+0J_USO+bLe^32; zzkkl_yjk!pC_a^(=#g>G?Ar84Q$pl{`<{5iHGUXAO76nE4@ijU0O&zFDH9@38#lvG zQDQR<+&xlK8<19_1CWc~^?)EU@AS-Azgi$qi{)?mwi-az#^VdEAodZl2l6-_ug_NA znvIW7(7RCISm0__tyr}?mz7Q(t{ZNnt%zg1@odDKksqDh`+)|g0HkT9PoleZd7K-3 z0K@xFibyA|zQGmAOOZY<`Y*m4(OUi@ko_#@$67Y_MWX&FS=2IaQQ>2r$@MpeqJ44f zlaBBmfhGAHnI^`4M__1X1AwKBdLW8DYty+u$~PgdwdwPfS>rI(-9TTb3<7bufnG0` zf#7B}z;feyUCS>ya>}~_yW`33I(der@K9H?W(gXYsg3nyBMQ0Dv%08s8 zM2(13O2$=}oK4buS^4)=TqM229GKQkv(Dzhi$fk$yqPD~_+5BjK&VUKkC1V=t zKUtNcvDj7G1mBT92EuEiH&UJf@@Er$omoujkWexC78qGScUI(3b0YYT>eSWbW_m}z z2f<<*uLw4~8NNhEx`qg1wqNL8A0U2Qz0BB)J%Ct+8$>*5D+$|L56h;>_@S>DrOF$* z8v|+4913^_WggI6pP?L{i71QB@1cO}Xt%&&?%BC1;C@oTuMm;JW9T#wo&v`fv;Hmg zwn3}GSf=@LP#FwjKVJMZ3M+rw8<4>_tQ7&V~WR9=OIN1i~;5Bhv8bYu7# zLcU0mrM%W-~=V!7QTjbR_A{wtptZuZdh`#!`o8h0+&`32hL7* z)^7xrKKfq?Dh4le6;y4cxuAkTkf6TCp!IGnrYkbDzH6_OHPu+bkkAPEXOt? znq?Ivc))5LGBGYKVEI<#0I=%^K7ohfDF_l}|g=yQAN;ko0`Mp_J`W1_$^(h4eF`et$wbcmmSnAjyt2 zNz)zvN}F{3L2id}$!!mZDDObvT*-#fwK_tSHw0Ed_SbCJ*Qtg`l;8G*D8I%x(s_Zu zdg_&bD@s1TAW>FX%7@{r5JwZ6Wcgk|Aelg}d~sh4jpX}+&S913yLauG;bV-B#+;pK zif%&NPn&V>AYxRh5x?c3>G&e4V6qu1+hj z3t~P6vTvl`A+Usgq9qc?Pw&v9xtP9xXPOpCE3dWL<&nC-@+$C>99p8z(#I%Sla<7kh(hxL%DDeShi1MBgdjZnYk#CFCfknOR^ChSAHLk?4$Ko%6Smj4=`N$ z5(H;=WTv*7?V6|sv&=DiqVg(ml(-`;&bDN?$76ktI0rrjoG;T(7^^o_#u1ybdIx0$ zh%sYP*h~;ufp5%y!lJEs>3x9A67xL*cEt(^n*$aqr-otX|8ck&UxP3g^lPwfkKp0)KVYD;5d`17fMwcN?Dz3{k}`>Yn~1{po1zT}v6N=V+v!z^wR46ZKOG6S;^$|ta-VAh63&caKokm;FO z`oiG$AZFpGnfMESR==d&!Mpx?R-Yf6h+oK8=s%Q(QxTiX23E6MXgYNst1fwCw*Fm6 zlZ_bR1loGus9}L?w!fPZI3v3{!D_jdXkGAnsgiZV0^CyCt>lfD^m;z2In)I#vf}(J zt^uvGmOlyp91HY81UDSON%AS5WMUhEWdO_dDIW*y$|7`_@8flt_$+C%7$Q*`s2C{~ z=nH+T?6mb_HRis@8u}>ZCnS#>a49#5@fSaACdf4{dYhxNy|2J^{0%IYir`%}m%(+s zfb`4K$46SJLb}s3y+eP_%EkTQyKNQ31R=hzIPJDohI`?K=w@Vbu-i61egdYvDw7mr z7hXW3O+}eIL$oqa_cEMZm<~%N({uU{!d0TkzY6)Cn{NqO4uo&MU9emqB}9Bkah%;7 zohe1U$QOqaaM0j@Ql4#MB;qPyif{P{U_G|>j$&O`plf&!Uqy>QSu6Ax8hqT%2*PyB zIgBgLU9sFiiLe&b^G4GdW2?{Ky?YhaUJ|fUZ)Fwlei)ZiRf%!@SGx1v=2-riiQ(Pm zc>Z%>lbK8PZeaQ)tMBptw4#yJCy{;dnqKkumB~+y$qDH518Bkv5sM>3BvJ`P)N+)Z zfc_51%kZfA$Dlu8|Ga#@_$z4ZHo0m|D* zw^*g8ld2TBs>C`>_ioI`SyT^vKMyN2$P1r`A+#(Pf^^0E^%;p)$npkvPGmP$={N}N z!N*2nYaYaTMGu^Zq|EZh6Mt~Fw$?+ng3Wn1>~#D)-|&p`*MwbOc~n`o1oXi&_4v? zhqZbyrEmZ0lB7btjdgH3O+?{<&l&vLcKYEgoFC4@`5FD7^lrax^fxROzDCbd{CWN6 zgR^(Q=lL3`_-(^FySoUdVri}VLv8`9kofj1V?Xvo=+%BUe_ys2-pDtjQID{tvrl}&x%3cRgP zRBrdFE(zP9TdlFJ0aakru{b*x?KnI3K5*n{#fELvuTx{;8hlT^=Jg~;#$Eej3P;3M zlt_CZfnu76R%3E8rwqjRKQ$J1(J2BS6tW)6tg#YwSYzW z7*526%~*}`)ZG1~(Q9%1%VW4)NoyP%yzzMmqsa4Oav(N6o)v7-an{V^Vctx}dq2#Z z$&=oAA!ey0(~*zxUgIj%ogz5ZIfB(6`l^-qm@W7inGHrdg~!FhPxJB9CO!`zC69{D z2J!~ljW^Fp_x0)Mmy4gbiG@x%l|KSVp_omYxm9nT3Pmil-NMBS(qwmnedJhsx~c$k zs`poMn#ZhPubD;(QyB| zpTdl^K_Ef)({mVd{)Y5%ab!^5IdK6<-4cCAC(hBeFQhXS4Ex|cYJ$#GP{4MHv%4kw z{Gf;o3}t0G=-7-`k#MG>eSo!mBHqT2RMbOaG!o)OMT8XEBS7dxMH4tgY|4%i4cN?G z`qRqp-qj_)?ZUi-a=9nm|Bv*kB+gpMOI@Lu#`jh zMX}wx(eIipPw$2s_ES0}y$62uXX(`?E%xfQaQK3TrSkBFAo<}7LGr^Fg5-xU1j!Fy z2y)H70VzC4V-ikzK@1{{a}cdo0a*=1FU2~=3J`yZ{!{MLSPZ1DSX7cbBjy8%-~(5> zY@8mS4di&K-iz9u+h~tsd{UHBFB}s%)Gd1A*>v?zdEZ0AW(ASZw@W_<;d*~dU)1Uff8It)Lc_E;WXQvk1;WmelGOAZ~- zulfYM(4(3ig)_hJGkvH~pX)Wyw&5AW6aE3MfvZ$g1UiRTydIwL2@`|*6v8W}*fZt8 z^n*~w+zRuq&UtlZdLD5ruziiWiv!~5kX8-*uA@Z%Oz;U{WEiB)$9LQ6mFP6w6AXCIlHsAH&Q~o><*If??ZvjN? zdWhn?9(>B50z$hU{#F3|iB&2Hi#Bg;T&}M3M2t6ET>R>@R<%cMRA7)jAg; z*9Uult)B?Gl*(-jujUWZ;#c0^*Vp$9FgCArKq8y)jgE7g9wS5>X1ORnk0(x%iy!vJ@Vc1b~jqvjwu0;H{2q1Alt~%90+BxDU?HrNE z9)7@7XsoX!ue_r91>)IjU1cYSMFe-Wx2(NIvD?;-@QITcfB` zz~f~=YC1EIq;m3|9X{pz@YB=W->J=~7JbS~fY9Xxc^D2}IjN5hz}~rHLI;yIc$~`5+EcYgp?)H z#1N1!B?+O|JqHl!#9*h0fQWQsy$a-9g=3?}LJ^1xcSQxkSg?{hN?>w5g$SyM;@-Aa8BNWdi?=l>y61RL6L(gg- zc81D7(7&lwb_ku@FBoa?8t5Em{kO-_L7nL<=~||Lme#fW6|V;IBY#wQ|4C zZeUHx8k%UOR}Q^FkkpGae~Sf4-$pYrNuP-IlXR!TY$SaRSXwWfq_VdXmJPHvO=9|v zSHh=Ds`;-;isgSDU0qQX+dPn~9pd+kc_O;qz|{)zMV7uWx0B`l2@d;E(y8g8P@E?` zY$RRw6DB;2PX7ZD)!fiapuK&{<2l4>$|L$&1Zc|RW{ljdiXEd8tr9p ztP3HtxrD6=9PD#1Fs5g%dSFM)5NQr`7O=ODqO)5LLXjh;>gZ6MgK{ORtvXS_Q$!t5 z6LFZRwYg%vTgyZ|_Sn#r*ro{VL>0-Q_d-V)YdD0}8hcD=s33M+Ow;JGezx;Z7OkaO z%*2{F9bG8vw&fT!)OnDTG}L^QB5^r_qDEi!e2Ag1>*lZrV3)M6hSxYp(#qcIPI_(x>kCC1S?M3WJHUy|-*2T8h|lOP@EZtE2l z=|XWux=@@*Cu_*3KK4XOM7noSio{!+Jygw8Crs*83n}EWk7)>=9zL#Zb~~42dno;! zidH#+bAUO!k6W{6h)(>0lGC*n2m06z?kpG{$k_1g})4a_sVqR#m&E?djMbU0#Qo1cNJ~} zxEX6KS>pSucs0g>U0SN6Sw9*NMpNcRvavB8FddFCW3|--dRf zC7407+Y_pW`Rx9{`N`cCW}{(eU{G@j)(5|V_hvynN!K0!ZK!@_8uCeTQ|99UMF*;Y zLs}crVGHL_=?|>jk$Q6M83ffyt<&2{fo)Uu-xXNab?>1hqF6taQd3}A*KI-))^)`Q zyj4rT#yawcw~n7^Yl<=CD|MFN4{2tiJ=TDSfrqs)bD_eBXqD)HOP%Juz_MIebg}20 zjcAqU;DqqELn-uSvBSJUy^bs^3V{_k%wYvf--fIj|=YD(3hRmhvE!~P@E3Dk(u_` z*QZ&dxu`nv&xN+)|2+QX^QF6)nq_2VzIz=JmV&E390&t;H`4>#zHUGsvR;0BV8d|4+9US;3j>>3Nf(F4l66<+S)YNqA;E;lr7TnuFiekK#@WnlX*1uD4Q z?Y)f{nP?~(nSzp$DJU74f_!?cOq@!W7|Ad$S;P7L{}|>XeRIRLaPl*u#o`Sw;tg+tj_mFb#tyAki|LQ}!+{3o16qC- zP1hNZ1_hS#xY{5t7S33#!&)G|L|nXq$LuSg>laA3!PGjJI$AlK;K?Q1+qnV85PL3 za7N9xleREbY}duy3~WF&C!$Ewj)zVRWyKtoHja0Dfk}PkMQA_KN*uDsF z7i~NOQIX!J+BQrRB6K8T~z@wTMR{kd>NRd`~S*w8gB0<{OAT6DJ zdpgp~R*z^XsqDTIZ(?U(qTl6Tt}vUj`xsc-vsi_7Pn5SYWl4vJS1nYaX4=W)Nv}aidq4d2_!bgo8oGUz|CTwfW1XfU_e?~o@WO0 zMz46pnhOm{dqOL5LKlz>AwX1$WK#-CHl?7LjCu=q0v$t37Kpx$6dp1l&cNMjbp4dv zMDz`iF?`dcap6aBW>@C461%^}ruu^Mfa(jvrRt-)K=oyhfVH+CS<|U%OjX+eP$n57}Qk>4QM zuP|`FlH1RL^^Jp!DyCnE2uVEWrVNs8>P_UP43e!1v&ra2U}TW2XkZhgj0WB*LNeFj z?P5q_p~IY~-liO-WX@KYO)~ES274sls-P^Pqf5w7p~ZXqTi%l4F5Hduzm&{_yT-HQ z#{&uu6XpnC#F~USU&LAufq`O_DXoMEAd|QoiiUY2%LyXod1XOlbHo5eND9BW zTKs>8e<_7FO53DR-T!(GUZne9W#ZIE-i|TJz-|s;yL#P-&YW(3jl=`G`Bf$kv{rR1 z)mp*^Ig7ZoL4HOsE!n%1B&NvjhuZ)db<+6$iDW;2Kc_Gof3F4xe@KFr+1Q)xz8kJe znj0V5*t^`_5?Qv~(A+xS*xQ}Dp&}>&`MDI7nx2BB=_ASU0Y>VL8f{HMuhJcX7g@6; z&?G+|bpS$>{Nz~rM@z^RxiTB4iUupPYkHekDG0aumA0&+F_;6!C9bZwHjgFgv!5`PwPr}4>?+&do z%KtpwJL<~h!@=(Clk0_=@Y(Lku5JiE$-qh%SSg=!YOfZtf_9 z$nhVLkDYRnD2vGV7|N+hzKaFkPGR^k<&!&tF#Jg^EpLW5y#@i_0ar5t_h)fK@t8ufiy2={y(+41F~&?raIoqq1M!())qR{t68)&nEc| zqzyis2B8=#BUVV(~=c9FZ)Tv$A~^#F3%|fQcL>To8`LeJdC(Q ziZPB-_&GP-`s5mK)Bvu5%^)QaCPOt8Ck;s5aVS0!bB^*WR_z*;mV_RUDnA~@5f4^0 z#bHi@46CpQHe7}mWO@hGDEg3GsS{enA-Pf~6tBR#Fqz-fF`XM(6LSaEvf8xvUQ;9I ze98g+aA*$swEqtMa44Pwuba%dbuHw)yS2A=t^4pPR$XUqLswNZa*)xM5$j|YY}eC> z&k3~mg5P9ouKFjh`Zxm}a`8uh5a-8tbd}Q9n`TUmw?1wIRW};V zLYqEMxAE%!ES2HwRj(sUB}@YqW)r49z_Ob5!$Bi$ZCSqB7UStJL9f$oy*OZqeTJ!i z6F6SwLwQRRm=qGHv#Ee6U_3aTcP;Y10o5fvu=-l>9LYw@hm2FwbTGnyoX~=ciu{*` zsK-NMc{?b##Ov7UEE_lGl1RF|^-z_vM|-r+r-NB2ITu*Bsvg#3`K8nRF3y0ph~-X7RPL{Cza2}TCg_Z07BqMux4XHi^siwohL$eTm zxtiL6jA4~E4NE`nc$xa<(orOrkwVX3NFfbNWu~c}yv-VYf0fWF`5EGW0{-Q5zsOy5 zjS!l2)zAJ3g-@UC*4nCD>8%}8f*fWB1eJFN%N%xnip}-A=S-;WT7g6hMMIGNh=y1S zWTg;RI(Zt%gFt$bTb1vuUVvCW`Q{pi8N%Qb7615Pws#@dr zgJr`Iw_PUy8?;POpiLXkEk%)Zq=DS*nlN9feg^w*5sRmyb5R%(s}u#*Bo|x%_yqV!S)x)uvBvep4D3bLGjJ?_@%tppmij05u zwvjQdk9Yc&$%w^E9bLyk5h0V}nlwjwB@nD#YDCQUEy8N~(pY>IuY};k+<&DnuVVSLQhZKFq*aMhi1<6Ih9d2#B!_ zP3}(ucB#G|Z#C=>0-~$niO{b7VI=bFlR*DcbUeilv$H+RLSO|Bvz0iyPprc2awkKt;+wQU$}z zOA-I~;-BAvPhE72lvG{+UOVPHq^G;zWg7q8@1W(!ctrjg`3QHvcXYi0j4ys~7>*RL zB8D0K=GMVO*)haw!o^*T_AYdo%OT9*l_Jl!tNi^#k-}`U`Y5p2u@f+C_F~u!R^zFn z)n4!OSLO|FMpALbj`AL;$!nq+X-N~1jzG3?GbTu+HINdi^tLvZg6sX#FStSNVC!Oo za9bA}giEu8nU0no)FV@J|!GiS5g};&!NM;U9L<{wozn{F$FaeJw~KNZUT}u!kZF1 z4uO{?6%Qs0Dq8bKT!xkZ0}^t_+YTiW3Adw^nk3|ow;_^9-B%Yu_Ss!?xKDHqO8x>N zW=cNM%+HG_6=tL4QDE#mju>g<#a1J|x&I~=!Gh1C?QK*9@&pi2u~B`5 zA46CXvW_C;?i>EQgk<0GjVOr-`9q`25t4baFOo1XW+OmL!+LEbw=AvaRAQ~>!90p= z?QvaIrL&xRkj4tL^&pABVn6DWU=1E^BjvQw-rPXzl!_kYR|pHY4zjF(=Aa(rw8ALM zJkf(314hfkR*VsS5-W;~G2X%2OnlmmG2WfjI7Lu!TTWyAO#uwsGBBkj2W^DJl*>o# z8{@=S_@Y*++=`Y++ct>T@l8Zn4A!INwLUih!G6*cJ$M0=7qLqw{Ag&+ehA+p{AQUG zv5p}J@d926W>t?9-moHjXQ0-AaeZx_ibt*i3&qn#=RwuQ8n7PJ83pC1mVed2hCkjfh6IVwr{(2iZ1Qvh2j#%*GuUCKs z7JqF-3|$BAPMPSfD-V*fExPtXnz4cBjHd(~0dAmW1_Kpllh;1L*jz5k7c5akBidK< zy;HQk4KbsCqtJR(PibIKP#PE<#JOr#_cri+p2HXWEa&{5$*wa9zG``Xn2;QM6v3@h z-Q9*9vkJs`EQt6vO&5gQI*TA&b{14VkH>bQ5F&mK3XnvXoi!!lCBwx?q6TEoAiQv( zo@p&A991jNCZ{}Krq-0qgCsKvC$;cfdb1T~lheC^ExaC%wu(tM5^6UIIpr*sr8iW) zPFWTTIUS%do1FHhEN>Dn25u1FP2T=mSt53N-t4XZU&$zMSfdq9m5%c5Ad@&5jc@P* zvKdG(?(7xvJdhmWYmo~yRss=jF||NrIS}C(W9dgeOMoo9)tg&GyhvQ7trygiLR@bk zcUBM{EUq0b?`=Y_2POIsWOnN4e$5*7Ky8U_b|;AcUHJdEWwxU$7O%6wCcE4S+N2ef zz?tVlT9dUZ1Q)g#bgh+ihnL+>g3SuT$`2QYnO{PX!DeNiU%?Xv7*OPenPm!NNfm>P zkAU5B2Y8|*+)gwjyZR3AU^=Pe3_D^pvBvCq^(N(33JxoFm}?Y9xk;{j23YgS$gK-< z>jEFlgvs9WwEg&ue((eSiqk6>FU>u77$V5NK+|3nJ410)BsmHn1M-JB2Sg(G1Nq%ryw95$K?&v|`VZ^S6C>D@ zI1{l~MDnjh29tqovGPBh(A?@a9o)%Pwe>`6iRCfksDaapN35C)#mQ4EKX>VLte^~i z&fGq<=6g;#FBF=ddMK6O7dg!urJ%mV?W-Gz|CRWc&sX*IQ*T!%KTUi55tXVMVClVZ zD4jy9EPP=g97;GpA7P*9ucy#yiw6-ev=+ZHAzAy1k`ceJoPhzfpF<^Ylk#DHFTur< z8G^S<6lPPan}8je0S@gT-K=Rd!SDR$HCOw2`vLVPDN~!f+Tz z(Qd`Vhwk=frq0I0TT^irHKgR$R7Z8S)^KABoQffdJJmTZK*k(DZ_>%_R_EE?2AYod zht9^50Qth@dHLWdJu6zC!1_FzE{lmDO@nSU2Q{W#o`=|S#F~p0M4Qvcxm`;TKOzoC z+PvU;xAp+yTknA|&PQP1Js6vF(V@(XVRQ|gnD;VF9n8FatfD!WkqG8s4ERGcB@U(& z&qMK04sMOw5(k&m7yn!E&+ovr`u8~a65330a23LK4nB>z}|XfMXz1RqKc-lH%Z2fqo74TIO_3ZCN?r{B)SYBqko2$z6L6}?iuPFYGe zeo|pJHh!G4r2QRZ=h?DcIM2ITbAcFH^TE%b)Wf)80qi!ArYxX4DJXR(1*Ps}ROn6) z3f)OTK4U^I{ydDl1B*YuK};ya#mDYNez6Lm=IRK_QX1fpivWh>MZt zbs+7@#P4Jr_yAr6?DXI&+t^T<4K;AK@^3g7ij&zOKbv=YJiAD+VVQmCpv;EQmzfO( zZwIB9Y)C|5v*8ZZo7nJVUGaY$|FTfYhLlt)QVJ?XN?~mE=;-Q(9HiyY9>HMC;Tj-p z=O=4dA(-{-pw?FYecr?XA7;RE$O|*Wpl6wpuECwKk`FIHL>RO2;W=RJirjmjjcJbG zcNsoBpkAjeB_DpFFdHB41IBzfxzLv7vO@22t#93PzUKFPM>w^!u}Jg)R_jRO$WEN8 zAUbgh{*R1!@j+0m5;Q);XDnEQAM(1jZxO$=0K?1-XZhy{9~JjU$R!pZ0TDC0>XejH zAQ!B*7e*zAzky)&MQhdhq3x_X4`XN<$_H0wx{?1A(;2V54`z<4$;|%&-?3|QGAd4d zcPd8wpTPhB58t&TVs%F*a+HZ!2gGdL2P6}S9AzTb6tS$oc{8aOFSAehMLi1{F-q)$u7;JNxEfZ5;xw#e4C8ap zpl0=#pfDnMtROU3vVJxhmlR|N+FeK@9cZ^x9hYERQU4|0<|M2|o_?9;nhYGvm#3BY z0wEY%53E3g>93jD3L}CQh(n341GZ@i%pTY%yq%zO33ezjsj<0BEdohWZz4Cf2&93+ zD7R7!2a26$EHGXKGI=TF6qXcwe3mWst`rq~4%ZYFqooQR=9lO;R0UOwmMP5Eq8|a{ z<CHco7cNt9>fc{8{vD8z@te(_}(Lg>miJLk9e(D1j7HsX&JIoHTjHBPs0&4zd4 z?MTqH@-HasX*H9I9SH{MpCC3DOFxFyz@<$_q`kOqP@c8(38CzQUgjMMSgI15Dep+Y zQk76#c7~McQreLKy4(o5keK`sCH@cNUw)G84=J_m4=JenLxz__ySGCQVoQSc-5XdE z(F$?7Ap!YkASO2?ESWjT9g~bWZAg%1v<`?QZ%D{#II)(?i8Q<*n&(-nqhbB85W@!{ zl^WJvWrUS~37KW4KhxTOMroPC!1QYhk*+wb{3BquSddC+FrFY-ZFzAA6v=oI?t3c6 zFs3lfT%q1XZfYoRDvU))40j#_R`8@v#-Di-2HeHSbH0I3c^`3V&qQLZ{Isy(h(=PL ziV&3YL_sM}j0$<;ppYjD(vrn!9H@6lbDAY+lVf7|Dv|X-ei9>M98OPZ)&Myy`ca(v zLdcUq>Io;1M2dja5p#%GPeo}S1`=T%`eM*k)(6iD1}m~FVHyUn*SOaV#>s@kxvOZ! zAY5`SeL(6;F$@lR?xYoiVz3a5(;#9bGi(qp8J6-}&_~a}H56tSRGAp|jR^6-1OHqN zuqO3Jlvc7U1$(T*8vQuDvraG_VSJqgrgn$|VR$445|P*(O~@Z;z^!i&Omb7?7ep`| zZfCV#?QPO^4>@HU;ubP_qSwb@RL0f=tHkMDrQzoL3L~D8CwjdN?9tWW8MuFVL4N6K z?{tyd%(k%Aa8g%+%Y0nDNx8`ry_PDBa+4=|Jpydn8e48JuJMi%xz)l2OqJ-1N;Pw$ zdXsW123Dw?l*lv{?dLVg0qeOBFKRIn>3 zICmi~L@f3`uZ^yK&i8Gx_bI3LFE@7mKJU%d4kPf!^WF{Aol#p4`3CC}Wf&I|QUA{@ zK=%?!cuP}upb*UW5-B*4nl7I4r#{>_5T;GZD*20Ee>k_LdeHDpu|14y1YTu>qdfMkmb?GkBv0y!)0dXva?Ku+=j zWzjoDnrnglED%}N)j;}-v(hBe1W0d@vn;C-kX&o}s)<*PD0Z3M-$IXBTvPV+6I$+`IJ^(bCKRU?skBr(6eq6{R3j_rE^lOZHgo58|pj<;}%jeib~Z`_HFH-2ww58QC`Ej>?*{#p|vchj<5QYms$M zwY4a+XNo+~V(D!GUvjU(t?LYux5JzX#|h!WK|!;XVDY0shKo(AWE29a0P?jMhEA!@ zamVaO{8!kR>Jzr2F7E@YEjmr!G=U=vNF$0 zxa+Po0>*oUS%_|lv2(x*ffYoU3lv7$Ee}{mggFP;))MH-cu4sIC= zVo5JG5(Sse@&_+IiS1yc&^h94%I;1m<9DHxIv{YG0+|TJzK1|l1hOcQg1}G;#3L~6 zJvb=2e4DiK@n7w7iR;SjQn;2JlwE7$lFPY@$FuXS%=cldgucwS#U*CtpiFrkw7X`e zlEo=gwk_~=?>Pix_q$ZZjNS+Tigrub`Aex=dwCLrg0L>y)x(Qx@FE!)GV#SH^V@|3 zUIsXJ(dZ;=&0cRU*F%W$@}Wd)H{#kt#D{*Rx3m7(>m5K%UP27CCJ$C?L0I`vjTs1s zHzddllC*Cb8g;W}pLMjak(oLw=lb?FiU14aSw}oMh zW1;?*|C*+)!eDdSwryuLw0jxu?GG zzoqcvt*mSa9gkxrtu|%e^{#u7T%2N07pqbRcL5Q%6)5C(AP>=CGsDU$_eK+|me~26 zH`{90p9{r#vn|Z+P+ayJR1s{p%^p#xnYV6-qMyLr9+Wljx4oq%&iidKE)C6EiWbv# z-Jm|!ou9$!8k&g5nV3)r#q;GXStu?=i!#MHvq>sZ>GumlrtbMu{NIg#eh+#{$QC7+ zvPHpDC$d{xXZ{#ki(9D-uhZ6B`O4DIp{(Bmb~BG>tnWU@h9Mu~j|9?8?Jz7W9%sN% z=`Y~XU4cg!YqqNmcsXDmX(qZU)shQUzGYu{aYsh3TF!@)yANm7GJglBK?;gIGa*x& zxH<8x!ieKbAydUT9~W5VSK#h!bcPGSKYrcl*tFkQp8crpDmYSG5UaMZGETxz}t1!y45F%ONFfCv>pCsNI zv_FugZ`ywE9v4Yn5eP542@1+?f`YP}prGs~C@8xL3i6!8yR!5BqY85leEEY!Du6T> zHmJ0P_XEigcA>N;%YghWEKZ5+1@a@?m+^0koOc5`1p8OjRj>|~-(zZbW!>{p6)VS& zace7)d|9i(DcW)brd6O*T0%&L=#+}=Ldnh_j7>RbTW7`2AB;^yaVeBkG=wt88gR%P zNs<$kDY<=)7S?>3+&)Jit%*xb*$y} zQJwsv@;8MMuUA4QAkGf}TlfQnF%hjoQ^vj@aHxyQO-V_$d zH=4d1^dlrkWjXCfY=4my{9g(VEp&*cWxAD)atFSCi#P#@HsAv}hZfo>H_g!%9%m4L zK}^oc%fOBT5x1!E`BQkO0*E+SLLvKsOtf<64Q_5dc0_3SAU-8W53Rfo{e%F}d@puWVXQB~qU0{@cA|1+Q7>unbfDvU-R zm@iIo83+V?JVew1K;Yv^(Rw0)$>OW6AAiR39zSaoqshSvP0mY3yQeesG%&D2io#e= z1JfL4Ltwm!yZeUE!Pg#YZ}#V~yTrwH=>pCY*69h@G5 zdX?ZaS6b!Qjp6N4>k)g32O|lzR~66K09g*{qGfL$*K3PRxm3KEvq6Rqk8+5X$T@=pfHANTOEd4MP|^f0|m)p7g#%r?ZHK zO~rzaG0-{?*fLKy+-@o97@;s59cuyO1;|gG0v-Q_vZxEqeztE9RqmS@tB5Mts5gE_ z&yHF-$T6XMe2Vq~0@IH6Oo`otz=x7pJ@FY#tP`jIyTqE>c2e_tD2Qm4bXi*QRMR{p zkyA}GseY%%Hnkd_^^UDUsyrwFCe>>JQuR=njZ|GoO`e5rI|p*mKD;Amv4K~%)a99M z%P+8*s!+#L9v1WV9`Mv@B2BM}DX~Woctg_b)?Wp^jEK#`p%BV1|0#d%L}5g;Y!vht z{Iw2A6n{O9Fdq~f%32E`z)Y{_=#o?+qH`2xqt{GeJePUkSFqNvAQ~O~lYQUdOsmCj z-u73f9G~5iQaISHbw)jCF4NTp0kKUgfv+8Ql(zt)HZN}Ymt;5Z@BdwP$*c#Amr~LBwbn-mfMP(WLr*|baM;X~-pTLw8!6EPZgFQBNQE2KjaDkig3BfGf&$Bd5GO*G`m7Mv;>lN z5q7u-f$WR0!?||0o{Q(4a6oJgoRKlUAZQKqG!;JNCEx(A~Brvgk5o|!_$V6ZZ zXAMrUS~_(W(K3jrZ=h43L5Om8p`z*0@%2Zv;7hz7kmnY z=5Wah8G1&_<(c()6}~3o-Nn=|dCb9Sj{xbyDIz7Z7|2_-^_mjN?%K;pj~X0=N{?M4?;hR9S`?wP zfg04#?&TMgbTj&tbl+ zFk*rXA&k3$@g|-1QF>$QFH5Mu{3uFiy3$|42%+DqDhh?>koO3_|r*gc#N$hXkKDhgEmaZ+!MM*^SohSt~BwWfO z1z8r;k%VQjAqD6dvBzTcx+FqHo*!`ER57Shh!r@HR2Il?xGTFrQ14fP;jZie^-cq0 z>Ya!QP|p_|t50WDM#Wy9d~~t5HVr(HwJ?{vt6LCWECy3j!%YA}E=5vf6(^(`Tl~CV zjRle7KP6oU6h@@;p`gDYT_Yr6($%Mc|Maj8_4Q;w{nliJm6NydG&q^**VyTIfgBT< zpr5oceguZ)qdZKYwO&@IIDNTLXfK8N720NdZfG5{G1l92%LA6-FpGh?8`yHoZlLeb z>f@8nH_(%`D6mChyw3LDU$+eJYNu^U8CcMWH*DLIfOG&Nwk5^Wc|AZffs7DB``4NJ z@0rI7k$7Qpz(WEg42aD`0^|?Wd6Knuu(!F9@*G+`n{9yL7MDBRxwY)}3ELqfNkIjr zms*eN$UEGhO}vZ*svYj3FRLByp}5p~lqoMG-Gq7*8)Y6B|E=)P?*vI=V2Arsq^BM3 zGL3zQ`+Pj29q#fG?{J?CEU?3U5@PHe8J7eWgf$YR0DD5fnFWVyei802upklc3`|@v zfm~>~N_^-$o}|xb5iSadFa@Osq#zFz1`pBQ+ID>9>12$$HY2cr-D7NvR65F^2Xe0z z;%3K`@@p(eU-TEsF9^3OzaU&HKdK3PMCPI-BK?J*ndF2^OI;6TTE_EoBqoJCiGv5(0}Av^2Me~{l_H>Q;vc*;<5hQ z3W6y8_aef<`foK5rT^0LQM?>?&sx9!3!;Wi{{`Xy2KBh>n1#ZKdR0d+M?LO3Mk5L9 zKLY^__M7*1Zp^{nGTMh7Nvfu=K9@EkB-=`yw{kNeo zqGQL)(viphPa%mM`KL8 z(Fa|kBdY`7*5ke2G`gaO8Zt04Ri(YSJYT_l+L&xhoHmvfEiI&XkxB5O7(0P%6E?8i z(Y_ssF0ADFbFkHFGvb4Jtw(qJsfx~=L zU}dZ^^8}CifUTZ`!S5%n(A}skPq)%Hhktr&h0qLd8Oz^LuskH z(NJ7S(Llcw~&OpQ6B<)8XMUZPe782L6Jg-`3$6% zDMvR47YNF&5Lgi9OkhLXLoUAnas1x$ZSD2;SEgLRTRs9cU~l4n@Azo%FV`--4F&jGPU#B6F%~9rO2{ z^xn+dY6TYYxFyR`dlTposlUr|)Or!pc}tE|`6hJMzjI!>L53vu=ZSjDAm!^tzC`rT4q@8XnX}_+mqU+qI(B3`9n&8x6J_^Bn#E$Jutc(f%;yy$@pL;g z^63O*4%TMLLM5wH`B*)W70oj*&hiwb+G({N;Z17fERRQoP8M=v6E~0SQH>{14RudW zho>Q#aAt9qHdUJ+(0*n1VS|&d+r-L>(DaM`yhM^ob-^&8kySTaucc^la7_oGpY=S}huQko#BF7scj$(1to|toGmF8N zj5Wqhx_Q7d!pv0yE8!kb0|qHrP8DzkL_u1NruCG3Pg8_9uYe` z2{D0)ot^O#c?8IXK>J=HQ~AQp^a5=KO^l!%$0J%TcnIe}5OO_`->mX`yjWWvX3lvM zjg95mp^e8LO)Sq2#o41dtR_xld)e5#Qm{(ynm$5N1#^nLej+qe4?63kX*DyI{VLO~ zkKU}28&xNvdE|TX{}BFVp?1bU9+5@&RMN*DtH9`a_SJE~3GpCtO)2s!#_=PNCdSTz2Md7}p#Kn<;K4j#84hy=u&(`t z4ac($Gy3WE{5s?>+V!3BsF8-V5vkI&>H&?4Xfs3u%N__x1)`QctUic7C1SM4$g$A2 zQ8mfR{l#SjoV!?9=b_CbyI5+5PX~=_R{vK?{<~37O)`G!9oJDifFu~_Ct2zGxLR5{ zVmOf~m(+L(sc#xkkpWx+0SEC)JY~3}8Ny40tW5$dVgZ(etQUa608XH70RyNKHj z(%bs8RPFJQJ97MK}Kam`1-HZ2I+&H}<~ zl%^mc_HmPNHcs>#ayk?S^Vbh`{f68ifeHS~05fO~voA03vS+Uy+J^fib0h^Tp0zW z!qlsvOX-2-In3Dt3!>g#!1!wBL&I&-sg2O{uS`8QgHP`5;&u^#h%0ejtq~N4Fy9Lv z+YE7K2EX{N^d0qk0{rS`O%+6q|A2bzgZmRyBkCakyWp z6^pA$-+-_(+1AJSJxBi#SddbC8Q8v&&_Eb+@y2!c4PsPZ;_*TqmV)5LFbQnAss80L zdv0hH>R+fYrpfc4{A&ghW0f7Sp#RKHmU|LhxSF_a~j$k zj>r86c4=cius{gtAYl0+KJvc6 z*vI?WI5FB{AMe(2m|+zax1@TbI!g7%K`caKZy{9JpZH4K3@eadf$$6~!Y2?`Gpth% zz+Rf5x1cgRleez^e$l{-*<2ud2vIua6@wgn%Cmr};A8<4GfmC=1y;7E7+5JVI0O~~v+hI#yo7o_Hov#E?@oQXs@-^0+RgRHp32=(JsYbB zOQ-7{>tv%W`Brr&>rhzV263{U9c)jmMN>y5U5~1@0+@**_WFD0o~yX`);AsLSEt^N zYEvyM3ez!ANH;w{G&AF6%`5VNWdK9X>&lu}XuvAdOsaVluv_l3)qM3`dVW{Vtuhq@ z*i_Tg4X2@^wHYf0RtOBaeJilCiUMGHz>wQlz`D)|C#`1dO|^f1QRN#pThDj8`vN-peNSuX ztv!={U)`hM^O5TVDAeo9=b)WDyjLmtJ?uyaRsTONtvma5O{kYx=_C^;yqxL z?+)HX*nqYU%M#y|PxkW@>*PX^=~ZBj1exkABC;W#Ajp_W@nXd5TQ5H|v4J&sksek5 zX_*J@H~Clurs#Wg<#5{C9=7#=ThYGJtclxwCR< z<{&SxIuy?*XT-po_-;5@WQ}OAqqYt$uxT--BtkRrke4I2W(K*Gabit;B1kARwtXsA zC}hQB&nA6aG`?$3fFP^xgGF{8#Xrx(#&{k!Lf(K_fyT1sHTAl_*gWAZKY$clcwRP= z=Cpv6msj}~7Gkb^Ae2U#=Uf~tRwzrYR{11|DPa{+Ip$&fJQL$h$C@a!=b|WcoOo8^ ze+Gr(n22XNQRek{*7X6si~CjZ9QAN>AJFrM1?5yX(RAcQnmyAa&E}UY#eruP5oY@3 zO4%J@_FNNTCgEAugL;2|DGMLe^R-1_`N{|NmfEb(t9-E!>1W*;j!&zs+RpooUt^us zN8_B;6&d}j(;RWfcRL)zY3lskC)i`R42urY0ws|BsSQRGvr#a$3D4C~uyq`31V%gh z(NmcdRa)NK_X22I;4HrnMYglf9vz*m-HYJDysmtt=v@f6vi9V4Z4kXlB)lESSgYQq zTt9LnkQ+En|bSdfFRN(YYox=?$O2STOYsPGY|9Nh6*FI)z+)9Ld;WB_}ZgYpgPB;#o;7LabXjZV5+^E629`@UiyU;2^>7QY*p9d)I(ntP zNZa!sK7^lgEm(Un0?QDH>5afDY+aRKojQOg zRw%cNGjWHbgt5#)Q2=*Ys$fhH<{?TvbsZSTjl9~4xrCkTutMt62dMIA!&wxo5N;xN z#mlX>r-7vMc3dm->WOac2;$9)g>nxXljPTfI2_3#84JP}lbD>YiB}wCn60`e@zA?9%PYb|l-JaHZL9u;Ru3tbmFT?(aN#zaV=--Ze!pLJD880V zhJ7`02fAtT0lw6i^%!U5S(xqei)xVB1%4y2G7|ra3 z*B=Vge!?qrU(=tjdkreNzJB7P%SSslJRIq$w$fAUHq>6n<4bGvQ>=-fT^DW5+@ZJ8 z-arN~?trR%fS&EpJ7`3WPOs~pxTOe849ltB7TNGoV&QL);to8}ZYza)eO=Gzj;F}u zg?qaa^e=UolhCpxRh|<8m-hsP)lEXDhje)kb2PA_cXW@pa(1HQc?yOZ9fLBoXU|Mu z(N29g3rQJ17D7U|p-9dmg!DBliVR#7`!*dW;T+f@qdaOf z4P|j!;G)qe$*!=$9krX0B>M++FXIuQ`_6q6_vp7e<3_`%ZQ-mP<#;YV)`Q>Z;+EF8 zZ|if?RwLb_h-s-4TTV<}8!MK^2W4)6?xVn|X*jY-U<(#-cPSqG zQ{qfTOgMsLKHII9Jp<=o;|qzr0%TdixFpVW zBO>$o(wh+(VdWpp25X>`3vFt4`{L-A8aTOqar8?lPHtcM&2am+vkvTqFF7=klg3`n zYZm4tpKn%8oP54A)7Bqg=6MXNPW<-WF7f{@{^j#6qy6MNb(5dI<0tqBtvC}~5cL{l z!d_p@;(~rxAsTS|64Dq5yM1xk3Ze}V#qus(y^_$gwpH|@el&4o0{U0YxjE-RuM2-` zozwCqIOP@}=xHtcNFSB<%Uf7I(0I*|0ZI9(=@GZ5-i`Mi_^$>d&)8k%bAPPQ3DX84 zRpF=ltfB8gcKX9Su8mjHBYI!h8@jNGDBFn=jytFqwX9qo_ z?C5!uoq^}Yc;0uP-k~pLm|jO@RvVc)Qq~WNK;n@yvvgpO$;{{(Wk%06nHfF5AJ0qo z={rQf^h1VU))pfZ?w2Z({U<)nQy57{sW8ZA1M`&$Su5eIrpq8}{3gj-F=VaKX;PI` zZc6?Pg;8!9!Z02TY(lv$H>+I#gv6`_A|=I)f-GhfkYYwbDQ4m^^9co0KSwwCExs75 zAI+W(tSO&Eoqmq^=?||r`ET20`Ycrm@N)eaSEuT>Q4a8@Q=O-!tD&jL( zwyexAgaDM-6|POHg7JV<1>sVvsJ0|kBT8||>P!f%kfETYEL%c`f^m|qPApqNxRfm> z4;@)rh>i@kC-M5}4e|d2{w0B>cu{I8UKEt##nof+LM9!Mi4reFGZD3k7m%hvlz1VU zf+$WGn=TmROc%d$Jp=w@#&``o=8K_lk@&d6h%pL8xB3$>?pEu54JG^-7=j$i?Y`FE zRop>Vrwf%-4o3M+a3{B3VR&72VT+k>R$21ZYO!k4`tG~o?m7?I@b#o+8^$5^e4x+C ze)i()vY)m7*pER3=WVw&iTt9A4I;m-iw(kM7fU4FwX|!q`omBZwaJ$#M%G()v6SS~ zj>9^-IwJ|swj{ZnQzx9I&(>g?cI?WjFFi{kJO- zY}J;r=#S6@f1-NNad%DQIYNE~vc@{Qa%f@$ik?99S;=ive4ty!#BQlpk0XNHf=Iw5 zYsbPKgfq#y*2HZj+jTKFBOax_jnar}y--q3s(pG%r>&^wi%7*Qi*koqy4XYn!*h+W$qr$*Bzke)>1PrIr4x-cRc& zQpNig{i;uPYG1y}4{y_6M*!*LeRuw@=Qy=Vh`w5-kJ1Js5PME9C%!82bi+VS^3bgy z1Y_%QnYrYl0)-J@Y2d3$tQ-WETn)au7lS+Et6|l8|KvLOaAgEUB20bwA0VY0VPCbr zIQ%v--j3P8rqCG(=+ck;K^~~m(!2tP>BI-IVuLk=Xf^69m@$!<5y)8}Yb5vG^-2}5 zPff8}o=5M7Ldt3gY^$8=P@K6BTp5ZJ_c4YZ`n=w({`)A3n4>?6k$7tpx5Nuu8LZb) zdkIO1@0O<%SPf++C zltWujTV2ox7bJi#EucJihvn?7-EzRrDp1!^yG5#FcazjuJlh?fv-6w{iv;#?f}>=2 zB+^eAypt>{m0qLtF*!Sbw_z7i_ir!gI<-_8nn$)21!YT7kbNVvA!^}`wZefQkv~Bv zu^zDjwbZYOJ|$af*2`70rBW{aAGFkmD2iHY5Q_PWmfDIW{+4$V*eEjnkbW>RE#NQj*!((tA ziZj=v=MTkgT+f5(A{0intdD|f(vk7t4w=DZU2rIn1rs(rFwpnw|tQOA-~%$?8Snj%_1> z(YMEMfj)!#%Td;YbRG}`Dw>ZQc4UiQdQVkmxyR=&f+4aF;jdg0pFF`6|hkcIuY zSrl4{e|`ruOG3@?Ck-$v5oEb3bvWAxTu-%{l} z9%Hz|qE+>qkmODLHYwfLxSr9*)zw2@y=!oBoK!(|(1eWb#VuTD3{vv76-JFz3I;EB zm>RH!f957wD-+O2^FWJd(MWG47%Pd(`J;q#r=YD#)OifFX8N_4lqp6xL=#d11jblW z97Wb6q71T@o1jY@8ZB#3olOetD+r}7v$s(8L9Ha&n`*@-1+P%oKRU>0c6!I;q zo%`f#Em!vR6*n^KIcq(HM=M%(Z)$y)Y{W**L5%9qX=9aDm27wxUXAWzfTyL|f6j*2 z&~_ybZyqwV+v6mq{tw)fB)LNwG~3_&~~V@dl|Fd)??)j6p^xbB<7q zLAXsZ2H}!(sCZszb`DKNO?EE|l9iQmN=bO3*>^}H7n*&E;IuSjdBzOX5xQl^rC7&~ zqwwTLEFS+_w#za7Bh4{$GmP9$Oe9;+luz>_5PwLC_#i`@n`2fgvD03Zq9V6x9_*Ou+Zs^u1235;I z_(8DANjMO)n;9Fl1t8_|W=8+(?m&PH)jz(C-Ecn6QJv;?Oh1kZbLh7s=(p;l1!3lS z%)Z7ihT|>QY0~WL6&aO|f{KRsgnF3m>#^v8=U)}F8HiXU#xu0q^N44)FmUh^+ERI& zJS|$Aq%0WA5M88aO>6T$g;hexN*$&LZ90Ebm2Y(mqrX$@15zDtX(VacFT$sHwegfQ zZT|~mO6p(5u^TE@_rnT@Wd90>ay)yhmGMAi1_J$sbl&L~AUx2DHRsfo#cl6Y1 zW6n{SY6sAKCNMHrd@qQ||$Fn2tj7;CeYmJFct?W6t zFxwd(?R^A*KMA$po2lbtYES?Tf|6qHV19t#>AYk0Y6(BwbX=wCHWN(G> zZ{H5a%lwHRxJoNu$#Oy7drPgBzG=E-eOOD}6$}bnDITMgvvc#qY=Zhj`6$Qx%-r z!&sO0&bq+cdl07XVBuQ+)-u`~@_i3ugnEH)(6P$)4Xj(|vDZXXet|dk@HyR)68RX& z>A#B`YAEj=Smq$VS_&h5YLE6~JGwUFu^1(!(n$^YrgcF6f!1CqTb_I}w_(6NG{?vs zz`59T?;$c)x8_ub;!gBJM}0N%beuFKYjO%Z=i=qg`aJzw547%_}$WX^d0Uz51oE~d<%Bih z3^`fp7$w|+p_F5D0=-r!&gKLrD?@QICnVW;hIt#xBmU`#vLtS6bDm*-3Q2f|*+gJr zFJn$zeI$PMV&3O7!M?Oo{aQST>TR@)YA$p8aW!7)4HeTER4?dlWNLNSRrwz84GUBd z9yg(^DZmvNg<<7Y;D083oA&0K;;{0=rD5hT3M0Zp7t^u(CxLz62ZSFb#ecVd81;&j)+yTi%D&_6fBiWzA1@YNb@c%AOmE1`*AuJVl;Vr+1_+aY!@Vo_dW zt+VzA&sJG=X>|73!nCV>2X$kM)2#!05+ki?CEXhNHV-qVIo&6psj}JwLKY)@_lz+5 zIo5Of#~82 z6vnzAnC3Lc1Dn>nPlDBU6wJes7~9bi@WV!7bd!rm%SIVX+#pj4S!x-hjkUxFCD2kA zZ;5P2H*KAv$_W)guoO%RO6^@l=;0`FC060cKzv6&Yg;>7>%A=X`NMR^VNQAHv#u8m!CoR^eFm z%D+6toIn+oB1yp>BgSM|Cld#|V@9A-d&MWx1Gb3hAbNaEFFbmgN9y&Z`P2$(Qu9makDCUsq`!nk3e|1^gg2`u}?o(b0C@uFe)Z2sc$@H5FT zm$arj*=P+v6E0|aT6G`R&IyLw^%mm7#grhs6CV)eWaXSVq$MbfWG?oyl;&xqyO6{`jdVLAvE95^TfOs*WI;h+(jf(EXn80~W6=XG*SVX9V@p>U}f zsd1nfGg9!CPoP@VJ_%2X{|5M%Rj^3}7@tR9vys}S9`XJ(Ancx6^ZDTVzScJx9i5ub zs`A}(v+-qQR9#pAr{f*<>wXq)^__0)h>HdAGj?*4+qL z>Cg3Q=DTmHaig>AAr#~B;$+XtNbqZ<`699a4`U}EPWCJYRv2lnQ&=xFb^)-wNOL8y zv?8N}y9?AV9L>HlMd*x4B#Jx}aWth|(R`hHm9mp7nmZ_rva1v;n%e;T+yvjZM|QNB zIqL65om$#;kD)tWVf5ElFT?(#6~+el-gK-9@ig@%TE<|f*6A^{<&(yIr}p)uRlXxn z8SjQ`O&_W9ZCzu`(zL!0SNWPhXUuZDH>Nwz48U8(n~Vsj*7QM)$zL+w)&BKhm2dWD z<9TOd^#d3^VI_W5Mp*UH=3&*ubhiR)x7GM9JVFfbmhQw2DEu_J;PM~|cx zYNy8V-;iEiQ&+rfG}dlIacM6bDOx@P*%TOszyu2D2rQ&Pe*{)jAQx47>t(|eR(J3H z!Bw(yeu=wEn+*v_+-8jG#FesH)@y0U$Vl9iMs=~{w76)3AGcoIX6Q9uUQCIOz$p~+ zGV9mVe%#91Zp15c{5v$@`-LQNwnP1AfTXK=#3;^rbCxFq*&)V|-Lr0VyW$YXP#!Bp zttJ0J2N8vMF~|Avu3~4o24sd9?01-9eZamQ9Mm$KX>o}XYt+YFZJzo?)-Rrf|?w(qXa?hVVKYy=Itsxb_p$&}$XJ@PV z8^(sHvnadnwGOlGFP(kgzG2J{i$h^Wjvak3EDpOd)zL6N_4>tFKe@~B#Pu&kD?4sp zFyH5;T)cpyEqZ7vu_zv$f!ZecF63_p{1M|K+!;Mg}@5J z%-s{$lbgkb8l=HMxI^b{7KQQ{Z+4k`EZ&2XM7) zg5jaX@((d@lMz|1x*-qUsky8sPNtpwv;~iiNVRq!FxrqH1--nMR@x7%`7+<@hQ;wR zz1931qdIc(y*OS;5^EysmLd>g$hStvn0<4_!LN8s7~kk5f_$%9#m5tC$81NMo6u*= zG@`R_kBb?e!-FB**|W^R9DEkYUF?^PqoaF)JON}9ULH^V!R{|xxAZ;#Pb1sebr11) zH#c;@xRSE@0yql@D+4B#dJ}~aFG!`H0xazycp(ARq*3w6gK(s5NJsS#HMRbA(0JMX z0oXfpXJ2d6_eNV{68bQ{J5B`o0x%I|4==p5Ycs;ip9GOcvMVhb8jg@6Aj5<+O(G8i zDXuV9=21;63c>#cwcr4%ZF=X6+E?TO%K(P27znHZ${{x&r`PbT689+W1dr6i#HLgj``|tv3x}mVn{DP1K^x4>Su^N zIHs#fELFC8Lf;L4{6EsZJT9v0{eOlF3=FHX3bKr7N{VPMsHkizf&%KD1$PijbIsJu zN`=tem7ChtkEIfoTPkLKu9X{6nVAZoG_z7sGS^(P#;DNW`#I+h3^UdDkKZ5jn&-UF zx#ynyoab!MdCqgNJ|OMRqwB+-wDE7u({P!&2~`Tdc;H2Mg& z7^EV<o8I>`cbrD=jR3%rH+ zU=Iqe`C@1cF}wz_B*W+(UZ!aP9F1s%#aG*DL*I|In0--kuGJq;pVu5isk zooK7`5lUl6;q-LY1ITb7W9x?XcaoA)x^#Jhvow^_3Bl>kICZ@0x81J8n%Yr{*yYaw z&d;&Kf#D6fEbrFSSP!kf@3U~M8qL(YP%Czn^I*g5yJIFd6tP9n%^*C@v^}_F zg_G=V5Kf--&WQI`KXyKzP2ql$RNv^&0U68p%IPX%Fk~8#`0}1%exRQMoq?v*3G+UA z$R`6j$>ZyX?Wf+i+;D&d3c@3}NG;GwFl-6D7}jEyS*eu*Z5W9~8L(olY`K5awuqD(DG(0v4Ay zSSLJ*aJ*K`AhuW8H+II}B*xw*I2%9H8*pWhR-CHUPkp9=y1z!Q!lBSiW*f3&M z3}2*A0Cwjk7!dfliMUBhWmUYJX!=K1F)a}(2*Ik`_>L7!OC(2}O@RUz;U%nr$bBe$ z0b!gnSdfyCRNofs;XO}%x31!3$vMtJ9dpiRdXm}ts(e;F1^{ad+R|0XM*;uS7=?Yx-+_RUI{ z>N-?AW9NErNFMLXezjpt@_-fNCIet+^&&1wQ90@7C2n`u;V8h}wCWuBa5HgNAO-f| zw->+n@Y{`_T-aPJ4Lg`~@Igh+!NrMfBfGTk5jp(JoP#|+&pG(ri5w*{K>R>QeOfse zUUjlaqeBUhzTq(O{dzL^B46@>+k=(i5Srr%Uy-XnPY;xLA?#m?@TEWbhE%^v`2HEWX~lCP!(HhU8-sHnFK87a!Sx^ZA8`w&P0l90vz+h zmvvKPzE$h!g96kMDcj}f?jk%NQ>Jz^bE+V!2uGY(kl6{R3Q~*9w0(NKj;dz`UZdj7 zMGr4K)ArpNZ>R0MiU3uRf(mM{bG;U%DVJCD6b=p)!C*a{9N_3_p_`QL822sW@(`EoCZ!{8j!EpP`xcFd zE^AOs;xVm|i}x2>#2H$lcqEK{a>YKvO}sl{xY$Q4!~mKzLfk;rOASt~UJ_fidKpP) zx>t^*mWK3=mu6FaRsvbfZV2{M&!m0~q!=fB~ zQ=D-cNys&TnqE#DCC<~ij=&6d=0N%43u26XW0d&0-hUdaPAcH0%v89z<<0HFXtBGH zh}0ot#5Td5L6CyS8soA3WpsyXB4$ads{4IW-Wh!48~r0T5Zw_j;FhIymkGY{Au=(^ zDc>fvmhX)b6GYTld5vGPbQwQ`#v6x*qj6|BS~@+N)m&rTLd4ZX;m~lDbiy%?Y7VE{ zQwyV{&k^_HSh0`pEIxs@I}VQ(cL@=rVE~>dwh_FJLEJRj~)H%?Cz5 zAG{<0FA0#!N2vv{#ZdvaAg(Y#+U^*~LP=IJ1IG~dx@Q!iE7RNY%Bh^RTrDcwBj01=(beBjp7f);~fO2-C z7_0TVj;4nXuQ#C8cuj)jzBA&1GH8;R?-I4n%q#Z(#elkNwE=ZUw3JF4qX^6@~@Y!P}u z5Mx334h8WEI>CRN5 zxngJdl|^`Aa$dha1CbYY7q~;AYP{Ys_gT-6pZ}l45R0o;Mzdo z3!L#S@HfrULc>u%s+H{hlGskzHw?x}FNy1@cB;^(FOUJl-Iv6dgmXi&B{)xvb9yhk z2+ulnKg=n=4M#hQ{Om8Ko%qMYZ$p&25SQ4yI=HerF^nLjD*1is=c;Q?4MXfbAt|W%O-e0k)e~!h+tS= zAl8>qC>h>`{l1!a97K!tCZdE~;Lqjv4<}QWVo}}Dj zfC=tWkPV~UYGJEW=_dID6JJJdA0an7k+J+`aVXF2KnThKB}=@8*q((b z;Xag*j6Sa}6!!`vhCEO+2P3e!Kb_;Mi4#=q`Xza5=bSKXj|7UhSgOBlNhvAWQHn@6! z!I4ZLY0M``kcy-NNoveCl3W4tH!xQ~ob+9W30f3V_Gj)RY`KL1!SXc~zRl+?!|?8h za348k<=}8P9mqB8Mc)78uYQz+?RQofHWv^cAbfS1Xrg9W-lRKdi{|$yJc2mlt$_ki7n*Hz0#M9Ob17dts+nnDjBbFbRsbx4SBPe({3;&9b8DQR zD~$%e(HSp9pQ7e>XoZ-a;P`QdHh2!JJ10B}I97KmE~l*&-w5de*44zMz*w(EgRx#( zHjZ8`5<4sHR*9#z`fge9TEi!0%qbBkRmmh)k-smJU7{mB^WuZP;nnmC^4Y`Xfuc6; zPJu@`mJA0z3-zfTg1-d6vah+4z_{HqzH0{PG` zG5jccf5-FgjHuJ{z31~nShI*l@N?cQRB18*NqSX`@M-~~9GTQ&`a0oNaj%H}s;a?V zOKV@uZ!t?sj*`BGL^g@@_rtscahfQp+A$98UsDr_c}Jx5CE_Np!QA3~aDf!5AFmPf zo4(~&IC@Jm;-Vv@rHGrpw(%{>;k9BnA&ClXFv2^D z5Q0uRSo%%y-SH-BpW(>5rZN~EWU%yx4Wo{$7+68Dv>sTO^}ORMXBLp_#b#O|e-Kp3 z8^k!_L^gIjH;7Mr_$|SNbSZwCHYxRn&M@eHQ|#6VMgTOVD3jk5rwT&mK+HYL#cs0y zJL0b-KP3>7`3v&G^sitmN)11}=*47<;x`*(OwfYXl=}1m8zX6<_mV#d99Ivx6{jvB$t5u(6E(Lfh z?CW*(dG`cQ)(^=h$<<55aJSwdyUQuo?7*Ned1O~0#>PA_vFh#?11yA%NI~lO84jdd zW2$VrNI^YArAO3@Y^A1G*K#gEKK?HjPtSpelNIs2-*V^+&9fq#dz@MKpZwSq#j;;K zp%sp%!9?IAF+(qOO~JPEr{Zj{r!k$nffGCiB)b2pxKu0bO@_aw&&4*bgYs#rrD@i% zM1PP9M+m?gx~b&mSZBctV4RN#yEP525~hy>40M#z2yiNVOw<42Z%d-99C?i z^|ZL28gA1G2kjsvWKctEimN^b9q}VjD5+n5W5>8i+4YRrfm&~qhx2JmS8&cWpL`5@ zHQ@4uGvXrQ!$ef<8F8up0{Uz^l)^lvxg7#IM%K3V4v~L6D}F&zTSe*# zoA=DwNla=R<*93H44^(3Kz*cXj&USUHQpFNy`>3=gVaKGeol;O5UPZ8qCqRX*%#KO z--%}gzlj)s(1seupri|8pGHs}gO*ZGF78jO-8UVDRC{AO=g!GZRb$zK-yQhISgzkvcc|V3(uSMo z&}ubCTm2s(2Dx*3W?OmTEiqT9?}pZWOPnXP$;9;GXR&i8dzGC|fh%dvzdPbwNo#S! zld%?8iyIl#BQlI{J;P%M-b~8c_wYtFo*i@J-@wlQ1|bPM|LX%{^=)w-@e-CSWHQc| zhG)TShRuS%ee{Svn$rr`-l4hR~8XPfv=70(rU%mY0-*zGekj;>(6l!+ljdS<7c%!(aU$npyKr!a??OI?s(hcEd3*wn^!N2)j*6??1ZmP0CLPJisaOl|#am zhkuC6TxhTIuHi58^Xd(qinr7k0>Q9;a5obJOz@U^+Av~htrwW=C3OW>Sr4(Ci)jKG zS^ils9#gaHO3qkd6i}v-rlT4gvMUBwpphooFv>0sSd2z`vfG1okBpslGx?-LNzfW$ zHh{0HLf`wav{7Ghfb|uGPE#7tF|WcY8&5lbT|Lx$kL&?r;oGJ^hmO#>ZAJKbHpa_7EfC&}@GP!C8|`Y;2{OVHT#e_cd#SST#V^sa z9Gm@4cuU~e?03YIvA3Xp;VL)dBx-w2@++cc`Qj9(=Sp!P@Y?DIT#0u#PSpzQFkRfN zGd`)+-|xu8g?M!G2<&w@V?|)4;I)+zc$l+t^L_BBmrz z5-Os%@g5VwDnp?G%UNG6XMLnosIP|XDt#c9KGK&qjIt{RR^TIj25f;JWNTSoF{LEsGCvf}v$zADOsw!v=7wRIguDpkC;1W~uS2$g z%mi{-o{qC zQq+XOIKnCGiV$RRpLM!T%3DGEJy85QW*v?7oLXM8j+dib{Y`l*pamxTTgQhhh{duq zuKBzn)A`x(FRePwu8T$AfR51izVMWe!Balr0&xv-{*7^}z|m(;d)yo!M4c;|#7U&O z-bo@w_JD*-m`guAYz012UACKrK@) zkT5<(XZ;L2r6CBzDZtrg2IZYL##GnDBJ7zmi^MWa7K(9=BiaXgxN^g3^m+xr(s0z@ zhOr(Fm;kq+!2FU;!E(>Xjp5Y8m5_#VKBsLFKnR>bniqyCkLNUGqVqh!`ps^arr$7QwX{#{tm6IQZwp70DV*K6B z<47x9>wz^1b9f{F-qV;X9EiacGrf#6w0=)xFB``U9=|AP?qMTe`8v^#3p|!>_|LeM{;U_v5i)^6OAeRKw}Hpf1q)o@Qp1rYoM`*P{Bj_!ZsCFI%F8f z>x4i9hOr^WQbCBsdU&XDws0i^xePU$gi{gl%rMNDuN9gjZn9{6QurNlUyH`kLJf#6 zM&nT7IEckYAp4N|s?m7RMGydOwHQ+bb4z&lu^2ya6BdSJ1Q>0s7GlCM6CPtcAxuD` z^s#ua8OY7C$e=HXL3wyAE)34&@{B{Z!Yn|w`G^|@B5fSXGyufLaTpc5Qq(wOmJp59 zT?&kEy9m#v)?XUTVb{g3Z zD?r!L83*a#Eua6pKbdi`)sg5(0YAc%qhlg7VboR7u61N;XiTK*(-{ZTJX*21Cq3Fk zzTNJzNcXAySqi^}bZ#>;>!K_< zXNs{+mkubv_8mKh6&~zYPjqIzcIdGk%btw`{c?4``oVDKS6b1pp292Ud2TE_(@&m! z)z~wKfI<&At%cX;($D(Uw^zf26PAChU;WD-<04br6-1W71FtQf#hvGIl$OPx=%>U_ zMO7pkfEc#4Zs%-dn|8vhX&)ac23^zo^B(_z*0|pNio{$T|wwi zW*H;g-UhK>u6S!ixZw?u@1rMn!_EYqNX$l?8{h7M+zkH|j*~0;=NRNwvyA#o_9FYP zfNatiB-c6O%qD%YGoFmL{jY^(orF67&PBo4zCW{p9)gg)UAne9JJ1voj9Te>=1a`j17cp#R6wD(JsGB%1y^K;r2?ZbrtzW02U6 zklYOX$1loKgt^A2b;8@tV2D&`EYgPW_lI(34*XQ=lCgIgaC3`#VNGA8@Ol|FPxW1e z!Aq@gBGvjPlGXPH>O)W)2&e`*+7)z44+#5!I5Mj zC%I~eyfq+A4a@^Xx)6Y4mG*H}@u*JG*-I_e|kSqLe?0yE{5A)sOrP0YMctT zuj*Oe=y`Fm#eF$qjj`?4ymdwws`T>4N+(ifEs?urEJYMN^^06Vn{f3qmI!+gzRm1H z<%so0UBFg^Z>ZLwf1!q^M`83@Z_FSOD0dQp)vT(U;7kN$XIz6yRg2dk0xP))IFyr} zJ7Ih1F4dz@9PCJbfg?4l2pEAh6@kG(j>yvN$F0J4;C|T7-LBW%9Ahk ztEc~zEBya@M?uWE&gpA|G<9^g@e7x*L9uR{W}96!&u0G2<0e0L?mr%GnxTX4^^VeV^_{j2#Y6;Fm_`A>o1}*>Kt(< zENz|fXb1~Si-|bzFFf4UFgvBj2QYRlfCL4_dksZ-zfn+ttO8;uC_r8Tas>Be4-S&e z9~&pp&|7ZE>xkJk)U0VPl1b0xqr^}J2Q;ecb%+h4p;uMC4gwZ+Ix9$iX%~jx02GF1 z+?#h9_iBYaH^fa%HORB}7=N&pnH{p@Wwt9m<1VdFpmcrF9eb;MvP;unATxnTo*^|2ggoP~Ak^F+Xi>d8X`}%B zevQ&R@j+@c*a2%kyyT~;s|nE5*LZ2_@?M!AH|~?M2MXL%Dh(r!C$tYe2 z6yFEM%|`Kp5r=kM{!Od)(gPGNG_9F@^#fy^a0k*6@?YZ>#taQ|q1=ce#0+9WG(Mbt zFq}%#KVt&kVq?_cp#JrY2@(An1E~}~Er8*JlMS4Kfp~Krm{a2i2Da&6pO}Y5B7XPV zYo1sOCSB5LbY8?x#*Fc97?JiHPiRN}6Eo;DnlJ-J zCx&%EQRx$?c-biKbQCWZ#c9GE6p5HK`6FXD;VV~MUH6eOLY))aHOz9<&LynM3=_LH zG|Zhg%&uX+1B^9H{{y^XR?*fz8fKPKc)&PbD}1a~Tc^h%-a4z$%c;Unq}n=(v~Qi? zxHz`XlR)fS=jRAJw$7E9d!lv5QNwI9OR{U2O>n!0*#uV`=0BI!zF`)lB=!ySMTB|7 z9Hu(BnhAs)TxIxcW=z7o@fy~`%Q3P4863V%Yv0)Z^`FG`ulGjf5r+63u~-y6j)vxi z--?tLlE#02rAb)i@6_3_AV@|tA420x8en11O~jUT2e5Zqigil}1fB?Cb!Gag!$6Fp@?ASgos60Bpe@*+Fv4V|LP* zbj)~;pFVx&2|SLGC&onzvpr5(3cxVZ1lcgk5*vQxH_sm!`OK3iercEG@-K~Xx@}Q7 z(~|#~eE3V_Q_Y7yCdKY;BV7#E%*ZTiCr#G2Qxc9Fhq}5BtGD71)}aB>^1G*ucWHbo zrxx%zTL}`md){z5rPy(D2CWSVng0?)n3n*KTo^tyUVn(j0c~~GL#w>H8mqI38yMRf!5I2)VwpYfQXqD31JtuS+-8ANx;WH5fWu(k=5wTlKCjBZlD z53s>l#s;f$`xyn>n%(J)my#omea<+oK-90rxfI;m`#)m`YM4zjHNYJHTAK62DdZe# zkTbpoHkN9p*&iqM6Q{jAT=lweE2+EhyGZvYzEn+z32zq<@Ny&I z+EJs*AZJa9X1fe@)EE1O0Tb1Q!j6N~(SKz;>C|M5p)>y$){FW+z|E=*e9V>vgpR)CwakNW94UNqE zyGhr|G*ae1VJ*5`IJxK!!H1@?KqGBLWigB-G7VUaMtTic;t$xZ!8C{zkMhhPj3-F0 zN=U9a1Bg_6Rw7rO$2uelCAPcJ#4Q2g9n2q66m9?@-CjJ9cfcePjecNi8~m)8a?Adg z$F-J|FBpdi-y+D|Q+0k1QiAmnd#~NRll8RNtaQX#PYd;=BOZ+{jDIaV^YOs;R!;q4 zrM(qg&&s_W9z~eM#2R%lS3X@dkpsw9i&tV;rs(4*qVHFJ3aP{CB2DewV>qH2qp< zwVf_Lad?oAbg_S@UtIz= zk$%+!|Ehj9LTP>7xF2Uk@G8S7a>Ir*F_j+Dbu@>jJfw@j zLT;iz`8|qxYfy4-8r@iSC5B{NxKxR;waiUg&L72w39>8Z6WQ~yMs8aT;3HE{A!Df()PKKY4CFh31Ea#KaWcyG4m)K)LETIF(XOL+#; z8H3B6fxOFYDOKbJAh^c_3JiHyOKkf*i?Ee#j4cLl=f@4WBHlNi z*Xpm`x5_+6a`cG9sIvy^e2u?ZfM>{@x&Hp?w+z?J?VwolXSg`90YRe5vF?| zfY`)E{A>RBE+GHmBCaBD|6*MiZ;BA!K+NHi;Ss_*5J}eTFn7Fd(z-2hg}zlz`K+fw4s$i>sbMr(BIVQGG;bJ9aCR_}H;g9umP>Gaqq5D_liWkSiv+1S98PEH+F;lv@ndwBe z)qU<+<@YcdvX!5AVpP>?Cq^VXF`CD-E{wuz7e?eNcT;z_M|Z9AIN9)U2(w*&fY1WE z*^7nlAoM!7nI-QksFABc`muY|$hfm~Lff#bLPgk9$df^?+=^4}5%>xCR>X(2#THPnyM^iluB-wfP#nSsv zZ__d2Rh7YxSMd;k#w&kK1Fs(ESe3z!S8aej^5MKHCtfA^s=WI9!ZB{`LGhb%Yby|Y zZf!+|7<#O>jGI5iTG02e&@I^?!3K8ZT_htxzB;xBNj8x4zTB$3b&b zwG+3Fp>i3wUT@^qryOg-t;4{g`lSTP?*^D!l6WzeoeD4wW#aYsEb|S`!)i=Zo&K{` zUdd;g^=$_0+>#Jh?>MOU$DNu92ruFi79ITm!LzZ!;Mtg)|IRa3qWxejXBu}gQ;slm zF|!Q>G3?n#SR!`%d2pbd9BS&|_XUIu3&L_u|Nixcw+ARMhMMBEx-V~7v2TkfTbQzV zn;i(}JhgnM*#JRhoIMS!jPEqJ2%kyz7%0R@Ai=7;q?~xxVWc8OHM4Ec~MT4bUy1W+m-FCwZlA=sO zULgSKDQ%zr@>l>}#-bJ(FtmStA#U*T>hW}>CN@8ExD7XPT(9CH@U2m%tPpyrT}pnW zCzMR2Q8qx4`UL91E85gTXb+-ov?*5j7R(l-O~b=0K+q$4BsWxWBZ3s@TLq*%8f}UT zphyoyl0sIC{O+TqIs=Btn>VdWTZ5^YKs{oKtqUT8bwNb19r4|~t1h~Z-jrDh>UVKu zE|80@O%c8`Kumz~-#_NV^oVLc*+~41TtU``YCZ#iOkpctTh4uf9B*UlNh4i}eSeWc zhup9|?TE7x5Vio0xH?azZ^?ellu5mHll-(a978eVh#Sbi02DJSE}weLv`9bpDr-wD zvq5?`%OU#VNj8u$6E(JZtgZg=8fG78H|%lPl^2@hVMvJy?KVUdH%73HCM;iRD3lR3 zg%30WkRL2o>SMp-^7zX=hp~Li`(#`INX~ztJE2js8*&s<%np z6gTWQBCgP18pz`s_bD*|Xz~!3>@TGtZgs3FgQl&_&Ev&bld0)jdbs1@nxB*!?I$(+ zySHc%SK}+`|L!eEd~tBiR}v7n_;I_poPFH%hAYk419TT= z-c_qo+1|8W8+{yxYSn45SyOA3Gv+OLbvtfp_1jr{Jt@&mQ{cY*+D&J?5K3V+)9fGASsvYdBk$^C()p(0dzxdm ztEOOA;?QX?Fzg9Lks4Kvf|C!}{{Nih)(mk5#4T@(o7OA63vt~aFjuP5rM8rb2aqky zbER^quPKgsO66N5Fh{<%02V(0 zeES+)p(*Wz0pQzf*V+0Ojet-4|Bh{#q^-iY*s%@BD?m8g&&oKg)LZt< zFnKxgj(Ji18{V;#N_M;(lwpDw#aAx;EAN;m#hQyWF>Lgt_$|VAhm^dk5GGHG|M>;# z`$49I{vxrY!C<8(3V*qZc0lG1c*xxmliq39f*LT3*t24(tN~i9EI*1 zEG;3W{LN9O;Z5JtH43SNkUB`pa?FX|QWJ<_Do`5W7)Ni}g1Ev!DG71%XuG#u9c_vu zd8g4fY>a6@(>MMYiF47x7+!)UcgI}mjfIHI3zi<8clc&{V>05RgQedQw{MKy8-=ld z_g#6R;83V^)G;S|OEls%q0$k@IC@J>2);Q)`Vet@#@fB*(O6SA=Wo%3VHj;8Nsc+u zTaL8Aceaq0ImXdj3K5srLMlew;yk;zoXs=MYxUmYBYY1 zar71q@S5gQBI35@H@-!AkWXuXJrKA%`C&@?0+Xj!SB{YXrY=kw0@c-#>nYx%rWMfRVyDz%eM zdvy!8(-H?8#O>y8+mA~rOWNa?dCy()(85wfgSdN7NRzP>dSk1m?)qU(od&mPwgc{w z;wd3*)ivM zU5@dQHhs%Pw#tA?sS$9_s@7ZDV8c)uHI+DFSmrIQ1(r4oJ>5RcA*fltILp*26lL+J zcd@eI-Q|;KbeB9z^-AR|EbWCpr!lNNXEF%y;-kAfXEF)Gn6ELm%{BEAKL5t59G`2t z;^k?qvNG>__vIN&Ozo8)7nv5i2=AP-DwCI(=E3m(q*dOo4m!+R2&W%*89_=S-w9c8 z;(>)6Dt6jP9Ai@H?3?7GjpH4$w6f6`f=6&2$nMLH33k)5C^d29sF5T*lwZe4H7&Vp zx5e*xqVa_%pUCRy_0@)lOblk6f`qIv8QdmtrdRB3Yk8tjKwEf5YdGQ$=xIm)$s?5{q$s z`k*>T{1U0+=Q!hqI4PvEJae^am{WeG15wvwRci++xVRE5laR=sg!EZ&l#^NZ^(4an!l;N6goqb==|Izn(d`ITqdODTbcejW8|aR%jUCLUp}iaM3+u4BX^%WsGY|T5+-sQp z#~@4w6>2_g(?X?j-qO~`%#XJ9N3S7|2VX(c!u+Ml^~l5R4#HRY4qV)!-f%;NFpeim zse#_KvxJgg1k#2d);h_Nvp}A0+`>SbQ$YU14w>OtTeyWpDL? zr3vM#0D16GJ~>8gD>qwjx-UFHC#>6GIwMq^#L9JpDMcsT{mQDul$xG)5vCrqDyz#( z)vm&}qnJ={Gp!T;_|mHUxy>|G5O#fzDty<}MkoU@=UvnAmMcKe=KD3TW_4r)e$B5L zyE5mG&&a;#!>q^T=DSR<2`7>3&RwQsf^h#ct1@S=={FbQ?N6=B^!H64xC(cWN!t%i z=Y;*ATNU9WQ=Cq?g~%=yrgJVrR)tmZ`_z=-CQLePl}8>!few6PRqh`%-E$EZ9|BLm z!k{!Cgx3k^wx3WnTjj5>m^ue2A6wbsw;!P6y#qd; z1abV1=}F;z5MAz?+O*sO;@XQSf4ExyC|>?h;GCiVxodh)xPtfO+=FUC$lr%I)|sxj z3d(y>t35PH0WTme745PRx`S*gS0Tddk!hYV4aD+Crl}#lkb>-4xZ)%Lijx*Qvfi_P z;AcMOF8rt5Du3^8jt!Z!&&uw`<*CA1s%7O?C0u8Y&| zpZLKaXn_a9cZ}U*RgQX@&$tLJkZiNB*&z6XsPr}Ghd_?u^Y2pe}=6*<)Wh9IWcuU?F;Fpu`a zJlac=kV%uc8pLfuT%nh=%rTDUta*q__L7Pbx45M_LpKNWNLomrZE0?%6%L_rHzUj& zggrZ~%Hl}#Qmrl%Z_X?YlS87-dq;X8wMTwiNx&41)9oaWte(q5w8?b|ZkiABpcL{s9VItew{5IS=uvxHtaxfhi=k%BecuQ01NF7GJA&;4RcyNGx0(z#l zv_<>s$zK6~tYdgiq}=sDax?uN-nIOUxB0a-M+jFy#1nBIL{3}tY`4Q8Ci0zH^5#VS z5D@O)Nv>~e)(LwM*0nR6GFk3+<2ekcG0VuPbHueY-Yjs&kDS7}UtYq#2l_?IpSCk! z6Plrk?uj+WIpxl5>mYNEx!X2B9q}zNFjRAggGJj~gq_9Z@5D*r?!G#F%%60gT`dPZ zI|PxU7T;~%ie`yrwi?CG>;9KVT|rbiTTytEp%D_F2QrYWU&#Cn$QdB-$oGC38%i#I zPaw3qy?H4Kd!s)0NDPD)uD+6W()t}tni}J_kxM7l7qep=344v|iy3i~J3!biSQ9|l z<&Qght|6Us~CuNq7*B&m6eX>rNZ5}(M@zR$0^Umn~mBK0YN$m7NrSk zI0d%sZL5ML8*n!(*H*Fvz?@_UfH}!5t!TuH(N_P0Y-VyVqbhO(2sRQv>lLU!!P8s@ zlGp`BSdI?)Xcu#zOqRX92+>(T`1^IlnZ4Z|XFT}_+%EiYMP$k-Y=ct~=i&8-X~<<~ z{bnP??d|lW%}4xHAb#DUp1E!AiO`qBiKH(F) zn}f7|6Is%JK>JU1Mbfbe=HL9D2Ke**>}Jbo9<-%Al9|pl%8Rg?L9yq8ZC;JWx&#bm?ur=Y_n>m%KD@O*;Vbeas&U z-@J)#t&cg5C4;kiIjS!@;9Wph_cfRDQ{e}qu-N2&c~9dbA%o?H_uF8t39MF-PT4TF z*2D%~nIL@$EUFyGLkpA4Ep=wB_o&w@OEMpFFX}1nGQ=wrlFj$D!lo@4+*8d4l9Vc} z*LL3>fvc`L-FK6@fj$(JA0}_f(R(PjQq9k}xD79*ML9WK){`I6T21v(APf4NBO)?D ztiYs=)bTXf`JfT{zt0E0pXDO4N3?vdzuAj~r-?F}859=d%(w&23<{S!3p1#Xgb&m|wPCcInyXIG2!7$b1O)Qid04 zBugnwbyKv`>*Viwh&hXxK+A5m!4s+SgQ0ZWE>!!pk2QRg6^;OBY=Fs?iVOwPLoU7U z8K{S*p3-Ch**w(TlYN2BXNzHNJLz#SlfJ4Zjr(jd;7i)rFacPtyJWzZM3-8XfMMp9 zT4Cbr=+Q)THEwg~CG6WDkTbP{q4@8t(g**8 zNu|GjaHRZjxLHpPp~=F!2o`zU1YBtCfS1BC$2I{MT07u17{t`VPa85g?6q6zZp~H0 zo#rS3IdNNyHx`dD@1=K@G+D&cpno`p8eJ2-h<03$I^$&M#L})*=8rVD(&~+vt#QC6 zbR`fv=59%a;kTos96j3X;rkS7I+b&p60!T6Xly~fnh^CgA8l0TWdT_|+KiJ0Af_C0r%JUD8Bg_w#teW%~E_`DPQ(t?Dr}Z%;IDPbt~eo@9DYU>7 zp^`yOO;6TThT@4(sih60uPX*t5GsWLOPFN$b<-!AySeMV)>-9PKG8UI14>Jkp4Jiv zU)0Hv1$qe;emJ|4J`^&r0iULa<9S;)D+V{vC!059b8-g8Of`w`{Sh5~zIvVu_+zhO z@x}IOy;UR<$YHjV>ph332?p{p+Y|O4#}Qv3fy^Vb4RHtJ&-abJT^I^yYSErq+@bzQ zh-}WM$P4+4-vbiKomdrfWCxHi=IAO&McxDwj3dHo;l{LOoidfEW80y&ax%|8YKmza zv$(%CbPCVm;V+r$#+&AVK&AmX#Fsau-U9Lz5F_6mP?0e}PSy2hrljU|P=U`jkJb)l z+1pK3D|(@WD@dtx#7oKd^kiqe2Bz1%hGXc^G<-M^o{4M_k*L zaHA7`1g?8|-tw|J=EuA~U5h4$8Pv5$$#PC!?bHQnc$zf5o}Ug_g_?l?ShP>Zl<73KGJ11=}LV6NBgc?UX#IjQoV(@9avh!@Q- zGZt6bKc^*yXm}ds*913&0*`UVlPeh;s%(2ovD~C0d7gP8H7Vfo$(Br_iF`PS$vKhC zJ)4@s)?Nv>wO69&&qo6g){wD;)IKZR_s>_c3}B%Ns$gP^#lr^IqP#oV;gSLy|9XA%0(1TdV|qqRlm8PuQSqs-QtXT{dGkVZsK;H8qBtow zrI~Vgp*hIKE0&hKGulY8`EK&XSIjK~$~|VZ#^TpaT88C>T3Nn3V7%@u5p)rQJZrHz zB%sQp8M0{RDm~Ts5Z%9Edx*KMw`G=_6(w&!+SgC^ZZX2cZF`Bei6hKXgp-zFaN7W4 z>=JWJ{auesF;qV3aW+}@rn-#LRxd&P3ceyzkwSWO-te$AytA!;=$2p5#$TC~kL znppu0C)#Yxpl_~-Mu7zh%l$w~Qv{{U<}l5S6#UbsAkvh3DFjEDG29>go6AOVsVmGnVa;mj zomZImvfiuQzIVu{ZIP?2muiaBjP#B(UW2nNYN2qCNGo~CyBV!ge56hTaP$wmO)Sd3 z(;}_azQ4hl|NRDBez3}1uTNOXrU&%F4_BiNmaT%J0Vb;I`!=Pf*p>~45^ykQbzWe}waY*3H2T5eTd{1549!Ko4&CxWm(BtjK) zA{npLlgx{kv$LM$XY=6e5b6a8=d2kQ;X4P!1uQxLuYAb0R++Zih~)p3FRe9&yA1~U z9zPO8$2t(%56HeZ%qb)SCH4)ah@3fESXDQ{*}mdfXFM9GmDK`4gJY&)zR7c!=)hNu z^K)AA``Eq#myd5kujjtZs@&XUF4F2-EM;wkc$3{snp6v%s0&|-G#!%kj+oc!(`KT^Bmzbl>F3oC{qRT6|17` zGEa38;+Mjfy4>8;U1+zEr4{A>{@47RFmP{+F;@aNoRAEi}3SY zl6qmsk27%jh5xHmTtNw2zcbj zDo0~2S{K*Ur_d!;z0^BezSZ6`%l%j+rmJYgf55XHCz-JzC)sGFo*Vb`bRbcffN4-DUB=$5M@h#Yb;H9!1b@qAzc7slZ zW6NridGyDR;pG|JYH;+ssXDhvgjMb2ypK|KLhuBvWI9@YbMg3LJhV!4!Gh#JLt4qp zI$MSj%c~4qz~0Jmbco?nEUJrPzXB@;RuC?=wqeBbG+;5|QWUU|CoG+H-=J)C2r}mh z%WRmyQg(OYYXyt!%UD?NnP`_C7TK56LZuxxjIxUXCWK0F1AEj3*_}gn%gi8Jcp^<#Ag#~~fTRDM zDRXbSia*c{4=hNvLa@zf7p|aQ^F?R85C>M( zax4o-k5v5oS!%Ry8Z_6ga_6Bv48~9?HxyG8o%5q?OU%z1XIo++&NzARRbSQd7G@;; z>$9t2m8UX-oafSUOz_AGri++xst;g^9UsKnflKujM8%>rRio%cuJ)wYy=wP9?8ZwY~JDcu2fHWQL{8efW2 zu(IDEOFqeIi6IvbD#{?v#o^MY{7KwEf!qp!rG-m}Z5WeNU_!X`5wM+uxY(Dov%iBZ z-I&;yFtIP@x}*`dM=3jq{AGx_$%avO5c$isA<__FVip(sauWOHSr&tje(4A%_T`Xu zW=$E%HS_m9sk#_S_LQ7l4X`uQQP5OWOUqBsZ5jUF z7&NHCg(0^|Y?KPR$C2hhmhkpU`5!vjzoXX*asiLjTErb5XNhpD8%{eG_rC0f-BEb! zLnxmOZQgY44Up?V7P5BCO!SBe{ny>*ZoxX9O%@JmmfizK|5tgT`CVx!OKm9gnHRYFE!l++gjk`bHR#OX^6r zC8r{NfxyK*?KzWK8ivL0xtKvcZHaJ6*iOTzoqW+56}mRa5x<1#@3!KhHe61cVp*gY z%rJme$KT9R+`R+49GGL%EaSSnjkb_JwzCOGqVZxALVMX_Er3pn0LcPUhH40zgf6Y7 zA}LtjJ=OAy#|jgylQ53T$uIN>mJdy{Oe2O?8NLPc3iz(W8E~3m-n|=`TxG++P#cqv zQ;qBz0LOyUF$4MlWh1U`o^H{?Q1YKke|x5-yW3V2;}W}x!W*0Fv?040$a#71q>-WS z2+1a^GGUe_R_nybQY^Ub7*?mr*HlMoJa1O8+rNi3F!JbZ%Oasv#M0+EOPziP<|qGF zCb~9*L=Ue%V6@7G+`jHMN8ShWEEiAJ>&&}A#><^=jBO!zeBSbl?$$6EX5kfMU$C@L zlIL1NwYp7!t~_N`0L5x`!w}kl(CQa087{7ehN1$Fgbi=~+I-7t;pmg-%wDwADOC$B zL$t29hNzM9z#_!{HXb%iFI(Q$QazO$?)HX2^Y!W;6oO%0>BKr;ukNs6Z2SNwxJYjU zgGo?l-TQnrQW6$oYE4yCMbb_JMuaM0M6xYRb*6U>#TlqhI|Ff@P7T8SScBKot{o)p zTOb9CEkmiQnoL59$UYSlPDdPtW=ljBS8gu0;Lhz&vY`xIYMH0MfdT4Y3THnJ{VRv2 zp)+pv4U|{oXD*u$uT7gcMC|IT>5B0kn;F)i{6!Uv4rg5!JQZv>1)&lL$xH z)$#baN79fmI;!0k^aNh$xV*tSAu1bog|Aw=u}-7hzSGF3H7*X4vX|I(ChWp(93)k7 zW#3xNgM}S~uta^$QlzgQ%NWSYK(*^wF3ex$xapX+*A6DP3i;;;272G%<@_Fqk@dTB zpNTj|{x!k_#NQSqR#CXgrDYhtupxrkSFQzRFXVuqs4>d zvB_A@4o@X9wl%?R*F34|Wp>Te7aJ|O=INIV#>x_^&dgDyTU46~A?*CrV7%1+{8T@L z?aohm_oiZ^A9ly|Qm%5#41(hd%i+WnnhYLjj>gQ7t^bT>z%mA<{i_WxyQUJz@*E@y|3Ryf15J!U-))gy=`nGm}}=&0VP}m#CF@* za?s=^z=UyIzI&@#q;lvj%Y4=imKbKaK?JdVE$F3Y5K)L=iQxxewb+EN^pw1THE^zs zZ(!?y&3Ol$Qy>;(sJZ7I3l7%)FCC{+wplXV_0#*qWda|!BFCwtF1uHdW6ZegL&#!* zw))rrn3VBj>-#xU0p#!=Ogldu0ENjOOTIRfmlTzv&aV;GSPj|-ipd3}p z({V=%4jk;YwDc129uH{UH=wYm_FCQ$E@2Wf{XI(ycQvV9iCH(Uy0Eb#{d%VF_rA|d ze48QKL45+fY37En`U%J~x%9Res`TGynJMUANwdl)ELP?4e=Tj?UH?o$MdZEQqqXdP z(2^^}m@z~jvR>hVsAaamv)k{99-8Y_e@eB>u9E9jFL8`#R}8E`BmDqu z^LFTOdmKlq67G`PV97BY%L1y@rl}>S@KzT+EL>45(;Q{2q{>xTZy&ukQeInO7z@!YR$0Kw8N8ACC*AdoBNiP!NwN zZ4HoDfiz>wCGXETvJ6OjzNAu-mw~k9OR7(Kniqh4|D)v!$#auYyR;qT){n_;Q=H@+ zN1@g9%7ZJG&a5+TlB$9ZYTa*0)wqnHvsQmPJ>hxoYX;R4xNu z5!jZs&n9m)kbME{9~#Pa6`E`P=I*SWvAQJpAL=`3bJ#}TzUc|WmW~#;W?*7n0%p9t zd9i2MJyo<}gScym+mD8#=8^rrI*6TI-@Bt+c+=wHdlD(uBgNBvNaJ@@aT@FNcyHLq zQ%3J2+4Fp`p#3)>?*hR_Dcx*9ZvTM11>`oD2=(=^1Hn027}++b29GprfqaYCjltC7 z@aH)p%B#05*)EAp-1qxpOyG83*HFa_TjGNbp4)xZa;%Dt4VB!D;ssy}=JpPfJKaH3 zdk*EM)+^pY>t&B0@y5`CHeRWd4%uf}2CP^oeQ2L$0kAZk^ggi4J7{TYZpxo`ENxiB zEw^vDx%Szq4Og_!PHni^!0sGO3zlcxv*7fFT0*qmj!MNn%URrO%9+hC@#8eR#7~9U zC4QXdm-um-U*gAUc8MP+`6YfTOqcj^k~QHj-5i^6dmv4la10P!;)g5yyrFoa3JV94 z%BoqOYQ>&I0K$D)3V9`ky%6rj44UL!6c!NXe)X8AJ>>9bSF1dPrO=Zd36T3h9$3+U z*|*!xhuFDJG+-y31|&3K6_*2kw|tQ4l!)4IWkaH-?H5)-j_IlWG7Nit4ehs69onyB zO4fcKIOo9H@1q7>k?W}aCOm=ZJzq()i#^pvHJt(BWRun_b>Xd7eIlD$?_jmD6e8{{ zZ<|%rvs3FO0X+nK}TW228U@xm=suNgn(VQ@`VYw?4GQ35P+PeQ4?FRSqK0H@Q!~SBC7T%MF%K zJhFHRZv#zwWSJ@~1+nLmC03XZ;`>LI8A5&+>$;rWIKhPf1-Y?8CjNKkZV+OSAYGe# zPxuLpO?1iaESv)|-6gk=a16vA7d&$i#6_3f8NwD2q5xzqh+-jkw(uN?KLtGXG>CXt zM2!Y9);0GHp&N)tuDNxBwKLMVA?gN*_U^geynX<&#XWgm3NL+xE}+wruxfy--I3=$ z5IP;oxD7-X9p1Yf#8zEyoYw*nTU_Wt==gQH24NO}vC+A)atDvxDMB_v8$ELC1z#dO zbGr!|5O><-2FcevbK7~{?bP_*!(O><!IFu?V_if<}hy}s9DZ-~9DuZ)}3VT3=g#16+zB@juqWgO{o3J4X36MfaNMH#q zw9tD=2)%_+Wba){Vo*T@p+aCix{5;akVZoH5o+XdLYJv zfF>-qbf!=Bh#QEvY{<*sO`*Rw`vA*tAez+&@&kxz_2Fk5i0C+oaw!NFhuozQ(Ez#Y z1>#Tx_^AbAc0**!AH;`5+>YnvzuHm)Vre7$9!oBWl*Y)*Qt=5}$Q#=`S?0iXp5RF! z5}Md|Sh|7e`N!CBcB_efqNR@RdM4ifv*mOXWT7dvu)pnRxg3SUQxM2<9BMcIQTudfn8V)0Y;72Y{rWnza|}Uy zYTsbKfEMf?SIc>4ti8Y|unM3dP_M!G@xblU?F}%=8;MEY=9uJt)V{)O?FiR=s0{b; z)CBTSTnqZEL;jBwGzm~XQ~`tPy6np-_GWC}6ZZAiH-_Q{>FhAJcB(zzIdY=?T_5Ye zBW|!gO|dEBNqer3^>8@q4N6=O_bmk}Mi3{0l=xUrhG9bj$`8J4J9DPnbA0@p1DZjl zQ2p!PF|5x_`!QFTy0h%zzW(QH-oVagco^n8q>j`6tbMtUe`jEsjr2e@=GrqTP(DR8 zXRclGwLYkhIl+do#g2Z_&KsHbSADD_0ln1#O4!5^?tDAjKG(;(E#wBPh=b5yvQNVN zH(aaYpqww;%dD%wt~1!pUWn>ZbxwV;Iv2yP4_6vH+r5S&2svF%falQFtq%`NKWP%~ z%v@|wGh654Q<3e4^ZXKf3*W$nLrpofw&$M}=B&HSp6=s+JP=i=9@3w-+|bqid7LdP1vY42|K zcfj>dEZEUamCnq!?5)gJe_$!V7TmF)W2;u%n^}vhV%-@CVmQaPuCceZ&IM8wBawq^ z?QQ+r1DOkigdOFKU1#rQw*KS~O9HItEfiX2u06O(7-y_ zl9O)_G&{e0&mL>G&bDH2c{FA>KCoY57uVazTk8Xv6pa(#8|;AuY$*g{}5Z)-8blg!-Q?u!lRl zZL>G`u|@$(ug%jF?_*u!i>po|Z#a>XA!ci5xH3@@kP5uiw$uKE^_&F@`1qc(%ihpz zWpJHA6+kN9Vi8XJd}|7jl>#}(=6#Hm`U6R+g>)fGv-9vLRBfK|f$F0|Aay&~yWMS@GkXjUFG90O6MF8k*D(8CK#i$jHD0sFv1bbGY1aAX8|;g4&bGae z^{VLx>mXe5W@qouN%m>L)}zvJq4wDip#}mO4uofC)fdRl&Ic9jZm2B$zrOwZgbW+WM5>qRs%G$ zCKqf~vvbQg_Bv+k^M6;cgEg=_?1(+pY;6wLj2bdM;U)IT*5mgoSTqm_^fa6BElO-L zkmIP4Ts>br2KDR@WGN7?46BaYJ6cUZ`T;>DIK#G{w^wBaC+v-^yYE&oAHXT6?LQJ6 z$cn$S*RwtYcrU6j;8X0|@9j;k?Sae%g79bAxs&#m)@yevSV!H@A3wm)Rv>=`^H4vr z2S3{5txp2k5e$)>vR8xYh3hHt{TJ5cG~zjTyMo2zJL2&(Ti3$%D{4D@pJtuT+FMyw zAi32bpR@G67F^@-9j;$kS{cG0zXe%{5Tz8Ol}$Z|TrCCsU64B=Ras^^d=Cb^Ou(nu z^FJfSRe=lx!gKZdFUZyYn-wfj_w&xL@RJ4P08EH3qGr|}Kwb=lUY&>5S#RB_z&!_C z){|J;Mf(=(4j{K+G9Z19EM&fy>0^Sh-VO*kM4d9xrd&>VE!A@6Hum%QXAscxG z!Bzr3T@}|kT%lmY;9@W=Tt+jmK}LZ_}>p;HztAbTS2&f)HWWx0o3<^S=VY~i> zB6bDxypA0F3&@Q>D_D1bv^;-NhkSy5qX+tihph0ybAJ~9P5nj1WzM_y)@^SL$NAq! z&Dy^DCe8oeS^p+xQ^$iyW2wp1?m`S|cv3%H01>gtKMCJoFx@IZj-&6{wUi13q{d(u z0?!2Jbp{42y%>bM7%T#VwLamO_F=1g8p83^;Hi|m_v|~mmeC|$W(a1oG4+h;=k_Ql zjs;c6bOR>ricDH79kbVPP4+bd7SbUloZb7|jtzn_;!Jbh`}W7GT!aHdwyB?CceWsx z+zjy5_2`4z~1zWmC*Der5oPLke-Mv}5U{yKCaXXwD# zk!H=b$!9qYqIpz?L3b9$!58X!3U+9F`dmL=n7AQ$RRuo#Xf9*u}m5*{;cR0VYC}=L^Cug*ulH_u+ zj4H|}{!^}2u$^cLSn=l>;m*!h<*L~_0D2M+1D{Y;*=i1*cLl;g1JJ~T^Vagq)c_^k z*NUX&$0NqkA<9^nV|R#>>T-luS6-yD&9}|PDx56a=a4Io?FS~yc9xDA%Jyks<7=j4 z7*}24WlQ_ASYQq1GL>yU$~N{b>|hckzsz2cJ^rd18(P>4tIu&(t#c34ay^~1YbuZV z-M(DGmWZ7Paz*AkkXM;Gr#qgp1X(v!Y2A?rF_tLp`w=CYZ(Kai#m*90qJ*=TLzQ^} zZGY#*Mk$oqN2Js~ju!N4%U?A>bPwkCiX!?&(A&e5n80};-h;CBGu?20AEu1*@t<_5 zg5{%~W5WW5MLGx9Qtp|p=YE3`e^B8}sjd8Cwmt#Zw)+*%uF*<0AM3e`_y$)>j8enL zItH#hG-z|`D-8qV(E(0=Bk^w(FWX#SsqM_KtK|Dc|BQx;l)E(Bq}^C>n=2o?P{Gas z_YCJmxNm&w#2SLMl0iz&SFlLnEYn|U<=o#;Ip7mr1DGA{*afg}3KdGkk5WMjw!Vpi zKEk|TpTTYem06>4&g%7bQ`OoMJ0b#|rdPO-O zZ>?Zcx&zn~ZI#8A1!#l!c2Q2Vzf-DPB1~^mI&9& zWU7h5fo@7W|BA8-)(r@2RXwtfvtD;)jKvxbYz$h7>_p`;YcrUd$Uq!R8N(_gXsSYJL zrz%(htTM$;Qph1GOdGA>a-$nRqQ`(w7~t8g-w!wC-+a`}8Y@bC-I<7!TJ8fe*cFeK zn_BG)FPUzY;u`Kr$j&rHxo#~)2wR%j`Gl&ZTC89GfDQ|6J7;!sIG!iXFthVxl@@iA zkxF8=0h+Bd^M9F`MQ-YZh}w=*RuQutFk@h5bN)3>Nwh3je-erV+xN>46}5iGuhe2{ zv(GaAyD|fP#z3Dk&?h-vw<-BQVW7V?&_@k4`8#BAqjhqA_^2{~8xWjAs)IBCJ|*Xp zeY9NU1_lK0LeZ{txuZtMih-4*%TZ+3*iRKJLey|JcmnLlcaS6P0-iQOxsKxt6#P~! z7C~Wa@=V$R6p@Q%Hn0qnR-|LZG8tH$Nh<)h_I9rbw&MvU+Ik#3X`k}3CluU?3kRxm z4_t}I8cbBi=zug(^i3KlB9BZ|I`~b4c*W*D+Kl)FTtD#5ec?2Z3}ifz6PQPqtPR2W ztv+;#5q$N5FC6%$?MQqZC?1ai@&fPe1W2SkkgJoF)&n^!qiy56D7X!)wCqMtEN;ji zeaqATI@}r}lXE4kS6`O@q~hkvqe$o`Lz6Y31pY$}F zrvEPY6j|ZtZL!KEkq0L*wiD}vr~jo`gKxsU9Q9tt;;HjDQSTAgY53aBbw1#RKu!Re zHbV*b9f9aseo(J^!~c2>eVU%$nMkKT4Ng0GW-f~cG%4PA<~`gyD%1~4b5Sg8rV^%0 z+?c+esU7^5AQ{IQU31UA`Lw&$^3sV4=jNH{7}Cy;Yqkw_v1b}Lx@7y5T!4yl>?E)} zU`0M9V^R zfmp@?vzWB@!1g|?w6=bPlv1N}^I2u1*>dt*^xNksJ4kNDuyrj%dF>`LwgXl^1v<1h z9`V~ZSD9-`KZZ`>Jk)Ik#0y+wSc_}8%qSJ^OrakXcxsrc2ac`p;`4CsS6Za$etXPE z6BG(omEUm-1R~yX3zF(-0kTr;K>0x^+Fj)2kl2ADkw1Z8Yu^`L_;X>G;HtGinMZZ4 z*w~d8+s#Ma^2Ez<6o;WpDt+b&T$S**K2-`xt zgn^s}l9CPEl7|t;%G^PbEHhhKDE4YCj6+Q|;|PgQ$r@N5REJ{Q$8oNE%mmXRHEamyCX)KDEGZppynOxgfo(_REOC-P03RM)?# zw8!>dA%*{8{kZ=I_TZ6(%1tGEP!jT#|ByyFMY;>_t1qK!ZUr%&+qxjStpi@)0}>&o zBXDYvkkvrMr8)r;Spj6)LUhMGHHYsC7Hv_bdPChY>N$D(H)z_K^TYbGRe{^fVsK_SgHsNFW7^bW!G5b7Pb zf}+RTwhDw10=Vwa<751+Ab1Zf+VbEidKkOMH)5AxRgRGo;8j^%p_L)JU-{5zF~M-Ur6JU)5iOA&2SZvrBDXQ#yCp4aXdGvz%ak2QS^l^SMU+ zH2}(8nI(MF;XQbaPISNWktLZsB4ziBqjb6n4&F# z-cGez>~Lo+Ryud2ER+^OU-L|wty^QQGm`7>dez$0US>(xY3h2l0=D+qAra1tiJh_dr!BI}02^+vuKB-RvyL_aN)$bLAzObV8sAx+T zD0-YT_*r5o8Wr+8bs3&;jrqO1)o&s`yu($z&Y!{-qybrpqU94z5MAlv3ida%Ifujz z&wSC<-^e!_enWqw5^m^kRKn9le}huO`y1=B(s+M^0NLLlawzpTqL3Uzf5WdP+}IEM zea~>`>#r-S*$QRNi7)Kq{BxNy$?Sjn5Eck9#lT8GQ6kyg6-rpwbQ%r@VT(1&=3KT( z>jvHAD)%%lC(8hqY|=XF7^z$wFpEiR18nWbog-M;3JeFO$~i47mDaApdbkeJ`2w~$ zeTdcXbI5K5Kc5lw2c(;4D)|(M#%(VYu@0QX|11r3iMY0{2oi#aM}sgk@3n(L`19FY7oLXSLyRF^G2|;-QKV0Qu0rKmIwpN)n$xa5#Uba58+C@K%Ih&5H0D zKvF*H5zf{f8&cCbZk6&cvvo5hKN*t${!L|y*+1^<3ic%CF8JmH_T<~j5~}Puwgyen zE}&u;`Dl-#>^PQ#E8y~gW&3Djb&MpRA&i0@7{6hp|7uir46kx9yke7AD~e$GR}n76z@uR2nrYIaE7Dmy1Z* z94oejxMv-(9s6t_f|f6DDdt6z1v{}O`&+9?Xt;t%ASIO`|h zgf#)#T4^Krt%E2c?k7NQ4ZjA&lBZ0kMj*#n0h4edm+qVN#M99MqWdO2@iZ~Yp;Q;- zDMP*Z71FVc(Y!^f6i*qoRO7wzbx=?#yp~4?MXmg;s$Wf9BuqKgkY-Z2&;yuLd{-G8 zaQ7>&c@(#-K3sUhrV%L~HITFYqY(Tx(a_L0e)vgtYiThWK41Dy zvQNp6&~lF51C}91-Y0a73}BuZc^3ma`aC8~CvJyLT>-Ju$>c@bmDbz}7Lye$+JR~7 z|3X2K5sNdIe1z0hXBkSRUM|#Cw%W5^NET4n3ux z4qHQ$l%9B+yHu{2JCUvNW!H8p{(=8OR8%~F6~RjGQdR^U0U^t2+*n=-xmMBP`ydiN zlGhqx9_+&E=+79{v+CxgNJ|Ys3qDf%xFoIj8?K_DxTI&&rF^2_@SBbq48t$L9()A- zUI`)7=%=GoS@q9SFNa9diS{7pTAe5wn} z_F^s9^4-1)cBxRAPQ_OYlf)0k36dWH6C^(vCrExUPLTXyoFKQ=#|16ah(qO07gpf% z6@J1%-jHwt$UCg$!AL$`{S918i!l290>o}U4-@dc2)YNz_TgiqXjXd{=&MEO3-FW~ ztXvWukj~~-uGrW|NXKOW7Z!Qr^nHSC)A3%fc)TO&WT}!(SdnAHfq(!wGjO zt!=-I5%qK37pR|okz&%P1AC#wUnp6+OsAU1#xnbtSX7b0?)Soj8mVP7dq)l5uWp_$oKo8^9`B(rV@lpx>wV9kbolNL@(E(|_3A?K(Xz$maZv~j;M7UtC!$1!EJPm%&j!REr6Xp zD2xD~0;%=2k|ns^L&$7P3ElC32USGpR+~32a(}q;R(3FxrCU(0E$tI=ie#tn=bw z2BP! zM1kiaz|msVrCA_SMPHh3SHh<$Ktf7H{mD1hlR}zgM2Ct;VyIWt9?@XS6Hi26StjV~ z5@l$r=XV?3hB?DKoQ-BhEyJmOs}z4GCT;{jaZT|nOxxQflrKcoMhAw{9*ne8P0IO< zTV^f*Tyo7m{#F@jnGP`In9_nOawWz|d>WQFsFm<^-T>RZ5<;VNkr0L&iMJz;DZW${ zDY`3bC|T=JN?N*1bL+b6pAdK)!m(UwJ`h zmH?TEDkp==mYO0Nx*oF>^Pa>#oHOBPHNRRdjyiz|^%Rh$9u@ZyxM|Q%o%`CX&k3yd z@fy;twX25oLw)DiI$*L5@1QS-V?+Fq=hG;G_xSQ7 zwcsb<$`ze^TD=7F4G>zrq*i?BZqbUf&%Q_Jp3A_XbA~3oQjr;&@JhIB!by0%3C}}J zq$mv$i?@7v6TT2$coUupBBa}}rtI=bCBZE?3l>t!@l*vYD;L}tTnktPGXj${QpZSe z*}yVPS_&|JxcsRfU|QaQwqTjmx%3Cw!{@3hdib1lS6k}gvmvJxtKTUkR`&0wkoy?i zvVXrA?&^mqGg5qmKSgox`@17;@4Ngj^n)N4(rdK_2F2p!*TnaGN^OC)(xE1sHBrj9`VQF$c8_Iiu@+%TFsq1j|y~ zYgQymBTNrYEVD&vgyeC{zOXS&pj04CP2DA1ByNg;+i0~Do7+9NY64DWCg?+afMFzPsdm- zsc?_Ko)+Ub07NAJz~|G!B?-vhGNn7!j!Fe{5uK{HU@J*!?F062fUd70F-uNd=>6 z2N|=poLp4&dSlQf;cYIwjdFWC^E1}(CIjmsj3>XFCIfD9H%(1>H;n_xNQ7#L$%yg4 zD35t5S^{b{SG4}P3{omuQynuXT0>wDeu2T$b*$sB$~S^rb+?Y4g;Kk?Ngex9#|%1l z0$9)U;3n0}3H1^qOUk#jpPUp1fJnMagndJ^rYR8W0{0pgWY`bL9QT9V!9C%g?H1O< z8S;xm`BRRjk~#=*Pt3qcBn*g{qYI$HD>wBE z>&&=-1b&eTayJa0UKI_m)Sdo7hPgc(Sn}lou5m5lM`&EA4Alq-X&lW(vYaU+>#$*0 zl(ep>i^VjHwk{6S4aq(we?c+RX{usE2Unl?s*XWZ^l6FTfYG$X%ByHDo_Y}ey!Hoqe%cNlBi*y$M0~lgwgp)ERp_41E&7_$UT|BE z%TmhGqb{;&ujwJdO}}sGWgR1K8Ss~E(Vhpk=$e6B(KV$zam%s2+XFTgraR6@OVdLV zHw!SBZ>pMH0>llb{9K+{dj!~nLy6&R*mY!gHnK|>^v}4Cc^#hJYe--o%rvT2ydIob zW&lezX$^FYSjGXfn6$dUuHGLU&YJ%Lmb1W;<|0%6P=2W*wcvg(?;Br39UEFOPTZU~ z|DYtsz0TK?=;QnqyiZ5ul|Ny9)svMlfzMg!~&TkHaSQn0?2GW^x%)?BDujpG%>$LFQfsf z0%Wo9gW)4Pbb@o%_5$7J73Tv59Qv9c5&|^B=g3?~;A4 zIy1FUuSaydftc*+aTk^6*oPI&m#_SV(`#7JltVylLivkP#R?9k=>hJ4Jf^OdhovV( z19~;Dc358VzX4&6@n$Pr&akcnat%XZq?EYG>Pw`ozC_YWRFItWn1=wjgrd_P1|(z_ zkXoX7l@|g|0n(QDGXmu1)W?7%{EdFvSP-|l{<0y>ldOTG;0{MF>V8?_oc*^l7FQ0{ zBrD(0wSjjt>Im#!vCY4utH<%aj*;PlZKSSk?k?KE%guB#jQ)y#YG>;tgo`&vt$10D zu?+gKV#Rv(8%r(3INPlLU@1ijjPOw}THXWE)1scH6$mkpSOi;`XVO-o$Xrop1IsXJ z%XN&RP6ifd(v|`{`+B!<_LQ$$$2tR|q+az>U$sRwAy+Z-9>5B7Q$yLhi-UYwsjphy z(g_jc5PZ1P-%lNhi%Ucq1aIValLWuykc;HK54r^i68|{A0&m*WEige6$p;e2R|v!T zz0Ky54M6D88p+haX~|E6+f*esOWKOll>Rn>T^d&S0n4ZqA6Jtj}Q3=C+e ziziM)F3A|Pfl;hgU~*8+mdFYXy7Cc={3!b_k0dha_MIdzp)o|-X3|Q$@)>%0ENyqJrmg;THbIlv8`kOxS zr}K3t({0+&u7BTXS~vV3zB3l6+FYFX2CB7P4vMCd!xd+|`5$@Sz8LtAX=0;;)Guh~ zL%!`VR72eKLpOgZ&|i)PbwXVLh7(sKb&TqV1z33%Ed|)QpXHt;}|gh#=w{m)LotBf)I6-U^x;ji-bAYtOutAW(#xhzK$8pK`yY6 z>V^dNtFFExxSgb|iJO+5(nE4?z%u-_Cv=Q+1BO27qrjH_J~D#YYN*lHXOU;xZjf9< z4L1v(C=mU+-~c^5@syXR`RN$(%)^Ch+5Vad*s_|20y$Ju-R0(%j6QdUPsu)Lzb-=k z;nUqZ25$QPh>w8n4mEK5GgO^L)+`_OO7<3sL~oI9_vC#=a_gNjqV>)g(c+SG*+*2j zR_Y^KhQqz!=&;%~$$|}p<0E0@DB%3~A$THN#7kWmoxT!|y4@Il718o^k5F+XEZmsO zjj91YwLqu3`Al`-wLi&c=p{T3DCw5|=`MQB6YjXSopbxymPD_6i!^Lo&%2L2f9U+^ zaF24gcX}t=g+JzS(f4a1$$4AIKxd8V8y2)nSpK(w;4(i4u9K3;G9d4IdNu(N0GYlNS+K(6Bj zhj&s@9sD$rBzfu&1-T+S@iWmCUH6Ma| z<)YN)UJ)b_Bhi3WVw6Pp%3-p`GePyx(KJS|k(FHU7|QBJtF5RF%P}U>OjmBr;XEqi z#2f2tp8hjMcRUAreda>HC{`NQ&zF51t@1v3B@SgImJhu-WYMd7yS?#JtRV2%FiBEJ zeaS1OS#=QZl6SZy>H+`hjnnQQ$?tw0wIxZla{8z{UN^}rhq>sE(|zrp{?}o}LhuvC z7SFPLx`wix7&Xi*tx0@{zy~>%;-op24HiDgsf3q`o&ia<$EYEVqMB_Mor0|!#s6mf z%e=^LIeF#Rj)|!_ST8bS=#=9=PP(TNb?n|I1QzCl7gwy>A@~xozuegUr~B1qvsQJh z&aW9mm>==|WB2!hz@S+6LR~d7_#i$Uc7Nb6kIEGBmkcG1mke=ZVLjD9_$1ae(;`S}wd=8{K& zSXt}q1GrI8;fmq2X+d&KIvmJa_aOjq9SGzQapfU;!Br-fqGdm`%cctFDVu7>&4n}< zLfwLFbPFIC% zguiu@VJ>;|y$U=@lti{uKC=2ckOu7fVmx>)kyqcVaK6<}onrQDiEqor>#+YqaUy&p zAUXU+*MR8)i3KvKgIZykkcVyc9n~oVdE5p&%ZIw7ao(TOYQW9(Kp(d2dE#kz@C3BX z*UYpiR_xo=*BRMKoon`D%~$!cYrvC5A+3fk^Trb~oh@18PQgY|3Ga$}y5k*jWSt(< zmfvH$sQ=Q%xaKFm*l-QS)UsW_Saz}tYSv%KFFhG1{on7RcCeJ^RX96#Rd<Fc)s8K#mz#Cw#F zuG!WeXrC=`AEK1i3eCmmyO6_I$Pz0z<}_j&0mc%Ky~xd9?3#WZ{650xV{Cf+)M(2#kZa>7cuQv) zl#NSgVt1Exmgty4IhV^~ za-`wG!0!B!gx5fSEsoyJTi)9m@&epnN*VdNWYqhACnLUYtb#Mi=%=-wGU98-J@J{Z z8FwUtwtZFatJV<`nuv!tq=dqCY3u|hB~)F<3=#?y62hY?;Nq50U-jAlETL_G4C6c1 z4gS*73seu zru#^!QA{^T98yeIK^n zM);b)xJlxgv=N`Vq;iQEtj;4P5_1-qn>dI0i0P=Vyqayno#B|9I9F6fdrDyWTsnEc zva4uM0NZ{bC7cBf5lX}-E)s^QEvSv5cpn|2&KK;dw^Af@EHD#1{f$%90WNN(7QEV29;od%a4RjsTLO83+Fk><(rjQEf!e3Q*3QN> z=e`t!NXm^YX(QS@d6tqD2A2AQTaJMxUvSF{))oPKVwfR;Ylo>x?gZxH(dg`I+C&4l z(hOk9)wB!)x6(LZmTKBKV9}`tZX;6F#{@SMil_*aAD94XW8{X(kaHRSS_>n$WMFar zS`%P@5;whwnhjS|-D%4fQ#NKJw`4J8a}U*&>m3;-3$Suu?Iy4VcZPC(dAr4j0`N;-6rl?}&$ zci%|WSJ&ECi~0FqUZLFNkHb6jE-1nG4Rp&l+<1=?SI8qX(96qtqqB?an+AWsjl#@} ztRumXsIeX?N_u5*D7!XJ^{s>-WE_9`5qCc84(%^gx2H-14 zySZ#D?Bn9nax^AYzJHtcl+)xnn>Sju_B;wVF9B+clhON+^U(@mJ@opeufKjGFkvLH z-azZGJAv`z;3r3;P<1`IJ6dh+))Q%!R~T7JtDIwGDXsD%U?GX4BG^2;u*$sNuC=SF zx-5c=(M9A1XF8atchXWt}KUD-OWXOH77s5TEw}>A`B?q2}=Q0{Iw77rf96waJ0xu;-ua z2hm5SKjNZ?{@6E`6(1c`J@9uKa0LQR8>7bfEe6qvCp+MM!Sh8R+wsXV55!Rr!LvZr z!gQ95Wn4^(i!)s=L1oEfpWiPbXp3Mn96{2AG&T!lAdoRU{{bHeq!*B$2NI)^*DfFz z3E}JzAKL(VSs+rJO@Ua2xYh|j^?_IfONm4Qag0-2(@-tP*z_i~!;lOMo}Re5F>ow+ zdg7UF_~?PM_1!pipclWwRtSfsW6y9|^w_x7A}5Ij(-ThbmE6qUe9n@&4FW; z*Aq{Sck#PFULBX}`Q6+B;m&%84N%G2XVME~A-na=9jz-=CL`S0(yuHe- ztQk$CrFx|=y*}Z?z3@y-5enYyO#2~G?CD1zlHe?QRb;z&!p!ulhtnH3VcMZ`f_FI8 z(3KevVQr&4Z}u*$T$*IX6e(w8=w4>x5QCBRLDqUO8qDHTef{KKMLwS|vs93w4)+pK zI^`zRJJsown`m#G7Cj|Db%NU0i=UaYfTyZFlWL|}*%WV_W;7+g`J?b^O3sC0K~Ybw z65Zr0m}RH#^6&VUo@7%&)pT1!JZB@}Gi2{_9#bRz`XX#HZy>`D3!~8kNE&7srPobn zJjVL&#i}*J_lxf>@V$Zi`~6o$!%b1phBZBksm~8~(Q9_N=_Rka{Tz85P4v|_a3L&T zWeBG=4YVxhfwXkT;1R;b6^Bo;ul%t`dB23Br^z2Z`hpWF_-G!Wmn_f5&f9@C!uN1kV?c^-(gr;wxasSwdBC_o>PjcWAG%3vfYsfIgY>PRLKmq$ zSklqM5l^W}K2_qyG-SbG*F}$4T8RBOCq*Q34oJAzU_w!eDr2E4fvtduG{sTErgB_x) zJg6P;#B=$fMa2uJ9ZND@bhFy&$P;{Gz^vQ4YfDmkeLo%UZwL!@H z)Bx9jYr((NRW5zdwd+Ty9eUw8wk8&rcAWs`(g&$s#lS|)fObh$V2fs`S%Mq&>5GJR ztu}Dewd)NdH>q9AfGt?s4^M;4gm&o)yI`i8{(n<0cKJYOtKaAqxVV!gjZTgBO9A-> z*D1EObeuJ~AKZm*xfmo^SxMybFcNR3H5R-xX>tLOn#GmH_4o z^%4lTLd}Qk?E8blS?M!ssn7$=(CAv#3QZx`s-N6i)eM-YRy6{4_gQFFJJczfuW$Pt z=6+;aX>{Ox;W@RpnUG>Aek?8UOBxIOE!nyOUHy7Nz28R;!MoUI(8U!{c^)6qpzC6e zz>2xul)AVG7+vYY=FNpJA|ZU?VC`HC24z%IhbRTmA-=tWZVQ<*4?7%2AZEJ5mQD=~ z0xh*N8RQq0>{VAFmF-nqAh1`YR`uo!wJJ8+6|z@Stt#OLwW@?mwc^SAx7v4jtASz% z8PA1>y^`uxDZD|wD&bPSh%dKSKff;2>Tyl{Pr$#oq@=x~P~2V>Ae2-u!gPDJ6);z? z_dvMSYc*UcFk@AlVC?N**ypxCE6Y?vt%!$C`m&|?79<_FH()Q<$}Ba~1vJ4%ECO8K z@4~ywQ8&xLH=gatQlkU)Xf~QQu%%hp?Ii)W2%cSz?MBD3EVWQ5{%gLjE%bL$Ex6K6 z@N;dUzacQLbov(h>%g#uzO}Uj^o^z_t=ZTN#Y1LRac!SJXyj(W_WANE+I|DK(jv^G z=2g-50%O?*Zb!4#9|X5{R?Jyrb__FV|2A+d%>b6{r%g9)GA>vbx$;|5Nawp|0VpFoY;iCh6vMQm2sC;a>h#7FeWX)JZ{=b3fNA{U}U@v~tw5N)yYOh+yqnZ_0? zPdpLl2qeGYT(y_-cOO@)R4L!N;RugyVV>dnJ(1WJ=84PJE*Ul^ZqEgI7z8y!GQJf<-yts#vj)e){X0gt zdh|59m9##(jr8+{r#qr%(wGane-Eh-<9!o8ECuoxkiG9>(C|BmouX>}EIj`V#KtF} zgDwcd>4#=~SCEdJUJ_yQL=U}Zn7DD z#mG%Iqb~sC=ag5yVMyTaH$+=nY%{c_V~s4cG1kj4X?7z^*_Ms~hF#eh*R3+JT(C-A zp(|#AY)h$<6v(!eXxWw$skfy>>uo8~dRt1gY)gsM+tM7+dRt1g-j)(A+fq&%+foAb zwv=c-lZGlpG@nV6wBD8yuD7K`&wm@$GJ6rNuq53W8Wtqm&^bWFED^i>Htqj~+uyZY zcrsju-NKd(xI?}j$m2g9&SqYboCW#u2CU1-?eK$0g zm2g92SqYboCGkUJIdphQ5*nlRym6`I&(LUA!VQgPC0sU|#21Zb2lm;zhh*N+a#jj# zXgMq4vgIVEXgLR_a$Pix;|wikrErE8vl1>_Oz;!y9kRvD+&sAX@ChUcF}GDIjG^VM zgd1AUO1Nw}Db2j)jD$ka+}4{5#s3@lmvu^SIk{iaauTVxoJ7l(lSsYgNVN^YzcOq(he6`4$XDw z*S1#&hHKj+*rfMipS!@&sW`g5=zZ+q;LX>q5OGX9udDVmYBk5evNXFZOnz7GtiU+S z(qv$9U9}&9HCvB1sWZ5B2Dgm$V%nJ}ur#?ne6`oM7`a)1mABK@8@Uy=!{D)<_71SX z4dAAyEqQ}zFY&w;JxSIUBiXjvb4G3%z>?c)vy9y0fLYpVPXjwf+%RdGLp%5aH>$Hl zPU&GROB;Q(yElRx<}3N;=RY@!$tqHtMw`@s zi(;XTN_jPr&YIe7XunH_8NiZjYJUk#$S@9=rKWZj*!PaesVx9ITxy3f8^?HhVL;MPX8n%6I!_$dLP*iw)Ts*rSzf)z((x zCiZQ;S&5t2x3vOT&n@6q2i)*72AjP_oi1_;ZP5=}J#OTdjgC@=pO$XqmJAFXqcOm6 z&?=mD+KOIVZLlPjacos{14Djd3@tI7&L!@}-o+tf%A%Sn3Ysujf0O1p$Ag(AwaaiIdUw9MC%PKdk46MBd1hpcJC0CCdX!q)Jn@6BOQ&kFeA4-VA+ke z5F@t?V9AZO0AQ0p05`pK@;*?LtW}}f@zbN&r4O*zfAWi%z4}m3@vU$uRZB>-rS>iw z3s?TLfn~JR)&g^-I2l-6ON|9Qltx{_k3&+st@0THA%ZfA?*S)~$u9<}Ex5HrL{k!PfX-JHF@_7SvfFM}Qn++I}E?1o9=2c$OZF*RCW| z0Hh(y0us<$`1$Dh3g@N0YC|8(;Vj%O`?=asmr{?<-HH2cznc#JLXGWeLMBZ=M`{=1 z!XV=Crn#McmUC4hV{Hk8s)TBPKy!f=^Cg|4P*mwq?J}^lp9}RVrY50Q5n5_lF8rRS z?xJvuk(x`QZjq#y6ydayQ96?*c%L@1xh4Bu5l**k1&@&Z*q8Pmhy)P9t3hH9azXggFf^-sCI5fRchi4|F_7jP_>$~G|^>R=uL`~ zZnMHRA5>@gHOZtaH|T8%*1ZPa0jLLef_zy5Zc8NG8DFdMjm?NpKPf<_;%`(4(oy}S z0O{&2U@4QkN3ermt2e1^@=<;Ty@aX|4bvsIpi1LK7~fujOU=lTtXx2o-mO2wp=60H z0WyWZI2M2{SLElV1$gM`u-ecZ*9y_;o3rU*jppQ*8?(#s25}R(*XBKnYch_g6U~0d z=hM#89S^#M1&tM&aTv&XLP8@Bj}g#*K;?J1p7X>X6}1Pnv@OlNYmZ&jHu7Jk7_}!C zJbD(R_N)Ri9z?JPV$V$%*RMwk)uj+u3^aCA>l3BeOs$iAFSQgVc4~2@r;x7A)GV_E znm-V6v=%n2ugFU;AT7Af(ydq*AkwaFxzDB92FO^}dKsFF%>ro(L}4X4ox|!#q&|>Q z6?*D*^KSb!5Eb=XQBf&9Pk!r8+mdh9p_be8V6wi29Ik_SK*U85b&r841JRR+A3%&h zrY7my^8PWkQT!f&G{WvV*ZTtV-}j4T?u4HPOrwNLWDAgbEcYdB*)0-&-UU+UhMsWN z?ng6~nJ2SKbQq7cMhB0d3e zmWUl79)Jkm2x1hrIqM}bgLi50(w!@dzioOH`wCAYi!Z@%mP~1}NY;En^Eedv+ED@h z8_=bbYG=PEKvZYfp}(yA517gu4|fntg`%*r3WL7>>`=?Ot!2^kd6 zp@)LZ$J8(#IRFF?1$_(TOW|i9khTJ$?Tav|9|O50_See}Q9h6ZvJvehJZ%89pZBBK z>E{PqtF43kDE2(!#f`AFEcc9Bk4^bW4IGF9tu%R-GyqFrUHjhl!aD*__Qu!cm_~BH zi`nNtsgHZ{!<)HSiX3&zlV2A2(bAB}0Aa6P@# zQ8p5IKX1I=(=LABK8znPj~U+K(o@Bfw5Pl?C%gDPUZ!sIDvxv(=}772CBMRfz(;%I z`!Zbo#+}0*7oPDIjz+j>?{K#Mz~j7eQ<~0CZ-=uwVdMF=bGSLglXp7tKA-5F*1o{6 zdgEyhoi}^3Tr@;vVV0C*qTZ8t8S-`ELvQ^{Cpql)#@CI~dF$P6?bevkfHE;^q-Z{U zE|nX9qM!WvA*zv-4%XxQcx9)IMD>I>z7M8?CmWU({JgSII2PfWd56m)@wD~E>mh4` zpUA>RR`PhK(0~`+S-{O8xWwR>hZIE;nS}-3Vkt`o{<1fo)?1H@4gB>XvM`e@aF)ii zSkhB~kMPF#^>pz&^Q*gPe;bNjKvG7yCLxL?o<~dm!!ziUoyW-@Pwq)jkPA0^d&OEt zM)ZLosfO%jpBa0oJ~o-Eb#(PlX%9P^$7TX=$)%1u58}8 zskJNKsY5!WNG>2(vyiK+7tjfr0wUz%L$b$h;4<%mFC>L{%NtK?>Wb#oi`c%L2*w|X zmYtM%&2`>;By#AvF)lf`9DwapQYu}3!+c5@1!GAsjI14KE(wC;0C)tkr1Smiu}^+` zNSkV-LdHQQPchm00DsvVPsHs+GQ!|XNaxwvxcdQdT&zR$$yl<+RZ^0UZH~=Wl790N zicI%I;XXvTeeQ6Sk!s?*ULlhDqC$jYI3$A&{2jq^5bR&>U`u|-bb&EgRhGJRR46+I8%%r~-@u?Ji(Y$ObV0_0kLKbdqKxNP`~=i;M+wv6O7)wUA>M8XmdvIPObiRx z1fzC97P%O)`Y*i4O+`KkjQ5*SY&cftx zXT{cC*s#!9*dAqd>>)T*_rfV}oSsIOLLJ&HDT<|Cr7risk&3HO z>4PBF5>W_Z?^U(MK+pKn6TmmSmsdK{n~~0VdL5y%Tb=DAZ+ z@E0UJ0~m%h9TNEfXEIzrvO*+-wWz=VB?IoM{9tD|9qa^G2apGD9{fIeS$eTi!xF+b z3U5j9))ylH`RPi&JT7yk0&zCR$3(FkgZ49mYh55S#eNaEYQZJ;i-gb)5FjBy#$n?Z z+xKNk1bgR(8bMQIIkryK`5BIPEIuWFpssPO9aewi#QolvftAtCue2g8SB@_LyZUX< zaOQs#vu%ID%F#CbW;fOJuG}lFW@4u89A?+{7+99Z0mJOt#|D=A_FOW3U){uPo6haQ zP0YUPI*kpnY}hSzt|e(EMn$*OXZ0^rKf?hRVP#vclk(w{^>i+y+*HyX{#Ab9CqN?Y zfz;hOIL6WfM93X=fX<3v{-;NX%m3KAJ8EQ4ANb;VqBYebabV>-)LIvlen{YVV7i#} z<51^;@lC?j?qcyr&sf4;bqK{-jFv$rpGYL14hhhOFafx=i4vbb1A0PN!hqfYT3iXk zuhIds4#=0{)c56z(N@1V;QmeQ`8h4Z=K%SYX{E#B*sudVec6_K*kHnAHrPoU<^gHz zsVB}~n#92;PnFt%0M7upbSm|Dr<6e65)-{@=#G9{XzO50%7{`>=-( z{#C(V!igaHaq6kGmJx&L@_jJ5f^T&BzWi43sSH@q`_Y8(Yr@ZQ_{ntp;d8L`1~-Bi z;nO63dWe1V00v?=+>4nlCOz8nA;_aOhc#Le<46!y3AIz76kd!9%vJ0fwijeT6_ZWc zLV=07@Hk)=la>u^?`NHBuUO}ZB(0;PDJ%9m3jaar%#IFz35a`#IMgH`ENl#9D?ii} zfyOE~&s0(u$VTLfF11?sG}21X(j~>CxUAmd*Wa|^Vlrr)e#w<5zRq1-{6?7ySw^!F zkrefPy^Q#sGC#rtzf|1WSJp~;%OtxI8hXnf$^Js{`Pf5 zyI9usa|{rr`);i3^iy90OZ_$(vUWT-WP9U;J?;i9&(G1?`X>@d%T%ZQ9DVend96-bj*42Y=Lu%p{Rla-_B%S%E1of#H&Um)A9Juk$tOwMV;Q2|?$D3Y4HUx`-o` z5;+K@gE+SItMF3@q>Z?ETs|i836K%u_NH&zrCTjK;C^6r#Q1FlF-Ytyrs@G5%LNh= zEZ$391^RJe$FBuF~~UCt+i9d|7!g6Fj(IC z(p9#4Pl6ZuHr}3Gc|*5qv%0mc_PdnvFVkqnF16!eOsamLWDPzI_d;Q<@}VO=F5^|N zdC%gqk;C}FUv;AB4%TAC>j}NQQF4u5`^-2_1U_pEH z`T4p$QE`^TfN+i8P}gO{mI^GNFUHD>^C~c2ak7F?abU#qsfV#N#F0d*PHB`)Cy~76 zC!%2RgbtQRkdB1T6JjhwiAWtE6VeyNL20$Vnj)>%#6~Wwm2cc_YOq?BaD&yVgiEVM z(etbM>L4=S!XP4`n_sgGKPEAVs&Yaw7H~J`ytW_1BMIwut;1J2L8XLRHcvym)1!lNLs}pbZMm` z6H7xK@l@?ADaZd-nchbvB&8<*NlJ_0K}so`Qiev*KXHgD$CMVXvCM`M_1RRLBcj<| zq>DDe+(grO3%}dYH`)Yq!&0~D9c%`et>QzfG(Y}uZ;6sx5@ zV!Rp-Bi;f8UR3ev7sgiCcUUbAr&Kr-A{;}^abG~$^}`pm-=&b;$#kG_x!EMvg{-@yI*LVDppk+Q`BC>%6v6Ux0|Am+%VZEi@h& zex%3$8z-9G8Q-AuO8yO)>NC;@Qw<0|&ECbsSA<)d6gr458Nv$73z_ zY7@s+XM-5W2A|+pu&}ofKMHM|%htp@hO#F09B*4KlkmPFJ{+p&nCE|PA_lH-uzEK_ zV_hQ8ks{BB$nzocoJu19sDT#QuTdqD=O8!It`W)Y8WC=h*FuW9$U{IFMQ(kPi#*EA z3gaAYWIoDbo%~z{dlJ7v z%^laRzdTmKn!^DRE9~tSjt2hwfdm3!r6)t{v)@`c8g(tCvFXA%bj{GS%l6TzOkp5$ zZ1oz$7ywK5(MW3CANo=HAhag12ic>;Sz1dNgX3}xo88i}+OiNyj7xANgv( z+?ajcKhG+3&PZ^K@~LuAj5nv=!S*mgj{B~oPG0#gDItj8Q(-QN0iWvP&{G-pZOkR% zK(JJbb~ivG)qpH*sYFjjp|CqKj zN@_v?@5!4>RzQ+RyEvl#%q5FKE^X&XuS?Ub#_GVIGp8{RQa%NqLfWIL@|5=wlrWd~ zJ-5931M`%3GB7Uhx7!=!y|=yNqENruiO%gE9M78nIScf59Dh_c&s6dvGTje*15)_= z+4JB^7MGsUnKOK!1>|a{|AlDBcZO&`eDuF3T2sm28C`BpVZFh$v z_K6_(tqSY46?A9>s+}-iv-rT2U4rEp4`LH!umDZr-88kYkN4R znB8fY)ps>?PnU#Vecuq6;9V{*vsngAycm)Q71JYFkmzVH(r&B8b|*SwNW+R@wSw>9 zETtgVl=9AU@NYeJWa{r6nR)>yE2W>kxSahLp;|ql6wR3Jtsz|XI>6Of40q@NBvh{@ zkT_A#O9avgNY8nAFAZN~LBAmGaiV*CfJ6Yv#N6EfEM;fD=$Q~CIh{ zcozfNd!P@G`2gtW#3?X2RNDunjTp{J~C_|2dttey3ZLUU|M+ zaU^<%IJ?W!Y%pAAdfZ@vaiI-t&jHawS@lp(GCF>=D zX=2hS_JJ#o*wMHtepNq5Ex-L~)JX5x*e$HO6y;|?8bOr7tZ?thICig}!`~}8^j!>i!O^-^*~f6Y5DPZJ`nifRuA3VW+35 z*5KK2$0Ajdi)`7bj?6FT)qu}z$+6=|c&3h$^vq|r0zFb92L(MwIXVQ7KrH)&s#4PFX)rdW8g5AKg%2Bfl?au0 zsCEHDkN5gwqDA!LeI9YNp*QbxZ1=3mPA^!CN-GW0!!ADOy9ck}pELT$BHM~61kL$%#l`Q7MaYG1d8X?i+dPV8^OK&>Q7+XeifMc`Q$(@4CP zR_x!}#4f3hdcGJn9tOyZqnr_3q7eeIw+iGYU@K=I? z*EUU0g2`=S!e}J7nYIYHh^?o#P|r<3*~+X2qL`Tixf*mj2_s# z--`XqYHNP#u$7~0~> z$>o@tOPYI1rCm+Uh150`GPf)Rv2shXKqVJ`-)Cmd<=hLt@9Xb<`{RD@Gv703<~iSa z=9%TpnTfNc1r5n_^NCRwV%=^WVj4jO-EjaDy`Ut=Exn~OS6rjXUzQr44A=79@*63$ z=o+3j9VScH@L`59T^DtmB`sv|40mOMxS#gYqBsfohc-EG#$e?oacwm`K3z-4KhreE zO&LYkP^_!*B7>Mr$G;op>l30z3{MMj_6bnZ)X3p!*e`Z?n#+?3&6I(33!>_8fvTus zkxJhxt|7T%w@-}f0!l8jnG&Zel-zzKH~o`frJbf7X+YZHpCxyztr8=y9Wd}~Gw{!n zi)^ek#x>?3F1NI`!WMW$hLNi)Li>^t7fl2w@-1 zPDoGd>$(Xe2I|&-m!1~J8W5^nq8TPpG{YoP1LA&#Tg2j_SRS>oPYAVm^B^a%ro)|v zbwFkT*)}4r8}*yA^?gTU6xxgdtg*Gj3+e2zw90rqx_zQHqh=?kIHsrV6YGd4h|P8! zaoQ({yrqtwmSF4yV&_Manl$^lL@aW*3K)T01#XE1A7sem5d z&(Qo}^XqI-L}=$C*6k(nSf2`KJAV{f-?$+-0FSr6be)z|s~eAW_ENKBO>QpDarF>) z9Uo5{?CR10;Ud2MMA+;;*rx_zL&e<>`*vuq4sYAT&7~$TtYF<+_tV@WT!3tQJ}u1i z!BeH`Sw4(nIUa70_P#9M)#W-al&}u3ukd`Afc%E2TQLo!zVu02UDZ4~ZJ5-1SgCdQ z=rl!={uqSzaV#bPIt*pd4^HYgFQ=`Pej6z8)?f)y^PSX7ucfV(&JSRCZ}sGav^1&d zQ>E5c6Vt++J+`D`HT;as)Y2%!#wE9XJE0GGmdq)bf?1p< zZr(BwH@}e<>Fm*@e^ob68c=G*&EuSpQ16RD-v(79=YT&j)eOZTZ?=BIU5 z_is)MRzIGSmLz?O)L5o1-%XPx$<&A4yiwZJ552ylY2B=uOVUg0dru1PTWX!YDlNuE8rT!B;tl}%D5=!iZ(Uk57pbs2pv`F?Rd3O| zRK0^&#COz$C279a_$_J9F4e|%tI+ACUH#lu^U*Z3v%?!;mP*y8bgoLLZxTwa(5Xz4Qadqq5>)RW)9P4j|B$x54exN}#n>hnx3t1BXw(T? zirE%)tZ0SHdXD8WKPhG>J_Lph=x|)9n;h!;8pf^kMR=l{JjvA!e$p*H!kX(Q4>DF8 z#fP-)v|%oWeT2`-q9pwpe8UBk$Sl!x4c@q z(z4VV=R?rJrr74fSN=%y2Gll4o@cbS43K4`^h*;Mbs#P@X~8aBagy#fW`@vP9TO@) zDAvdX`f?oE1UlC-wt2cHP>*3fTVZ0Ff1=ocW4!Im0G22zk-)qf$T%?(325rMO0p~|L;H%lJOX^)m+<@*G!{%APY%F^k-4hyM7jr%rp4=5% zWbdCc)LFgTL>}V&+>W%fAU33#ZJ5&^g~u4~hhI^!=z#eD~HKpE|&>W zBa`HMYOhvujovI7-IN5IdO&Z;5kG*kqu!7sPAd+CDl1ya4WxZY|NRbf@RMKHd-Ovb zplilAQt!O)R(5%%TN%A2Y6(mvbnIbgGFf`2&aLHGmxW04Aa_u-#0XuDIY6d&l{;5m z$Z0TGR>(u@+6s9vFvmhp0fs`3u`l0lP=uB5XRsw!zAb>T@?A#uR=IqwDBteJe^Itp zl161^)CpbT*Es2>vGN0dvsm7+To&H^H2t?T)##7 ztXxmjee^?oPuCpEwF5AeDFDk+JmqoF5|ode*6Bdy2xqZv$Dw4^*XH z(}3In5|JcFr}~^VE~0r}Myg}Y#XPSg&Po_>{v2_~5XmhhKYT`B+O2cF{rA>f5m5fTd1jw9ZIfa_iY*fi?UL~zpljYv5 z3>kQ5C9jUtYiQNcn%rNWZ@^r)gLlE|te6Lc-63lw0U^#N`q z&nlHdxS9H>65|!iu4Gt=Sy+X$!yQU2;(H|Qgc%fC6h)#ac`PUH8IMB#xV`rs3y6SlnZlV-n0`C z=1tcDVcxW-kD<61exfFBHIp~hz{(AyHGDXE)4svn9l3Ug;Fgf7w&*QKQ}2}?SJXxl zS#4z4#TqTNX0SSxU|WR-yBhP22=JXk*zt__E~+MF z&zxx<5@ycyY>;rKKR|%?c5Pt-utyZ(S|ng!gv)`T2>sRPM#y_Qpty1(om*q%UmN|F z+R9U~Pln|HD++~!4OLP(#*1(bu&hv}FEGnUbXf<1Kw4+6j+EQ;)EdR2vm1gJHz7(> zeQJroqC%90`qU&~MZrp4U^SkR+i0m-dpskT8F_MDkz5A0JxcUbvSEET<*+@{MQn#O zhhtnhY>jjg+abLPZ1Qsz$*I=oplM_D)WHOv8y2^xo(fW+vX-( zcaN2i8eKa=JM1)QT`*1#GX@UzFIBOl)h4c85VZ5(v@Usn$C!RR z#`LbyNI$x74>j#oD6Iv2U#kdMzk5yo!zgw4!*-4n<=~Jw2$#@}`t`f`vVzm`WuDlJ z3HKGl@Yu;8T)Yv>-bE2Qe_RT7(8t??!Zq&7Al%(W9rs>GKXuk5*{fy}OD$y6uUHb< zk?ka=?wBM8N}YfopCm^nq13VqviLr8ksGilniR6>Z^;=8ID;FPNiLh}fN&Nkk?%Vf z3G)jD774xzBw$4z3VDzKU>#nU_e$^jmRj$6NNYu z;y}IcIhI#Ygu_*H-I;nvfKAAPt)VpYs5G}_$q$^o(!ER7huAfy1bYsdA@6=uem8tw z_XofIWhkSu^a@~qt&A_ji<|9ai_5%At)t(PeOzkd;c~REphu~zyWmUy<#T0kdT8J( zePO7{;j}?4hxvB0TxQ$Ja*=N*E8vRQY&%(wvh8HKNZZM(#q;EuF1}v0`x)C0W!`+* z)ujf)NBE8>A5&ODIG0~PO5uB+aEAQ)9~Axz;dA_Y%>@WwL-;hm-i*RU2xqWONz}d+ zK8LV{Z9t-qL0CG0@Pq}Zl?%}oTfacA-+Ts;iHxhDP17LX1+QB8b&4%`oB;Xq?`rd= z!$Ph8*>VkM_og0L=*k~3eC~j{YM(`N%kJ#~l%5#4@g9ocF6sj9i$#5*DD;UQbuCEr zmuli)B-r_RoL*P3NcQuhn{!^{DzSG0^%8qy;W`Hj* zu;J?NrE+`E@p#@3@!UdH&rKE8=~!)Bb@KE}=PR{WY{jvLBJM*82d@hGSV&Ks{4g}3 zc})*Y4-wg9ZXdJdLv*YbA@zXt=Sz$*Q%Fc{ATP36P7h2m6XFMCf$f7NLOg&xVV90G zOXt>GLjzqY!u=XpN54!qxmG8~jYh8R`|?zyo2z@NnvBktTD(k-RDW46d%2<|%67wI z)xVa@GmNfkb?m&1e%0g^GWH0jzQ8NAlP}gWWf_%AFcpR^#g}6lz!Hth1&;CNHj1xz z`UzM>*93nxekJ6cF~)H=mdju#n(_q%jI{k zlubr;c)xTPOc;uWC%eLhlgQo~(5z~PA-@-%=M~O_KoWppJ3rIlU>8Gvdju}5mJ`S* z?7CIyWTq{!<+%gSUL&-%;nt@r^ldkTdfx04bAIU?FuJc_>)syJ5tXwB!TU9EAjvY`4 zSWc7Wtei&4GAyVg3V|=X`GI4i5csm2qrfcd(e$*&Gt$RK>Uz1CR@&*e}2$Tt3> z!a&Y}8{}Cy)R6di)Kjvh;9^1OWvEz(J*C>|3;5&$ge|v*he>B3WNen_^`^x2J>LU( zn@n$l9dY)CMy-tRN2OiyZ6ZzQ6_kkupHHcq>};d)25r9+QJDxz-r+ z|3au2dvj1reA0IfNCyzU1AX0yZ8G)+rYSq;PUzBttz2j2AWDQ`UjtjincfS`Nb?A6 z&VVz$6WC|lz^XrTr*7`GZE)p6mGB(7izZLY=o6x5=E&HZmg_k?M~;;;p+|0xj6Go~ z|F`KJaJ)E)k`!5=zXYtvNqI`2e=bH!Yn+r+U`e0o^3VE2PT;BeVa?PUUQt`FfjWrMC9~^Ix@zHx6I}TCvLV6%^(`n=_;JoG$?B&+8B^p#U-hNFVML z*~bWmd>M!re?7!LJuu`C1X6>?5l9~(u6*U*4?LZ&KoquQ$Xy^Eft=VOcdBf#IBSS} z1S>yX(|5oZIDCX7o>^hAw10&<@pBm)(@^2-Zce8IeljZGoIp!?r&8l0tTg;Zm1_rts+^|%E>zQoz{E;k@)|A? z2-oH%FTQaI1QO4hx>{oSwil2mkj~ivG=g8qR|1y+s1vp^xdeTbg^(Lz5N0^rMP0C4 zKFVu?he0X8;vQNk`VJ}_t7`?ou(*d7ip~UvdY#AWbt14RgEAf1g?Bspt6TP<$?}86 zlgm85hga@A@`(?h3|H&ymFr1S$h5~^xfhu~U13|3a*=jB@W93^G%wy7WaAJ6&qTJ; zwJAcMs^iXd3HCAO*F#_{o{73y9~sf-t3E7J9sZ^4M)s1Yx0f08b_?r99dY*cCYEwL z;;Zo1OQ`kb{0%&clbm?tKiY{J{~Xr%w=z=WuiiVL`LY*qTBU^5s70=dk3P#>Y|+2QRq@bgnFTDv zRdEG2;b29U)@=vn51cwAz&awIbA`724Rv1>p6vwW z)rT<)=8JsMZL;PbmLD)rO9jTpccL6uY<^lRM~v?@@!?C%0aIi)yc3a+ReV&9;T>yD zDa!nDw%FlGeY7-^Ut*h(Pz2hIMzix{4bYRFy9?GGWz6?9&_ak?X*g|8Ak~0i0hHX` z&toT#^RT=`J;3*gq?Jv$>o$;`>VdVxLS1e^+^#0PJAfUw^BY1rY!Q^lZXWeKke~U@ z0yzcbjH-+p#_l+V(2qR3v;2<3K(OT!mVC=(!`#&Ut^TGA_J*4v~ocsnoUKb8l~#Xk-&4`YfxZc6ecZ;A1P}1@PKT0i4Wp zlzV%-``CH*_bT6)P#5V*HYKeqkD_&^w!-f2)wD*B`w}}mof`GEEoS$duoXkrn?;hz#pN3HsRj z!w+u&`H&+8T&drHIPu=V*Bm(yB!O=+BaW3i1;otkP-TZm9Yc5ug@e41%VC6mhA!Ed zpJ9vYtv{TQ4@w>2Jc=W~g3nq5pM@3kyJ2Mvb908{0hZ{dkmUi(;q%_WBsb*~V8>6x z$%NpE=#UcEGw^`y&bcn|fbeWM>~y|9HF4PKJNneJa7al;HDxBStTVdQcAt?u@zk8F zK@S{0f&)mN)~ANUNa(OrlRh=kBOU^*)mdF?qt9x(y@1qm;X2nyN*jG@S->(RrKLW# zL|{>p(gfJ=`qUzR!q|pA>2;(Q#oq(mL0Q{)D?(p3*Qor-G0xi>-oO0=*oB{Tx&@w- zn>9ppLL=F-E0XsUSJ!wc)OU45pY?K-q3m*~q4;VjA7hR_Cl7TZbIgX-zBrGWBZ;CN zCy}+|)RD}5ODL_1dH0SnCw`*>iWZ|Ys6mFVC;igH{+%(C; zO|uxnO_MC#G>O7ZlPKIYLxr0rd27GEEj*5Ky_Wr5g7NW;@7nsg3*=oOac>W1YmsL| z#yih zMv_MBE8kp5E3UUy#)o6lL`&2RUymi1RGdA_O4MPP^%R%3{z^Mn^2&vcV8gA&zsi@K zoXc;Qs7so5_xHgauiPzB`*D{}2Fo_~5qBg@Y?h5+OrMgcC((RlXp6wFxUKZW&0)5i zD;f@pHw{y#5(&v&St~)}ip|}dtKLn!yU^1-q|1Jb=8zYlK(< z;|ydSk8_ACaQ{vTZHfPNw@{Z7h~4>`?`F^U#j~VhOXc~V1?9crD=yKV3I-k0@&EzmH_p@ zHFOP2;LK=va;;1MW~%pfc|^4#e)CtG7Gsci2TwyC`+mjpNS@?e9JVUqfN>0L#_N(Sz#!)$ z1~xD1k}SX==VDQHWfZWR#b}ANGHG~A?i70;Ntf0zl;Mp}SqO^vHj48uwkNrVcZ-3B z%v!^c1D#Xj2U$VY5f9IHKH{aucRu3s!^P<|k@D~;KIZ1g3VgcFw=4-lwPO2cctg9+rg~}sa$H?~rMjO7Tn-_3!TWah*3Mrb#Xxc@6spRe*lK7T?@S3C zMf7j@M_K|o1mqAqeIps4O;en`K=6r<-*Zm!WxRTem7+bMB6VWeyzc8M84voc(Lqw_lOdyL1ED~qGLi_5vH@?t#fb7&lzn+ zeeaI^j+XB1yYPCV7^`AUf8f%{66!wa4_q<<;Rh}a##;$uZ4eOph>2LMK54?;Xcxhn zgn7s!EVKq|@u(Y&k6hjti-h@i07hnCkj49A)BVXUdY?;Eu+6>l9gk92lciyz7@T`vDwq9*fANyUK$ z1weYU9Yfs(at267xs1)Ocov(=>&qiLvi1HPt@_3Q!g zGun@oC$e?Ppca9rxQ~y;r5reJ?ZMT|>RoE9eom%=jh7W;Tx5*j)!4<5;%+qTqD@8m zY~#0i;kF4CDbC-G9Tr5t>meSJpEk?B;PJeTaEUDk{*6HqPvuu!3TE?|?s&mP*6<6E zeiEMJB!sb&DWNx0Oy`Ot*~<1ocOCHre3we695~{u@R=}wIQsr7MD=qvwXT%t0s0C& zDS`Zcp5E^l;^Qqko!t>Hz&jX`D8`8)>K11cwgBercE(FdO@@;Xk9-od9gaNGYchJ? zXYrUHGY0&{XW8u=E2@>iu<}D7Pfr6-kH7Kq?9_{DzP4SF?Dky51$=* ziB7QQP4D}EvD$-ub!yt0-X*|Ld-C*6uL7)}n<>V%6c0i({%^UNShc6jSyd-NG`J+L zi0|L38m2^(U?|7C4rlvRBtqWJwsES3D;*HBibi(N4bjM&*4r9cJF<0+tR1dvWbJU# z$TID&_G?hf2bobVTZoJ*v&Z(GynPd6f~Qi#oNnAyo1bYLV69WbwB7ls*?8dUZkYE^ zk5n4rzgKYeIjx31cefRM5o3wAV-akw1@pYQtzdH{$8z*+E(7KjKPW&=@HVlIjJ6M6 zGd0_rTT70{D+z*E64_>W&)_N8zGY?-Xy3BI5VU>EPG9F_dQJSuMrIBy7l#U^2Q<@F z7ae(Yz08n~y+94suL<%fJJv&Kio}V$twyr6ZTdqn_aO=a#S%g*>G>gPW1z3@kTjQ(2shz}s7>|3p=lzCoC2DR>7nxpRc+ z-4>Y?KY&v@mE9Y-X)^vdST>}7?c~3IA%2N0&OOvsS}0G4f{*rK_{)^oj%{e@A?V`1H>akH`BNK@4l9 z@*=t4A$>*VCNViKCDtVZ+Wg2~-K$5x=;Z1Wi116a}K#h4YG_X1a;}I-l^WTA3Z9_;qAf+e`B6rtsAaehMwqa_`#-QsNAxVjbK+t=CSgWR@I=;U%$hcoO%SS z-c3x-(lvzOFY8*{H!=Ad1Je=A6jo`5Och=Jy~LW))U?-`>UU1$OdNj=A}@lxAz+?i zi+~lOhU6NQ0l*IUh@tZu-p(fj^NQ`~uf7xmzj+b^C}MeGj49o@+BbYS#lGO@BKv}$ zi)^4nFA`v_wSLuJEvO&oC%L+~Bg|hcgwl%z#Bc&~094m8)cKLEl$Q=?bT_Pw6Wu~v_FnJwB~JHHWFzp0f8#YSSDn4r+k+_ly`Hl% zfBPkB*@IN~cBWH-9dSh?x;;zCZ&O?R-)U!RpVkP%a8U~N*+t(?QS^_|$SB_O=R|hJ z!Qq16J}4D>xqtOeo(cdnU#y#itW1C7d|rC_%TwsdtM?-6yt4i|NRC}VYC67nQg?_H>hRaOVg zh{Edt-fa&?0PnV+uzt|Z^ciy~*^!x;i_3+9f-Mge7GsnSM$ZD4VNhIw*%(a(7G+SJ zfbrL~y}2P1qiSw%(;>3s9B3!(m_%X6Br-dub%2sV`4}qaa66`jnLs`QvW3}kfIvO~ zvO%^b7hnc&5qBQA&}rH=JM_hCG8A|gwFVMG!x z%#%gwj|P7TqAS&QbFOf2#uZBx4Akf#nggRxCh77i(Ww-OqEgS z7igpPNse&}1+8s>?Mp%L;Vjt0GG+Bnis`|>X79$ePES-Xj4~)cK-CZV%2Qej4CGrN zD_FG-#Pk3m2Z1aT1SbB>I}qWh(w7#YN>^cV%o3}xIA)1a|I!lCi-__^mP?T(F&TpF zM19g5BXuMYYbs(fGW!RoI!mu21bghpc_c5n1}2t;4guT{RYKjHq04EaAm+4+2huGj?PTOhNE-Jn{y zeh?u#eS>-iiRZ+K|I$KRt5dl;^H#?WXC!hzYKQBpv*)U$2DO$VGsYk?s?6YvC%VT< zQxOI9g;axXuR^{##FSD|kJoVWsFpMGehjjam&7qU^11_KV|ryMcZkHG`q|L`z!F>0 zQ7}c&lN+MiHw}CApF^0Np*jX(uM-GsMmX>%L0;**HuAD7`9e;f9j+tK4j1HQqnH_a z8<822*8~}XJi>+fk;urKk0=^>Z$ggigH2El$fhh}FfWp-v0$(tDmlaE2HP0y&9Q9# ztVlOt(@iixIKgakf>x917Fi$VdE=aTsnz*!_HKl*^VP8_g`dUL&gB>A`GK1MWLgkW zc@m-b_zNAe58zQCi-qMSpXKDKdo0`q+A+cE?tj7D8stRG)kiLmVD4>1(U{AG99P;e zTD?Bp6y|;8M687& zm&&ZM>A6fqVaLKugy7Y&e`B@gNK;geAl$J5gCb*eH?_k^Q#WZXfUJ?GW`UO=@DIiO z*oR_w@ha*9up=W)W1N47pcb#}7u+0g^vEB%8R;VO0U@1$DUEf{H>=-#K-a) zvJMEo!8wGJ;qmDXt$11iwkS90BA_AO-3; zw_f!J8kCLmxJzSd>$-QV=?fNA%t|=s_Nia(h|}3E;?d`i>z}BO8i(<|Vle z^{{)yCsZ?|Q-Nv#)q#)o-_M z4E_g}tmbUIj`9mJ_KnFdtYp!v@ku0NlVlfUWki zf8*{7j2YP6*I;0u;~B`YYLk08gv`ac6s0wJUrY`Cq2ACdUi$p_rt^K9c4NV zL$_4C3pj|P1jX5rGjTqZpm;AZP@Jc4^>zXqTQ4C%{bn+J_YU!T<=SMtrh|rgaMFTd z5(UEy#ep5#eq7U_>UT7;7+9V9VXq;0gjrDljiQ0P2t@N_H}eI_*|TjV=T+5tVA<shJmJ_m?gY+`yXCm9FaK zX{O*n6*g~(e>%Lnchhipx9D&~*oNfpNOHP7pgbaR2Mj*D?v<_&4EyVb8{E>v zALJSox1gt4gcoJ2Bth#?j4L;QTi zZ+Q&YE+Q27CqmC1!?kY_+I-9uEamPiu^u^Qnq`#I0YQgm(jW-a^Gt)JI0!8Jl01{2 z^aMgI`$qYuj?SS7>9WtvM+`4uEc+b9kjlPf*~duNA+Vg|e*k5mBYMhH4Qr*1xBs_EPmA)5~V zYTuJ4FDVQdbQmWYC@MXD@kvu1sd%r@q2(#l5a|bm=A1G`O5Z@(cFI&H&4$2K`0+Hd znM|>NGi9i~&zL+VGesg5-adnC$p}G(kxR~+yq#Mjpwpn!S!fUmtlwE^;7l<|gMzcr zpk$BGpw3Uw;1oiWe}V=_A*}of8q9~lH2CTqa+yxCiG)?ZAoMgsOoNF(Bb15|BVo=t zkkA?-oeIryWz)EKMH7N29LQt!dGzkJUdeu1%f=wAeHTybZ^#KN> z9HFkfW~wQ*pr}G4Z?)?mh!6pYX$133QuqCVSVlm{|9~QQt;hn#YW2Hex^9$SL6EtM z+Qp{Y(lZFbRRpU8i%kQi-V~KQ#MgAK142+KOdax@sjFIi6HJ8z;>x{r3x(m0Agi!j zZsG2d&xKxf{>0tCA_SGjHTxREaJ+wVM+>vk$uO=a8njh!#^2W%+fUcK8+IkM(L~1N~}_uX{wX72vXKPQ!{Lk_$hk!J4&q9 z`=)ebvl|GNeNv*XqCQTYTFNOXPg}WU0;e8(IKs=(akze{M7@s*uI|2S?J4~{)DaI& z^`vFcVa`L-N6y=kf?8+R5I?`4m|DJ@h6A~e`_|z;HE&mhpZZd{skJnK-_c7gE;q^2 zm`_R;_cKTOW{aBw#7#18id);G+2S1YBIz@LJ&fjN(s~FJjOO~%UOdZ6qdD3r9R&29 zlX+AGUEA@rK`D3gzm{HJK5#K!;=anh#K+zhxHdpCCp1|Af!OVvQ=$$8ZSP?;a=|J1 zT0ENEzp#Kyd-FRB@%BmP`f-yX1ff?k{%J%0`10}{udx&ZHoXcw6NzY~nV`QLFd}Rn z625>3f8{IGrsv#4)y~f5C#ById$KchzYkv5IGfu@)e!HTvpKjt=y3zX|Pgm>mb_1fmfYA087hEzMJ#Ja}S zyu(R4zpccY=59V~^u~kdk+r1YuKQb|V?l$&M(PV5=C`FITT85WJj@4-(qTxuJ#8k@zeh^FnFb$0gR#TIPJCGzrp8U-QS3E%6CZrS29a-ru=mYRqHSaJ|;yI*CUFdOi6H9!rw0KjAbzhkIs8LcNEr>A3NVbSuk>=2i za6NU+i=`$TORUdEnfhlF8JNrWsxlL#2BqKyRtx|8bH-}ok>TJ$*me#CBB}+8Ncx(4% zBG)DW)%e}RYpZJ$%~L|}ui`gugL^2DXlxw(L?K?IcLCm^tNE7X0-;4WbC~pCWr?+4 zH}h1Z^ubE-+#T#^1Cn}}-@{%=h_$k(xs5HWXz2VS;;F;W1&6Cnz0A`>*CI$dUa(~q z#Im}&qQv@sFLMkMUV(&rBd^7PZuT}mFiQS_ZuT+9)Nq3^%+-(|Bsr_c2jCgI_ch-( zN*@7^>t}9H8Rt=fW#ajo0OT33>xYc*ec+gJAj>%6gA!|8e`Fk0vK*f+R5Ro+a&pVR zP|a|wDZCBM|6h~>pP&kKeR+v>VG8N<0%9&4fM>S=Ix@frf-$Lw#d zJKOxZv-Dy%oXUK2nbab?#Cm#x`5R~H{(QK(Mdm^&cYcZWt;Oa8&MxoHqwn!z-Z%TJ zPcJinD-E4jVr}t0U1>CzuH0IMEAFez7o{t6P^7EON1de|v*C$9LNZfk!wIcJWGU$# zeD1XwP%Q{aTVQrO-bA^6Y;G?dejD!Y{kTYJ@7rh~J~kVT(iA|Om&Zl=j)(A>XYd?t zdzO8;X= ztpTE??J#$fzDHoq4w&M(nI(bfdAa*>3f}%4nS6zuiGq>3yQkxZ!>Dzfg1Z!LgNW8k z7cB$PHrb**XGOHRB3d(Dv>u2y-xlo*qJ_RBqWS2eH9@qO5v|Ei^U%-%B0|aH3XVJx zVGts$+-V*Z+Ezq3ql@t88zne+2z7p!xs7uaJ?rorskPM+yUa^{OL6mX_xQ3Uh(82A zx@-yJePNFF{f#b!#FxE=3mtLcDlQ~_fsV&1T$ucYxs!Al!tO870on=SFA_FEXtLWJ z6ZHWEO0_f7B4E=>*v}AXu@Z@_!0!Y6rtdb7q*|FBIT1(u6&Z0Fs#E@Y*doJ5YF}d~!9>1vYKnFzQqx|NPS7w)Ef;ls zjX`-C*!27O#G_!3xwfmnm{XGWnm>>{@FZ*Y!dU)>`q%cF+f&tN^D?x31sB=&6vT?pOJQQxTAT@AU|w*D>cHC#gQ3{X<<&K;$QX zYkS#$2V`5FE-Yd$WV5O~*T1b=ypOvPyNM|}`DH`aQ+JuhI`_hteGjRG*TEF9c)H~8 z%(1Ea+hf8D?`0kDH`2~ZcrRNC$NiVF8q5)=SzwXw)*s9bd|!dy!5FeIOIqS55BXWo#Ibeh1C|ZbfJ?BMgRJ>Z-J`0QHT7=EmHv z*20FO_$sneR5E6z_bZNOE7mZwE7%mZG1q{xWi>g*~a7j`vk1`0eEb~PS?>sRJz zn_bbTrTih;r=?t+_7%(~3sKoyyHJLi-KRe~2dndr znmeckhs|ysBGKoI>}a&P402SgF!nUHxr{;$)47bFfx%_?tL=`UFf_lBcEpT*b;t{4 zR``w2wcC-T<~KgkFrDAn0*v{MyOgBnH$uNg`E~~xyT3;HwuT^mW5#wryd>GSH==xL z+Z!(aTfgyeDWf6{|*EtV+yux|d;lc(fJ?1<<5oXtF8aKZf z{4?kA3|)Zpa8)XtMaBc~Cmdx$_`VI1ds#+nmSCNU6ekJdcpQ^LQGFz4I6b zgq(+Sop*Hx+oOY#-Va@GZnM=Ua54;Q*TQD24Kz$=tC7IGj`8L#hnlw@$I!g7J9W*Q zLAw*FX=Zv4HHpR3ndxm{3u1Z%sQJgtp=72x^hFBHG+9kJZtf>#gQbPXVXM<1oIB2K zl_(Lm%GlwyN}{k;5=9$FqG;nt+*&ujh5I$`XkSK>5!?HOxjYXcl`k9;X8bgeWIIb8 z2E^V{Q-Nrf+8Z*r)YMUJ;Nbc(hh=9hx)#qKXCFGT7S9g1H`Z8H{(;v3yGZ}7#on9B zEp_S?{y!Q2%wlus0xULVL50PR#>L0C*gZ(8!eX~0WN)!sfY@8?S|DVx((@SdCH-jb z)Gu`^W-a@Dx$(hdIpyd_PGlou*kU63Djm#=2er0 zPn*~$W0_C|UpIwRLqj@|(3u~y(*q?;%E#1d#L+RrZMh1L#;Z03fAfe1EW^o6W4tp zQ>%XtQw$dh%yrd`;Ia~pf1%nl%KBq3X+h%+4b#zhg-f{t|O0dPF@01A@VNHtsw9IBt{-7A&iWvrX$aS zy99Z3iIJBKOe3#5WFpU7kk{SQ7`@Wdcy}efzyV#^`fA&V(}iwR8ykgD8m6N#9N6)$ zu*8`2+!ERPnE#x|t1tiCTLw|p+bU57ZtI}%Os55V#wgJ>&pUY&<%n2y8&z^0d)15{Jt|BJ*3D58-V zNU|W&i)11(=6^xrW)Mas_L);*l+R53cSiXQ?s6n?Com#$7;1D5WFql(%mY@@me}$6 z9%?`1^KJ#7i!@Bf=K^4C7mG2MbbM;Fa8x&hdt^0;&%%+&+7cNGv9@F&1lE@HfuOY| zM<<9`xc$HKcHgct>lze0T-Tu3;i5sIyjg=%7dcUbvKF~8gSV^etU+-_6yBgXl}}_} z(W*cHX7;OOdzVnz8CS(^ZMJto!*pEz1Pne9AIkpz_*|_=@iVSgLSS5}5HzlW1XroM zT2x(!|697oATy%t=4+3nD-}^h``a7h&1RMcPde1nmKrPB?QBdn(J&oT4S+FM=X3S( znfeP{Fs80SU`!Q3(3l#52cWrKFBieol@K<)tCsK1sQPmi%IFc%l{h(q>c==)TEWRd4byS57Z|#;*slc-Odn96zG7DwoV<((f|KVVR%tZ-wC7(`!3lXIM^3r{Lq)1En&Y#v z@zSMIbG?6MIeg=#z9U?vnot03f0*O~VQia}Fs}zt`;f4gY2&%QsP}K1-CY0M+H?Xb z6ETC3YL&*a6A=V4IS{Kf7IHm|1lo687>lA|I%Am&j5Sh|?mm{W3`NGwSW+M`W9bD! zGnQ{(7KD6X_TLebe8=3-2MH4&tC47xd^jTl=fmm#c;0Z=_OrM-?;MY}D|ugK)KB|nW(KY4#z4>!UyV(LXcAfAYQzJ);fX*hPd&hh zuoeXBKYli|qW^ew9AoQI8s2z-S>J}Zk9v#M&|9R$#wvU)7zmk;$u7i8yRi>3+2u&x zZPWrrT~pe@p1Y!3HmqXm;X1Gdo$zf<*~7=BZYN4xqb`SJLEQ$(psr2a*U>gV^#7+Y z;pLLW$1O48t&u7*crvSk!J9Ardj@;qK8-=7Wn-{CWMWX_47Q2uUs{e0mh25MNMr2# z3Ko4eOlN?ez}TF`I42A11^nj*_!F!^WAO))1&iN8eqXZucLwO5fmDWv$Co*0spbdf z#^Hl03>NRaQNg0mf575s+^4ZfX=-+u2ANo_k5@Mq7fWS3d=fRE*`bU*|Aig4(J&o@ zErBsFcg5v#8N3huH3mya77Sj8%XCbwHt}w)j5QxHH9fhsN{(D25hx;@N zDKVmu27yx{6NU7C+i?)+XphgJ+A}uYaH@e|GhM@UY|6k`2cvy;9hivkzqQ&@rtZt|WMsoB`#3!i6z=|VtDj3__1-c6LHw?Bqbu*oo2DY3cnBu=6HzB6i#=vE%7!Y3q!uf}ISARkG7dW1_f% zovs?DV<*Agdf43NyL`u}U-g1+|aS(;CMS2zt%{ zbEM}4Fh0{6_*nF;LdJ}qr4SfB*$^~(d^CD;g8l(|oGoUI(p4CVA>Kf*)X;W`g( zhYJs#t$FBAkrUC=n$tr#n`$D#91Jgn>w=#J5H)_X^)1+|a1P8=c2@B7636l)b+v0W zIgxnu)F0I5{A7z3tP3>=hgs7pS}&G8t*UH?Oc^&VAuw(lLD0C_I7)ESKl~ry<{>yC zZZeSzYL*>0%n=nKf*|J{#45=-fa=M}nTU=5h4D~x2+WQga%yY@cr@ZaCTAuxW#mkO zz{q(8f<{j1bLg(s;qKYa2DFJ=_Ds4rg#W3{^hPGc%lF8@k(Y3 zQ={c>1ufJLI?^H$Ei}6OpzeQ6OCHLL(egC}M$3K(8Z8OXn$@S`sDHp_mLMnMCa4N- zjzywA;kw{vJVds&L7n;*?;acAeO?=EjDBUBQ#44ht6(X(#%w5)4vOFos1L{NY^Vn? z=78qa*OA3$5y*HeS21l4!56A%1CSadV*oj%^5HXH4l8vk7)M zGcrD#V26{D(RRg-#;0>k$qg+HYMlUqv=VvHvz3jk^Nk+O)tAmDxq0qHtP>b|2s6CV z&=M=H2R8N$R!rgnRzlvY&gd%ps&XTXH+2l`n4JY@!kFEIgER!QnH;lYb~1S%a$S2H z>6pcEp@?@o2$~u0dIk%Jij93EQzEJ+_P?#Ap2&cr5}tr+Z0g!@P8CZ| z=eRVg9C6K|IpSn%LM1j#8G_7+s-H$8Q?3@<&4r81)ptS^!B!iH%%?fB6{@in8HlPBM6!V|E5*0u~YTm=rZeu8g9(5Ew-v5HyP3 zA0a5}_zzK33~Gp?myyvUtmq`72#StEtdgS7P;VJUcPl8`$}u~NHUhiZ>M<#L4Y@Lk zUWC9XdIo|<(eD|8qPJ`RGgj0QnGr=_BBMu86p1K;qF{(sQdEu_$SA5)!&cG$=9nEt zrNH*ZJ|;y6QGAS|FCZ|AK82uB)Jmi1$IyR}X5xzQ48?gL{%!r@C z$OtCHaN5$8i_BN=LKI;_pFq?o%F~ZoRCorMP)_6!?DZ~Mws$#}t#8@p0kd@E6tO9B z;j1ZM=Br5%%^4GE&@v3UGKx|mFp7FZ&?x#YT~PEwh|PrT9$D9%+2Ok8%no;?s17nC ziata}kD$l}Q3OQ~KxCB^6`}euisXvT+Rt;$j-s=`F!jc)=s%`t9dcz9t$@HNS^`0% zC{UwlXYfBm(F@3oD7rEHkrbsMilC?$#40Ijp;1&^K~du>D5?*vJmE1Z`V%BDimpOn z6kUX%QIrAAS&Q%d4^gxenGr=#KANHr5Jgb57-E$aO@^0XR&=>yykux$Qirz#a?FmRy}(xXcub0BBUeVz8xR;puS3u%x@Q&?Ef4%>DC&>Qh@u~m(IY5ogD8Tc zW)Q2S$XBE2CG6TMDDtd=qUyjf0)9LzI)&n66di-WC^`&5qo{|V$m?=|jiMZSZL}?L zM1T|iSB8uT@Yjt-ggegBTCC+rj3@}_6fm5(SR}F*YX+hS3MN6+D9F*bSQa=TSV?wd z>smGnh5aC^+aO?ZeK`d=y3qw?##$^AM2p2lYO(4fS4Key1V%wE2pR(zut;eu|R!E5m*nw0YK|m0q zZ~~mX&Frm)>wd{{>L@5%nQG}a`b0l`RPmuv8IC<^-0oj+YgFCP)*XdZ;AUuD0J})X zT0cX9AC9UDQ0f7v4QaMl!={ai2F3VyX6i*uro4gdOM%nGN)wP&>SEZw!70A|Wfw#1 z5~Oh(Cyy<9#$W9>z%ovH8UXnblX5nnCorabL#0J z^~69+j5G()TnAYO@ky4Kup4YHW(?L~+gwCv#kL(-7O)J1(pAHL#Ga>#z@iLF9I$;0 z`v#~V55g?MNfZ}-wsd@u<){~K&xyQ5$36RP8U~^^54O~=Q%q0aA-*ia5O{5s!7wl$ zd%U&Zj!@|%pd{n8kz02uqP;4FeJ??v#f2|~tuYmB)dV^@QUc}i0 zWHu(7jQBd5mhd%Fef+ybrT*dzzksiLgiY91b*9sL8ruDsG|>5n8T7#g?SAZl>-+{z z5f4#Y)=2bdt{_jxXI!3E@r-0t9tc-9s$)Yeu`XkA`}gdz*m^`f#Irye4z-L5{Sh>h zEtH-!Y<%Ml^IiJPgZ4Q(g$SF6T7uiP0=?DnsI~C>8oIjS8Qjth3Xc0Iqt8C|w0G51 zT4UI#u6kieZ8d0^#oI4d2a~4jhGEhx{`GeLYRWK6lB7U|mBTFlNiAUH5zdBB449bN z_j;Y3WDOLbj#YaJ_t>dnimy-uv_}{MY^85Re&xd~ZG8X2O>Q$XQ*TEZH&Q|w2=_>{ zw2|r~r|D@hQsy(fLv3F=ZH6ukTLlaTN+0j6(=akps6^XCtOn*K!?$3TE1Q;v_K+>} zn#3XF3)sMD4Ym}a-F-SBO!>CQKkc#V6qA`sw(CO*%9b#4M%mmM(c5t0jtSX%u|^9I zY+Fv>)AU4azT3No!~@wtJHiKJlazJ{tfg;&qg79{1*b<)nmR)}Al}|P;)PtVM3wn<1q5OY7{)Otofm3W8P0)&FTW^77-RT5Ct^kR!SW*&mU{$Sg zE`%fP2T>lV+&FWqV)y91z*syT?K^>icI*Oa;l6=RK~b++EN7(%MH$l#3ym5W+lcLeJ&>}ynIhk=+h zXJG34xF93-hETTRdwqg`PvN0ovJvzDoWRG42OLIIt=csW>^*)c+yhV(i-XSu=^dIbuJeIK6EGN;Fr_>noO z8b%7`qVldWD1AwxQM$)dM_Jlvg}?PTtaN8p@UQALpTO$DRqQpu#pc)9ECZpPi;^@n zTp7^9;{x^(f|^E@*KK~5_<4?$JyoLq$qtHj7sxFj<qd$+T&GM(D6aoFO}0_?%R$^pqL8d z18@^BTr#5Ng#LqcRd$ zxh^$p+i{izqm&HOpZv0Al++5s?=Pc)6HmD5iN4{Q?0GE7CLg>1WVrg$cuQ@r3DsrP zPufFcFH+E+OKXUCY8Yt}#T(+!fbDCN9-#g*9xcLWcsOz{<>M_Qwft~2v@O4_t+0zR zFS{@0zRhcTpgyk7Fy_C8;{Agk-24kiUIcQ5osZ=&kY|AWT2U3*PT)K#wi7rPr@e|- zkBNx6ZDRj0mktmv@FSo9con7E3gL4sQMKl42sc4^D*F^(ZARfJgeUPG9%#c7C>9Fj zRrS_t)Y+-8J)+KT$QpFl(YO=X9x#I|;qj=GqD;1~jqj2g?15e@I?s;xAHe;W6RW`4 zDW8>bwv9Na;JnnoySilp-l{t$N=mW4$tj}F@uX9tcuDLSpL!xf+3>dg8-%PM$UQ*x z0RG<)|KhsMG2$#_t%SqZ_Gv{Yh|j=nQ!8rQjR@?-EedWTI>*oA^4pAbf7-kNH&}oS zsYBhTucNZ=fS%ODQD3)=(d^mwsAvPI*GPR6b?Tz7t}e&G$6@Y;=(D3W zhWx`o4sthQI+Nt;^(Dezirz_Fsu<1}xbqneP?<*^l$E`C2gR#fC-I83wG!_DcIPQGO+Vp!mwnR*BP#ROy(muVU0%buV>Y)0oA@x%&b zvpdtWODac<2{SCSq)xcCe1^q;I;W|zB4K#O_!>nL?5WFzW;`$4cDe? z189IvTJe~}jfU1ttKl5$32eVXU{g4jNby_@Z3;3%mBzQrdBHEmwJd)WmA`Th56_%>AzzMS~(Y5;E5uH)|!=L2a7tg4xemcw2UHSnL?#;4% z&;!q%7rCf~@}YqbKf8eOI!=bxPd^b~ma!y$7hOjuJCAj+TVr3ug`vt>#34MFD$|x0 zO2&`D>V-EgZCd;Y@FaeCro7Ymok4`N_+NCsrLyB{uySfyjB;md3nl1uu+ly>MooOn zk`fUCy;s2&v>Yi18r5IIDW$8B(`Rp4W=PW^w0+w$s4cR{d2++XKPekzQA}CzQG(%# zMHd?@U(}oPCuMafz>Q^d8z+!1PjXjt--eUvid3TBu|!MnAre}}4G>z6f!e!C)SVI}M)GnL; z1%6J|+E4$KI|8ObyT*zkCcf+^SXzg&3P4_TLWt(7 z$`CG&_Hk10%(e8D*5i?T%(FCex)rXzHqSDcT8-?;p!!NdR3NHzpwdiZl$=9R031eu z(n!OI=wmOHVL^|*$nnr6Brepoo2lLU@yO~^~7OM$0 zd-|zi3lRPt;p=KTg*zcET|l_U0!yz3M^Of>%D3mdS8pF*7JaRp{KgZ3_t_Yts+=A! zK-Xps5_wh4KitDl?VF8E-bZ+xT1c6ULD+L4!ej2)(g^3hV@mGDFS@f%Gs&Gh;Gi4+ zJX&9xV9}Q*@u4oZ7?Tk^tPozy zhByIvhQ;xp%j5jrw?uvV(LDYiZSNf)Rnh&A@8)LNG!jA*(nwiC3nigLD5-P^geIN6 zmw;lS2`CBzF&2=P`+#1R7KjCcKoBt^N-}%(~@64IGGiT16bEc8Najz^aut*G88i{RPluW@l=?CDI;y2NO;QEd~rZckO|U)VER`{a!pKJ0W5GJMuO zLvtPA^WAY%eZ3%Bf@bgF{}bA!X>~@?-g2T3?((5Be1%t=wHkOLjdhcM@iK4OV zu6Vl(BbTA^0~7slYc8c7hqSesp%L;2M;-yvteV=x%q|I9`QJS}trWcnUT%BK9%bo< zfUialst{2X?Sb^JPKPDEi6MV-k`3{ywc*v<5NJWbCbEMSw54y`t<8P$JREVz+vQU{>!CT=Xb^}4CYjW=z~F@l(ORvBixXoj zb8#MAs>J&&fGLJH$|HG5-a86JcW1)_Gc0d#OKmF3vtCmw$A#4@FqJ)qr>ef)BI+V+ zM_8YNE$<_2wj2+K&6Yn7CnsBS&Ql^lmozA>ufJDR%aiqGt}9Ub#TT0 zoBCqD&bwrGo644<*^V(*(jGLMV70u0=Tde_ZoNt#V;+!0f;Xyqi+am9|JU`#)(Q^= zajLiDAnaUkY#KWWuf;TWYXqy-bF(zhb^>)$0-h-_ss4IBohJu9uxyj+ZLFsZU~wkZ z6Ij47xt{jc26(uN!Af*v=I#yl_Ey-@d0w_??e+%yw~~xTDJifI`ggTA?)Coc2F=$H zZ!td=S6n~(B9K@4MObv5T7{|Xc_6u>?(X%%0E6p<2d_4v?tGc3C!TZ6aI%GJnBjEg zHMUTV4-HQ74Lry$!pcHsRF^*>Bj>tgmteKWYyA?emIw#DXK&B7wRhqil^KA3&6w^E zFj1L4z#L2`D$@dN{(Ia=Wb<~#@7Z70V$&vA;I?q>pG;fZasXGj??W^1W89_v{ad=# z@(G?lW87EoHs`h?AfJdDYb|O_YqgPk!JIz-zo;(8daocSsxB|L>SFsv@m6qNHiFBm zdN$X_Z?ZojO~%uaP4+(0C;UG&+jH+6x(_3<58~QZN_!7?UKkAf-x@e(Nj$uhAM5$<@gTUsm z>mH)b-3+m?5)Lrf^2O^m+b5cRSxL?|R{J1Mz!v-VT8p?J@9^;6x=YW0P***8d8#8g zZyv4|&CY6~&D{oWU?nzm9(G?NI*%L9)IfKf9Ig6SZ?g|@ zqi3dcz1-88X%-kqr@H1-jsZc?TXrn9al}%Tm$)mS2mh~)fAN0nC`Zj*p6ICBadwAG z9alAWkj8-kyQdM=@d(2Forf{MX+K7u;w3v6<-&Q((DiIEeEoc4ar~*E*r;Is-?y$EG@<-{J$Ii?>Dla0J(L3ymq~WNpb35#7nkNGJ=8H~? zfA+vVQVqN|vAixJe>ebX4Gwiq3hzXMZ6DbuO1=n$?zF4YpBc~&ciO|7oI(IgchoeI z$#IW}#b&|GRF2YfXC&9&-HI$r|Du}rO!U!Zj-k8YS=oAvFOeBFWiMo;<707CtN0vRZ&8RS zY`w(>1TeI=)F$n-2lJZu!~S^ez;CTe~z$DC^ZSzu5`LbOBsFw{YWmC{_# zm3>&vauS6&xZke)=h}2ET`Mq^d7?;s>6$kA?hvcxJ}B^oYxPLYLyQ|hXyF`4x`xRc3??6E) zfclZ^p$cykKvVYFB5xC47t1qEf#(iVoq_>sOMu_u;HbOz6 zjZjc%BNPp&)H2#MJ zV~f%}PW|5AKJrR8493Z+l{91@$Na}mvuP)3CDW1d-tRFs@57g69JaqD zy@i;k4%@?<{|f;c^>1Oc*GK+ml1-H>ffJeLV&o44iMS*7=`l~@#l|l>FD{0rF$dGfX}z~`CPc}luH3dBy!0jnv(>$InMlD&bFQt<1T&`nU2!3pS=p9#X0oJ$D9q{!x0uVK@xU&&n)ZWzNplrdU>Gxt*qFJ1ZcYd)oP>J4aIK13 zInQ>enbzc}eKN_QJhsB7g5OQF8(oKC_h~|w%bSmNj0_i{i*5&YuflY*s0Cc^-%?xot3CGrFJI+V^A!cB z{07*O{n0W9fUySR`AQ^KKKG))Kj?QU2)xN$bZli-g{iC~kd@@5W0!#? z;wevCf85>#_ksT#RuYz=Q_~tmloRgCN-eJaKW8N-rOE{hjqk)+Nyh(wWF;o0K1C{5 zRzj6*0?ee;dIW@&dJ94O*&6t08pIdlhB4581Rp)AV+KBY6xhA9;3KF$Y(0M4KWgBk zo_b26Cio~##|(Vb6&T~AU4L+Gijn;7kN-D(bPly=X?C#4gzC* z^uk5((X;Rml1{enA{3~{xhMGHdghk6N&3VFNfE7-s_GCMg?kCM>f7i zStcXktU*l#;;cc91>&qh4Flq=L1hA2{x>uzRz{fXJh|c|p2T<3NT+38 z2CuqC(uX-$Tp#9KaT?|XQ6`%n3SL^!p7Yc^{EPSgn;aE(_{+|^BaF$WpOK1qO2lNt z9AwkifEiEiML_UWF@pLS$Ctf}F>V=z7B~YKma7S#TBKtJo_Yyb?p5&AGiY<;7*}dD zjByk6ltfMNlwHRRJT(d!Wnh8E~DB&!nfsbyZ_v+Mi zKKe(;41DxAuv12AObPFP8%ntN_Ww)S#FX$=s6wL>z5>s>622H=XC*urh_ezt2Z&J# zpMhtggvVCazyi7w&WdgjS-KMLio1xW!P74C5zjT=e<7Wi65bHyCf0hd4gY@!|Dt+p zmQG9wf7sTYwF*pSe*x&)FNMbPQY=0VXISmAt&5 z7F9rM|CY#29hFq+03*V7~XkW;5W&q>U^Y_qi%n#Ke_kf#1?o zeNj(I)Jm{rufS7%LC1(%F5m7q8`usbwTt)dgJ^gzvYp4t`PmZ6A*qA(lte8Km?WwF zb&PcZm=Gl%YA;~VJ}{JR+XH(Vr#1pN-C<&wb_O-nQxdgYVA*ChM#oqe02XIfBY-u3 zXrPw;(EhmRn<$%B`p|Ck$PFpJ{?NY0BXS|En??9}{T`ym{}Q6wwqu__fmNM?*4=ED zZNtr|`SWm$namBMO|kLOIT)nyjaMm>Egx&cC9h_6AOs@eIBR-n%iwRmT=aC+4r|i+ zi{@SRfH~q8g{Y>ejRPu?&J*$DJmg_gI(TM|hpbY+EQO-5EVWCt9>y9;eRg2kpJ@(w zYoqFLvdUIKQp)J}**qx)*M2)jPng`eI&ySB-1WMbOk;D|8?9+-`P%4C!8)=G$W1M0 zOwZtuJv`1UK(0Mt<0w(Z!b?XP9&U7G_Rv%AV97?*tJ?mIE?5X^k*$`|c)p|sZcf8O zP6w zwO@oE!f^=K!^+61nt4rEn>MbN>_du3snL$#PYd6UFzv<(KTV76esaglu^>*g$mQRA zw$aYkk{h}aO`{cjtK1XYXaQt_J6?{Bf_gKb?Adl$uB6^S2hoJBimv6gQMn#-$IZ0m zajH8mL>_DW@8k?E%1icjD{l_=Q=V_@o>-wd$}aA>(8h@9)>A#PQQKVhS}QK<{1W-U z5B~K}+Q*bxiha2LKnJJnImj0G5{xB^9sEaw!a%N^5jN#52dn!3YrM|2{v$GDv~RuT zQ2$Pd-ncsYWstBm0hYnNiP(lp+#CaBEO-6TzBVACK;~3CnSlfVX~aE_=Xo3}kQ5e& z-GYudRrs8*edHce6kY}R%Hd7sf{|9w?@_5i7liQ0dka50zTz%^w;v7WyAY0qY6E@c z5bC!@_$Iv%Q&{w228%vSVYbd$M2}A6U7m0(bf!9>px)gW%)1)}x4tnf(GLtpvp5S- z+-chS3*NzgXj(#M19?iD{#I89G7ZQi?X*X)U_bB_#hC;oR}1t;UtJS7&}xzKJfFqT zKBwmqc%H+lV)-Yf$O7^Xrz()%K=N4}A9MnWlM1Ayw%lIwKzF=XTMlmvxmTK>&3BR7 z&IYNG5Ow(lcrNiMJB>{$q4ZpVXGy|ySYZ&Jd-=Q0}0k zjRadrT zyiJZy^0NcE24pc?_hPw#;CjyH)H(3-G!Q#SE_37;AX9ng5CqDAysS;1F*3+=Aj+!6 z{@p)V`yfb`v!~+|_~96Kc6hq{2sRDuG5V;49{iQaqdX5P* z8}eaTDKOD&^*QD=VMd*Q{@DKYw9I-kGtFtbq_X*6dcz5o zjVgQDL1tT0&_4_UXC2Zk-D z88laY#>y4fXRKWDd~O$0f!I=liO7s9^;|OtUnQu?y5wL-H}pjmwv-?p0sGlOZMDnc za$l}arA9lpch^O;uqwR~>e$|0n`5j>^$zL=WkJ-y9*g)T{1fgxq0ZB=Vuj zaGavjj@IZ+#!$s5cZI^34TUkoQ#}r50#;;0Zsl>nBu}*rm_igu90#H)Yt-xns20>3oP5Bt^(GizJap6 zzMLd|O1w~C{zJNo3eAm@TT2xP6i3OEc}7d{3D8i_6nLni#*A{gV5)1(C<9m=_5lF1 zM;kKIqUBvNbK`MfOi8=NvoVhvCWSAqs%4tK8PXiXOdf_AZEB1hPPIzkDHxK1f*~nL z3tap#U{lZDfCO@6pw+YEwH|t`CnO#*_z|&vFgUQ z#NjzWyB0Z!y^X}vJidfH>Nu8^2jRJ)rmVp16d2hTPiY$MjM2u@TM5sycDimBt`%%1 zx9Y+qFwOB5aKBYKdN9Lq$-F-A_nVGEIONAcam(;1I}WT%bBMWN@LSR9vKh_g_CyUU zmvFDT5QZP~lu#OA$V*&X+pc3I_e;2O{{gVXM!iF{JI&?#4w8{AB#%dEOF6ApA3UIqE|)oc@eeJ-s6h!`dw~uA z6x?&hu_Srk501Fxq1Rq`ZmiW34Q9(E%^-{prmBahK3uQD_M`Pc{DJh~O_nKRfpRT8 z+qt1aXF(vw!^T)w%VMz8A%NThLVJ!x8Ml@?N|SJhjqy}4IJFaf=*$QtIEn;SY8IOW zKZx*SECa12WmtmeY>l1o@p~d{LPpe}iO`umG{NnLv-3Shy5V%bhh8u`-(&yp&~RWo zx~A99_i)3>*6imVpA1+*_avR~;n!OBaxW|yuvqBhN|c?zgM~h>I2o{l=(yH$uco8uI@m_!sXDwY>I(qs_6HHbJ|3cc7PlJd)BGA0qnUqazd9G%%_^46jsedu)1G zAfD>rXYdS{MgxW*{`TTYUYQ^p3ZoF(u=t69+-ev14iJDOF z#_1SQtKjP0NMMQW4b&cMFDFHgLP1Bt)Se09aZ55aI}a240)8t!>S?>%%WqjCQ9J#( z;X1hk2D>0UKidIho%(@~z}If>}Y*357%vy*I%wc`=C&vdW3Sw}CV znA*heUl&1kj~6l@K~Ym{XGYa)Vw&9ozyJVpFViQqy1pO6?{|`uYIBy-P0he0Ip~cf z*;CKhCrR!g$zarsBzYLGak?~F=yRP#(djdEeXhNZQH={}*$UXvB>4}W>YmQf(r(A` zZtz?Ky&JqfV5}|#PkQ&EU@2tHyoW>e;KNza(NJK5_k{L#gs1r63?zY%^Q{gi6vF)| z@G0i8i9Y07#Bj6*Sr6LGmdeH+Y;ccqS8o)Zu%+$?1qxV}STE1u#S)LxFg~d8mKWH8yC|=iwM1 zN71p})DhluxJN?mC1RaoQzW->i7zy=SRf%>!i!b2VL&dj4Gh|rSd1BU@O+LR+O%cf zBi0ZvJXfFyv}~HB(?T0NvTaZ&+fb|8^jFB&b4;{3IWG5;@9~N|z8>=Y{B3t!h8iQj z5$9t?Xx&qw&oRI_7z83Q^exwf)GAh?IVK*G=2L zMhUG;kDhoORULItXlA0H@Vi_`%TD70J;hP+6xEHS{*cMCOwf@@Q=*y_R; zP!3!lA7z<^z-}$)y?&7alMyV&hY(+0j^Q2+t!ocHE;})!?#^&+Pu-p2ijzA-v?1G| znSq>$^S?wcdfPr^st%QrZPILtDEcPNScC(*W;N3$_moq3mC*p14e1RDeiPk^Raqxo zq#FlJ@=&kp7#oD3YeL_=NZqg}Mi0HVVtVlbl23(|Kz)SpJgBE6YPrC&P3l)VM$|HZ z#hKLoz?S!_rdIrQFZi_d$`^VjeND}rYT!ztXHs0YVxP|aEHRgLiq%g7^%F=dAOrY{ zebP1&rzw!W)%*n{7D)ApjT9#g2u^H_@Itr_!s5WjO?|m?=-jSiO^9pz(ZnllUUJ2S z630HXuRMU{OObIFMxStX#r5SNuDHvPRzJMg(@xRF;o3$tXK@w|kabuIB6P=M!!qR%#r!q7_l zs=xdZV+b}hxmK^f6~`54-8RxazUa18rg^>-8rOXenNeHZtM6!o!@S#46l}$5TMI=V zhgj5eEeJmn%{SyM7$nQq-Y}oNTKCk>4U#i?FYaV=_$7nT$5}640IYyd8u)XJ)u`^5 z^aeI{FlrQPF7r#iKUk+0i(5wFUp!MGsTE*!omzPbl+Xf6J;^cNKDofMCG{6zi9-z3 z9vdQ$;1cFNU<3PRhG=z$!kX0!*mfwy%vWd|Iyrrv@c%*g zEh61_7Ucgk_&p1byN5H4R?kaaQHj&1cGi{D<1d=j+sDJTf}wJsxW_?T=QKLmYa%@h zSwu4%3ZAj4f3jdMW9Klk){OLa*wD}lrNOcMkq9y5 zH4pCvgHNNuX`9F=k(j+{U{>?}O_d66`93enAA02kFZOsKuh@=vdp%6M^cG(Hh#YQZ zTsAoaXR6CD=%q>+4mI>Qun)1(Sft`zLAT3^jfA{p9L4Q&3JQ5iK_M?$g#FzU{eI!2 z@@i21hAV$Rb7Uou1Kj&3kR?F&F+^*56;6?t@VtPh!LdO!n9l{m4-yIy$V?!!xxz?U z3LS*y&h17DKKz53kQ7Xg9h>O)Bd69IY2Rm>pWiW#qyi~mx?zYwIssW%P5<&pn(zeH zmG$yEIJ<<(6$7LdTBo0;ek(T|Rw0$89YrUf;ofP@q!7-j0Vh9Lt~*XXI?)PH>LaxB zQCv}U6687X0+8d+RdVD&u_MPH@I0g7m-&F7hx#B#T^%}cSXXz4M!-ngcd$q7;F~|- z6R?NYHT7vKYA<)(Ob74sVaO>ra@jE&P~tCoM`&4L{ey|)D0|Uf6cmF51x0(YAe}4| zo7Bh4@&fqr8Lr8Tqc~>)SyAmo^Ph}onGY+J^zvVW6GMcmHwLd}R=;9eprFzZuk!e~ zO`BoRni)V|)Yez^4AKsbmHi^y!xG-vrf2029Pxe~$E3;VUvy^vLbUqzv2t1>>sXUB zD!t69m2@&6`#3x|HJd6YAptI1sN85W?G*8}>~V7Ye@k`5|Agu$Q0zmL4OHXo+#=1h zUBZcR4cW z995?n&nYNG76sWI8ZUuo*c}>kDL{8<%tS!HL*r%`WSA_+lm6kv7zRDn2{-7ePPiEG zC|hS&M~!NFF#1su8+sW4XehXQP5(&QDxrh4`?Wch0z)5UeIE_ z)bD{gsB07iH_5H)qS4(u-iSd)aanC;KxBiccl zeIiQ4fHz|_ZK52{zwZRz!oPI}KCM>9?<)WXpH_3@_hkdiu&9lJ-6LukjPo!UYi%Eu zTgIeQ+nG`*FLtcv=r5|YGXbVjYPIwOwYB+=>REc>%-sy=8*qHxLR~vrO6VZhfH_*K zgzF%efK@z-EXN>A%>NZfJ|@rd7|uSYKe@_zp3C=FY4C^@cEHUBjBIy0PZXw2u7}#* zm{m46fm#`}5(-LlVCNo3RwI#B6230x33)89s~eyuL1n2hsb(X!67L_?F zux#idz>1#$HMsrR{)sD3$nRP`0!(@7lR9dvo&=xk4?jIAC)JAQo^_w$Nzr;Z!4Mwz zl-wY6C|a8OK{@)t7c>_+-n1+Iqd-l23LS-5M1P6u$t!;pFM}Is7wKg)!%MVHUilMv zS;wrUOvcL)!%LQO3SPEopskpUbv_S6abWgjIZ7{7@+n_O0bdL1r8~p6RtFP&;q?-q zvuuj&2uB1vVkZYQ2M7g8NPdMd{9-|F4a!uU$L$y1@hAH{PpUn#c~&;AGTTnBzI zkv`#0M+Ytc5Jwhl?MdF9j-HVwuha+A@fCXI7;7$Wn%pg7jNv8KT3w92f_U<0-5tb} zCysW6w^nw9i>naFq~UPdr%|9m+G#a4)SDikz+)z#yWGShj0e((&u?z!$S5E)G}~B( zCmD>#sXW3K9-%LgC%LcgJC39S$>OTlw;bsVq(4{J1kwgbZyskKkJAi@CyyhL20%ZonU#jUe9`2RZm zzX!$%L6`d+$DZn?XgW|AB<$Ez0kgFaBFy~iB8*ER66!6%fltJ}XM?d$x4OqNpSwmMqV%62{nyp$FFy+r^gb{+5x(hxqhM!4>e!+=bE4wC|z2rPe2Zl5w6lK#5n34>EAyd`-Q-j>XTWHwi3nAEVU zhU(3M=1rZY)XL|*O&_J<-;DFFVKz4-rQ;g5h>sG#7UxoGkk;LOpQ?NOg# zt@aBTb)Lj?n%4TW)L^Y8p4(*Oxf{mb-O`9VI7gYyL!6c(3+u(2R#MSP+u_TixCy?l%R5=0K)B-hSMKTGO`n)Dd@!Bjs6|EhvRVp| zSnb(hd3M9NhuMS zogiy%I*>Qe0dxcQS{=Ara^#jIUP_H(S`kO0x#Br=F%}nGPVs4uMtm8wTk~_|V7&?q zWgCz(sDq_B3UQ2Iyzu>}-Kdkhs@YP825pm7*)-AQoRV|O?vcnb|9nbhmR zV2_1pCtifJsvSOsCXJar_8)5-_E<*`Gzl}uiYY+m*fs=obF3BWhpmPz`vwBu%EYSE zck5=EYdz^^nJZ3anJ5!8%U(ui#GF=SBydA@vGX#YKooIm;dlheF!RriE7Mt@Ftz)5dqadtZ=rr|7AH;3w}io<`F+h)DmBjdqn<31;{p4(j5us zp}n3*m?gfHs4ag*?k4R=gd?xWNxbKWVH03>UG+>xUG*gOLy`uiw9OEhR9F3lW4v`L z0%5}hs>gt3yo#Q$H_V(@<@TX@_~3mc&9ZTifK(sSD5!8b7~$(zVdgQiWagFBff`>& zeczZ>F0kx6>IP$08NlM|sB3`5EJRjq!2`5lX81z6eRD?bO>DVA7UKiBnRh;vPj%C$ zZmN|USXeJLFnwB#R=iM7;uQpw?Dj&~M=Uj&WN`r~Xn;DxSe6QZe4@WP#8{RBV7dP4 z0AQmRRhOlB#Uj}vaUTDS_W$_eGkn$O@y*Dhl+|JeusC0J7RU0K{FH!I_^8u>9bLlZ zXA$IQvF}oOsX6jjRAa@|^hzS(;b|IV%fsfSTtBru@J8{DW%3&He0*VP`EWGqM!XT+ zaI&~cV|Xa=L)G}tz@a!*;!wbytWan1t^yW(iMKireBdZ(0kB+e^*N65f@TBD@K$FM zLrFe3SwE`HnF??1NS@q?+Jns*+{@#PRBEda6EOoef1H;(#7J2JR$)~K7%7*)h%d0J zBt569yha(d_f@%)giH~n-pSO_Bu^D);5P;HuUVjBryWxve@I&Brj<@Mq$1jT`#X436cMOTa2TRpNpvzmtw2mPVIqMoe_b&@$6jz-sMV+YO+o>8(0P~P)!21?R9ynwBHwU z?!cldEZ*B&{Dhy#AbIr<_T9mw=dYMq25xC2YTx=l;CuxTkMY+4pu*t8VZ zZCVNoo0fvQO-o_jrls)KtD_QXA9@=q9U3heOeXWvCYVXJd}KHzlL02zo^ z((4FJMZkY40v~W)f^x=v1c`ndc;vZwRhyg4>p3zLh&LnXCy=LrSonIDkvz@>Ah=Vt zs&i27rvx+x&^OxlRdTT32p(xD5X@=#_YU?e<4AuXi}-Pwhd9z52=;%ZcMT4}90s*h zS0J-cR_*@%eoe=g7x=1UzW^_0Gix=^sKV^0)Ayfr$4|qGJwL-8FUPVJGzn^eTX^x> zpxYf`;jP6a0>cef?EWaw=#@@(ol~Cdg#Llsdf`Eo1}TJtAS`5nYgFi3uY!0 z_nbRU>zsLkwR!8XB-ynv`^iL<+|%XIx@li`+{BGf#(Xq=(jvcxLMkCh+|fO;nJn5A zcUcqzzyGB|i9H zKpt>A7Yo8D&TByGYs$bto3`g2`NR2f(3Y~{Q0C?%U4|T1SZOs?PCZzqO_EY~&43x% z2iDPySAx~}w_0NpRo$mC5EV5DT=BN8UA$U>ds*lb<(RT68up58pOA(cLdWqn>wH*X z(-NU)c_D87HfJTe&pNU&sEcVOoXFahcV+L6ln}ORGaDj`#DzXO!Am+8+N==>%3V?` zha>*&x1sL7Cx-`7Vvjl~%@VBehU55_?~UTo@5y7$LA~*Y%8vVdrh9$gMvdRpMmzYv z{H@g73TEAiQPOI?QQTycoaPbZfqF>yic)XErl%1yd^^*p@@NlHI;KEg-7I$-f~@k& zt*NN2RMqxQJJnQfRnzxb)h*yFr+0FD)s&BS3#{sUcxNLWK~INK+9cy$s#RTwccCB1 zeXPN7sgZ&6*ax!WoJ*$;swuUWnjTwAeX6EhOn6srQ76`v%RY;mo^Mgd;a%hwLoQEl zky|Fl!81+Yk$ou$6ueM% zl)S6xJIPa+txZ98O#b z%vsb?U5l>4uoCz;;0v*#72g8JS}zw^HZZi_N?;j9^7j8+EILhJ-x)O+S*B{Ohbxhm zz6f?@CDeCDr32Z$UGBrnlZ}~=4D5_Td1CbP!~p|iQ+Xov@>IZ1h7*Iz6XJcNIORhy zd~IG&e5}L%oh3;a>o%o%>II#*#IdQsXNH{=8mhm;ZJ4lRLEKNONB*mDyd%74N&jf= z&5z`v{>B`<8)=s>c!!3^@Opj1!qve`m~|8lhPAhPE^zhfL9Dz@sQtmm+BeeM*ZI}S0A@{Tkq%n|KCh0;-c${b;^&z1}S?G?I+8-42 zceU~EQDBCStE)7%B4_SdfcV`pn@|H0Fnd>w>X4f_|6@lGov&H#B) z8`M9%zBY2V9O{d~vxrt7Ww%Sw=IoYj^UVra;?M zIPknJPRqsbHOLL@bxFF=HZ_Uj;@Uzj@-w-SFFmjVKx+58Qcu7uFdU+2oSxRIOw-*-c7c{Yo$!7ar zEDK;+x9WtYauRN6mdc9Jkr;L!SOKsSsq90JF&|QX1u$%r-2&{?UYPzE`8H@M*MT&-atyA;DaCwx>GVki9vJcuXw;aws(=pW@T3E2Tda9e{L{r@r7z#=})IP?X3V`K$sNIb@ zWdqCbP*Z?u`wclA*)PxH)wTp%Co&-1vuHHKgruuwCwjmWls;R$X30l4DpOqRn!`y1j?)rQTL zccd@rq7@&27qTN>-aa7zLOr|`;}G*5i16CYj>9+LJD`DsVmzGYm_|5Bjs_9=@K-$? zG19R!Lcq(WJ7VLg89l~;X^xE~(QUD%LZ{I<4Rg#eQJKs(k%3Jns-Hl<05XKW8y^Dk;kP~rq!36g9tZQmM0o=c4~`t=$lE~P=BWhoFCcI5IAUAyYe4?x zn0qEVF9PYUU5gkRDLs$isf;cWet@4wI2A+QRBiwAWZO_r_4Q&%>D*KrQk;C;W-|FO z#p;TmCOdM4J5E!tqNYy%DJN_4>Vckvr-As!+^jpUMAox?xP#nq1-9PC+`(=*&BF@f z$;aSmN)5w>(tW>!73oUZMk8dLd-2$y)7%};=OZNX&f4#=0^F5e4vnms`f$Y+T2YR3 za9nYkaRpWcdN_inal|iG*O}-Z{gD5U#J_ltYxs!eC@R~LE8xSm9Dd5f-}i{IvKXnA z+5(^SC=q?xoxlkC4Jv zSY7mDv(#OTbTF+2!c@uuU@&Ff!$G<}SXhZz(ljf^^|3CtZX*y-*NKk~)1etzE2_mqR*wge85oALu$t$HKddDZ)K1-1swXgh zU0~|2?~Dl`HCG*xlRDya^S<#h)s2US@S;!ZuDCwuJ28sT4D#b(-Qc&(j3e?3Mt9nj zJDR`4!0lTq4-24(&CJUpbnRejsXU7$An}zjt|%ysD;C6kpnkL^yuwuW2)H|mbDTg1 z0BO%p%BPjUh|?1Y-C{^4^w;;V^O?3uJ0XQI)5dZ#D7^Yin=7u*w7KFm(o8Ik&(co8?oE&*#{l%*+DWRioQ{&^1*d2@#l^q+KnIN309`=obcA{M=|0pMKqep zr-AJT1~v~2R_P;ZX*=lUY`i2bk6zy7!(l181gyuf>6FzyTmkygLdzk78D>g$>=YpR z4UF{)eW$?7z~&#rI39}Xr`=J-$K>{-F-VpQgPZXUd1H#-t73XuC(Ph5%CNijo$O-` zx#>IEM;LO`cd`!w*6T;)7J=MoG2#3l<>|caq=OWor{#%NkE1$+2|t>8OYwZdPR`@9f5E^jcsLL^b1z=xH78^-cwqX?uw^j%%Mf;uDBQl z=_^kD0@ttWd#n)|dOpLw6P>1I=l$GqG4?Tf*up-z)sC7wVH!qX+QsggUmA^pq3*b0 z42Cf)z03b6;2*T|@ExKvQgF&|7|Fgy)K_@JGE8=OX`>^u*fmjG5aZG6 z7}(fI%}J4yPr$*t0aLJE*DRVW_y?wRtxPj2T$0%9->`3 zA&1SE(4lW&$xilXe6%6?wD@z3Di}f7sB*%ab-3~SfHh9tWkyG|ji|-2vB1bM^8pQE zm=)D%m`NrTazbqdd4Ua1Nf#t$n9+UmTJG=MFe5i-p$&%Fj^E`6DYLr{aXJZJtXS)o2(WW$iF+d&(R)JotCE0ELzBeh&$*^;^zSY$b4Rg#18yMiiqGE+w`&x&j$&xEZs z%~+Z^*iVv&`lPWm6|js-%<7}Sa1NVRg+k~hDsFpP_BQhmB%xLUVO3yK1C1nefn}Ri zKO@NuU~wkZ3hdc4T&U%dP}_C}+f@Z8vorKWm@S$U;Q~C?H`^Q=|2a-o!pN_(brC9o;wOAKaH*J zq9kJdF@-FZ7hJ%`=N=SrU)f{A6PuDB4utj*{U%s%I9sDvDv|H3L$*Tf3#NyjQvS6oP6M)W++ z5Sf36OI`DA{$F*=A${j9a){T5lbA_Cse}PSK^%bDHV{ph1sZe)Cd&(4b#J6DbfeWF zdQd+DGni7eM2g1MDc0`q-j;ZvKHyZYAd(9WNH7q75~j9vCeDBH!!tKPv@I>ta1kk< z4dw?@+{cF)PQe6n1IWF<(;5X-mH3u9D(*Bia|m5GkK5f{%-fa+>7+e& z5vv@%A<@0OxZ+GovsVjg2%0p{;Z}nTxQSmr#;^0uA-&_6^v)ycU2>62?>t?4U%x27 z9(g_-6kGSK48pc2DfqUX>f zp3>;3DL;Ws2QsO8UwVP5>~SD`U%DUJ#XuAwv3zH9w@=4drIC2HU&G>yK?sELGq4b? z51t-lN+UntC=JiqOiF5Wz><`N=Tq0@)_vK>8H7?Ac`~5Qx#8rIfHvoflduvMbaGr~ zy0-cs9DLv!X+I*-=}B%l+Xp$)4JQdDh+h5&?h)5?x@zc(GxrEoLsy)Hlc2{AIQsG? z7fQWu@c$n87w?nFXUE%fKtCTxdnRvA(&6Y;Slq>9z_s6&4zyYddQY;Z)S`Y$v--b` zXWCw_)2vKQ^dlPrQD@>+e|}=d@6r&fSo1jb8pIC zj=r?`rrd~g|1^uEo3=yGX54=WSOwg9l1Eu0$DF!pGhi2Q8v0V)ExDyz&m>`}Q`38< z)j&<}nI6Cv-!f1uxuy5auFz0L&pZt=>7bU4-kM=jPjJksXZ{3?-9z91Hrz2cQNyGg zPQ5K>>YZxJXK<17nqRga?kXOnBfk7@@Y>BsLl$slKp<}dS;sm;2(3#-3*-S=RoysK zzK1H$DGm725v;krA6Ca@XPedDKGbR%40bzy4A`7qH=uXHhLEzrN^PH@JH&CTA%&RDR^?^ptfEWrm~f&^7(vR=~fp`lO=eb!#fuOfm=;6c$bgu=eqU;L{yuTi7BY4y)z8F2I z*vrfc8$F!f>&L6O($kMuam5X6$Zp$-LV3xiTz8fKufe}wyIew1)>F2z5rcy4ww>G8 zuCudML`?m*oj(Dyt5QxPAg)R|jv!7|3DFiv%7|*FisMH~7D6g8HdyH8aPGa!F~$b^ zF(4!hgFKbi);nlN~zYyOzRqMmWSlvViN1mFTy6 zP3k)14UX{wqBGH+k1N2~IoW^LQX;LDs7^A&1FXu#|8cLHG8&6;Mbi(sh<&djoZzK& zkTft5?iPw5Q)M~A^O*lHggO+ESAjfVEvHVdWC|zilr+~U2*I3pgfHh;i!xe#D56aH ztvWhp8yz^CZq&(Oy73Jk#mka_Tvu?jnI`*Cj>bTi^L2k%LrX|Bki~pDl1}abQV+0PdHq>7w z_Kj|o2D#xv7pF4%*RFw{LW_H!WrEbH9BHIP%y-9yASHU2pUUhxcmmZWrc2z)LkOh?#a?_w33H0T0N7 z6M(}5l;H{WJ|JZaOmg8e9Ok^ku%dHgje^2hqu`z~*uB~6e72Y6D@1Q0&aitm%j&-e z&$N|PRpX&lRAx$M*rRxG#t!s@oMuOFJ6l->}8nt;|%T_WpOxxHcHg zI0uxwbM;(!9%leaL$fh7Gv_hD8tt#xN1*`@`#%pP{{Tk;@-a$C`KD4cex_N ztQPdf)l)i0>$PmmGat*|L>zX|WobPn*ezo-DdsWm8JlUxW)pYZ(6JwG?%z1#w@bV) zkG;tMN8?{)YUtBKQ=(Q9N;n0lZ0wWB?(IO$egHbSx8uEjtc$#Zr($kii6L?|kXdxs zb673JUWq4MfZ4owZI}{a7OalBcF`f)K+v#`)88Mif38ThQiBvM1 zSWw>U4=UL_FD){k>0zog0YfruCJttc51#r9!*Qh2nxs!2Rn*1)jQJ_N=OGry3S3yT z1Pk?^g2I}m;Jo@uvLy%YFpeF?=}ijyb9fxZXCX;O0htcu5ysp;v`P`k<3M7flqidW zfWZQgM&j8XrF0|a$uo|yO#1T?))^)|I7oyr-Pfb)UJ2~WkEPQ9YcW8qnEt5`zr@elOGcl^ku3l%}|Cj|w6Qc&x<~RvC1&1ACkWxtMu@xJkNR)73SnPpTr=1+-Y#z zM7%!(@`)g?mG4if7icQe3Ec)Ey5q%eQ+k-CgBL)l0Vq9J1Ep+}`Ul<oUhH*o%EW*fE?`hYCCw+MI*)M;aew<_MEcTD-;nfL zX+y=!_j$Z1!;9|7wW6V73u}AfdMK@dAnl+PUQ(a9d=94gvHxHv}!6*hFCtUsib@evN&>+Z1r=98>qA2dKm7xhmr`AMu{e4_B))uf zU|VYeoN-_bE$hO-aHu9%(dGQlb=3WaQ_ed)!dn}_)k~%gQg|T69=2Z6hh{i|+(oU; zKav&hO%MOz;bU$c9pSJ40y2v)<~+=iGeD-ZI3WW0706_0r=oQJcQMb)3$*pRw;uHW z%i+kZxtQd=^uvBGD#vP2+`@AuD-Os?Ae*Y~Iv`7cyvr@IUwNFDfE;5>KfMJq_fIW3 zy=!PZ8D>Z_6A^Brpv05aibwE889N0<;UoU^jd){pCr_8WM4QCbXgrOft1Vv5uahZ#s}oGZQ$>KdoaH^_KvIlVgtY2~2pR%(Uj zl3{AO(oksH1|yy;o(fHk)7HkFhpB}T&#!J7xSeF(kh9k{@p8{GW?~Uz?^!aWK?8c7 zjMvmDjIEbiRi)EQXopI!(@yb<)-$b+=zTF2O1q%FHLVK{mu#na>U}f$E_2pWX7k!X z{mw;s+H%$U`*yII=HPiCSwxZkGZ2izU?50c{s&90IJ-x`(?3BgPaEy!KN4}8RL3z; zU)CPfQ}DVISLI1j2Wxf&GL#M3+JpAUFA>iTnEs>H{$r$7YC;4%D3zU=aGO>w+$}uP5cKDpO_LHPgZF)!OdOxAOw2p2?M`fg515@r|ml*$!amO8Ugw14B zqKp;jgQ)z2R41WKMO%W$ubEC!?+%af5|9#nHC4K$f-h*)$~)D->H2C$y_s~gLtoA4 ziswTS6ZOqjGmb(|#1ALVIN0UkU5CVD$Bw5UioTk$Bf>|#vziq9cUJb8L$^Z??1jL8 zFlYb9eUkk+D3?M_EUxIHyjzQExYYJ@uw(dmh{O!5gRAdE4Oeok$T)o5IIHdX3^n{q zI%@c5;o!WNuB@RNE(K$W8m6GAVHUiLBN&95w&^sfY1=n-4fYYpdLRS+Ga~Au{@+6Q zLs7jE<)V6*bm!GeA0P%=?~8`&b;1qR>x7HyrQ)#aor;{Odas>g)l0ajUJA169f~M= z_4Y@Y7K;{d?4dOEu%;r_tJkj=|I|zAWA3t_s`Dz&NGSnx7MRo#U<_8B6Y9Z901Q<+ zgk!uqGl0dJ)B(V7401hfdLPv1QB)zFXtJUYACg%)FuARr?V}viE7-MGp?y-{`U~Yb zqm^|Y9cej(;9GoZb19}zq+jtox}VaXgj$iY2AO>u#DtdxpRR1&DfG4}v)20o8D;l~7v-wsGP-caGh~mlhQY%w&R_r!}smNRKA2U!%qZ+0% z3Kpi|I4&e8xa{|#?J)gRjL2KL*>Mv!pKU55GKHL<1@bFl8RkpXEHq1X~x{*fJvU}lg8XC_9SkyGj zzkyMI#BUA`f!VoC`{5DgdCTwM2)>Wl4~9N1a{duWC%)4etVPK8K$Z{3j0}CM?t-+< zZlG>OPh?mH?`TxPn>d!IcQoo??*OAa7qzev%EF*eKyG2K{SH-TISjs!@VsM$@|Q0USWWbR)P`C%j`Rzw)i z7%XulbsFDxf+~kklaM+Mw0%De@v?jl92ZR- z>=^7Pc603nGJ@|O{*F`I0%RyR0P?6zbY~vQLE+>vN@qRH?#~l=w6zmy8x-a8JZuf# z5{`u?(?O>@uoJ$XCK5(75#xl@=_BG>#*M?o1`8X8V0Mt^tM2L8 z#Kv-W+yp)p^w{C;es;{}xDq|hW^IO%f#6gazBJ+yH=O)ef+#zEB;T(1dG`4Qf~?3d zJxcrDuK2p;VI#GDw|fC?v|tJ|KdyPx=_4W!wkf%*tOV;VE`|$g_6mJ`^M43Y&EAr0bSB}Bfc0OEv>1rEwC3<#6w(^4e%Smn3sd)M9 z1UN8uqG7g8P`Y&-`!n}2$emLwWsJu5O`a=Fm#f;3Zq+(hNA zCi+X3w~4mDnAI@6B)o*2L#x}V*~h}Qiit`i=g4#s86sP1h@AMSvc@@bIgd<&#Fg^( zN0mWs^g5d9i}dVcN_+Q&4LhoILQTzBqdoTP51e_$!=U zMRMgy<+51*>0m3odVreLfb zPE9pMi66e-AEPu%ZEI>)`v6=JWNJsHW|-Vf?G7x}h)wIJrU1+DW@@()wgjz34#8UF zo9JHo?2d+@!j5>~ajNn{#y24JEq?RqESv}3)c73SASJ4$Vc^2Ismh3_U$3F~-LLZR zy**XAV5dg7)zP%;0xBLivA5A1AQTGRi|EX`=*$#{h*QHj)z6`1mC|O^kclU66D?&r zxb{a7sKiNzZ%GT^-Z{97TE{?~2$L{!G_t3s8U%vprYrk{oL<~9t0(dOyPsAj#(eS< zrkgwVuB09D>#C&b*Wr%5iRK`FqHAnYW+*o2)CWA&BBY)%LwP*0nruknOG719#S3a= z2%l1&sm?y6>u5p?Nf7zYRBVaVc3?ra=AJ+?Vy&ijXW(3Nv~7N4^*Hd+ zGnLi@of3V<6CJ=y+0!LaX=8N{5i^_GkMUeE*dI0Il=g$h>c@Eh+e{@qGUynL5RXV- z<404w(T4}jQr>m`@Ixjw65sdrEG5bLMZQ_}!i%71ls+jJj$=QFWZD%QWZHEX^-3*9 zEoGPLUo^w5tFr>NmJ{egS8O_O*qn*cjZY_sGY=9H!uJ{Y`mIy?Z@~*=3qe4(bhH>H;t|_Xr69^^0L5ZU((v+*XL_7oy^nM zn*jLlOM06kgqf$u!jVV`-k@i^&k+g!MbDn*=`?ds@t5iEkse*U)XSXlpe_pkp9*^# zX&jZ*&caHo?R{Pun{p4IbsxXu_(T|Ic|U_9WK`)*Xa(1Wpr!jj=1i@vuD<7|9w&kO zsjnLL6Hc7G*j5`oM|oLV3Gx+lly1_`M=@;ARnijY|G>xm1!Bz4Dezngw@iBnZ$O=( z9b;!S6-Y$QTk2@ud@P+nq``Pe)enBa0b{;Y&BgcTD&A&0WM&@8%QIGf4B1`$ zKl&qNq7TlY1tnW)jN_dQJk^`Y)KVK{r=DgMaFdQh&g%G3;MwzdM`lHGu<0>>)wH0F z`UfKD#bRvwQEkR~JLW0vGw6kFb{lc_c1U3YBGb*RbWCl;b1}Gb%@q8z2b0{iwy!b* zlKUXfchYDQ^pfO-VkIE{FC*L@9!jE`z-0lCWOo>XeBG*=1n0GV^S=$13UA{}2+ za@^@XRa+fd1HH3va(d@pQnok}Iobmw04op@*3=#)FDpsziGl-IBJ00N)ch4?(R@*H zY%pV=dxt0b1?8_HC)W4V>GRhw7);$!=X5tZGwZO-zy8m3irc=bv^KjJ9hF4iJGti6 z+KPo3@Q7_raF)4BO?i85XLWUfpE?SxLd_YvNO?Vo%B45uS*d$;HYG)a{FiMOiHe!|x9Xx)d)dD|CBE-9Xm20+uMsLu z9(imHk&i4<7IDw+u{ejjv9E||8`IF?DDS~B?t+Yi2L(k<1;%z&Y+MRA&JH+h$g_KJ zDW<>C|Srr;Qqa{^y0D8%6A}&IIVp1 z|3}-G2Sio1|IcuN85RL$mvzJq6?aA4*fhm`H*;g|%;Z{T+G1v4+N-7}H>p!uijuF2 zn)IfP=Du5QkeXSRs4bSJ2wC!``TIQQ-aFhG2EXWp97NKI(;P5 zv$Qa{>jtVBeyw_{`~bln!3!ORu4o5Np`Fv+O{Us2!9YKya774hwru$WUZc22*NiUK zEy#ncZAGLXN2FZGsh0UwYfzjBS41yhX128_2A(H1}zV zEPf{cCWuo$!E{LG$#s8FJ_@}TJhmLmk7~7_UXGPd1x#2Zj%D%r<}^9_PE8%6wNM+q zMPA9Cr;T0_t(U-Ck&o!NL3-$b)ERsE~IB>$ri$>d>*QmFswaiAY}75 z03%0cOrqosm2?N)hXKFD%XraasHq=JiotU;cwYR5xsjUjKgsx-QV3k?P$dHIP&>#Z znDkR5nw~nu#h=TWf>alh^p?C4h?@z-@d1b5OrQsN1WAui(Sr02@=KB!eO&&nk6$HOttw~&%TzLk-B-c} z0tz}40oP#FNAdjUTR6II0S`~ZMzTR~n?1coTNsLO^&&$gTl=;-Jb_PZ zo{p2YWxdZA@Syj7{|m`JC`dga8C%}N(rz~p@&UmxtnHCg z2XIC}7D%Ul{3-ecJfO>>S7LjVN2!r^-Vb1N&y~;n0c`HM@|Avo^77xDQ75d=?k$gDHsAx(7*ekp-J!OwX~x50?t<@oc!h7SSNn)?eb`uJESyN`vx2S`A8 z4S`0l!R%xle6Co7Zf6EKN7tB5k&~79&U!>FPQwVCfWGDtx){ffKN%e5w+|wuOVddV z(Kac>!8iK=UEVd1%#>dReKTA=FS?Jup|?SoydC`Y=ROz`AqZ?|p}9ji^;~sA)9%x+ zPo(_o8fv}eM%`G4C5K`#P-YIll5FG**cuHtmdmMi!@Mkpj+MPHn zZFe72+WjeW(snPIo3{I|VegO~$m#Fs2Oc#qc{&BTJ^wzY4Ms#dbgelhJPFwA_BDvr z87IdEq=~U*iHWgIKdZDCt~D>x4@E=Z^9VlSi5Fmn4+`Qri@tAv{x z<|^X-4u86AFM4Q$ElcTIhkd!p+|ZDZ6D$D6E^IbW5^_qA&SlIYgVw+rarvAxhRNo8 zr@?C}#I?O;_K-dYJ>-gq^n);A5Zep!9B7nw|GUJr`(7>6?(ZAYZ1GLZ`EMCK+EyUFRD*8%&rv%2^14jLKGGS-D^Y z_0Z+ef`6A}ZFZX5d7VEY}(|4U+WJLJ~{!-lereX8Pg!Poaehmj_oyT8)@V4r!1UZ@9O zI}ey61wXLPAAkr6G5ad*;}79D4b@i(;N4^6qf8f)?9#D0wzR;yQ3b=Ce}?a1c6(`;kN|A)suj8)+`UIpq1!>c%xz7xDtH&R;M;J_Ja{nA zo2Coj-xLGZd3~x}`DPRNi)-?;aX(NlpM0Qk1G_!IH<;}@W^UidH4alF#4)gD9Q@Ub zku~`RFnlVe5i+8_PY+(};}*30xFWMS_bIo?mtUTmz%FWBpd6}F4wSk-6d2f|C3 zI{$Ip93vF%g=C*F_Z)(Ri?#dMCLB?{cAiJ)#Mjd)%}Z|h*x$a3vCsmT@#b+UHaImj z`}Ksmb+T(h{N~=`EGmyvLMGZjUhd$t(I+uaQewkANgct{l!*<>NUzH-oP=B?qde>Q z`CfJ(-vKT0eF#Silz^}h+L8s84)XF>R6sP`|HTg>ut}%jKN#PI)&2uyMO2KIq9uJ{ z#8!#%<|%XMfFJf$vhUo6;t4K1ZT9y%4nGI^;R&|+G*UW%@6H%zRu_qvBZ!qP=l7HPIFqg^aC18F3eo&@JnO6p?Z3IIi_vNZk$B{pLjmH z+pZS}b)CnRPvd*F zI!*l=*ZUTr(D*(ZsVMw$V;##-e4XbYyeR8DJ3%gc@JOR}Zvet=N}T}fW(7*U1fo6) zfPW(3q_O!hrCzEKeXFz3^KC)&J&UtP3^8D&T=csV3yqk|lvpZZk?%TUC__wM_@(jI z2qmU-h+r?p6aeDuv*z^wF{Z;xOqT$vHl{6VOxJeum||GoIdkt`?!@hFL_y;A5uzZ` zYNupo9-^Rcax+5QqJ;TstbHL?|JYNz{4EDU*(ZF zUB%iFrjZ8l;?DLDWlO%mx*nGoCm+Cg-7tJFl`rGo#u=5Xy3&5&;2EgC-9osT zVQ_kYlOdm4p%XITbOon7_Y*4#!!4j7 z5Yae21hc0(8HRxEkd$L6i|SzG_;NotQd_b90|pxcR>IHA)qeOnb+TCnaF)Vpio8Om zfc^?N%UGM7^eF#1Am<`nFRV$hvhU5UsrA|YzA-22g&%iT+LOOEC+US1pe9^0KcN>= zL7gunUL~@<@jG*zz3~J9axF`)@)*VSIrICpl|T+ z#UIRvg!jScLB$^_XrCPjaLp{~dqHL7k;=II;6b^nE^?6$sf%|INZYO^+vRU^)3&Sk zKgMRl&t{WhA#gNCrr9_CY<@;>YytKR%$Zp0U;2fx><`Ho>C zdJdhb7c-RO>fi>r#ZHy&&RZAB721U-40)Q2iR?CzcCld=2zR1eqX? z`Xhp-#g+DUbtr-#w_wrZ$sVDsd|D4&o(T}Mg=1iS6d*n!Yyy!GDBc&Q5)mYh6^4PB z7bFfAQnx@Xg2c66!nsYDlZT1Zou?IP*t5c?UmW!T39nF$^ zi~f!K7=(%VzO`UfOkg&M>7@Sfmxuw#K$Do{9%E>0S1dWk(AKW}0w~ajVmuCaRamzM zqQNT;>G$CXvu?993|`^*mht5$>7j)K!8yRvzf5ju-`qgV)DO{X+rUIjpE13rHH$Tn zXta+K$FzHEJ;$2G3RgGYJ`hfaS9LbA5tF+%W)mBV4XKUf@%teS#o^Qvt7D^e*NHu5#sH zrmGs5=DPCZFFqKiWQoqHvwcZo`x=p&aAW4$>6(GlaSeecwXTt-op(ff>Q4t=u(sBc z?YoxlRTm}lML`Ox;aGW*kID$)Jw3#Z0p+NR0<<9|YXPmqj$W6*Tg0Y+nGs<`1n2Sf zfh_62^nm1_rVxr;w-S5lheEEarH$k|+Yjq)ev%n&9+Ft>kZWr&bUWO1e$r#EZX|7G zzF6P$m4?EtR~ty%PzVLdG;1Sv8*0`rOwpp%J|8TL`rw^DH>u>pE!#(G;Oa)Hq`@uT zM~Z@5leS1@7*Zj{^;}!=ZDHnmEYGwP&jtEIxL+ICdGRC&cOR49{(C#Ij;FAeGr{Rlc68_qb2)$vUZ)tZV#7d5=F{aQ|4R+=W9qJYN$kgn{*LdeLp$aSJdl5WHuWY*1JB-?ILG?FNR3LkP*&1h%TiNYtN|q0F^fnJPUZJ3?J~Obr;*n;Nj}{ zy6)n1&sTx%oBo~RS=Ur?rq9{c@|q#uC+Q?Mv6rQaL3*#5@X~@Wqxrug!!#9~rhK8T z^L&|O1*ajN>-`l&dm6;yKvf78kiM6oki-jf<}pjUX!6r|V$0IS)xPChE13eN(##0q z?)0Qvot-I$06(PksoaRj;kDesEm?NgF5kxERD~j3$`Bg~w?G&&#h%pgOSG$2 zT${AZq6Y57=h~!8O@93Qyx~)7T$|)=9O%imXNs+B#LQL7gqksMl`^d+KW&vGW=&a1 zrG!m=R|a+|N>K)26-X47LV4jTWd@uTl|nqOQbh2oRmx-d(yEjp6oTI}u&?YXiXL2^ zOgC`dR54Fq02w5CGA*PFe;868^pr?0IS+DFRtVlaPw7qYy7Y!TjRKBj5N<|q5ii%% z@(oRn=iyS8MUb9RLsD#+;3WvsQ!0;Q6TrI)WAfnrNU=SN*vML6T$XswU_>8?oeTRP zS>hzUar8=Tfx?U~%lo18F?;)dV!2*83SN@|7;bM^S!rK2K=k4LTQRV>S?XBi`O^#U zD?-VDyYeUA>k+x6l+TTz$P+kw5}#U4UcB=4DeYq%u!*j zn2PC-l2pmMk`h#g6C7i?-y;$aMez3{etJ(nJE25Gua5A0$cX1lIDO1dl&~l0Vpa*h z=gH$~vSAA!$G|CIx8EET!ww7;J9jpdjO~hW9N1Z108^yI`xQJazR=avcU2zA7#3e> zi4c+SOVj;_iBTlA+#J}nVd8C4(Jp0BhD5~WN5OV~f`Ml;GP0K2St3(~t?;#)kC(am zU2vL!1M_~b_DV|ENxg^3MtfWWk0FVnaK$6^#d+cKqh5<4_PeAM@e658) z-IDbhE%pqais6N?&S!CR{AKBU`Y!Qm$ySXPpBaj|HEwsbm6D*tWxAt8H$wqC&UM#! zRK*(*3eLL$o>CQgDo;}ti^1D+dr&BQaSY}&BhbuoRK>n(jOgVNH4SlI$LS5D-goh) zIXSN{^$1w}0sd|wGkeD&ms8+jl83SHs~*P1>+v@Q4&md)4pfbK)uKqGQjJ7%nWF`) zLS5;ucj(aszU)Qs&VaKO9Qh@hFom-ToR+|gT58hUn7?IP9SASjk zwEC;&^5=n#>%ELbX!X|<2`GG}C!j2^T-&{)FacgtM-Gk=#)H7Ij*e`OS)4(Qpu}`B z3JTO83e-<(2-)Mjf>^9f`e7*GC&j5eLVg~27C))}du-)%UBg(K2;ed5qnV7|B8ulc zRQO(d^)Wu0;h;TUP46ij1*;-9alP;ua@+TDaYr~LsN@$^RUf@Ssz)cCLUjc}n4%_# z-TbJUe09FOdMp#f4ql(Vh1<=ts^qp;^rZ*D`H=6#_$r)F-m0{JJwd#q?}B@Vx{&AfXpL08ojkDa8`q@4P!tLTdk;xG+>cBE7Y-aJ9NuJR})3wW7=^aFT*Xi~Db zne)cdP8Q4V+tW5;lVfoC!Z`K^)`n^ZIU= z{k-=^rG4N`v726q#OQn3GveT6o;S^8i!Pxqd^)Ylm2bwK%!MyF_$>TcH-YEEl;*mzL%HNM^-Z5V{d@SqS%`{2_sSlN57j{h)s8}`Qrr&n_hBZiO-AS0R^ba=b-}>hXKz+&n^RR5nn_P zrHh`ZlLg?6s`kZgAkktloSuc#YqFx@M$Pr5Pl6-L-5agDz|Z60JTLnp3!dPN1E-mM zQj^x;!5INg4{ou}K%WEhEA5MCiF5R%n2R-v8MH$&7i$&smv3^J&NB^4awz6ADo>-B zPk{%;3`-cZ(Mfi|U<_*z_T{t1rTXwEF)CCQ^Afc7&1mhXpnH?&h)IEy;Ydn(Arx{S zFlWpW6A9-M=&?QhxVaZ1Z+7GsY>1>qH2xZcSJUO#f8(7MzdH+c91qTDzN}6s?npsL zfHP82$8Sr@j$GbLSncD9Xarc*$*z1=C%f`VCo38KfOPWB*JYjj6jD+6E$i_M#guEV zlh42l*U860aGiWIM?7li4V9(8kik~u%1eEDreQdMI4=;2H&B{@#t5x~TQTt%34@mq zD2XbMYCr(*YJfBrytuj0Ukdna218!NN0j}0h2m)5ir5IDoDO+%mnd4sQf}f@=|$} z+C1i=-$%J z;^Qd_aWLt9Cr_7QH(Kd5ocXY5rgR!k{Qc;O?qUQ`iP?t&44;^1za_S)5xEIVE=uR& z6bWj3*s*$!VmW#$GCe?%pQw&}PcrYIsgme*L-x$uU4yuF@RceC6?$o<>S4vV}Wyp1KnWH_f+JLBoumMs1q(HPJe4%yWX1DdDPsuH4*-=uB9 z`W@(D4Dg39m?U$cK(?9{MAUbog1C8JVVy6V$)dZ%`U)c z3^T3h&sQW%@zq4$4(2bo=u1BZ=Mi}m`HI|r_k&ZHcWJ(S?5r={vAEKHX@#iwp!I+f z6Ti0;3>_6LHAQ3Kym;K_uz;5tEG4KsYE%i}3Bgh(()Ikp~6kdGkbBS<=+hNQeD zfF}e=yHy^=b`=`>V4$=eypL8@=goe7mAG4P=#8Qp^+9aQYVqHl_eV-mf-Yp0uWtH& z?1AOf(@md?U!x9wZVOU~;%3f(TNvKC#V>a&^=8Y~i09pVw84+x2h0%>j>OvPIbOeoamiUZoC~J#bXI`6*7YJ%#>KUad1N^ z3Oq-sK-cv|$Ob19KcP=d245fEO}LFBQy(F3D|Ng(4k z!_f>Pm55Ow#%~rQyo-%>TS`ONhgE(de*cl9>H{}6XwoCmUKyZX<0^N6Vm_ubIIlu! ztg2t5%8QM2Q>1pt`Ks6&ZV(4QiHt3!VI-&9+LXn8Aci(URTs-uEnj5{ew9~0?pIL1 z1D-`M1%NmD15|Y|3eNYV=mX%CBu;w7e*6RRu!mX+{0(6l9{z@~OwtY;e^(12HUF1t z15o88fD_BRd*7>a>7&3I`5&>g53c~th%3DfmM*4cRJroat-yb-CO<6!?*%J)2<{cj z@;<_1s%v0Gw|gW;Aht4=R&HLNN;{TrU7fQ6^mc4k(yf~u%Tw)^hEFjYx4I+ zIwB=ux9{63w%6B)b$=6tj!Lgl{<(AvGodEG082eeR=a}XK^a~C)SyiArv_zmK$K&a`N0nA zgyut#Fo#kC#g245=?3dSY7-mhm({Y)rX#W>gdjv)+3r8>1VVoN!5Ja%4U(l+a6G}8 zSsm-1PmogOJiK2~&EpRQ%Xz{B!RYypkMZ(G&`*6sZD6e9WAMtgCdWy-Z_28^UxTi6{X}$|f%M)?-Tz5H(`5h87 zSk`WFfnf?b+2CwBDw^26L*ih2)*f-Em)7T}PM+-WbXM#&a)t3ogf=-$R z-j*+A)mKcjnjgOu-`111D~3?;hpA<i=5|aTXs4rmO77MRI2r6@hxSKs6g#xtE@6lE62707C!A!5*6TdJyR-DmqoVvygB*hh z-^S2u*(LF(&X63~kbvYALL%nrq?hM#ImGy=ImUC~Wy1J~$|K2108h|K&(9&#v|;R6 z8J0gGi~JnT^)hi32@e%R=_-j-x=JD)rfE^Q?#PR5nwAv|&+zo>i0`9ZR^;P8y3&^5 z_+1g_3exk)?iH~O^%zc7p{`N5^3^p8S3X(pS2DQg(X`n5{$#ZudHD_%MC-?oBO%3| zKkhA;g|Ah73NN%);kO?IS)5FZRR(%`TAMLnU(FTh);M zuJSaHR)9C{7cq=o{sBuyDyG7Z;`a~7l%Mv(MPu5Wcmw%gPr|`BFP7r#eR)EmY+k$q z&X#N9wi+_6?xwf`rtYRFd^Yf%UP&zeNb|m6-La!U*FNA8bR#1mRHaM?G3x}W%PIb6E6G5*9gp~{F;ONpp(e@q{Vn4yNWClT6e^f)Z{SJ;--o?0j@5dwK>}`J& z+ZqgCPsc#@UzPSL_r6Y*#2s*s@TY_!_wVsjqUWh_$zzUJ^jf^T7MyRJOjoe$Qi(-#`fQy+<@$5D7b!b+QSA1WQH3q zL%;RF=SOQT>7DmckDu)!U4x%fI$b{brE+dSYV?9Ok4jVHWjF_^M32WlV*Bv$cM%?u zZm010rSQusyrE|J)tK4t&D53NpPjzp*MSGPoogk&m2v5<+Q1h2WeZGT1Lhkji8c$g zyQUiCF2H)e6702UFfkvr&SH#J^XlXgE4GTq*vpp2eisli5?T z2=zA+hJO=Lsat_9rId)hS-OovgOH8uEZyq=))xZiKKCy*!npvsPF9jZ0Hu0@9o#3^ zTRM6zK=KFq(17h;Z!rit_&(huJCc>Hw|IIzhp(OVcu)A78}K;|pLUksAT^jpZ?FUj ziTG}{!7?l7Nz@)aWI?APs4yMfWb0aQ%-VNnR2lcjFVAfTz#d*3Z49WeBus$(qDZO`lRINurjH56yfj^1^a_(7fOw44> zi!3q1zX9W=t(F+$F%0%}!+YIlt&1!X!kY@4?K(8R&Ikau6)EN)h>~*g42SXFC1X<$ zU2-T&QKr|mU!I|puyR;#f>Aaau~CVBMgz@7ZePZq?%keM89_Z@Q7O3SOF%$zc);Cn zqa~*A=U`BPiI3pI$jIH0DO^OF?XlthJe~9)Q(yWfBEZ@Pf8m5=m0meHh6r>EL!|XW z%w1n(0(mbto(y3#Hd-3xP%}gCUsP~VS4uXVeDS?r7<)H#?zp=?bH{IA1d}M_b`}W} ze}lKK)HrEUr?}m^={g8o+;shPx;tsE17*H75RahfN)cb%iAac-(m#~*UiQcxVgZlr zc$8)0onJZKrgFky+(3y6kiefvD9%&YMu$Te(-hue{HAWQM0WmGQDn!IToV-ZWJzzt z+#E4a#2#67a|pYhhVdJh0vrIE&_9+HZ?c5+J%~u?#1##ERwKK6@jaI|5w76@Nbo58 z%@Cp5w(Uxyt6dT`!B603O9yWyg+C|wwhE;NjnWK)-|J}5iqmVGEgc)Cg7*b!b-+zf z%8fhhI_P{XNJfo%`e59A`@qsd%?94kY0Kgd zjrR=jKnygjQSa~vL~-0mVx zh6nEOTA0*F@3%Nj^>`#gvI2PS<`FBIRr=%l(m0iVGFBR`(&HkfM^(CBgfv{G{~az3 zQR%0{rGYY?Q=Z=-T@(m$9a z+Lz!NU1O4xRl0#mYOm5S$4hNgx=*~+QkSCyD2kRy7J1+SF;Y{Nt`{veQt2ykQUjHq z97mc+_WxO|6s^)vM@f+?-MPL*BFp3aAW{le>HkJ>LzA4JGay2$1BcI0C#Z_@K0e{n zl*9xnPOqEZUa#j$M_m2tJEn_dZ6u`VDr&m}WZ1GMeS-~M!Q*YycF-kxUo`#1$S_$+ zWrs@R^}5>)^$XuA6R2&36g5Q{sKpXv|3|9k)}g~iO{vXDIU)N!dBm+Dv6R3UXv(Am z*5J=HCQQmO;^>PZuI*KLUI0G}Az?;{-$b3R{WaWIK}L6!`Ng!Iig0v8k2K(7Z(TlK zp3v1zeL^?AH!e&8uHrtIyGvQ{%l$xV6LG*M9#YG{A+?Vq45uM57L|s;WUDj; zW~@rDG37{)sUMJ-ktz*|8K%;Zn87Lyff=CE5SYFy4T0&c(h!)QDh+`l(+)gC5SUbz zhQM^?bPh@iiAhl%ATb?P8WKb6tvoOUrnO3=J<<^-&PRKsBTSq|du*c8Xpaq58qLe3 z(rAydDvkCSHCg>YdyD|x4()LU0)(o3v`4Zv#}hz%q!%Jd@!Jsm)lu=p9l+ zP(e~VMS^AN4d&827lP7it0go?mZT`j7@AfE$g0#pP3xvr#d~>RC~GXD-W;QZ64y}z z7iEkR&<3Zg;eIw?ty-U!g7+R$nqst&h|z*FQYcYJ3J6!Oj1<_xt(HhZ50Rw7L6hF- z3w2q&?o*0uU{j!$+_8jhmbnRCP=+##JT0d&ax#4<$WwCaklW$==r&6m!*ZlYYuUGs zrlhO7p5NRBA7g2Lb5|kzS=)I-&p$wOXq95cl>%Mq??ewCU%wvcTcGKnFtwkjGUWpU zL+aj>U*Y7Pg=Pe-&c|K(>U`XlU)`HAerDh>5~FUc7ZOrBB7Tck&MKdWQ?un~2G$U9 zt7jM+yxkIPfJBreuGXnh^w_83naOm}T41I^CXBR%o=uvI|t|NLq&TCq2 z|E`V7I}4ryZVT{k?amBiRXZ$EhJ56Q#=TLWSUSY@Lq2|2luH(9dOqM9Ozr3v>7+&Y zp7x0)DRn~zw)hS5_>IOOYw^uxscz4zOLV6j#@`lE?IUKRzGoE~gA0QZI5qQMe_}D! zUXLZHQkt}~C+ei)2qsQD35&0eaQk{xK|M zwlc$fCb&5urru<*T>B&s$lINs~7&szIs z`X`^2E1z;)6^^2z$(I!EZerCPKPsq_B{c289N*K?g0y z_A8YDV-P^6ORM@UqcWU+m!wsO-=DpA!+inMCVZcTJM|4^*uP}uzK?{E`YAR>;+n`o zOZw-59!Q21ZLU}DkOzoLEgEHKG_pv>jwtL* zm<7vuNx$Kv`cM(gbUU^}VGect}xQicDjRLd{j-AXE_C^6>|fNpv(-$f6>X__~cRRVJTKRb;ZoQ8zOAzff1a&pC>eNLsRxiqcdyGRXU! zP4L3|ocBS{qh#!{W0uD~d!X{!m?q{3cJY|SnA1gxsH(d&)(;NqOVviI$NoDv)luvr zeGLf6R0p8W)0*lSh05gcx5m1>0{<|Tr-6SUcx4B%K0wbh6zbUQUqoN_#HZ+=(ED@s z!_9Wc&B}dsaI+oJ$Tv6J5dwmn?eGVon(bJM(yaQ-lK6kwO>oPsSAaL+ZbbsXy%^G= z;7;Vq_SR%i_)rXX>;*aP=9ot8#&Ju8=ZsVUU$*Me5dSB5Bq2r35ea{#)<;(g*{0=3 z*6V~NCi!bLfc5p#c07x9jn(*@SP#<%sLylY)9T}D{LuB3>A_4N#$uo?mO`K z9!2D7h}j#cHM&~c<+P=n=c`DQwH`bu6#YDvT@g4=lARctOZQ?~of3<|Ya?pxguLxX zZxy1+7lLz)?`)|XKr6r*Sz_rxvRAAfqU@(jHgZ4Y#HTt@`XML2rcUsZX??zCQhz#P zr;$Vxj#^03?XI=dNjoEQHw?bzDyheBqr>P2I0rGJ3IozBN-d_L(C)>g-5r)8bjeZy zDv7K=e1cja%|6rv27U}NZ3!;=&iNCX90R~IA+qf&;E~3sOr>EkcpKk=pIbtOoyb{} z&n=CDFY~Mh7hU4NAw}=OVf^P7lR!;n-shI2=DWI9hA+d%pZKdn=BP8HbZAnu4ZcY{ za`1a(5Jq6D%`q(d^Ui6)2>9-D#xh)pN5l_y431zM&tL_!E!fA;SWLl*AShQ`17s7D z&yY7bczS|hWsNhNvVLbRQ-v=O^UkxD6yZl;ld~e#Bzy~E)#hp0h+t_z9tmaw&)^~>mZ**Mb$7p^Je;>QGAIGrr7ta^aU~B4aTp;UoVO&l zbC=YPhXnip0Y`snY2-Fw;X?wxg@7L+pmQD?p@oNQoi=dB(aV0oCRB5+OdS5#q>0LhM9{CKp}P*zk}LD-mMFMH>7=4M05E zt#2V^uhj@qEtm5U!tf31gDVb%=<8s0~*zIw?!#QH+`3C1Ar9yj4{hVeIYiF{)sQk{&wV`Mu>AnoJN(+=!P< z29OaindC;iWRe^4l1XmFOD0$D?c2(qOmtzA`x(GpEFU~lI0wL4ARkUDm;HPK&OG^S z4V}P7sQ-Y|ULK_=oFZ^q%YNvZ5&WzHrv*!Yv44{xhi_qB3_HVWt*bRYmn?6P886D0 zW(>KS&IphhFBd-9a94`{+Vnx0tm>M@j|M?bf%Rm0qgTzqCJgY_&l`Ey)qh#F*!{V& zU*q~ik#7>aa~h@X!Gi_&`gEf= z1T?qb&QD1A?shdhdogMmpZ+PnB^H`(yO=| zhCSQ2D=UTU&=@=0dFDFk+&@Gxea*aApv)GsDD&wREG{@=WhTv@B3^nI6*9+Sn3g#rK3ZHbwDG z1aDv;*fKQUf#!P-86-8;{Eo#YXRzGIq4~OMqnsyezGQ8bnX=|<3*PZN$lx=Gjiyq< zZx-9bC7K`iq8Sq!+MV|5jEP%t0_PWS4sm_Ol78rC2>2e~`ykwktnmZ>3XKE)s@%Qy z1MaUWY<{s*p>eU(!N<)`)%&>qxR;=K`ExxUQ<0^2+?)Md`F|znYzfjm!yl_vIrG6e zEk9^W_tlWs7s0^+zzn>c{*BC;3C^W+J-HH@3i>j4^}i^)TEY2-wYfhk%4-bBD%tUp z>^KaZJN!~~(6=(DA2_#hRCyY^JR>8X?WlqZ<(bwrXFXZog-1}lrd0HdhD7Shh*Xdcsp27Z`tBTr=dQdb?v8#&O3^h3Zo+Zh*ZdN zB=X7Z{&DQWJxh4NOeB{o%P~2eipC8srHtdY^VJ1ncmHEl%di%7%>v>z7(v3SgN%Ef zA3P#&FTKILG$Q$7Hgko_IXzf7b2 zUvUY^-JtxhLHWM`)SK(A-3&7kkVe?k^wu_U*)Ab+DK>;yh!De()?U4JtVg?N5#$S` zwNI1QE>w^MhTPepxJ9{K zWwZ_-<_`ZgE&;XpGX$&+e;x3rZCJL?Ye+Qv)o6{EFVnTwJ9@d%fQXOXPJpNMawBA3 zF?H(d_?}wgKp$%x!?RFA^p?&7A8QAw{3cO zhK|qA)0gU7LjZiOFswtpepEKDmo<;wvM*V$w5y*2eXYA|;aNETqEYc4#>Ag6)NN-pJ}E_~IL)px+0L z%kbf>kH59P-$E>e`OsS_xDY?h-#VReD{_M1*j!)==?G(qb*z?5h)4<4 zfwYiB{r)ARQLn4_9Cn{3;@!$O!K1bDF)pzYPt_8G5!>lH*2K6z5Al==PvHU9;c-bW zp0vW(0G<{HSVv7!v&0?g{3Eo6??VDUfLm=+J244U4=hr<9(PpIU;_iKk#RSvO60LG zM@yTltB8C-pf!c`CIQ8c23i}%oqR}$0|?<4WF71XVF|LD;?_MR#JdPl7-XH*&Rxl0 zd`Q6Q2sp5=wWk3(kyb$2in`XAxW`;VWNVb+K!iA7*ZN9an}>L63{SJ`S;wZ;dx$3k zJWX`c)xkxwt_~@Bss$E+u+XjUz$hZhl7oRn1q5G?gkUHh0gEKFnH0nkN4$g!WJxh!Pd9FzZG@i!y@et^& z8PEr`l`n)^N2PWH7X$yi-y3IEQFcr%a4eS|pg}U91B8xx%0^gGPK|7Y6@3Qx6`|J1 zoF<3_nlSGRHInv%@``F$(JpxEz#|DQnp7i_(4wtyr&F=Vuo!Q|(Yt*x6Jm@{+ktm; z+tx+Am`CJoQ{(N2%=uB~LW};5aP4`#ArVDGYeXDUv=ScrhFK$9{DCUL{5mgRjb*AD zOGr^3Jkhc$&e}DT;ExrTJ`&;kRr5-kUywRebTW~OPA0M?nfX<$<9>%I@bJ`)?jim+ zp^C5SN-u&lL$*<(aL$4=O;OIno69qDRuEpBa>hQ8tJ2m?$7@s0{HRJ1FHmq%3#3w0 zIrF0`%iu*ls(30|zVvP|R6M;uH17ks`r?gfzlOY?D zcGa)_5yOf97f|Di7{3B7>e8M?LN!t2ix?N+MOnls1(`b7+PE{Fn%2N&hh6|& zFs0+|fa^ahPXpIx@GeEkEisQ;V(PoSx)Dfu)dEMPB5*|VZS5D3F5lLE8U)|go(w|W z*1n#ofVAX_1Ef4{|E>YaiLU|4iLdnglspG14T%v*2au4GS!HHJUN}gN;6(u`2BbTX z1Qn3C3=WX~MDyjqX+Ww1Z%eEOBqwpA6qTk)qy{N2PKQyCT%2|jLE^Lxgep!Q6{J{n zyxanviv7QZX)#hFnCjFH(^K%Gz%&u0JD3KjkmMU3FlDJc4NN`2gDi!zw@lV(YIfcD5 zBejwULh4NrDpKJpQrj>6Ge}KEVuaMq#_}ucOyd=ui z{5$ZX;P*O6oONv^-`Ll5hR;KZm}v9un7;$R87fbM-;?0+Mp@nhjdCbbQBHX$v9u&> zh_{jjZbeqk0yo_$le}eiMi#idwIzb&tr-Ya-ZnN;@ap%iEN`ym|KH-JLt=#2%Sfme zyuJsN3SQrUbc@$Pv|f(azB&%P_NY7!UOT|USPNDx|39F51*vnW<`6+pJp)38>bHi9 zu8(d5UH^ZLQ(vS+IGsc)wcykmUKE^~f^>^hfQrd>ywjwpFdvnt!O0Um$Q8C=+oE0m z|A1A33guuOBZ9!%2SNoaT?MPW-9G@0+zgn;Y&yDM@Y=pRPeSA<_ABpopX+02pQ0fap9h5Fk zP+DJ$i~mgPD+53Tl!%0Ck*dS+q9C;!q+6+?Zk2LD^;Ebq_@F?wyy>WBdzqm zprdR^n9I^wB1o2ogHUDZiv~)=dpG4Dkfr8Gi6GjHRBC}J2woJ3j3C`YMExm;=v^4i zP#WG(Do+E^ci{2KU}P7$;gyg=SA?kqgLOrih*VTLkzANQL@jb*+5mzJ(`pc^Ff~wN zn%Y%{sic;E&xx<;_ni1jzej1`{BT^8x=4snsxonuh^=&cMDlKL47?~P4Fjp7RHB^& zc9sz-F)hTqJqk)4RGtPUQgxW#gt4ExX;4z7iIQ{=6Yufv0SGQlzY;;xbOVGcO;4Z% zaj90=q;}aM)AV#sNc;ta_yq6(5+R6s)DF=)cu^o)1=1}#kZz%hQenA<7b}#87pC$wP}K!*;3KjI|2qQp4RGKn zog;!!ItfBWX#g_M@1O1J^?$3Hc*841N(51(+96s9FA7AtAl*XrIFuHbrm`>xL}rzz zfr#`RZ+M-u{(i%2iqtty@k9_#5g=5Y-i}pp%IotF;B*uC5Kd1a73Wr0tm^PH@S@;! z9Hfeq)3WD>XuQCw*z_fyCQ(FblgiWJM9Pl$band4t*)4QI#oeYl8O!|Qt9f5f}&;Oawvo0SFbURw`5_ z=l&U}<|8qJ%DZ-`Cc%pWl^LX4sCuce#838jb?+fkVM) z8K%5iw7e5v(=MI(ik8n)wR{m$BA8mpFcDwT@MpC zoIIs*DzHXzIr0B0K)(SP0_b@pfCfp~(E!A|!LQ*(LFf!fw+QV(yXFYBj&~qL3Xk(N z2yFq6cZ0u-|Jw+?h{QQUGeK~Krh-rr`Xxe6LJtGMn75!Qc|dfXb`Jn0|MN{x{S0kj?o)C7oY zB|msk5E4MTMd&9qM2=8-wULkSRGtQ*OW<*YlBNKmcIv)DP?oy<%b)3ycU<^0Ju=Dl z_9oOJN9cVJ9HDnXs0hWN0K9k0or?CBNa5VEG;r15ut=m1>n5V6Sgw1f=^0aks+Py3t&8^WoV^+XO8u-UMR0yX`eUO zYSRmEg1Y{)wbWa<9Dozhi>x*ep;rKIe=f0_g--(ULevuL1-)ReQ^_X0W_?ds2Ewom z1sfWK6SB*!(>+D_W(9fH7xN*1p2h>Y&Fsl*t@k~I zOe1a|9ks^UN36F#>mj^nK(!ZHryDNQ-6&miwzt?C$+9DUNb&-M*$AMZUVEQdD;%vFKwha4s5$o57p=MYtl}ZU*wV{ZKl|BB)-i(5{JRxAwLsRkvL{zqpAifv5%1>xE!anQa8myUyevuY#D2enQAJX+2_HI{$@?#F&vUTROk82uF~2Y@Z>45xZkaz zecdKA(NkKBC)SUw_rh^t*aTmiJESGf9J=-Ut5I5O^^uOW@MSrOFvqQ@8@^5vim&Gm zAp?bO{T}mk@_Pk-{c7{O5O`=ZD!!K6V#rmzqqw7kF25Kj0F(rrt1SejD?sTAyjbd8 zYmybxsGd36{{}~DQfi#Wu zu=O8JAs`DSPC2QT1%5O!gULBr&|H^KM-}&s)#Wo8L<(E(6jlS`0}orGVRCr|`_Qw} z-b%0?*82ySSA;*nN%kr~T@@=X@CjidUbeID^ZjM0v=-(bkK71j25;NBz_)KzFfRac zEgUx*Z>O>A-nKS8B<0_!#FYQEy3&zH>#;5dTcmqW)JP`=OGn;^30s3L#gK*Q^Pv8a z(FXQ&1{>20cWzeLr}@~D^umUls8nCuGb2^JYNR(aTspD@i+8}sW4DagltdY?FGlO~ z5v~~dEOx?*vhZ%CbmYtWY>FSU&=;w^?onyq=x2LHpXrIOiJjAC89VCQe}SO)Aitl$ z%*Gd=wUo+%1EMN{@RZP{>X*OD9YUvCL_8E0-`}H|W1D5-cd|1y6A@MtKI(G;eRCEoSaX}OIVoPc5-6#MZE#XPq{2(Q4 z#>w0vN@0tU!}`T)*5)rvme!s~hL%Z@1~k&;d*Y<4Exbnlu5{9*LHVw z*yhrah!#w!Yg?44^~B-osEKk|XKC%d&d5R+sVkEj*uvR~y0)zejtT?3Yrd@Z&ns+Z z5>#bNR#?xL5>Am*q#oLGwN7A_^=#deT~odSupQYfj+fT1H%UjHY9N`K>hj}Jc(UO- z1jAr6o#Z!4WpG(zi3-Z6nRE%6q84iRMq2rNb2}#TQ{;E z$319cBx!Yc)JW@LXakHZNm@%B(pnyEYu#Lpg(m}vb%d5BmgiNK*uF8g&A~8^m`D2Z zE-H5$bmbQmMsv1AIIX^rgQJgfacu z!iM|kn}6-6EB*;5PIEh_vjvT8!&^b3i%rI0sexzikZYKC$KzrvJy1uIuGS7o`PwBI zo|J?zzs9!MoX+W0MwpR=ZOkej-akyb5*XW74X=!vox|V5=xIClUIm?$aa|shP%Hkt zA;u-(og1dhN2Z+Pof;v%tjX8?*_n79AY%i&vDoGliwtUkrA*F$9>dma{?ZX+5If!2 zmMHA`qk>J#vPBBheyp&EH?esMH2$g?PE)~Mn%OSUklZ=S zDy2Q2Kajqm1U5p#>1C(?Apw@!%9dDr&J{(%Aw*wD5r2i8cT*y+Q8yZ8LSabJP?)!& z=3CbmMmrL_)ykIQzA7|Yq*rTO{}yh+sP@FM@Hn44E-vm(~V& zwMepc?QPxMXR&&;!-NjD4uMqqJAy|M5NJjS^y=_GBVZ5jXdA0Qr=TQHVc0tDU$&lV#+*xB*4WV|{W{rV)HdmeSzYr;?PN=@ z=_t>L8S7-*@js$IEyWg^qqZNQ?nq)j%{1SNmX2(~z9%xjrd&on5lw?02yiQ#)u{6@ zG^U`YaSd9T9tdz7Cd3m7DYF_%=t`v=$P0~oRCOR{fDXl}{WDALY)kCx7XJB7rM2;i z81KWREFu;?=JHh)w|>ho36lM?k2>2LxfjHIOhM$C5|8l89XY4}LQcuLzuV$zWUP4? zTO+EF5>hEn%5ZzEqrRtg!PH;%H$-oQ>C3f7Y%gL;R6RMxv;^a7O%^jA9*3dl#Vk=8~!qHD|I zGHsCtBceCH62ek5ZNqcaYIX`iRkj4H3b}Zy4!|}r%;l=Uj4JzDR@ybInHG(vVzFR; zOIdv=VY)}@@=qyYzN_ORPB%g(N^9TmARU?6kq7edakTQ9vey-BG#bBG;Ft8%$#7jh zJvmux9VucoyN6QSHN;5M%Fpz$CDnjGu;*WZe^t+i!N0E~z)WWI9oJP7iW=+hRLwhVeYSo9RJ~@bdJ4ok#e3uHmOfFhiCt z#(ith4EZy&FyuF3Rh$p`KmWFZEzVNfXbq*-1B0DBw2$1j>@UdU}5QZACZ>YU3NmuJpH!5DtLfWdIB1n{PYjD6WQ!Nlz|I_GGc}>2KrVRap{@l}Cqj)@yB557kZm)cn>ZC* zor|a;w96XDVs-f~XlVi?cy$fV6*zLMZ4K^NeO-RE5b8fCnD_9P}|8QSC1UpT2|&#*@r!CA?%l7w!O}kOcSbF zR_4wO$I6_V2u1FpEjCt1nvB58oa(_LHtSu>BUr^`PU z4*M?H@!9*Rts9MEi_yV32fh*F)Mvfi#nHdjkhl5O{Tu5w%GN<`<<1dS=Z38qWjmSr zSF)UuE@$~tU3uTumqmK(k+fOv~prSfd$69sM#9|w)7SlNf%@R?t)i&I{r)ptm3#_&n10-Et z3yfrkthUxPlpqM5lNorD_e8DY&I_s_ZiZ3 zF;gbUo$$kIkgbEK|3}%i$3;=S{n=d<6crN@6@gvxhNvibLsWLryrgE1nwF(Yx-*uU znwc3XvuWNlHqqlP-GxlWO3I4NO32j8O47>if>vgh7qpbjc)!nF*c}+;_x`b;*)#Kf zuID+=xy+fFNrpQ57lq`P(P(Qz^JE=4&*Ou+98nqe+)_a7bY;F((+L4%x>?ixs_H%E z&$euLtssAPWoM@=Blw!)0@CTw2WzX(0MLGb;;#Q*E`L3NzIB1w6W+rVo}b;2)i(05~!Wi_2*^GjujuI`OU1(rI9-?laju+ZAsPeio=# zdURz+ABB{c5wNstBz&&RrqS!`C1BUc*txEZND`uJU+S)rqqvx*S*FW1G@Mp;jmSwm zce&CA+K1tr#)vCbYrWLKO(dA~Xq!k3vHndYS+aoB9!0>%5I~O_7!n0;DuDoPQ;8uq za8n6QZPiUBHL(uVW8kh5V!TFC=8+a$&P#q}vUMJ!*jG1|%$Vou8vOZ*au)GhdEvHs zE|WQIFY4&rSbWXg6cS2%N%qWljk1jS5@X`|u2(GWzbr4@^Mva?vt{0KjIc9ZT`doS zd|M_$BmrmGQ?5gn3jCR}&^2HzbS|L~(S=^%rV=D2ZBxm|jg(C#hBW?7CG6rt%y%@9 z&MyD1lESz}E}LnHAvvLCv{SFIO3=wIu*N~>R#a?In*P}8R3 zU@S*b4RZn(doQj)N3TiOnG>+sJ9Q-%do_?wMT5oOH`ttO4Z=g;!0L;3WA@le*O)}m z8?LeWpbuPmk?FOS7b1f1N&*E3-fRtD zjb($Gr`460n9s}EsefD%Z1!p;!PKPnH%xYMwd>FzRe(NT{cD(Vg+3jkOliieS?`~I z$bOi7(RY?8M&(F)t&loblVCuaJOM%pD$#)N8dvUBx`(soU7X)aPBT zOqR^gFalod8WpIl-|3|6eFHp)Kf`@kqg>L0A7l(t zJE{bqG6$;(!ow}wCq{b?_l;p$K4q|66ST9pXL|^?y?)q-?e!_Mv6`SQy{e48;&a_^ z8Hq|Cn~QMB|3M9h@gJ45Ehvn|QI41kAD6SEd4P=6AlHsyZvzT{;V4700U5L%kPBFW zlY?p_E|sFdG)NL4`(FYiTZ5$H($grUXpk=3wj)o-Maw! z@;g;f7A_q|VIhu)-g9Ay$$|z8En`C(aLp(-PwsYIw!|DRFFg9PE5&3vcBs5C_*K_- z6Sj(%vpsuUuE-2!oSKa$B`$0V)?v&{vr;lVdPENAIht&$B`2Q?F4g8^5tFeQ6xD=zqtVsu4nu$U?4RU}4zYRz<&SrfFCLe$X{}1CRi^%|@avu-}u!bNrc?g$Y zLt(lGu>dlEKOh+zq!BKSMFHFjcfaep$7GoTiNWs!^B&eDWH!@_Q8_3GIHn$OjUNhE zm$=|=0Y6&r*!~SN#V|aGJ-Da|I z&}UFF7N3Y_8u$mwSrX9p))u1!I8;>58bLGJ{wW|0{(uz6bXrjym-nC`;3z{(fMgv6 zWQqo9h)Xp64$&ZaF!I`mfS5GM%LmHY70kl(ag@2-4#=#-faKBKoHF~JxU>$1ks9PI z*quEB$n6^B();DC4+l)0<`WXi{YoW*=z=JGr)eTzc221x+q%f=DHDYx z4e}Wzj{X!7S{{(OeEnWIi$>u~9A!bX06Fp*AfI6hEJL2ar2{BDu0d`CB<&a=vouI+ zT*^S9r3TpxiG?MA+@?X^eHY8QD7=HCENDC+iN^uiiy5#iXfiHsN8vsVat-WuoB(9J z2H|jNC<_1WSGjBiB=##nt{qdk-Lb?X|5p2W00VGv} z{Q6Eg>x#n9ILhi~0kZ5{Kz_tfn$%5Rj!VZ-Sc+pO8cvv+%ilyXE$4QHa9l;KWKN-{ zAVZ||lz3c^H#KKxzQY=iR*3xGWs7`ie|h9pZ2zQH$2{mmtBx7qIQo0nb}g)_`IMmf zl-TfK#FG0`Fs{Ml139TI{0G;7ILIyu@hP%pxn5PSSC(56@53W3KPYnL!j2zYwnW%o zB{xl#dvhOh!a?qfD|r0oW+t|%F6KNccXsUu*LxGxW~SGtCkAkhFo5HfkFKSMN^+C_ z_PDHZ0?(M z7JJ#%-jaYJ=g`Zp0ih?}C}*uvXocT%moabAESOa8dNAxL#*}5V>=oL{6XmYk8$AM& zH*w(&{8-7p*ycO>UcuAa={TKw72B?+Q@VtaldihHGS>epo-7=Uz42FDu+e`Ze7@d` zJ`&vUpr@Qv3PNmA?BHKmZvPTYul(hDR%2SY>~B|uNh`6uYp!nfRR^EE1_x`h2~|;s%8y_#MXY5Pn!FYDF2RARcyB{)1bdvV(20 zEbfNu&ETbgJVUS>t~p^=(2FPt__^?#@-N!>xV`?&G6v40%n}CRwv>hug)jf>>S79h z|1~_VNlb3KW|CV9s7l8E=lZu(Ho`J{YBs{M0Jr)rZIa3?t@BUgmx)FE8!+rKpmV-U zXY(tuNP++?Kx`GDhb%x3Szx0m^;h7!NkV+fNfX+Vte7zQz#_k82D}V04)ZvqJLa? zkY}>B%Cca$Ds8 z3f`&Bgn>kt*-Ut#pIR$+`O|#O^B26V20jA*eWDMjO|mOv2tH1v8XOre+#90ObF6sl z#BjDcTyV6|PN^&hfaMafIunj+n)`~snr1^6s-|uLL^T)2Q+(;&%ymW=)tN18F4!oI zWFw8}088$R_iR@|N16)*g0JkxAONy3G><5>MhK0}HJN?{rk4^52So~FOvYTBcJ*wZ zjSafiZftK$!DZP*3bsNMyN(Hw+zRvZF%U+KYaE6jR zeWIxhyGl+YiRI#)>^(<2cCa;C6ps^HyDP+ha>qPysBA4P3CRw+Ie6`MRMe^{;VxS? z{>fFWRaFXb5_G7vSiZQCjHmINHW6B~=52&dmM_36tqr2jP6M2ulM0Wu5w@GcPGKxd zl}L-WKj1%^60&SpIs2UEUw1w4!dp&agvhXA;0!gfvl@YnfUArVx>`tFVyrMc7-3iv z@94m?Vug=m9S|@WzuWN}f*-YxCA5Mt7>}J&YtEku8Z;W?Q>qK|LV<};L3db?}lSkJK=?ghk)!VD(|iTD&KUrweOJA3Xbj|?o+#Ip|sWyoVe zQ+^j*XH7o|ZOQt#7eXw1A%AFlVV&hB{+wzr%(Og+FdW@M@I)5yF%Ef-Gnxl z4lwV0H(0X-*JNuF0el>VuG`BCW4jCSrr^^rV$~97M)weUS@LjsSr6fru(S9>!>R4K z`UfT?a`U?{NtkFkf-8kdLVVb}G9)tpNkEDTl7z&Hnv{)CP8RMDe;8LPA4=|9h-%g@ zo7-^BY}5K+To{tC+4wxXf3cSk%|d!&z#*gh*F;GQsudgAQ)n)uLY8pX ziPvdMgU%YSM}Rue6HS{OCj+eg2~Z{M{u+Spdca5p5E0p+5m)jMR8Hf#M|W}(AK$8; z=Z*ngSYj_!C}~M2t(dOaW_R*v@_(~%70HUGZQH_DQlkntxW5k9R>8Hih7-5nEYV3u z+-_4)?J1*`RDr6o;uH{^(>u^PP%O|n7Z4Z+dJ9&zxwp{3?;-FCME$6s0$g~P-b0_( z066u4{WSoy^?>{ufF*js#u|VPdcbl5^b{gkr@lg?uwih`xj56z5c*td#hq+WU$hQ7 z$=$q@&F_m*>V5np@Rn2xjQZ}<0<1xF{H368}#5}W5+qj%kTJP-E*(AX)J5gnycD5pV_9|g(3_mi8RKIM`wEeksbF+1MX-&n z5^RY|Iuk}8d2F7~Men@xDOE7ib-oMW(qQgpX|Vk!XT_VR@J6^mx;QgwpwK-6x*7d2 zBpFyu)kOiS?#V@t>W3aT4}VVf6MnH=2HAmBAtDaBC6Y20I_K;VM}jB(o{XyOMg8d+ z0I#JA_cbcPl&fT_v%6>_F4Tik*vFUtib3UNOEN_r~Mc05AbFi4Azh z=?41JumA4sxpwbBPs_#4+3xTNcb!EI)u`R|y$CShziS0?>Ekw|Ou|sb7L30?XyiL%4m@G1|chFgxDSot+#k{FxOBls3){ z!T;*3)3WZx2_9uI$$6$@k#!jM?SwcQ%3mo)xsM%X&fd^77_nDs;(8K|gD}2s9vcT7 z7H2yJal6tHPU%etS8!N=;JnG6klgZ4Oe5}rFf1BMjFLTbxcWKtvW4Mb@_QPW6mP=H zSl$*cE8XO^a+^l{wu1)0_`c{hBp@f>u+uYk)Pdq@^6}+-)m1-OMcB zDc`@KmRX#@o*ODer)mx-r_m&w9KOvQeja1gaT>>PaBMD{?~qq4ua5p;XC`X->`-Aq z$Lb710K_ZPbPWEgtj9(S6MAJ8ZPgEF0{uZ%9$39Ez`p-a^=1V4V`YFpKB=sy)ou{( z*)(L9;X=G+1<;AZ(G$4wXY_EPy=6ZB%pWdnx4elzv3CeFhr9x95j2c;QEqF(%_%c; z<8pA3VkM-3y@JCamgZy0@C6067wZJ*@I9gbRI+n%_Fa^5?BBBEcL*IUi$Hhd4xv>{ zR3LaN=ebe=aGpZ}f5nnU2)&zuF#CL1bkf6(B%V^0{R{Tw2%&T2NHFX)ic9&ZvBW2g z;ZlyG=U8nsvHc^2IhNa@ZQ@9wM?F$eVE2y_CQzS;#Z41CI8w;41Ow1<6mrwu08AQ% zjHO-PKMI#WegS6RDfCEdiOawLR~h*$){1_?k18e{=je08^uHa|8FQ)d4T zB2f&u=jOYnV=i|Keu_#xh#4St7TU z7j_&CeJtN$C218exTds&;_p~e5PPliZTP>>(s!51V&CWIW%hi2op?p&x5D*ni$ivO z1bOFL&=N?3r}u*C*C|Oh!?h4}zJKQh?|KuNiPB$VoEtqB8LvM6%or;aTfTxH62}P< zmNfhsI!@@^HaiJxmr3f{WjNL@!}EJyt7H?=j&|Z1gO=Z8g?$_X$GinebG-1Qw= zMcpm*2=;9*XTPB^76qB#vb%-52Nr?fr6doB+M~fg@!R-!B^wTYzkweXfGYlltIjRv zc1^c%Z%l&AuA&#mOStkgcbHk!1jurN^T7$iIm;NZ-!l=*hBr3h1}F;WCkpYwzrpkn zUl$g2k1#xr!MAj`!Pyq!hPw^7|5F(m10;3RfxsD00Z5=O2;jim6aQ>3k2HZmTi>B5 zcnq4##K_jQB##nGu8VHetC2i@h4Q1@HHwJ)6n~01uD2pg{+@I`WtU9|uhQ`7q>-qU zx%UdL5u0F~s;Z|9wqfpw(FMlZ_O70EiRKT@^SAxiWY=;^UypJXo4{DpmeLwAyMlLk zSXG9}k0=aF;3Q&Lf~SGe$<)s95is083Ef*dZj%khRKT}5=K8rf^fKxQ;o2ljx=(Gy z>iK=>#m!(p91Dua?h|ZT$Z`c*2Zo&mT9zxIPV5=P3}rbOSAtHgpn50P7IR?g#7ZkG zOQ;hY4m`5HO#3JT6ge9IlRdBhQwJl0`$&k|A+GuKl_Yo4F74vS_usWy~?5L1sD z09AMVlIOszIAQ_y%P@3crRQCpLO##I7zt;Y^ZQmY z?EN`HXUo@+bsm2@7-X9(;atTh7c1qvuqV*&Xq6=OQFLBkL-?deahu=+{Mr4eP?jot zIi(SX!>zA}Ai>aB+6vEe--LR8JIHyyzXUc^6F)ZcoRjA%QTaPNrtG>1@kiz&bJ%EI z?rJEzHdh!mdMNayTQr+7Z*h);NL1H21W{=)B7oE&E1R<%MTaSb>Ry-Do~ z-ZMNOt?U{GzGoj3Y{BzTz!1MMY@XlYeu>ju^$F(>S{K50ML4d-s z1%f;3T@>ab$?sL40BcyT#K(7Qk>{U8)IAHpwkLsHjz5n9`G$I%_3O)oY@YuTkg1vQ z@?-$yH5KRO20`qpOsuKI;M(R)VMXLz%m=A%$-?P4N&Q&|;8ULx98tgE4~@_}C39n9 z_nGD_uZK5rW5OBl4#LAc!Yh#pRn#r=tt$0T9@ObV)amQ+&F+O5UZWXihxmH1YYWk( zpi|3^MxG&i?dbd12<$ zLWDVZB2G`hk1c_F@4%mj!*{srJ)AoKst&;Q6OAwIV68dL=ai`5^f{fK&E zM=}drEsRm_TA}fZt8r6OyRu`oaC?{oq?Bf~lQ#%%d#*gP6E2K>R`6I(K8q3ev%;t} zLv{S-%DZCI(e&x*)ODEUdCe_WDT}t@`ENkWxoa@m%?G#5YlJbDb@+2}jnK>3Nww~mK2=;Ea(35UQ%Xhl2Wed;5eYLurwZSNo zW`ltbBa<_zafN_%n@4D+@bRUw10KO``2!XF9HG6Uc3CeLwhn<94<3o@gz=V(t1$D% z8Dky=VV>=GHO0=1+t|T%$jkeH=3pXj=C@!C)(eqJTFBs7$Mr&V$Md*cYP#Ng1%lRs zCPqQ>bEw=Vlz6>_U0u#_He)?_$>tUJW}9(4rK+$WY$D%Z?f2b&*hs!x0M=Of9d5}5 z?^Gs?i42TDxiJ(qlbPo+tc}>oEDR)NA?`lx6w`#DP{|-R(=gtbkEoK92GpBy{B%@kABQ*eWzOS+?Smya#DGu4mJ91xNV~#%ajC zu??*3I4iR{za0BUQ8ssva->6N`|Q^aU7hjg7Wf&l#l_? zZwUsuZ1y4q`agNXBbNW*ml-dj)m_4$ycdQ0E#KgeWxKE-j9LZ7=!s?6R|Kk6+l3w! z6mnf@R&9S5uSmYHEjzJY=o<0{kT)=nWku`7Hd)8uCvPl1RuOBjh~;9>V+-;)j&3`R z98zJ%8|BI0CJC>qLl2dUaYBVd%vV|7OTzFhMMygjXO@mXfZdh{vBu_2gi?u$QVxu^Gz=Zh-Y&9Y zmZEmDP&a7WpeFVLpH+ZGKum&&79YHjjjENtRHhHXz*OQJtu8N|y8}B4;&h@)RZ(_) zEe7_P!X$n_Y$@C+*g{7@mN(K~(GDk$Z4jf`T~i*sjh8*vPFB!t?W$9>>^6zt0IKJP{;$@Qfw(X?jhw;`JZy$tRAAikOVMwvkZdO$@rD`4R zFgJm~ToA~>()KLu70gqsQ7J@r?0P};xk0oZL>i_P^`8srxg;H%8obH1N>}(u3ZG)| zSwg~rmw9>VJX&~`o$YuAk8T(02iSRV5VBd2{}v-tZ@QnmCDt?GaiTYs+<#{o&|{k9dH|h&@7dyrDF^0?Yug zzN&2!8?#40%_yj?{y4?0WgvPVM7s-wcw_D= z&=D{3yNSEj2)NG7@|w`zIGmh#WhXTP5UmH1mITJWCdAiLK?yQ}t+T|tL9p#LtiT%@ zD=9!XfHVA@k)jbwaVF0TH!E3go=I*6lxZkL%n8!*0=x(#cd`C_Tb#!pvYgzh`t#{H z|6&WSQBLllstat&>zKN#8nMjRg=k~-xGstvT_nCAsYmqyH6-Mo^e)ozArR+{MC(Ua zr1dHqhK^MY*sAc!0H03a}U@f;bn1vXD~B zXXgC#Eulmf{FQ~K7sU0TuFX&hHI|Pbr^fYd* zB}@Oe)|vrcyNH*?N&8g({)7_-w7x8Y9+&oSnoQcx$b2v{} zPU_r_@BET%+1>FKLMya$I*B?#bBd!@cp;C92nGxc3># z(-)Jhz~SC|EOEp1hV15>LYUHEz1@{zQt3dohruJQXyL^ciN7EAC%z>_v^e!59DrdD z26S>x=WrA1ojmqPq0qvZiB(}@!&}`4gUQ8%f=v&!r|G2muvCx?;K{dyX!Ex(vY35B z=Q|ZgsOow31ZBZ^Ejd*W#tKE9;r+3k$K62U7o#0*GSGIOk+vF7Ra-}h#8<*;)wM0a z)JmsqF$7%z@O&Y(&8ewvf!V1iFg22RnjMg~nX0xvRon3f+IFw0t)Hi=Z3cM0W2kMZ zUU(U9)a?SW@@;54+DKcwk_|1KT5C-uevPVaZ&h0xM(5<)rUu%c&#e&&1!j$>s;wJ5 z=c(GJ2UKi<*{c_B!f<;UfD(jxvE)oHYe-7$T=i|U|dpP)H zy@U8YnpZP^Uoz5KW1?#91C#Em)_Q4Hvo0cREpU?*z>fRj<3o9J{1QQlNo!tCnV>}T zaRvtIK_FPWU$EUvK(45VXB}FrA(2Ek{!IC0Ai6}^13uY+uU}Bmo6r!bVjeXxag<_W zJ42qTiH=qnor5Q9`nJ$cuX3qg z+Dvt8Mt#Mtf8^GToFhIt-mAG)RYY@ZjKq&IR=G&8a&fH0rvbU+eJv8~Jv}8)SBnIV zNOLRZR0*oeC-BiFiUgmk@+$@^FE>(I$269`Gkf8)`Q7=z= zb(J+DRb`q3y#S)bVgzrjfsX%p4I)8fqUu-%CQC?1?;)YnWL;A%)$2%elQ}@r7_t>S zM61qTtoKZVnrGzOJK_0d@E8pWF8UCcY3PyD{5|p~iZ<06u_{B=h9)87AY;m5p*;;_ z{0YilPglndjPTO|ER9w2FbP%hY|jTm`=Bytz)Chuua-2tdN%F^yx|pWVheV{||{ZaEoUZ5T4u&}fyXYBY@t|HKH2I(F)O{KD~2 zE0wjZ>`TP(6u`jF=V?+x?R?x&lhZ-3)#P5czb0wO zLrxuNP?N2UjM8MNMmdrsJ`XZ#)}%F9XH;>r#CrfVs>!*Bg!bm{KDOv+b&DiD6H{-A ze?+yYMSw*a0Tvaj7X9I^8JkD8RgDq+-q&QP7G*%j7(M3eULJ1v1mU6+x(N4 zU6?q%Ewk?vLiEkSspn+thb1s@N<4xVzK!&*7G6&p>8&wQ^>%|v5SVD=M!$hYdTFNq z5`P7q(a9rd3>&=$ab#_vGt@BlT;@<`*Eo1^jsz6SellVqS{0;!Cg^cW*sL$Y=A=~s#-p|S2SP`jmDjO~F&w$f& zpP|VI8|Z!dg{r`)$wbxLahJqDtm;h(#t-!Br4^5n_(=fv`5aB&w5_WD^Am7Qbn2PL zNxU5d)c?`vd8q%hVPZ=C-v?W3M&JuZ+G;#iZ8N~LqoKBvUU=DfETaNA;uy4jcWYIG z@@reFC$LSF_nV6~2p@N88HV&tK%2JNRv&%|*b?g^+C-4$Tb<^YRKs1LHJgMmdRBa1W{ zszpA?SY>QcQ=LV&$r8Vy7K=`N0gGC0^+!Fem-u~Cs^^s9l=ul`7Q(7BP6;cAI;{Hk zg_>dY#ukG{pz&1ACJbY?gnkoc|yJdUtB@q$4kaOw%%(=ZiLwS7m` zwk$|#1UUxU&N9+g)T7U{#nsn^jo1GWH3VbNQ2G*WPJ^v9oX&o%!jrZ1aqmLz%duYLlBUUUv8^3y)v`n_-f#-Sj=rx<3 zy}8~u^CbQ|08_t#wvv&ylAa)AzQi8@0ck6$+M3jea2ROY#zbo+c)nz)ZK+Pgk4 zEtL2>0i5w2)VsP_?o9OR73m3zvv4aO1mAxr*dC%5%h~&Q4rW$M0UD9Ewj)V=42Y;t zJ#6#$skc4l?^BC8r3czVCRgiI=lf00R!4~?W<^G}HtzC4h6ysZeJ^w+3;aN93vzI_ zHYT+_jj1!bzKh>07G!f=U(X`Nf|^9yQV)o}1rb@`4zS=;&{ZvDs1{5xupr6E0!=Zk z(iY=h4`kG|K+;>_UV;uCK+BK97^;J8uBfl4Yjq1WBGrP7XC!{PYC-n^3o-*N@TnHm zH?W{=V^!Gsy`;&|S_NdxfDCP1;|G@NEpRNuP7naAjcW+c#{Ps+!1Yb~QGlP5HBwib z?iCW>hs;9bK4n!>kqLJ&Dc$eeRI~Nu7@48*RLv*@&lvF3QjuS{Q!hMYmBcp&aMmfb zp1qr@5~rWQt0(Y1i#v?yFG<@?saIU4^RnJNM zM*s$PPLGfh>L`E|c|(?LK!ZmRm&t@`-)jWr|U&<2CR)_AJgI@U}4XhUtC zdf~+k14saOpN6(SZ#0SsJ%MSH#K)=H9*tGv*QR!*+YPjpjI{NtJXLKoz_X#Dwp?qy zt2Sc*i5z_347A;5q^(^~VB0G3KY@UJyHwTIp=#?i&^FabTaBlxts6WKfoIM5_3DM2 zyb}KgfPwLQFDaqMFDY`bVuU`TxG0^~j$Db~2tH}QAbz6^wEmkJMTE*k)!GLplB%^{ znxvOzdr{(N0eJQo_&CDI$EA9LjF+&U4FdAkH_Lv4M8Jz8f}@vBIDpdydXRy}G{2Y`1NsNCL2WsRq*vTcvV z?=e)lNH5%1An{uPOgIOX2P+<>35-8YTVr(Emc5RIr)ry^)xWB3Jp*k^*BeBu##7bS zu^0CP4Yif@!i(QP#|&WF@6fiA8RV}bJ%OnZ2~XAb*JveL-Kw@ltY)-sRuy|%Gyw_>}`o}4q#wLc!!iwGXg2{j$%X{(N*zr z>iO9ABM&}_Ja``SS^{!Xif83~j8BY+v>_pgegRR~A4nsjfvM@LsfJ9n$bT2xfxtwW z*Xoc(dL7;G!4@FB2;v7+M>{ZYr-4p?1L=`Q(lwr{^fK`Dk@T95w(1<6aR57p0St6> z?*K=WBE5|qE$R9AiZPJ}pJRW*XV=!(43FdM6^MuAk^VtUyf1jpx+rS#)Y&xyo z2PJ+4fb%aPm@ltaf?3a5Pf&aaGiDHwkH2Z7re4*@uN!Fltf96lPgPsnVeD)(*0!xq zTi+4fCIoQRMQHo7k+x1fLD|QcF)vWGU8`#AQ?;FGpzSatZ8e^%wvJCE{y2Eb5ux*K zsa|;TQQUn7aN8wlE3Q}8Rdv2~VtYR-M{BF5&n134X^R=uC}^v#t8RGQKZ7cU_OuEa zN7`4L1OAtzq&Y(ws`eR>u^ckw`G*dOX9@z9DLW?dj{_Ju|4{Ml)MeZXj(`TrtzaD+ zJ9cRX*kn5{@#Dc}bUB=G1MV#sI_MJ(ZR-pm$oLZdFbE2Xpv;J%NKfGV8aJCk5PJm# zM-+lSI+ZwVlnjti_Km~`*J9b`E0|fmw2s~R`1ICUM8w(qc~;FsonYRVTpvEKw%t=F zh&J&D3i7)7(kGPqH2s6y{CEPE>UI;3vG&+GcI?zNr1$otoj)P@HlLd>0fVVmvC-BL z$tgEV$^d*1z&%&7LD&#zPn9c_dD*#@slOuqe08IT$Xm8B1ROOiG=9dGw_^-Nj z1aKaJ$Ns8KN2$M}vTb+s=>Tr7lOuqM0G|CD zDFPkJ{Z7dbpdTV-TW2wrzh(ImH~JQz>e4J5bfLL=8pn6 zA3(Xw_V?}jIL*j+^MwG?&SKeU=Kyx%x?oE%^nj%Jv=~HrAo3>KDzi#m(OfV4#6R|EbMDJKjEz zpz(od2#CB1_KLTWf!BiImQpfab@R#9q@1Z$ilj&>22m_Y!QN;Oq$J+JlNWGfiCS6N zW+kbVXq|+6kDG5q1gI=L^Tp@=r6iS4am4m-EveL`FH!}9{$B_p`U6CZ9n9H5NNnKM zpN^4ud(aJ`G1X;FCR$wi~ZLZ*8Kn!I$dK4PY*SQ8()l?bz$)p94_5S%+xT8*V-mz(R1mWgQg* zI2}N(j(EIdh5l#ac#Ar^WU+Fx>ZUi{{6v-h5u!yM{bAv9?5Lv+I8q%=`LB*TDh89= z!Q{FBj2(5!;#H-+<>q?`DOr4s#F?gt(92}U?qB2 zwPBW+ka_mjMdW@P!KWu$7b?mbpjJVSeQy3lHJYiSoZ+g|z%PmwKF}PXt{;#7^q5z^ zZjX5DmYMO6n}3<`YRjC8H}%l})i~a=*0KLsPB@_7qS9v(Eo!~HTI)ZUm0BNd5^voy zGxodr6=0HO66KLVP3!DtMH+w$06bt4<*`L|U{%7&c-PGf0EU`t<5;9}1n_PEN0{s4 z_@0{|1R$%GqurwD2w*aRC&BTS4KCw-H*W<{bNzYM_092ardzrmyJ2P5gTARs9}F6D z{flrpHMqM}*JoMka{U1}fAcZ)Tb9}!We-xM0r)3?7cF%;s>scM2ViPYZ5)eKjsSiF zU}jKV9E;J_19+rXj?Q|DjsWfeFt}b_uK&Qz=K!d=elEEWQNOh=*JBH)?0V2IQRzLZ z>szX>|InmF{hoStx&EM=p93bR>ec2bXMIH)fEfVB*00M^AG-NF0i034HjZ4d!V$oM z0Pe1n;~_Vn0N}M+Ibvs|>=6K?0PGW7myU(8i; z#^89%=7BAkq)`Uwe^%)S6D^v@6Q~<%9_`dRN(`x^j%**f`7gj^N=R)Ul~ic}76Z5~ zqz?OSAG`Ti0X$zTN9=l(^#^b(fCξ`oW1Uj^X&2DRx}q;do>6Tm`nq(Nb=+0%9u zLjeH&L(hgRtYNJ^PeWN>H;Bf8h#ulP{3!ZS5ZrP+=J?djJ3z3lVI2mVK6CTk06bq8 zuo%E70Q;b4jfa5+G#6cpQ?;6Mr#$+MR#1!!N^x1dUEBn~$M zmRP)sXg7fG16bKqY{7~fiD`PY6;EPArlnL>v>~?B03Fv@>|qS#8p#&Xvq`G}oZndN zHAvN3QB>n-SAcE+=K)By%HhHKU+1X*8`&$)sQ=66lowuXEG}%I7b(fQRhjIw;}Oo; z7}`aO5k^3GTM=0d;I&yu_mSeWvPaF%Mr=|`vHcL8q6+&GOOdK*IySO{3Xd7cQ;aVX zxSVN^pu8849$=or1>y14LH3F(tJ&d}VrPZ1wK2N}#>VOtHC9}8J8mn1aat>}mn9h- z=eH7Vmd^OIxs}+pqpXv)383cu=Vl^F<3Vy0UW?(~Z{NppZDYc@4l$!1M!(rgbjd&0@k>+aP*sXA9iaOLbj;pX z9LMad#SrFgBX%NmKHWsddg&TIGxHStAWmGWoGVh!eV@thZddKxTbb-kXDOQOAnS z1r{suFy%XD;Qq=Cd=D$xUf~^TuXxhV<;ZWJ#s6OTe_DQAiQc6dkw1F@J5Btr@c#pU zN#Sq8*1*LYf8>{sMyvesKNtT4`KK&k@5hU|=B5kS1D(Z{=0Bfc7dneiH*-(MkP$C} z^g>4;9{7)af<2ueKHWJX6X!>B6%Fw=6Ypqy#a!_7c2seA%KPv6DEF~f49;ZTx`;`G zvY+5`ni7_tlIQFxWfrb81qxRh<{6$W_gC3!hQUL+ojgUf?yK$PnvML4P|fQiwl@!d zyzrAQqS^ESQCCrTRSI?W!!cjtXM#ct^ni%c(GU+UqG->alW5R`())H^p2xa%6Jwe^ zzEF9G%Wisy%R!UJHIGg1CU!O-Ucgp%6IZ4molalU;5y^^=H__K2Jd~2UblhFzSdrm zjdt~?8CEY=c#`F@A98bw@%lh|zCLFGytIm~=_ZQoy+kqAvJuQqC5o*qlR_ra6vK#V-RM z2SFc&U}jHoSyahLE(d#91%!TFiUSg}rUjqPUT%b2rnWmu!#zphi5$xVx zVvPCJJoaQSab@d00AD3;Xge!ZLLwO0pT+bB&NYG!q~lA7sNUilbIJ&Ifyz(LV@>*q zxkCmA&`fK|<;Cbx3zG(b!OkzR`%4_dnOH-iOh(}qAeqv0+M;`-2 zgzc-3v4Q=>q%0qmqo52LH8rtP;*0+?NDj(QlsQgn=1ny1^B&|pBk$mHZmXtnU?O-s zv05U~nzfn;+^Z!%QB<0>Z!yO%_CrGG1Lac1O%o_%sQDn{#XC)L#!Q;ZDZbc; z8^;KqfhXz%P}A-smgbG*ticO=1dn?uwMp=;rDimah%dUu&dXtB=M$ zN^IT10gQY%82EpCD?K6cpqF@`x*smX`M-O!&qs-;EiaWKx#`jtnzfG~@OD5SX3hpg0 zTzs#XVKRT3RQT&8@pqH?T?adUzu24Nvw-u4dw#~Viu7Oge~IdUbmmF2rtS~%#29?C zo<|ERo-9V0r3cwhlf{@snFF@g@2G; zPL&EyIRvt`oI`shu2U>wUWAtu?K5@f_OZKO#<$wC3m*z%e@qd3_SczEq^B?b3^N^~ zpJGq>c{Xa5?v&@D8H1neLE0;j{!klMR49aW*0I5N@ldW(!-stbMXDN&A7uGXF{a5$ zVn+{QF6KN(rn9e|VtUid)BPg$;y){KJ=iWu$JwsuOgjsnRXO9kgE>CD$ItyFTa+Po z?x~}b^mJ})FnC<0i&5!TKM9G>HDWu8KYy(j=_!5KY2XB9+yml(fjS_Upfft-JBc5r zifG&2-*hBuI`Chw?riG=Xc?y#u%8|f`&s(kgJv*QjJDi~P)?mH_M!$-z}X`_FX2jT z(Zdm0gKus0SDX^4A$kCWlitY#Wgx`W!Ldru7{Kp5V zLN&UkEV5*&4jF%=v5TvO*#tmVd!W1fwb!TBC5@oWCywO%TfL z5pkRWt1#xhWq3J>4s+q3C4OucX$FEXW`J143-&N@ma9Z%F4n1>!ps3?cH#y4*U>3> z2U$FKL7`nVp<4x|Rv9Zb!CV!%ZDg(7zes#HVgv%ZvHlp1&Z%cYmcOM{R)xM8^f91M z5XDxhhQZ}jfMo!NksvUBf`mZeE6`RB5-yr$iCEP$W)LlF>ibpVZ@|<-QR)9`wqr>F z76W)5z-yw|UhYV$a=&J~Jx1o3aTaT+09Ms-X$%`NUF=#55w=~T8p}ZRK_C%lWjjFB z%TRaPp-2J!8(usZNMyxcK*UlO8#7&uO0_<;fk$l57*$(x@Ddy$2{t)_Z0v2>lm}~* zU4)H!Ao77|p^gY!-XMDn$?j;Zwq3E+bPn$w2qg6?r2W_{wUVk9J3u-*kkpF(YmgfE z|FhT)Hhlxxc-ygK4~bokBSp2i7(_M@#m*30QC()M0Z^a@f40Sn#dNsF@jHg_#2v#K z8E0?L#2I3AiXoAjV%;FBL^G`-!dRFr!)pzBO#UAh!%4ZCGF9?okpBVlD>IaATr1FY zUgEzGlw-$=t}5sAKaf#lFG zkY&iCiae|`g8mQi>@!om&DejcDLxQW3ZF4kNdq;dsM^~8l=wve?w%>OGUixBV$rGq zoCV<7nPQ4;KgY#;eAqqRuN%_TP~^g)x?EUOBBm9@sQ3czn}ZSA#Mu=dmI2@~2t2Tw z7m!bD@^H#L?D?jPc;O3}3>gB#G!UlMK`1H09iZz0x>Jvc5i<;H(W?O60LB4Gj3;0{ zFb_u=U!;s|&8391aQ~DY1uO@^)uu&(HY&=7;#d z#EbvI>VGbQ70wcew}1O?NX>*vac0j2OkKSev*%)e91og2%^Ko(#^iCbVo8h*r^QO| z2(DshRfu$E6K0DGZXKWH68|zrg1%X}a}vC?8Ku-(TZT13t~1jWiQfhq?}7A`*gs72 zMlwV1Nix2Fz6}IxNysF}0_)Uea^9|0NRcAM0h*KUAY49XeJ(}tGL5LN++TjH0LhY zsY;nuo@dx;s+CV1VZ^2!FUTPuJ&#aSTA08tPT zrD9zjQ7um+GVK*nwYyF6S}7QS-VOSzP>?c4KV*+81MGeSF4e*-tEz{S)OX2%S((Z# z2+VG2fnAxE7lY6}I z`eIer(%X|8XYu6WJYgnb=IcXn$o(7W;_8YVfr~s>W_rEb5ImtF0)~O?ShXlE24?!~tGEsJtB0xhy|3yTUB)e_>|t zD=X#$vyX`xJo6+z?@M0$_5romM=GW9(bfc5Q0& z{fPPhJV46#fkz&AP&<4H!MXzhD0{`;Q%R%frKlWa#;_xGffyaRl_a1wZ-lyeTBW0r z&RS4gBUQ%+88;+;KKTG*`XUunRSxXex{|qdMu*asxWQ|h%IgdiQ4?{Nag92auD}PP z2}A_#Cxb}#88g&XEV< zwCVN~4;=+8N6=A}QrOui#jee|5NBk@uCi2%C;0)^d65{~5bpHS9UXfL8=WbRnjjaH zoR>{~5tS{HG77R);$cd-tNO^vkful-If3R6(9p;!&Jd`LoB;fZ>Vif=#z19M;|8z< zKpNG^ICbUa>^Of=-2`Nq+>^f&SnW8 zsj)5+L(F1likG&*iiA`OmU#BmBC+``BgSWO^Zm(H)yCR}da4mq44OpH)EO~l0NMbo zGh$3ZZay5q>Jih~U*pCVu11Uv^cJG87BQ{;^tX-}2N+x#|No1a4AA@v8ZVYMPSRF< zb=Q`m>%3i3<KtZ@f`nE=*V;~4GAQ zLp?FT99<#~m{f!=*Ti*EhOAt&GM=$3(|mdadMh!5O+)BG4_X@v!{c*fa4r@958|d{ zs=eZ4+Jk`qw`13g57%>X?)qpvfcT8q%e?w=w&@wMZL|9x#RvpnP4Us4Hh@DPXP-YK zb{nEo0JAJATb$}T12z(8kOE-ZKvN)(^DKuzAC9!1L~Ed*%w_3I#eP}$Ljl@0LijZG zajySJIZ_r%aoFte6e-^a z&fm=ZNd3gy9_8~{VH~@$R2<%0XON^f$kZ5jBvgY6Nx=jtf=>CKDeTE*VtR))PQL*c z>6t;a<_O$lp;RhwGeedPn!-*m6M6HbsjT;M@hx-lWOiY>*f~un7c);PThy8~HN(4u z5s2PU)o4@#eO-+<4iU~Qbzu`$h`q+@m~iUwR%PM~$Etn+ld8!9r-hF;99F{z_&LCz zS|QFEr(>**n^ndc5ts-P<0wVD8jLl3ks21j+ky9Q^+q@wAMh7|uM)8#Xw&_;6Yc$OT61=3wK&pz%E<;kD;{ssdJ45N zlLvS5E3V$pV%CV=!rLQu>d}q>%1BZdj}7H1YsB`cI*~=HilvHGJ}XvXNks%NZF(r6 zK*fIq9)j%ycIp{1S{Y_)I&-~rHqs{m;#CG;;8WRhb4A47HP_!-+M=~QKSv3uhY$qV zyKtPoJ4ccIC2)Z)g@@MFT1ukaR6YPOu&F#Y%DAa)nafr_C$^4~-GCLrjdy|}RgSZ( ztT>#{4m>ADC)3HQn!s$I$`*A=Fr$OSpCeZgVX2=mEL)83V@Rkj1^Phv6$lSZ!3PCl zVlEASNszM}o0^TMN#sINH>Liu_D5w4mna{Dtje*TT{+fwCbIq6Vpn5{UZn?y^6d_PSqe?sM0l+icS;s+X)pl>3Yqt%(8tux-sLyksorV<$AC1s}Q0Ddwl z47{wcm(H8>3)pLG#c*R=ixkpgkd7o#(CvHrEEl#4R&~ZI8z(s}uoKpzUQ@eN;blsY z_!N~_=POmC&Vk0dJJoOSfT#-*A>(Yli=3|7P)gU$`A^ktgAXiP5(}8WgKY43{+CQD zn=W3KM*fybSF7TspOzbcshv<&B1-JTWR9xitS*aT9$(wj)p)f@%R+qMFHM>DSo3sV}X;eh@mhES1@`bsov2=CKy^8y6iP%J{H=Cuc z7h5?EeXbH^fane)I)ece0{sb1eo}y!lBS^B&GsQ z(BXvR8ancQJ>p7%CQ1{We7H#fofi+%Cp^l&{xJatbn%_la%wtzl)qu47=qc0-o;c@vu zpf3!!6iFZkB|Z!u&G?q_?{^@O7At{darR|9Hi~6qbxf>g9TNveq63KuLP6KdXy$5o zyhc`Dtp+{``0qD~!^369rF}he=z_s+Nbj>*9BvtjVA;P}jA6dbVx(oDQkvHe_!7j0 ztbo}mD^jAFozVifoB(8{c{AHEsm1gL9Rtx`J-Rp&TX2BpU^DZ!pKePC1efZ;wpLhf z1DG7e**Om@`D%JQ8vFT`v06x}DrM;7Ut5R*b;-3+JY!QP(nP~XydVyU?J!aSgac5D z{m4%u=A3436_&nAY+MT4@q%cJZBY&MP&Lq50@beuy0;pr<5qzF#!1pg6L&{7kO+|F zSDak66??Tep(^%o702|{nJMYbw8h}rESO1?M4F0F1i6Q!4xBBgw@(W6Pm!L`9g8f*$c4##x^m7dZrRuW10cotA7poN+=S+ z0ZjP_V^8rs0L)%|BvqTS1;nmjI9@wIc#EVgyE-reeVc@1h^U}wQBhGzM9qx6F6h@4HHo;R(kMDA zE)!6Y;!@X&yhT~rd$*9DcuwQl^LbC+Z$Nn3t@^wY_m^PF?;x##ZZ-a)Qe zjt`5nsQ^7E@k|qDdJf~-kXX=T(2sP@k~t7-5cCnOMIs05k%L&3w{dAp3VHeZMGDx{ z1U5Dq+oNV87VNs9IdL@Vo-H7^3UOy0q&Oe2Q-FPPRj|BSArTOc5JJuqLS`JKkQlIi zfE~7)51VogmlT-?VMh=yS{)n^avvo30Ok#iRG;Bwv!NO77;$sa?L4kp>NA^lg*d;( zCj~xV6Ccboy8nHkH(QbIMjlUnrJ_cU#LJ&hX|eEO?isFoLX`jPoo=LKDdw#S0!Ly3Y&mInzwORw# zru&g#H?z|t!NZD4ZPnjCN=?`ics2hK98Y!6q#eTX=8{K(1Im)%$>zRQ;SDk9N2@#v z>Uu5GH$H-x@ACoM0hohVZzO7Kg2xmIUQugYc!L>!B-mq+hFLok8-`d|3g3L*@CTS} z!u5eSVn86JuUr$ng7dUE;d>zJw>DVmNPGo}i`E7&Y4<&`n5=B*V~$xH>}|GwG*~gJ z7->|h?8pZ`8%vGi2S{r}b9tF_QUUL7Li*fCgOyqW56d6Lk$;;aW6iG~4Hj!_@#?on zgU9ocLL6#=i3=g4^k2h*A@#*-H^jlAa2Blt5880?ScT^Db-`2k52eW5ll~DdGUwC= z?`5LUf|z@1VbHsdz~=h;;CV!kE~`WR()GbcwTS%+caExU)kbslE~AHOJszB`tveD& z^dAqtq;c|OXY-k-f+zAH-Y)gUPY0*8rm@C0mFv6BZ$#G7=Yx*rRS0^%8r+K^a%+0~2zcUa*7!U5FJuVQIm^%}}@=@Xk6oEp>r$BVoTYMuZm(a@zRSz!Z1)-SG*QpkzyJ}BBKWZJo;O_uVWuukF z+F5>qNzTUyK9%4@K6D5UkI1Wjpwz!|g)2RomH~i<3lPmirvNBA@3bObIH9fc&gJFj zydvP$lXAQTk+_grBdT(Zi<_oKbN6CGV<0Rfp;+&2;GKJog1hab`AwXMkH|6Bnj6tV zZGyl<@(L6t4uEhs2!)AjRE1(1T(v(#pxLS2`Q1$Se}k6I}1@tNi+2h zUueu#Qxr@J(ATITMZvs^LapeeuyEVF;>6xLef9PQfuVBwPi9b6BOT-KY*#f` z0Z}j>FndHW^MKj&c4kR#iVYcNn=2VQpwUOw{8}YV3;n%NegbTjE8hU)rPNjDXp{!0e~DgC3ga=4Qby+@?QHUy@YNDDFN{ zTKJ`n6Z-86_c7FZIvTeD6Vp+Zao3aL}1c_+!f}B?*z-| z{+#TqDjb`z)G_)Y~7=+ky{peN)%5`!;G=@GHymz~K^Uc!kuL|Kj zGc;AN^4_V;gc9y4SO!#>y%qPs=!$F*(v~CbP&>wJ!{Cs}joBEaU5m640>c!H7jiii zB&x&*Mz72UA?*^Rx$T1dHbKgu=y}-~r0GcOYR80a81JB{KMNC5kT@TSZR{Y+1_}>~ z&dmZTNIMp3jrhaX-%ysLB+JnTX72c)=n(?rZ^e2`WO7i{hcwZtq3LI5ZbG%Eal%C^ z%7rnqilPxXl?M|?50>euIM~FDS!z&pw4I5YAKaNGcqH=ifb$WL0!)T-`G>dwrnPr) zv?ph@+oE-A5{R^Jc7b6oaFi5?T~l73MNw+eA*hm8dnLBD9cyu{TVNxE4Uy-^i=r%` zfaP#-^!KS*o*Ew<{RwFg0+=?pzld_R;ZnrRFa_}CRTbN}28!`>M2~~6mZhVXQ10b3 zY8b0cBzysurp?~(1&czjOvaTdsMM&ib;^GaZ~Ov-0*0{FKd-1aIrY!YV`~!_j#5u3 zs}V{1{xq8=;FZ>dJ!5r~s+@O9h+TdF&lpM#C-r6z0>~7w3e$FFHuVpQJ}Jz@X1ioE zq}3wrx&pSUjuFg|=$dRAq{Wc7M$#bq|A913NE9{_??K|5lE^)WmP_mYGN5_#F#>X}cyc|q6EC20pOWbVMADAv(n#hw*>?v@r6 zuox-d{eXg_#RY2E{Ir9Q0r^{HLTnPB^%cdfh>GDt8rhKwk@}*(<>7|M-abJ5OHmRX zq9sxo{D#2s!^~qp2=<~eI|Jc=oy#v;-XtBNKu?E-+#^u(%RazL6)PnK-oA*;TeRd2 zCaX}I^t=uZ%rqCw@29g@#b|BC3?}gB0bZN%ejJ=w=5j4^$(|Li6y-J{Yo2h?d60p7 z7fuuH{jlhL()!*G(XXXog`0$$Xs!tVy;T18^4}r(JIsGC!EdS~%RWS3F14zs3PaUb zXb{8dN)_eQw*M7wE87R&kx})f9`MCi4)BVCCY>xK)8E}B($Q?&)4Rl38EsRNh32r2 zuy$qf@-Sz86g=iMo)vDJ7&breh3(o>D+Eacp^?=15M+U3Jc^{J345xDgkm)KovxxV z+i=jE)^!(@m?Js{3)2}tU1r>!DUL82OuHJJC{7!O=ql7ukx3eNSK&Yz?Pb_$V^H%H zas~YV2maSisweor#d#f;-c^kJE&K%fl9izUcDw#0XxIEqzJECs%M~AEjK|uW_>|}_ zcrCS%t}fvQI!?G11dzUg#vWMpJApkPuE;f_jOSZ&%)w(k)KTH;li?fFKM4+~5Jduw zusbv++%W&Y7;^EYa$;cK_(`ywR;V)El9HPU`WTA|J-Aup925FndIWf|dI$Ppp#SX? z?7g@!wkq2ZoT2SSp)K4IJZf^7R{j(ohVg~gbttuWEX_Zf@0m^VHopB1A2ml%Bo%J$ zeevG>dI#>59-cs!)u0b^uROOjQa)OfyPsD-snD zVt!BUah(Fq=~*(Dxz9BFTp==}f@p(_!GpEiWDSvaKGJA}#7r;73paDRMQ-&dp*c*Q z&J8vCih|))VKj<011aplbY*+8SlQsGCHVN^>}my6ZT|byX=c^uSc_v)_;9+$e_}gW|F;f@4As$=+g~Q?EFpcrs>$Lh_qv2&f)pHUN2<#oOSs z$KXosG%IUV2QsHL_uorI*^(dN9g2rFCZrnZJEap30TY1C;wu+*uRms2u%D{6h0Ke; z44$I>G6~Jpm)OX!K(?*R!W+JV`Uk!Y9$r&Ij&qq%o{xl%Nj#9pBXFL~ zl7wt8Duxf0rLPOO3_&zq=R>;!RDoprevxjW|Du>&*0VBy91~rIAtKtdE(3sZBYZ~t zU$AG_0c0c)MksScm>gq{q8GigU--wG^YNlbarO&Dj$BQn&zjnEN(w6w)voJfp8rj-*TO$w8|E&< zmBntfO~1~a(YO-NFd8;J0QAt z6>9CP@HEJxe4@Ps3I4}3j( zL70S99aK5thq-__KU3-h{dUl!Dph;XjZj%F`aU>d5V=r2w4!?Jh18#sJ93JN89Q%N zl!<0Nh=(;!fW+lcb2(S@TmX^+&=&yFfnY^tqFL|*3cNL5R{em0!Sf+cir6d=t?eQZ z9@7rRNLBtERC#I|G}MpSYLyJI%@v-+^6gW@4G)nKk$wq`MiPmJG`bnuu}kyt`+U3$ zxs=^uXt=g=e~9JjTO+(Vn<{YjchN6a+~O| zCZ6Xa18|-6%@%PuJDmnrI$@U+GGs4@BJTp-U>;!?dN)SYj&#?g)2w=<(R1P%@ z_XG#DXJ){0ygLKtp?iV@X*6C#Gq$%t%$^n7Xq>mqFz=z!8~6%AjbeLGE=K&)j%`WD zp3MFFZgdw=hVd2Cn-M3$S~DTjJ%uipJB4nqrLhi6fUh=o0s$*mQVbw^FB#DApV4~x zyao=Fp6kDIqCztimYMmm2;F|yEmVS!QpnWXo690Th<5bBWKrqNTv!Y9Ec))nH_een zOU^xEvJ!MjbUiK7LX9f2=7GBIgUrTlwrmVUHZntq^lYD*g-k`RO>MO_52XdrCOiNh z3hJ9xJX~okgeKHb)FYAR{4~!eq7`W(p7!dA=B4|B69-FcO_J8akPrpM%1OTadAzXi z@F#GBMy3t|f|ZV+6|DpDWg79I4N)o);atRf5)r!HhA5B-D;M!95Yk*s573ZF;@W}_ z{$9e(hsorID{cI!GBW*>$YllEe~iXte(E^C5L<1LL}0kV!4L}%=SYTPUEprCcjORz zQGRJx#=EpD3py&l+_qjgSe&11OFUMI03LXl%o$U}#(+9!dm0_Tp-QPJQ_P2cLTk-l zy7>ykBB9x9cFpiEt(l<9t65xV=H`dXRDAe%7x+08v*Cqe-B7c+@GQ+rO#jcpR-yso z6keg;eRlP{Hudl<9Y4o#?k>D$`nh`aN#GZ<)wAJ+dLc9zIqF4e@a`yOxXo8MTg7aN z*76MLHvXaF{jc%+CK(>IY1M7GoPtB73{ywp5o?}JII{$8Bo8WZG(cwk zufd+Ph%nvVNT7)Givc(szz$Rcs3))qRYWsME0=Q(F6k;O=VnNSQA-|VW>6d@C^&0_P4S$tc=+bvgGXAwWH~GxZ&}!XgDfd zjn=MC(FV8}jz;JgQr=uR(SwE{$isDoVlHwElHO z7UnxyOKe$^V`H#Gs|s+bQ^Hlza-eaM0JFLuR5a=QH>$!je`93Jh!9msUoN>G z3lua$OX1~zup!Cn3NoiCih1B~KE16IPO{DA7v3elmzVkwU!R9wFn4tc1t@50^dCAk ziB(2AJHhgV$V6J!j?v*(oc{PYh5s16$#)p=H!gtrsUnIokX>GgyR(~r7%ugZoGEx4 zYoRe6g`nJ!f^6;l<8VWGGmc2?VnvirpN8}+kxoLDFusLApVyMZbxfP{2X+mJRWN{=p7 zGEL?y$uR+7-b!P7Hji;@wCjc?0DxWs=vEq6!myfOW5!aEFZ%5YYjZl-4>1 zo{KX)yF0Uu-BDut!(H3;t_$*%RGLi+Y)%843BrI1497n7*R%@TG#2oS9iq>0g*UJl zxb*V;?htOx@*e}?6cEZ8c$0NSX~XCfpdUl@w02d*gEI1D0yB0_pZW~fQVjrr6*;~o zNB>pPYTy7ub#F4RY%$yg>`?gxv~Nwc7!0rZ3z#y#&oSU5WzfomsgbApn*@(hN~8DG zaCLm_x{IuN?J!QI7fL(xPEGgB`e_Wf4{pUSmcxtOn&oZBxT`zE)qBB}xSyHk-Yz;1 z4Jl*jZf_pY^Z`xSw>@K$0+SB~SalDGDt#kJWlFdHJk6WQsQKT!H7B3)66qJRFGB}`x+%Eg+?Tk9TLNY7JlMPLly{{oj9 zBZu#{)<@7ndM+WldLmSJg{%FdY-qCn8r*JF8x-hfHn_lK54{|X6=?j1b^SUST2FRS z-4qCnb9)FDqC<6mjN<;M;tqRBn;oJ<{kD8ZAv$;A_h{fqPG%S7WwW?*ur*tJQ{4zE zZlh12{6b<0D+!l>Ag=|u@tm?jr5AYw}QnR9+K0v%FHD|Tck1B|Om8Yi6T-i<^k$$taon9$0 zJ@7$7eMtIEReRf;Pp_YPt|a0&Se zc&|kxL}B-8avwAr3U+x*N8^lKkv>4H1d9blHWp77>GyJe@ltb62d)g5_b``t;A++> zc(cj==79apsE&H&5nQ1j(SQCpVA3&rTAk%-y`qgsW2?2W|0i>?(19{wK{=F(c(3R_ zyr=Sdcdq$FM}6d6!U-p$xN)k?nGtxsSUn2G)J!IfcnV}cal60oJ9Q31# z^>WvvCFZfkdLJsGI*+@zIp_Jax|=r_>lNCsu*&*ky;A!c4__DSr?fAEqI7-AO>@no zJL$J`%!R$_Ai&w$a!}3etk2MX7>=_Po%J!=g-F@lS-)4?FnoXgf-d?x)iu7_Y~M}C zdYwHx2%xfOCpH1c4^cE0)*kS2ybUO-<0(4zNQ4hCEfEsvKH2|5Kv6om-*jV(y5a-E zD~R9h2(z(gcX_lB&l9A{5w}^8c^8VdBKy*MP?(Qbm3Vpd0DV@Jgra^@(~?9TU^Mv6 zm@0juzk-IoXu*Et=JNd#GuVd>6YPhPBH=#K?~zU)o?*WcZTSs;vu7ywRb%A=vsk`# zS42~`m!IRA!WB59is&b{cOT-JF3aFetSsH6(|qb=+(iQOJz1hpXuqT@N(^rCcQ^CL z5`Cl-=pF2^dteG;!vU=7t{;_EKv{%UIH;PZfZjxt#0qGyJAVOr-O+Tm{q88u+;}$K zQ5NPvwzJ$(?8%h~!?`g-6GTaO)C{lCJ$>!2lXPm9n1(B2q1l2`eMDB38REz*?bH5E zt$UMIM$mgbyd4MqKG5$h)rV*=;-RpI&bEv*l``y<5Sf8bM}Tl%4}CuwZFh#gKD=M!m`SEs3YI%k+|&!fXO|x3Byjp6bNqs;j*4M z&c+JK?}?T|gdCgr#oYFJRB|6RvWQof8x=VX5MrZ6xu9kGY_ioL;0WiU7I$vNH7nGz}mI z08JdyubmxkIF_V$MQ+edQZvwGZY@8sR22E>2jZdAYW+V-W@d!iUQAA!Up(PA^=wUn2yYE{PCn<}Pre5^Iu^ z?>KlSN{veEX%X9QXZQ_D**3z@<%3fyG`0zVPeSnd+{s60ntjj`qi}!5C;~=L3P!E5 zDk5+G&YOuitvBHMY+zOa19Oy^qs#T#%^ELte7HJ7)a5#&`~rXb!zYuW;m4iu7|x43HIoEV@JQJ8)ZP z=6%Ry!)n@f9R^m&%yW_@4Dc*6kE<#MI(Q~UHY|}1T-|UXFn`{mkIhRL=X5@to0|{1 zId|&iv)TwNyC8(+*G-qQyJ{c)ScI+7a7C2Dl}(huwcWxE(HAkCzgI8Oo`f%Ky;Hx) zp@DlWFK4&V05P=Pp~1ox`qY_r!}^_cDNJk}W64L~m@&fa9pUvOH1J2^*zA_de)?cjX4g*z8ek-!SY{H9ZE2iAIT8G2}tKom>ZhdSo!XlorH!8A%I5rm@DdAZ%w}3ah zL|bOVJx&x9k3qz|yZSuvS@Q@~lkO}beRKRJPVf%^Hx0NyuQb@8 zI+Jy;Q$V6KK4uES11m+FAWbXjq{5){fNs+L`k4NH1S^R$sG%TR`mG6#1888$lT7dX zdI?&iTtdMy0>Xdb%A4=kkJ9E2M9}2}dgXiv>$sD33Rf|{N6wFW(k{ywd2vFLilZa1 z1GoACeTvoxr3y&{&Bx!-yE*hz3LP1tTO1z(s_H?#q@RPmBoyrF`o<^-FMCiAXvqP% z#^FKzC?~?}WUZFrOC>2kddEa`YFyl#GQHY^u;%72(d~p zS>WI;2}K@!AiSP*LW7_dp}(XV9{No>CO{vq&5KR){6v7g6xdy>be~fjcM*3KKaW;R zq4_=?gfmxTh2~k5=91O=1g9hW1;P^T)PQjHp+c<-C}^uGQ%Ri2P71i;z!g5Mmus!i zP7QllKg#v)cjl!J>r=~FW)ML~nfwPXBcn&58G_=bVJmu1 z8om}kqE|W{Few1iKd|QY9th2v`}A(OlSCh$Wu*>|>XaHDuHFdpt&e0^C$}J!d~wa* z;~*?pgGEYFK<2nL`Wf``k-q*8rnyExR6c*WMh`f>IPMf18I2XUqqT9t7{RO*Q9Gm zoXBbfxU+yG-&Al>o(JQ=FIr*xf+6x$s(0W=s~oDT%w{c&f?MQ>=vtcNfM^1U&c-DRPNvf(;vH|(WeX&sgm_A}061S;tp7<6Ltzp=&yj58| zgtl_nob<^5KpYz{2B7@UalU(F;pu6@&SG zXL&J6eotBinA-(r4lq=;7(K+&FnbzA-vTpQvJpBoKdOSn_DAFm%J)GL($dOQgZbtp) zwTDuN3sY>y>de8IF9FOXdq#xWlz&2*d9A1gx#gztfX5V=3>1Q|5Q}5H4CuY9c5?r; z{hP>u2v3}W##HcmEQBprYmmat3$19gc}Po)EFN&>10xqP0_OieEJ3n_7<5$uQ zzcR{!h9D=l0tbda5+gA5xgZW-&0^2xeQK(ubn|%T^dddBBfvX1MxM5{kCp zXhP`2%~%V@f=tdU0A69;>Ms={)99xYl zu&2i-o4-A+_sN?{OUS@Fe*iK>?cA%n>APDz#2~AS$u*Qkv{;J;kK-tFhzXmAEh@^m z5^fcx7{5XIZLWAm@9b!X(;4N~@f?Lf7ch9^8NE*)x^0?hVgjHW0lI=`n<%+tE3Ode zXlPD8z5@!R-Nk0W?k$xZuHmE1CBTbDF2oDVLk)D`@oUOd-Lv|Typ|P8c#cMh3WN~w zsf-ePRWC)~@b>R}bO_D5tccX{f!Ak(msH{h;6475KHjUO#(M#|m(x&8E#t zbQ}!`uu2|VsPO(h+=)qL(WPi-mH}kp-4FOb^9B9%s&D%sfsV;&u4qRB9g9*s2KLW8Cuf$0_Q8vPk*eCwgpyL!723L?*fT{^&qDerd%*bG6L zu=IF0TCiiZ*$Z~FAw|BU1-n=AdjS;($|)0I^Xxiv^hPWZn4bOhb2jQ@S{KBRKx=}S z*i8xjXmfj9|5~QhBgLo6U;O>?n=|jts#o=oTOC)9%(;L3R}ZtM{@hjtt`6abndSTI zt6tN~Rqa4;=*vb|%GjzBy%C39>3yRgCyLhX9rbGF#lg@{o zkTIb9ZL2=;P`li?lP-nj!V1zEQ;U}<${F8YpzSXv6SpeP+opfe1$ZUgJ$iL7<~gLB zS+yMt1yx8`u$?XMWfaCXF9XN^l8LqW4zx&8 zr^d_8_3w%*g~%I9bH&Hqd-_0D9{~=%mjzbFIl$!l zRJk|3r%z)pErs|6otq1Z!1ezJx_>z8!Rzy^nf(7#?tar$?)YZ8p8H zPaMLt#Is=u2^L2Nio@0G0HCryev{ef1HGR^AxSQBodEgWAYb@_KB41))#xaX#@SY2 zPrlz=^MT&iHRpcwtq=5p+LnqJ4KhiJ5Do#eMo6W}SG?C{N_88wL*F<|UDt9e57boRo&v6rQn?BaZI{5pY{HaT= z75s~u<1cZ7e+;<$ft&S-KGDJ7a`F!#Jo5&@|C`(e(v1ERC-_rX=jFid_(VU}X=lM- z>VYNa(@2jU`mqi@+!Gv5AMu2%y+V&w&FLX=l0R@`f%|C(*7eUqO{-diAj<$-z??t} zn3d@tw1P7s+1MXemF8E9@nbVHij;sir zyh4-Q5fcE%h0r!=PZ5Y$OFm5DKz+NXS2{Dom5F4yw9u5`YOcV^A!Sm_Mo4Yl@irSm4VAoi8cj3}>D#n=#R?}{vL&0Xot z#R(M?z%2l-Y9||*Waz?9{()h*?-g{*ck10S9?7MXSq9w{p5+ZRbFuhhF5Q(OyVYE* zLU%QyMF(~yuv$`VQ}SjAKIGKJhc)$HBm+KlRdacjIH6krxFX<|f&ba|Jh&%0iaRwD zAu2FD@jtaW{t_qn(*;N02^@~YZ%}8O9g})LeDA`RWv3_~7Un+?5Cv-i=C(=a_AY)E zK3Q>?vhQ2O6Z{Qd-~G+MdbP*f7?xY>@OxuQKM55*!xc*?e*D&iB0el%uOhDS@m9@c zK;rzo00O|R0B+G2*u=aZf|%?5_X~XlMmZU2${`MOB_<(SkEEe?yp_B1oQo4$rhq$D zXld(xa_Qq0(L(YM6>H(g0AWOxkguWDRazh-t&c)d?mVuuNU!Y}n+ zXh1WZC7modtbvzO47LSi;8dqrq$K+OJI^O^*%?Ft&yt7 z&=t}__;t#h`ad?J$Yeh3G*WCTR)c|C`agXd1}Yi4xS+GRF@0F#z65ks%;g)+AG6s? za$)-f$j=1%xUcmIu6+-h=YFkEa(I!u(ot3_){&Xcti`2_S`sJ9&I8G24Io(ijVJ&V#uoXE!r1eTK9bR* z45%fz2eiY!#R9~~c$oPuTQ-AMoDqFH_IjlMz2tQ5P@8!2p$Saj(|L9rpT6%W5 z2e8~zH%SG2=8@rsRcoMS)(6^&Hr(ZF*AKFc6-`ly(m^XMLAdeWW4?OQd=kIVxOz8*n#%$97Y4`TGTb z&|L+(E#Ox~25}E$AEq8+9{(MSUdTlX2|lb6oekum-TF{RMV6Wf2{F)BgYM$pGQLhU z43bXpqg5v_=r%S*7v>s!W}!y{o%X#x^rU=6k>qp~uv`W@Iyo{GE3D#s@h5m`AqPcF z|6S05{%ih0+-ksd1ZL^?Sn5b<=jA07xuSsOA3$i$!u=wo1*(G= zWu6xk=UN1SNfKtdEBYN4^N5!2aSdP*FKTZ89@|fO;XZHJv?C48p3rf9x;6N!9 z8JWk~_^qSrapCGY0F$<|+PPTq=65|&yc9(}6|l{FbkF4Gtds)b2vQE#xtNrj1?xzk zu!foydl77(mjS}qDR(|ZVD}ITs_tR9Tfo~mx}`G3&8f_?z_tT6BaqTvwHMGvN~R8k za;=l(3?g9ANc}Y`fd=hYVf9xkON?CA;RYY(+N=6G)B7TQGSZnMw$k09rhv3fi? zb232k@pcH=+5izfo2U*~?|@**U>Gr=TQDc(V_?I3dGxJ1H(b3%;@!M8y@poN$AQPV zEFQyi8Y0dl0wynlNen`*r7An_ca*t(Pg7N2REz{*>&R$APLowR%*CWY{{Yd$IJ=tC z(Wzo@G?pApk@U9%yb8jYMbRxS-;bEDjCpO=iHnQ@bhXfMuBc_y2j;~fDwx$WU@ioP zl}LOf>!13Owm6n-jmolUyu7!wX-{${>WP?Cfl1X*dS(9lC2SY~;gKL*`BS=j@R;pe z;kxz_P+pZ4aTDrEn4VKMp;UAAKVxU9IYQ68aP?oP!BnZ*K*TC+kw|)~RM*Z6HypkS>6@MDtB^hw=|rm_`1tgP zVf|sS{;(YDhn&`ra}5J0hpRt_V9DTL!~nbEv=L3sL6a_!Oe`n?S86@z@s>;?1&O z^`7}lMTklPbT2^je$_pvE1+{bLs@B z&$H`}TvJ&;k4CjcclL80DeyQ=Xm}~A0WH>0juh0!i@NL&H9u}hawh70ELRW{O^u$2 zn>^^#(9$fV(3$hY4R^+nKHZsqEz)m8IunS41gkKn=U;ByBF6RR(f9tV(0u#uU~%Z7 zE)bA)1_#UB>76hp&`n`7ndR~iin(K|xSUSXW-pgFg0Fl>%jJuqL=kZI3s$Yk^D-?7anez2*93)_;LJl<S>v}q^eO$`C-Y-=rzDkVD>~&) z&;7lPTSfZY_&@JYeVvnITyRWsj)Cro!vV*Bf9X$Y=K=BIUx;HuuD7Y~$-H?{y3qe^ z(vFFq_}U*Av7zFs0gEZ}HZQ$fMEZb!2ho$2a9r7<{Yty(sc8~vv}%On==M9!R;h}L z@*ri*<$v=M&ecp@q890ejd@7g`nR6ae(j7v?0@tb3mv+7v+{!QX`OWI>S!7>5+prt zuAttL!mUr^dAH}qoPR*y-$~d^X^q%GL>s5f&QIxG`#Z#kg?Kk-7Xw*)urv3zF?v4t zxKXSY2uqk7UB;p2->Ok>PdTUBUM_KGUTB5#3}m{=yhwVHmk8*qL4UDkeB$7%baj+B zt?G3pzJ*QLNYV?w9?%zn{-IU|t=ijcnZou*7o)yvo=oT;;oNF)pnXL^T z`68XtE0}pj!GPJ@V0L3`;|ND)uzgP@kapg2I2;VRCNm@HMP^c|Ftdcjzoj1w53pVZbkm46Ue);2^4*cA5R(7B8FqV|w+Oz)XNH`QpH zU7d&&*0c7YwLH+)I412pbK4m&Itl|feb~iBrs1Pd0F7#I11)Wz1)}H$n{EjNip>LP zL7{Q#Si43_iGz;9mky!!+t~t`y9iiEi$G?d&2;dIYGbx$#bcbwi10cxF%%6=apS6E%%jz&NI z0ae7GE>6)3Ceq%)`-Pp2DZPgRL1VSpAGo0zFD6oUP$b*%->fSz%FVai8l4;-qI4$@ zOnXS;G<@y})P-G)p03DNb6^*vPsKW9UJlCKtsyhxo~%F@b}?R_N(CxQ%A3X1j|LY^ z!&vLFs+7h}7xSHH(aA9$3%VM;*q%I$73ymEw28>n=B~ySS}7i?x*3;fm%zUD^socj z994qG@I5@xCK$~u>5_48TjX~XN(^US-p0FNi7`OijEChV#!W);DPQL&{f;zT24Ao1ib+0vbvXyo{~PvE#w2e2lSJAGd*jBtJS#>zXJI+vV}`r zi=8{rE$eNZLKdr|1_u^E zb>Svm;-h-2qSQHR{LlwLe177xt!Me#iV$_ePZJD13EF>#Iw z08=I~&jJ&&%^kBrb(&jY&2R*ujsjG|7bfI-bS}o?m>4iBFsq>)Oi`yI*qZ*k{1ghT z)n1FqoZ8_Q^Fz1Mmv3Vnrxsm4n4 zyp~E+T(jr{&m-DlJt3_r3s-m5hU`pXZE}&5TVg7%WQ>667>A-{6<6)KcAoxLjOTR5 zGt^A(<-Lty+S|^QMSZ(!PZUf^!Dj2D)rJ*~?=DQYz$fF5s9V&Txx#JCwf%XklHd0XhI={SFQxWuQ?Pd zU<&<%7Q!0mbhHoAOdgbheC*xXSL2MFpCEoL-W>lVW9}X_t?Oy#3C~n0Gqd_ z39NcgxH_CCGaK?`=8l8Rj1N2)+4SkGx^ztGRj9yETt` zXCI_`>b=-o0?)Y_kK&d3G6z#$|Bh>ksjSpsIs{Bh2ebKdZYz}}C&8%=(Dek}yuk+F zP|j`vz5IBB@4j$#8_=x=UAmX28Y5fExH!fDx}V_nt4d|JRe)=Aj9x5M%E`M%bMxt) zXC)R%fFb`fu&V8gAp(;KO=_y?l^tGL-=3Pun73fI5`xNeIpz>1LuO4lN7 z=1<@;iq&sQH{TsR@~Jj|lu2EQ@K>2P%#Zk`~gS0BP? z8w@55H~O%K40j}u#m1ru7fo=Dnk=LSug2x3>kKs3yo(B2qxy@?Wy6i~>2545i+-X; z)Px!>Ebc$BuDrxV~a^j?87Z@vjd_~4`m9Ef)s>wZZmQkuDPL>}#!1dDfvu^1{A zB+$@kEeZhlDYJu9d9|{*X%fIZMp|{emU$1pU9p`a0bHNm+|W@&I#!A!?QUuCU~Gw5 zYZ31F4mVt#GJjWx!cp3R+UB}NG;aKDYX+qwEX+PONJ;`}}BNKS(W z6Dl$S>Ap$EXszSgGV z&^?+z`=%C@>BW>;h50O<0eMdm)zn=Um9*KLTEBs>d`FvF7eHWp;Ov`P_D@AfhxE;vVR~Chm3g6(BSUjJA$9#C>Xl4lxIe&P|6^5IfTrE2N++onQ>n zs_}s187$}uSrG`t4A?m*+9R?8gv%!wCt;-}L#K>%(iLHv2D*ZY#x)K)uanMGjJsPv zw{~I{zi<{^XPn6bUBx8hXa_&+e%kembqQC`2Hi5y^>gSq%0cJph6xGiOlyKM(!9lg zZkN07Kev^6*day-R3w6y-!6ZzOO`c4zU!Qv5!}P z{T%EmMJzRne#arkEmGj3$}E8hN?>^t0)4&0)vp4>1m50~KnWHC>7u!(0RFAg*skq$ zq2Zijl$gmwjWKiWW{Nw_!KV0*mAb525R+med1QUwk}Lk_|>e8!9p z^g^+EM`!%A&%Do6-$4KXC1tWThGUbWxT|m-1+cX8H3DmE=}VUEQX`hYp$PW^fdA_?86uayogj5O2n{ktm1fuT<9i$&5QMO zYy{YIBo+}T`_0AEjZ&w*5U4>cv?Pbb067tm;B>>2pHPI?Q%LmTAY4D)D9=xbm~u8y z^WkV42zO6!DyKqQ4+sa?w0#O8mo4VhOY!1}xC6Gk#A2O%RWmsi83+K<8j!Vz8|C@k zAkKNmK==z)T(|+10KP%pvR)!j31I&xu_%Fy@?(3mGH}VV5SdB={2{;#W*9y5o7nB) zCdP)}n;={X!u(mWIH3=O8-zN4Vd&4ci;yL{bgN0v7MJ%1fUOnStxaRIvSRgR8pZ%# z3GkdFn#@W+MwkHMtsqygF6I+dQ2J) zs#c2fNC3MO*e8!}%5I_=_RI`dUkt)MM;kr!7n~>w9|+G9+VpF#;0AG@2l&?|h1oB6Kog%PnXemI%d=QVh86F{O8giMqhciD+fXQ%T zf?$sa|K@hN)6NX-l{dpIKd&(7|=yb4VUbGwoyvhTF4`XmnwQ%ri;xteNo9RgIjh>K+@F zwAnN5*T7f4qnY*;NdM?}Zjj7HD(njPb_HC>SabgIY)%HNj^!gADg2}Gi2{t5 zz-Z<1#vho+5uLfRItvrd!gRp-bzpYj-Z#u;GrT38oAXw2AILeN+jD|ZQosU9_m-Mf zbJ@y#1{4>}{X!v3sAmI&FDH#Ce3ncJzkeG4x84&hH;-FjbVi^;290$t%Bswc2h-=F zK-=eg!W2CFl0M9(`9R+X^vh2)#tzQMSI{Lu*G}*qW^R92XTzjiH7w4S?&tUeI=_2@ zajrvMzf;{n35KTnA$%t_`3k? zI*DAY(48V@*8*E{l5visbgeAidtl`Qbhx~kwpud$l1@6h<>4aYH_7N_c9>_3b`ZNe zI?9i(Y?ue)1@lCZrF2^?iP_6pEe}^u2Hnjm1YK(MvmA8{a$;4np^MbBPuafk_t5Tpp4)jar8+SP5hn;-Y;o<6jpc{3X zad$u3+~S3^&Bf`kAHnsEjKD1MkA0@uX@Swr{OdHMzji8q_B-7enHT0B&l>m`j^{TJ ztY(AJ+pIa=sDv^ZA#tWmovi7;u{b0P>fNUs=ffBoI;AriBTW|>AFi$eU6wI&>2V1N z4R>OozYg^4&oJl;(Of!_$rR`=2Hl=BjEfxd{Z9ERmS>J_PQIiU@@Y9|T0Z%bPRI{{ zZVc#tTVR~;(9?3tk5%Ga59n_68{$SB))8!TC9~)z-#z2xzc$EiJ_A5X~!BHz|9*`C2Nrja5Ac?hv2LXF7uw54#XF84R)Fp;V z-BCh@t!>Nj^$U7oT$(se0sR{bvkF(z3FE4mf(?f;3ePgWa~i{PDnMs=*P#zCJx2uO z$tt0Abr{Wuk;4kmEy||zJLyt5l^O!wrgMye?O`A#JU&|d3%u+cgWpIc`6KL_d3l_B zZ35>s&lY2WZO-X-#uyTlBJWb;>PO63p+Oaa)&2Hf6~K#SwlYOD7M}R9AKo=(wWF>T2eMFP6+@z57-5Z47%|(S4NW4c}_%( zg~$~7S{JyCh2u!l`ZQsl-;zx4Va)n;zI8nD0%pyx+Pb;<4Sv+l%oi5JPI)IKU(HZz(F*ua=j~dan)d}~g(UJtf_+lQG!G+1xjE{nz zGyL;sM+L~`@us!HTz)?NWp#ry@pzsH7!`q0x)F&VW||io z16fTG4%H(+vkWf;e3G?1r{dHPT1d)V46991R9|{-XID`0)LP)VKy&j5!vL6mDwuvG z82)0noXGK>pPFqK(ix6{-<#mKaxv?i^Y|i{>zR-JFOrJ`NBtpB-jL54P(I4c7(n6C zZa!ch6PSQqM=y7~M3#=BtVXa-W1($WQwF2^1f%Edj6`Oi%wm+o$IBz%BH(iq@!70I zhf}~ZN@FtkiGD4_{Ej-Ql`Sz;C}a*rd>Xz}P7J|lR)$fHiY9~j+}si$Kj#wwpEG|^ z_nG4^HU_dAhESu3!Qz$}#5n^x*>$u~WCXbdZio3E0kqVyD(<4_did9q7h}zKEg0IT zR${d=9oItu`u;ifk}|I6^SxrIkwkh4j{(YFZB!vZzN6K~EAYD;aAcXxY9o*9p=bgK zDTyk$4DA&&HbQ4R>nw?0x%{KVY(-p9+#37M$lTihGsdzN0YDveNlr(%EANF|oFmrz z(=v93qa`@H`HjCZEMtBS%ITMgd6?uV>AajyZHpU(iQ^^4QAI=XU=`DhR{xOqo%Zx^imtFLhc1UwBe`Kq#}||DgwG4pqq1r zF-1GDAIp|k7&owsOeMe)io|(&t5_IRWE9YjrNWc2j28?^Gz(A2%Ecg+6VaZtkC_p$AZDqka3bj!K70`bqLNr3I#7{PCg(Y7o zO!}%=Q;!Pz8=-IL+AMt~y)-!Jui^R*Fu%FhI2+AOMrq5bv~M&{4}tiCrABuagemKf zq?1+#-3(F!L(Ocz(&RFQkM$(y$#5j~GMmBS<&&r0RleP!l+cW}dDjSksWJ4W~ z@1%p?mW}tH;n}$NhkfRx8?v$?;UXJ>3D~#*e8~;S#-s<$+8c~P4%cvxch&)H2wX(! zp(S`K>$Y>Ua=I~>I9WQtodw*m8;xrmb&;A&O@$0Nq13vEDF~K}*mH1tOqp+_TU8@FwF7hXIpLesp2( z$Dktv_Gm7H5-0d4fZGDx@|%rn2Y>ejM*&d?>Jx(h4_UX3I}1qQ1b>P{wSb#^i#SX# z?csOw_e{grB}k83vg{%01V10>t_Iy3;OEfSa`L0i64wM8Y-YRg&H>yeb92Pyo8#ics!_6v{0zg=f0uhA`!5G1DMUd1iiU?AL$+Ue=^=|Xx`-zFj_5HfRdIDdU#zyS2KFcj zqbN8Z0zzVFMCcfhxgA|%sbW^$W|U}CKrrt%!QPE{mjn7*ZgD9V#i z+h9-a4&ywhDoLS=unVnS-2%eJqzZjs%GSI)%p`HR>w*M$u(EU&a9i#$uFi6wNe=gk zVUgkl5L$47JG1UlcL;C`oOE&Eju1GqO$_(P5WN!b5xwd817=6Md&k}F}4%9a% zK+;PApzj3wCHEMooZ?_?IT;5QW94smGnz|!!8ii?uLONtGjfkH$UNa*W4O~zl1>?s zi}A@>!k|c7W2em?@9)q};=H^VV!*us9MLFB&!`8j$`|58uXlXM`H}mms?vk|kHv}T zdv2@IeBKPA()*0_n05-TM;Y`DHlVjC8;Bzv1C`Qg3CVR?xZ$iTQB&rjrp#-qJ*?#A z?x*8qs417>TUJ6t`hb?5-!$+$j`+=0LXFnk78oWu!vGkb35G}EfTlGEip*&Nr5S?Nvm9e&xZ<(-)WUx zjI;_cDZ;=aKjB30>-b~kZXWf3QCOK*oY2v8B|hK;=qjkl=_uc>+E?KG%gn_O8eK=_ zg$wfp0DsvIw|bjfA27ykd8Utv79po)HXFb${qA7r8+d=;FbTPDHic(d|bpV;qt1u(9 z!^0W)PjDhuMGn&A1K>5#&dXxF%yE`M9}{U(2fBN!D{vPyMJL7uDbTe7-Fizz(ehDc zPR;XNjesi*s&=wpoQNapn$~2Lz_LC54oV z=se0r0-zdzNNZQPg8G+jYP^Cu*ezdEvw`M)p`&%rRa%VQeQ46I2Cp|(8GWWT;|&qe zokxm-?~-iUNiO?r$R4!1DI@U{b)GP~B*EuQ_TLpf3unO{c@g}Mw&lf#J;yv!+VVZLpg$$v#tqlNF2GE>`jZ-lj z%+*pH^P~IV{=(>km|sWRZ|Im;%@Qp)ucx)s&|zndjdJ-}+`8)0aP>EW->IbRXk}kW z^r5*Rc_ad$9RN`gC^#*cLRWG77Oo6^_rf+$$>kwOmf-Q05FEor=@x`jrn>)f;E?pG z8|J6ktwWq2PmF=Vi(s${AV%lzYwmo+=!Lz+T%ocr2j)>B^f&mByw)qP94|jgr(TEC zh``KQ!}i2;c?*34pu1V{E})sx0wvv_S_^O@Adp9A*~qrTt<9=`Ih;!D|#bt z@i-NK=Fe-4&bU7>R|(Og1g=MvBfvs{IchCiLd!$X4@Sm7Uk&<;o1&A31Dy|a^)1kO zZooP?=>BYhE&#d;&{aL!gnmM940Ihqx3mSi6zKkjvEFEb&U0h9`g_n7u4`Uy0CYP* zH>U-<80g*t-JR=+LWA=Z{C^;wB2#D9< zN(7c+qmaNDfDZ-eZ@LQx6E9)hI{I7|8TUjoE;o3cn&fH6+0&E(=0lGe-Erks8gn?k zuVMv~##GtU+yl&Aj~P>kiw#d?vQEr;>NNiV>R@Vpw_*FAG6mT&@OsSb{Djd%&xeR} zL;#4l2{8$XaR?AWZ$AKt#f>q2s zoCmRdBtUmR=w>xVC%*2K0^KsuEq}r|BClLGKR~H2$G!TX`|SyKQY%+(n9~J7w*Yii zPl^~)UePl-7Y(plgN5 z7&)T#eN#q}OyjMl6mMI3De{nwyhwbVreVaAxM=9$rO!Apnl0g~aalMEAyDoY0agGlF zzmXK)3mm?gV1D$J(SbD(*-n_`fD{0a69AW6FvjjOv+L8wz?1V8nP|m*cVc!8jQm!N zXvJ-27gkqBu;QW{Qg0>tQQpRn&FxPa-OxtoQcI0MeYN2JC;B~F(O%UrtsOYxf~Q@M zb~=}rmrM4nz|j}Mi<((-5+7E5hUT@Q#X&xRPA8D2MmyeV9{Y?@n%9Evk=z+UehkQ0 zRR|ruBh5RXF{b8iN~8tvLWn0YKRv?+igl`&c)4nQE#=G4WzwCXy+}pKe7s5L7o`yA z7!NQV2!r6a3UUu*@85SEFbD13gCBYNpCeHlS7rJibJMdd`YzYlinuGq#FzEHgaBX; zBc()ue_mUQIZ6PSBruboYpSgjccp-Co8Vn>kh~MXY$go)+4qshRnu{2ns7WacHeu# z4TTpWeIZZpM@VQ-Gi=xVy-Qv1xL)~)u5o!BDx&ONucd0f45h!%#9 z%jykJ@nu3;v?Uw<56>Ixu^lxZ4;3%qn)$=1^n0b z+E>t!CHH%sY`7$F6Vw4%b9urTGjBg0sI11rJoN23 zn65^iAScc$j*ifOjTHrAJ11kxJQiE|;3R3OINFjlynAn^vf?xFEPVx6@^2z3ufU8J z9tt-@+?_()`=1}YxQ7v;&^k-pI`AQJmq6S#c)oKp#Q90etHuoNSUk*q)p$TV^;7ug ztHv=}7o<#o4GOfz1Lb!nDNuC~`Nc5r@X44=f|EVJW#D7s-PcDbEB5Z(SHI;oqf*sk zuwua*#*|r6Jdl`op*Qv%S~e@z#am$mUds}*7JQb2p>_ctw!VQ3oGCazOq}t#SE&>o z`OjNmSf~3EoZs8w%)sT~Lu+`4BLm0adET4GG%ppnbg8)0rD)qZA=V`y7uoQD1OU0 zZ`Ni!kbTK7toa9F1xy+HV}E@@mWYqR=Z&{eAy(tzz+15I-GcK+D2ao%FF3c&;`|u+ zkbN(op{$7D`Nl2A>Dpp2{d$WrMmr5DW&bsf*Oq*O%Ku;Em|5e5+)GF<`W(x4l|!E zMVi0$|2X^pz?!T7|NFYqjL&*AH&;E-Q+ntSKsFLX^Zl^p+^!$Md{iukGF&S>Hdldwx96zsaQd+7}-_zS-U9np|IVAwao~! zB8d!5l6E!$g=o-g@L31YRKIeh(i`zr-jh;v1(9CF9@s@}Y2i|9dPn6l&^(<}G8V4_A86A4DOr1O!EY2iMty zm?C|b7aLZJ##nTgL9X(T4?!c}irU>4gMghx4YeCy=o4Fbv`gAijMVb@4ugBprd}_JITD!?VY?)zCWu`riTaJ%50=UJP+%O6`(aT@4CKFQZ zD_}y3z4nz*tb@n@keAIqgSyB4kk__eBSd?mslr&USorZJc`^K4^rQ&>%=Wxc{?!k8 zZP+T1?md;~;K?U2NSF&BMk5J)4f)2x7jzN|%&ZDNnKyzZ!FT;63b8gE7|q~F|Eatl z>;g&>NaNW--QnOvf6N{cp1{1KdeOYoJ*7H@@F&Dy55Q(^JYlw8Kf9> z24kP5hbq17C)65NdJyB1pYw)EOr})7pwO?J&AZ52=)QC8?AMjvW9RZTi7kTe2A;=g zpaemC&*#mRSo8q|RpzzjCH6_RZbOM1y2q*wK0gelPda*u5#VY&zK#1*lynJM29=FQZgY4&+HKcCWOG)2mO6=XN-Ny`~?aA3ZL-*FHd4D5r|<|^3sA^?bip! zJZFs>PFCt^dqRlfp(pFfxqepI7oTz*GLp8_A-+Kw~#uPT&`IYT@2X zf8|ZIvVmV#ddEoeNE_=9((^HsW`=#d5B$*#Th7cn@E+XPz49==FLu%g{N5n>6{dYr z>Af5zZ;@C8A~)BOV_7IT?5!g^oTtHovYY}eaSF+2xJOx)T#}yUQv71TzbX#bFGacr zkK8M=Tx{z8Pw?ncSH5CpcLOQCo_yT)+o#lb%#&ky`}*?zeO*SYYt-Rli9SvY#ZWbe ziC6uycl&3jAy7ni?6vsWSUHv&QoV<2;wt|R#1W0n`E1gwi_w(A%ZOW(Ndh$~1y<%;|S{ab>3)OO@!qXu}F zG?8uA=#HT9uzGG9Dy>SY=XT%$!W~fmX1m-eErufs7gNgmc^3S{$~2z9S4 zga{CYM7Rd>l?bE$=-XiQSzNk8G**%bGUF2{y+1BeHK!;$!U zb2%YmF;VUWRumE{_|0*Op|Y9O+pC!)1@ zYVj5+a$9FT1W?N}kn)2`iAhW?j{rx@L%&rm4<;qHY<$ih0GzbD(z_x>J|#KlLViNr zNs7QU@|K90M&@ENa`7X7Q8{q-w?>h2L|ktz_YBNbi^01lAYhtR{3;7_a%Vl1Mj&O9+S97pxg{o|Uazfvj9_BX1d1 z3)(`jyUo+fwT&hU9xEmay)w3?Q(oglUaNXz;zsQ@{W1@I<*s*4YeHRv#|20i1nI)s z$x)*Qz;Po6(Zm2Zl|ib1W`F^itsZW(2w-p)#aqx$j?J~*gux#uPY>R2yCnnk;kjVY zDuBTkWIu>|v5jR3x4$+al6zjAXe;P;6LyD*T@4jRy=_PUyUoN76?7KZ(eTfL3lcs9 zO@Qw16s1#2%xb8-A~3t~p|Hd%+gSo;hf`$-I}4!esd7~RmH$Fp*%z{5VpuUK2>Pxk{ta{k+({b%eXjxCw9V2@a#QcM_VPOt`?<8z`*sI;sl-|$+SyS) zmHw-+C_L6@uOlAmlkiI>dd3XTFv9Um;XfdJTqk*2+%A&<--T0&OZX*%4-kH_lf1Im zJ*7Sk80^skg#LkH;MO-V%u>hQ8({}J%VR@Q;GkA-{SM44yU338CI}EET~XH^XS#tL zW4eJDWx9dX5bniYJFlyw5sgsyTz$k%WX_Hg_z>WVSR9ymZ^$Cdr^NY-x$ z#);iXS<62__-*p3xUp~$bD=Dp3pSNCiU_)+BOC_D>F)A0)&-6+JrI)iL8W(k4|$~2 z`V+ECEbUwDSY?1dPT&MHtt^Oz1cX0^BqYwY_k}o^XWcFb+cbpoK^q>5@n+mEM>19q z{({Yu+P+?tDchoB|4W@bR^!dHEiJ`!OoT5Aq|VYC|QE$bt@Fw#X>excfohxe1) zd)MA6OI9(aw^(r(u-wV^;d|gx`mWM}e=$;R;_d2`m)N4`Z8N~BF~N-$1pWlVQgh@c z{Ai9G#DfRPSAbJ&t*GS-vo*HpfQtUhdPhx^-L(_DAR$q` z|7IoM^^RWB^akrLoV~QY1?|t4$9pH|%XW!90d9*Y%a2RYK^dto`eD+69jOT6wUSD{ z5xj;^g%N%S&*lb``f%4KxgH-~q_*U3ACVWcMf1B_>+($ia9Bu7dt z4dAaoDQ8Ny()9q(XrVZ~_2$V=$(CE?pYyc5*~%^hKXm~RR;|N$bxyv+TeLvlC9!wm zbuN^zv>6Km%ERe5D*3PABFZQg_l{uD)DA=!hh)C-+o;}e&{ecN=K)yGGtbJ8*qC(# z76TT`Q=F;N_`WrFcK^tT|*^veBv5oSZL75myI9|Ae^G&i__vH5Rrf!yhk`gySB+68W zm6g03+-BB41NWH-6PX(NCJEZgAT9A=wVSvaTG|BC%brSaueasjBt{_6Y%^Z`B$~3@ zk*TR$i=525z#Fzz&a^eB@SNF7tXJDA7fNCG0^H1~6K-Vm&FJPn zff6);_mdXHQsg~aTW$}ZVB^2PD{o-;AV?^?bQ^q$@a4ZJ{}w!Rg$~JGuVSd;+AasP zi3nP-9a9tal}c~-|H?D1wuO+Cx9=%O@_ir3GuRt1!`h!#d-9?kvOO~I6--Ic|5?Vn z%I&i)%SXe{UCU6AM|Q~BwhmQkyOtvD-AH@vgGr6~=cV!lb`Ci_7KGKR{vXQWAuA9^ z`gY(qELdsFmwYJquWN-*m~RAse2dzc&;Cf3`J|8JKcZ(K#?*&|BBrb>2rJkrFN_{| zgUH@`WD4)UOFr4d`Vx|(o>PBheZW;tD~)|9l@a!XZ~ug_S3pnV+40LurmC^tCqI_2 zO6)(#@cJArmcO)Hp3EjdYhin2Nn*_r-a2klbFS@rC?u?fvBH=c346}cVZP_ zx8PGuKQ4imCJUX3e*7!%xY~^c8{#?% zI8*nbH`os3{e(>ALpq;G$QXm0)HLOTe8q;&tC2CzUK4^tA_2%ffYbeR`APOTkQaRc zi(isxdN#@+||9_W|cBA;%cV z_Y@k)AO9O<4C#Mc=C9{v!0{kI#VSAp3T-2VTF@GO!>dw5+ zd@pykvTiSkmL`tB7doLX|D{5X88jAa5{_crk3J&j-LV!+xP6a(fyI(|Foza5>~-Ds zFu)dW%uZ;vMYt zQBV9@aSymSBT@?oT|sQpQGLCDyb59Q)Zf$})pfV85bVO|V%%%9%VoHosPHV~@^HGF&}Qep51PlUfFV?K8nV zVVs?oAE-r!P|E8<%0@X!FbS9jqLV9j_{lYKzEPe8*`yCCCv8Q!Q=J&!3hD{5?Oe z2D)-A4RsOh4PhF#bvBsBp2hweR!tEs4SC@iG-AC$aQ>r7O~6iY2>J=Lrw1Vezc2~= z;B$VGgKQ(oTeb`4yz(dcYQ%PwGL?2>8_Sdm>=t|B-~2PoV4V^13+U;Po~igMGqC7_ zG9e($0Q=~<=x^c!ge(P4>$5PhXW$t43mTre2J%iqMo)H2WK^qc*v7@@{Ik!2v;V9- zKoq0Xw-`+w=J@L{7dBC*gH)~MJOU6Db(saUy>NdmE*cojU0c+cAk>@^houe=b0|^l zIpj)|=zKV+M1%BLHxHkp7__B9JoQX|0=J)&L#dF<9G*0ueoo$Evw$ftT{|(pDmd&{ zOtw>iC8qQ|=T{6d?C^$7P?~xd{wnX0P=+NAKnnJ+0D#!rmJ(9?7$t#kxgd9^21Vq= zXi&-|m&kFM)gB=lloJ?syzCZgtIBaE8Ua1W5j?e09>C&2P*90Rq$4#Cm1rJP;5c0= zCol)viJM7U9b(m$xquFAPvvh zp+$KI{7;UPs6Gfujm82w5@v?!aRk+eGG?Ls`E2XfG{Scti~Mu85(*UjDkAvi%kt-} z5CH|hqYh+)l9!%W?O0q>g1POAoXvJU3!TnU6L{JFJeya&B9E{}&qtV8MnT8@EQY<* z#ugz=%y53cD#uH#6TDa=Xy)zlr)-mKKQ9Dw^-Nm+i>AYkkSR*~5+YX@la=c;=|n)D zSXk*@be+}{ID{gqgl8&wGTa_xu2cZ3T!ax*ZvR>d=k|k23@@vt90_qEoQALc@QW3y z1pZZRCE0cjzNIBtud*-0!nOK$>-Zxaa($``PgAKuo4Z(`7IRdP>N-!MNoCh$Ip1R@I zI#{tKCx*|fr_8tg2%T^>bOI_rn$3eK)%5xb20_zM=H4*nb2b-_dErVo?#b}$Wvba$ z__Hl)g4aam`?GZd1o|kp;7*622Flkg3vwN6pp0i zj+?R;I~y2d6+1k!{8;$J zM!Z{;lHUKO99{k#lX17#>;R5-lOt%);sXg@+6nhceify(tZ_z?+u~aO0N86N7c(Qf z0UMZ+J!VEO7#W$_Na=EO(+J4Ons)d!D1hUBlcOt^Uv8v)aWB*)!Ny4nYet-|`V9R# z1_{SbJ0aux6twy?DWd&b8jo=&1k$ubnz$Hc3gb_s`G`?8Nto4u>RzwftndK}!I{>a z-3>~b=U>{_U`0YnpxuoF*Sa|T*ZcAlvM*3w{F@0u7GKac0PPt7dfWu{H0GNdD@SWA zVR8?A-u;xngfEz2kZ|1pkAy`4{Wbt}jtS~%?Clk=U~OVBLb4K+-`H2EcsMLLmK7jZ zE1D=h*?NQ=Yoat`nV<rlo8 zWdhNGO9iM#dXGDlQC6yw{zBrT1R-RF{>v=%J-cmPZbJ+xi~NODVc9}R(00L@dY0R=J_^P5sF1PDs>_PbUYC{X z`3E|jpeKbssKb?6K--q!;;4LT1h)%tuLi*NtA^uYZIy%?%a)54;h6xi_SInStNg=M zC9cMBwp6^8695|_n# zo)3V#%?GZQkdE4_8dcbAd_D1a09;caxN~RGR$*^6vc{!*5{M54Al9u$^oDd$=3^{} z5T35gOurWn4@SloY$}slgd3a9gG@Izp$C|5tT5dLcUDJbe1Qrcg1Dj%mW=chyc5i@ zoVrzE4YYhXsJ|yZ*j!{%&9x1bRC#%u>g_Ne|;KIw`|KI6O4bh{f-`PRc{H z-RKBU#O}OuwB8Q|IPnI_-m+REH}JI1N;GfNO{wRVx+wD)TY@ADZd2N(Z-B#7Xmzh% zZ55l=t1!3dg`_JHM%aTWQ*hsoFb`<%pNsdgZd2ZnQae$~ETr67opR6P2!sD;ic6B* z<8!h64VoY4RPvoYlsvZnacso)RDP1!BOs0IrOaVN;aJ`a9dkC~4);>tl-PA7UzDjh zQvZW=RcEADTivfg3X&=q;X=$M$UkPi2j(ZZ>;<|Yu{R4p`mX*x*Lsaj>XByjUGXT!R9vz1@Ki631t5rLe!CP*QBsOc)Q`#|C0twH2N*SFy93J4mtFSk4Tr26a#z{F$N3 zovaUhSb}K8+a8j`__d+RL^c45o-j;tGgbuI#I|wjbQr}*eZctox;*EZ}C zP-7Q6ndi)sgTt=mz8gCE}F+5%odBY$`AXC_M!>qY2)3iDCex~8z_;^$#~C9QbKF9(GO#{;t}O1 zEBg#dg$+&1$BNGVN~U+j4CQ_+djsKQKD^>FWlv%-F@P;UI|)lHQw-}tVNS*(&DRK9 z^p(<+PoA#U^46KHbeC*-0P|alX~~z&QHDl;16p%8!`!3Yi?Hi+lqt1Q7$ufxy!D4n znj!ID3zSx26e6|{;#}p!K-R*gq*Mony2|?^aEwdoeS0Jp2QXoy6+o0@iDbb&{`j@x z-hbLsIDyU4H#MOoK}SR9VaNy3SSs4{V=g7O8W`LX030+ofLj;>d(BmP555Jrov^)` z0o)R*xw+3A!kU_ywHR0V&!9apS9$bSxLH`o>>Gf4c5+oN+*<>1-v#aRCzPjdr5)Oq zZ4iLFr5cxyDOCCum;#d-w1pz*%<%%XlG9hZzH!ZsxS|`xB^q&aZV(q^#65b0xCWCd zlLf>48${MM5>7;%vq+J#H&yJwYpr5$3N0KOoMJ~#1ATAG^jE+iiM=Y*pVQELwn&MU zY*!StTG-CV$HnFOwK|wMSZwseG5scv>Cb7%M?IyCWc8p?mE4#Q@Q zmZn5w@k3T3ig?9#k{(>S90(#QCh5u2Wl5PrC>JOG1 zjVtJ6e+g&mV8xcwH1EJ?6ztA50|k9d<9%eI@{ZKE6l(_Nd>LGe4OJG4M<-~>$53T5 zRubzWsYy?jo*Ds4W2s2v`HPgc&RGbcouBuSB~Lm&KQ+KE#DS!ThcsY0@!B@N_JjM`!Vl~Cf>A+h*r_6V5fhmx9mywT}if2o94Q>$t zycamvpHmjzTzM{k>DB<`(nS9}z5o!RJXZ&PV6n3C=3pLwu-P=;UII9Y@zWY>NEYa4E;6| zn!)8_+oTH;nzYnV97a*^cm+e$H^z&j)=l{M6^cTt7I4&z3pke!XSJjnu&HABnTv%mXc1Xf->o%!O`N?Z0HkkMo& z>@Y@!G`|qBIi2{$)yfvzAjI;?BjlJM5nR!g=MPg;syt$W_fg0t_Lns{#$3yb(xY>H zY2gvHLrq$zA8kb!U)(M_Z3lzamI8;E!FY3CQ(ThmiE-rrOo@Mft+K_;o`8P};)=EA zIV88(YmRzD=}ty341kPYx2N{v*NW!@#7GlksV9MI(ow;uz;;E!!{`^ip$uRQ1Y)l_ z9x-w2Fbiz}N8fcy0;@9t6FxYkTXLek=HDOm=kyY+*x=;dxn99p?jOgBxm`2wj7^Ga zjn0HuECt{bs@>S=r)t*&VOL8aL>e3|-c$zIG65^Lqxr%&m8@Wqm(bo6AS%8p_;c2twcLIPoPXJh87T=P z9m&9zFUofU#MRjy0w($IV)zz%0f}gW@gsiug^_Aw@1||aX~`t)H4bOow<{y9e9%w% zwXCqs>+dU_Y;B2}zA6w$5NyftJ};?u@9Yn-;^I4&fo{dfjee~eU8v+sSWXvFGQXG=4EkO9>p-Mc}h7w0kH-7bFr4Rdg6uR`ve7j8qP54CV@Ha_IapQ}Sw1+OK z2Or&IZk&x%G->zyOZqkPtV`O1ANxel}#(K~F|<{|KDwhg&RXU_!ba!mb{H&B3pfv6Ag}q~>L>YwNuLFHFlLv)l<9S$+_J<4xt{OoOdDx;<7vD6fMqV-7*@-6(X#(cr|n6rXa)v3Ep zfZF-JGN6~q-)OjsrBVx(Q?WINz7NOEOfZV50KVIxKccaCBtGz%GNr{jXb{)Mw4#L^ z>5OGtlu`Xnj#MO$;W##P3{#(nhZ(0g+IN~laIQ++jx}A(2`AwB9ZprpkthCM_xY3~(0wp!Do(1{(dm_|#lztHKuurG>*( z%>qC^C1FTw6;>X0LTOfGup)HLbpyaQRfBnFolpiyYy(2}o>Zo>hHwZKi!)QRx%>HGm4Lim2;pC7$ICLD0{NV`!1V>=Vijj?I|>H)V!nbJTwR4*(`D zF?$g>bT!RGA7E>v{WCbOcj~kf#$E>N?muBudKBUl&nTT(8W;^fgZ{G*Ld3z|+YAwA z{|gap@p!H_K!icSIeP}fn|L_legcdBCil7s8TXTt_V)sY=)zhuY8hrnIz_{aiQ~fo z_>D+TvX+cm{P0go%FV%Y{K04zdT#*O9}rD|<<#QNpOrKg4Rk6I=X(@`;=e}4S;G?9 zg&As_01joqIs3Dc$)*lQ%X}8d&l<>OgnYxg7hqU)a2~TuO91j3;4D9@w7t0kux&t@ z(=8PDO*F%sDUia~V5lV#3Mj3`!*I+pdMyH~E~m6v-W-d=-vbdQ&R}K}HI(uciB30A z(h8(8SrBcs9p#2Lx~fjJ#tmF8@S2j&RnU@|-UpnWzhE_?xdAwl0O=~FTLEJIDYqp) zA_xHN0i5pVpygxtp#083%YVR(Nz@*MjN_uWL`DmpjoTU20OW8WpFO8*S;$W0J$dshy9skdl1$UM2F=J-<#UK}6#H{!~ zUlz#4YXg3Rn45#B9Fk%VDLf{6UjE{E{z=&93r$ z%$T8mG00wq8S{c)46>Jsm>rjVSuAyxH$fnj*MvKMQ=(ZU>O}Y7lr$RS2&17fj=()EDJqhj*C#x#XLR;24>Jv-EE4*!j^M_`TF0K(FLX*&{&3aLMsv%2kI*lzH!eQ zalhOkZk`c$>IQKxBkubf#Lc{?vOq9Abc4u;jf7=4h*ONXPj3*HYs7tYgSgQ~-1e%t z0=*Vc?(a1s->HhMjvHviZM;F;okrYiH;BtL;#S-s?ly`mfVy9}L1em-(0zlrHb&fk zZV=bZh%3B79GMXn?`)sA7;`l$+K8NnNc!TCmwbcaX1Cv!Y|OLp(O$go;2U!=hg({U z>sR!_c!{F|{t_R5X;ZiKj_$XV)^oRl+3oxt8@sjO7=A^W&&t8)#1#x`_P`PHhcYud z7N$yf*3j2EVw(kJ5{aRB6VTGH>0_E=bCn(SqfD~YrMgsRb?LuM)G3@_PQa-&a7NV-^i-!F zM5{-%7FS)q{+bfYJ_f<=Ymjj(9PCdVUy#8kiyZgCaee}Jk=OjGs8soG%(c{?YY`rl z9umOyG8Gtc1?@-gV$zx=xyk0~Xa(JiOIO$24aq2c2GqC;;d;*Ws~W5pS4{b11lk4t zYZn|##dv{^HE#p(>whUJxzw_)94Cnb4FjnifxD+jfay>u?&T>&98k|-{0y|`r~<8| zFmzT~L=Sfw(L?K-A&Gf^{D)vdH0uz??O){C*+QfoeqBiz5({$F#a0op0kLqCCAm8S zit6X{1IRvb-N87?9R|9p)9YXp0)N$6kR-_+q~olck2JHaTEZxib2~1pz!J-jD9aL4 z77N~*6mc1P+`B$;cAOd(aXEV2n?7-LLAHoS9!tb}L8EiXzE3E2q_5>Uu-4VQj zsV$iX-y$0>a=6CScvg(O#o5#;td|~~$=aFmzuVNwEZFoF*HYU=P@7KU6*|{lfdV)W z|NdHPp7Sdsq7hVPj0%NK(&R-*Ur}59>NNl}C5#Glu}*(Sf6)8Xf}ep?SX~4{)_rodY!@QrxGKA=(_4g_9h&=>#85K0yq|hs4GM6MiS4sdhY)C?H;N= zQ9A@{H}(*|GgMt_3r8Rik5=3BXX>f3BFYoO*Vj`U3pY+^>^0pLA^dDT^;r?_!pV*L zYESky3SdWlHIKaj$FU?ejo%-p#?v6GSd6*wvGAO`u*?^x4tT!b79jRVe(2I^Ah=dc?B3?snZH2~b5c_q2OYjCdsz!Sh((GX=l9}c1Y7b4UK zqJVNj_~r;Ts=6d*y2@oFe?1B{=~{%^p44{7KNQD_fv&+{Kow?YsW=`68?!iiz74fO zU03>I`W>mh!M=baDN4Ps6_qWT5?WFiA70(el-5I&XO`boSNU%MhcqK^CCKW*SY-_m z{<|1t*<@lY^z-_b_*ZDyC6?kFQJ{04FLjX3kF zI^T3bMqE|X4k5mWu!cW;9ZB;Y0*J}|_?;D_YOE#1N99lB@v-XUkjrFe_}=X|{PNhU z7Qma>SlwcEwuPOOHRe;+b}};WGM_ndv0>iDRpz}j>q_o8+^KelP??}5m1O}ZF+sh@ zS=#`-lK^+r0B}dvm7-kN;28mc@xa-hpmt)75pgj=#m#4iXhw+^8zow7wTlupM8ptf zylb#C0PQ>!iBd1N*hBgBCTgGV>!B=97M}Q|`}M}fx#@nr&S1F`VXIcxbFVI>?@%Jv zt^5!MhOq7c^ni|x@p2P&m~#;jNpW8ikhcc;^g?kD;gOF3$zBBxPeeXf_kmF*{)>E` z1lm_fWa@>AVTMmWhuGDT&Mt0+ubCs_GgNx18enW1R|8b9C{W>83o50V^|IAIOI;*qvz7_dQhj5EpsGWj7MIu9% zru!K(%xZ{z8g6sNf8=NmacSbm-wVs6!l08eY!4FM$1DWSofmY@?51 zcyz<)7*cH*4vfjG45u_CLs(85Ujhuws|YG|fMnlzj5Mp_T_N7rTdB(==U^inOOQd& zB9V;}v#Bq|vI#Zy^jp=`FG7puat+=E%|MHSmb5q#I1AdS%L+Ck!UF?ek6*Nvt$I~W zTH@TVA*{OBigSNNOwq2EJaL_enskM6?sw|o5d6+K_lv&tC*s^&L0^^r1ZH$dhfB8g zNf9dev%Rr&QbmADy$%V?u9wQ(?3UM}5U5)=yI$Y8l}4P|_4>xWXv9_VU~%p#zCtF| zi*svw&exsKgw3{7`$W8tRK9no_JgkGwNtxwzXOzXcWN%gtja$oYQ>cQLdku*FEr@x z10D50{{`~ZcBsjVV0@S$-NPP(15>7Ed{3&H8#0h=3iJc;+oip#1&NZhV-(+BO^9eo z;+%l?7(NBSjPo6&J=|V(gnI$&LEzUQD6l3f&$q`B$d+kpOnO~Pl4QjcT2JyklB|TE zggHXO2HD=A_?HL)H1C0aYMSa`e?nrOrhc3H0c90gqL-wI>0LmeuOl8IkuS^|=+|t4cP_y54Inn@$T~Mb z45G211)jd1S|G`to`IGpU0uk+;7IJKz8TsMR5V@9pqmdetjPTD9n~`hk0YKE%%)$6 z_!xf4vQtdUJ0ZEJA*|XctZp~58*9cxF`92Y6f__44a|6`;Ys+-a};K-Nx6lYl|6)| zR)H7741B>L*uB1f2sjviO8iwXG>e_pVeB<1SxlJYyQm}BlkhF-4qJJti(0|5vT!(~ ztC}aVGmrtUOy1@;%(i#Kmw%hOjCtTd;<>B<4x~HBvU(#)5A{_mTLwLgBolk7cd|#} zLy~6RZ+fXNiCyZ6raDvoFg*Qsk|%OqWe?OkT1CrwaYC%OPj59{VnvX3Ru(K}791TN zMaIxY(jAzeeg;R_f7Mj}?BKlG&(Fkd6Yn8p{~hRCHk*z$x+9K%w?S#hTlQ7cZYmWf z1H{pkYS&H-<^rU86=*^#ODJE_S8Z~qAu$bEDZDC&0a)3)@D6Qv{~SJ3jpZKBSN2uo zYl?OfX!`@uruv}WPH55Gb*DPNrkP!{8?U?sKz6H!hEQRbc-1c=FKJ4~cIG6+@gtkj8u24R!zdD+=LBQeuYR`~Ju%Q*Z zhWJeypbl9K4RNY$*pdkpWs;{6K zsMDaQ?i5{w^v6FBhx&xmxRLy4* z1T_@vBOBld`&?_x`wUZ)an1>6@Vn7byjG@L9IG2(FtKIBp&z*lzgLa-;$O1F99?n8 z>~J;B%7TF=&I7$LQtdCXH@XxtY`03 zhf4lSCp18^I?@)KPK0@bnq&I%D8d;0o-2tbMronpH6Y03JbcR~bns^t|lSa$h;nok3o9B@1IENIS zic#%jYGq<=gXkF$E%qVW@Yi*Ipk1YR|19+$iQNt=+=SW5J7SKC7dpy8D7?W1YOal~ zZ;#R`RHw0pdHjobH zMTeh`wW;)Oeo~FK#^jixJ{P16L72F*k#z&Fpr=vz!&{^Ie_9vX`?F9zQ49Xc3v#sg%6xUN#AZS!aXVtg0@YRLM*mlLo90>d>>ur2L}V){)K(+`wm z&#ImJW*7|zHPIfbYPbfAey#R!@ylG{sCHOYz_hAiD||$5&{HS071<+Ni#?o=T7(7K zG7zj^gzE7j9N6Z#=jQOG{_x2-Nct%<Xe&h zR|5h7D}giNd3CIKgMCZDES%#3 z;FT8s+I<-~Uarn@4l@8b0d}teV0UCW3Lo?b04l&KcmWc2HUMW3V0sMz(;*=M*9HLg z2hPZhUGBCN|Ybtxk;_Af)d_!dRh;zjjIrxy+~iYriIO*2%~ z7?(Q)@c$e*mtR!-IiE8CzaqdIW+*w%HP{vaxE44ImaE#$YlXd`Ull9DLAP(4`kkxYk5fka97|sUk0GX0PIbGIBIoEKpeH&1;B>`02=}4 zz{}{>>mnlk6}2Bb+zj^iiaP)13edG#rGQ)qj?M367DQ8!z!~Q{& z5oDLun#6}>^gH3vZ6<@<+Adgxz^0@>S_#6V(;LPp`(F zac(m1u3w|R&)EGS6=Tmk*Qy<@>~K@ec-N_&Z0uZ8rPsSjJ!NI1K(gXZ3=wNPFvi+8 z$>F{9raDn#1qdJWw)%16Pf7Z?FyCIuABEc-7cRoMa4W*_NkkM6y@qcLX1t@WkyyF| zBigO%cqwKIV$E@yc}P7MVfrQ7rCzm|J(P%!`h!X7ys;Da1S}ghDVlG1SFIz?eU!G- z$4)2;jCybkC0!ponf{!P`q;_zXLRCc-&H&NrPW77)oD$?nb!0p?eJ}C0viqS^6#J2 zjol3g202Om;5M}#JKhwd$M@7e&i!zZwKjmVJWf$n#VQWfeV15gj1s@h-bk!$u5zNQ z!ssd!`9zrsTB-)8fWzNYM|Tm4Kuo_@Tt7v>EQb*iwIlt&sze@C0{D8{k80AXmlz~y{XWL9zd)i{@2i=t1t@mBucn1GhJy|zokaSp z@2lFtYm{~;b7x9e0Pr&kipgN)}5a}tjxaT6*4oj@q3R*-K_JP`r>b}S_jnajB?6Kn4 z>d}97HDQ#FGt3QvXws94wnA)5W5F$cqjun|$`){<{Foa~7Tf{9(hzYI;#TiadxpwL zMOK{H-!g@_zl1LkZKY}qTLkdLQgvGNG!i#a+U7~j6ed7R23?V6eW~jAWsaY;_QpPi ziu*iMutxzLUum;VY3+@9(ue+wWPVsV{#bNyw!~6GgnAbkqBtPbkey(?1svz?RGWpbhl6anEhsFsFl#TyHM5!Y6_lkrKfDt{y+CrK zio+U&1w8>PTa2){4$pxS74!>VAf5!C4#a_b z)Y#N(jZvH7@$9f{t3}NP2rnaSE3rnHXNTVSOAxy!67xN(BYO`JsVv6gzzdbds&R&F zXwgVE_X%9L9B&yyy@rFf>CAYKF8h4M^Fgm@b{_w!8XC6`{1yC#Nk^vs!*jEb=# z_+@>H%Cijw(?3N&R|3cKPt~sr?xQ>vV!0B(v|QN&qKjG2YRNqn`KI-&uR$!rvLyH2 zI^DW5Gi;~i&NJxtnqeofbA>S4L=)+t`3$71UJA9kd%%y?$2K}alH~5H2k8EBIL8P- z3DyC>B*Z%akK2o(_y{O@)?V~DrxCMbFDB+02sykLo%SKpKe{n%hD9&pQe92UkalHZ zZ8yg+t)7bFuh8S3Gs3Ex_sEQy7F+3kQV+`zDuT|?-OAOC+=NS}wTg@Z9S?=U0IvK< zJmLPTF}4_q=pz(BOXS>QMR$kRkXDM(GPa_)&He(GNS1g}&QlBl^Q#5KO0ym(-$KCp zB;ZaGut1maF;hYWl7t@!rj6Vi07OE(2mz_VtU5Ic>0d=$)nYJc+@K+?Cm~!EA+TNw zprMw9Xc`j@22p?V`Jbyt#ENdtZCv?69T2?%BpxQY*U>N9ndA75@O6l@{|hx`_-v%} zq+%#a?FNX}7{qVk*ED)MIQk;;LtRTL6iQtSov#{T)G#`>`#k91#=%Icaapmbj{9Nh z6j-=l?JZ8YdE)rq{W#Xp7_r}i{pJ0b$qfce89oZo>2+F@*&XAk~3JCR2owg^5N4?mG>poxwD~!ZO^Mh^$g2fZBqH z%x6bTwTX2Nph-4pwt^<&fST9W?z8@iT8v5}Msy`sPdwH55_4piI~?D?Baul@BfFO% zHPKi+@qFh2b?nW-EKU5tibmjkV*uF0CYYrOSH4pF-5kv050*XBHF#YB*xe?WrwPCM z73Q0VP+0k2tA9oxr#lqz4Y@>b^1#N0-+mh}Jc#ibbvHW>sy%JnqtTzxBX9on82Om= z>4(&2!%bxv!(y~P4v|l*OaEo14%i-s#hAxP0V2K%iG=b%I~k`d^bfki+##Ubd7vPvx%RD!JNb=Lq@8-b6r1XT2m$aZ z4!(8GN1jYND!m9(0DO#a`dhWz-xY2#a+8sym!6RudJA)40N6!TO_7_7BtGFg%tE~g zfF*Ccf?S9P7krjdH0pjmxyKmiBZ2&o%%- zaTi-ad$|D0U9At~t>LcnG>Bn=o;;f|n4?Jrl)e)2tKPP{8w1C44B^Kz3dA!)E3pDr z35}4H^lnHFzAQcGt)EOkzA?yw|CH%}Nt#lDvGH-!A1_VGf&ZxKUxRq`i{G05 z_DB!^*TP>940H647QRG4{{Lxd1-lH&+EgS;4T?m8N#Fz8&H?KA4mcjfy$02weQ)?E z^}@$8wq;^8(G-8wD|+@r4f`R4&5~9TE!G5i+&;OUbEP4~3Fy%?t_DJkLlwi4UqpZq zXkYli6Y3V*hmmOY!uRIcog)nB7YTY)4WLKiQ(dh4eFg;6T&Rtigr;liN%aA#U~)2A zLTMe1^jE{co*>{}$XLK5#w{rvpEa8xRduW)ncARYW^X2X^Hmt8>_Ve9B7osFDiFl& zdHgya{n%x!{=EMNAM_*kpRXY2^uTRa5V5&YRSsl>s!Xr(b_rl}7;JX@sIFwIBG6ht zgj+i1oK_XQY#WUmXwRUjX5WDWt|^V?xBaaC#g-U8@8GlQQ?*!|hQ^v_aHTrg%3cb` z&Nn^p;kl@mGWIiK#h$tAGGtyFR_W!J)tM5zw*mU>D;N-^fob)obms=x9>0QZ{6q-} zsd=1Nzmh)-Vwxq>bCGMY4EhDaa81WgeBU*7hAl4)C2d~SF_gdir}{|rZcvChw6WPt zFZ#WQFudrO!qvajqP`AspGtSV??i=7EVXnK6}Q6T=HM;d7!9G2#o7|_6k)FFuul<| ze?@NGIsnT8j0D8dD2HZQIhbWp+9L?_xdrtAyeqD&DbW+5v#Kx0uv$*DG6i`)hR6vc zkUbiJuFf(i*AeT^)mnFHMgg{h^r-3GB3ga+^MHsylrceGP_x(ot`}Fkdz?Hr; zO9`gjkP5lDum3}|m|iXAyUe1}0L4i|E3d{l{HPKkJO%=oBM z_$#d5;kC5UlI`;lV|dgB;ng_$@TeNc^wZN|gk$<~Q%6V;RPzm_UJ#^pW1qqyROz;7kwGnz7AwV5VVORGn!E5mPNLeV|71@-Qvk>T&R(aIG`__6pZNvAV+X z%!>9Y`xRO^&_L5zIUHFHwO5^M;UKww2A`VBm5hz2#$fL&*9X8!kI?!!iwwX|2oU!g zm_*df-Y}yum0SS+FW4XOMd0iNAX^e#=?#h0(j?XwB)y`vxzTmuFzvMa8hx9$7Qzli zX=B+DFh+wCIzXr*mni{Zt4(<{S%KvJqT6A_RP_rNx&gzK%isj7{ZVh!tWM3+mL zu-eeRrfDgxA!yGpnbe5aTQLz&Jf~^V-q2LdW)0f}3Igj0>h31>Bk)vFdqLfuh3#QF z;oX)>J`8RF`z$H<7(`vSrj_12p4iVW?3ru=n*_sY~hWPe-}={xbRy|s=> z!wrz52t5gIz98=aBuNLE%l`N01#d)_hC4tXF#!f;1K>*}A}NL=^nn0?NIWw9GQx!v z`?9tBZIc1V%jC&Xd}A+d2w&1iYs2cAc)#}n-UI{h+|>*G5@hxjC!~|T2FQfDdU`QoVv^t&Qn04CZ@&zAT^r4iU|D}0<{Pk7;s6RR^pdcw9*G&G`Xnl8a(_GY{Hd^oB>tfdbE_i#XTCC&@H4yJ6M7_{T z%w1JGZ9T)7=(oz4P-t`p>2V!V(2{nW0%x_Rz0Ar{`r_`O-EfdL>r`j{pOKOI>=@VJ zZUM+gf#aQ|z2W?i0k{v^F^cD(0Z}|QoG!XnDKcLrs^_;0-u3zD0G+K3M2!$}L=5Hg z&xqJEPsS0Mmje(pfzx7&)~$=s7^)rpT5*0-Xs)!im`5E)!Y@GR$wE6v`|ijutvjRv zj8D-V=xw zh;|R_M8Zwe9JV%a@EmVmG9NTeiz#qHR(-_)i_s@6Zdz(R5B1X8t`O6sUn_e%WT&vI zwOz(Ax}tAbO)%4PyFD5YrEktm#@Ob_5d6nvOQ^b2!X4P8cDzak|D*b$hb6 z*X=2TuI$HMX=pmXh6tw7QZ1YbZBZJFy*(c|1D#Rlix<3a&(I#T3L!Hh{d1ZV>z~sK z_>I{ET7En@(U^~$rHy0@e)Y+z31a5N1Tp<4i0KDN#BAhrEo2orT}FDNLon-RYwh|% z{9^ME9Yima=sI}n2_X*(e6L97|r43*k;W+e^){ngiN76hk zlg)=?!aPlLYH$#*&B&5R?=kHrCewoKJxIu;ZTrY1n~I zeOmzFXyACC)@F`wWB`sJKz-Qp&w%I)itx_g(*b~OfJ6Pn@58Qh32vGd=kS&9=0$it z^D$sTn*!rY@oiIJoH$=s-Fm|AQvHn;EmOz>ZHluHMMY}-7)4-=V*Q20j*qZ658WQD zPvC861AhD2UyaLvvwHzXu@57nY7|>7mu}z1RdShrQ!djFxu!pZFOKP^Y)%Tfu*+u1Ma2ub)`7iAOLgIH;9PtLqgWMM6{FbEaIE-J8+?a>Xf*I8QiYCa z&FM-xHjr`F2~}Wx0BRke5{-p!`F>XWGl>J#gR=#za5jTZvL%6l&S?xF@ezIiHjuhV zi(+m#`YuAZH5-ma&uLBgwnbX1b0U0H3>Zv^Wn(i7Mg#Zv?2bas!I<~EpZv4?IB?R7 zwNB1E4Z!~p;P4vgZ#dQ~0Qg=2-~+&UyI5<>TETIm7$uWnAdewrd?9d4Q3ql`iP7|; z0OWMwjB#sG&RTGgP1CUy+Ejmgd&V}>*OK7|VCi=O!?vkwZA*^raGfr>fJf z3&HOWx7IA_I7-X6Ff=fr!Y~Voav%!hFiI!!IjkG)fCGgwz_}g{Du;6ff#v&KW)9^* zbv6OKO{(vii^ZH_xg9gW;#n?&7F_2dgat+I2 z7ruii4?untI3AQy?;+^>pnCII=$#0^QL!9EdK5uhzjCRB5L7Nh5NVdnKAmvg-T3A4 zzp63Z9yYxyh#8^}; z03+W*NCM7^rP|2!BPboQQjLXUItDfo5i1$pCmpfw9L~gui%Q|21OQrGeg=$NKd)uR zjY2@xz!eeGjck5<8XeU0+GzF$>`_d!UV(!Qr-E4Fy8%;=7s~{K2Y$KWBCzYe^s~^Xcu1joz-fs<%r* zLEvuUbvmG+6}=sBF200jC&mE0j{vb;eM>;hXLkYcKLLR4fHU=FG&_Hw^j5#D9c52J zH-)dDsoaDRQo;oU(5(HIENIq_v%dBK7Q28Gw?b>ukk-sxUG-50HamBnf^t@9-JEj` zMmvd-Zl(XM99ZH>FuDi;Qz%jn2hM(zkw<6r5g2jMT?ZrfG#uSMT8guu!Epg`>|TSc zbw@AI+BJB40LL-F+3eAtWT#LJ`E%3+K0{UFy^~jJIac-@!szpjt!uQ&5^Hi2zPFUd z-i5Dfd#$$I6R50sg(T8Dd9C({jm-zLcxa&G59qr_;+^`^WBK)X&qJun10GRYbI(R? zHj6lk_0Ub)aqM`49v^sg<2_2WXA(;RPVL4W$1m^!aGTqk^a{a3gsm7Y$8LR7n;~^+ zgILjiV+@l*BH=1P2OW;Z__Hl!qU$|rNw*c;f)3${pxgYGHrkdBC|*2Mw%dM%E8tx{ z*W23An9&F~SA@-X^#)O@(rkSH+csDU<1z1G)jI{^=Rb{YpZnj@g4x&#)cmK_#(ebS zASixEd!#SQwZxpRT4;SN<2E<_T1)j`X6X(?!m$;c@_Qc1O?t9}+aNE|T1s#8I=5&u zYdPP9QpuDrf|4%bHmRwJ($Voi1ybm!7zC$c^o7;8q+|ZbyMYt79b=^D48X4lP;VfF zxHknvZ;%Z@TL9o%;4Ij#ZFCMb04Xm<15s=?5Rj})$`BHkRY`~jA{SlaC*KPR1uf-W z22SCBAz>#2a5@3%4a7eKqJf~B?_Uo9bOPu4f3>fj=TMBK!&CyqYzI30XFym^Hr|9B z69CA5fDM13O{ra5l)^LKFM=mOCGm<}*~aakXxX;ohsj>nPK@V8pJ*u<#S1nxiWiE& z)-3&6EA(Gxr>8Qo6b(aYbHra6WzaU!S}J;YFMgs;lUNS0v6Pp@{aQ7bV_5VlN zwZ}zKwg1_jRlI`&A|bK}-bKY5q9Uv4tG1eomKmw5U@FMWn3b6tYg%@(WPg^YvU0t3 zAxpa0W>#WaT2_)>e9Ou;DKkqcD>F-e-{;JnWp{Li_mBPToO7P}K9}>H`(>_;AtLB? z-8W$@@4|OP0HQO}2S_V$GWZ@q2^)~*y8_3HT={cE4V%M0*{w!1@B78SI>X8D4TgpM z=$rR3K^}(bxcs2q2w3L#700mZ4~lP@d>H|=jdI~}k!vQNTW~nilO~vT=!dIbE zuLln83Mm5oE#FrAb{;5x+lB!r8r9x`7I+zj9oQLY3^;kX0%2nki-)}f*tW{zblb2m zk$tp5FoQ=67_`M9Fd{5qL>Mp`pI}O3CIme&4O1Eu@xZ4vyg}nRSf$)jk*#|IrapNF zxv2Am%~lvC=0ONSPnlB#GjU5gBwxm%;?tIftw^Q8tlMX37iRnyKK`rPPDDQNS#hGR zl0%=6Z-g*w0Wauz{S*+! z%AB7UDPj9sDmkK`J@If3ZtpH&RZ0S)4p6ibzn-a&?C~FYFO0XAZqulHItI zm!?n9c5cSWzq?GVIs%6p#@~j*4)z^4#kNYq7Oy17jv2Hg2*1Zcu;)v#E;U#?kHYbZ zb@KnfnkL&Om{|V-oXKBdW_TQcB8#wX^ECtcFUo!zW*B)ARw+~vG1JYZ$dJVw_(W$IDAWI{Rys`41?o zX%B0?%gPLm;nBvq|J2vH;;+`b} z&ZsCb(bIs6VY$_>|H}?s;%szeZZ$#1lV~&x1==bHhF)k=X$RRmxD2r!&kHOr(YY?0 zG=Br_3PU<}3-6!_s@A~zckv#!XH#J^>(y&cqsYhcMpC)u*W;l46d9KNEzGbN4~xHr zscyl;^WS2`dke^#9>sE46d42qP&!ILQdqnsskQ9T=hZCdXmRh3ybjjm-a%Z*G7~N# zC)zg=zwT&peExPk1g|%JMBvM7*PB{W7;8^8pcCs&KSLz+YHJTkApIQD1A|`(cU-3_ zyA|#EyVC~J5^k{b=gD}Bk=Kj$^JiZ8Cyl)+ zOttlK07NGNU_(C6h~~)rB*Jl6wCAznE^+_;3~v(>*3t->2ogZ79xLuYkQ*w3D}Oa* zC(?RBM!u(Rx$HSfamO)_h-cbUx5*|wOovX_L!zU{ier-=131mfPgj{qE^pp;+BKj7;$9T zR$}H25@?VhaB2z|V?gu#cg2a(!*$}a_aK@69lT05JzML@#(ps`f;Bo`+-A@W6uxBl zz(9wAhaFjg4nvZ=c_v?S^)~lVL&~3VV1EUk^NtrMcUz1H`i2)Da-b(lr}8F z4lg%H+%w0EyV&l5F#0is5Z>rT7`$0TRdI()OCPOVB8#kU{a>!24|3oWKBz@Lq--?` zKNV;V2IQp=w1cuy`T#CDT6n%7I(mkTpNeP5RwCz#eYPCjee^uPAh!(Sv5{8v}dtD6!*y%{OPm;FLUY9u$qY)E`k##~|f_A2E%d zgQTNB7I#R9CjpkDk2yX+ouRxdb zQ}NOqYG*D7^r`^z)dJ-M=+h9m`0w^}an@wyRC&-CywsxmQK_|pXL+gcqXNt;y@i(qJr$lABq8kr0&Vv!z3Gx} z&)Gp{4;L)9n{5945dx>MzBKDX)A| z&Ds$a-$bv^ch5ksikzetV%smp>2Xhi@Vp>2vU$g+)xLAT&_=(NhpK%wr;8_8DqN$gyY&ds54=)LNvQ-pdg{_VZGAbI_imH8d z4G-CfejIXooPN|HIYOFr1QL)3(18!XRT@6&a8QH`6FO8gaRU0P1hhXW!Z`8aLim6P zRY-gd=Sk30MV3@q?Nk3K?qZSs zDB`#_FM*xjR@{p1|FhU7Zw67%0qBmo78f>P6V4TPvORGSd~j1-JJ#c$xmWpKJy(o7 zSW*#5haQ;weDQeO;{amz!ou#a{ayToEcZm>`hSa;QY~L9N~gaG&5+@;dHh=|^nY1u z&YL!x7#aUD*OSwep1(tUqLnI|`SLFoH@7aUg6-xHLrpLWctj(4BUy9KhN~aA& z>8%Gsg&Yr@Q;n1?xeXq=HC9H;i9qBhfN}_0FGQDz#x3|_s9OMgE-*pI0r6mCC0TwP z2^=x?e?Uyd3g#pe;$O&NXA=nfH4+|ZqP&~Zg7SR2w4)KqAU}_d*5M9Jc8iv>HB7#s zsnS7S0>X88$a#%&>2i)O3?{T9$439jJ9?|ptygO+0jC`-O z=!liFK%~kB8!q1kqM)ThIQQdf-^ymnJ#s_5WOcXnMMo*PJahwKsha8Zel_cX=ZP(q zDRSQX)xK>lp^rQtQPVAj$-cj0l;35!WIueXjj|~6uYDvh`YPDk{R^IJe1+HgK8#mx zw8&n(+$}-bZjtXo!tu6B=19m<8B}@T7)La@O}W*p|I2>-)ASW4iAvw&a&vl;yD#)0 zTFD#D@)MEIQ-HcMQJEkQ$HS3C1#K}%lG-VrNYa-d%WddBv<*1B+9{*61#|xS0svX; zF*6g@ICjRaoR{~4 zpk8RpF%L4)gmw;@U zYCWu(Pg|JwhN?d`h{di{WoZa{hkTrJvZL~^yc1wGos@LBHy-+Qu1DU=D5<-FCR~dAa~9x4ZmjRD zydcj8+PE&t=#c*>pR*-Nw&y;gF^16WR4NcX}m>@1BJ;Q z3QJ%0ZDfMo3P0zND z1*-zs$=#tD`Je#v#-Y_wx`YSAwQRvQq+1q0GJ(w(V6HYy?WN$uMd5On?sf~x5IQ-x z)dV(PfO*@nv%Qpl;lb>P|IKUn>fu##DdpuLq(bCtzsN2%@8h|^X(O94q@W!Il zYBUymfHu>F)=;2T#IS_k%Fw2tqSVoc6dNO9c5h`zcv-!nvKDl3=SG^)UqN-kod>tJ z&F+I0szbYRzN(LcPX9`f9_)+Vy%U-n1bc)QdsOU?i-|RJPY!R$EVZZjK541i-jqVF5M}?!O%- zs-LVtYhyxtQ=mcCoIy&5rlruFmZsl(r`oq*kTT0AQw+aaw2?!(x1rn)2z>X+`#Ul8 zys@Yc`*_N{XkYV@$~jqnDAt!YMp9nbvZl>*ybq}J{knKwb%D#w6bLas6^?&TdoGJ3CK-^dok z;XrIxwmVlD)qqC3d>8*V+7Dft?9L9%HV=hMCwp z^wd5_y@_Rbyd$|2*x73_s^|k{`40Y6Jn-diL4FCmKNOxeMRzyBSHi9w-VgZel#k^5 zeS8Oh2772nVFY{YWMMPb{CXuvz6OL7uUCqlz41T;&Rcj!NaqE28dq}Va9D!=b)_(_ zL}t-=eKUXsEh#n%I8CQ0V{@AsfY%TpCVK=?SU`;6R$!odrwOn16iyz1U5? ze~L0`>JhjSNt;OE*o#spIGl7iI__gl;J*Tg9Qdu|8ulKZY51t`yl2>XKb%$Gpq%8p z@7)o)w}Dpo5u9ZrZxdmAbKToSSZcw}PWh+}F7fDVJYzULWz1lxN3@bXiRDaH`pGs# z@NdwRO;s{@L2yL|7bz4B9Am02QV=XQxJZ>I`(s($H1yVg+#Xb#1c=Z^fQYaF5n+I= zpN0a^2ukw(9_Jx=7;Wu_w#kOJ`V~^N-@{_kmg){&+hpJR=}K?C&TzzqD(J!ipkM|4 z2pd~kkjvO~n#dw%K*8?83JMURfB+F;0V2WxSv>;^j)90=!7N?DOxA0rVjl_DHRWl0 zL(3FH%M`s9ftERtL(o&6o_dpEWxUzsbb zuLk9!00}5zfQYaF5n+HVFThasK1jH)0DYo6@DL^!Qw{w(82Zt*H8_O<{qBMY!TNO! z=+}X*o29&)@D5Pv(_S0%t$g+L8W4E#d^=3K_$K9jxdRYJ&Q{WzW+H}~sdcZQ5t*&T zM@J!rBK{8%`YPrDrk=+2H1Ez6N+4=k`g62rQ={K|=z)bm(O;qz_Kv&e(XiyHH7ypM!9`=(R3V zvi0rGNui!eA88NHG;a!RckUQMD{L=lMHsaEico*-hCqC`^Q(B^yPf;bQzo}UPu$|h zl6VgG3Se=eDP&ncPZ`4Fy?XpRh(AXeI8T}Cj06GIwG+rNgLqxbdrwA1UTVSmI-Ian zb{O{$4Z;K(2GGl(H!_pclCyRI4l7nNou`3JfV~JXqaJ`6Sor~<%LHfxV1k0V=7R=c zO9Jdu55PW<5C@irngG8C4pWr3@4p)xBY8NH8WDNT19G&?*@o9)PLMA(ZkRcIpY?!!uMSF$FDybQkyd0B+T z%OdQ?4eqb%ch#gfkRCQ)M|4}c(Ok{O!?;D5QT_+AX5WD?O_eWFR>`00p_iObz+T9I2O#M%zgzDCm0@W%H`z4mQRGB3= z0TcSf73$_%5Z$Deyc0_x!o-pRBEkTPyAwq@4XX35Ks!93T1{bV?^JroFTtC*fxo^} zxn6z}X&EI-JFDHwCYLDvoFzymL+?g{cQ*IlQtCdC_j<8FVZoU~`j`D(bVJXEU0~>6 zU*LA(v}EWi@c6 zwleA$K5oJo0t|Xb@^)o|mOU{DDiS9?w2@$YcXy+(fxElu%E&OGx@<8y0HvL>j;ZiVJ&gbv!T|Q4G^Av_FjxVjLD|# zXRCdkpV(^u*SoY7ON?W-tLJ5y4Q=AR(KyEP- zxk44FU>epfP=OA|Wh)C!3=@E}>oN46et-)TU}plHTo1s>Xnz2By$SFi;0$_P`N-)t z0KbF1=tOLt5{`r8V*0<83Gg-GOk4*Eml=TMB>aOghMmKz?1ahyJo~iC#=tqaPMPn_ zH2@zbK)q;H1~s|mM$szQJyb7RbUEx^9gx#fB{K&&4?KY;H`M^Vi2%|2hRRn4MDKeq zro`8p00#mm=SisCzyKUcfaomO35d>e0gg5lJ|6k2T7=Iueb)y>P9k!={PVy1lubQJWIWm8E+nqYCK zvt3?gyR(5I-bfM;TVMpS;ar#c0%ntGdVHY?H~~1jHYl^4U&4rF%me~NkD*RL^ceO6 z&}jlZ0~~cDrhtCgjNP;wmHG0ko2z{Zo0Osdg9WgUtpcwL8OQn7tI z<0foe$2CQ?2lOx4Y~9lslq`iYPCTuQ2%py#ro8TttJ6#Zl~WForWNVF1L9Rl&nqXJ4g&$rKm5D+3lU^n9QFO7|PTPc+sfPw3k`d{ zxUtXZzV~Nfq4?Cg)okt$V4Rj^DlyuueK%w1si5QI4qM&maf+E5KMTCJ8QGtoP z7aD(AplccTOb1RzLXjTDl?;DEuxih*G}Ya zWrO@D?2mhr6WGVQm78^S-MAPlSY0d|hp20B6RNHh&lbL;+-lqPM6kL7MW`cCL|CAR zFi>*#DE))SXk0m0e_c7h{x9QPpqO($4~D_YJqca7a{m5o*B(?jZ$bNWdr**H!~^f$ zUbk226PATLgR>GWs$jqECKgi!3wH)PxL0{OES5JEi+c78O;`y6%bUUWy{kMP77J$< zNi88)DmvZSCamM|a6Ml$e9ye6w6oL~Y&ZtsKdcM2PUW#Hag}2NRm$fiHkq^lzVFf~VC&?60#Se)0PlH~bENr}n2mGS6sl zxgS%5#$5x4`)loj&JEgI8e!jL5`h@WAD}_oZvZwSK)pe`G9Wc*032un{1!N`e4vb& zwAlds0l7h2LWMJil@N8*W}J#`Z327)I5bqfrvVnZtJ}?O!%F*U4cNbf<~H)pKcGZf zM%s;@BJ~uYGe(fSI8<6IxD6_WZ`d#e;CmdG2^sWM=JS9~??@E`eEU9B{;4m}1XjEeXLRK%?Sfr|hVebrwnb1b&a2-Ysgy1!PQh--={b47d+ zNc^7j8^2LDbVMtaTsp{Ozuxuw3`vTz@3%i7Nl9Ojc6^)PQum=R@PhiS(t(ZoR%sI% zNVywd`O{OfLL$orxj%$_iTlu#BBlFLrH$-?HY1NJ=_NqqeKh_-56EM&52PF@r<(!j zEA)Hd^cNoC7Uy(i@%4C_Xe9d}Pobpm_raM7zI|IrNM`E*1JDMw<#?aAb_b`m)6=rb zmRu$=&Uo?G%cMmaX$sQxU2miO%Gi#yXpPMgykcGCl^wYjzR#w_`i~*iYCV zui_fvc&0T`8;87!{0(_igz@I{$FLDaSj+I!a!bWv-C8)EMHZ2{)%4@%`QRex$!Zb8 zYK|-x_uZAiaM(N;tO`r5qfB5w!?Af5xU$&t@03L{L!}+~faS*03YA|?v zFgog3tT?2ij>$4{I0hUl$}e2J2t0Q#9aeZ1aXWuN>$?RH=jdTA9l9J_-t-SFd@Q2Va}h@Q_wnEWHwkFG`pX|xKtTVIW69^*|DunRcP z|EMerFP%G7y1iK9S!Dw0C8To?VGB+wqn&4AXOgZTNr&;ZP(7@@F}|iR$jmYUHwJLT zPYS*|aqQ zTJW&)S7nj&JLEd$ekyX)`>BO;pUY_YXQ@#i7-mL&@aa%Ki7?3|!e78~{-$hjK4So$ zg!Q}!>j8Lh==sgqUKeiydvyGZIJTIo;WiDhO~nSe zmrZQ1)7fIG#^O8jyK=3?`31~NW^O}P!Bmn^Dy*5&wJpFD$S4!?&%jyyCwA5ffJ>~R zH#N25VY;J>3FISyaI2uHsrgeG8x9Oz9+R#(EN3%;J*$IZs=~t7oWnlFFp`y9{h?sP z`{BsS>d^d}E5Q5~w)!vZqYVot@osTI&4K~$+`CO+T?Ck9W2?_APlg9`go3RY=*}Hu z0;@*G@$%}hu?2r$NlmW_EX$qS+ywTL0Q1_IdI7uO!>idKq>{4@apzV)6l$}F1(?); z9lxMV!{P=Cd;>P}AEiB>OD&EDOcl?r28@YkcLU$9f0UNIQY;l!tc&Is^eVR0>TTem zu&83IhPrd}b?%&=_u+KzrINP+i@T^~QayHgu!>Ny6~nOK$OLu*bpUrv(7yZ^>M;zF zq@RbLr<)%r-h!=>+b*IW+XJo#FDmhays+#hObi>To{c%QlSVG<3W8S=PYB*dHS7<) zvt7;y5jOXswcwmmqhz*7!UJu$$%0#ZM?TU{O~AKAxdPPxC+(^KPyeF-zdQ$@V|e8s@|? ziU6Nm+=m7{RQAHZ&#RrK;8Y{P` z>2)!Z|KrY`VPe!Eh*6T&VC06cTGeScgmWBRU_!PPUT7QT&h25sJ%rqIQ#}vbC(i}h zf6l#!)`Pajs$N}}y!pV5FyTHATq9rEN?G0FoQw#n#~&lN!9{Pv+o>KWLTWB+g++7O z6Eg}|qqn~*)M1K&v(TmvDG8@Ex)8NExIf}L+|_8pxJD=q+IT3PRy*M28Ab!n&!Ny+ z3^)TD$51A=0!M^P$oKa{86xhA1Y=Yh0C*PwG-6G;OxoKGnP+c`XXRF0)b@1)^)LC|2QVuAtSH`B-B2BDi96N`ldAS)eMAep z>fuzD(@1?zPJ%JcG*a773o@vistkW4UO8A@jrE!oUuU7|#1)vITLXNNfmD}epfaI% zB+y#_MD+tE()BsD)sMe1QyZ&2Ow(hvJftQeJT`-eX5tYect}my@y05yl?Fk#CTbVk z_xGd!5!DR$G0uB#PP0&LG3plDu5O}s3@d;uRDczjIP7W?;A3RAu4EH-p^2ItcNPR* zFi5&l<{P;rY%8ai`ZQHL$W?gAYpSNn|HT8ogqqB@HdRMcvw}%-b~I{EYu2)vx@n{o zG+jl0OJ=8ktG%i2$A;NcF>)`1qJo~xehnldTFKs&U1+90m+~ukZOXUs7cKT?xRFDz z)E85s!}AvS)V}8G1o>4&B(#8Z1%Pz6P>0GB@vypu`W)3-rMw2l4JZ#Ha%7}BC0lR} zRPBytx|Ccxxhx;+`M=&5D%~S+RxX{t89N%OzA%yOMWy9h5b9T5SUgj3?~N!@bW!vN zNDG9a$$JRXJEQP#lrSzG#T|!qN2Anuc`y<$M5#-|8`IT1#Fz!xt+NO(3AM$P|mGT%iH=W{F|IeXvGCVOf+~tc`a!;Z`C)xR9V-_Zv!W9Nl8Ul<30N;pO#* z;%=rzd=u_#0@okq%ZpRDTgHTy62&f9%Dq?vUb8Y(`wW2wS}UYvrB|t=YQ40v`_ONA z=*V=cOBS&PO*x{|AMeo+Z2Fx$_>((f*$r z&z4-J-W%RLu9hJR6?DQBwu$2#f}^XY&zYdkvdCYM0&UgN@;bOtO1aKb1yYwvDwTyjfS}eU8Di>tnxCE>!`z8#YRNZ<3f#DY@3Ah! ztp&f6zoIopON^g>6N?>Rt38c)Vn=br?k9sT=}p{Cg0Iv5Ai`eUO@g~jz7yfsk&f`U zBD@#rIL-Riebsi(DCuGSa+5CvL8*SZ$svT-Tj#|y*LU;UINvo=Bj8cAl@A(LicK2G zq)H1uB18YWSEG}Ft$e8%4P`(@K}%)%2yk|_Q}3QEB8}ovX%vr2t0Nc)CxNh(+|UG4 z1`uKcD0K<4&rUI!#76Z;ecK37xx9oH>9Ae4mYLz zr~A`i0(M-oni%&!CFbafuTdhNHzU!Rtj70$ix|lk&(0Oq><&Cz21^rZPSPUbd!hJ; zYXrU-dJ*a55*1d~BDt{jnEL?&kLwx*FBH2=?$+bVBJj`Sz|3vLSw$T9EjHr*1z(y> zU~XB7k3i|tkiaVU7Phs`p(pPYEVE8-uXbq&J5@`oSc{3uNcK^C^>~7X`ZCfGy)To3 zt35GW!{gl9>_CcoGOjrcMwXz2q>89aNs_8#D_XMysp?hM@~ha1RCSAd4oa==pr$*i z?f~VEzA&oy>}B#0hgrGD(cxCw@_ZKEQmkVXK!e~sYy`lj9o1{)ryzfRN41~q1;x6K zYGO%u#L$@q?!Y*7LojES8@KYw*j;JE-SvpGLKGUW1=D>WOxH-K`wOC)>5c@`K^?+- zQFn>H+!E0!IU8~!_}629#5avg@B)RY?(joEFP_^$VmdhSDqbw=q|VB*A|kjkUW0>15Qa7b*S?vRSaQR{89(Ydarl!l}Et9*USNA0zR(4ZIP&>sd&^qmh z4pG%zq4v8M!W;Hu(cRT_Gg!Gr&x~@bi)Ti;%*zN?tN`|&4puI9Qxxi8<&rCwJoU;obAN5_i4JLTTizE9BOsH`J)gR|O+)r(8k)MO-0v5Y} z`>XT9W1G~c+53M>LM7e+B%%Jc40S?yFh`qEkLuyhJ!}G7EWjLXd?N>_w_Yh{LechO zhJTI;t(ib`xADmX)nivc!&Mi--flzJ>DxO)6@^FZisGt^ZiCehG}0&ynvpFv>Znqy zpM#Z(Iw}=ldvq{PPcArH2P>68+xsMqH2SFa@QAoP1L6e`hXe6h6XF2&qA!w)lXo# z;@R|}>QWg+&3AMtyg+^$qKRnV^&@eVznPFlJUe?-LN)G+m)=%nQY#K(;=aNM=@!w^4l1RC6a5PIbZ z^$}`-%6S9S)P3kPq)vCD7(4!>W}4>2ON~aTG|&iP?sO1d5FS8&coap3tAVzn><8Wm z>EO}sLt8;x<3!&62yoNH>?PoP0N&CBzP%QlO&_T$VYAcQHpJe;F&A64I8@Mk1(vrh ziyno3$2}m(8KvG47PKN1lqPteHGz&1pcQSIJX*cMiq>)ZXta*#yDuEAP6)B}NxaN$ z{qyL$ZJl!s?pri*`yHi8*m~FZp|;))T5juyudau!0p8IB{y{A`YwA=-gowUU7yX*L zJS1hjJNNV*p@#pzT42xAV5#HWhoD4N&tQ;8t|@%GFTl~cie(jJ)BzL4o8dU5Ou&kXi9>b}hbFq{Iyyve26X3G z_1f&ZfHwhnz6m(C7ML9!t0s2iIy(~e(r?8rcPOm%g|%b20zaUW=05Z}fI3~H&Zv`X zelBJjOk9ru)G!#^ca54H&AEDOx!wYT3)iUel=r%#V7XRj*@cZ6r?#z4DRv)PhLnZl z)CqM8vuC0^_r#*m+T4Tcv_<#qt2#;iM!bArRUJ$ER8Pj%yP!7#U(-} z>du`a%`k&B8lXm3kIPGGRYuyd%cOl{qz$@E+80Jz-^-*Oyra5=GfcZo;(p`Bj!2^k zg<3)5%69X#=(42Cq`hIJwYf~%D@Iz&Kw7$k>@{#b@Z=yHuPz#f*a6u13=JHY5Ng459F#@O{;DvKx7Q+x=(Y} z$DAt-4)23CZ7mXSh2_u(=l1g4x#s~SXoWOYXxFlGG?hw^uehGfBO6q~J~?CcOm4=ye_TZPw-l<_V_Z^FSsExSedg?m$1$hY~)=gG#tvBlMe0T1r3q$jB zVJ)g}^7ZOai~JAlkIvrE5-PvslvJGP#GEim*c^6Zu3@%2cdChn1uVQs`{GQtI-U7$*?6z$^gfd=qA@!1T9aN2jWD!-Ju}6%3YI zjE^&$z)m7-iAF+yYxOkrKYzFto#tuk+tQFZTr$9X)UVay^egYn{_jY_^ z+62}eU_4V@?bz~J>LcO7+@WB$JMcvz6WAZfe-7q`Wp7fK$#0XWH>n-5@LVbR+uE=jz|8=BVXoR96@suR$Dp-8z~u$6`Cminu(9LF6^oXR1wP+>t4R9IxFu#<91@0wh>BEXDu z0f0~49BP}@z&TT-wvQ$i+_fq^1Uhzoq1vGdzTx1nsi`J4CeBlbLD%wNU8!byW}fO)qBQnLv05c)jw+s8pT$r>MaR3;JuA-Eb6t=7kj8SB=00IP0-ZD1jl^+TL64X3JEqOkc-}g zcx;bJX61JjHuC|{Z5{A97|^m2t<(@$M}UdNwO#m#2QhNkr00mH8{Vgd5-zxZT45@? zae;b!f(6k5hevWEWfq`HG}v;1I@eZ!2Uf9U-VioqRADPQ?-m@_yal^4;%>m3eI<9U zcR2*uLjuH=eUG=}ZdXS{A603IG^xmi)j%&2FMwFR9V<+aLF8v{S2H`k4T?YH)@8v| zUxLan$Cj1g%_O`0d8S(Ji&&&iwaIglf|E;$Y{gPFMvhU?e^`pCm`Z}3R)iA=8w*>r zF?XsrCXM14(PbYOSF_I{J1scS;n7~`8pPr~et7h2P|6P@gqPd1w8MpwY+i}_rmW$m zZf-SG{u0vh4~tNCQ1QA85r%J;Qd?~luTo1zG8OkyS!%Br8S+hBbN(`rP!u^WmD}rp z^QjvKCf+GgE|JNSCA*lctG?C4n!`O)#R?keT!ftxl(*t19-) z3w4^=z*)UQ9Xg>m9)it;rN>EK1Yc4Vf_4yLC`M*W7GVfZW=j-d2(Eu2Z+4UsmHR)) zNw+uLWs1y~t25#@&}z7=v%VURQIsC; z#+>)4#qw4_?Ysv&`;4+<^sY)R_7q;utX}iR6mqQ8#8_!8?taLYJf|14wa{%3BDa|l4rV*2X`%YC7mN3CD=_}PXFZi9{BZ^LayTB)qz) z8lO_@z;0iq_R6jZnwYfH#H7^GL;qIpBXU^|mejWu;sQ;Bj_Ul0C{{!xc{{QbtFTvw zGFV^1j4sUnuH zD%^usEz#FzwQ9G9$A*1~hrmuvLi;i|REsn~aV;u3uo90tgKVTv3S!~!dF>&nVcxv91+dg6V;&1Xee;^Pp)_f|!H(kW*u1vR zprh}cQmxKJSVQxK@EQ@;o1aOmMR+r6byT-@$<3xSHQ9NWk+2tXQX3>Ph`JX%gWSQU z)aUy)W9{>I=p$&!i5~?H?lzqrVmXZR6co5gLcp%qdd;Z*|8CH zyfc((NV}M%MQ2Db3o9);LpB_Cdfvon9B|G&ib)*-5Rg{t%GI{I^?$jdEBb5t=bbeZ zNQ{uy-IX1G3{6)iGBo0Gbb3?qkoP$J=0YJ3%RjCzvd9I9;&-cqBOkRGB>+3=x)H}p zE9WGa9Y;O2?&N=+mAIh7$l(74 znT=PEu2)A76Iz6`$?`~d?!j51Hd!F}c)NLqRI(l$)lO{L$)Xsv)|a;kZdD?=ghl8| zhZjwlxdPMGot^Tc4hxpH5v0xApn9kdyJ8M*!rczjOvqM&j2!H?QOydUao$ids{oc| z0y_qa>h93pw{4^PzD0fl6pJ^j9m2!w))DN zfQ!vHn0ALK zy$4gv zF`+qR21cyE7ADe&pq5G>5fGKWm6S#VE=S0S0EHk_L`P5Z0*I*p%Th1iimkwm!%8p_ z^dw@pfQUUke;(j%E?fPQ8Y@o$A#Zf6VRGt|^hVwojV|YAG`g4?>&3b0T+l^8qe~~L zW|}xP1gGeiF$PM7mGWLjuR0zND-lC3a(M;3!O%FMg&|g|33flk<2Ls8V$rW$2@IED z5}~lhW`J2tU|R&3zZYBoin=?zWG2&Y#>B`jSEy<81z1H-_ROo;Wg1pZdwPguHni3o zOkg7fm_3~(ZO1OtuwbrGuvCDpG=X&!V6JrE%I&nVY7DYs^`rBWov$F5DYyTCWoUU; zunC*nSe`9FTiU_I;(g#m_|X3M0uV=DX&}E($T$j6Cvs09qxm~OJ=CmE0>|gWeA6j` zoNFLIOvqRPt`iy6)83ZYB4R?G1Dpq5SLcVftvA%Rv_tw)6UbnI=>C|_a(3Y4)(?oF zOF8(SW}9P?WUIJA!l{Jgveb2BiiPLAr6Qfr3w|fdU9aQxj`PpLqL|+8O4G7i@Eq}m zn&~`*e4^}$`5%n97wz+KlaxOK=YcoWE(7M{fvW3;;6MW!dX^;11IZ{U$^LXtGR{lT z*$F;jjI{aF^d*k91D3|D-Kn;f4+1%9r~0705J=m0s$G%_07YjqHsxD98!+GV9mYZD z@EXl4$3yOOJJq!82}A_VHZ9jDrN6@yeqZdmQ;BMZ^ct{_*Qs2WzrkOlWU3+C%#SSITp{G_{Y$!YfG`hlW*}H zhBP!>%S0NVQil|W5N8uKkmg0>{jK`@Wj*lU=PisJFG9qm@9~|~U-3Yh(}#3h$o;TX z%mTwDN{yNlv%pjzqo!PlW)c&6`9Olta$2gBBOr3*+v;}bO9tRs*w|ZC55OV-qTx$1 z0qz4%^(;rTz#WA}Y{A z--m~c3bl*#YJ=A*;+018^ez3H#IIO@MC!Cu1Kxb!Q$Hq4udGoVOatK0?NA z)OCtF4xKR|p8$ZMr9$-paBB8pRrNXp@KFN9-Wov^woo}yN&&dv1UL^ki}$PFHEfA% z)Ny}N{`<(OzhO|yslfz}Rp(2zy!{hYCFMg_6JafDt6*V&Te#6L#tmiH<}$nm$-+C+acf_{{U6lpGesC6_#;- z!2_+#C$eh~sO@a!vcCaacmUqM7^LeDp!%DOhZ6_X-tGCqK|ijQwW7bSotw0?lvyyf zV}~Y#KE(c(k$6G<5Y^;hJdo6PlGLz~*O(fn43KCF8B)`Ku#ISH|3#QU&{B@(0_XUL zYQM>C4M1{tz8X{)AR11ZX@AHB*c&+1m|om_kwxHH{YXup8Ut(;YZH8XsYEoKHgn8}BG=!>T_~T@lML_kk{&zU3eZ zmf%|sTH}F;V%c+t)FX`yA`gqYrO?i{eyTQVtVi|oSlF)rHJ~#XCif*Y1F+uq;E?*7mZBR0&B zPq{wSrvJi1Tt9n%U-lPtO8kY%)xNwcHQK`7_^+CcLS3HhwXmB1qQYxQ#PE!XWTeX# zkBUJ$LuqiJ3bDbc%O{62?F5|FU!n>r9mt;l662DZ>jG5>=NA1Hs*q1$JmMBj+%Ul` z)C~BcnH#E*R8%23CT=Hyv-&GkAx)t>uR^SNV6HZE5}D-)Hf2-~Vat!GJ*@U2?3E+x zF*%EJ?Q1oi$_{362a`^fR$M1Z|FVm8!zLljxBd>oQ(vo|2og>1o5PlWgQK}WLtb8x zj^Tk6NFkeJ_y(#<(FNtux&oE5Fc*ezG{-m*))2Jh_ve5!?pqY3-3FjcfOLSnES(@^Mn=XgKdOF!O)|)jzO3i3Y8SS| zulAL%xfX3z6Rn*{IqZjz-U0j|ADxdN`KS**TEN|tt8KVvrNwPnR1y}=3b8SId-k`qZb^5X=wFf9fE^fQb&4scRVsr_ghrV8`yv2GHXn(WK zKdYVPd=MS{S$&LZzj84r$V-(Z>jl=W|I6IiST;gISgIp)dUCI1l91fXEwgREs9WMT zw4^JH@FiJXw;ph+$|mGgSrJAe+XfG_ML_Eyha#B|zFpYb*Z7QTw^+xwWZkOOVf3$7 ztF!c-c))?Ljn#4dHr-j81BaaDMxlq{ER`1Au|~34T@3@yqD|nI3CJGrTRIbZ@* z;nwQ!D!#_u3n`cP5tlBT)gLUQ?ju*5;7%ihxQ+c0xY<$tQZAl=uZ5gb8(ZXDWJmsA zm_QNw)aG4dBk!8%d513D_Hm(lPYK{QVF&+Gf06qjV%Pc0d9n$Y&*yI%A~0Tf|WV+gaW?@?3O za~IS>@(jp<{XEHYgjRuy+ttjFL;shh=3EZCO8@g~LbY3@%TX@jzMJ7YFqI8XVnYw) zE4SdPB&tNVwx+L$7Zs&aIW7$<$DrU`%B}9^#I;;-8xC$S>)bd!`OtNOo4YwX@(-%u z7eSEnFPf%Kc+j`@%s?9*&>J4FhX;q<+7nhDf2cgEn7YDiEGGt`;n^fwoj$ z2-~f0pmmV{z{9rB=O(g>opWvS&j=l9pydYdnxgjtj_-&H)c~`TV@$lNfx&r!cIRu{ z(auZQrO_UAe8Ff35uld7K&tDVXl^c}mM*urgPG_HMti}in~Bju;GAiw%`Z_X0h_YD z+4^MK2JCRT+hCG}9WVa4^;a2JtMGouok&ZO#rMHp8>`O)#2Cc>o_HtxH5U7Qn)h&5yq zY_k#NCag(le=z1k_c%lIc{XrXH_|d2l6&IQ^dC3U9H>{;iwMMqjC|J2?b}UP@U|VxVQ_a=rX1vL-E^kJ@O;Y3 zyD0}Cw>xw$q11vaa^MT4GA@$h{WHi-Q!3j5C1|O#oC2JE&9p4}S|mg?*OsQ7C(SU+ zzG;)bNU#xo%~eR;l*9Y0r52oQd8WD6q3Lo&(glATAi`lp$QMS#&zfuT2^vxYo6eHUyM}hkM~gnWT|zJBSh2EX4ZPS2^vm<vK`x30?5wL^^Shf|Vr1?TOa<$psMN0;oDQ zM=CjqI?7n-$+vhKA+DVm^T-xY71EqBT4MCqcnEkHWcmyI7bBr>WpDy`{)~hGA^7e` zI&rxg|FrGz-^Cx|Kv1K|SavK%>(vh4lltS#R1wRj#~F6^$FjwU=gJxHABnt- zo$WgIXKY!V7FW{GP_B;<)}bfwH(sT?clGSiXC^KG&6!B6Vx5Z{7zOjh6$FcQowDaSBhkMczG`Z?Aba31#2vls! zs3?hYhl;t`Jr{X{Npwg46Lj(jwCh1j@s^ROb-ygUioKOp7;WE9NI?i^@2*972MEk@ zUtwovA6;noExAhDYmr|D3_rT#YOBS_Q$ez@t#)_PD+YQdA{-(IY0hp(mvH$rYWcO0O3+i=F_4S}8oI5wK{*0Rg=-a z^uoisWG!C)7t$UbrO}xRE&+9;`CB-qPXAWU88b+jF3C4>ju4#vZ9Rv!fg|SUY0m?H z-<9a`X6RfS;qSvNqgG<)H zKGYHU9Pb$&5iTTkpg0p8ill$tJm^zWM+E)-1|~tD0}h=*xs`;3c?QEg8zAgP4D4SV zjx;>KPBiedWYnP+e{)=9=4Lxnw5&*CAUWE3)`DOLei5l!mY$QOA`r;1iAb27s-@`( zc39j+W$IaNz_wnK=tbo~!nZpI#zQb-=`2z`N**Fj5n z)}T-l;7|g@h+GhbH5=5f0^ocTU@QO+chHu}9|AD1BV77TJgn=ejh3Io1AVdF_fJQy zv&A{Z;J6Nk_b#Xh#|2nV#4g1HIiV`3z)?GEBb@yVz=Z^;)&o$*1T;1(K4SuO0;i_4 z*3TJh08S=AY^tc!CPi3l0^mv$U^n2DbkSmsjJ5~LavBJq>7r#hPr~YC{cgl*c0D-F zhUgdw<(W9u0Hj9V#(E&Kf1b7rU+qw$T9lGf4;k?I&A)mWyS#zH> zI31-jfqemW8fiL2#|F+w6Q@^z<3(D@3n*`JF3H=(L-ju&e&O8ddN#DHmg2m_VD~1m z!ybV;*`b%Z8SH+Byn>c$z*69x>ZT>8#2`UTVH3|skw7<#iUYN)klw936dh%7zMnW_ z?H_36V!;IEz0#srER}(ZWik}Sj+i%e&YYGwPXmq@X{Lh2Vf3F1>hf$NHC{NehfHXq|Mq2Z-)1FM=yjMn;gZZ z7o)pSjMm{j?(H~ExZ$|OF7(toIBzh7c!Gq;u7?oWXu`04=|htc8gPnwX~ntS4M2qe zBP?~BDPk!9s`gVRz+t2n(pqd~*Icg+WAoCrDJ`IpIA5m&XIo$GI(_xc%9{4mI*R9vep;e!7ED&V@?yJ@g6@CtZNx|V zX$$3}$biWH+6~+U{tmpww_4nX9!C7){#p;+G#vvyffb0~DdHWq@wXuULVv>=u8y9M z5PlRtbPz^6@5Te^x(~dK9+0V`>O?)DO4)&bS}H>?rwX0KbJ?M~t^>}l4D=0dG60_? zK)r8pWk6Klw3+z7Ccq`Y88kp!)U-LQNTot04g<6f`NG6B55ntGuP&n1-Z@BAeAyhE z1fDXX4g(0iBZ0PgncjF<{7pRGJ(A}X(&&Gz!DxC|M&3|H)FWJCVq_PLKzr&ry{*NiE)AZ4LmJgM)T!hbLm-W4s3ANsP)ja39{e)IpDbR+ z^Vg=AE9qs#e}Q=3P63qm{(7+zhAVP%DXkNvCk7qxk6~WdCKy8s)7TLg7%hROZFY5I zJ{Eim!1URYSoX_Y%r5pCg74TqIY^6;7lG3=gD@AQ;o-m_ZG?OiilQ;<;NEA9Iw~!W zF61NSR_@NY(ikU}J_IbRUP|pVRmTKEG?KrIXAor_I`76f z#UxoPNJhhqZ=Z!!7-nqQUOUW)11(9K3>uoI(Jzd7@7W4@I=k?&(u6f%KZo0_nfxil z$sVG4mXOYy)*xDJeP2`prU`!iDc@-1FDX*|FB+oj95PeV7o zo^+iqY-D?qg1nyeIJ9Tv7|4uzGKEbWs!c}qUM{)1dpaTVH<)|RP;IR9TRf2c$+IqR z|1|CuGS1M5N^Udir16j`*fV|yPTnw7a=Q#b3jyktoGC+1fT-lE0GMt9{2VxkhiSLU ztMM={M;l0PWAUc3)j68dm7Z~oON?@Rf`;bj9GGO&{WHz;5aOob*J(I!+2}}+X9>b1 z@l%IuSO161;qB?6@{o=nl}A689qF_$T~~DvGLEKN+mrX8tZl+GjgjeNQrib34&lQ{ zs~N8K;HGu=@{9&f41R+~82C6E(g)#-Foqd_0^wsi=M3d8%Kauhb9{K}U4)PDX5b$f zVcs6z>4^fHdEL`{SSI_I}wR1fJfwI(VLKV5dNw52;8a!X|DqsO&q;G$f(}H zVFKa;yH6lR8r}=8VY=uzWzXZC?2+2&5;r)J!@NUcW35RzL2ZFGDFxNC~dmj2VxtwA9qWm_A9rz`x><$`MF#sW32O- zN#rabaqq%T%SI%2aP5cfcw(j}8}CgYjoNPyj2Ec=D*CZ?qm9~6>d%^9txa*h59^aL zo02j0)t)OC7SwRmqaS3F>?m-yU9H7ORSg6X#5&D^F^Z{v7@xBG`D!hu;kSrNYQ{eP zMQJ}-WQ5UAD7QGUc@X7+Hqg?)UfOZ{KDy-1O}t(L4z~hmmu!I*P=Kk@+lBZNr`Dq+ zXswp$0@#j>5Nzsc{|s@3EaViW0voh>gbfF2|1$nz8;<45@K7yJ(>@+j70=OauvB5l z@G#zI-N$HcQW_wYZXOjW_aQ|erRfu|OOZZ%j5fj97YURFw;`{*4@l=-K?`nRS!$8E zKbHn7zy~l$z{T!Q13=J{=vMC9c%sM&=mfh(>si(rGp>1I8bD4XX9M zh7b)&h?05;Q39>-1*ZNcA-)36o@=1hW&`jCxR-ZvJpdO&D*(1O0lonoFVgNYv>F?% zl~>n_CR*OitkvoiXcmss(x=~U2=N99v9KOOEQD70@Y7EK3(ow9NC>3eKtk|_zKQ2a z#6^tP(wx^COc*i21f6)%s4*|~um#W*O!k?W6alAXJZ2!y3^3|%gVO>e=)SGrT{asp z?i#OUO;0g6&mzv4$*YqyX7UO;xpN;ean1ye7ikRw>NWR_LR{ViEv-Z{m<%H(nBA+B zNfFcolbcOUS`!nbeYZ(>&*w0o&P%Y-ae6#N>*k(zpoiAY0y9jl02rN%*^H0jqf}s` zNFvMv)+rHY0Sh|2a~&p$s(`bO0Jj=|r>SIM7O+mhe5eS(b|%1gfRi#2&GkFbW#U92 z-)SIM5He={>O`InQM=&tvj7mZRQo&(oFfxatfm=&UIN6to*)YAYI$F{%*Ff0ZE=)kpF)@(m~j8tt;l3`g=DeMl9po z>+w=u`nXvO>3^*ti;lVdf!_;S0sBJ|zg zNsyd&e`gEPY0$y*#XE%mTOHYa&_PE9?&`-gJdh_HAvV!U_$J-D8CW%L4gxxy!S%ov zXTHT3V$!*Q&LBPoB3ouaSbm_WSAV{%JKggCjJ*Pcy6^l8I00x;T>*6uZs1Q`T>ON$>0bFI zP5J+VYQ;?lf*J^aOL_@|fxmGClC>lMOmzW9QiU4OaDKo1#s3Wq7dEJ37claJj{OU; z6X2K%3|C6L^W{Z42Iyoxx)$IC06lKtLn~j!Xv4K@SV;ev`G2DB`*UymaK9)t;?JmW z>go-3ANVIO82-^Or5BV~U`Nh@r_hf3SL4cCV1YbLdN0QcPv8H z{z&XvB%8`^1SY>ZX`xvJAl-oGs&6#%dm`%48s@|jM9$joXiR%ZsyiNK#Sh4as1-XYic6F^lG15w_+ zvfLv6|AsaZd+bqvf%YY&IRcFzw97}Ty1M#bs6o!C;&0r?rn+O;pHW-a1q^lXULQ6u zgeadW6&`PL72N?QZG!8E;E2v>r4f1L0{Is08j%mF;5iS798 z-#X|KS(GXvenXeZ*Q7j3JSsok69kDXl*3&JmL-+)gOAGDS}@ro=pBdqSts*zkIL1t z^FjVplZ7u|E*oMWz>h=tv1vKNbRNWys9wP7H7RI)Vq&mi)kJ=7xok@$7&O@DW{BH! zS4`xUkI9y-MMFtu(%f%M6dJ61vPl_C*9^jwb;#fSn7l?y!yUl8)W($)`K-s~4`7!0 zT|z7`ctRf14QW;29I<@P69}Kh?-rEBR{dV)LRm?be2;Y35UgBPFme`x*yC05U5R_Z znc8k7=%TySQN+s~D1B)#juIUR{9c2E{tAD>A*Xx&4*8$zlTx%vxKt@^zi@|UdvHP2 z_KF{HFSJIsXfFU?XS7iGI%NM)jhqjw&@W2e6>);l@B}JJweqV{DM0?K7KaOqQ0rK& z+$R&Y$gdobdbtgy@TH9x8s5P;&Ov$Nif}oVS)BMEcGP61SN*P;M;VkJmGCEetY2*HjmRO;hzot$#c$^L2 zmMo#U4d2fKd`Rl{NwnbTd2RVy>O`lpKV1;BXbJUUUM;5)$XTo93G~fZ%lC$dG{bFi zBzj|?l*fyb3t-BhLO41{VlfhVG&0Wfp;6zc!=K@9X-`(#q%>oqZuNvXo< zAV_=@8{tn-uCM8-RA7~Am3q1t1NhpfS;2GHno_dH6Ev|Hahm>_-WT7l zmQ;Rf4TR!2D&#yXr}v3;=W0n*z8xbpH2oUV?NjqI+||w`KI2&o)jm{S{;WKKeD%bA zi$SOCL*;>aW<`|fuZ7dykKGmDya5*zhX8;Z_1mA7jU!M$jA?ge8AkGWq`j>yJi>0k zP*9&RJchE?Jvv^p7W=JZU`EwiaQdndJ21Qwtosf*R!HJkk?LQfx+Sj{KekpjX{UpU zMD?BMH>+OGB@PixgEPfjUN4)(s2SLb@D)mU5^PoEF(jbviu?dE?*n|&z_@}X{giky zQ<>_@;Pal7ne+-eJ^q~BMoemL%v27Uga!fQyb`p8nWS@93mN?QI{9wuGk`bxTb#YT zWexIRQTk;7{#x~UIa3T5rMatJy*PhCE+W-ge{K10bqbN{JpO`gDfvrgunhmiVHHY_ zUR&Oxt{m5v|7UwC$mr6!q_bQ(LhvGVfdzW}4lX~h#Y$RF(sLS6uW-4Py1od7;n4T? zmj7M8A7=T0@FFgaMq;RWQJS~&MPLhE>xs8ydGprG|JB6x%0|E@c|w2RPhP(VG`9PBh5v{tVrS&C^>o-(^Om+yT`en`6u71SlMvJWrwVt~Do zj8;vKx7`aCXzuLE`|Of+n$;7%#k-($qVB{J%U8T3f0eQWnx+zV^V|ufHDSqF4BjQX z<@plC!cQ5kEjj$u9=T7~Z&$URC+?Lk1a$gd`GcV#)k9YJB}p`%m$Hl?Id}kq8GvA3 zyc*I`UsS#v$k(i%$fxd;*Q9`ZYUWsErsA^((s5>=JU~mevtooMj+#09WhLdhNX;zN zBJlAmCwlkp$Kos<&F=J89*~PP(skKT0q@JLQX;adKEN7MwH-{*+cFfgJzXFrcUWJ= z{5R_(HbF?zZ`0$_M9$G|$QNt{Y8@x)3qGBi-h{MOA5L#Z+JVaf1m|U>o#t?Q3(`K^ zlA!#pNC(W}vDQ4C7~<9X9;Aib6g3S|^6Rk@5fX1AZLSEXUGY^Y2qdcojZ|O_r$MD(5W;Ct>9<;w z)HGxT~X;A48(EbRWsZ>@csA&-C*SBcZv`VA}=_*uGsch}0 z7N}H;;j~Jn7^mi|RN7+Iv`S@5jG9)d)P&P2l{L|7zDi|o7zr9yy;D;2RU)yiC*+7o zTyhEjP^ol^YJo~+0NWo_QmHhD)1cDhbC#(2pwbfvz*!Tf(j$oBG^q6G4REd@A5?nG zE#uTQi1b)(;WUW!I9kV2e$`P>>2ccBA4fr@$0vr$O4#ScY8?>iv06u|X%OjgII4=&AE46X6vAnhN=KoZ zua2domzu^{dIZ-s0_6Fbq)( zR4VrjRnsb!6@%5ZO68tGYFecd5i7)AmCC?CHLX%<4X0Hqu~1MQl}h~pHLVh9?XRX) zB8C1+6;)El5^-^q7O=<6(F^P;Tp?A3@ps+e$xSLy%-2~*tGeOIux?N#*%j6wDpw+U zLX~_=rV3N#qBEQhcN`uXAXMdd3R!9;Rp`v&bXXX}>G13br*l%nh=r$BAGIBEBo_f% ze??5~$QmX}6=GlS-}}*LtLaVg*_hjo@DG)R5us5r4rKE~e%Vl#53NZn%euA%>=JZF za-)z<{FcVtys<68^b^Xh*qb`qrkQ+_P`L4%o+ermEFv~+ddJ}*eeg)*Cs;N6Au;O{ zc|rnd2wE}#q!j-ew&@djlo8ejZAEBHg2yV2NpMD;>fOmjcqU7d1m;2qHaNU|@0z)E z7)$xvnSgp22Hv}596f+&F_k+uf3{VA(c^^E4Ae<#|yaBtawwx^C@q27tM zcSTn_iQT_(ncIaLFg-arPdHJcF5ja`?dV4 zjxfl>2Tx_zuaKja(*C8v%83>};~RO@7|4en|8Uj{yCCC6p@Eoe)(A~c=)#UMx^qT@ z@x4uGASX*-6?m$O;NEZGXaaD*086b5u8g@@uN^|kQL5;R5}Lr}Al>p7(6KNqO8I^c z_Uhdb0u(JYtu#(Gt%Rqhx&klQ0EwEKsmpvoWZw-!!zHv2NJ7(q2ok>e6XBiHx!ZwA z91yvT@&XkRU6g8oW(8!Mc9@!z;!a*Q(Yrbzzb|S>B1aFLmVkM8w8_I0i8X&Thu62s zkCI(Ze}DBI{ws}?7*Q*_a`?b@dB_O-uIP{RM3l$ikH~(4IUeS@8e4Rf5U28cQp0uL zb>#56cKPXUDx7reYxF$lq&#Irr%u^@x6nWqv@c$0a%y1M#0pKtz-KfVn2AfxJs{G% zv40F;U+4tk>rcx0nPV(L3kcAIsWdVqJD;JQR5_U+KZ#w7Efr6^ossE#0`iEJE3`gqz8ru!Hjc4)XPkm(qKX7!CEQnAfTj;N-CfhX6|_Y>X+})>z8LndDR0KG zG#0DVxxN+7r`g!Fx8wA1k1vRx>xM79!0~esBUk2RRi}H;_ ziT}2rF;*I(Fb`?FudMl0f+pM7ZW!{=VW+lt=@kRAXT*e1ki@BcZ0pSvh89R)ZB zN1ighXD6qb>ijj-REjzxZPGZCu8NDeH1 z^Ch`g4*4n?hYG=1P)!^U``gmp1g;U_q|35F3m6_DN>EN#Oy)x`|?H>#iUib-$u3=@+>r zg+{yeocLzx`6oWj1EO27Y#sYW?gLLnJ+_?nFvaSxLS^o17nP%$d}U{8zEYT*&r`0* zU-useqy>AxU8Q?W~~y^4tIR#2t8CO@v#qt>G_DRpr`ZR0h0KopkrPX6IF zd6byXrC;UyX-R~h%X0UHY(M;~{8WkqH3Ub#a)O*Zl=k)IDIqv`=m*VK!JLCPsbNUG znt*qdL*OSmF#zSRoxGLhw@duIu%eS#S+Vw#-sHti48~z^DE8W z4-&Q?IuLy0>m)X~V35kFG&gqk!Pl?^_^<>JV}AxYSmIPB7ekAjlGrlsDwWGA?iNRX z?}8{cP3#jHG&2UP2gV2sMx)|0^dJH}6ieUqC z7!vQ?WHIf}5oYwejAgb~RJvOK1kOpZ?5@P=s8k0$2p?PZ0KPburA1$l%zyHhA7mW@ zUD%ykSXU~EW#C7Z&7Q`4$FaDPP@ifp)MwBLrkKH$lVAwd?vjhY$ONAi$5uh5*VFPt zOObfGjGu{P*}7Wb@FG5Q&4ZNn_%`JYRF>}@#B<_7$wDnOPIrM}1dRe7$gW3)3an2w z1Y*rVJ};gb?op7rGf$(um7-Cc7(j!@NN#nQYw7M=2|%2{VA2_V__IT5Og$0+o7t#D z^%feIz`&SsEwppvn-VU!;Qu3l=9Y3xaOLT;;8skI6GH5n7Ou>GDCLE2Y@Ea)G$q}b zNgE#jO!b7Pwi~-$T8xqt-Izr?L1j>HcMF!yfm*gqT7;6VT6VkkY4mNtidJeH!nNI5 zM#{6uSQMpQKPdD2pQ&JvVF)kojwxG%ZHPT8d3`DV(Pd6|)-M*S!7t&zV(PlHmwP;k zAC*__>ol&R${23z!BR;2{Isg>aSY*i^kDt88<3IgIPmkHy+e3i4>mmKDYemk>vF4y zDmt7we1|ckZq#!m=Ma9p2g^z=X(irwGHL-64>xq0zc6_*t;=-1;r@5^47^;N@5vsN_)LYtU@I3bXHIH z9qbvkarK^|T${p1&~Ix`OR%+dn72HIy+y8N|I0VwVK~P~9-GEY(ipI`ERDU@RkOt~ zj7#avAbk`McWOGDJ_IWRfv~_kbg@KexbQ~}1Oo`xxw@yLI25wbx27{C@o#8Mnw}QV zTahl;u{FBkNYDye4V$tW)+h065c1CGSdp$zq_8F(wik9T6t9$lyy9M%k|VnzE~ytQ zB}H%n5lGcAsB=sD_ zh?_FlfV@Tsjs>?VCD{J^B%!Dhb~*MBoixZAgI?)dox?jaSb8ab$M(X3aZQdQ;ECY- zVcb5Aya3j{?_-6a*-)eu;;?UbnefTA<(BQC+ORt*O0bwPQ~WkxAurEleaIKG7Qgqv z<#5uLqx8EP+L>&%m`Glt8w-`QS3-sHapoXN9rgEaWw^iZuY`6IUh%-`D+~ekT_zSO za9?ziEY%=?GvFOW8I~zO42sUx_}&DE&mPcs68j!9H2BF()>pbY27d4?=F*7}r5}dI zE+SL*$Ktp}GZ7q+3!Snziw&+yN3AGS5W71L_rTd0DgKo>+wR&VsH~qSG^Gv@ioCTN zh58Ffz1^+8LZuXwFa&!c8jNd}@{1xiGxT=FXE~wzA0pBcOgDD8`CG=K( z2`hik8*Tc#y0Pi)7WWoI73tg?08HK5YK0~YkOzv+^AbMB>Kp|JGSipOC{$kBRLHmX zX1PYSZK~TtCTC7w_VWD(27D4t>u?%M6&#?v5RKOxxx-p&vIm`Vz1ePo#(cw5u z;&B4y9R~JE4uUBYIrx89L6tp7T(u(gkq0hk(5OP3+#(^=9 zAuk@5c1~Y#Y9$&GLOJ&pj;8MO|Bgvh;1Con%)&hH<|N@X%T~dQNql4WoEnKbA>;D;m*i z*C=JXSkR{py~U;p4L74clzpca9leVkN7sBKYT? zTnz0bg@33zUpbA__RlYd3Pp58b>0Sp0>6ZcG9n%H!uJq#(&d{-8f$@N)Z3j5BS(*I zjx`1&IXCacik)Cz?v@*sRa;C89YF637e z^7-ugDyl>x^BFpZ0QLcPtr8d6mP4bUGo5~+*tV#Dg9JuORz#0m#ZmvK2TLRe%~ojoFS{u|nAR)01m1_Lv-I-l3|XL-SOR(3(~Fw3CUsXvWaY ziH1PD2Kufo->Du%lYfVzRLHM`1=4>#);==0u`mXgVu7T^62>>L8^AK8?Hbsm1K8k^ zi%9GQp~#GttrbeLu~MVlhdfdiB$i8nReutC%o8 zc%-|5EIm-8_^K)+ODhPXi>`I@My#XQ0CevDAAz+(1-%F14oI2qM*w7(k!57v1!6Yg zgcZwD(MCx+(+80BNy5y1Frqt9L5un07qFr~4ew*hKp4}Q`~FvFnS=cMGXC&DHcEqC z%IgE!n8`4pl2o2&y5pcB&ti{4^MNz~P1@N|;ug39NNj1c2hN9fR$-1nH2lGzAODnA ziX-F@8N~Xh`pNT4h-zRMRC)$0CxP&SL2PjUSX8HiEsi;tPY7^xVYIs3jHHrY1xQG= zpZf-}w5ga+Q-OySd!?D7&`uh17b=jFARt|eqL%PL57(Ce&vyL(ms@q+W7x=gEW{9E zaq@HhU}hlaN!eg_Au$y>WYCatM=@*VL)g7{!}cXpvenU7**OKV9I-+nM#rB40h>C0 zQt%;Q^7k6Sg!P#;sE5`e9RL5e#U*%FIEt~xsBlD9Go7|n7i}iRFTw;H%I+z63yA=% zK(HEoP#xdF5s(!#SdEPoG;o^xb_^;X%0~6X1BFz_U=S1&kSGR;Cx)_g%&2;w*@X8` zm?0MP#7{fTykTqz?a1}ukr=JI|9wp|0ffb2HTTf; zUiqLU=!N0F3iaU9IPAlvinb*DZ#9Gi8p}T!^w2z+2RbjB@#OwUmP=0486(+X>26Hf z+L3GsOlUA69UIRvN{NJJ3FzsupZEnaV26M@w&V4->T!x|w9xP; zRNeJfi{q7tlZ6Jnx~~Hf9x>VR$EZg{SVp2zfn?WtNGtlm1aI;VD`W`nOUEWm8pUkV zwNQt5-YC{jl*%xaYm3Jha<<}0rcnq6B4T;e$t`hDY!?sJ)&`af5_K-9TiQ{8gbIKYdoS_hSoT8fa z525MSajc)Y3I$daK#uAgG${ui2()}YMo@C$ZSIOxA|WJ8MLlZ-(zl`U#`#5Xf~LB8 zVA>O@TtA*g>25_fRfX>pHc~2Vq!jnfzjk=Xj%PhYZ6c_#ZYT?OLR-$5z)H#eYbzC$ zj6`CYWBNsmFcw;m^;g`of|j@y;^)NFs`^z3Vu4WG!W{D+oWS;oxoF(35tX@bBm51R zktnTGxsc(u)rd+(wT8cLW2F%w*xy8A1>b@? zS49inxv{WJ;$~*0U@B`B_)rV$Lw)5@Umqag2I7kyUp;niXp`w~fvc%eui=X=ES+4y z6Vcasz=TPo!fY{!e0>DwXuy=(1istCCR1IQDD~JB)$auCUhRVNQklfFN*M*Yp)CT? zTpC_pieXL;b@0`t>}U>#h@!N}CrY}4bR~`oeiKUWdt_NEuRktFWnsnjI57omkXZqY z?AnA^;;`=ZGH3){PfUT`IQ*fAQ0!^L9B7mHfr;#6ji(>ylUPvt`AP?0H<`Ujo~(e> z1N#Y`dmf~3MmeVWTPUn8hvP*ZHB68rPyqibhd8RWb#5aJ+AHN)$)GVkR#ZsEjL5l; zy;1)2)eiL@00|Tc(c}1^3`mYK1{Fza;ExQR0ot^BpxhYt#(tuP%Rx{*4geboRi?Y1 zO_B})*qrOx@PcXAI#d~_Eh|A81q4YKkk^5xN1>2%uo;!T*R#7)G9rZz2rE@i!|#GA zY&KMaziVW+W6eec(_vF>rqXLuwDMAAG~YM{wnXPI9emdmX2`k%a5SwBzh(*cjK~H} zYo8R&FHK?p%xXr>4&dOt1|1${HeG;g9RpK%01aQC%Iq}Q)IiWj^MN-o*T^>f`Nc_m z_CrdmV3Al6Z!RXS%q;(WV(`gr<-z;mFW55G(M+q2`zBm$w8Zex4Q!J30Tj@h)zTWn zZ@Q6X_gEasXl;pA-sHF3$g+CKku0$^R@tUzX&JI;2n=n}{J@QDKw2!&h(p2X@`G22Eq*tFYGA zFPN=0S>2Z4A6?2-ZZWuaOIh#`8WB!30AfuyB^H42HhB}3Klf&7@G#1kM#@_>S|xh(t@###)yf(tLqGJgw#(F>I)g}^9m{e7- zi9uTgosY6H1g|2d7A5Gl(G%3Z_fF^-W9gO++EXWBS|Nq*np0Z;I*& z6ApSYS{VW{S#mQom2UzN_3sE_!H_Ipf?UPH+$GcaJkmrY*>Pu)KBN)qe#U@xLe`Q| zPB(Dh!ZqJXu<_2_%!X&(2w<DSyBHBMQNwwOSjck1Jmzavev^=W(zprQ;^(4~P55bXES&pRkj zz;J1zgil_^NVwq3r=zDEp^3;8cH!7@6J+G^%VGI(ejVERU$n6U-lW`kJ1g8=?G@WeDB<1fxOqXJzX-#@*aCfwD_Qot>rrNq9o`+_#wAja}Ij#?7 z-3q1l1qQ14R<=Eh4&}5kY-%AEB-jGJ8}lT^;7j3GZiT{+CayFh2m$ka;BD;X93t~R ze2lJCMQck{U`uyqLT;u&f%evS;~lrLTe7N=*%v$4T!20U+(|iDUr-eTzhf2~f_1iY zAQ~B~)V##A05z3-xh-|42A*9fS9WZE3hj30A;1YSE`CmG8ht$`X|SK)GH6OJH7iR);4Jue_aQ z52ea`^xYI{NQHU$uEy;LHyS{%7@^vWsO(j&RW3^jfBkl5C!j}5c0-a%#`99Fw#v%zy{ouUP&MNCp|gWacz6B@n*33MpdH&3rL z5D=tez>4Q-1d;w0>G}xjF97uoNQ1GR@1s+iW}7jZ>Xfvm@bWvD=?)rhtt(zFoB)hA zoW=5s?|H~?wWcclyGYv^Dyl(VDLQxv*giA)I@1llP$6lb*C2-DCp1)zNJKyNX zOYX**9UV;?N=x{HyIHmFKzLa)I@X6&@gey(m`k`chustVC;(aZrt-ye*kEnAH;6=D z8sAD8OVsXhWZ9Os4C%_p7eic69t8|1^uFI_OXoROmZ7^2Tyva-SDr@+N~5dw4r&~39~$-7q!{ykp|E?h1&uR)`aAmflswNVRt*@9lo zZ~|%2i^?o8XgUbmYh|WbvIsLeGjpbt{@axUViUk5OXHZxm%rYm;?Dd&kW z>CoeTOGP@Ia=qQW3l{u+ywk?I=WV^%L9VJd$W;~iIyCb~^iH$1l(w6|;&x!4Q^E2v zjr}bWFh_bs1Or=5hGIbPxT&anIFi>|p;LMz?>zE|+6R$e-PVh5s$lf6g1;SDP`*LR z_+K*&6dS%HGBpWkq9@GV^?gcgH=mB$fhJP(!Lnh$&OTdTDTpMw~Z?pAL_C6Pb zYiqsTyMM-@B02#3nVF;kRLm?nstDW)8ogA$P~B5_2nUz54`08Kjp&I*gX&@}_q6GA z6$7;7iG{2W<@Y}pDunV-%MG>^p16o*PQ!0Af(Ig$1AdlUfC5N>Kknlrp&}>|j}7nw zh8{{OLL>*>1nVzDpf%P*urMnis)JCOb?vtwZl}04yvd2woSOGOSWof>SJ8dk(*} zm`x$T#F~KEk583ZKD3{w8lI9yP(hxOU04-heyC$0H1^|bWj4H|=3ICuO01&B=9<0= zxo~fohDJE(s5&e(6AMouMt9R)(S;fM^$b(gnYi$&J2>Z zvjZ3N+59ew^c7g4maslUx+<3CE4dKetpMP_cKqHq&CMq!#xMthZiqXocsp_Ov4lAtK;!1n_u~T}!YSYskU&x*d>3k(4S8*Z?Cryz<#o&rG6Siy z)!L6g{1AI!D1KK*Mb*VPaK!-c)#gG3E%>a3P*hS_33y5vQ~uM)=tv{c$jHOA}(80sY zSfBZ*NV3ze@2fB^1a$n5 zdN4!>Kj$I{Z(1D{+=LZjb6r$$b6KuJh=-Q3X6Y4lyz5bxNfaD=6vw!npghW2r1>b> zyPQqO$k&T{$KeWGI?s6wuBI=bVb?y+21pZ-*!4Iwq{JNwsoDc00&StgwyQrs@EF@K z9RLiq>Ur=MRcSJXYX}3p9gnjY#Mx>Fytb7C6x@D=c63aq{UL}$MMSe(jM&_!xQ|52 zyeRt?Z{N@aL0IT-XRUOI?ohq6X>>{1z45;ox+-Rz+yw`>Z+1ms{1Y&&*lMrGcSi(P zr)_eu>j;%x^g<{EPj47jEnwZ`KztJF(k18$IREM#m|zP~@VWym`Ti$JjDuB6`;b^( zt-3EgcR*feV|TE%8j(wHgRSk9Xz%Fo=G3qZQTiL|j;&=Z8D^P>{HSLzmDJNtE*`M! zcxNq(<6qS>eKF>mM?DjY`1xIQl>?Op%)7kE+^f>S;f|wF>{FWHI`beto{wAs@Ard0 zcJLi5u(e%;#DNv;`IHhQsuqkJ9YD2lFgGOZU>C1s{ZfXb;50Hr^T&=h8zp|DYhK!pO+%(>Cn4*J4 z*Kp-~Nap>BMwq&Dk}B2ikTpD~}iV*C4)xxi=W&2b10DAZlkFe6BsQ*vv*#O;s z6u2H*KV1ObEm{AzyE3~sQyh4T!dNUsqy7clrma&zd*VSKhD6g+rf&7DBfN>PvoAEU2OtTjn8@o6G(rZ5y{p!HuQarn`b69a{TobN|Pq;EnJVZiKJ!NvN2a09f5N zf>*u8)En#6cZ+ibKlm0i{lBRBzXjT8f(t1BcDTYrQxV_zabvf=7@luE7qv zE2x>|Z8kb2Mdv&L8St`Ow1*-PTQPZx|IPl<#SepTr1$v0S-yIi-e4&7#=gxisy|km z2Xg5@tOj`2&wT{`7DUwD)88Dd42a529qfpxIG zg-suYayniT|Km7}G4jmC5mQ&tJgqgpKHz;4u15&5N(|l%iN$P)Z;j;(_Tc15*7LD@ z+2B|Vj)w+j@m`!6e45Nx?PbQ;G2e9X$AGSPFUwCrFQM7d*q~*&OW~M4vzM7jo;>6t zheM$LUHF2w;Oz(8X5wS_v3qYr-pSdMf+H#iDz|Jb3zll46j!^XJPj}Sw@@i$6J5pk z?Ax2+P!Y|9sQyL}X$BFMsM7=W54?+rt+wMG+yg9MN2Ujrt@Q%V zj0B|>diglY5)UxL*x6rqaN5*K8YF^e)cqKw6X+BHm5Y(yeSl@;%>_QjL_yhsOtUD|krDbKc(DU0eS=H!dvm-X+nTZ?nikcbkn%8`uNu%#jzdPnlj zk>eGb22P+W30mdFL8ZLl19g|Jj<-QSmaqPRS@M4TG7PM%k-5AK=DN^y7>(V);BHv! zXFhw zPE+cg4&qBbV(A2U)<-xx*#Cz{o6%^%?ZV6!G%7|JR* zuR9c8>31E%y@CQ1w9*WShNlceNpoJ5@@7GlQZiI9C08uqRen}f ziCrdO;h7vPB&G1i5)!ktLId?Vug(&@Z|qc4D^~da6NN(R7n8e_Ch{IBUYUzSo*&!h zo9?+{ZvL=TD7q76tDwmU#uN^4c!6lEd_R8AJHjkOX`pF}R98<>X!>6Tl$h^BYUN}|HBF1Ys6*4jfk2vLN7$$d zKzG96(%=)T#ULFTEf}gb^+w&tu(@%=lQ230Q_LHuP~LFBqw({?&p02{Og#!aRs$lI z90g;#<|raQyhj;5Zsj3ivRKCPf@7G}9~|r8-$TerrTcCanjo*ZMrbxIM1=*%SoVyG zpoO$BNjJ^86%bW=An6dgqdb~Aq^-w9>XEu6?ffX}wIQ-`Guq_B1#}Me3EfA4;_+iR zG|h|9ZPicUS)U^q#0&^`e9p2{2BE3CQlOhaChp^-N!{n{Hd?jU%K#z^-x5LSFI(ODAvj7FVHi1}wWCU6B~);(+BO+^H0ySq3}@BcBwlOB}6K zp!`n2A`SN%(*GSU%!Koy(}r{n20c(cT6ql}>k9F}8S?ZsLg5IMQw-cB%_wCcj^$p# zf-@0x!v3wVQdeTU<4D-vKH3uOFNKfKth>T$BTyM?qQ!Fn@~tk7qQ|me-5oAVC)vO% zK$=hoq(}wP^#{k}w1I_x4IR^K!6c2OMdt#EEvOTK!-x0^nTvAUd?r5YOYCKmA*ZXq zWW%dwBC&g36r6{+{eUxAa&by%{wA859|Z6@pTzhd zKq*1UsA~of$4LpeDvTg^v>`chB9F9^3!_O(zPv+dCiJ&o2_@-n2ED{+niFD$$jgtj z0b0^ltx|$ps2InWA7{o1P#RW1A;xu0coOg*z*&Ye8nLeE#5o(K;2bGiU6eDz<-Gkk zb9VQb7tmGzOn2#s(R}S!Y`An3#P9tI_vQMdzu%B()$pNTv%z_UL^2+Dp&`A|V(kO7 zxAS$;9GrxQUVg%n_C6mT5dE61k!k@Z@f-G{0|TIB*Qu(M38TljW7G*=%4495da`ACYonCh_ZFP5t<2g zT>nAYIE9XXZ@}5z1K6YhNfmGlMtWo`To&6fn9Ex+D>fjpsWrT)A8QSp+cVn2HVJQI zM@IHQg)4YDp$!q@TY>ZPY=Kr9|K7c$l&f}3g#>sUmSQCUAJoxu#qo{pIN@u=xZZS< zO(w<3PqJHbUZZI{6_W^1Xl)&vCN#lH@l!lk28_$tZ`lhtNa>`W2vSRX4BzpsdS0MH zZru~h&wR@oOCwwntOz!QTpu4MG!RUjffo_6h6pAGgyoRZdG}-p?*NBk;@qUu(%y|9 z`i|ws0FJX|9KZA(8vzr=FF8jk>DWzBAn$gxBPDd(5lr+~#Is}w#=|QfUKca*D4AA0 z6Zi`A=@j5oIawZyPqAf*q^R5O4R=@_(DF;CFt<)%s0vO)osFYXFs!<=JD+#@ck&FC zF?{Q3^&Xr`uB$@g?Wa{&xca*#FNzm`&mOP303m?yr@0uoQIN!N;7DP~HSRzqE%`{Sd^S4^r$Wg+=@m@L-Ps9+I*W5CBVM6d;(~R-~N4MF%?G zAB;B8C4NlUi3rphuY86LB{5Zx1{iw(R&*fP#w#0eOhEbFp@ag)(9QvoGQDfO!cj(+ z^a3#I;UAcx7HeUG<*ipk6i~v#8g`IxSXyq_EBkatGuYoG|)7{wDTCkP-fla`O zgpZ%vM=Nhf>iKXPgs?TDp4KtSTYQFf6G_i^0X1t($^((gqzXZSrvR1XZKISk0!YTZ zS${F4!-DSVYU9+K6x;7@iZG5I?2D$?=0T^U%|cN8EZSi7)suw{=26N)r5OU>74kRlT!@dsX?nqb*>e;*yz9U0F6~I5Ngf|tTMwT16MI!lM}3rGk$QNK z|HQr*QyO8AyN2Qqv1su28S2XDf_x`iqkT=?yr;V9Xm0UYb}x}^2+$)rDei8F;BfSy z5N$k!gWXi_CvaL~FaoJUQ#x&)kVjsq-pF@gW~L&K_88&(RChY^aXGFjC=;(- zLNY&e4sj|k`@IF8$wDeNr+sqe3O_6!6GH}nPWWM}7%cPMe z#OQc}m`)9+{?2%%>A#_!4d7=xkdP3aCZGe-ld0hINNa{NA7#{jcI2Dj+>Ug3;ef{q z$N3cyw=!@C_mzsUrBJ!kYE4#;*m&v%mL%Qk@9-8}U`7!Jn1}qIoAa>Whc98yMJzQd zAt|db!sbWD){EE&Uj%pBFXEPRzfWO6qsQwoogjloSFVD)2eIyL?ZUD#C>wbRhe0O~ zscur^5BN5tB8AUWBoP(w()}qMPKqhY3()uVfe=3dKwWPxTtr<523sSTO>IyVn;@s;LOykwO)A-p zUd)e~*U|K$sk0I%5?yz9$n#6iV`vHgSbQ#_{2U}c6-<0-Q<}28ER`<^vIhv$qX=vd zk94|wQ?U??zrT!k1X)qaKfxdZ?m{K%AQuz8_!nkKeMOzo6#w4TR#;I!KOTV!3DHp&nCumvL%?txC!*~|I%dap?+RG|b9liAO+sTTRv&WWZ z^PfJIW4P}M(@Sq3#-Lqc-zE~=E;iA_PsgqzNLn?#@v_h5s!z*sPQtIjY}XRg}Z(&Os-p638Fn*pP_}mPGXU*9(<&Y&?>Afckm-FUrpvO{vz&F*Yg8~j< zVjXWx{RBf`yuGZ?^X2wwv=w|Sc53kXAIf%av_C2lTHoPtf(|G|pt}SAM$|uf8Xp>E z&ycSBsKYxo%3dT&8gQ#N+D?~CJQf{}oHQJc-rB-<6q`vK&?r(K_fHy(uG zrdpCq#LYNx6QHO4?{S@5)(b&Hy~J-yvA;O-4KTntGJJ3CI_$YAWRI$!LxAG7<)5jM z=37w*I-t`B-^Y)T`>a&^#JJAgnAQYlUaI{rEo8CYnFmh~)c2uOdnU;MZ7r;5vK37( zrP}AB=UUti?2O@+Y4*DYu7S&*4jG&Xt#X%1%9$8P&mR*VJzZdVHOlA@Lf{Mv4tNkQ zs5E=N=;A%o?bD;4K^ea<-98=}ThhVzPJT7ro~;4gES=qu?;yC5^Ur+vK>Mazw#VVH zf?#ec6A;~ps75ER(AkX%l=oy`%XZ2~-amBq30m@*(Q^@WB-XC84~U{lJgJvG8$75# z3Bl-xYjsWS;lrKNBZX^putQhyt}Kb(9^;$CXY{g9lH~W`80clE8>98>MBEF;<5Mto z>Y)efp%3bN;RtqlWiGCN=PLByn@3{Ih%nQ+ow>tcz&Q>dI0&a=FMC!G1AfwNUY&c{ z0c>6~?Bk_ZQ8p{XK5Yu%kX7Jn$yF}qsdkmo8YL9^0So36%5;cl&s8*yBNWL!Lb)CQ z$Rq2+r9A;#3T$6gQZ2c8cr(DBp=|)EFNbj532HJW(>@|I(m_j0p7Jp|FykQ;0$KtQ zo0A!qze=2+iF$a5S`2(G+K|i=|5{t~_`yv30O`f|I=q)M?WH1#eJL(lVa)+*P!P_( zd}?p|h@MG8Jtj)$X@RU1MD7O=%hB6z8Ym(25drTBO#SoohMUoVX6nkW1~o;v5^uL8 zCZoY@sQc-d`KGo4UY2d|*IkE9RkKzkDcoF#1OF$p?ZaZzknO7J$9HGjGpa=VsF}YM zH+kqqvV7&rQJC{s0zgdXRD>2;ufP9Kr}?yWYOH;gXHaJYmeY66hl=(fkJ?)t*mt3Q zRf2H#`*We0fbHLlvR?Qs1#(s(H^w7M6^jZh5=bAXxmQ6i zx8kLshMs2A9(}a2HaE(606^(ta`#9_)s_Nf5Ay1v*XohqBa-hj6e$0R38f$H5$X=48NZgMw~pEm4-C4uv}GKwlUM|3W+&uW}f8)ZD)GGDG>NC~rnNgv&EV zij>zBc?at4cZpK{`yIT_VDBfbLgHTr`{1!ZU|y18LvU0P(DYYo@Ma{v@)f>bvu|6; zQCJnI*M@qKvoP~C{drcd-BSDl7RavIP8V+J1u7Ds)7UXaF4}H?8|N{5an$=Qc4R3y z-0BOhurAmB7Fj)0^X&I$E!y9qzFv7M2m1{)?uNhd6ou-;xz+vop*(w$bQaym_O%yf zO^ww22{mcJk|H(RP;*vayBfUqpY~|*1Jx1P)Yuv#xy&(upUbyTO6d!RSjEd;CoKvnusNW%3hdeap9BL)LqDfZ-n z&qBNdJzQJ<#`YDE7G7Uqzfl9{#)$&^T`9DFJ$)~(m9`7bI}eJ>*5HWurvCPf0vd_l z_`FdoDbr`tvKDx@<8VCzjL&lG%Tl@0W+?Qg$FluYRS(g6E@E#a+h4O<3!4;bz7 zQLzBxe|l4n_t+5oU`cu(BON=!{u&vX^l}QlnnEE6m*LtZ1MA=jJDo|_+w_8R|6Z&x zBklC!zCVcPs^`N%Ifrj-=%?SRFXB^2+6@D}z79MI1ho$;d2efxQi_mK+GMX)DNA<;aRFx-FcffL zh5V*B)a4K>b*`Xn-Gdc+ls&C@KNA1iq)~R(Y5*(+9(PHR9FD^$p|;#8qxT@TfxKAJ3ceY@YH3~LSO)}py%3gvC^4?RU?3r{_4<$Z|$BwqEj~bj7 ziuu^l_EAvU{)M-UR;sU`kK36-lI=-DonFW}N=uhfFnQOGw!bBzvFBdB-aB=iT_e&_ z32pAefh-#J(0tB#yZWr@QcH>AMeqw4;<4fEsL?i-cZ`SbO?;<=vl!eWf;7{FDc)05 z_c8Kl5`{PTI(H0y@7822up;o5>QLSN$eT66o{t&gA>%Yh5}I4~j#07?Avhfywg!w0 zpP-WDu~nG(!3p*$vm7-m|t2swTK2xuT z3cKoAaKW4McOqYp|4;i8uvS5`Y)}OUUaCXuLwo=KPGs&(7i1KMDO0~>~D$barEa!^bVll-aLUEs`#UcGJ|*R6ciFp znINDy{)e`;G>Xr-!G0TA0#zRf%~a7SdsQ_FpCA{QDyE`F{ z{-`Mo+<^ZixOAi4cpKW&=u><9o@i6GzK3%9gAm_>M=FZJ?HoM3?8AyFTe#Mc@xlv*#O;M{sS}qNby68)6+(Q1<~W3V8SLF#e4t z=qka16}HI-P+uL;8Vx_!m2T|r&AG|GOw_DQ=Kr|aUO;bO?7i9kG<7Cwl9UBN)XJ6a zOH=s5TkL~U9sywdw}D%otJtH6XW#(2#olMKiU|JAqcsWV_M)TcE7;P?@yYllKp+qsO98R;HqU;&i)VY)>Stk+6d+upz5L0wXG0v312Q znwjtJ`g3_#SrpnWm=05;=IsuS$i2Gxz?MR5;I~!q;O1}7p^;b0nkY2UT}z6>|L)&7 zok2rwJC5hl@le_1o_Q^=b@ zOrwWT7SFWPW2GKLX_B)3eMGf_7ds(6#8|>uMw=Zo?bCY3;e4qgP6_LYbho9tC)eI; zr?(6sDTs;{d-55#+Fe7x29M0R@8i@6CfxhcWfK+cp`GMpIu9(fkhhu;z%@wvca*%_ z?89~Os6?c+s*c?>_Y#mDg}eo~*~d&q&$)&;<#{yx*^4zDPqn59f{B22;z)5fIyw(a zo$gvTVx(wOjRhebhDw3OfNQ{R;LL6IA4oF`SXps3QhEHn5U&Fw4lGZ&SnBPVWq(=h zUyWYrv^0SCfPVkSm+)W2i~#hmGVXY4S+7`Z;_HR(IQzZbZlhgky%kUMAWD;$&$d5H ztT}?k@{&E3pO|fbNS!@DK9V!z!#z>WYkCODzPn3WAvK@gDvN2yiN0SXy$Dwod#~)j|DXj|4sNF;92q72VLM_ez&~_ zI=)`tlB)QmIkYs^=hmnGuNUtBA6aJ~A4QQo{MlU~K!gAxBq2a{6JCRWyaWgc>?Q&S zoFXqLC%%wP6jVfHT0}(2ZctGX*^y}b3fTlf7KJEahQHrl z^vaF4JeL~L{Af<0Kp^_;2Zz?cshIri03Z6U1?H%q&4J+fwdrvccwpoO69=? zW|AY3vZsrP@>WDhQ<*OZ!w%o(o5A=3K1f0y3ITCFJ2?_>BjsC>4*(EO3PR(}1*YvG zdZ@tsQ-a{Jg&0q-7=J?yo_Gl#DKx*73edg+hyP5@1J|K` zUbzP~^*VFf|74wUJ%eX4Wu;ed!-;d%_2vhT`0FGEronNqa^50yvcnY*TW-F=+&RJ~ zMwD58AL*f$k>r$+H2Qa@$jYJ{&31Nt3{mp^Ue0a3!KpFEL2DuDL64E5x7}n8N|t7d zE+d+;C~M;ICe1x@lQ|^2%_D@KBRDea#;j>=jkz2?8Xjf_5K@MpB57wj*+ z_0^j*>26MI#S?A-^y+AgA5kHV$;I#`RTIGHbPuZD8X9G7UTtjOyxPIf$g|bBN<%efLsxhVW^s!CzhGd#C=7=jK);G&NTlN zcaoQz&+x@GR|*%^2Znl^g^Ly|GXpKX!Vov$5g1;Hy1u?^Zslf$1>3p2t3G<0IVEm6 zCCVA|naj-#Ht8#;E;su)I-(WHq9fmM=%u$~jp#tXZoA!_l_uF!x!f=1uQ&nJ_P3JX zB}Q28Kr0N0#1%|9@9ko$CxR5B@3h0{eo$pPFmlbqH3XW$hc+N+W!5Ua`Hp8uF-hm9d9$>O|-inF3=niv4 zI|O#nF;Q3EVdlgo<|4^wPuFMfFb54@SP@mZ8xa8wsOcF@6$af{FuP+_+coH1v!_?d zn!jjvM?GVuITQnUMO2m`d{~~WU1_dND~JMFme0XOFTR1ITwv>pTupk~oyb)(PQBC2 z6-OU&x)WkKv4b6Fub_!dDOn@QF`vm)E;ko`39;-=|8P&%7IINVYStUCw{Yoc;IN!> zE(5Oq=bdJX{?DCer*u#fT~+1|F$8pEuUewUxiM#pQ9yTT#x{E4D$|`PBH(9!TN~U~ z4=P(*m!=o2fQ9IgjR8UmOSG2`zN>P+#1FFNE@OL3d!xA}#i(i-YpiU!!^l|xz@od& z>(d)~5G%!kIMzWjFI(|k1f?DIH*wEwYEBz!jAlyr}4-+y^H264;{$O2KUSD;1Jn#&F_f89!=<@N215L-mp2Vdn6dh)*J6NZ**;> zPz$A#9{|3TmQ7;mW*f9)m>z#0R@OWDSa_fLWFI~h+?Tg+jU)b`gPWHc5RoswiV_T> ze?)SimV}4R;jVV1 z2U)eD+}@)_sMDmQ@d%z0==<7H4f-SaZ|bri`&xlHh|)LUzY1AI5aR z_pKE}^@)eg(M3G}jgYb|&*nD8%K7rgSl_w>WEX}_ zej>ccS`w1Ukq?h8Y*QlLc+a%V{?ZF#@^-YxdW8$mNb=wJvbPysqC(GZYaP!YtruJ7 zi2e|B&3s?gIE1w1mDoE{t{3?qBtHYBqA)mG*IDLthV?){<>&X8A4gF=+uJeaPWgeId+q6zuK{#RF zM)ddL&tXd3$Sz)g9(Hdu?K^ePZZw~;*==KqnJc659KWcSS+-T+GW3ZOa~y-treUyj ztRDQRIXqK_OLTPfh#aLr6}Za?`P;+Mw$`wVSM;daBU%tQXjhKj{HW;}BUN8K!%=nN zOkdT@Apbp(!%agi_aDsvVV`{+aDt@4&vx?W_z1>$_EB>+)}xBk{Qk@DkYk(`jigL4 z-^Y-`i|B=x$7tNuJPg*%V1MFasx}9ueFcGJJtV{SbAGndYUxC)wqc@Pr%{QHlA%tU zS%|s{;peaTx#u~m9Ki|nSg%M%;{@vx|3n@CxS1hiNYZ@8Io3=2qGL@~)xzU~oP2Ba zjJKS*Vuy^&+8)dEZ}OapeHX{R@>u$(qzh|BdmL|CY>UM;7h6xoz8~c~ic|%&s||a6 z7~r*yhM{|Xx!gNIe(Un0Y>j3Hhrl9b0&^xK}#N%c^N1HsDLw9-7 zOm(s-8q9y2w%brH^4H$cz4GcO%`V(PD>-g`iX8CHx~I%3GH(j+3LsB|p^rUfW@mcn z%k=MDXF8w)Au{X?VYkcLTS@I;AtGqZ)8tKJ_&A z5xZ@0JGb#1f7+ZcH1_))wjLyI-^Ur||L$g3pY=4X8@5s@R=elN;5^OVx6np_hr^Qp zf=Duz2N_Y4R{Ug(j?xYJ=y&qHXJkI#t3mErm@k0gLGU;Q%(%WrSFtt;>+4saF}n|Y z3G8}dPHOAwweIzlHfNU5Obn}sE7>G`k<I&FGo=8_CAR z{d<7HcKY?rX1~Pm=*8j;JVRnYgN}CkEC56%Km5A_jgF3bK&dGnw-p6!2F@%sdkfRl z>sw1rJD%R!Qf9FqA;$hv^B+TF;2b#dou%RPz*DXTI~-#SUs(#iq=DJ9NEfE53!4+K zh?Vi>ccR}?BV#FddT)!C?Hw6MVv!>1nhh_TauQxcrV~kTtWB`fhmkIGng|(559cOu zIj@;JF81!{^6q4;2tCO6Cix@}B&Y}$ceU~9Li+2Zqdwc^gPC3Rkur1o2;POi8gW*X z_IwXsTgdkS?cId;_OWDarYtPZ^PVSB&n&kGf?Y012%xp)IF_8H0}qwkN{;=(SJz9Y zZ!xbu&jGGpdhHg>T~zoOtoKAinm)G0%o-g-peDbEjli8CFbD+3W91BE+HSNX>ZL{g z0k_Fn?NZV{=6TYy2*?nXE`AmbZ^RaO@mX_R7SO`Z?lz?9Kx#&6til9*Crud_XJogk z1L6E+efC-N3dt|c_tZtp45G~6C_^akoWd_#MoBjmQ?{`zNw3&yPMi|U@6YdT*O5Se z2^7anW5e-h_O#PGkiL)fb(AeiijwfWn&R%G&uwLQlQNG?g_UdFdg?awNd!~Hy#u0S zqtS5dQ`@54`cN#bIMJKqG17JVb7nEKc7?MvqjKAG<`QT8pOA6Y>>0{A>hvAvjqZJA z_itq z=F6j5Y^>=P^$d2j3mh&QXe_&ev#XE0o_g{PxK(Twwt1TlpG;ZdU|9g4eF0+wa=u>F zRBnjU@T*KtF_K_sAJSW1#V5 zQ41VkU$uFDQ(l~KWO6u;JD+&Q$_VrFd{Um_ff`^LgxK@2T&#TA9F*`!faGJ`l`s`0 zwC>c)=C7z?Az1}rsAa7I*e;OzoP46T72-ts`aXo$e@by=*=K&A*R=VRPGNQy znx(tCpZqKGRyKj6Q9gP^UV{A9oMqVD&Ny=;nmJHHc6gc60XTL94oCQ&`3lRBSbD%a z$WGU!FMY-A(?zh$A7rJ09jC#&4bU&{H`Dd2ubA$lzs6RW4)zZO)(XnFyBMR;9cd|o z5$7yPUq*TZ=`9_NGo=Z}+^=HaeVzff^YxALy|a;hDeEl$rb0B(dkH~mN;OmJwP9S)$A8{kVL<4fKK>}IcUsByx7gg zfXUfeolLWnzir9BBHi08+x}wG$z{>yp<7yIi3F!u`WN%kv}ugF`|tBLXZd~2>5h&k znHJ^_Ci4+$XvVIj9s$}m}jBo}mp1~-tg>nrW?H*f)8>Z@0uba1UeQ|x>YqlM*z+J0!|{_sXm%jBK+;!NX-tZ2Sn2=c5_qsLN)>ii@OU6efrqlbe z*uGrnwBF`FrLM0&_Kvy4we~6YD-JRjQhMn@^UGmkLlCA3HjT6tQex{4S=c3JiB`Jc zV#hL>?~U(U=7J=#GDqmO@0wS}(X;iwHN*9Zcg<_!V1)W`(=a{bJtl1d7t9#0i{3MP z$Aby5(;|-J!}YfJOn)+Bt)7mrhZ6N2!h@|Dj^Wn&nu~P$`{rL3$!z*re=V3`;Qpl|JIW2r3<{us2V~`50H1i%Vp(f^|d5wint9t^Mq~0 zU*`XJ%UtHnke37WzYmAJ;3`7ZkS;A`=lcBhOkUFEP@sOJ-W0df|1sd4uRRXM55$g3m+f=?YzFgMS8&psLwexaqS0eVcQ?t5(H+HPCtw)a+F@2 zbJ(1gz@Q0vS&MFmM6yY^3Kj5)`LGZ|K<8O^g;c&GBE?y z_5Vt}6(5iW4GvWcKyC$JjHUe7m1-JC2&+K4YlpN2YNv z7>S*;5lvAHwBng-^wl?gY>swKq&ejuvq6!~!-0=&C9Qt1cZ@#uvDsft)Xx2)*b$x^ zd**RQ{^<@zNq~j*7pRpZ|Ayz{I0~x2nN6*I?hlXA3;vE%KZPBQSys|>FdjqfW0-?c za5|SAESWTaS@p_xrxCp=Rb~#sO1x+CE>Fh5=D2TOaT&n?$EK59PgVuyt#SQ6kC;>*o@8owr$zDxN5I=Ew-_RWqh?kfH&h*7>XFbX4xk8xNM;yS9|7lJc7<)%?vnmKcEWzd&$`!?p zV{Ao_S-7GAx7Hu@`q$B9uKSmHQCfd=yDg+6p@4;)p==p9oE><4s^0Z4b0L#dMInw_ zpHa_Qw)o~}j;$Qj{ zv^Ag0*48wbwIVFT{tBYl!OCx=J_)&DTCMM?Bc-S?`+uZU3 zd(N0&j!;4dw4d|T>zY~@)WpNg&CzvD_&)L-NncU)mu`sRVY=kz=RNl5{Q)+?;5f37lz}`(EsO*pmZ^0*9wP zeyVcYan7v74}^ckYeCizai5vFBkY_U(H(jdqotEj4-dcbyP!q+^NnWrza=I>FVvB=$PXLY zD*D{aN}zm9U|4@_XLQ&3C-AJP|J>{?E9FAgTtXKItCn-0+rzQ~p0m@N^2ehDM!yX^ zVeeE`6bHsz&&DtcvmTgt!W?J!RKs}9F174zRn(M@*ZWW46*2%abI5=fkUyoq(N=Kz2(WgAVjatbmuTdsxga;I9=+wm97NU|$w=IJu48AZr)|5k>3=Sog$fbDXRO zaGJJm1BR@uHo&Hz{=U+3@qFzONujQ@z}Xsu(?~uKu$Ux6-oV9HUp&5B<7>%2fdo!t zV4g?b-x!4>N1+5(NeqrIJ!7_+aUqZ-cRsdoZkaqE;7l-D45Yp>tQ9uH-$w>xy^}oZ zci*017Cm*w{D#@50zEABD!&5Pcxw&1*u4QmfBRos@Pu}T$LYo2nvXCwU@B*O)i8A2 zcTDj!ty6l~cdZueUJ*}tl3w(kJuS=XKg)4^qCWT?DzAr(C%)tOlhnW%Xca)d+KGDb z_x7%(UBH()QD61D_Zmdry6?@QiLshJW$aUiQ99V+)PaL$hW_SzbBqiWpV!cXe=w)h zmS_zR$3z^WE{IOQ?gw+Id=o(wM&Ce9u@CYVAs7z*V2-A3e4`1O!*#-0bK&UU<&_!R zpFhdEoV;7OpqDjZwnS99{yt~U2hbEv(Jm{^-Er2|cz8z)Be?Q@G^b0e8(eK7;Q)c7 zfEB;-RORL$&5rh>Lu5*B@FKmt*}O77o8Ebh0J`F)lKhidASF?@4;zEVT7&o|Ztv@U z;)F$ZSN)Hl%n|b6`J9qP|5mx?o zZ3vo{9C?Ad7N0Y3lF8u*=CO9i4XZn_nDauX;pJ~h+s`!i?KyLKJlYcTZ0N8Y!B;wVci#2R%lQb=UCmEC#h=-sc+0>oz-6PX^eOc(t9Q zIg@3=)jQhQ!J)(gm+%W4ytx#Z^NX2103<8i_&mr4;5cbO^a{b*cu*zpVg3{|La^)t zz3UhAqr_4Y&Tjx`8qG$ar`Er+J3JOBax=KxC%!d3Zu`}5w&+xBaEE@yRC2=xjs^W{ z)=DIT*IUe{p0u|;@e2%kwr{D!V&ND1k@ds9d5%Z-tLu|5TThHM0N#lHnNRxmdA8PC zImV&hbhvf^t;MM(G8y5(X*9oGIOY7^j`>a;d+ZU zw0~wBH6#HU!5QP%?7d1kWBmFVm0G!_jk+erD#;OF4L4S`Q1@VKl2&$Q?p z80#NG9A~|+%59X+&Mrc>rR|mNLv-D(5Y!obhMiBG(|3FeBz-Nd*2z; zamW>DYu!LvRcqe7juz(%bu|ZG0)#PyH}+hI&s-|(*D4;LAe`Ys(gNHkbU@~3Sa~yd z1>Jz}FGj6B+hed?o*?c>9aR6Qm4`)3UA$!i+#sYs>p#08jZN{^)lcIa*^z_BP|K6o zQE#S9v|)0(luJ4~s2*2HgMi+yT-= zDQ3|gI_;0M!?wjw%D4G1RZFo%I|P6M#Q+&9vN2@Qw|T$PSJU`t^>=o|L4Qg1A<+HrWa%Bo{V_w80oTRV4&>zif;mA3T4rhL&%lTRh;AasPJOz2ENIZyOp$$ zP&MR8DrmbeFoMixzSQYfiR~W(x@T2^8QY$stA_1Z+>|RpwIE#j-{B~#0gnWzlq6g8_%ev zr?>E2#xwHqv{;Lu=J^$#b2Hu6V?2Le%bqb>&igzENw-_=?qT(!)m~0(r7_Pv-PXts zz;x+_Sve@*p@BxA&1^X)bGEa(G=2@GlgMVzle#)ldf=GqpCsa;h~Jey2*!atZO6T7KD#S6^^io?-Gt8U6OpcfU2 znz#v}UkAJ8!)~aL5x3LWi+XIAmWz}2cT*D*{&xQ#@(G zx8emj=Jyh5`E2X^3c6ZlnGWk91;sTRv;AC|ZDkIuS<_V?PgMQl;cN`Ni4kw$0-e}h z^>b}`keG+vRcdBe9>fT|nWztRSF>CX zQDIt=niem1kJ}g?gd5gNlT>flNWN@HQrQDvU@DWH6n{Ho*5;c$W2*_~VvlxYP=7Lc zkdaNaXKTty>aFN79@Ulal*r73E+r4Li(H@^wzyRtnHzO#7l39 zSol_UH+rb$>Cx^=iFksE)>)jzPd(luQ*uaDcQGK%Nml(5P#x@qv#w5A`{=T@B&MUt z+lgFBbUyI82y}WaOD;w^n5>q^M~RvOQ4{ry6m@U15LLKR5Xp0Qx3*Syx4vlTu1}<> z-s!>?yAMTO6~l#ct|~=*Is=Bf0Axb{&?_lj5HzTL>2qRl$LLo&dxCK!7J z(>%UK#|wPn?P!%38P_%6OonYmOq=74Ju(;}=E6OAvJ(MK=pt)>mY9#b#bgMk!FE*!g<-%L#_5jpJfTu_0$Guf= zhwEQ3)7d_1T0&cZhJ_GNUdH0gbd{8RKY7>k>)^>`{fEb~t3#yGxInK;SCa?qh*jhd z_ORZ23`GK0i06?rXo>ZVm3oJ>gO%CTO`k}&wV(R34FVl|g)h}wO8%WIyv@?;pIs?g zGFNs6!F7~_Cuji2Jw2VQ;$SChB63Y`F?kPB`!L_iRtX%AL-`Y}F?>tl+puPABc#2| z_nM|&R@ull)|#?5)~0*y!L&@@?^b;i+t9{YkYgObS?{#1V)3V6cPnu-vq|P}=%bIh zRZn!a`d5P;ERmXUq5VycHu?&BSzC4)Rl~quxbF%MW!?_fa96!7c%*gD-X5RhYe=?! za<$9)nO|S>iXYWGHj|`8X0V-~50gwFjmgG_?K_@gJxMR8lJ{%6NZ;X6opJ>zLty|J z?>keczn;c@PVM2+NO% zz_gtA?(Om4Vm(;G*1OPEIylVI?pS{{Xv~LePO(Td@W&O`{T`8`n?{e#=j7u1q%Wkv zHiUP+GY%gvF`T4Cj>ir(Qyc(5;J%=2L8Sc4PRA;O^#5VB}_Uex51daq&4}Nh#h`BePV@ zal9vz(5*LQ#RkanI7{-^l)I6Ry&?kl9;UTgV8#J6j@V{>VlZDtG`x+jIR>~5tQQV5 zXm%cNZ%G3MMiWsyMFcn+f5Wc=IPt(C4(lj38*JRJ0>(|`FY+>inC)OdOcD-{br+q* zRG5`d94o2p6)KPhNz6tAW_=zrP>{++(d~djD{<56VGTJd(WaJBy}*FS+C)CRFM2FM zxC0Hee(M63r1>7PV%C?IdaRT@kA+QIZyU@k{~nnS3|3QQg`9AqnoSp0l(Sd4g}o#X z5u=`!!i|{pVStW(oe53U{VN4glBI;Aq%;JU`F8 z^SEz}rAvpZ6n%P#a<^kx)VurY9z#`z>s>&M=bS|*%fn20Sj9t;JS^p5*D%f@ zQKqbri^ssXd=YNc(4smw13fz_vI}?A`Oq@&B4zfZr={}*iJRy+>G1hTo=gxrbdl;I z$C+No!tm`Jacpn1{W&=G>_tkvM=A>Np6-=LWRBs=lL+g;C25hWI-Jo*8YMHRplGt5jb zfcNci)nBAr;W%&Abr>+JGyCZQBUFE3jF}_UtTj1p+wT z2*wgl3Knjz)j@>v$_!lKfWgG;EgRhHmWDB6#6fZmv`Jn3Hor`4n)^1eI0 zV2foe6moX=NVd9@&F%_)`DiskAtUzz7U|OtrxttB4@^%(G)%sN+=i^?G zgP+KJ{6d8P0_a{14EA$WbZoSm5Z})3=j6x{1pR<944hA-DP!z;twIESuwft<+^ZpZ zEPvpLd3za zm?&Kfj{dT0|8{Aly$zbltq?#H<`CQDsD#|;rG*^2^*2!4IJkEM+`C~MRHy{Pu5oI* zGa*->8>b4|0mYMlab@9nHPiubhknGHT_eA0aHmP3q1#5x$T`3SBx*9ehvC-9+6dq6 zzgP_&K>khSl`^Y)7*&-#`vO_kBKpfo{vU`mDP?q*2`ZbB74nlwGJj0QV0D(BH$i1! zaSu5hS=JA9dMQEk>;ex>P=k;Ip*zSpk6%sWAYC^>Wwl~h36LGJ8yAZ=`_9|=y-r|YM-t6)Fvj}ve24zak%ZpCw?PKt<8|KAc z(_vlNU@y_FJDx0K<8d9$K0Z-RM`DJ~&EaVGRdGnn_SmAPuU034d9 z(nP$^$Wy5^1rs?+vmEIm&lmE12bJs}?`>`-Cf@h2d7Ga)+k(EC7Re=D&KU{tNj&>w zh#Sr z73jgcqWY|tiA)0bvYHK{REA{zXVbiVi1kJF5G%`{YTev8#1gfLg=DBBdKh!i<)Ilo zpizb%;vbP5`WcMBW!f&u7-F5x9b%;v4zcF18DgD7=@Xqnbo5-tPXo+|rFxVI4oNE@ z?Gw_DU7`l1|NHJ}#PTo`kSK4LgJlQ1C8?1tOcVnqt67PA$c>vP5V(&92wy;ob(2-9 zYdasdO;%UB-XX;`MO~Bl5)Vw(qeO?2tUGyEQ`C*|!dgOO2}5~eit59rU`YIwMc9a% zUxx26*ZZ(oaAcJujLxF{5!JQ147GTd9zInKcC66XOjRi|K2}UsgF3ytlk@v2#nXbF+wHG*GvAO2B$4~4it!-!5Oiv^>`T`V>}u} zoZSSDyZ@m2Em#eX?b{f$IN-aCwNut0GL<6N&}2fMvWu)@4F3ORa}c@s$YBbL(>Qu` zD66X+!Movq+(lDqlmvYf6;faXgTwTgY4qWz_c==Tk`Q(|tU@Rti!=;3NDo{reHZDX zX(}o63?182*M<8B_n&Vqv!m^yBS*`w2j$9XYNC+$>@;;*9{{XzkH!zi=zbK(+hZM# zWj>1xDmp0BSNZJoi5<%Fwi)};Byvi5PdwJ&sZi@PiKub}h*KFDt4~Z<(`9d_E}!t+P(vuyKX0g&^9U`BM zpee^kS?}^J^-sZ>?`@u00)>j&`9@lA@q%qV)IUJ1FrHc0hwf__X;t&QmFKqtBQ4pI zuz?n4Te8HF{Cyju&oZ`;dq-POlKx6zw2?A^9H@D@`C~Du^~hTDJO&FKWyQlOL_Vq9 z6&zh;t>;C=9C}Y^duXUN8G-Dcw&;JT`3RP(DH+3UGdatZ({H&(T2D}JJ$8 z2A)5!8E$Rl89UJFcE!Ujsc6yyJaFK}Nv<}_eEdJmw>N9XSa;j`t}#xxb&j#_i~;zJ z^~wsK1@N=MG1hH7Kg9FB#7|kqb2_Xg$V`UB9lviGbqi^~tlDm~nLWI5q!7JgBqO61 z_KLq$d3s+2)0U!kf4U3^U%9SwsiuMG(ZwL zK_zSz2C?eAi*4_Nsff#6Gm$0&O=x+cZ?siOM(G=Qf2ee{wVU^AR{S#Oza0 z=EV&XYdtROG>eI0bJR5V4A5g(+IEb8{op8(Jv$+boXuNyC+nbwHmbXRevZ1J?I4##T z8}UPC+OGO4&S=ghR^Fs5RPQ)p>W-Y&Exdw7WMCzyi{znc1+F}$E0gu=Ln}J!@2*hp znKHhG+J5&W>q+8#%AH%nSwd}2%UX|;HWl=}q)U%VdKfpE4U&$|6!@hj`@UFuO<4hAX;R9coZ92HwPFXEsdkjDR+eWdZUZRwxYptSF)^9M-bLZpZ(QCw87>+D(= zMxgEfvwBjd=$TilCq{>4V~RDI=DD%0_kzWXYbT-2_+v&7NESt4{R z-NS|AKOpiiGM0J&iMS^ufLP0K{I5gq9?2?YgUL;vQLxLL{1#5)r!F>jM~9S5h~b7z z>j1S&zAvdQ-RN+#`tQcv6(~`G1;!qc3v8{OmkDRDHFVkk&Fsg8Ga zYQ9SAdL_cD6jeBab=BL}+dNZG&R0*(nOV+VFf`7MjwcP0DWrzr&nuXRg5Z~k(a-?L zCW!3wW?TPZ9+Y=kES%)|D!wDK>P1^QFtObN0d_O4YA98p~HSPa==q|Guc4QjJM{2&s6aFJBNJ) zPod=){`~=58vJaL)kzK`_Q>Y7|# zvVPqa)obu}o{Q&ti31tYvpCw((S8FD{EGyS9+ZEM@-m+Y++b6CJG~3(bp@(xya-2W zpD&QEj}>5v$)JB+g~}6uf`dbbanIo|*aaC@sCswmA2v$F!qvcKjVJV#g(|H`^baW= zW@Y*4y)Al@D}C{$eT=#Edc{u0-)ZzaY36@$S9y~ELo6^y zX~+}gSIX~xB*VYHa@b=U50Xs-esnNbB(r3@=kV9(T68hnXHniwDPp4*T2-f7w^MnL z4XaX=}EI3U@HW_Zfg`ViHe=!OFWO*WiiCQ z)qAf~J4P0tMxkq2GdtaIEq(~CIXYXg0iQ3dm>fw0yo2_&4!EX6MCL8h)+2ydb?&q-KaoJYeVipl2DB|D35t&r}Npj^_WcRbtD-|h@iGFlle!_&tq z0B`ZO$)|7wwwPb_k{g(-zSq_bOqk#37j97Lj?eXb^7pC!TKQbmoGN1v-6W z=)43vfiCn#th|g(serLjQ9u&}hBT+n7-yHigz_sXKQ2~2BIJno7B!zXq8Q4U5C9UQ zS_&6~r2r^rTnar#0pLmi42uES34n%9(wEWlGK{1=k?idTI18fXGn;bk@_i{ki}DT_ z%pK!_iNESw7OOsv(R%%2dU&XQLH_#d_vEjS{(3R}{ag&bEIkE&>zK}MjKVMUrQ7iT z^J9zN#C+60hF=-@Ri}8HACHxXU+Sei{1PQ_LyTV>(enSKy!7{wSov2dPk?B5eJPDx z8v`OUqyP~D)q+4F-MH&!y77)!29}g|28mm`rn>j}Zpdwla@DKU@*=fNjMXChoYhRj zH~iL0yF8b9*}d>vE2C`iJmrNA+CxPHi6A5CtzQg1a|u)DYkJ8N2=}sHFMm7r3rnEi z*#83=`q}Nz^{3nY+e*K?fIJlXT@=G?KbRTJ_XA_)5r;Nr1e^*<^D_#f<@0KL+w{Mg z@*jYijBy!nvXz|Q1qMrr0e~}Y0MZdQ{qmy#jvLVqxEcUr32G&cbU-!0+Q-Tx)$H;^ zW27mIHJ~mwLjFkk?UWZp1-_?v0HS$DuSiX?c=vM4xyRT;{NYedreQ6=Eoy!?Qj9&K zBFKq6akg4j=dh)+o14sKYFx#H@27u6;(n@Am#Xx%rM*}k^16ioqHd1nAU9Mp9aPjF zpQPt3Rs9fYE0?OYLiA7YK>sZ3U~3g0gT{@~yf%I{$NSq0fDcG7K^m__9d;v)rvrBq z()cAKFna{5^3{}?c(sCj#8Gjk^oR+H58Kf5?*&V)q)=R(=75y8^AQ7mC z;{`aP%)Aw=@db*ACAX?+=?|x(jAK4!VUV?i7^G)7dzXfhNODi)!u2D!D$lUhWLn@d z76*nIb5En~$f|!Hcb@jdf#)jOE@VsZH&S1yGnc7BNwZK2WdYOwYf(#N37Z`GkM=K9 ziNhWvDZfipIhA2lvR*9OcpNfPKLi} znfp4+C7Bmdmg+rRTQfLDxkXS;ChXL0QM-XV!`SmYx<5Ogdv<*9D3SZor8-HoTS(rj zprfRL|10I6Z!PG80^^EjP}Og3$wt4l(Fi&-h`Vm8e!hFtoFxW*xrTpXv*P8a^kWb} z#7Ap`e6@qD-NEQ&zmk0S(6EBeZPs})5=FE}sq|qfKRZffMO4mwDAwn2ewHn9Wb*%# zqAAc!8Yx4rF~7fFs%$%aeYm=t-k?;{fc>l*B&_D=KRHUAiFwThhOzesmU~WLj^(Bx zlX$&{ldK07e0`}tqtqDBGqi3KxLnt{&$`FG?X5t2UvoLjUjyqw1E;IH>S?#BG}qh9 zxHRQ9HN5D-3ZtYN$C}P}IZ9-~D?GdreinqK4iQLxPY){u!Wqz@ugQ=jy@4=PW&HmP z+Xk){zqYhU&Oqo!8uMb!N?>>}NmP7Qf&6(=o`pl=LeQvNM@&&wmK|2U=74 zFb+WbSN%pL@9&6Yj|xw+HGzDG04#*@V;uFeGdLegXWq^vw0tS2Be|ndu(5ltvAcCF z5H%S{np7I}bhl*j+ZRAD14x#V(^zcEwAji<4#!}djp`|T6OBulkZRyJM-)> z9cEoi``VDX@D4TMf;JBtCBHln-D`peS9k9;j-}){?I@9m*}v-d?oi2&@%pnnl)EG4 zWkcWNzDOsmRF`($$}kCFnti7<`u|70WTi@LQ@+V4;bi`;-F4|omC8L|71>DM6q+cz zaUP6P2UprV+ZFR%!}Qses^3-L-RUUVv&LcNclI?q6QZGiYM-*(oh51g5Jj>fH;65u zE#y6dAI!pOOty}M&7^oRe3A7uX<{m0 zOa0<7BW!68QmkK;>E?8Jt3D-Iqj02EM8O@TU3=>(eX0Izm71CPG2y)JxcPDa8&hAnQo1LXaH{j}Qo|i<^aFRP zF}*K-S_BdMb?j6MO-eS)#6@5u==X*G*Imj@7ljR`dVw%e3g1H0@liE^|E$kIq@GrnwF+A-cnAo8A?*^Cvg^t4HZi zR;x!{KagJ)scT$Y8QMpR@Os-#nU*3Z@e)$f0_p+Rm!xb9s7qabpq!P5emqPK^68zM zDHT+MlJiKRRawtNB<6_<*_jMCjM0h3F!+5X#F~A#83&LL4@8Vt;mtScu8Ah*3PaE^*sG|f^tTt zHU}v4+Kxb#Gca1m-=kg;7{w?Mwr=Ff)<^D9+1Vj54R9!6_Zn~WoJDP$lkBce%es@M zAXv{A2#2#R1(FTi67s1YzG_9HzWiQwQQ8QoA)&IQ-$oG(Fdxk|-!S(44c2(-Ud|@? zSUz|HnbvMdd+J`5)dP&1+3%Jv{SKqAxS1VC_ZfDddLn5mnf*X$;A*~|cq|6k#y4~@ z{`REQ_w4&0nY{OkLbMRHrP?M+#;=73-d#-C%(WPZuSe*cfV?E(+eQ_^v`$pn82k2nB;#1ogPe*-vJ`X>0<#CMDw}=*bVq($onVI z#o#v4e*?|HJ3<0rO?m)-L1-nGH`$IVV-lAhXW6G8$3$@O0W~4H7eGWqlM^xm=yM1i z;$!-Qs^8#msquDPwrY?dZX~W`EamM*eAz5+@LLtlP=MgZ1z{QWKOnKk-h?*eppFg7JB{#dlV)_HGK5Pn^-47{OH)~8TkY6t2U}z|SgCuSq>$m8b(9f%8z&T}NhwN9g^JswWbJRt+$=+v?*Z=`*$RrTsw0ot**7>b;1+su@SLyGI2NyFShQc9Hzaj zKsO`%zx}<acpRoaenJiIJ?n%f3Dymu|EPDOp7W%71c7?KT$3?LfBU3*7&%a1!#QGakoaf2 zkYL0kI|&LmPnfKqdP?O?edb1Dp;Ixs(B9$n$w%~~7aEizG}%%L)l#^zV4_vC0zFZf z1)UK$o90qzDBV_xTl#*eo%S>egmB`{MMMW;3p4L&H8G2^Uk!k85T|`ABJ$auL*zL< zVRCaS+{EtEN#ntjw+_kMx|7uB@8i0MDr2BUk?}u{Lv(bw5$9q+9Ul%xuEp7;;6(<=6UW#dtNbS9%0johSGOFXIFn^Z7)8O-mlGd}qG7uy-2 zo7|#y&!SU$#%5;q7q3U0Z)Wm-f`_x4)eD1MPIyqszOlT2 z&oo^NJr9*4Rv8AZm;Y^^Xf$swHmW#Wr4z#{7PFAkL#1Q13M&arUZ2asxAL%k^dyAm z=IpSytv(cvo;1M<5b_0xL7m@Lp9`xgq8JzO6WQ+}J(pQ|PMMmV`H@YDj*%Tyely}S zfVeCgXV{t|UMN}y?fx<~Elo0tztm%pZ_spmw*U`v7N3E(I=x(N>gZ0g3bTynt)cPy zK)I5@PSnN`FmJqGutm+zh_S1~)85)k6pqQuZ7+#X)57RQWS++M`pA~w4qMk$x6`g? zZQUbO7Rj{{^1D0ekNTuO+B?_XZb$v# zOcgD!HQKCOay05UY2YI(qd%WE9e~GfyQOW_qC4AGIeZ`cBBx*g+527Cq=2V?F#6i(mAb1bNfJ3H{?3}%nD z+trY?;nXG0lLl9`%hJ*wPmF}6064T=rOvq@E*IAEv3=$tv#iH#QODdNVl$UQ`E36T zCExx(w&-3L8*{?8V`N$+iTq+lY0W2kOJDMhkFfI@;^V3at`gmN7>&vo@e!gK9V55#|Jb8q)ZEuwYv4ix5F`EqcFeMA7d zqOn$Y(x-N)etDlUD%)bhZ6Y3Q0ZtFE8@(3az*NE_H*|or+=+bq3h8=7yXyJ(w=-7C zN~#*Cpi|)G?re;@6u|SI$I~9&__PhVE1?8K$g-q4>lpdv)Q?XhaS+B`?a-oO^Q8R;Y;y*yY zj(V48@&2?|8RUB^hRrPiuBqu%xnieEb&N0MZ42j_3OK?Ysf?wE^I|JsjZvg*tm7k1LD3RZeUQ3ykE&Mk1Ff*dTjEt zPk>{So8kS(d?vrWD&ky>7wca2C)Y-hnfbC>k|5${C82x_CS17$@Zig8P~06*#ZlNz zpL-eN+An#D)^oSEXggfabZ5>2n>W)U)KPyIrArtL*Q3hLt5lvm73)8LSvTt#h4N`g zxm_SJvXXBTndhZ{J%!z@kL5c(^Az8ixEOV*k(XsAt3<2(fP`BKSURGAUURy$+etS* zWUtYxn!HqA99Y zvI9~|DTg;r&#S^p5M?$80a?21-BrKMP`-?D`ecrxhhUP8`r0F zLiv6*Jnjaew8mPd z@Ef$J)%qc;y(6f9vf>l}D2ZImmETzfIBN%Cur;r$Ytk4R5SpD2L;MF)v+kjmQYHpD zMtP15@pqA-J>Cva*Cp%1zc60rU5hQ^FRJ%otc3NK#LH><yUJi(P0%>~H>*~^k_o(o}mmDjfr&5jv z>5pGmBT%^OeJ*cRE(kW%z$?{CE(fsN9L~UDs9N=qJY{Cg%CV-WF077jXV`Qp?O{Dl zV}vFm#)rW`o2!+?gsb-%xFuApx1#V^_`7@QT{UWbLN;BqI$}T><_GQtnNh2Dp3j6Y zgR9P73Dhs#8p}gkd7Z5`)fY?=M2Jg*@^PfjK7|jm62PaI9`lABz{h@XEG1C>8>&AG z8vETJ>}9?CKAZk5rMU|)`Th^*8mk?F8l65^%_$0>;bJPUSp*JfKIko96KFgVXa-KRxS@^R0LsFi}}LU3RO znkC~=W|u#~X@zg8WdpvviYcnOWzSz@A3AV&t96+y=LihEG;g>DHRUapdex(Ff|unD znov&gm0YYG#vZOb=Q^CEh!fXdu|W#2OAQjn;`cGpBtFVLN9W|+!+a>LR+Hb$j-@gg zY{T60zVv`fO1g}f8pv{j%uC7C=H!CT>pt9{D%k?caDr!rP^X4-vvu#;xbP0%;lBFY_tb;^`Tj+|!!oAj|BuVOmpDk( z9Q_NsoYsHoj`H`>&|2ubL+>L<8?HH3dGdX=*O|N=x-0J z+oQM>!^PcCt0U^N)^|T)G!Gt8H?_X|YPb~aL%UBZjsia%<|N05obh`eK0jTjj}0C95NWXj8$0CQ8iK0J+X9I zh1KQ{(1(uN2UzQ244cT|AnE?L+V!#8G>)_n-XFHE?8aqWqsC>^xxK7T??kN=nsxE? z#K~2Q$#Vf4pLa4BEa(uuZdd|)fAVqkVCw%P?OmXvs=oN~d*_0vC?F#spu7e&AW?jP zXv)BVmZs)dnffh(@ll$Yaqp$nWMF(`d`oVUC$*A?`M^}t^hQ?lu&0%zrInTPC@Tvr zO`ZH2|IfZN7bkze|62dG{;b8ich25tpMCb;XPBzWEuuOycv4j9dipgJrA zjCj&UleT!J9-sErW=%4=kzb;#D2MA_jV|~4*LpOL1>ABQz!zi-m3ZfKE+C@00f(iU@ z7HDA^xIy1@4)-&Eds8Dk)O`5ce7fYeCIyqn6WGFst^h)14zQS!mq{X`vm}oEsLa@I{HPuSOrhJ#vk_ z^4dvW+1|=4J1+6cwU}7thx@TGbtXS!cn!phAmie35GcfsK-q_z_C?_Ou)uG#oZsx8 z;6&G6`py=6ZFA?^6IEN$$zXtf^^D72NdQF^@oegMx+pPo5tGRBztcLUQe7ZLMak^I zcllN_v(>o0X|`4gd>N=Ug@t^dpNR_MYl_Ki&iDDFVZx;(unK!JtNK1a0qx86yLhnD zIUj4tsN`0TzwlW@=e>iVBu(Jt5? zxRm7L3w0CDYE7l|*H2?hDj!~`HHqBl1eWSf{~H45D@S8A5LSKpKJ0opn=chs&U76F zYypFFxZn%F{?>W#94_+09y}5El(x97smPv;&mkD9m!k47q4M|4=wK?fec17JOpeT@ zxoX77wR!jiFoLuKtTS`y)C?%7d;;fu1hlFVgI6sw*T(R$nk6(;dWOw8mp|6Dg9wc_ zJAcKJl)n8Tp2rE5v1` zLs7**=*x`4h%@?XkmloUx3PWA*m-}@P5g@BpYR^qb!&6JcAaJhd;tb`r9q_zWz@MK z<*A$zs--3WHQs+Wa;yW%glMxu-;BN5n*Y5e4r0{?HuU*)FLPQ8#@25Ek=(0*ndw|~ zM6?EBU+e9R!fbcC50{2^(-cL+6|Bb{HR3YbAM+CorQys%PYe&1{Fomdh6YAHw6wl? zxUz3%hI1v>$FxXmL2UAANT zIsY5~!$`bF7nM&zJIV83WlPjL0FRL*(g-VSy8FZlzto1zb!3`&2; zNapx8U#4mp>I|&&*ZcwLq`!M0el8|T!G{E#nWR6G-4t?=!PPdLRbCEx(w?1S6jzBT z2=fxK2lS(+6gK-pKHa%mL*wmSbW_xaR+gu*trzlF!qIAY(NUw7>2RC}v5)gvRC24E z_9C#J{#*XjzB4rE5L(?_If{Mw8q8w0+z9r@Y*Z^D>xG`2cwgmz(rdZr_PmUhWzbd;A;I1RVh{Ea^JC^P30&d%0*RWMAhmf~k91-nCSG|tpI4S2 z;935k`S+9VpW}J;_@DVx41OpuCk1ouc7rnEVchuqSN_B#AS^}Nu*{T_hfwDzT#L6C z)^zq#2nk0 zwBTC)IO2QlIiBslmcLRjt~|#}nFjKyP8?@`3@;m;hz)IcIYKWF;N^l7H15HR@86gX zoiMdS9rAa64}-Ano(^@)|MEBSLLBOF`UZe)DCznQObq%WCHURc&jrEVjtd@tddHIgMH)+;%KP4>)bGXz4WjkCQ(>? zK@j78;g)ME2I1ZmjEp0_#JKRFDIE-FpugC)@ZnMEwcOGuY!4x4;E(hrN#Ej($I$2HoI;bs?|MQ0z(Z9mg2d!T95(gyiaU=Kor&FU| zkJ+HPAWTcg=ip{IxN}OIgS1XBF@6kDqj`<93lm1sf#5e6-ZqNPI$@6EBC%JL;jLX9 zpMLfU;nUt?Cd~070-lS0z{9HF zMKi8X$;Hi}r}Dhn@NS|Kxn~ll3`TGxUdB9i8vegU>0=_zI3gFGupO}0ZemhT5I^9P z;rxz99X{f?`5=T)@FHaLq&$?2xp?f8D6k2p=31tyH$#hHSN zmnGfBXkjm2Hgp#s6lOsRm%59&{y})LV=#)YIU$fl(?g8*=TYUT-?R$@68=Hrh92T3 z;p9Xd+3P9B3m@TSHod%ym$f~`r-hF}*2fnqpWtPGQBeM7{AW>q_wNeqP&MN>hmSfDykY@X z@$lQM!)@li&QYET*xxt;zi0On<3bjK*NP=(=W93sRflP3w7GI;>cFhD_aLx|kPGc&XFa{r_TpKbkd=o1aKvR~m`>?|UTHh= zbVOvORU!QfD4y&sX8V4Mb~6Tm&w*(26Q6){#Mjx--tD1mtDhLkFJ-lUVr0;YKCTl; zXy*x-nL?`ws$R){_Y>3k$JD|8;&4NE&i$w6^bw!q4R>~^9f9H>-aYeiInaG9M@({QjH5kcK6xKk}$oW}Fp)Y|@Htih1op`MLEK|)S8DitfvGGxIv;>3CWMd*$~ z3w@@?30{5TU&e>-;>2A753H#J#eoJ(hgvXD+{ojF`QIka*Ai|Mb9t||D2II)FJ{NQ zl<9o*W z4swu-*efH&*MX`|N)aOrhIEAdqr`{sRF91kpXCkXI@B4X#hOzpH~jb+H>FqIht}zx z)}f}~4_*zaxb6J`@zw5zk?6W|!N|xC^}}3oG2eYTguDzgWOvxa0byHk@6gBMsKq^d zl)MK)e-5qhg`n@=icZ2NelOUOZ~9#5)-W8W#^;OEd<&4*j?H!*Ph>OS1)@v<#{%&y z-+2H;0Z{XJwrYD=oX-QI9(zO#;|;?))bk6)2zp^YkBU#wbNQp<6$0ch79SD}$uObE z#bSESSPGlK^T<+hoj@3qo)8c6zLGz-Q5`bZZi^Ykd_~w%%qVrZDAo(6TxfdDK(jOM z%L&faF`RQ1){EN&@9Gb5Nz(!__45jB2zgQ*Y?Oicz;x{9)^6D8TaAzRuo+LHv>_<% zNil(*7oHS1kH&N1cyn#VFm$^3&vX`^OhVcs8EJ?|C_>6ZT0GJ!u)`!T%v?)5P2z@h zs7Ia>pW=l~@IPj`_=y(Hn0qL7!kkkaA{u%kaH*-oB75WtaimZJNz7OwCKnopx-K!M zfT0s~%W>%;*NaokNYBB@i6$U(Fvm!}+Eu`*<0st9c+UlHtBcf3P#^2JYta zq0``@*nTn+6SRG+)g;t)rFcUagJNbBqDy*aFxqON_+aE*WTP6IQA2n%ob@s$BV-P|q%15yW!r;x^$pgzZx#e#Hwjk@;+~_?++!=q_=HX}&UEI2?t3 z3t101V4HnFlca@NN48;=nAQgqnOcG&ucv~g$G{UTd9@hc+uxnsf~ES8v?La_T71Tb zLaK&}9&F!gF)7%GPHUQLY4g!cifAxNbG0~By|h|1@PLC=am84}=LOT@*-b+@}XF}pcg zjo<4_z{%^74slYArwC5^dT>&l*+cCp5#xB%Y(Qy|HVU^pK7jXqc!!Fbi02IAne$as zpA#4Ifv~{kV2m!5zAuot~p`aSX z&9&EHd$&P4bTchU=h6!Zer7`~AsgU6ZiA_B5KqxFq)gmnOa*`xW?$w~*l_$lT?Xc6 zL0-h%19%pIIqXH$Do@O{KuoDGir##mK7hVWV#1YFet1_|#fy)Jvxhf|Pa6iI*V!n} zOn(W2pis6BMHHa^W%!*FfhZgMGNbVSBN&%aLg7O+(hjOF#H3I&CJzedbIwWx28B!v zjeHwIBX-`xle8A>!A?VF4-_nZ)~67_k4QY%I^SG@_xD+!Zyz_ZoiB-5A@hhpgt^uM zw$SDhNQ5~^6E=x)eeNe9sNaj{k5nD@#+{Op-MvYS5_*H(C7Z^rrPKUI8!%^@1Y4o?6hAiT_Y zSxojH2mMhqMQ|Nh2qm+Z#S>`tHN;eLR4)Z{u7SH*@~dJ9D}6=mE}V+P7MWMXyM#u( zoPR|e?0*K;BnpJt|F#a*^r|?JHvl?mt4O!E){xP)7<}1|t>P7$3MTd%qI)T4uXHjA z?Asw_`Xr4X@*FM~$EM#8=GG*bYmWd(8^#DBuO}=umNrLROI?EZPM%woiw~z3_T*|w z20?BvWRTyJiIfjb&6zOReP;j6(#F$$+^bf$oNDm)ZASP!OVye@t}VmcCew07)U z!;x?--CV-T0;VS>Bb_9&2$Zm3mrSrP1GmnafOHm+RnU*w_lRjRm{HJFXzHcBgq#~6 zGuP5iMqQR4M0coX_8@515sM-4DQ-mUYU@H=5slWg51cQ;%Y=Pma>yYRYzODGIja!D zAo#%#Z14O71;aZHb=vz$F*G4TQ-SqNo* z#Ej0GFDIxA_QT1d=PK>r9rD1Fq7L@t0eqmYmy%`+R%Qvo3J#Sn{RPMKqFBY3D+Z{a z91xd#Lp`NcXq*3FHGgWY*wQl+@eFn{?MOGXAt%L9_1?EdNt>V|tfGtncJi>;V2J2Y z**l`Q;Cl`oJVE@<`LP{G#CqS~+zG{eA2q)Yee>-t?iBMmKZV17>M8?QyC1X6`;i0*#706Zo(pn>&fTN=b<-!>%Nh5^rdY_&SwAU^He?xu7+I#8X{D9XH{ ze}{VdsF*-6O!z7R=48it^(CaT!+B0t67jlCM@lu*AWP-?PazOlHzA5OK|tw{~REb+KF*!PM% z(`S_d%ywKn(bN4qqr9)0-h`l6PY8@Ms)tWtXffW6ke zqKJ*?Jb#4;JU@_|MgsH(4g}k@2e7-#16kx(qO22Noza(V{Yu;;ZyLa~l0$NQWwXEp8VAgDJA3Lo0o&4J#cdw&VBVGh(J8xI^tcBaZX-gE#*h z|1%rXl=~V-tCO0=HD1)&LrOK+aT<6(J}&lE{V28dM{#ryT-Q+g2KY*>=&ShlT&#Lk9tYF44W`b?=7wEovu_ru=K5-I7xB2Xe`_9Ev+%Uf(iC+l7o+9YBy;(Z(tX? zN$(+5-R&d&*wa*L#%@3S@4`PHASl8)d=j80LCMA`$DecJm4xPa^+2Gsu7}qbRGPWJ zRE&Fg8~aOFP}L@I)I>rms`FAR>x0!}1Eenu>6q8K7>$bodti9lqhCmE`u~KblQv~K z^X|$U)e9R$pTmf1FJRAOMAZXE9)LzX1Vhq4X-N8N7CRFq4feqZylFnhr~c8>V^E^z zfuhk-u8o#n9gW|dJyfA#LsXD!_+S7&Iv#5j$4#<4p6$%}I_H`OUttJ8*{uV8Ccb*u zqeGn&BSrWS?*{CD+>T8xroQG;tBc~<`gmzHSxW*!q>DxI>dAO1P_xa4v(0av076Hi zl-CWqH3K-~cIhDlLe3h_9!$6tHK}7cK%twm(9bHS^47`&T?;D>5lih|7JK}!TSQdpDW97ZpQn= zc;_lIoDA=ShDrlM*5f4yi99IVhx29h{w&gF50y3<8=)~wrdo@l=>{ab)fRO-^GTK- z3Dp7hHvvkU$!>k0^-h-hvm1}i^Vlue(ECK31B^8>#V-m@*(k1Ng7v z2eb3zq&VZJ9)Lsxf%30qJIm7JMMqw~JW0u|(NP=53r1_o* z#YDj{m>Dx~X3RwJp0-A*AT60Fc)o>f{G2Z6k1( zaSy(XqEXtg^oa+Kfii>L#_`fDohToSi~1v7g$=OcRS}})Vq@->qW!O60%Y%0T5*AfD-|nGr(!-bF&ge|N2xZED!0$ z9_c3JJv!KK?T>s7sDn51K7po9x6+@~%K@LoFddr#Dj8_E_5m)bJ(h~+}J4>7jO54h5{0_y9A6P#EdI1buh6OMuv(6anK`RxPtzlYvW090#1)Xb3-{NBj}PQC7BJ4mfnL znc=c&5*?+-kgKjtV*6%D@tR|x$umC7>}>eeqMn~2?d6F& zn<;$~mkLrmM1AkbM4l3UanU3IXsDDmXx5EN_ds9I9o*$J2J~r_k|*iX>%K4)EM`-$F|!>(%pS!m&CCXNKK6%8f%)N$4E9aPojt1^Q=ZOJNf| z(uwaz@ZAQ(k9FszJ=k!_U3p`GV*!0Hc%pDO&I`cFzShpt|04}U{Yr_KdN}DyIBCd% zIsPLJM4(eT_u^o-?>|xl;ZWUmJkp5cL1~Sa?(XX;e^q&s8vc+po`>qR3{_CYqB&9o z{cZuG1H?DXaTS^ub(5e8c&Fz`nYR{X1AbzT)}58=Zi@?de1sfs+Nl_atzrxxEP-`0Oqz8$w}4sKA*#=?AJn3@l5} z3r5*7n`U*TG3ZM5^eQmsGgoT^r7dpXNP@6cB&lQON?6^w+|KgnNtJNmu7XeqnTLRy zXT4yzzRbJK`bDVz^es58D0I?%Da(w(;md8x7*Q*QdGth!~s#Ph<~ zzuMKU3#3N`VLN#7T_i1|%4Nc&2)`NljnF1rBxTdHr2GOHyo**QtVba_4e)cT-nLum@KOZFml3TOL1)OLQbyrx2;8XR zdZAUwH1{p^pg<&zg&^wR^@;1+nK%&Nv&YUYs?$B5+yC{a1lM>CQ3I6R|BsFQIJm50yXC^mZA%{ zdk|-9iL-3)|2a#Ciwb3$A^@ZgVI5FhALR%hmTA11uWjNp-ZJ8+ITTx zsib`(X8BU-W8pOHV!{*BL819_yW07Llxq;~gt^%y={{i?UJgrAT*yTfLpz)+Z~&dY zwMQSs3PIXcNt*2I4=mbh*Bj5Nvho5}E~mbI>v=K6N($#k$@B zutBn3C+*hfaMLgu(xYzG6nkW*Lf0;XZIFfQyi&nr;a+F#)&gYy3>n`8yumYL72v1w zsTsiY5GqUoPM6iAaMHU848&fsTj$eN$M9EFMmQ{6FQ*0Z8LgYGZDSQVIB zb=lR#%)omF=b;SVg?4L{8<}da6C`A>CTz5J6AS{*TOg>zsRjZh(e}IDIv6-~hKQP< z4kzX;MB@j$H4gCQfOoY*x0D)50>R(dtpk9N4}@(XP>eB&1C~E#g%p~4z&#WqZBvu6 zK@>+X+O55iLHxY)Aoc7}ev@7*wGJB;Te3om^FIUtWh7P_(Gre;Vj--v3p)m$-vJ)m zTJ2W4?cvw!Tp2k?2(GEijkpEp1)LVZ$(-t;BzS|S77r_LB|4wlt=|w16z~>sAdjxH zhkw>AMuL_ya(+8G){7m~&)*kAs%G@uYF{uh8$91Ce5MrJx{2AlgA+yoAe zcG#^40H-sVkoLdeB<)o{L;dI)!tuWgc$0w#p=)>$x}u9K_JW;-tdzq1{BLgFqB9NY zDmP{0veM#358BsY0PNkPilMDvVVJl0i43YUy?Y&QQ^N(R0{GfL_Xd6G!|iKHqejtFVb*m((-oTT?4!9vO~HLWFAD8k(j$W07?x3ikreDB!@QbkQ;(W~+kwvibrCmAa1mc#sf(*(`v*N9@HDqOl+Xu*00F=5h&Bgq0u9E zl};iup<#N36j@0;M}Tt)IQu(E)O+ir1=Xq_0s76mO24NCT z$@AJIPgi;-)Y^#VaP@g9!t5S{Xmr4gCbWzq>wj?bE-_1;!kP=XkruNW^wBp1zUW8? zWy(MHSL%LgXK%7Unw~PUhu2GcAX}}7X0Ss;6u5D9P^ol(cTWHby%jvIe@P1VOm9Fv zXuP7nBxMMBDDe7AQmFrzm^0Ev@eD*@+9VYXDg3pa(X~Fb89zt+2q*S+oNs6J4cHt* ze{Cag41UvL)yqG(vy+>or-b{EY3gQaH0iNqvqVD}mpo!zhG64|va_3|pu$!lqT(lL z#taVoUr1H_P~|8rG54}2oD;NJ5`OkyIE}#BhMWB!aN|%1hR&f2hb+?poVmC(U@CBE z*9k3kKLt+DaU9Fvf=K2o)cX)F7oo2hzJ&AP+rahJEz&N5L|*l>lwkO&ogIJK6>tf! zNOB>5e+4S=ou!&vLbYgMA{f98L|cywmQgF~*T6Yz5H37|>3jqrUAQ!_*(d-P;nN}D zB1BH0AO-EQ3y0{LKyMZFyGO(6n{X639Gw27W_%!xjvf7sY79d{6bifFz&YOm!f`00 zv(fOyD%9jP+<|aoxogglzS9T|YaaomQ*KmSeCUW-UX?Zp$*AesSEVq+kFbSTrSbH% zY;|=LY^(GT6sU1l56+2ui!hY=l%plzl5XRMvea^Ez?kXa>>bGTJ8(tZeG1MFc_3$! z2vEH&Ov(7T#nlL$WN^Q}TzXX}+zc_05>53(S$c)kervj=5$Tmu%&qCIbwgQxW54z^G-rYqb0? zK7d!a-8BI9Ocx+o-yQ#_AR0ku>JI5MVG~pmxl^0maakv7s1-nu3oQ}{^1QR zu<+NVar7LsNBV%C!d_{ip}Czc*^70C=iKoxv8PoN^4YOhnps$K3&2(n^BoQUgo_|) z_sf58fjaZKV2ODtmCeL`l^8(;a06#hovzUOxJB$cf=Yc?+ znSkIm7GWC@-UorT9`Isx39S(1fqhbTp(lVc0-$)AK>!(dAmeI}jBd>;Z5fyv1AHss zYi@xzB7Yn58v$p4zjO;6O+nd~ZMXUYzP_`wFl3b*0jgDWxwctQMIfvNffsKf09#kK zWg!H@)&7Nmm)!z)0Pc0C-FgXd+DozV7I-7&A8)r_0DMX3w9b$X9tegg*eDR@rb7}y zSO5aFNC_J{Q3O0XHxr#h=Q?pOAO73$e*;UA4OxKU@=fzKL7ni1gnhQ9I#tY;(S(H1 zkj!@Pm!eH|K;=2CeS#Es(I4cD%H;<hqGDdVJQL8 zx{H1d=p!xl9cds%@LHL6SK6X?q;)=!!$mG9SiSxZR$>!TjV8@^Bbe8#5qmd=Ru{N3 zuv|*DrwKqJnfRVG(ic2v8642tqW7eDAB4jfqjA`I%X`uvWMCRJ<0d(_^@tQR1*GVJ zq<$NX`GUo%;&=|7A^HpJBTvGk^N`FT8#ZoQq7=IDsbYx1Nz;h5@gerC%c?bH;N8DY znrRykT^O*Fi3TV!0yjc0JQ{^(BF#qH{SVqSZeB8=KEyiAuPFzxqI1L09D}N>a)v93 zfb~E@@P-=mls|?BFOd7OI?SixblrtIOjq|t$&vNaC+Kf9#3Hm(Qcx9SalKx8-ZNbb zh>^afL8`_k`O*xS)TBl&aCPM+`$yi^x@2{0qlDdWAR7CG#x=WoR2rCs-)7>}K3wVj zE7^ER^(K)odmhFG$KOSS3bNEEtCQZBh6&vOm|K^^93M#|2Yu-Wb3p>#YZc6y)23iE zY81&TCso0xrV`4JakXXGK6LgYN!D4`E-oGZXW>($-ovvF2$?=%CHzMd*s)I_rD;E4%J35@uWO7$G-JSJ6&TC^R2nTH zoMttjO2K>z`|wlO3e-C`&e`~VJ4^jcnjGTuT{|OdskGs24X)9^Xdxl#Ogr21nY4OP zKa@{*z;49XqOW5_vll~3IO7_!Vk#*U4bs+-!X|t!4b)0{{B!Bf32!4ik*vcFprh%g zEKsOGlOM?!)gMi8X5tHrxDjle759ey{1C7qlB`Y+g z9hTwihO4uWOBn{=B2dcwZN*zvEWWiZSdt}Ye#BWMdCHFkXWk+yIYBR$JJLMgh_HY$(f0y3V7 zE{WnIPaT8Z=0x|@aO{*fXB6A|jTDoK_qr%o-W~zw+H`MjX~q9K??sEKF*m1b_>;k0 zIX($T^wA^KoU3!;!>`tGMWfj9rpH5B|8FtJi-h~Y$fAMf+DCDSVzGDsz$5kC(mLFo zbgcK#RA0YQDObSAsmcJXEQeID``XpJWk40=m1-g84LJNjH%^hd4&wI{!#JD==5XHw zuB36}pTkDwS5X#yYO20*wDQ181R)0Q0(<9MX#iOh>9M(GG;94w>)ZehXFbxdKuU!32hvko z{570%oQTZDKfB{Q>2AveK+*?rOWUGSlxMJU5(+7ulsi(Hch@7M=0maXKND9{4#nOH zJg=e@WfwNC5k98D?;VN~ybUASvG1fXE8YhhMk+SI3;&0Uz`eM8hal}dKT_f7E4X)X zOYg$bzT%w!@kfBM`GRG>1@%|Um55gE}b^9N@e`O0$4&uEL z?^1cBLI)+D2mXh-V-(t@Oib>;<*pQxW3W-WAo>nv8{VlRYn#U?6?lg^l=?K^q0o94 zdce{_6?gPfXnC77I3f2Aw)F=oRCpVvefS3{28M?%f%p>S57GyIC^gT}x5R|LrLL|Q zQ_o68LJZu|m~&D@%vad6fX+rgBaY5la|}FoS2Vym*v!4z@^jL#|2Mp5j8}BL=+3sd(nlT!@P&;&u>l$_rz;FK+ zc&o30VQIm%QY~JNv|uf3A6|0cMWYZllLw{H`P5e!;k8JcyE?K8@C1jg@xG%?dcL1t zCrlu_)0J)0?A9+?@=sDfHt$F2P4e~BGu3-!P5cS_MNhV~13yVq@KlBKm>3`JMs%2a zD@DB!zM{iiH5Uu1&90fBTjfYN4G3LHj<%m&yIZKBTm&!fbfxWKyA@y6(PobH{M6!g zygYKyC~w<*e7zHRbOjc94INHAQ~^GB0oL&WZwH(_48e&{DvNMpQ4WjxMOv-bHUqUS zMnBvN=G0%Lg?f6lI~|3x;lE1r=j(-Gn@=$!t|E+(0aI2X4qE17Jn#|4JTW?z#2@Gr-Z zEw7S3O=(2bAHZf`md1^z0YVm&<1yZkLme0uEnM2pZMItS*|Q+Gj2}C?e_a|W?8D24*QM1)8)6GGA|9r%i*(Naun4UKDsBSQOaGHb@;4!nw%bdn zWB!r$7>rBY#G>IpG_%g={o-}`#jYInpk)9ICd{gMIgL!JiH=?TBzVE3`mhVUJnfdm z0Ckck9n-cZvB&?|*Fu_}n>tZvPTBSQjp|?ChNCU=JZ@DPs9J0~?w7fU>rr{p@ z3G%8wNK5S||F>_`d3?T;&X&~;?WGhh#96Zde|EZ?9D@j`G%u4^1O%6Yk37=18r9bJ z!|?&k;v;V|N^ZebpvlI-u&Xk0A+C=+ZH6vU4S>mk)(m*BFR^L!8?Fq+g?MIch}JSH zS)XFw31N75;L!Z~;~vB-v1v#Ean@b_!Z!~9?XFd`AItBd@mWK^bM5FPd&q;0^V~U` z(GJNts2!f|Ay09Ibohu!P5?{oDd!4*qn&N(DQEZBbJX9=p=8}vWPRjo%!8EHP77mF++uhI$Xibyv!xja|E5UiwLfmO; zgHSI8$O-yl8&94ULI8PXF6KSHJw+p4*C!pIG>rwqDTYFzZFPDdd6_n3Cf*#7^XWkO zF$5${6*R8K0M-INryFIO^wu&{x~3DPZ!yXVI<5if4y2tl$}yg}4KV6fr2F*!cRHC{ zV@7XvOka7t0Y0ti=bB#X+FKXyD+ zj-j$CtpWd4Nb3xhPwBWkDo^Qzdp_(Y|2+7~BOi|RA>s1;V9=mZCDlIzum&_+g6$5M z$?t3BQaX8@R-~u*mxCef8XZ3q=_msW*slFjzF%VA3KJzwXaTUwF1#w_E$J^WB$Lx* zjo+R9!HXlx#S5kB zyd*~7>4v2imQ#vE*1eh(*N6CY_CD zgu*&|(_=K1)^w>9qSD26JVsur=gB}ivDt{K&N0cs!`vdHbYc^1D659JRB8d6q*5BX z%yr{AkZ*@ce!^3Irr3Y0Q;of;&LRreK^N6v9kDmnSx@P1b%Uvmcj+ssZ5ys64)(9mU-IOwJ-b3OQ|8sy@G(sVv1+;)=> zO4s@D%5?D|{9pK}x=rqiSTm5vtwuF6UXCE2)71_pBxvnZ`yK683>3iDC&$X;W^v9x>JiQ0%(lHN48j-jZkK6ueJM5BB4UADhuxnYzFjWzC&auM zJu(eslLpJlri>3jMK(Lr>AA-2981sV&CW6O#FT#;o?8dYp~5h{93Ct`W@x}+h9ubv z)t5$7BpC%ygCa_joxsu4ijigltwBTOA;M^7Gs|7O)Tll> zRDRBYEh5^5==y#Hx^&8SxIETqt!rmH?nh7>e2*)AWrdbO$7{dxV@UIH9?-Bjm9{MPs`fIa2Py z3!l`ttBEP{Xg&s+JO{~$!L-cv&{zYiLK<6}DlfwP-KA9d+v%tRohHZy8htB)EQgz$ z<&2IBz+|=$)|R?e@ABjOo=3=K|Nnqn=fn49_IsE0H4;UAS)Ztt*NtZr(&Tv7bnmi& z|0{Gunmk%tHflNrNR4*+BOhX0= zIhqB(>c9Rl)W*f&n)__|{pk}uC=q*>q5$P+3Jm3Au8by1CV9X$766YOZnrK1d;{Rw zx4^5wyYB?V`Is}iNDZ_ZeZB#KO{+aXJupH3l@CU6b~O>VuFUq@bp;B?m$VWVK*k5| zl0PR|J0{A52km?ZBhE(QiyO-gyKXq>gKomE4an%)2jzwB7~Z?)0r~Vq`9ZHKD2k1m zB*!2Qn>|U6AS%lz$r)Z$IaW7G4hG=#Bn0m>K=$e+`4QnByx8uRCmP;vXZ!A!v%A}% zR66~|nodbkzED~dF%M<2L6hY)A%O5F%gL!$H>3!XuOxXDLmu~FSM`UksR+7O0K(RC z6AsDL1O*?PEJyo5D@_J2kX@QAzaktxjIqiTIoGQdI%5Hsp6~!}?X+v}7js`FF`85G zk(t^*03&V^GJ=%J6`ZmYX|z`i5^kE5(O1JES}@_J=gdJGoVL7^xUw^Yls!?dJYOR1 z9;Ed_+TcuA+Hs^og-ypn`}bT|nlCv}*k04489~f)ue=wor)e?zhP8IA?%gXlXyK`; zE|@jWknblTfAQ&)bL)at(*ts`7ChU4J>DM7_RW;v4goq+p{{Xg2 zV^ED;dq1T=6oP7%5{o*X1w|a)Xt#cU#8r(d;M{);PGe?>(zXS&k!~CnIB<&pqT?V| z6}$DA8)q+YqG0FDzE~~|>3^tQJ0gAdBJb3WN8_k;2+{^UCTpioh@)t9Q<>=fZTJkq zfycD5Zt1u~G{6gCzDwk;O-&UT)3m_Pfh%>!5?S_+qAH^KWWnt1UglaFp~9J$&P5vi z{-1Vd%tlF`Ni#>hIf%`X24nu|uz0Y=f-N~y7Bp#fgNZ@AOapV6?qGC1wpdRTDj zcKkk?!zr{Kkn&nUr&W@*d2AEcSM`q+2aNBxLffWVe^qsY5};0 z=P-w;2cDGo@IrUkx@{S}(i=61AePB*OnnDdL&w*TKp*oT!_oCS%}y0*3-I1~C+B<^ z&&bKRwHeQ-T(h$Vu!VS^lgl|5;aNBjmop>3{kaV1F2K$%N8nP4m+Q;rTHoR53BK5` zX-++|LVk)5!Me-E0LXyqTjbVXYetAVb)|gJ5I*M(7dNyLcH|}AxdN1bpTU(y@59Vf zk^Gf08QC+@t?AiKFbSVx`DvlErd?fI3|CCscF8wuSBN5Lseo@jzDkbsjYU?P;3%^9 zWu2?!=gDcWUyZ3CEc<8xo)2QjkszGh)6RU>$a_qO@uIDbVucsiu;DxI#_AL-ybVGQ z6aHZt?DQJ=vG2g2ajk4Z?320{6B&*89WvKC|d z-B>z!MvgWP1SzUeJ^3vBH`euImS^PqjBz>ujiC~NDgbsrBR_(V$a5Eu8eL+j2e1J^ z8-R)HisJQxm?94iOsXqyV z_=tvH1SHOWR?hBXjuNRDV(!4R^5pc#_i96m1T1fiEFM2KElLO~DH`vmEJXS_q|p|N z4W|U{#viH(W!9-vMbb;;P)#Y6=s<$41SU^W3baN&EN$fAuuo!ZiTn`lm*^~!^cgM>+-FylEnKHQ9#oM5waoSUS+sx%tEw>&357jhpW4n%7S zBnt|{XzW%A!%cr)PB83hXN#V98S?e#F&bF2yImc#UbY(G5HzkTz(^))QI#92ZdK%@ zuGu3UV9N_t&%Pi(!5enAtJBNm0es{vl&DLe+7N9u|INbPpmvaP!J@8zQJ#n$?iO}t zqg*f4qR6cbaREk4O*{z?MVj(L*^ZC zlkF!a?!b`s6?w9dS&ebYEAqQSAYR72ih!aKFXvyC{}NVLx2tEj$_ZVoe!0Xw+JlJ? zW8oF@HzD`B_dL_Z`ay8PK10n;`n;BJC1gt;tP-}*wzsQSE9JMf-5wglF|LiyRh40^ zal5SD5um4&g|{MI*dfQ=_5jF-pk}naTHC#ay;9Ca-cW8gT%{=N`gsg@16TdluzPl( z?+Q~F?2z{xNXg;V@@u`fZEI)rz32&=+a4bCid%sk?7Z z@>F2HG!t`$w(>A_?QU7({byqINCriBy5l?Es_!28lmXL+rNnVA(DTsk3sqrCTdH<& zEbz8{Tv=~)kE4N;2j+D=OH~*Pslj*y{H5Z1yn1&?EG(~)pDb?go7a zIkHhj!$?E!gwmmgfaW^JMNWMCxf^3{@H7tl*&B zb#k3YdISC)NI!h=W&p^ehLxDFFd==yA$h!jny}JCa=gJ3&ki4wPjnFmB6)#UaIjUC zi}k20*G(7%lx?@$t)Y8xP6#`(Iasm2IE7a4GCkl{!b=G#Y|dNq{W|Sj4< z+ntVDE89lmkkjk<)I3Erpk0Bej%K?NAh>7)w-^;6{tndMjOd7V9xXc{y`vT}!8wTA z^tK#7q<2+&2!*ZMUSBASmYtgbG-Fpxg>aEH-q6-1bXkvbMqgf22_!kV>>Y0gWKAZK&Ov00PvQ zE+ex*IPMx!K{m+5cvPNdBtSHl`iLrZNCYT2DnD(6ZD?!}umNmYAQPYW5B6c5Fqb@*zxSGhV_!LhyNgbGtg@BY6#P*n)oQV<>wI#<-uz(R^VKH6BZlozdB7ITCsjvpjpjn8}47+uR8z=h~LU{-sKuGO8CKvHS6Qtw#4AJ0b ztR#LWJN+T{ro0%~C)!eDV+6bKxjbNaZzP_>EDa^LK)qE|Aq>6d?BL3*pih?{mR|`; zK~rdIiK5suf{i&Yhmy>jX#AyV2ALrVw&1ut&)6M+7!;!e1OUz=M)qp3>aXZ;7r+8fE`oB0Jt9r2B=Wl@ke^4S~^f@_?L17!jymIwIOfTQ+6xm zqda|(m&So)vy@LSo9s6KOL-!xMNe;lM5!{zzq}b86TWsn7U{lUX`SUwd`Q#O5W(12 z@}@zfQ28fb?qnVeD!FLbF)+fTdod_`jVt39WwRNlQi)G?|f`g5C1iJ4pTg zqnR)mY+yFmC9~F3a&kB!rhzJ12eC;Msj;A%Y{+RjFZGsmv=L?Qe!F!nN<;Onlz%4* zp@<^`zv<*UrLm7r%WvK7V#7CK(ietW>OjDs)4n*v`EhT)j5?cxi+S7^9#Xx?Lx5VH z$ayxx#P-p-`k(}j;-_EB@#8(%DMk<9O4>Mp;~(2xr-_IKvPWWvS{7wIxCQt0x~oR! zWP?Pi*8LvpF$ega!Yz1@LS2ckUq?lConFcZOm2ip$zb}5EY~G zj$XdjE7V7*;oo9`kN~+*KgpZSV!|0M&~_msosg@LUU){n0uNh5za8}ZJ8i|TMt5q_ zr~u*Z{!U(lO4U$d&B(7+7U`Dn<#?|V7%Q;HzsGV4#vNrq#1qaK)hUNmNOrEv7H4X_aUKQ%Kz}85W0@$>y5a+27zvQEbV;{ zO2B6Ut2===6nLQ?ToPpyxX5as{vL(%gd{SL?I0AGvp;GDbop?bhxl%wCfZXyT-&Pw2*hwZ{4IaE=d zzO-9=0?wXnlSg`5g{Cercce`Y8|INQkFKeJ0AtVN2wVj&k^td8fCs`?>O!Oz<@=*N znku#DC0FYt7)5ri)YpRXHPjnKW? z7KdIKr<^-rg*1J+^9k3?(w%7B0U(cX`d`JP@w1Mf z165r;FGo!DNT+fIqW?2S=E(aD@=bsYZY)2zOBhycr9leKP?77P=>>f~oaSMRv3@(} zXE~22chdNaHonpdY(~#dwqZhniNDGN7r6_hbc(G72x8SgxLKzhV>jr5uEe1AFvLnX z^TQ#w!a!p?AsFD%R38F^E;!L?Bm)L~IpDN*w!I8XO-)uYn4S1lw&<3c0e_!|e^Se! z3-YU;=?zG41(&BU$h4nJqfYph_-{nI?{9L#6nAV= zftbleF%j$tH{48B@QW}U3lc+>PKBN#(QIECD zZyN}>5M7xL%tNa;q3hW4hdhf91MnUujR*fGH1z_mK)^etpA&*5A#XxBQp+L%|lvKll43gyCq z`w*Nw(b0J#)3<@vn9Fj674Y8f+UoEIgo6&q)oT-O8UVfjAq*so=mxs<6-uIu7G65_ zmbw}c^faPAyDz)yI`NjengBb4GIbpg|9Ry0kna1}ztc(THt1%|Uve0&rj7TYRSdm4 zNUtyBGkoBWc>DMju531VLsRUMO$_irLy3J65g_0{K>x(IE>m*3;8&Tu0dfPJB2A1- zy5Q6~+5k7TK@iu_H`M@%mVD9obRm%u*`Tzmf5|bVv^zZ*%``&!sKk&f*juq4vjSHz znSQDi3pQ8eAG)MKJ{IwBE2MDYDi%*(hNmO1wi(axYw~@<-3o54yC!FP<}iRX$?d~y zTKD8)2b3}q0|_WH(&@r)5keBQ`T~Z!vV5mJjBJh4s(`o8iOJ4OVCl5eLjgc;!88IY z&wT!ti&OOaBAx1Mf>2fsETT|5aOKOcdx_AumUyDz?qx!uaGX6H3*u`%Ip+)LdG{@_zPkUIcMr^*+>_=rL)Z_-vDYNq1L6EAUP z`*BBZDyUU4>T3cMuECXt_b5<|f4GaLjO6P~1`|8dqaeum&nYkW1oyVU zT0Z?R=9_vJ3>JF91g7^am?!-Ce7kzMXF)bEJp5mrAL&&P%KQG+%@vSVf$X5(1%rJ- zwuu-ea&vkYWJLezPN;`ehyjbir1W{u?2N_ctn`J$uc>Tl?}A8QryI?Ld>48bj137w zxJ^BVzEXD?Zj)B(()|jSn)Fg~Q7hWRg3=VPA$GbH$tp6g>;Mo?`W3wE+YYjH?O=To zzUA#-FxeMM(h~U0D0a!eVBAD^xkO24uML!fK!pw}(Q?j$92^F}1rKu6rki|$$AFgt zu`LfM_#sfogIB49q8d39ThymuU^k>2xM-F2DZo70Gl(wx7W^e#T!(les32O1gtUEv z3l1GS}4(6{$F#;KlVZ<4D_^;F0EqIWO)_ zxf@q|2(UvucQ6O>IZZ9LJ&To&u!8#yYueeQ@PatszN9c@z-27z^6-Krtvlb{zaZYY z2&fgf{UQn{7ArzH=Ma!S-@jlOSg#@0c{C%cQx#ZG98mC-aA9q`x?@1WYF=0h>O&$6 zM(d~)3n>XsoBMI zgCeNek(u#mZi&$am4Z$&7bVf8q{9}=&c+smM&^NQ85O5!Z;Zbdx>@@noY{kK?}cNb zAtbKgu>^Oql-U5EX3L3HwxM=)3Rgz={$SFnx^f2RtOYCk;tC!yhJomF#ay2~{Gf>P zr_CFF03dN-LCR_c&-B>+Wpm+9~cpj=M@jU7|5kDFP3c?STK3^PcWpE z&Q6WnBYqTk4vbiZ3}~>LV2Hy!a$g|a23M8~!ufz>DMEugz&YVGV3}er{$~PCL+e#w z&@!kX*&pg|qA2b!>=Y|Pb8`$TcqkZ|X;P&kDo!azQ^a~?*&4vEB7^V{RqeKdWXn3R zh7n!@PCtjVx^v{3^(MCa8)v-jYu22}la4#1%H77K!d?k}w z&SPgV;{r}aB`2+2S<2v$m`a)6%u)u^%1YGt^6T~96U53=)Ur}iLfk_p=0`@SAP*NQ~OFUiJMWJt9?;F z(*Wt-Pl`50DL2)Mv>E-RVWCg1xD>h+)O>Z$gVt2Mxe&h(^^;x||DKC;g*YkR(h6DI zFaYE_yRi-NQW&wL-y{mnJBtB78ZUJfcS7#V@zR9uRk?cbEZ=)UunV4wuFdhfMXH(o zkxv(-iXDUV#r6ZFPa1iHig;%@yLqn;kfNzmcS9dujt7lPgAL6AOY_>tv~8&_@`dx#m!^9MW8MHFzx1C?|--dD0gO>1%%Pxhc;=@BV=xymt z@2uz-O%ay9Me-fv!6zDWd_5jhn#|>wyzU7S;<|2=AyJC-ps0ZN?i4AkIkEQK%Z{f= z?*{@Yz-NTYHxzj0Jda9xYohdkI0US2Oq3q8f@JC>X{k5|_*0Xlln?+Y`U`rplhmVC z(^cxyp{Jo)HxxuinGm3>yk;aIl6*Qw!DfLD(Xp=_UfV#ulr%?S3U(V8=-&Gkw zjIL;MF#9ZBY9s!0DURmSr4ZO%sUXC%8|l(;6t2|&rhKZUD~65EkUGOAN?ZNop>=ay zG1~J_%o`u8RwB*T$1?_$mFe)~fZu&Hb=?)@({|Rp0XED~h@S%nRNDN5@$1ebLCYs* z46wO$1TOlOQYAX92->F#(^_Xe=h^bye!GFo}i9z#mf;SGHM5?$pfP(|W& zsdEZalQPqw?j-b2#rSf-xi0$s$WOENy`3XIG!;}Oph-4p%0WYyv8g!3C)XLvc1)L2 ztV?iJdAc;Rm6)>#*0MlK5JxPAGw=c_UBm#vE-sM5EC>L&P#TKI2>r2Ie;m~x{)=>+ z{#d<8>JQ38i=8Yu{1c~b*`cIB~RXHVDpzqo%%!ZJi8hc zowBR-AaYnQs0i6nkdSAQKtKP(<04fFbb=SW!NiVx+q_JF`UUjHO6^ht%Fo zTq=zTgq&EHAehbqtCsO`65L&-FDXGJ)rY4G8~UV_glS#=^rSAwyr{dyKP^Ai0=T`_ z`@HN)>1jV&mh-NnpcRW)CY6f|7GO=YOd3vOFlngJ5IMus8*!8|e62<)XFeq*bdmA0 z2g`{)7-9SVPF^JKN`67)JAEQh`R0N}mqK5ju-wkRc}iLweh>KaaTp_yjPKip`gw3R z)4n7bTox~v?0rRppbS$xBFK6A=~EQ)Gin|t8mN-37-vYJatK7@X(a?Yx?DOTR?J7E zep*@@{thU5gMz3Q!fz+rpmgW-_QqsM`z=9x4IXx5C@qfc!>)OxR|CBUf)*ULk$t?I zvZYmiXv_JT1uhn|3R=f|a=#?+xK+|fF{s!er}-XD!!vAsygQzeE_K6@T*_WAl{#6m zAURMft+L(?$eUPW*dWwXm`sn`BRwxZnht-lJ<`K|;;K{(d+$kKTB%y2%lmjk4`6^5 zTTa7Jc~Ek-zW&%HL@DrY&*~^FWM$ozU~m3GX_7_U@E8_hhoratb0Ny~HhsOD%A_rp z2od1jZf8BY35AIPc^2eK!FtY$0VOvdz2wcPkXHJOVSm9S=MyPA;3cCR#Yug=(x=i_ z)}VFhe7TmgDwr)I35;5O)v*aJ!PPkmb;mQU~!Q zUZ$RuB4MPQA=NbR$MKz#wI`*xpvx$sZ~uJ(zfYf(o)2A%lr*tQg&FG8!FDD49>U@u zUpGa=;oNe;WfOjz+{xlh?#E7H?%RWyoWe@CC0^$L6~mo?mvw)Yo*!z%3yqXE%s1!` zGYzF9z@IiEs9{h8F~dco>Ue&IKK!TsP1-5$M}ojF@$wB`4t3{9h&r+M?-WN?pE9aMtHf#VqOnBzT8kd>E6vuOzG0IvI|J zUrUx|VmeaasK&%6883@#Fkrt6+@2aK#UI5lEyKY><7&8|9}E3nnqk68>2z9}0r=YQ zrSfLNBuL8=E=Ue0{~+Df$4F1=c9v|Kzo5oNp} zbu%*}{TK|`{0q|CccmgDszlnzxWszTMlfRMMQMPTGZ__m5z~uVc*%NEwzKL9%l%%i zLvu`l`&*s#7+B_0nQBOOn75c6$JW+K_K2Ivv!IneIj%iNiKATwQBAU>qU!-p4?~I%{cKjEAn%#A#iIA-ac!=DK9>-UCWY zH5Bi>-mv$1AkjGMDG_Oe6kUv3>RvBJ(?~`ZPH@6g*P9F6%zCL$*f_n#KY&}Jh?yBp zjXU+Ep!EQJPd(QAc%H78o-~EBBW(r#P!cxnH|Yy(uH}>Dc4xeH726bKUteHmf|XLg z9N?%oaizv`wEzs}6>UiyK&Tx5rH^s4xQYlF>fd)?^pUyCo$>1BS2lE{yK!s(j!+z`O5Fom4I|e#oPV(0qjD9v^`)MjK_o7muuXmmo~{mtYa>{bViQGg9TXlPd3^j zr_=A<7WsGU19)2HgwS1Mk!-l7UbxWkZsBlOebI|K`~L=HgH;|*L?cA`Vevh*(PB}K z6HD;&wJ1l4oABcAhnMwewtfBNc&^&}5h0OOOWw*-GdapX6H=~lCa`VI#eLEl3#5u_s%j^PlOft%gss9x)kA35eNkgs%Gx9o~lE;+$DxwUB4f$+Or}?ipl? zT7!m7dV#3S-BOMVGL=CHDkzk}@>d8>p>SR=sV5(OKTM*)_Hs*@ z1hVPhN`Av(aw#|1gA2b2H|HU}YUU!rwN`S^{-zv6$h&JQ>Uz|nK}eSl<{0WQX>uXb z)Bw3_%o2!nYuQ#_d@B0+?#<`E2k~gndnAm_d)iq~mo~`Yb_BrS6maU|PGDaL$ci`- z#y+LByq^rNikh$;#Wf8sb2l!oOd*2{jSfcgzIVxSStwN_AsHN%%5N9^DnLjENBuwQ zw~>YvOZ9v19Z$+Z&MYXJ`hOIm#01Gn7*-oukjl8Bm7`|^3o=-` zkZKwlWkWPDG|jI99h*V31vI7&5e;crB!fMSj*W{F6#Y7A9)lD#u^EQNGuJZu2zD_@ zzE4a8CL&lKg$V_hrVwr2C=go~EJwC7;JGk`ZNc)$AO?-RS1juBi^1j^G$OW>2U_pP zs-~U%mH0Foes~DRtr1w=gvi5eZ=t}qmc7S&0@5Q5Gp6g!dT?W9A$n(cIz;YeDz=bH zqnn`CZ)tQ7l~RLU=x?v_e%G&rn%KDZ z@{r+8+SAI75+$F+ci$(GnY4?h*vqB_gs0A=5>g(nf+rhj$PQ+K*Qxe09f|N7B07?^ z7&Q{uL7toiJ(m}aNU(u6*J{ZV5&n}({|hR_{9bg$@TT`eKJOp+yzlpU-{jI|TD{>N4a;J_WBXM9ZZW5^#reP!o8E1DNIgzdHlzve z?CbO1hu*U&17vnz6QXRO&%6F%WKL79N5j>b4sD_leBi0Qo8XAfYZRbLz(lvPFlB=I zUL{nwP2fMM`#_hNVo7#+uZGFfEfGAM0TCoMWZ;4=45H_FUGMUEMjygv@j?-uao=;J-_ROi3FZ8odE}ac4s*{-dLJi(2lre zVJChC{Aiz=s9RPYtOUbmDRpE-LspgH8pw`ymTA|Z5grMvEC&2qXF00xb1=7C%ig}N zHB*By1*WM7HHY6I@P7KP4TPB(f$7IE%yJ^+Mf41`=|YaPakJ(b)gTiRz=4eNY;xEm zh5!UF0z4POXLf-zQHn0SF*$5ZO9h1RT5?xJ^fYK_a)|Dc(-05hC4zs0P43{hn-}EW zM$Mxus-mu*3PSfA;StCZ?U*^Y2H|46+*Rxa{cfdFck!%*SY&vp|Qu zQapgB%^Y&4P_mGBYb}~CbMunI{zCl>NO#O3KOwG$ru%o1`KJwMcafhLCj)S!i~MN! z-|=#5*`CIt6B}Q{qj^~-JSeid%3&7t$Xr_57`H;=T5F=V0%mfk^7Y)xcY-Q}@&3Ra1PT_Qaxy^xS5PYZq1k>FH7SXwvW z-vWNo9e6kJhmpQB@SA}j$+cPBs7j6hN?pG2T(P;;2tLw*e-121hhwM}S) zmj;LNKZ~uRYsc$R`7s@9qCts^p_y~=zaY*39Wv=1HCkZ4KN{6KdEG^BYS z%`z4xe=lajqI09=$qt`{kw}<<47xyw*+{4%;mgUevog=Zj;wu*Jk0D8To9Sey;4YI z^8pu^fy^5tZ-i4pKD7tF{S0Krz48zw;xJ0YH$j9%@1A?*eU|vU=!hx6H11L%wMEmr zvt`q}$G_>_){1TFB`*wu!IqlpCGC<{9kKGaNk(oK8cU&7M#tkw3?#1d5_=)W8 zl}qew$N+hSDM&d4AxlLSGByB~+8c758GyZyt*D8B1bLn>C9QZWL7A5zPsX&DXOxRd zypSM2D`wpV$4}uN(-iZC0zJ+z`sjS2taTIIqsIv5@M<6WvY;j!XPc(?>c%FJFWA~P z!Bg>-I!vCdt(^&xf{@_-d9eI&^Lwy>rduCmFJw30z+R^%!=N$-!_6UCK0-s&+F>Z* zw*VX%CO<|y0_0v+gfJhMhPIqbsUpw2S?q8*g|^f-hbGZYm*{^1wsyGu7%Va$_tx_L z;RiJ5?dIC|*6y8O#;PfL*l^}QLVhW9=OA)Jn6a^tVJX-*dB51kbMod8ESE;ezlgI2 zUGna@U*6kXY=itW#>vaW7hzt6b@i1tR&)SW_h>J}|L$x2J@Wo=c4M6E3ZD)FnCKM& zIkwbVYLwg8_}ftd`FFwA#467qulTgw*5cnCziJBxdBd~h>}LMa_%*hCkhge+ z3cN`5#X%`H?p(8u%>f>`Woc`Tj73D@DTwi=7;y|I@V zbu7b>Zvlw1VX=BwX=O)O%M$`pk(y3n1f+JXk;jNDkYe!~tS*=0W%nAnS4;5Qdfkmc zer(q%HH6(?3w+~G^Xfr^w0`oG$hl1{F z(9k>0&roUv$JY5#cPbVaSXst%@@v#I2~iH9!NeQ*JoZIRL`@Tdjb1C07Y0uN>Dk(~ zGC3~r-w)#VnYHpSQK_^L5kfUO+{2D;3IFZvppjE#<8NDg?MohiiM7$>e&KFdCw&(w z?R8gu;a*(rX=sRB0zT_=5S2-j7vA-Abkix$FZwAC{3%k!)~Nf5FQO${@PbpE7py%n z@mjbOds#tr>^0c*YbaRw2HB2PF*Xu5$UVj9p|JTIXco@yTewM{l)B#VZeOrPZpSQJ?ZjyxEX-b2%D&$VO_)j}eN(3F@|$whZIq7fa#~P7 z({^AY>7dTF_F!zg+}ocz-No-Z+41f2_P{t$6{7LcacD6pR+q?1Kwl$i1^@v&30LfO+0REfmyx8#ICm_wB*6PZHZTk^>My#b_}G^rgBBl$j0%Eee= z{Ty(k&x{iu3TjLYWwL;s=oId|Be95r&D@E;fT%gwCOcv~cFGB)PL9Y0i_1H8#dCnA zsiN4>UD(!-GAKC$RqKF>W$n^UjHgKRF|p()==RFnJ7styY?0fLfj80UcE-frav|9T zN0d{i3E{{tGUws8d{g4vWW2Cj9v0EwPCE}DHm;S?QI`n#Ff(oYKj=UR(o(s1fYU8p zp-(3U3kXG5D!&>#r7OIy;Bo>#pp(^DM4P@@G-9DUs7gcjq@zg4S6mRqCcZ5%ypOn~ zgNr_M3f2za&v#c!EXb}ScEIRJ+dN|K(v{pGn=cM$f$zw4C4`rZfmAWz&?2_cIz79wA9NejM9>EFXpNk68&sXVf`_f(7nDi)MAi!?LK)RR^C-SAG8rS zV5j%V@xJ_uKr0fz7(NM0c@+FMf?uO$Ko+8LAg$XgCp8DZT$DP`E7J{!M!6zMF2GND z<(DzN;&7r{{GPngq{}8=XwjhaI`+%0$bW!EPRuJDJ>FO(ZPlkj!sm@aE?O&pRZOXExS-_(bU;ImJwChX$!7RKim>uuNWL z!n3g#a~AMoz}J=W86YnSr-ud90)Dwn-iQ8)!-+lza0fhJ&tW^}y=b!54keH6ZeaU# zD`=vFrgM@0Ou4>iOS1CxR0DtqRLGC`%0YbHfJ+s8k<0ny!eRDw1vUy%rKRb*px&U5 zu=i)Cw4jYsO3G>I5jma+bBvN^9g+F<6K?B9N9jn4VTX>$A-?H}u^aI3j>yAJc$%TH z47kq^Jt{v*e2EVvVuy~(=_Z}UpesiDz8}j^oA5Mfst9~3edWjUkvrkVkaxo;a-Yct zUy~m4X?_SEtEp092J@ctN%eNd>l)cgw#|&^Pkf$RFJGMg5)iyDSKLD%^b`TM#Dcz1vY9O6KQw*z)^E zUKoI`3F97O!&vWS4d3V+biC@&*_}mJ8J^DGao@_HTmAYWD}38ZKb!0Sz5E(&E}Z&a zjz($nDM<}%vx1UjWajQc6`8B5(Th~%~HN0IQR$3U1gYYEp-M0MMG5TF37|}{mBHn9#iQUA| zw7@?+?=Em`drzCZ_#c*?qE*P-z@2HO3>H5Rz|m=d(o-zQ%eVlg2(?y4dT|-0a^xb| zP-}&sp%Pro?d*+ht#r3odU>bZr9_Dl_ah};uoV5<^L#Sfhk!!bob)v%zpir3PM9c!z^;Bl?3a$i;{ z{F6#Q!=}q6JQ1y+^g@1fZH72lyOL(p`atm)aEMsY_O84u{zAPK*77ZU32LFK6@`Pe zj|y9A-P4lR-gO5B^p(wgW;X!U9a9~aduG1kD!_HRFHZ8$D)_DF6 ztM=Zqdz7xtOqne(Azl_|g!fvg@}wUSyygpmpb^xa6v47OD!Y8)lv%MW!aKB+@TG2Dc8XZKlt@UBFNW2MkN>t$Y<;Yt=pD%Wlzy ztMF*@fW2LQV!kynp{x*vDX^v z_{VKqp^?%Rgsb>XZG{?bH9{d@#&0?(Al$`JymsFo{t(1~D_ z=T^3ee*vSu$x5X4W*wW7tUTGuAj}29>13s=I}Nrr101daL3*QHYLUyiA^JqTx+V4F z;U!Z*cLv?VuRb}Ejw``v=rASZ5hFdpGLU}rU_Je3MtV2WAG;$x<%RT`-yk${&{YEe zn-71&yP@FS!<3#8QD8s{?v7`kL1d&-?pOY0YSvCgqJhm~W0yxN zy?o)M@m#=TM=5i~awuriC?zQb`Ck{?lu$2EiK#pe5M3Lk3=>a4n?pw{VJ4RvOp=Iz z@}E6g8DfcVrq3+Ql*K6B;c0q2xnKQ-^=tJeRO-teO~`xZ0R?do&fKVD-Nz~qiWcOP zHC9OqtFL3UBX%BaQ?Z9g8!Z+16ARI3#wyY2cfe~4U>@jR!?7zd4cSrj8hWR|(P$Wr zJV>#{p!LI4nDCQ8OYSjf-HkLf@pmJind6kmu|9CFkV2c5jK(_@=_pbTdbq}Pgs%ke zOlX&QBW%X{k3mDSqqUai7QphxVTi@M6J?^s4y7qhvwQQ#D_bpDK8SQ6YSZl63QX}| zYRG)3v)D+G^#f&}O6o)ny(@g0DRKA93e7x+xzX97=0U{qsf=?E`UhByM7 z2K--u|NaiV1Ng(;JSkIvp9Fkg^plMYXaK5Bg#chM4g?Q?fK+Z~K={g3J6kqU*%xlW zYoKmEq9Wa4R7E?aW7Xd-2o5q+niQ0B@g!xenX(Wm&r;>5L+>zf3>o;0U&kfgnDs$r zE!syZ1t+AuIVB2LnPz9(9#qoJDkV70y^8@4pR9z18ZwdQ9mEyw>Lub@_3q*>Y{6tj zK|jY!Ln(P_p$-}%uVJqDv)CbeI;cxfYV>oBbX3=3x}7iN+M)mQ@&#cDHSZzR8>r=tctVZHT@;H!g^h3Av zqjab}Tqornexv+mtsQ+xsT2F6>3bhmrigD$0Aad2g66>B^9%Hijo}hl%+9J^78sR@7h$wZs~sW*E)Xr%A;Stinih-Xb!;W zh9n);(w&f`)G%E2Rk~S!0sl1RVX+l5nwqW*yZ8F_IyjUa)OXl0YbUo|;UQ;2s$h#x z#XZL>*D*>wEo{flg?iTJ?9z_xe7e%3{XYPv^BLM^Gq=}HgB2UUV^MprGec=(34IPU zUa*jk2=z4m%*CjeZbN6EsZ4GTea$J1^j2mnk6Og`pmfYo;v7M4A%C&8gGP1RY>u!# zdkBU)y!WjhwLiVN&^EHV6M+Y^F_JewIVT%5rMZC8nHCVG)lIur7Jx=&4 z|A1wOC^+{&F~Ira=t378I#cOPCcSGyq*gX^&H#MOy^U>+El&_4z9e%tgKt-ZMktHq z-(0D|yRFQj(NXR1crQb^A36ZS5Sd?49jSeb_se*%Mm!q|Q;H^*FQhv(Y8qtrwj>At z!VqsJkq(XhW2Q2g3$gIug&-~1%KB)+L({LD!W_D8S-1w*)2hX0(fKHt3Fi#0U9?}3 z5f?1Ct48B17sl09yJ8A+wu?q5xVkW1H1dd_LJKm|uyu{D;WhYZ?oep>emqIL-Js?F zsNuTg`hWclyMZ}F!&QwMzBPZ))I!#5 zP3@-DVl8zJ1L`-Jsnaq$sT=hOAtn2f!R{xN&ep4S?6~o~Y&-*J>F`)QF-OfW=q}W! zmvv=R@EcR<{DKUtM%%qP)m>TcETw1Yc`%_C&g(2g&g8}^>D#>+>Xp8AB!ZfyQ+C7$NSv{jIahOisNVjA)|Gh3M( z@C{aaZyrsm-wM}?DRY$GfqjqxoioECt_WozjLpFsp~tUv-r6||yanoz@bX-xxA;0< z9P_Y0u>GexHf|ou_+uTLKTmnW?*~*nYa=fRVH@Wu&Dr&N%0uG%t99Oq^OY!T&_`Hi zm7zbRwOu5};9~4gu3e~%2|NM>9iI@Q62J=!l@39bKGZoFZ8CreU8F1zpdO6csO#}0 zwrPfb(S zc;HE85haL~l+Z25t}0RJPp_mNr`F_7E=Z4{xh6?*>{pM#&6wK^mlYf>YXGj z11v$LHqvJ{Hd(Bg3s!<~lcG#$R5T%Iolp#fs483B&{U~S9>zZ{Olow#segZXXnSEH zI{isQ9}pJO&K%za_(1;zG4(fekU@h;>U+uTf~tJeBqQeKMNlfqSi4La(}=J`czuhb zFLOVoBdSPPI;Km9u#}?M7eS{#MFv7#t_-2cs@>C5`xo?r>w9q|lNIt(cqsF55*1yQ zUENpv8)&SM(+2Mcn00;;%1GVKx6n|zt(Eq}oLz#W%Y=TK<0c#~P^R;2!n0DaS9@A1wFCoSfj`oYmbZ?+RKD)ycwNw_*fbj@eu*5ah2$jpw~Ny1-kK^zOrQ91_#Mge&R-2U!^ zKnQHXKa^lLK1XRGp1g!HI!Adp_UaXM1W;cAMtExr_)+2cAciNpU-l`|Q#}%2vQBql z9IMSymWrPuQQ+C7otT`fv=>)^*ScKg1$1*&X)r@--jxs`c7^gjm6e+U;6<3H6a#)^ zh0?i?0naUn(`bW`LMJ9;r~2#q21Y(G=n)#zRglpk-RPCN?zl)W^>m~men(gG`4FeK z0GZEyTeYf8_TJqy|AE0rG1vRVl?NnA~=_)_aH%)UzL=*w{8 zYDF~*SOar51v;}@Niw;V18xYUb?JeF;D6&XZA}xGa;U=Oa$!wVu?hhFG&%ll{0xX~%xJD79f+!4-XNqirtrOE)=xYA6%45E8>SKyg z-DjTVYXM!ipeNyK0e9pnyUaQyJ{3?_Wnr9_*#~!8t~anU)Zu4_t_dFrez`~|KBvT+ z`P3MNqWnic$G4_Rscs2Q`G}y;dQMpcdJcCP`BR;X&nv4;cs64oXiV{t;8;F}*bL-$EnkVI-jLSwHO>LJIv!F||Ff_@LWr2X^H#&8j}4p!my>B9 zxE5pKIjk?gtj2obW<$SE47@#?@S%e zERD%Q)GH!LD{mq=NCfo_{ZOf;xWdoz*);>$F-?ga1sH{z|FWpRX1m(3m*)Ae!T``W zmd3S5AkJWC{bbz4rUfj58kELY_t)qc>vOzQg_o0oKyAfo@!tL~Dm^XY(TjC#<~m&! zy!(J+X>_ZFV#(2-){cXIZNNpqU>?y6g9GQ33%tvy1lmF&x;~(z8yc9B=w@W#i$P1< zGCxBFQJ^6YKy*8eG_;%(Gg9MO(0b)%)28f5d=~wYm=@0ttXJM4OCSM}F_T_W2BsLl ziH;c5A`{wv-usK*CNQLMdcvEQLSb@t0#EBnQ%DmJA({BHqKFn~By!mSX#5^(W#WxZ;38xe2B=k=i z;68N|ALBS5dlTH-y+D~|8DeGt<`h)7)-zD+f~{gW1EqZM69p#1>hpVA>;{+IwLlM4 zRQM!4LrQuAe!NhLOZ@KJIv&ojpfwii{=&kJsALObSYfu3-yRLgA6qFn-#vK)%znk+ zP5hye|?E?KlzTR!yl%&Q|lB0%M${TO$i#rlD7o~P=R~|7-o$aHIwLb7P zqrjx48{7G4#)WkOZp9zLvr2B~yRAfdMtuDoPCj<ne@kf-u-RBs0vuqR z_=Y0l>r73;#?TRda$jtusPQS&+MUYuAQMrJUWXcFMnNL;-=!R|v|^RJlr2F=zTpfT zot!H0d)aQRFPGP1NxfV7q>+OQCE<;(Akmvwsw7y#V?mqR*;(K74jxhXedcZDEAjoa zb?m@9%0lstvvuCsJxW(gBe!g`30DvD&U{x{+Jq_e!Cc;}q*1xFOp^otOXBJ@MWK5hpP zbKV}LWsjUSAOpKeX>06xHtZ&C_u*s(H%HANzTx@#1$}9=4$T2&zAZN@^Xd<=Y1kh{ z+x8*OKi~GDNJq8~$m2MOwX7)*37TWbGwmRZ!z@9gpl1hpPajlXq$b8Qt0Akwc!3gl zmz61qO4{%*919BS4b#$wVmcEP{mFT~^O}nea3^p%n94wNRfRQ!v9A|`=?=wN zY#+U@a4xlB!&3LvG{Q z*FJ>hRw%tNnqJXoKp`dNc6`*>$WuXnWtc+kCOp1SO7hfXH{ll&9y6#?!XxA(;Vnf? z_$LT|y`dizd?g3=PI!Ao6F!ab*Bbi8zC#3&I)Te-X%ygLBKWnT-$BB6)A8kQ3!7G{ zL^rD1m}=z~4PhH9l|oUguJaB(tfccXmef>}-iGb?NEy`)<2C)pWLQ)G(!gj2T77y` z7_H8VkOSddf|Z3IQDQA^*ytmCRl>p9xaA-n;nQaRyG9V%jw4F~;3GcO&*!Q0u!BAwJ!>)e zWC4yzf!^|{e?k>h77WogW5FVyZ(#30b_@+1p9}iqpX%quCZ7t>X8?ZVQ$7*nbcNJw zBOiiKJEpvdk(a~MNKR_m#2@l@1%E!U@Nmh8`Jm#PSNG50B4tbzDeq&S=|@hKw+pklv@IKU?Z8Txv1Epr9J9qhmOOqVkZX%l@#S#w8D>uv4|?= z9j<0fMrzPSb1|LGSZ$T!5+lCGLG}q{EE+*o83^e3g$Qb$&A1yR!bzr7e#^^JGVq^u zY{Lm-S?fb9y1?v&@~oLjp-(1RCzVG~PR={m+00ve5}AhYg^1)l#y@?4E11`?j-os4 z>KKDPBgsmlOm^a{SrKdGC4B(%UVFA9}O+gN6_2@c{P2Ybi z54P<8_d15}uh+lJvO7E(>OK5VWxPc!1~&8z4oqIdOX3-2f};R=FAag4md%CkE2t#> z9$bt;Aj@LxC(=A3bB>GcK7)nzuCK7>Jp;$Jjd%&DR_viK;f3nV_s}OFFn6`GUF?Yr zE>|nd#bIC7dFR(CzqPcUtYfn;C`t6(eF6Kkct%`=ik6I4y6(maq7 z1(v@m`jt>*{@mv3S+Nxmd+|-8MKFT-tyIn8HwmfP#Xz--w?}JL@ox?bTWx91wgssZ z@wgGB(q2kc+W~^s#!omg%+Hx{9`LMSbtWF)1*StB$)DBie%(>7`J>Jr$rKjT@WI-oZ8KNpd zYeBFTQvbNpRlo2Zq5h-)OJd_f)!yQoPwKq6p=w2EYgru|5wAvxeuwLDVOPCdY~EU^ zn(n!atxix8RlEYnet4PUt*8q{1nFqn(Y0f{vItbkp1U+h3rk+MoN@hVd0pt8@RhB_ zyh4P7C<9Kw(~iFn=^dwepsjzu9A-RFT^jxYgrErWskA4Ay$~G9p?2GqoIMDu9jGoJ zw+dam*_TF zYR?u!jUut}?=1~x)rqPt{G}v4JlnfD9WinSm#m8y)_VXG7T_-BAT>T7@O;3qadqV! zPIAc9>_Q7IX`bgKojKR}{;B2quEHyGHLmWP2fY8;qWw2?m8uf=6*vt$bceC$| z3_9Ib0?J@$QwFyF+KT^>0efnQ+BOnJ+Jg&yX|00t(qRC}xIeS9jdTAui1;@Hu$d_C z?jdTY5a_bX)MHH?*JG9N7CSpc?H>j${0ktQXjW0xlvCBf7(E z??j@TEzY%SD{+7EYnS>0#UGoUq<$zq0z->&tB;BYVTpNeH9?&DA-W{Ds)=_4H8oj% zNo!_bI^fq4EfwS(go6t#VEI83H}NkTt-x^f7OhwV!SoEx>@>W`D| zbFJ8pVQSAX2Ev!|=O>7*s-c9p!os*ELh{n`w9;Kuh`4`YtDsYeQMhQ+O2OI z*z>^QXq-HXuVicewSu`~ec6xwwO@hD2k!VTcfBx6WU(XE$(=EaC~ye-ui|)!4w>yj zkcQ8?o?KBCqumRo7mrXM>5R_B^IYfacA>LYlql>kf)_G{uixC}UhQtsgx|0Bp-cJS zqKBsaO@wH`*|At6oOjjR(LJ0+u$)@4dC4cOgy8RB3!Xngi?g5LhFsyqO3?bj*05;} z9y!xBkJwW z@W#T={BMQ7gZAk^Q+V($=rKYs{G?I;qwqShcf%+(%pyWdtZJ;8Rop@Q7PiR$ z!*FnWk!*AqOTZUX{zUO@PFDM%`mp%Yet3mXR{QvSY1$eZ&757Ix|eO9tVUsg&R?I? zS*yg;>hYXRE5m2pC##(&xHi!r}a~ePK%b!%%i7%LF&e#tlCb{R8;XT;d zS)+&?6#S6~e#AXnTGJ36#b~e#5p3cVwQD$nt6U+5mNI?TJ8~M$s)I|M5OduWK5NJ? zM)c1*Yy!@BeExuQ&Q9#;6!j+()@IBm&e8%M7if+>q;?Hlj9!+4%}^Y;bS#G(9#UT> z{~Y$Px(YjtJW(1pV`-;0!xh23R9`!+Z;E~iiE-xHNJ9tXxuD7Hi?F8#&F7#YyWIM* zlg)laUFrAAd*mB+d0{YXF;%sbTzHg@p($3GmK<9|Ju()HYa!1ky!zT30Oz`Y328^utCd_ym^}rdhSYfH^~i ze!C1x1+Wi-G>!QtVSB0)`G!ve z0yP7#yr$3JPDibbo~HH=8U|CO?T;d)q_Vl3Hnw(}+AhK@LOIw#eC_aP-0gv+n2)C{ zKKKQ<≶h=CNrNK%9@mo*n$2%5OBlWihOzJ-GKxMaO;4PiIdyOtbMXiO>&@ zQS}Xz1YyO=Q6OBFs%{YcfF9yy!cRV2|4cd1-1?0PO+tTFJJtLusnL??3j{ zG1@Ph5B)WW!3e(WZM^EJ6Ok>Oq3+~I zCfqc@k`TqPfGIQ8-l39FVA|U1feTSo=o%Dn(@gb=@V#J1+pk-~TO{mp_-RwYdT)|V z`-jKI9FMDGVt2Wox?>mN&7RW+%fh&7jmr01oSk{2WxDZT7F(fPDD-1Kf@wnQJdIrZ6>PSB_e74{T z%ot(#PpHw>J=lDBLhTw*2*kgz#IY6F*mqB;E5)VAbN(!~bL2a9_<9#Y9DfowfDRXF zE8on5L~x*`?4G6C14y>E{?7WOBHV+Sg@s-cI3&(iCtJZ`-E8%VEJ~UJ>G+bq$i_Q} zMV}@P$ollY0j)rcHDz=hIMAM17*s)ip9d^L9N*sVhRI`7zI+lon8v9c93AMI!-~L4+DtJcRuY;5z_Mr#mJC z!c%YHouj&9P9g`A@(MOWe#PpOE+u`01ZdJ#R4P}2UaF5l=a{R$Itb#4r1`=!*P&5OQ2W8Fvk zCIi2h3|-%`tIu>sva9peQ8=Ec`T&22@S)m66NUOm9CqyxzJU3<7^xk-)xb4oyIbhD z2OqGdr8Q~lUSuZV%LF7r4Z5!$_-$(@#8K4{-h!J84#432Os7X2mRMm&xQXzRPJpKd z3UTj>qE;}`SVVV-q)L8NvGFsgi_#jwC>YithfJm4N2f}scD zw3eDMt=8a4hi=5vo*kx9edFU5llqkygf6>7`wGB<03nVHfoE=UXnzHa4v(nv309uw z(2fI^ii0o`xQkKJNTZ}SJjF$7AKHC)!nkUxas6+RIxMIGiXxTVq9;^x15dU{eJSg2 zc$o{!`5Hx`qgBc!4LM7c%Y}x1bpA*=WoJ9IMS$UKD$ZA$xqww)ZHOBW9tEh?MC4j# zWOfkG$$&3Fv!{8{510>qk68-MkG6>x?Y!v6b}UB!un~j-OH}U9NNpgu+QIrSQKLtp z()QHqQCDd&S&h5*dy6d^Z99<(-hesMwCBA_i{=%r8ky#K>~&&0iknsqx_H{%$*|ek zjwNchUci4@Vb{{J!$V#p^ocSnwioV3A#4FcKXiR4YzLeQ+O?K|H7rqINCJ#xN<&9V zqf>DKKB0<3B7A)KL148MMymt^>DPXn`tC)H8Z zi;tGnfpijOX$8Og)UMbM>rk>4VRg5}3iXE}1Qyg)TVtH{+hVD$btu8@Ana?mFDY1( z%nnFc;!H!PrzN!;ZKN-;Mlw-W=aGh}v@WBxwJ0s!s3IR6KPoL^(l3K%3LMUQ1+{5Ur?OiKdYZ>a9CWp!*HKhh?Sx8eIt@UwthFtN1Vf+rsey~0SB4Zr4e;QtQ% zR7LGfUg}g}nm*G;H5EEf(XE3Dn^e%1c@>qP`CL}8efVi9HWXD=B^7h?fr@vlD!EYV zogNB9on8juBbKR=BH(P!GPRqf6I-`TO$gYDoT+3x@H`CyGoihy&RM`y>MCSVYG$zE zDYX-=&r50N1cp=ExO0*`tlo~!z}y$xg&X;_FZO3>Kl&9jD(s7)?rz%`BmSmc5buJE z`Z}=x@_%0l{Q)h@T8>p41mK%^w+Xuj!U|2oE@~3?f6_klXM_ds0*}6N(*5cGA*@cz z=0B|q`|p|^4`HjjHflD$N!b5MJElq4Qr|tP+q4DV1-Jl3OU%$LedptU5wmGo>bz)Z zHsf(u{Tn-k;B>qv;eFz6A(%8S;QiNk@Rb|9+aGtaYgy_@@uA%~`}3&(jIiN_Y@8Zz zC%n^9MJhJ21$>jc1AY(9#(}6B`fiqze1g1eG4|eLR~Hn-HAKrE7cuhzzZmIuzTx^Juk{;gbCgY#t8hPOVbY`ORt~;!{l!k$Wmh8Vn*Tn{-i+ zgH!^BCY{^foy}gOh7G?XlU$_V3^!Q1S=#Vk1It5S5e;E)Eqha6TH{FPNfH)4zxkDb zk0J1}H7Z@JTHG~`&kD$);ekeihp4Gzlt9+wur|FvQ7 zH)6|@4}c?GR_&@|m|-;K4S7ZA>|CrTWjuJ$b#8dcG~&rpDj{1J;BP>u%#)`EXB_~S zcYLTSz{L$o4&UcVNd%WY;DXt2qohfOmbyfHQu+cv`wqO-z@O`ZZ;k+;0le33)$Ew+ zlP2u8u9_9S_buc*rJ=zubR5(X`kb1OH4KX~`jj>Fe$vr8;(9S!jPfR~uA?o`cTfsK zaTD?%4QwLr7t*^29B4|SN8QogEHDepC!M;WQ@%L2p*}Iz-1NeY8txdx`_?j@7Bjg< zS{U`+DU~3mYpp+m_&lrmWdWjOJf}_)$04H;&#O@}AMdE+9|Kv{cu%RCX8Qy@U1_;LY+9 zo@Ov^DsN^I!jXW0JWTid2xN9Eo3TeS7I+HbdK+FB7#9Q7SH;&LX?VVx5EBRm)nYV1@=KkVodriRThM9)Q$vaxE)flj;J?@2kZPcJ*#3D-5@sA$wq zGKYIo_5lAqrn=-DZq_2voQ0qnq(AT|0S%6YL;qHS$(g49y_>iOw+VB{jrX4&vtqzilt6 z6z}9V`drYTxdR>vxkb>2zN~JSR_tx#xJuNv>!u;1OUsxL$vIhRu^{JBxJhv$1zUIgcY_wGGL_H`{BWI@#N!~2t#;N*wt2U|k zSp!{IW>JqEj~>8&-!K+fgbm&{oZK9uD&B03-xG`A_+!})2d*OZ8%y}Ot$LQYcJ!`@ z8}&Bo)xalxe0!F)S~NQU6+A?j5`dBe?h`St%TmGFornm_5Q%I?pxJPG3$!4F#u(g zXPtoPq-XFOGui0sA6o6FOYy`c01TcfhJ)Ky^?Cns6XEAW>{D_4(lHF-3UJwTC_V<7 ziaWbDKcTJ1D(okmc?=U4CItJ2Go`U(5_r&j*^|?mjozhpw&FQ^m)c3pDa293E{wSU zD#A(>m~H@&e$99b*5hn%I1I0Ob z&X)#hb3x-5gm!Jv(7^h<4-NGX#h^*Xu0;JVoe%BLlAQSl9UXm$IXyJ?f2Hcq9)>#T zqgX2q0ve%74aFXW^o1Mshs20!`9KVW}4a4|Zmc8rB@?C{4p2bzoVs-r&o3%DWg~FtevUB-+BHJ)|yh zJY4s#+T79wiK!0=mKxaoAS#jgJ~Ztb*2h>7^wAPam9t7=E4`M;ZOP5B{LyeAHsJjn7>$y{3cWeaR)qQFo^#8Zf zxpR83{$BV99)NT+z1YX!1XnFDc5$9Atn=>hs*C)5lTb}MkR40v;qvr(Oa;K zOdoTW#5eg(9#$nw^*UAG{&*1N8|pqM**({X=zCv%6oXT-%piMe6m0t>9;ZJU0vKtpYjLLd1YdH4-zc zMmR}P2`T6*+2j%~1%2QCp3lH%Vx>A6#cZUt!iFkyd$0qQ@C%!^k;K%$mqlKGv~N8b zV(OJ_EvbMI*DBR_uxG{@WFQmT)~bOp>8J`nOdhVG8UM0fpFqq(hE#yzi{TcAv}X>h zbP0^7r8HCkR397q5vt{`jp*4vQopoff?7(cYMedTxR2GjSr$}OYIQ?D3`UJft$Oun zo5%AQNGX@!Y+%1Z(>Ugc{yUzq@kZJrqn%`8MoQwI11*Vp33M2d8|f+_k{i~PIZ~(l zyH3XvKT+>a@uef3q22k7)${%WbYFoNI)X-ClxHz$Rv0uNfu;&HXhWQa+S!IrF!I-+ zl8=7^pT3Xqvi4Ke)#4&*feeS0J-5sjWHQZ0fsIaq1sqe8bS-rxEqSLLQ-8Ad!F+`5 zkP{ju-u$4x%lg7LiY68k-CpkW#Ghabkr%RsLpT{EOXPv6L! z8b&SB9{)mJgeXxQP6xV?aPfE7#Asd67AGJb%kQ+jqy136@FODZP0I771a$@|58sQ` zCRXR_FCh1Tz5%8;3m_pdWIO2r5G$0us?lfaqpBlk7 zolr;m+b|Iogd}$P1gfU}8(2kNUfzxkIH|S?zZ<`3+%R?Ff*yE#ua03ECvo!Y1he!c ziyp)q43C{u=Q>WJR#VfR^;PuDv1o_e2JzgiI)S+ zs$0zURoLIDL>-y&eF9Q?)F*pNS?+BaZ2MOwbD%nSolrRSVbqD513g8{VY_xgO(5+f zemEpy)Tb-y>yoK-1c@iE02`&Jye2;JZ=$N84%eE>uAbt{N*s^Ei;;O#bE>+_j4R@h z0lDfghN0D&4jI%?75=+qx54fg(dsL2^fx85vp4uhfc2&}u#HJIogI6-rh}D%>KZ?s za^O^eo9DhM8DY5BF9NId1vW&S2UWu=zld`18jpxu{!_Bbu+$e(1~SEnXaj?%{sVhl z&?f&_kM3?k%mDvuNekC{npk zwwAn#r9wCLfz53tYH2(^>~H6K9)3~?LtA!R0gr!52tyZj3xHdm7Q#$`O@LSYLkI)@ z1-sGak-hjAtbjAT_!k7gpLy{wm;l?o_-=b)u4ko2A8;b@dA_^y278ui5xep{Mnuqc zNIY|VcUSzr3v*q^PM6Hk8CLj2M>m5|MYpx2vGniZpRw|W2(dMdReWEvKJ*@61R0l2 zEorWhGbOWwGS~V{mom`NLwGfD#1Qhk*Eb^|@k z2`WIZ>9>+BeR6eR^gDl{Q8cNGqn>ch@f2Ec{QM??o^NkUD{X>9-RP{KnXq2s@M_u7aH zLLljgpe9}_Spap(bE!ar<(IhW#lH!UO5KL=W0y*-TInd9xT!&S>}6~!KY~gvz03_p zp0LrE0U?~ZT#}OE%YcWYc=qNr{tQGEnCTA@(9lX#{s-YyME_1SpyN5Ri7mQPV)Ey1 z^OcfDF$}rQ^ps4}*fCLVTzjLuo|3r!zT9{?*hEWF-$o_9xP#_dro{EpPd&J*%K)lZ zk_Mqsn?T*F1A+DoM_VP|H-NolT@}Qp|54IgD*(p@P7O%rpne}AT+sM8>hLbmqj-`S z)zg+gN=Ar3qn?ia!54@A&I|;aNc30#7BwZL24hFK{c6d-{L4li)P|m${wIbu{Sy%N zUnN%h#~HLJ_RU`bkm^-_^|{&DPm>80Ow;wl7f4v-!R9*)#o^(Gb@D6R5-l$%^EP`aekZvslN zG@kyC2TRN7e@qwYPI38T?XKql1c=iSWauF!8w}96G)dGx z{YX1o*hh-dKMYa!krsyyfcdC*v00q^~~I`EQ}R~O99g$Y)oW@+O4he{E*fra8U_Q95MmvG$S47FH#%+PsJ%znyuy-I_8d5swF}gbQ@LpPk;?DChuLKnt*@v-UpgOLN~39SA~Xn^)gON#^Kv$?me+S9_y9^@!`msSYHp3 zp6@GJN(q}VDFrPYc;d;2SYL}B6-HIG+B~s76KDQM5?=nq`W;9}3(gI=%LHAj?tWfJ zk+t0r-i!<=H=2v)piVNO5VpdhG}G)m%2jtq7=O3EUd*6IwF8I3+wg2u2sT3SHcHaT5{K8x`L>Cwt`*B8-Jpg!bg z7&^_^&MRxl!293Q?ZGw#EW*``lVhYI;)9Tg6eINuDd!F^I9TjRWIJP|#UXpS11|PH zi^j6hSn2kVeZGJq1gwjdMu{@g9*6}4dm#3+u~Krh0IQJR4<)xBa-t<2MecVv7|YU) zQbNcr$QuhH1y{<)vV}$|IRt`qyLOsAYaqNWMyV)**nI*yEdy36evj)i)#F9IScnNs zK7@!R2>hWTiKUyQa6=xj-@`DGfWV{1Otouce|C#WqI*8w@d$fBh+(BBDLH-$5PuMp zV)mn$n{`W{eW^xNVUVg(0m2NrO8ijSSl2O=RId|l4`SIoUV6H;07?D{^p&791HW7K znd|emF#{4Vg?%l4ghG z_#!G0urEovvy+`NKX#G^N#l4;5<3*(V~4F9B(3VqpCYvU2ln^o|Go42{I$fCe{Av% z`Ijb31?V?*CZoW*QMH%jvRLpC zDLHf&S{7JzljT=s&SDdWNK8JvVrs}@@oCbbU~1%aU*5NA(tyx@VBfn?j5!)k$%dp$t#n%Ud^$A5 zq>6S|>QJdl7jbuY;lkd=L2BGr8?H123A5e`5b8dTH?p>25^deO`vmm}`578|qP}-X zqdl8NXGq+m@(4uL(wxomGo)pxJonF*Y?muT>a9;&4vI%#9?<(9P(AY1iYpCJ*67`J zKcH7biMW4&%V3#lBs)J`qFVsnM5ze3a@7jB7R@GnLRRKql4UPk)>JYACIV-WC7WfB z_&aA4a<-3CSig~_gv4+l13+LVa+4eYUDc+ zd6KQt1Dj81863aJh?~)}Br7}(>(J(SSYzQRwc2P@D+1sqzR7!`&f~aSF!NGGHu@OH zX=xtClCq_=ETo&zHDHyaA87i@Onj78jaIGrzQdP(3NAgl4Qa`!+0itbZOWFGk$NOt zOEWH}%9b+nd`+Rqci5u2;~M9;9XGHT+S9YqjX8dqd5ju|UDPkN_+L9_bv86yEVXVV zAO1M5&NPBil=!zJCAy)}ORH)u>li6zO!dWAp&7=ZPAYx0Z~m@h)&exgsXqKh z-8eNaz)|oIE$^Q?X1xj-%tidEI3o=-D2dOoE+NMp0d%;^dkOXo#I?e0+Y~pR9T+V=LFFKY zRnahkO&%j{=n0xS)Z4;0gjJWThq5omU}Suz9M`dqm7WCQIzqN!R?><>+Hu2Cz<8{S z0lu=SgD>2z0PfMT(&)Ze_a}v*^*!2ZG@(aDjFV!}Se&PO3kRD}U}`jt4nf6`-e?-_S)eL1z$4Lt&fjKgEsINbG?HXH-+nGXe^#FC0MS-+Ogo8^u zJ>1KpQi%3@NP9Q#S7^sQ3seE0aRI}J+oETomSJT_j0{@6-(9;6^Sf= zyfnVAFR!9vZ-q`qe&fOa_VH3iCm(2NIS4Prk&MDXZ+UJ4P2xjm(Q!U^Zp0ViiE3i827UCv!`}W$ zms3F_dc_N^xX>#7OjUTW&3n^}*FzGH=}^FSn`9BkY`_G{CdH9PK4ybLuW`T>wn?)M z7Q_ffood3b9M>WCL&U-y%!C90O*zuI?iWhi;lPE>Y1j+Q7`NWUhU7{%@lzCOb*}U^ zcZ1|+slboZ&CipHDVxK2Qi8Z$!MrLDN(;=<7BpuNZL1gv@%hqdLR^?HtrZsn@r!&Z zk*HB4qz2fG$dH@7)K=UC!*Phx?%H{i6hz*WydUUjyrdPH2EDones*LZxE}6c#9;x!-k@ivCQ31Be&NMPTZ6O#zO>ay`wh~P?(z0By(?*w^pa>rUlJUmN=n;I zaI+t54EQ^|&<}3#gM~m>#8jz87hSEiM^KBg#Q3%beDl^F5P)I2WHMaA7(+HJjlq}D z#RN3t{OQsO8sMU5NV(B}me5$~dq=@1Dgk#8bdz9K13?@LQcW{36q+Efjv3NkUGxT| z`3(f=7DsyDLBPbebRJ&x?$v`e&6FMxpOD+xr|zIl}`MTU?>@q!)GK`up42;rY^(h-Z)^s(@>tGKfD8 zYgu+&s1$#jGzV(T$;FHBirc{GC`xskG%;dz|RuS1ZFE(SxVv3Q_Lr^YZ(a+)!F zKLU6r;6i=8O4sQu0NhX!r@m2&4|G(gV2o4i0rS!~nABGR^U^m%n*v4?brwRi)&b_F zcSNW!0_LS}h*9a49$xz9zUp&;dFd;|)m?zSrH@ss0Q1tDVpMv~X%c9bnyUt=+ws9m zuN$C}Um`EPrN6ojFfV;swE84qZ|S2{dQOX%z9>qiQG=JhxS#q6U|xE>SMnfWUi$J# zl^hay>5KcS4#2$hwr~|sK$Ut+-yEivAcB`3FORGP%uC;3P}czVmfoPQ0?bQa*hjqw zFfYB(M_mqh55}1Wb652az`XQ@z178ldFdN_sl|YK>2LkFt^w#cbK44z@>JT*tFfV;; zH`M}|m)_n@9S_(XM0MZL)z!8{;u|GgqnI!;qJ>?1;Sk2|l>PB^|8U zJk2GQNI#0=rWNh3r5mJYb$u}cj*5hF<3~!YNMq3s>D_MKN$bN|8{T_o9a748-)Ko$ zTA_z4DzJftQx^X&;aT>19mh_#!V{bfr)F!qIs&8gRm^Jt31jcm71#zSlb+IOnlQBd zRwfMz3HgEN0@Dm*OX}lNF{$1jt>DOe~d6Tl;m54^Hoz=yOINW=V)ifOPyW&y~|a~~JdiA}&6?2iLN6(Dr_G8~Y6IOV`W&3Bf# z6-?Jq!GLoHI8?Cpz`;KYRi$B}%@(1q(+@yMa!pgES}sQtjn~C3jRkL!rlQqwszqqS z<@iw%7WFABxY?U?!MmVJahf*-O0xq#m1U_S}WAkHE)EPv?5>0a{*U5PV0hBy#qWu)6AZs2qShfGK}iIC_}|~v!|__ zr{mBy6#BC*quAA_q*(A%=;P;3M3HPJuj-{P2R}60lAIogEbjKvbmLGBWad5&*{tx< ztUwrCy)R@tN2%)|pK`0&^9s_w4<1t>;~K!aNWlXfcii*`Z2S(X z?@euBq3FVR^~-;Qh92iYFwrc;!sY`&rpLqzp=TWUE~D?Bf~OSsP!^(QC`_iXz6guL zrCIK^_eMT7K@MQA?U1?~Rv^mXx>}C!FLuDRJ+;((H|7C4U!zA2gH8b=$2@~Qrq(;4 z-Jg+e72^?d`58>4x&fH~tklnN4C%-SHzJ)7>^N~0-w!mrT73NB>EopbvR7v@I1e~pr`i0{D0w>*mh8+Yo z?w9c{!!GGgUBpS)uKsf_nncpPYs+ql-)ivsZdmx=EXK9jyQKl~zgYw)jYfs~T-@F$ z9IUDlFe47D9ev8{G>&i zPvu`7ho~L5fOaJmgSJH#C*-n+K&up$sFzE&EHbC44ne<(l!Pu!n1M#%G~qy>AmnN}k&FCvbFSQ!l$1L76JCtj5So#G! zZe5{Jzf?fKTWMuAuSp3@wZJ9bKu!x>dhm3BV9#~z^`OD<)= zt3W)cdp06%{SA0G;IQ<1F9&tHn|vJ1&1duLr37M&2XYP&xVau96~g{&ZlC7x+%_RM zjH7&ag-hvRo@Z_T{|)=&u%~@ypjI}Z^!j`Zefkt zGv#_b9@h9@@CN1!rT(Skh!0q!2 zIfql)Z|8XGt|#IaaQR(dPUAZKI)U(UPu;HT@#_TKLD$U>zqC_Kz6?rkOn?mDxt<{> z#Ol;CxaWF&CuLCo-|)@2$qd!txE{Z>PQdMJ-~X=!vcrUZeY_F}%FZIM;&!bbAo9B7p`a)4-*AjSs&%Lf) zbA0pl_}*H47*{-Yw|RoErw@k-o9AxedzTQ|Q*TLgcuNu1(Fo5BN=_&!@I#!pCF~ z;2EOf&(#tD?x`gJ{IZrI;0gX2K4xXn?@P9XFg5oR*n*G-nL~w`-uZ+u z67xpbj=Yk4Sv?=m^;I(9jkozK8E}%9-8vKCL$FnN@t(JNj(G8%R>1cIzte63-Xfc~ zs|a|lm0YiAP4+P`vHBQaec)v&gCWJs;>c#MW73qQoeQp?I&25C{-@ozj1T6s)DNZE z5wF73rx&naaN~$8JioB>(&tFuT*f|>rUY}$tu}V{Lup7neK^o2Oj~W9J-~KgVq=Cy zIg4i(R$GAoF&|+b(F+XPKa%pa<&iS@PH+azc-846sb6d=Fa_9z+Q9^pUVv|UUIC=v zK9WqaHDJtsFy9jb@l*r00&YbAsRS$>%y(seEQvauo@F1$q(qqy4*>wN&jB#wHO_q- z%v)x3G|v2;sM>2C$=pGbS6 zP*#$}AyKE2+Z%1ALf@vaw=69Fgp}*usKB1iiW6`UyoLgAIw6gVrKymvQLm0U-od(R z>kYor$6H3SGbf}GIlcmT?zQ;Z0Ce=bb9{XYusqM#rvS&Io$yKk{36=MU(&z!QoCV= zC#7)x8y2?iq%HCN-D3#0GsFQ*}hr?>_mU&LI9kJ{#=C`H3it1_=R*YEwgFM zLp8=Rtl|qPF+*z_#xZIYGB|<;zY85Wd$D(~4V{{&p}17-@4VcS%muLhPJ@iQ|ozx4>$vByUoxGiB znZeC)vU|seRf(7}&C@@O)fFs@)#7M)ew0f3l*#kCe*#mAuN91i2@C>bZ zFwz!i#RD9s6%Vk>i|;l8&iz}SZWwkr-6B~+iTBP0(dJ~=%oeFgM~cpEkIeJ575J(Z z@YB!-s0z0bnTOLV&^NqZBlBFbZBo6yC)F(PfiM+|hO_U#ld^6MOZi@k^7g)qIi8Lg zzTOA;5PBl7WxzDD@)BOmVJp6uEYUohfq5Rw2iNcI{d^0Q#P?Y2`5Z-{ybT?gXTGZ9T(tnUP>jtsIKS-}asq$b;SBq!!`yK3M zd=~~|KuOGVZT?Y;(xp)V=H{kZR*w}3r1lFj%2&OA~^(=!HY9dC9$zuB~UKmAa69u-^F1W-sTl&~|B5z|=YI5l@**!d!*z z(qNqdLtx#w_nAGjFdp_UXm^GFDh<$!+rVb}Md@kr9stKKV&J(Q zKcc{PiqeX?3Oxxoqhbi7rcW z3iy#vnhm@D^h%G;h{v?BSN_u&;V*b@o=C=_-&?VjwhaHH;Dq-26=^)}Kap6f3PmP* zB)V7*gBM;R@JPu?6S0Uju&RfuAz4fTSdiVap(h?y9DJyKQ* zcWj~;(t4>Ij$dQlu`T^Ld~M(ab`ZMPxr_VV;H9#n02cZOoU(lQxbc=%{2`4G!FLq! zh*S3AA5v7;Ko#7ok@jBf{2x*^t!bD>T0A?@Q+Ti0iq-6!eZ2 z>BX(A4ZuEqXHNa9n#&Y8XIrTH+$k6g4G9vE-E=d-3c~c z#IGS3>*Yus?FeT3JES3o8OYQeC=55D)~S0;!S{JYhy$jzZ;O>5N&RCgzn7`DYALy2 zh1V|s@EU8l+A)F(M@(uvGfjno+fK@(`@ClH?89x!5V*7Q7HEYo78a|M$BDmy_k}vS zytLlpxeo}m!Bviaxj=*)a)3}zo77sdicqXp4BaS}x-kv*!MqOkA_PnMSACP?S%UN* zbB5vS1$xE!-i!1kPU4BubK8~Dr{g9Vq^CvYifcG^T&R}^Sbd0XK%fHX@mrJ(TMLMn z5O)E;U+^migAEvb7GeFdF)m150zD@d2dN3=LF}+zj?w6#hSWyTD8_Ff?2u)kbKZ{* z6?7wL5UmG6qs0`YYII^nnRciy(Egas9;i|QHp02+1Q`AU;q*=6WuP5L^szHL1@x~X z?kD`H&@}5K+HWI|qWB>7UF2aa3Q`xB1*!J}m-f$39O>ZCb8STv$i(+$A8n#rS`H(r ztr*MjxDzf531|bIi1W;Sg`><*<6&L8XN?3zaU#+X0V~BB9R+kT)el-6(oq~OF4Hr~ zClPnX7uQzkjXQ#P++$Z-@F60<^F>+^NDS2gX;A`R2nItY#5W@RPvDTGDtwaKg?ltA z5vP@g($bkQD$GV)_$DH4AH=_c=0gl$M0%n#RloFE@=&V)UXGy@o2s{Z5wH1}AS7x- zO~_~$tiE3mPYs%gQPmQ$GTz&Yy6Ar^auBmY4u7aovq7*tVaEeSwQ` zi_5~|G4)n^oKZF9VF!c;=&jv^-oM|1*OE|=)Yu<-?;4APUL_c=%xVpFK3wBs)*G`) z+iY}nQAuj6L8Pjo3zGun3~Eb@%w4#14s}xO$Y21#lfKPe_*F07=UAJbcf$xG|7lt? zCq`(d>UAQcl`JvE21ZSe?y4QGF1hgC{2nV;m$8FFMnpE^3>fFhX>d5&-J9Tfb#-?Y z4y7s^93)Q(0@LJsT^b}0=t`WHHFQ^Ju(BXInl%K;y)kGwsmeyupz-e@IjU<9^>Y-0 z291s&xur`asLzJy85>%)GK~EhEcejYbY~%5Jm7SfLht{O4=9SD&THzSj%w?{ zj&+sqffFxm-+qv3U-&~Ba8a(2P3|T?UP|1MkZF?*?sLc}JcYP?WR9@4xThIsHoTtL zRKa;ZysAnsUK8+2fwwfuT;JitqkabqfYZ~NLOH#7cv!C`dQb>QFu9~YP5D{MLII>W=1M_ijPQHi)=1V;b2;??P99N*$ZbA;=M3e>p$Lm28< zmMaHr1ssMU*8x}n?3(6nuY5%XGN;2k5TTpb0c1~Y(F8{$_?*_p;n4$XtG}b7-<#4N z#u_lhwQ|FSt_|<4UcDJ3aSwTY$X*|-rfs-BrH5=ug@*F7N}efTu??(lgi5als|Wt< zIQTqIfGe|K%wb7A z=BLFH@V&X0{A89dZ*5*$gHr4og4@{Ukif%h!*pzac%_Dq3_|Gyfsbd2KuN9!qN@$vvYt)O%T0+$9V|C)^tlYgX1zSDj%$1?@1zSQ`wfJI1vhhq;XUkeBP z7Z$)_B{~Jbm5?4EEC8pWt#irWW%G;yK5rF(e*r$1Jm9Us=aL5;2YgQFV9qSh6B;38 z++QO!FyE7`5d!?JMhI}ZMhI{(;L}zE5vGhxZmUPQEsuR0E|)`(yC0~GVoUqV#RM;M zN3r95_Gv;s&|F*1HN29ynqi6w&V|1HIaXUp>{Q1bZ^G_+A3T}O*~HM zC%**E&YMRO_|toNNIDC}i?lMv|J0^%eL5<+^kJiu@O9GWhqsfFOOAH-2w66jhOEkC6X$6!M#8j+%= z5-%0NK;1o)eH^wriVcjBSAk+@e6^Ql_FRlyfWBXcE>)+mG^&{Oxg(%Kc8EPx36rvk z&>r-31@)Npt-{t&uF=uMaOx#JRxY7a1{mDxx>gNWBat=>tv?LEQFvq^5(g)a#>xv& zvO3-?%_f|dl*dzk@xbN1&|%~T!)b_l;0$5w4v6ipDDx;B(5NfM5mmym2bo7zH5yrs zQJzZq*(*)zN-TOpymgf@e0-PirBpPVSg1)ZKwGO@RA^*NO>&|>7y8X4XV8C>Nq$6p z230UEPJXmcj@Q9P2hoyE(2DP~aq+nIpr4R|5hLMA67qJ{lOiW3f*7wKpM;Kp;nQHa3=AKK6fp^^6M>tVD#sBnW{h>e;s=R&{Dq~% z%rPFb#$3!ArBr#MI2joqP4#AcIaN+J`~z%~|1z=oFHo?=3pjNN%mKhG9W191i~9!4 z^N@{`SZeagkTl6a%-J4C;vao+@kI$Nb%>mnr+tHc!lO#2C$#BSvrn6@vF|lnzT(k| zxm}TX1PQcYoAZ3yP`sT(2f%^ZBkj=iV{>x zT8`g9%(614VK$FA=o8N(-=vx*<|JlRffH5W^od)Y3*1k@3K@skSc&-gzoct41@Ti2 zs|8^z;W?nq_2^V=ZOti+D8B z&T>-)v=t_>14HFFYS@>&)~l1xsL)GI4T%_=#FWeUkx3mq1+zdDkknNpPPgsK7PewQ zfVd2`hhTbd1x^b(%qxx8STpiz6(dq~4jeZh#@n%zr)y4P>xRjRBuI-nN&WZD!q%_A z7p#mr`|x~E!US$*)L8+avT~(YCjj06qXEjW&IGtSHo`f6bH1mah7b6-h7b5&4Ii)o ze46qSPntbYZ~y}@nd>H~CM^4_#ZSaup@F!thp@E_H3)mnX@*Z6h0RA8-9YXg#GCja z&b6^@_RRHW1(Dz@gV`5r@}q!uRD2`97^R zHKG$&W6Q^0nWFAO#pO-KH8cA`em`rt#vX*w5@FF0Q$(kwVKA#0E+uawm8i_%ycA7(*wde;Y1upaW#9N614W&RNtH7AihOEVc~cqL!y%cL1fNezOZD_zC}e&~dSX<)ned zgpTN2wPIgn$tK$aKEhQXoCd<0Ts6W?%^*zcFOWIs4tN8B*IAd%L)e&XJ^=sC5bC3% zWeAh9<$I_B4T5-En$uMglibVMd_BNP)nhUbrK({`BV}t};CZVI@7AEo==dqcm5!97 z$bz|q_$|1Q8=k~xN8p>5K|a^_P!Gi!nQNq+7KHdRBRp?M%2^m>+$5|jtd69Pl1uQ7 zD(qKlY3R=OkCGo8jr3HlwT=ur2YTW`xJqs2-=J1Qa`_=}c zov#=z4-0viE7iWWx_XOi-)K2QM=FfC*A^g5oijbBxmm>OsDb@cXU=B($I6pv?4*_m1eZ8Y9-vSE(sI26 zLm~ErPNEqVV#DSW{1Y~9?$HfAA6eR6(+yhb zh-wSaZ>sDidL4h^@asSV(?Fb)2jX_CJWSj+0iMxTc}6hBP-v1(UTbJV!Kh7Eq3c(p zP1+s9*nXSblDZvOg{8Tkh9I)x4Yl)d`}H4?y%CNlN0CT#)M!J3*K_1irFOHo3`O`~ z)XiM~5gOn7KI$5BeAzI5oaNhz9qc|VyU@Tk8~AHE99~-hxFbjy7KI8e!b^c9izx^r zFM1)!aiY(7@5I6ZeP9GmVKD^F^=; zsJMs001=;wWuBKo;DZ|&wE;H=WBwnaA>|-&p9c=9Z`x7g3xYU+yA2YeMJ@wsz~t`Q zO|9IJ>scK)gk8;*WAqyWS#+K}aS#S649ZyaUoEJnhM{UP4B!g1q>bhvb{=_Pr^Rs^jrQ;&TO~H%LrEoa>O9vzJ7~r z$*&rN?vFvsjIR7F!5Gj8-VWGbrLi&BtG_My7HDdQ-$+!sZLXXU`VOZsEU7K!` zTlJ7a9Tpo4Xpo_6T2d{6uF{3_t9q|$?_XPF3uF_Dovq=zFRXSoV3^v_iH6#hfSVS{bP)zmU*QDWH@xY}iP986u zp_Y_3Mv6|HR?us6j8+41o^hOy9vw9H-w9$3OXZPbbv9NrF2Eh4*Bx?hDau1KL7CK{ zkSm_38s0hVHV;x$5!QhBHsiSmfT6a?*iTJFm=R$Cs9Z{0W{g!$2y5|lIBlv5N!$0(el~s*VJqVj{r$OS_duqA7O=|%~$oU9zZbFT{jmg_sR1H<-K*`to$xH zO0*1zD!EIJfhKe21w*`j%_G}{(d^h=@)Gn7PJnu1H*p zfTW8EaA3U@m7g*IumQKoK}0D(cZP?jL;(KcZu!Z0P_06zveIaYihVoNYlu8Ffy5e7 zOAUfGzaT}j=6mFTh)eiHyYezZeG$?`|6+&lkyEg)*ct9)P<=bgQLxlUij*DNNheM@ z3etwOu`A@{hyvmh=3y14lB8W}YB>s-EnFcF4RD*>>1@jind#DTz*-)r3&F_f=570h z9JX|od~38{fJc4~PpfbQEN-1MyH2f=bvp6R3><^IS6(Yl25`%22o%PPW_-{jiVn^l zUoH3TI~1K1*R`I;al1qDbY&k}PMw}zT`k`ig}5NJlm>m|rlUf{WF6vK!S=nw;GDWf zj?*K4{~9@pjFe+*c=)W17A|m)Vag&P-m+Hax1?-Y3%mI{P@)9n zC#X%xwM4JB2`X{hC*;h@r z;Q1>Z&E!7W5^@0|7oa<!0?I*>)!hZ(u0`wQ+l-?5+x4y{CchIZ z-hX_(YtwV`IDV9hdJN{aEOm^1Uz!oT~&;eW@`_{S~l39k%05c}dq~ zbuj33E9=Ta-jZW={aET-a!CqM(_(}^Q;-d^b%p>Xc|+vPHe^3=!Ss`NIl8Jp0WK)( z=Q{qDYzjz4`@4{VI=cdFT8e1KoqeAp?03Mcx?5hmRz6A%st8x#IWn9@H_4mB1JtAQ zm%cVCR_OEC0HMz${45OvU5A@wy)FW2Fb}Ki5@sHSwNht5FY_qSt#f_(w)~(jFj>v1 z=*R5u%1Ql3sju8V{p2?M*5G#%zX#_od97PTSDXis@6<=qERJS$T?4$7f|cf8iKX&^iQfm}=T)>|tQTsx1+i*>?CVBLHgFq?3R3 zp=%bYtvuNkeF6+?bV#ek!KkdUq_EAO!jZ|BfQOTXhy|=1q}%i|2Y2@r&S(a{%!)C&aG)b?NO^tc=Au3ictMCY|5;#Z&qk6l9md z;R^j6jTV+0Ph4S6VbNd6*EDIhK#{kiW1!S{C;+zl&8W}SU&OW@^bNM-q_d=M5;~f zUYiJMz(*tn!`%g<@;DHeuNusb|3_ZfJ59ZC#~rVA=z1;RhkNj5=+ayhzLjs)i*JFU z?Je^Ana2T;3Ky_ULFNfP+)I6ETM%Z)ea-bpKygtYbA1`^<5~>o5o_TP##+&R)*|8I zR=Fs)5&+GIaXI@T*nzxwG~=OCG*x1)u}z*KZUoYnHhH$V2a-G6h62Nu;iy$wH968* z>}mf3Yc-9C*H6pa0&Yf9*8Kg-u;{*|8PS4Zu5cO_Urp8kwcRqGAdt~(>|)kUD@-6TWW|Dr`2x`2|N#hLb_JT4wq8PBBxs}GGJ zSdG505uFxX^m)_h-KX0BqdX*-mUVtG4`ppX%ByvFP~j)pBL0DbZ~qC)M~A|&eDsq% zb9R!t^TYnH?ZHdWyE6sPFle1J}pS+%4gvR-o=KHP_?W zC?|c7)D7YjpIuFQl@5&XWmcGBv?6G0Nl|w`*8jCDSlhv2AmE$p@Bby4#h;TC3?I>) zmYSm`^2VWT{yBL>HtM1?qL_>{Nb5AJkQo0nwu4Oo2WTFhIOULFQ^Qbp^qf2-1jC&> z0NtSt)H=?|aWrSq9|=%(*o|)!d)HFST#$=<0)b~n`cfNO$0W4V-~sQY#7RcN-*4HS$`#UM)QgL`u*AMru$! zdbm;(GqhSd7L3rM4>4kL5F?SbZNR^T{jZPxGAFyS37H2#xf88g;IsqhGebK=HDAXh zuV$>55ng3%hb#7Hxu1T_li}?VjbjC;Q4ZpV${GL*a-Q$viZ}NX7uB$g$ec0>8T>#P zDX@!Z2dghYjEE=e(_+j}jR&R- zn4$JUm=R&SMQ>OYE;I;1SmB>oW+*kkau#C6;X0KrK)5>`@8&>VvanxdQyz%Wx`AdS z9sq)=FjK8e73zzjRfs_`5DR)ML)AC>@EO5D?=;zaJNa-6y5F<8O!@`pD*o9o^0wIb zA&C?v4~N&gJ^CARejDHK2@h~$56O9K@~^TfVgyn?b*1!4vM$MhCQrI5P^kD-o=23v z{Z&p%2vtu#2oKC>13k1JCcs|=N|e`4nQzg-R+WLb9pq$j3%I-GH#r8Y64xQbS7oRH zxRUp>7?fg*>0q>n7l*vfJG^&7(4yzU9f2NGT`1fCo4hK&OD|f}!S#$N`dYjOi@Q8d#E7 z3G5*c1`xga(w%p__N~x!`7sP2D|C9-Wsm%$P8^IPU;s&AUH+8c$j`+W?H3h(C}FovR8z`C73$i(AATz+uX`%&>s`1Ld(TW!{lOTZ-c=>C&;VrvB!?aV zKT2}|V*$!CI%)fdUZCyM6xU(w6JsOG5UAYOiKi3UmO$l+ZhY|rUgWreH8n^n=!~xp zU=IZ;;}bdE{hN#%H;Q?_ejCEDAf=~duNByJ^ z8H>&ZW%?i{c2l0!1YywyvwhuAI7~$PLxpWKWwGPkc;R^AtB^i5L|H<#ipmlh3sGV; z+|Ph}I7C@Sab>_u@6O|#P@X4#H)gS0x+{|);5yEeHCR3VsP{VGa~C^i;cg>ZJ?C+{ zBSGva(h_cCMUZ;fhxeGfV^)=f8)8xL=X{mX0^x`BP-fU3=lUY;2Cd-TL|Y)@s`Jfx(a zT&4}Jg+0~N7{FFXcvpyi06Tnz2sjmpBfKNfQH#3aV1N(jTW?)mN5@{+lNmx4@1iBr zRv{f<%|>`>s8S3aQ1>-{zriee4HxH1wor9FZW^8!AIh$VDksq1+;OPFB5?jiFK;!_ zl8eP0?CR*HyrNI_FDJDEMc3bxZT38ZGGXBFM6AYmYO4-qOT&~ne*#{E zGn8!)Q*IAFgf{svY?F3`DJfI{OaW7(P=L&E#bQ7Y<2xR^d=0m(Ih;Kdu4KiavX>yI zhY&t8`0u-Lzrek>zoVg@3RnIKeTyB>2$&?$3h3PxeHFgUOy9clUhMV0N@5l!FSg2& z>TYm;7w})y@~P6RHSnB%z~H?*x5tH!Sugn-SYuHyS44yoq|=IIf`Md(6z!(oEIm@0 zN3EZlM}@IB+Y+ge_Y40fJU-7u_=Bj zj)G*wJN?=r#T`K$7*Q8(^ZNZ6f%6b>U-%Q@0lv(f7YlxE?T?d z@>`QK3H_O;C_`?vHQZ+Etqxp-o%TN7{j5XC5rg61I4D1;syRy?1g(E(2X%A&B8oLh;7C$HZ!QULD=iMjiGwKI)CgR%zRTkJ zsDlwN0PYPAFrs%7KSB~ml^h$ywM1t)aYmBr7^Gxm_~FwApbf2W*I+EA^zwRlVOnxs zI@BPuCo5C6B^q7`AFsP`py&|N(aHzu0oW=eulnJ&q9&Sv7ckCIuoHOO z5&ybhJn189He=G1&vb^Dd@*Hcbrb{HvG}1%kwGg3MG#L^3N}=k9kR=p0=2;|4^@U4 z_WF_F+=IlJVakZf&-q2@L81-yw{adO-aR`QO}_t27V7D_IJSiNHxcij)9b^O1jF-w z1bH`t68UYI(p6{J=Zh%ZZ(%I2;{H3C-I zetc$Ilo<-DO@7=LS^4wd zkp~e;GbJ4+{IrME2M1=1=zry?9DX6BFOAUtcbeyr#x+^_TpOHQ&_Aga*_$KOjo1df z7EBdvNWop55p9?i*_}C_MOQi^S^--DNB!9mL4E#{_17YP!jI#ewt41jIDmTt#|)hJ z5Z{6y&7kc4%^s|`Md$%r0he|mBq)f(K=@K4G&aXGQ6mJn<0=XQLa!qJxQ6qv&12SZ z0AB(QDVi4%|1N$!vyGVVYMB9UCpuW{+J*Qxy*Q;#`y!lc(U1V2CPF~k4updmp$~1I z1Pur9Dd02!=Sjrx!;hE#PphZD#t`5Wlo<{VKZ5vbjm~2^9)m^)@cUOwq2WQu0feVD zLU&m`-84dgagsSg0HJk=cWQ*@=6G}(A;2!+n1OQ-;vdp*Hd;JaF8f3c_$A;tfU_9! z8}Q>ymkzRc&I5_pE8yKgY5>x0Kv=6G4T1|!Ck|Y2fYXe2ARv4K+D8ju6X1_j~93Lc}v#23IVeS}g;>I5pudnIqS;OC#jS zbu~>>l6B%@^#1eHl~u7f0iaoMPjoKFvaBm+xWY&sF;B^q0@E;CafVDExl| zL42SWHW9~W6CFbesQu&8IktSBaxDd9eiFOZUchfTl&}&0mI-*G?hfqUJ@?*{k>}*# znS%mGW)EqIXIthgtY5r((lj)?EYk=Yv& zcxHjpO%I_t^$qc^%Z18pU4SPqr9IU#!&V64*?;@+^|LezPkBbYd?Q-mq9n4!A_*%z$VUXZd1fTkN^t&av1( z#Z@?ymXeI;O@#oVcNq4>xwZB?;+7~A#S=hUzC`I4-2v(1BnX5^r<$T+&xO@aT62v* zC%O+RNSrOwcLl+^4Ra^T$h(9Pw>4yQic{xC}=!s6Ovr) zPRNBelqsSN<+DPS+w@85+au851$dab53Y`Jr7Twx#i$C5yM$K+0)%H5fCmfr@eVfi zt_?Bl;d_*e0k{vWjyYC%i@a}za!8baJ;&@Tl}}=4qI|T*@2G%VKWr`$r7~muU7}oL z^!D7$RhSk(=F5cE*l6lgp-XZ-w+ch0I0SUguTc`jX}_FvMXZIvB7O)c{yyb9y6}?^w4=`-T5J_B{K#;g@(UmrM#2bF`tx2qOvoc2uxA?+qT9RC6HY#V{@`cCCv0o1T5`zr9& ziVAEJliAf8g>MG?huei@mc5Hl)}0AhLC9%Hc5UCKj0g~ie|L_Zd|r7uc)}Sz^0S3^ z-HTJ@dli#bgccMbj-+%XnSHTWc}fe{p>32S-x|;=tyR)=)Uhd3iYP`Rdjt0HvBQyd z;ToTQZ1lxfG=R`PWlCrx`obl2$E&LY_r_r*H1h?;O64UYwkB+Azn}~-tpA?)>Yws9 zTG6ZN7S98;Wcq?KN=!R_j-7o$v53#02{X}aUESndx^3!^bb-bu#XwoSImvO`p zXxd)lD^5HQ9_}mI{+B?Yy6v3n7!W!;Mio+7DP>uTEBj@oC!g4G!6NVo$lA(M*e$Pk zr~6tsm0d*mnOBs846TBEgxVY_>Oj~;Gk?Cu?m<_4H>0zN1)m-4MC!A+u*bsKg#seix^GgO2^4a(7VdGIYVImQ=N2qCB#Q9&LHpxJeLV zKffR0G4@nf&Bw}~Kr}&j?_U>=6!7ZYuPDrqxUv)@=j06t*JI$Q!4=v`I`gOxDpJ|% zPnCFVhq6!qA8~I3S5>h#?61v6B_TyY!LQsXD&hxdsA#5um{ew@R8*b>fy6{5C8dDlIHjPq=6~{Ld!st}`iv^aqGM zaV8~rXzOQ9_K$1vo?yvOGS2)x6SpBdUJUq-wDL14GY9NG+tl`|t>AO1Jg1S*YLt3! zvsd^CZSbcleQx_0NqL0$R{L)Cb8cGrrzw4hj5Kd`kjsh(wf2MZ?4iT1?XxEP>WW%z z>Dv`N#~G4RY3 zJ-sevfbjH@`cLXeIh!Kq-PQhL;EbOxvunK{(-%^v>-@BWvniv%r)N_}0C6_u zE^yaBQ|^=U*_^l7*MeC$N!$9*lphB9nVa;EzSmhR-1ls3@&XozuUC|aw824v1(?kF zjD{UfdB1*^vI#RA&!r3oyU(R8z4Hm0c>-^3$|K5S97QJZt-(h~Gq68-lCiUx9gr-} zJ`I3wK9nM7{fnD;0}*ojJY}SZl|7Q|obrLY{9Qw@hjMpb^?Ax{eH4;z=TlaW^fSw{hdbQ9X(gFF!uR!idTC(o z+2zT#t$q`Y-IQmtsaq`d+IPO~ey#K`)x>P~^C`oOZ?GxkatFb55uT8?9_F!l2zQNj zdecWCJo=TdgtDqd{+muhi>H7f3eyD#a=O(&f99ndn%j7#B#Nn`LFm6EH*5Pu?v2D{ z_t*dxbh=-e(OSTQN3;1zgHh*lC3=z)!Lv?nQ+>(|FF(FAAnVZEUI(wIR|Hmm7M-mB z$#0T@H=GyY`_=lCp~L*lJ#Q^06DmGsXqLVJ9jOyoS z-rh|y$JRwBuXh~OdqI%$3{LcceA!UTU11S03&n`{AzssQB#^AQ>mj?v}E<>dJ zLdqmI_|F#@y?)w&iz$P#x2KC@e)69&$u|_wiM=VVl3^K*@Vtxmo@Yd=m!Ek~T|%<_ z#L~VlL6Z~7-A8htHsxiXB_z*j9XzQc>(WJgUv<7@@2j&e*$Z3JhAo#;hD~2{rfq;m z4NyuBaQAwFe()6zQ~8fOy!M(uc?vs%70~{51s*pVkjv&Z3@PIybuTf1rqNGEHKaUl z?>XrWDP!0v7saff#Ke-6!A3uG^Vwy|y}QyxA<8p5`RLcY;srg|+;8M2Sdx~LF7HPDx`9XG(wZ8PyjPFNG zypI)17w86D2^Jzk-altwY9B>%=8rsStW2H6?3NUjL*31E2m66$lG%GU=O!0!Xvy3w zThuB4B0cI7z5LG0DZ>VLXEYl~*nrS8orL63Y$%Pf`m+5D{&&W6P_|r7k+Z69rc3!s z!fe@gZ#9IOmiP3 ze>nMWoRZ0VlF6Sm@#&!_R=GQS@wjsrbFjQjT(*3fGNr?_oitGhwTr>y^IxXKx$Quu z?Ij5L>b!^V#*exA)R^*+#|!Nl-_yu)bjr-7WR^Fw)4hC}U0!3#Sb3ABW0#3ZbL@QH zD6f}i&u+ea%*7*{J(w;uxOE8ALmBqW6j^YlB1p-QPs$V~G7nM4OjdYHJqNj17M;`W@JKl!VIR&>ya|lwHk5NSH*c_ak zCccI8u22?j{5qwtFGg*nzKOo6BC4lO3p)Url+qXLh@t zg$o_b3buwer#z%jMQe3)%Dvt5FnZhD!L7c7v{z0)@1b32PVwj_+h_(QiDn$~!lA+6 zamh0aoqg%aeYCaTrFeGBMP>ssuYZ>^uG`=FaVjs^^6_^mV{|U{^cT6r?k48cXxY!M z>8l;vnb=kH`5`4h{}_1-en>g%xf>Pv6^Jhgjd?U>A32wB`WdbE%<}{7PTyP!)G)@f z=32^Ro&MJkx!d<++c~4GqpYv&<1s;#wW~j-yl9lYCuTcuX1!-`)!Go^c^~q8U#2_F zY;EdDC%&sKy(q>hwDodZdQk}R?H%%op{?~D^2E21E~f>u8HyC-)?4L!CWmiM59dWV z?bp|mZ#(pJ%F8-ELRv;kN*~TiExTJ%`aAS~pGHZQw?XClRDJU6-*2*f{7cFhy*{2= z>2IXW>A?x;{`2w_Vt{WrY71_p-0PtC{h;Y!fqGEae+Ji-vcfucDeGmW4NUpx3CoNB z)b={6L$vJo&99h|G{aTn}9Rx)R`uB~MuH{xEzyE7ozTtzW_w!q^b?Sq5(do}hQOp!u7u}z-a zOQEed-nYwhM|NhbbDKPOWM{Tkw8>{E#A7?`6aOChw#D@ovo^cC8gH*iJq_!{Qv=zn zV(O=8r@E`bZV%$F%m^l9Jr_}zE>J^f_1;l)I%Qm>hLsn11&OQ8u(}%>UuyC=i2plT z)?nA6AZ?4YI@SS}JF9&qKXq0|4)&Lw;WshiV}!#y8I#w0`ioO6gI#0`Q+}=8G45(e z$7K1lZdXSd@9&hcp7LWT-eBnIZif%|jUS+850NiDmo*rAaf-IJhq_q*_PbnL_fY!{eUe-$ zwT@eevg=h|!oNHD_&gTm6NHc6g62KE|`jmMLpFG`rvoCYtvI*$fMPp7UT*5 z_8Ly+tsX2Kz=w_&k|nhF33J*w)7&4q7;!{KPS&1#i;Wo+vfEW1HexBo%j=`ZZnQmo zkRO_i>?AA=>Mu>vesERgF|}3}A}cFfFE)^s9naj*jO`5}TdyOZ)-!ugVYy23<+mc~ zIX5d|w|SAxJkd1w9rBmA>&u4h(5E5I4FOzclfQ_3*}r;rv|~pH+t*9Azl|9zYtF7l zj)oDvRk^sIy|8G~7gB*7xz+CCb{oc~A9${h9Ncz+R1`M#R`<%9N#nZq-isk~1J5t# zp&(B&zQKb|I&#jJ-LQPdc^@*I`G3T$OplIDbwS=Bkb{j{R57PM*lwp!{%d^ds-qlx zE6Q3AtN1QXL-|(z4fU05AN#QdL5l?M;~>fG$55}5%W$ARo%l7LOGkOWbc|L zt+;*GoLo~u%F05eoNV4obR0wZjr^97)%_;1SG_49OUseXIny*Z69M@M^SySjWzUs` zN<%ccwxq8*$YUEPHXRE}{>-Fq7RJaw#gzUXeO11;L}X)s^|5aHb0?cDm%P+2P6J-! zfGO{q$O}^W5cAvVw=I=#dIxbqs`phN81X3=pmK$)Iw%)SJ_|R&vKT!}Qw}kE>W7*q z&lsSs_Eo)xo*`3S8nsOV@W_Ajg#9u0NY7+pD}IMmPcir>qkyFOAZr%eU#d7(i2!Pa3UDP1?UXk z*{A-su|pK|D|mQf{H#_v$5E~xastO>i91aL%yZDWGD;oiHmHgd9v|fy6G~ryx}(3Y zF@%W%>g1s(JLapgFxn`jgPfFrQ|)ONYy-{1N!v79wcqbsG1c zewVJ_HQnrO;Nc&OOgEvokpq%!!N&BN+KjPk^x!q^g=`{2)-fT4CC8cYDQ{Kel28QM*m!C6&j~?>+oLm5ihsqymHRIG5rE`yt=NL?FY7f2> z)LMr%xj*_2262TW?>XzE6m7?N)k~jCF_q)hM{vDJHoT6V&_#K&6Q$UX_)p-D>_9)F z{3T67pDDUbaTPR411`vOSS689^h9}aXQUfFFDHIR8Os<**HH0s4L_yY0(7LLH9&^yNA$S z^wEl$6?A>m-?O*5ua!2ZW7jrR2eryCO|a)H@{-#JS-E{eIiSdGwzf?^|H1Z2W^%o# z+zPIp{U@sdmX?X?v-XFWQZ)GAo7Z9tRA=gBbN=tDqkTD99qvm_V!VS}Z$HXf+r&eN zSK4?|OHE+>a_KE2Cceuhl9 zk2ATCB7M#JRus(R>sZQKKxs=kKb872mRJh`{;+oBw_ z-FK@`cBIQ|1i7(dNcWhg{?d`YlXM53{E}`NI$dp_^@brG!ct*qw1eeJklOZ`Lzb}a z-1Lb8wMihNQ`eCoBL9ea3 zSAAK32O`e*sc+oz6HRrR!%o{_%p?DDQ`^p2u|i&9Ru zqkT0M?k&yDKE=w{_`w6=o24$q(V;sX&2nOO7WtfI`yNJSL?;=0`(wuu54Ru_Ge;e% z|BZ&-GDq#FKX#-^E109+tG`6b&vR6-0Z|;*<@tqt7o};E(^4Mx_{#GPoqQbkpgMWf zO((hjl5-bxqF6wD1Se(~=j?FqLJS;yFt{}W1?@rgK6xD4)lJvx$&!9oFwj#AQi|@v z!(WDsHLo7pRl75stBBtYb9NT4{zd7G&lYv>x5JDF`e@5n^ArjV4gZzpNai>^VDG;n<)L7-qAP8Ypl7- zUtS6f$UjO?*fLM`>KTvJX1l-uUz68Zt(?RWdE|CHmXS|gy!>x7e?Rv3k5hIa(=9?B zth+-S5y5!f!tYrT>f~I$Q#(KhuwzH38ceB(2dw6+-l^b0No27}z)V|uFN7Xy^nYcRdQT3&p z=1qLU;Zb#cSBldq-L&PAs+>*UJcJ%lN#5>A)t6mCbA=qv^5T`W^X)P+EtTIMkE!zX zy=?=Mc9FrOU)RkXi&wIXpRBrJfALp#Uk9pq$<)m(Uw)H$<>bk0TisM9w&mTU?R!kU z+fCtzlGpZ{nanWcb(K{J?koGCj{WF52c=YJQ0z;AhU8fud7Oh+HwPpmFtOkX^_kvJ z$(nNn-@uK5VVeiHROVSOKA{eA7%}*8+XJ$WNiebp^rva%A)w#TdQx3CoWhHS z6yDQnDD29>cF32vJ=bw#QK5z%w=Rd&YaczS`VMhKc7thxd4?0~c)4_1#|wEc1M7Iz zYj-SAhj%qe{d(=b1?tysQit19z7*~&=XY!AXa9T&TFd`(xox=>v_Du(lm zn7q)|!v};1eW^Btc;X@ZIHAKa&F(Nu@sRG77ivk3QAg->URpt{dO?4;l|4xud)QwN zHd&6usRwkts!{YAuTD&&9&(YfR)S}$0}IPdF#jCltZiDv=>H3?zi*M+NB=01Q;XD{ z1I7}Ot2px9dcsSzbG^QM{(U?n_8~nrUL7mjE|#&Ok9M|yFhfWDA{UoGvN+;;4ln

|gzi_j=%?aRfgeAD1&x_s01Qk1iNw|#ClcI3E7r+L}+ z+>{9+F9+Sbo>t}CdiL~GelLGooztJH$~{Vu$-%sfmnY|{awqAYe+8dEeOetqxIJIy znOK}+x;@`5zm9yl;-ywpz^4wTE>YjUX_++vuP(7)yV*FyzygHVrvhwk*TnEj-vxW6s;LA181{;)Tc3G5GAEpL)V`ziH zMeDXy9p0C?Z2F*ea`k`r{6i^1TgfT#jHT+_$7xnes?L0c82}+(UgjnqEAFJ37!vtE zIw|H4|;i)0=z;gXyEaB~9AF?h31ydfI=>ythfa zx>Ox`=bJ>z9r|Cn@SBM6w>#38KG5b!GL9T)dki66Ivk|%Zk6qJ?fzw|e1jIJ?ph;eNh&gM*1$IF-Rb~58}dZKE7iBI-OFH=vZ zo2kQHkd?oKZ9UBfEjUs2a9%+p$VRKs_tGqgxVDRUh4eBzkk`FU%&$H9f*0>PKJ#zO z73-Lv{){?adLb?ET*t={o>A}UFtaYYmw90qE{(Kjo>4vAWHU}6R46^ot3p_wc}Q>V z)HABDuYx`nS zE7X^ya~^+q!PRH6l$|CnK!MyggVYksVh_KV#5V zS=dFMuKYyD9+jjH8u|*6w`oXUrWQQ?vp6`ab197B7+hbHq{`2@+$>!ls$wYJk^8Ve za4Wg>=nXB0CSmXOZyC-QDv!IEL%CD=9r=sNmv6yKnOFICg|(}E*6u;=`{gg_qGZa4 zsxq(P{x&^XQ!ma+hOmdbfc}HB`f_q@MO1IItf~vumIhzIn7lbChoDqS#WC4*yJ(_N zZUk>3kMq!fJH~D`M^@@tb&9lU->wX+UEBy+z%Fpt2%fR=!nz#RGB23fBkw+|PLmBF ze@8RSW+68NAEa#kZz4dJE%Vm#(T5=N^cKY5Y(qwp#+S zfum)kwRLxG%Nn(>>;)aS(uyl@E+bv4M7iBuM*6Ym1z#5812^)ZZy3(b+%5kn(r#Tw zn$sGd;03p47TQm1ib9CrS7bk};R#-F>o>*r(;A-O1-Gu@)JHCxrFpMaN6L$Q3meZf z#*I~Rhigx)RVTQ4Q)hWhlYLh{-!bqzXRWF}BCqVJNsP(O>_u%B(&}l9kF!T^Xe`Rm zyqmC|o5(w18eZpcCMK7yv&k;Rl67)f{Ts-hZX08ETd5{DZFP$J+u#EBGu%TCSh-L! zC!rj`WB_>{D(98wlDC!eL)smXli%0V?lCN;mBtD0B8hq zf#xC11zR~>G54lrel>EQ_qG%?slf|eWW+`J&c65(=N~t<>Ia(Fb3V~bRcy5D`QFNR zUtyJfgWYPdGRVA({KmFsn6Q$CEFy5(f&2LKiZP1g!#Zr2o77cf+udD96RfBGa}0yb zRScv)=zn~eSu5nro+5{C1-tQ>b?WmRwlbu=-Y`h}avkTf195%LI<=oRdc8WKv&A7; zyoANjA#Km!cqu!7BUbac+?N)0>H|fe}MVc8@4+=gx8F$_sr6mcO@c)Zdg@$mXn+ZG&tfG79Y@Uv@OKmq%Ne zoFK<;Nucc zA;9@`MlL&R20*O|=e$n00_a)>r>pnsoVgY$l7pH>__UQT zstY~aOYy?Jg$y-W4aad*LkoUMb=&rmI5qwfNiVB+8!n^$qr6_>RAnXa0?J*e91t$~44|j)4Ag3G zJm;f@zoI(1b=beq-g&XFEqO&9G-*C{`V|`;7a1ldPRd1@I_k*-T0WHKz>|)kR(G6{ z>lQq&AEK4NqCPxyD+NghY!o~nXB?D1&NJMVUMuY{d${GlPTHg`+%Kx!!^EI1>K*cp z6K#t+VcyNU1bLag+OOps@NF!0mHT2j-yst1VBGUcp3$1Rhdc4aV~A($79JtQLx|r~ zz~dF-N;1={Gt^ZMZ*!wHLk;#AkFs2$N3I!U<0e7{E}p=Ps~POZ<`Z!?W(kDVRKoxD+(hvSX{-OXnslDo2Hm773w@p*nA^GE?<(lg-wVA&0G=jGr^r#ctA$ z%dW$c$a>8t4C}J}|0lCk>fVsd(G(@@+eK!~P`(*_hH|DwZDI z#sh@zjI-B?_;KxH_cZ`+7 zao_b+cWHizxs=iP1M|H-f?dqjm%Frfk%u=fk3PPv4S7`^qAzFQ%z9M~9wCQUE;pZN z%ouK#8$d_d$LSm8B{wvOcISf)BeZ?5axYfaX0O*U?dq%Qv&Kz%_Oa)i%LdoIyC!hw z&mw@`sl67`N(h@$kJV5fbEaZV;r&-R52oaHrKBfv^6dLU@Cf_SI2L#6Z&L!e$g`*G z7LKqV#h)Zy>8=FyYESoCKf=6_oj_!Mlc#1wfxWX`A$Zpa^F=b|<~Lb>eN7#wd&0iM zX|IrdFU(t84J?q`x80R6Tw9K6%G2GL zbp=g((~0$R*Ay~byK9$vx1YQtFRugF@s{2Y`t}TN6V3mSlV!f?O9!~AWFKa<*6v;Q zbC;Xx4)*=raP87Ab>fsx@(X3}rlz5fFy)C=>upR1{+`pZxj%`3zMbXJuf&;oIqERC zc2T<=6w?-% z<~pLd3`K^)zZK~fmuULkx$46MqNzm$0v*j6&5?Kro->{_kGJeMtA3|A1H+C?TmE?e z4J{D8ew_@5Q1DR3q4!g!x$lxcfqb`4`La94P~+UWG%NXj*P#;d%Y`P>*mDrhKl}Or{EB6dXf4$lVXcDcptZ?#{`8~M(tPE>ty0n z-c|O*w@5s4K>cgGh3ePzScq4g-X%j@P@*1}!k4^HzUD-F2*Q2`)qCX2UPbZVCtmxK z1mhv~Ro&nqrb)}Y_3{c>3Gy?0DgNfib}`9^brd~zaCT%>?;f0*)1=9ZpH}u%a<}}W z+rPh_w3fWBR%T#K-f7o5_`{p>4Hu==jmJVPDCutErDSHPo5zuV-m3cc#HxJhR7V3n zn9bQx)W&4@9-K$jc1&vV+N@0}RVNxF@ok=ia?pK-pV|IIA>7Yw>aCc6!avgx#hix4 zk2yj9SWymcWic2V2Qca8*8Y@!eMhx|o`M(CC{g+N{!&Nuu5rp`((zvN3yN9C)#J14 z74z`+bn1Mt0Pp+YJ?-MytkmAG{ZPt9+CeM~KFsq=M;w->M&m&Yv87A)Q{$SEda!Qy3$ zlYBJu?M9Ctk1Srfc=@tL3qiR5x z<%?qtzV_?^tL%1G#;sUIVM*~T;-X`HR@w7MYVk+aC7oo4{7yC|VR78Dq+3;*j;arK zZPT~g@0Yk@c}(2Om5Y}xx>a=cF?C~S(J4=@SiUT2)#A9-w@51X3`4u6DTZNV$3L}n zrIN6CRh-hPC^wmKi>lVWT%Fo$_0sWUS1x`&&S#|I?z;_l`rdi7L7!R?7x%~Q6#T8a zd~3bVMYENw{+#NVrYqXgzi1xX^>Q`yuByfZV*Zy0L^I(!!HM7Q1Os6-A&?MC2q(-Z z#1oPTrp5!>yEe67KlHs|GVhOBJQw&`e zJQK5gspa4Wb<1r*Z5v|YvrjFc4~&gb{{1^TAz^t8ec}(27Q`ed%b!hJurzL|X1b#K zb+WSZxn-S=$W~ES#3jkr@>l#~<5u}mj`FuN!yBE)_L??qCEH+ScSWnaqQ0SP%8VOP~nIz`)a zRV`*%E7}vy>ae?3N3Tc>k6W=aF)k)aZrY?3(aTmowS2`=DtI$)9|E0zKJ#qcvvG=+ z(X6&;so$ycYbNq9Ajl40Q}-Mb8u6=Ft7iOO_0{=V-jwKV7-R25qwW7I3zsiX&~|h; z4(qZs`niR1TE%tMtINz)^lt5&>uTmQIVR#(jG4ANesN5ETOW#vBQash6uZ=vDYNf= zWac=3etXyz zJ9JI$rM>@)I%?aG>bToi$^H`I^GI~UvvDJ}jBDy}%U^pM3mrA{HFcP_sa3UTvAvA_ zEl;=`d+IH|zp6`g+S49J=K+QlZJR6Or8e4<+E||&)TaCS&#IF){TFqMcKK&@cbl_S zo<^hPkssBax;B{uE$Ue<`DgVh?d9P{7wzE@#zafrZ|dsq+6y|PhgR5ys``5w9i0P4 z8~jHb#*7O*WL(+<8HUHVh{@Pl> z`y?)R8T$?Ry<7;xaLL@|t5+KC=0&26*~Y<+=)`F|x*9#TZzdZDyZv5Xx-(uIJjED2 z{0}nh1;$MqZI~UmDlP$&{(sT3h8yqh_ouS5W}~(KBaDM@am-#&yS=|?U2ZcPw51-# zQG8CV?T`D@##ijyR2%ZM`iM5q(>UASz?K>PjKgl%UL9^M(+-Ew!u3AJNm`=6ag1fG zk8#^D&CSX9z2?xY`dYqyz<7twh`rizC898(L|6$`gj&KmLL=cCL77k@TnL{37lQG> zW7Hc5{0US4=NvKqU#Zotl?ub*2tpJgfsjl{BVPiP{v5FFXOu7rUEA3^{jh%lQFY2?3HLLy-; zA)Sy($R-pLtb{6p>?7w0jf86iWjxLiJPFcgc5>{P(!FAG!U8z*9lI@rQcbioqEVvs83kF$g*Ot@kVzo;V;HGqYtM3!%+9X zk-PpU`G%2yUWPH0%okz)4&B?0l)YAB zdEzPK$lepUM7f6mxeB*@7^o<=yW7s-(x$f^+GB&-_+&dx(>TScQTz4a+UDk;X}V_M zL5ihzS!(ue#`M3Iia!dGuaycJ0*c#0$8X0Cr9y`I^=;wS-=>45!gYU}%zq$f6sHSH z?P31jQXzwtkH^U1{kOI-bzP~DA>*sIkhHN>$dLZ>??Xp=hx~P8sgNP*x!;G5^frA2 zIt+CvcCbURgB=CjpD%L4vuPqh-OE7jy^n9sQ{8z!TftFa&7CKtv&wh8L z-^x5osgR-YLa7M+vQ!K%dbU*j7eU+feCo#zrciDEnpDH6btcnYiXuYSnUpE?r&$I0 z`O~7ECz6&JLYSfOc#C%cpwXhON$t|jlD$4Pte02YC0f7sUdde)g*o-&d~jQztglcs z^V6nDf6q+S&FHvnc4*5}6h~KgU6)>c9J==ItMBF}ul{Bd?j}%_qPTP`6AfL0j6OTc*hn&+nRX<(x#6izY(Co#mo1uv}c9 zTrLu)Ktg;_xhM%P7o$VUg^iFDRxVE8%kTTjMHXS|L*=4qZn$vanoaFDmyGH8B{C#TW_Aizq0*T(rcN zTYi2g^{ShL=`Ks-=cz^~-83!g%TymnA-Dib|1$NILl>J6SEp;?U$e{L_MQFDS*v*3 zBR5J89{WL4FO8bS%dR#jsZxkTy+4Fp3qf`qArFv4g;6d{4I`I8#q zd8S63hSvx+1lu_r`B#l_BKQy#LeWL^FV%<^=n0!)?q!_$vPLvP7uW!2E>4P%TVYW* zr+qgie0tjm|Ej#LYjB@iG0pOS{X@}0NMIF-*>8L(Jm36KTq9)e_)s)iJ``n#J`@dv zW88S0`FNzjMRKJs-d0tneRtR%95?inU&6g>~>*;pBam$$e+V z=nv0|%+Jq?27>4Lv!bs4tnel-S=LS&mtp=bzk|-7wK#`vcwwyZ+s{RE^XDS{>gU2n z7)?0MZ^L(=i-9m`_<3O(abDySY=lO_K%eu%hj5K})3EcR1sQkZK7`qX20}9-f{;G- zys#4D3ES^JFX~`udyvgIe;lX2NxX)1r&QonRo0CIk{f3EQ#d2xZ9Y6z@puU`czPE$$-c zbqLq|fp8sZ4eja8@H)YX!rci5LI8R;f)amGxDY%E-UNTbR6-abf)GVWAS4sg2pNR! zggin?yb&WrYGeY&To<>6&HV0&-^#4^yxevc{ef&5Y1QrNr(r#ziO@oDq>M0vVd+J& z`EmYBBV-b`x5snaDbouHC4@4cb zqW&PAa*h9S;s2?Vf8@ZQ>l**_+DjvURFlp%>m2VWR62BP=xDXbX`PxyCUzF=Fz{zY z-tz18jgN;}e#_hV!y7tf<5%~j6JE4@bXgR) z`63KXW$up&w)}=+7%FfChA9O?xd(aZ1M_qRA{@GQDG(;;)3re4!4{_iQ3t(y7KlJ9 z5a?PUoMstyip!(|kxoJtv#?sA&%*^GF-)h_JdPqfw-`lOl7J$NUx6YucUoB>{3V|& z5E<~?ngUTRf2S0PX6ULG2v1%Xs)B(q*H|DTVU4LkB*VgW1tQBxq;Y+Lut8gDfvAV` zU%(M5kWLNw6t7_u4#38jDG+*Yp@z_AE)Ye~eJc*lCLj91(SIutVXz*?!=`OG2+K6& z;p{Bz$#iH`9-yFCQH1HQp$N-hJZyO#525!P1;Pra?!ZBK4mz>T3$u}j89R}OqjM+- zM!`H-^>+$_g}d2A4zyWCNjF57J%1bJ#46;fN+|y635`wDhh(` zCs2gVCksS2Jbem1*ic;{8ez#l(0ho!@eVBo8(<{Nc$b!h@$canOnjeB1vl3k*;YhG zf5^6)OOwDr=<+d&u<0p|HVFSO+6uGmM2!59^d9Xn>h8 z2$sMocp94EHJA-YU%?KX4eMb7R36bO#?3?wM1qCkB@EdWO+(sEE)f#C(T%t~4Sh9=Ph(EIXU zkpZ0=_lhFu`qf@h3#-50E1F^EmA%5~8inDey}}AoaVZ6&e5f10O?h}cyw%0z90S#^#fQ9ZDfTR0h0H#6L7=|PChk+jG!_6=eCVHX| z1Nx&68wa2dO9rA3vj!P45KHG9i~(3}zyPfC!T_uviUHU-3XhV7=RH=FaQIWVE_(%1_SW)3Jk!gBn-f& zXE6YkWb~KN+n+}thOI>(CaCDcOcVOhx*mOaE)9LCY(#&Fkv&^F1`?>jix_~XU%~)1 zY{meb|1t((#w!?rHCr$Mz0DYaYyXP=QuMZ>FPVuxZ2TMg@cK6Np-UF}aNw)x!_lvy zZzK}%ItG^E$aW0Ch&M0*=f8;o7`p=lFd-WQFli?S;M!dnfay8tFQ=xt=)>)Ap$~Ka zjy^2hjXo^PLmyVXjXtc)-zSVMM4AdPkcg*+7=SK&F#red!vGvzgaH_^9|Lge0Sv&< zVjO_6CFnmx-#CaqtUZK2th1mGuUXNDn@iD$-iOhL5l0#SEksN<46I;>P>BKPc?tv2 z^bQ7KQw;`SrF$IcjlNj)(D!`(0dt$i^7Gd(Z>JqKU_ z*1{I(G6?u8)>51sW+CcQ5W7AAQA7oO z`Y_@E`p|R`eVAZDe+}cm=r9IIm|BK`wbbMo2B5nQ18`s!24Krc48Xu@3_$O9F#u=R zpbt;KkA4ac)}jxyKSCdReu6%9KZ8CDKZ`!B|0nuJBBpZ~fQElzK*gcYF#t2qV*m!! zV*u8`EEs4-ze&c1op)M9M}&7>uHgJ7?8XJ1JGu`0L=Bm08G0R190HP z{h|&g!WOuF3i_$Y&p{u$M(r2r&?RZVsE3A0C!_)vLOdV z6wDlcK%_&L(FX)~>Xm>o2Sg-to@4ngxmMi)H1)gSX9H&2a82B%(WB?&sS*jQkoPhM`%&#Q$~xz*kiOPEVR+0aP4tg zbPM`bwCEOkefNHtv;ZvpiWYzazoi9W{13E%kx0-rS^$P!rv?7XHv5ehfY%(E ztOK*1n9>3ZotaAmtv#5W1FL#5eFfILGk0by+uno8IM8zdlY3ym9n2|#bzaQafNO^_ znFsnaox~}VVL!S=82yRJ*+7x-w48JU%b3=Y2XiMeSqE;O%#(kZbXSQm{Ec1d-AuZH z0n?f61Kop}Jp`|XFiiwDFoB^Fp1z0KLfddOj7bf!Tt z7OJLYV8%PN42-S8q1SQveH?<;4`>4Qh6Sn!vSP4~j$>diz0<4F|d(6tyt7|3RU=$)+$I z6#j7b@Pi@>)=oMovS8W$2SpuBjyfnjcQF1#6Ay}TBHK*|MLG<4@u09m_soN$5ti&g zFqKKhU_Vgu@^|{onnS`LW~Chx@z8r4cA$UmA(6h*NaQUdcvQIi zkg&noZ{q-tlocEjk#PQ=L!t$R!hIOpP5yq;;pP$?gH|ST6<&LVnn7!(MHu$8-`Iv-m;n>v^&M0U+TOx0jM{C)@BwPJ+ai46)ctr26$^%8 zwiUy$4%Wj^8=o*Q#`BXHhIywj4C`SQtUW`ELBm<>mQc_?u?uT2v6>zSYzx@H%XUnf;Kr&?jIRTa>B73nZ3 z*eYyr;Qbhc5p%3UIYP@tT16l%d=i7O2xh>{XsfWo7FY*QCt8JT85MiRD*U1HB64Mn z|ADXIDGBwN6bxOqS%v3Onru6s!kQdBFQtIpI0QErScM5D?6Zm@IJ?*?>fvY$1sq2I zh*bo^rem}StT|2vVc|(C2sgiD74ekQQiH=s8UIQxhA1fgBRqvRs2qc5@D#2+YZZ~u z^Be`klFzLo4~AaAAPl&K4ighmAHl zewlkC=~^nHV2uZpkYM#drsBY?;iaMuM);Qsr2+<)3LkiFdZ`G9Q-exHqWm3FDzc#e zJ*A==Cc{SPct2CHj?+@mAD(-Vsa()Iyi^#Ii6qWrCK9wl8{GZ~im(AXRkAG~LlK^X z;c)Gfr6L(t!7LabgB~n`_3-*r=vC1|i*OYBJdGYqXR?y*1e^AG(oeA|jHN~qNu)N7 z8bfzxJXv7?bGaI!)3#D!Lb3jB6k&W>sc3=C@8b}LsxIOP%>1cTG{e)n!@}nzP2Tgc zh=S(^9Tr(IYRq9#551?7UkyVJi$v%cZage(L>eDHES&y93&b53kuZMcVUZ2})x)9= z=59GGOz%*WU5AAgmc4ygG{f|LhlM9h+K(P|FQ$NZWv4tW!lCUShebM!_=Ixcxhsc7 z3k>@nxf(W|@t4CQo=E+5JcUWO9T9cV+vSLGeUFytc|-(3_rXVm2_||U5k>Ia$Rna2 zhWa7*KHK^(-H~7Bs=U^drIwBexw9%`iO+gC9~u7zXQdkb~EDBL^d`$U&d-Bf{q+ z`pk(VA|B>`a75IerltRd<7XNFRbL$u;b-yu+an?!D%X#QY8WUGJcj`$a=HGCZPlYp zguyzuGGT&I{mVo)2Acm2-Z$06ZNou zGImcJF>rU82*M*Jq)a42*LyGw4fi4N2|JoO6bv)wVh9#JQYNhM^y3r=uRU2Ne9qA1 zF=ZkO1}-WSS#bW6GEocHE-z!!8RLFMnec~6tI9+qY<>=VMk2{6Wg-tM>rjB{X=S1X zx~5Z;IyS*39Ds%`I0*CpN&(P+TbZyy>#Jp=5eB`19xdm&lY;(90l8%&9#-d3A(&lQ zChA~P5f%H4PFhkXjA2B)t#|@kj!-jLTTabjUL`eS6RbT&&0xg46f8H%2Q(#{AmJmL z68fCR;OEr5j+TUZ7bzIdzEmdCVeJ>l!}_m~hiPAz3FSPUyUS6d@F5b^?WhQc4KNYL zcRwn!po{ZSVTDz!99=KddmI%?JuT7esPKVRFbrOELl0)T9~Bue%>zB?<9U?1IkK;y zcY!`M;HWUb+Ck{Sq&tjE_9J34pa{Laj*23?lN^g4 z%=SYMX5EP%ESW@sm(UAD4<<~dKv)!nqc9>EJ(yvfiKj$zXHi2K7KUO2hVG+=(D5&{ z3@nQ~Dw1L7;-exPhOa#;s^Ml6@?X#w)=>})-9$k!BZGpVXC^HP%b*pu?4cYu@W4^w zd71IQ{SY-GQe>q@FrxIRNQYJ%HG)pn)Cd;B78qDdL0=-zG|4d7^x08if*I#<4CY?O zG1z>C>6I|E>8NmRWXE;ws0f6C*N=)Qcn+Ex8UOQj$3z|p@m-IJS}EvqOekN`YoP&} zT#tz$SO=qEhWjyLf{id6R(l>3HfZQ~Ow>d7f#`otlS2bsI~aX<8b-m*L(zu~F#BsG z!)-VQNT`SPuz4f~uCOV5F#xBI#Q@BNQS$dV49MRw8)gNd51U~o5pSQ27=^8!-d}w%`D4{_8PO z1S8$bMI%gpuv~avWs@da_+q(8h8Zv$ z&dy-UC`^aSceD)jfw>w}PGRZ-vN!N&XeW2Ac!OhY{15)O&;9Gb%)#bm*Q65l_1HUPyZS>*rL6YPfw(g;0bX|HcXtD5!~6A<|*vn+U+9e=tK>VcPe56(StgpT+>p{G~!P!q^++ z>l_qU$KxUl*4}npB*SaB9~W6L!S%SPhT(mV3s#|4&UqadK@JW|+F0aZ70hyAg%3x+ z2-iZ_+Z>eU3CP2Uhbn~$Dvwr*Jm?-(De9ol;!5Gv zojG7DDn%g7cpkg3VSS}hK47WQdHD6SUaF}!j2jSH3k%Nw{Mg)me-N0ZE zYCQ9V2!e)tPl!Yq1~cH)2Tuqa44;2OG((rT6T+vbgED%_2@wh7mz@wMSfZW~R(KB9 z!IpI=gp(@;y?jCh!jiYK3)2ss5ZN%)cpO0@EvFFdMbo}}LiodTwI@WBPZm~tG1sMSuiUbxxNlYB|i70Xd&So^z?90 zX1|33%ql!75@CHYhGCQCq^N_}j!+{{I-iXi!Mbm#5lq*e5=Ahe`zcWmZJwuuXFt;W zof1KCet)L-!=yo{LoD$Z4jQ?xHPl-knu8-tBfc|WX(WgWptRIg8teJoUOq+a4 zR7-}Q63PG!Lr=IF`ojzu1~Xw4%!0{qJIsLB?n56&gr5@4FdOo|0OK?oMd-iclt_mq zun5jxc}mp5EZ7Vi*I;N6!*SgyVS@?gYS9d{v})mV2fwqcMLgWRr&?se+(Xr(4qmIS z7OsOC-lwZY7|i|j|D))R0~^i8g@MOz5!97?)s@S*!VZE#P{bMpgP;hCU=S4H_7c7# zC<%(72x~?lzx4VKtPz2@ue*NqB^vyZ%dCqgrN#eBeJAT2m_ z>tjKYo!cJ^nq0U@Lssvh;oYt2{f-4079XG;4?bKwW*@5^XR^nF*gXvJs$)Tx=jV?F zRj$2RJLVR(WAuaWcTWj_*tjfZK6)%D2#Tz-wR|jSbL~?)F!~uC4%kEu9k}ny65!l7 zjs*?2zjZ9=vG?6$LHJ%0{?V}@#r99#m%XFMf;zW0js+d=oH!PYxZOJz#P99=AKH@f zy{+{%$AU6=0}1S1zwz;)$CdE$Ae69lH#;6g znYsCKUv-xdi(J3O@u0ztdmayl>^$taudtV7_@v`O?!E?m&hene^z)Ag9Zs>&3`d-1 zx$Jn*<=m;`K{#pPbJ}t9S4zsQ^GeF* z?~=)i8HtKr71T5)Ax_KeK+52I_L)X_q`^rJkS@exc~XSuf!xfoMN9jjyT82Lrsiv zF1)O?5u^l*FEb#IENlc-#y{*!R9wBpm!KZz4Wp(5n;-R!E+#(in_H}~%K6V4kjYg8 zG5&S!A8s%G)Hk{~(b)*HH-I zc$D|}OM?;DuDLYmGBMKbkWa~*Tox4ByUk@mo5MR?7L1s< z_hlZ}cPbunSy1C>`m&(U#TQ)`L>{C4D=!OD+=>~Of&UQUsZ=ktu5P7maG2iugz0J7L z4T@Y}>;_GCm%71#h2?G#&G_tC=>{1#zSIp$6~W>+49MV7=3q#c*9r3B};uLwdCNZ(Mp!sGW!HE@Gx zdWZV6M0oy!6P{u>ld%&)j|XmYBJfaOX#8d;f&?2kKM`bkX#7M_X8)Eaf(GYrbt338 zed`lJ@>ynnn-d;J_i6ZFCxSW)`@GJDJ9+)tmZG%(L{Jdyzq=c-d(RU=pZR;A2qMo> znftf_*B;;o%sfOQhb3_EL=a>5p(lbgM-Ou!PNYr*H6|Z%B51Sl$P=Ef*Z)x`g4A<; zIzC!EPCQ0CmJ*NEP%xF&kj=-r@$+n|$Gb5no~Q#4Jy{3VGADu#cb;-07%}oR?VoQq zPixOZPuHG>XK2q>*8Mqnw)^wo;S)hL=RVKXKIi-&d7cg~Y(HNIhF+ipQ!mniGczjj z0t39%3^?;L6=D5oP5KcDai=CBhCg;9D3t}VkIRUY%Q9m6 z6B1(XlM;HFg665Sw-JkoK?#~WK zJp8p2elzKR9ItOEJ?qSJdhLW~w)sasG#P|E!Y!$V|BKlM_LX;Ug!4%HH*# znlYO{w+H@LiH}K~TbH^YbC*e+yKL`W?^?^D;NTT9euYF%%9y*SHDvjWhFt8KA(zgY z;VYGX%Z-^mXJ%Zu+RV6ojhV62SGj^+{|jr*@O9cTwyhnft~X)tD;uSOwb^@v_%)sT zjq?(5&bNQBA;W7ZL;X!Xl)Pds*o8U3iOv?`bH;%f&{`hIT@r4 zG(LXPBic6K#K|D>DogO+CxbkztgzG))CJ9Zp7cz%H=_HW48pHgO2*l__+*gd>O)Tk zO)fp+WYFL9(8(b3|18y$48-PBPI}Z@BF{J(GV-0-zF<@F~$ z5$zpwATb{LjS0MtzdPwkXvg~xX3WNp0Xcr_&7i}r+iiOA+4+y($#=qwO2;&3ncw^S z9-BdpiG!O#m%C5g48pIs89%uhq&VH!3<~UhX)~yEmu+U&HiID#etXjc&F=qQ?HT*N z`?7sRdrlm6-;$sv7%_RpW{`NJ&30-t$T4!-7uk9EoQ%1CopwzBQNr^!+h4Wgfq!iV zRW986RM27jwx>LhY=*Z#6~x~pu{)mfAhOf2|5Q-f`}^*vJb-Lz?|mvL4FucwKjpz= zKKN9SX6Rw3JaBA{A9>1e8JKDMln0INjVGN7!YVd=+9?khTZ(6$3i8Z7@016N&2UBn zd#}Gt0$hKk1j-V7jRbh)s}kVqHzmOF@0=gy&eo}*z|OXI+&X_M=ySN^es5EW-BUq^)v?o_1GY)WPkWqKr5|-Vh%7i= zk1m}K(t;z8IUSU_I(0f|aPXwlL6`Ywo(@89x5h6#9VB?a^F`@2L(7d2k@173&JYV|$=^*@0CH$cdY%|OCpXk7~ zV=`v^($m3^b0<#+@rs!;&E(nBenP^g>z@vqtpDAkEm#&ICoKZh0nXaR05&1mX8c@b+hd6tfqd2?{Jc=S)!b zK2SM)CdfN>jpzEC8_Q=rA8dx7IOEA^Gymk7pu;{c9L7%g$8ot*IzI?`Wz&_o+BC)-{zp5P<*RWt@p{r!tGLGJx_>GTaUccJ^6GeMgN{vgx6zyEs1^S(CI zbT7#8K(-f@nP82f=kz@9yH|;x=Y5r!kq=mk!#&UYT1w`4ghft1w-?meV27*hmjq40 zh--{|(57ILLuRob=dp+{Sy6%f9-yt=lNhaT2dj_KB7Gv zA5$3?KcU3T)qBB^sn587O~RjZeibpIQvJ5@!+2&#_^HFIQYB7xV+m7!k>`X zjm~;*m=~P&+_23%cGh#l&j0*P&w6m!E*?J{gg@!n{M*?e$^B6c8Nc({puxj;@iQk3 zKk94{`II$(j2rUs?yp z2mO`{57i{Xu}_{2hFtxO`+mm6zM&n*zb}E$l+5_YZs@|;Ntv$5_$n3P%x_eH_1`HK zlYiEZ!@n8$v)*X_?uHz@$(2Et9hTX+>6Jl)3pc;ggUHtSPFDuu&)K9GT^S_VV211W zxH71e_FlNxm7YkpW>Z%N1I|3{${_lAGi8F67hM_Tx%`qVgBk~~abuR>cx4c3cw>3H z8*}R&R|Z99KIDGf_u(sp9%ngX^AlGF@h?c|vl3?KOIP~8{{?g3xzYp2)}*Z=4|O#B zqU%hteDunou;=kBJ#cJOUMd03aK!D)wExltq15G925CmR5@DWoE?liWS2*CIYfW%f zLf2kd3Q~e?7joQpof0y`IxB4Nz0N+9+h+V_Gh&n**GrH`ZqT3cU+T|w)>#1KjlSxAW9UYlW|}$Xc>d4& z^U&YTn5~;%6~vknz2#LwhP_)~6_lAM#jXmPg7lrP3VJ+r(N#hCYu5TMR|QF)zyDQ1 zo^ublDyZ$5yeepO{^F~G0XHAv#$Q*7$6giWtZ|nu1I8bBl?R#K_wiQ+6=t7wl?Rx8 zNENRNqTg`+_3qEoxbXuCarS50ar2mV-{hIA zf;2n7bw3XOAz?Mepf=zJQpMxdG5KO#ui&#e8IV3z&69* zQ?VCo$JEQu1qD`FWAuOAm#Z9djp23UF;)_62~v#Bo(pp9vBiD=tKs+EsBkXGGx;hv z;QqODLG%Y^&b$OtuRZ5cYW>*b&g&(jUE>WB*lYjBb3uo*^TyGyQPQ5F^0}bY6wC;^ zT<4GzZ#fr4e&}PA32rgN%v;X|MIK?D$+x*NS2<*CL1Jx7#1zACmmp_Z;ebs}y~B8H zzT=$Ff5HBD>i8q)ok=#{r6b4Rts{5eV@)~yprzS+{SuY=v6+8Ff;_@3H$G-fx%)X4 zWa9G%Vz_ZG7_r6JPi(?3o(s}E{3WHx2~uBCDt6dr>}zJk>e@L^FxxEO){Z-@u+lOU zCcYyfb{P7p^Zz{wF}f}xW?5wTM<&3npGb(SKa&v4rK2+XnKzIP88Lpj&BNU*B*fmP zgt&UfW@GtEOY?J?pHnFw=u3>D>mLAa}n_eAMxpMQXgBIs*d3Dg|p~%%i_?W$O z>#KtV!yopmXB@la>Y&c)k6j&fIrs6agV1rGs>|9PcmCJwR|h#4l3#FR7Qb}0N2Seh z_3B{2)R(UgA{#35Rf(|Iln7g2)1Euu(4Gg^B*K;TtApsJ-Z`1%+NDHgxzto_xEIUc$u=&;ElS8n8o;!ZeT z7hL1XXKzp!`oTEvu+PTWH9_*E``!4OAjhSfToY9G{=TUnh+{6S9TPXZCJ1l3FG~qQ z;^x-`S}oe+*BZ?|%)om~@NfyT zoiczDCm-p?O4)prpSxrB@!F|C_X*boX{MhjAv0}1Nkt@>%v=+s+`svhYl0%e?!79)EUVn+@E6X1 z{(VX$f&Tl=)Qz(rppM-S8bHItOA=t@5(!?bBU6li%#1nvaTVeEvc%Z=gqdDvLZ7h* zw(Xr2m1Lh8E_~J|X8dy!-Y#7bN`1i%TqtwIb;hn&$}d_Y?qiOttnl!c93w8UVZZ@n z2F!ig%-H*i3NX`@xOU;Mxi53f-XQU>TLSK|Q4$>Zh6H%{n>NocWy}o6za>*3Mql?V@CW`T@k*6r@+$p)Yle(*dRu#T z2P*hG{#pgN@EiB#_IVTG;ot6^|KD5V-zgarLo;BC1!h>`3hUfpo3no~BQ7vBv^N;z zzCYTW?ES?WOJM2mD!@&4d1zOA126we1vpu{Q9q~(vdrmtgk>&V(Dx{|nOxWp+8i6} zdnDUh-nbux|KR-Iv>&8+V7wm`xO^+^xy3e<5$!p5+kO!Fqa}*=gCqz4)%Pg2``o!7 zbXgh*MuL@#`a$eZ2HxKfvRt`~#JK;ieUD%(6}#+k#LV5a-!bF6_k#?FEb_=bB*N)? z^@F_o&fcdV^!&YZ-+mDKvpsP?_vifm`$6T;&VNVHa3M8m0B&>07c*mm=b2&W zK?Y(kX&`PqxF2-(yjVYuJ)|E*|LV9g$<9HQW%Z#d%YzRy9=F)}tMfk;^j%0kTxmy+ zM@r_LWSR49u<{76|IJbzQhF{k$6dxGJogv_Y8OhI2+NPt-|O3~^T^{Z4X2-=B0Mmq zBBj6E98WYuCVqQuP+*=FR@h{nBNl#lt!KK;@b}jS85UXOF6(=L5B=mQH#p>ZMt8lB z{NdUl#UVTDCDS!b6W4msq+O|SEe_=TZ9Q;dYK3-U~|%52zAd$t5+7y7I- ze8GjD&$}*2a{k|S;M9Ly=V9>+L%VEq`_|V50~RK(3nCX@=pl3Mxyc+?|I{&GO!b+g}$n_Wov<*?re}X#B#^24gqAFqF8%bwQdn z7P!G0$Nt*@oMGrD{%h=aR4MkE;?$i?gfn+Gb537m;w7J^OB{tSEQQ*F*v+if{mqOC z7C6NkYix6sJ#I2|^9w^GMmatyVWybn*aMZGlWelc9$O6E;=)kwK`O%~W^Pfkc?3ll z2CQ>DX%jKUAtMhq(71${Vv$*Hu*@MFoVZw`jI+l%hHj}MjI+)ZH<)Li<&t3XA#T7d zyR34+bw>V8Lnb+KP-&TDg;_S)W}jV-xWm}3E(}EAiwTH zoEuDW?2$^uZB}`nnF%*|l%?VHqb15RBeyZ&V^xTQCrFgTDKli^$=WlLv6Spho7jKa z3r}}HcAs7{kRbXD1F^^!=bvfjQM)~B23&oX8FTU3Hrs!x&|w4L?!wTK=W55<=i5Wv ze36;G!V=AR{go1B!vykdbD2GMIpk#NB{tWsFAVK_shP9JJSXxJ;vu#;!#)=nHuDw6 zxW*(0EOP8+X3iMkY^lGhAembym5- z7RTS9GE6gkN2h}ct}xBW8*N4wS>rm}+~t5<^D115dBb>tk#!LAEEM&70)lZ@WQ@nMQ}7P!tD zdu((6f*CT&&|NPK02dN$G0hPRjJ;DwrrBYE zLoP8I_fE(J2TXHcML+i6r5|_L;{3ZM%2h`0Zta<5tn?lw5u{n+BAZ-chaC>N%ji7} z_+A6C&m4DHWbSaiV3bV%kwO-w7;sPf+U-qW{(Ai4mcf5@W2Oj zO@YIAEKTpOz>OG4w!tgHg^g!8UUo|BTJeeXMhmElz#L`R@v9E`%Orw=>QWGd#Fr zX*kC^D{OI@UG8$kiO;H3(kc3!nKH*Li!89p3Y%=Q!wv_ZbN+{d(C4l3gO!XirkLg& z3p~^?bC%iWCI=ibaVUp8YV zS?BIo%yjSXubL^#j2(0XCfQhSmewx6Jz1H_IuYE zN~^$e=RYnu;zEi;<~g>ZB22QuX?D5D5u1!XPHCCu7IO?=sv_LSI+N_M$UYZ2Vw17Q z>vyU1pB9W~dEeW&CaFs=NS!Zb^ z=m-vOnjxndezG?VCb-2kqo>S}hgf5lP4?L1zS9QGxXw7|nc+I~jGVFQ7-xeiwlmKE zj9}nGg^{P&6ijl+94C5a$Z6KuV25q?+2e@2j6K!qI4faJvA}uOxbI5+c#uO*GyF8? zKQD+qO+zNR!5l}dFnpDPnP7)qjyPm&+Ur~TF~J;{Smiof++>&MIpEkim3q3jV8%;= zX+eq|7C2&s$*Yx^MfOGtiWw$fRRi@az*7?s1wp}PQ zd7XioWt&wF*kk0`)|g4gx0RYxtgy@`SJ-2RL+&v89En_SKptkE3oLW_`jU(VO&6L> z-e8Sc=8zpm4_j-dIP*(4V3B1mv%yuixyb?N2Kqf$<(OiNd2X}H?62$%&XxpSL6sxc z8F`+8ndBBTod2}}xy%OJ?D9NEjQz%De7@t!G-p`gB5Q23&GQ^Eb6$cu=f5mS3A)U) z&oak;Yas4tmuZfeXY2)T%rsY7V4pRP{mwv)vd1(-FEmreS!Rk&=3nUiZwjg|4A|ho z-y4vJIp7i_FLLe~=h#q17-gPGR+(dqOYF135!V@+ksy-{{lVU0oRyi9fdow#3hZ!! zeKr_=u_a)FyUa5FM-}2>HrQd8^MBI*C6vknOYD^dM+Bjl+8m5> z#02;M*?`Ql%vsi0W1AZsF#H!Y%zJ-en#;^_hZQFOYJ!|&Z|^!IFZ0eia{l9jv>?M3 zmbw3LO36d)bD5EsD>A_ z{0irqDb|>0msJkf;4a%d9NG>tuXN)ZZ3ks0F4*=xAaCXD^2mkTz6YeDW81z5WN+Pg z+t+by?wf1}1%_|B?Z2qt{h}mj3&z9S!GLjwUgd_2^3W{|#2k}uSZ2}R%dB(2F2~0W z$VtXtZ6Zvw&Kz4Ta)VVSZ@KNiq_Fqze?ebRWcdHtl}xbDEO%JozJHT3Q*3gY9acEx zRK&n@X3PwGEOLi+9{6|dnc++n0=k|KM<5%7{84H8DpDs9B_%DqS7(WK2sd~ zPYE;1GSh5uiCwO7#PQqe_j(mzhEptZf%TGLS)5Ald?S0#x{}G%Qq&am59XZVkTWqq;4%7c_V3wJc zK#OH=vBBNFzuzR0n0{Plk8OtDY(U0&_)aRpm5a80|4)Ohi_DOr{YuIhiyEX@W&AE? zz%mDW9T~B7lXtZTxXv8s?j~`rvdJ!cd#}fB?y?EqU8Oj~H0SPK(oxX6hmIV(r#0bz zwm5#k>0pv0ZZP&1uiwkSJje{Em}iw$uCu|+y)7xn?xR1CF!@${CZRnmB|%ltV2hiK zapJxPW|HBzSrR5V&n%Z&<_2pVvd!rIEfFUfU62q{oSw9_oM(-7wpr>427>bpz10?!#Va@ z#EObUpXvO!%y{yd2IgTFHCSYwD{OI_UB*i z6XP^vA2QLBAT8*!z_I5l4G*x*EC*~bvSiae&w!j~jytSy_W3p!*Vtn?XXYO^A;!7F z49~O3)C)|Ir6oZ}u*Kot3oo>Gm&lAM_L*n=MM}*ITO6>@sTq6aBaRgloOrRd<{ZoH zvB85cQ2{P<#9hW}&VTNuDo}IoS>XP>3b4X92OKc{G8Oo!rD2jsW+led>$T_jTeatY z_V%tb^f47+oJD51%p${YQ-O~;|N8|U7n1CAile=TjD6hNGtJO~1UbP9XV~N_d+ac@ ztUcolz1@J!vdl#`SbnGW++n!%37J$3#0=Any-S8X#41~CbAvrjyxTyZG!PREzehhF zWPuIVIkBkZOmoEOdyVrcdxdFMSt~M66^FI`XKVmIbl!!6LndB66oMn+Kth37wha56eb80>- zL8h2to^z~n-$zx3QylDFXXtZ#pZ|iWV3jGhnPvE6O3Mrztg_1n2RzTn=MDUEiE)z+ z)|OS0y9_n#rBA3No6K;NMUH*aL|94-I)Zr)nfjE3zTieoalCFO+|M!({-1%EXPaZ6 zmJnl%e9>O`jLNaR=Uzh0aE&?FyR7g$n_qPP_pQj-g@X)z$$4d*OU&>H^W0^Xki)44D-x$kySR?;uiaieof`R;aD=k;@6!2w4m-nfn8P@`nm*ofIS}MkTZ;~ndvu_ zoKfZ&XOU^vIm-@f9J0meH+>i}#n75WIl1QiR|RPo8a&K4%N%f(k#CtflRWrM19E{C zF0;;cws@XhM!%&$ry2UT`!UKcQ{4A$6Kn0A|L-Zuca-G&2H=o6j#y;q2NGnM4IW^Z zlN|6ML*Lb(QEoEDnID=V7g**pYdpd>Lv8(8Iw**IPsblgfJ;Yox?trb7L0HYR@Jc+;^pRKd}25WtpiTIRAA))`iej z)|3ObII(2_PI1HnV?R_%Cb`KRN33xFIeUSJ*$d9cp@*BAe{8$6XE?{gv|{{;3)L zN@=;y47Zu*h-F58?M6(n$truC{Efta=Dah`1*W*hJa<`T`n-xU&psC!{<%H$yOOmO zO#RMUa)TA_{$2;hhGxtZM=UVbv9?UI%N&O+GVuqMVxC>rIpP{4N4=9W&ht$1K=yd- z07u+l{Ios96o<@mV%*X&#RhZZ*L(g)P;_Cy8Y5?vnn~_3$M7u;%mb`5!w%;;WRuaJ zJ-`$X{F|Aw%qo}I;2PUpxRvqPjFb#`)*Hxe49MJVb)^5rFsL%j1`n{yNe(#0(3Scz z&I&W!{x37+dDb{}I|Fi>J+>IS$^;qZzS8YwEXXp?4OSW6r?ecqgFV3+hPRaPzpoDx zJis)=ceEE+y^{esb&&yCzl%h<#mG4c-PPu1^lmE1>HC=Q)z1I&{R}K9Pr3msY_iG@ zYwUBK;cI-zFvblgxycOAGtck?On_q#k_eMYiLlK`-$X9fkI|H+?K}UAf{F{FM;Mq* z_LzI5QvJffPqqXsyx5Jeb;FmqA$$L;gxA?zuTnuyzD@#MXO-vK;=ZB@aOU+A*tYg> z)SgY|w@Yp$sP4TmuLJkJNe3o5;w)p=s}Pf1WsYqYd7gDf->hOh#374}-e3usV#;32 zbA?szFB`8UI3Vb9ks~fK@=I@_OfvKqC1#dIF0#%gw%B2xU5>c_tr8x%FOv+vO~Q<@ z$Su~n{dVWSD~P{CN6s?#E2UwYJ1j8yPJ4s%Y_rV)$0`#2wa)}5xyT%g?=nMX-tD^0 zR$-2->~ezx4&LqjM{KUK_b8Dyjxx(U%Us}qHHNJD7ULW;#q^?*a)xa#?rGo_dmJ+K z8>i;I`Z2)_rtd#y!XP;;TfH4eGW=y|1opMkiKc}}s)dA7LCK1UpJ^8G6KTmJ@R zn)57hl@+#G=PoT$Gs_v4S!RP<>~e<# zMm}uM{85FN`lIt-5oBFxu)uXz7{5fOtg+9-AJOqoD#Rprm}j_VKu)v4^^Y2meU2FY zn2PR5jA?Fs+&CPvw&VQAmu(ssGVHO)(4W19GR|#gxXU~jKVc8B#})_dGW1C^WR#)5 z7?24znPr;=_E_PN^^)M=r`&*9jyT8IUv*%bo6K>S6(;H`!=3+A8HPWtAEy`_xz04l zKcgS_t(Yk%*<_bJ?y?m6n+Bh?mP|0gIcE2+e@9*QW{2Abzq7eRypJbqr1-Wmu(s*m}h}yF0jT1 z+uY=ULq`6o{Z}j{4>83&^IZB$$yy3JF0{DKKKFgqar&1;nBW|v&{wv>~i0C&5$X^ZlZ!rvcL>0%-^Im7HSEqE_B)8fNh4pCu1fUy6IS`%s5w= z;t}RKV3px@3G)E^JjfAqjD=N{Y1WwIc~(k-@$Xw39%6@C_PN0D%_PVKd(3j|2WHG9 z8_crHd5&0Rc7)H*;n<#UdA2=Q3MtvdhR%^kd>Dd!PTeR3aDRTx5zJX1T)x4;`_YSY`I#y#7-& z;r7pLPM&9nJM43pBgTHN^tT!d#hGM+877%$@8>0JCkP)^lD!5TaO0Q~Mr_KiHDlol ziE#at88O#06V5UJ@7DAx{r3`Qk0TDbx@DJ3Bzn#ga*_l6(hTW$xFm=Q)|g_KHJ)di z;j49El9B(=fk`ef#}!t%$vSu0;lwp6!AXX1Jr)9= z2;)p}jyW!}xOe?}GvzcpEOW>@!?$%T8RNtamX4DwFwF`V+2r|OO8BEPs8QJHZlS$6Alo9j3N~EmuzyoG;`GgL2oiVl9)8Okf}BJSGrRZqzv;+*x6+UM*KIRpuAG0j~T z7)#hREU?KsdmJ)!FKd2Z19FlX&N0sl%UorHJ$5`va`_kRRq4^U$6XPadX zxW&kQWzIMw4|JYcV4iENvd0!%57v*{jNDHp8Rx{s`Z3NdQ!H@$V&}gin02Af1-4k@ zfGvjZ?>I5aiHBG!W|-zYbKGEs(SzDg+H?=qjz=D5KyI+WO;)(YIzy$0+Z2K@`;2hJ zC?gN>p^~~GNOJd4X3YJE%$VWFN|ZJB*dnY zqM#?(+G?^@oC46^Nc>kr!5m) zXZ9h^e@{?$A@+0wvCQ6H1BMRzhY8~xe}+xO9J8Effi>3HXNRe08gTD*MjvVqF~tpL z8O!R&JZmMvf}p+EfI}X5mW~h8fGMsp&lbxZf3}W{v&lp3agpJNJBCa!{u~2xhGiC6 z;|7}?u+$OEAGYaOWhCVd;<*N9f?2M!!Y=DP{5)&OMGp2}XXp|35TiW!eEm7iEN5BZ z0xMi$ljAw(zbA<0%$yZQAL*@;368zM4H$W$j+|nXId<4*=uzJ3UZg$SOmk|+USO4V zMqVOe&TzyAV~14gB_$mM;g`ygmAnqzVu!JpNsOtN>+onZV48In7@O6ebL_CiA$J*l zjFP`Xdv376$SW-Y3v6?>Bp3+B3QGT212M@(<`{dGik11|3&r9Gl8K<`!hm&-zu8(cQPzP|j6QiRRA!1T<{5p9 z%5j=4uCdP{!x`^{ZcDcm? zcNuxA#4AeAeN3^yJQrBz3L9Kwn?05Wf`K6PG;97YH(-V-7MN$5Wp1*;0ox3}TLO$S zG_BN(v&jrM7gd(=_o^(X-mkJ;=8)^}cmAVKw@a%AWQKVzv&tqLJi<0N+2epiju?K1 znSa2VGQ%`ynByFatgy-&8*H)5$OoPO&@*ke4_Yg(G0V`0%$O6bF~>GnIbfTitfgX{ z$tC?*WreG3vds?r95VW0d+AvcWr~H8ATQ{!#@Hn~FvTHjj6K_?VuoWM(VqKRsFf!w+G|^5wq(O$s33nM!qir?q``ZKQsXj+9tsGk4icU@;}n?W!9E8=6+%T z&K}%VGan_k( zgLyVtW{WlEzilE`IXJ9mnhMwm%GtL$> z9I(XLuWSiZ?6Al_ml=G%Gr|}re{D-S!y*@1d%pX>uFzDm#~#OjW5S&G0OLH)4D&2; zn|1E7#rlp+9o94S0-0o-q2D?KoM4u7EOYvI=Hm(WUf}+h6hbewGR7JFy$LzV5-V)5 z#x|SmvBSWXCg@rrrseurbr#uTm3?k9oOigHVCa-U89(LzmlftzG+1VrW2Z&SwRybbxhZHJgSYe4xw%B8j zfmaITp8{lx33i!f=wDXG1RGprmo*N!!H`3~!zf1&^k$-D)+yyFi;V? zQ(R-7+pHdXos+{B2kdj|x+Z>&iJ0Ura}16O_|WSKm}U0ZWazc# zW1OMupB!ci3UP%JGpw`34mTKhoeqpLc>{s5#ym$u0%M0QRxTA7r!Ny&$pS7H7*k^c z<2);zzM;T4!$L_I-J>!fq#Uk_E zWR=HnsUJ_U$MJ{&-)NrOob>(P2GO_A|@Gnvq%|dgINadq9apm96o28OB}Gy z&|91lMp=nD^=z`p9&4PqtA1SIfa?W?NZI{ll7YKPIagTWCY#)4hmpHm;alw;qs%kK zC1%-RnY(N-JY|85Gx#>`8RHU@^!vXiR2aL530Y&49rn0#Pb+)7?+J`EaxbTrjr%yX zT)3|lE_;7W+X{}~PoPXN@D6*-D5vi)P#$NV(JP#dcewux2^|eoW{aT*IK^CI*g!K6 zIyp?R#Vk8)8DO7%CXUJAJMA^&Y%;@LmN@!g<1@t$^X#+C;Je)a4TaddO#Bdg#wiw= zVvTcbv%vwk7^(<>aYi3%LhdD{o}q{7#|bt$%N{EXz1sp9XYt{O_y4d$q0G@o*fU1i zWro4`IK7Oq!8A)V0^}xZ?6b*Zk2Ddp482zd8D*6T?lH^Yqs+%J3pIsf3T>v@W0j#5 z6EMy`GaP%glrqUW=h)#A1Mia&#yFC4xEN)QGpsPfI@j6ZcFO(lD~vwIUccYrVvJKv za+WzRvBEl=++>IQ417RfkF`?HGsPzJ?6S)E<1CPA4wz@8>I^*2{f{fGsz`C0Wgh=; z6LFb6?mk(7A2iTYq>}Y#3yeKhxc)+ilFRcB7q^+!ug~CzEbv7Z#%ZRRW|4CRg^I!k zn+&|zgp4!rVJTyji%fBqd2X`GeKt7p5@&`<23NhH7-N%Zc9`QnD-7ms1q&&Kj>7m$ zb^M6y#0WQ-WS1ERUuN$aW1X|?@C5r@VDO_dzzDlcaq{H?W`bodvT^u)LBJn%{|5>K z6~R}E_+t(YlbmOcJGQ98ebzZyG%;t`=N!YekwB3#t}@LQi`-|8p;tKrOtHr-10OGl zSRwjx9hhLBSw{ZP08FvQ1-7}w9@iQAgiO3zKlYjB;-ZzZ{2E)z27BCM;FGQ)qYS-P zh6)PP3VF`3%sDo=#4gtvTyxkMW9W5O$OLm-XO;VGajGOUOfvW>hnW!;ndBOC?6Oc% z7%0>kdc6S{WtVvdKkYO##_>0pm{ZJgmL)E-$~qg|W1HbOS~;@}eMX>+Gq)sDOuxzf zFDqo;B*o0KdDws*E;CT~O^9KxGR8F~dHl@+Vc;zS;20Z>vdvW4+2ZzFW#F@(zfC{R zGRMZ-4iA??{Ou-YjXl;G_?!j|v&k5DndTmI+-Hdgtg^B!gWP1F9R@$|mHiGY=g2$V zCXO=Cv4TQbVVpH4*k+PFrWjb4Du%ho1jpVbg`8%YSvI)DE?W$K!4_6b%zb8fz&uCZ ztse`c3N?io+l;fv1Os0b2*ccEf}`&-F{fB&h7B&V%enX3>o3`o6%#Ya6hq81%p#{* z`;z;AOrfb_h8@nb&&l^mb;BurzZ5h00f&^+RqYPzKWK$twvrFo8pfFBG3MB0g^>>% zpHX%gW1q7Of5rVjt`Pf*HyM+h_^1I`{Fni_%CHF=j2#A2Gobn;dz@qFtJ*Qn9y1*K zxWJiZon^MT&OY}UE^HX^69#6SX)dtH4c2(#leUJ7?6JbYRWkG`FB0aN;s)~^u*&eK zO~@h#TxRHN0$`lmEMyb{pAjjOtaFDQ&eToxb*W;Q#~I@ZCRt*RWtLcBl~p!4^I2zt z#n0QSrT`gZVBJC)S$F@7hZSEiF>~xN&pwL`e#1nJaE(c>Gs6w$xydqDzHDN)HcZUX ztMvb-g)zqIubG$&EVBPK_rInv_jM`e76;sB=vy+uC<9F?W{_EiSmgRQ^k;`{4%lP# zn=-d4a}2Z07&n;Y=(l8!>4HL2p}%RxT>g#@-?kFQxXL8gm|>eGc35SX4ffdPcFO{| z_I(-qjx(|)aBeft+>i9*^v`9Qh4inb=({FljG^C}h!e~+!(hu^?Ya#DoMu&hiVfD- z&fW%-2a|JN=5K5CS;stX4qh!ZB{s7i;?ep6Eexb zNfUCKC8k;DJUeVN@B)lWt*8F6r}u=2~}*c!N6%NVwAxxrv^D^{f6En^XQ(R=8bym5upd!vDGu&s1!M}=>C)i?@eMbJ~@cc{w zOt8-!=l*UY&a=)1wz$YHYYc7+kP$ZiUNEsjQ$>o$2U5gER=LI&$Nphr#+mrJz5AyL z8T*$B8E2gdwwPp>a}54MK#XvKaW1mPaN*xls1W>*6f(xhFTIF{QpnOZd&3+fBfVjT z$Jk_=9WFC$qB>LhZ!*gci=4QmH}pjy!6=V2#Ul)+zF31iGN z$trVfu*44Q3?3B_CmHy)evI-2Q*1KN4$C}X?bq&qC}>40((G~K+E(-%*N91mu46*Z zvcd&6S!IuV4DA?@QI1`=H%xGnY35nt602;p#n|?Ea=9&KoLwGg@DIjkgv%@>6`Be;?z6(NF_ALI9yb~K zqrGF4116Zev3{(ErIw2~6)2b3<1zz(a#k2+lL@w%W^%me`@ceO+)6oe3j=VG1NLtz z(p`r#B14QZ!xOi*r(B+J__)FrL$|Xf3^Vv=filLx?VTl_V2*Pvaq;#Akt?jLXz|#8 ziTE$R*)Yn{yVw%W#%u{E@1{Ltch{bAcDXfW!jm#MZG}wT&sK2k{xZr*)_IIAcG>5k zpb+ed{0b}O@&ioB$^#u9R$1XDo7`fDBM%bjDJy55@uUng!6rj9wt!&Z7DWp~fo59xX!V*k>r^ke%@lky#y?e7qEL{s{u()DvaOM6*nBo-Orj>~f0( z9x${g&?jln5(8)5|H@PC?O7{-nv`*cMK)Pui%l+MbvS3w80Pk~rJ7^U(U0RSGXFfO z=G+Tqid_b-cE%WH`6U*@3Nu$1yy;$VA{7&F(1FL6MB2CFHwlbmZ_$twWtrk6tBk%~ zduACpFN2J7Vp%2_ewX%)R0MSR^?PK5C5A58+V@&OK_U7+D`1bciw@TZ418$S!21UL zkiFyThXr!zstKfUhj|7*A|Qs@V2o`Zu*dO_dLI}+#u|%kv&zCiVP7F)!r;fOm}O?U z$|46Wn|Q2d0#32Z41<5QC5*AcB)6GkpB08bZVOprk82G4%@%*${SPYyKOq&I{G^Vo zu*w!29I(sCnhF1Iix^{;N%ooN$fpF#Bpa-KT0b^9;7r{D2hIjlEY;oryu#M!O~{>f zsprTSMEDOYWtbwgm9 z&fDE4$;L!a~E3{O^diIFRr%VvIB(TCbo6NAqJWrev7!R&?iaF9Z(cyE3 zu5pP!$>JJv;(|S9Zr?3PaaE@qeWrl6` zZeYA47JTWcVWFxpP-t=dG6OPjxdD&L1QX0L%kqt6f^7~C2VzM3;EhlDu*pjT5hi$y zX&z@w`#uMp4qI68l0b$@u7yt({3@h|H?cA&ir_s%6;W0bjw{@h@ZUDh~#D_g+qMB&u1r;xd=j@Ok^CK$Y(6?2khZr$EW z7>`;Br|)2bQ7LDNYs@ovN9{Rvr&E68@e==E@zk)(8iUspFe4njiww};|Fstifx9{! zjI++;>@adSE4#jWhM8uJOH-$O7NqC*lsQIOBkwSIm;XiJ8>Nq zcG=+ky>;XQ2i&-im4+?}gzsymY%$N+{iKqa`#V(Jze0PCC1mnaTgE7JOmK~9c9>)I z0Tz7eC56DeLgX?jeV_?gXP(=vGV>r4Fm+7IE;rzVJ?9#$Og+Sk*?Oo9jmhMUc8oB? z{-f=+34Q}v(ANAI!lbZWx<=NXN+V2Cj+d#+WjvnY`-6D!A zG*u+Hw<2ZSeV>#u^nM+gXOk6nIP(DkaFgL%nt(Bet1`kkGfXkhV;{5tX4zoyLo&li zL1CaU@?n8Q96ly^@DYJ<{-Xk6l{L25WawjFT#PbsD_i$*{aOBmm2>Tr4i`6BVPs7| z9&o^|PYL+e?tk>tCQ_JVg@Mm#$nnn_@HSS?Go1vzBMoPR2W+zZWtqIK`(OX6J-?lSH$={nt2E^7*Bm;QzN`NBmjtRU0djlG zwTl|)hXUjHj|9dTD?G+JlWcL0ea`$?Aa}43=D5+;?hXZe_7jn)2>euoJ4)5hG+^+T z24KEpkN?YIVvH+Ha+Mh_{6;%YcLh3WVrH58qk8T!cqfPUPcp^jKYPx=Uu{1mCN4WYEOMPSPF!vtE?j=v-~YRZfmOsA8$0cT2EA}tVw_bb z*kF=vrr6^w1NZdmWtbVpc!Ei0nPHB3&a=z~*0?xUI6Z7CEUD;ln}K`zF2ykCZfM0U zF~?<=IDR7mv2|nZ;sy?zkb#?6>EYLGu)!{O7`(S@cT*W*_Ga4gMB(OAcpoXb#c3ZL zXbV_p@Rq0j_L@Cnmx~PF*Fa2hms#c`R>A{zIdZGhJ}1y=XLQLJl9!%U_nGvI;x1>(;_=V{OV=gYvOy%%y8#2se1{{n}P^Dnd@?lGKld#)^4k;1~f z6>#Ro2I79+${u5dFLUp?&I$)?ab!V2kL4>(z?^aFoGS{LnOCWQoJ_sigbcq%W@ml< zUWb(%YXbal87h2ALxmozJpO5^;nrvD{o_sWSphKiITP^2=S{$wbs2bq_X4xbeZj!& zf62gU0e@LNqhD3eWe!+j=!w4mn&&K(ziwiM>Nl+DNjiMX7Vy}nRQ`__$G2sOO_o{x zjsV&Ju7QqAWy{J~y;}Px+mgP(xOm>7-ZhyuHm3gHz$5!;ru*#Lm zGsDo+oP|4`@quIohw9E}h8Y#1yBL7utZ~3D<1rncZtw1DAa+<{@$P4a;S*NO6bH;Q zJY^gnXN^<$Fb-!q;5H-AFz>_8`1^kf(TATI_L+UenPKdiQa@uN_E_Q4BhUDC8841U zSsAkoJ~Uv?>8$ooI5TW9|3v+sZJ|#-<72+Gd&(I<|D(`Q zXtVw7GsEO_?Dccc3_DCc@60gpzwYmq0^@*5X6H@F>Wih6^_S?+SYG=%D}Swt8F`(F zxWo$UCGFT?k0WnB@f5^*O75fzSYF6vCIZ*jJ#87Sz+k; z&J5#Rf0s;ht|Cxwvdt~_Sbujx#5sHR9xG(}y&`67MFzO|K6~{7sd~QvxyA}le86+& z*k_f&7dniLbDt^BSM}ox%WSg2+6M)~UO^#nr9J$xlyQ001l;+U2sv7_qIrAA1Q$Ok zK(4I`fTN%C{6$vCB>OCK?=!}Iu~&B8Dd!^7Tw#tQpA!fRqY7<>G4?plz)M^ohPmHx z+8O!s8Nb`%^s>dtuShwQ4CUPhCOChUE#a}RJM~O`Q)XXk{7v;d&Mw2>R{t{hzod|P znM3t`4LH%3%9qOo>h-$uejDZXyQ%;rXi_&cNQV%^ijo zW#k%r!vvGp*&Eil#U8s1yvFnE?hRvHW|9ZYGcda6qns?9g@!`%dOEz;X=eD)>+kuj zCingZd&34>p}paNoy+!ynb$dtVx&pBYwf zX=2t`V<@uc_x}$cM09wAy}Q+(UnFpinCH^1_k3iM)U(CpZM1u%!!%)FR&TpEEHZwF zyAhi})%)!YQ*ZGCVV3(WbMpQ&#s&5`b;X_!F7j{6hkDNR!)5rb7Q_U%3p0B@ zXvisjq`hVJ(e~_X@ ze1{j!oJ=wQTnpmd3yk+p_dlnQQb@hfo^a$!D`bqpcd2KD$roEGLoc^NMqjDE;@Zk! zhOOeBkL~fESk#~4*V&?XdtNdzTW@fNxbQ|Re~&GA)84T3p2L6tzuDfZsBysRTO6kM zx&@z>5w<>KpcN}%nt{3j8DotpwwY#+83x|xn;Byq`@D=W%reJWW0cMJxxYz;o{Bs} z@AplFac(ig$hws=$~yDxa+|>q2;>VU;^Y^th`9|J;Ph28RCO!9W@3&v^<(23+JDfv zKN3hmp{CGb=Enl~ko*2~6LN}mF8o6MhXwXaTfioZobPzf4!cbL%3iMu@YlAK>nw7E z6{db8(;WM)GxiaOn}wpn`tJq6VAn(+mAaE6X0oRP7f)H~$Gp2w%M6#9;mFle&!xVJ zYregnH!+W25GZ$9;o?Q(v;B8_|8ao~1jgFH{jVql|6w48|0Ok_5aEFaoM(gE>~rfs zCitWj2G07)Xc@ZZ*To*nktWw~l13yw9plVvpistwZ_?DgR@_eQl=UFszARg_1xPK0Ao%4H{7C4 z{TTeVejH_cqu`KzPlv0d@P|6E{bK`t&EB;|$mO3{83#WT7>hr*_g}Xa9RYLtHx6A> zf5w>kofLDIb&mhR^KUr3f6|Y|llt+1je!1XhyKhmF?P}dm!ReVV}&iYx%w>qx%RArNWSNutB7)g32rjYE#|n*5_ec-Ix7>0^$dMq zs-Jz%52N~;Meee~eb%|~92wxq|7!mOTgW*31%;f#*7FR^`4@-yZ_;a z)Tu~ZWuTv1Im@hn!^+wDrWF3dsr}BmVV=RZ6f?otFTIFfLKUnFn4cHR^7g=TKl;<30;5YtdblS=| z$t;&xVepIzS)>me2~3`|Q07^vD2!ZfARcGrw>mP(xxP#=&l-E|Fm+z!ztf&kHZIsA zrY_n-F0y}E&&cncEyg*z?|O2KS&r|!|3!t3zgjVSfAd1=x?Teja`zu5=Ei}@|DeOa zrIc|dd7K&6hf>UuBUcZDf3!7>u@Su5XGWO#+E))7oD5w(jQ`15V~W$E!qq-B!XZ&n zWSSLbS?4@kTw<4rORx5Wi86Ef)x+ejl`_Mz8(lrDF~TOJ>@dbY;|%`U_>6F#aV{1V zQVQ$La{9&sIBdW=TkLW?eDyH&7XvfODJHnfJoi}UK5IN+lOs0~2uIoH7=tIhu$W+B zTOp@#;-)6#99x`cmkS&)a5EG49400hVw%TTWRevwu*m@j+!?phQ_jH61 z5l30$7@Lf;!x;NK#^5=DGQuUs*=3G3|NkrWR8$YW zgVbHH1$UG>jxxqDlbmOfZ8o^WHbeg<^*qMVMb~XodnTA+l6lUu%nWPHPP+e1g`A2G z^Xzl$P9ok{e`g&zau+FOmfgepnAHDO{as~(6=u1`GAHgXFecgK1|xqHFyl;3$pB9j z6iNztR=LCmt8BB*9vck&-C<&wy?Y3Z@q1bc6Kpcc4pZzi&EUX_8DW-j=9pq3uaH$Z zV1*<1vQmz+#W8j{&H*PF`iE4oMe|%9I$(Z75v*)FvC9c9I(tlLPi*5lOcAPVBkN_!UF_cP{=>X z11_@95`#l85=Iz1CQ{az<>0{r<4RI{W*(+};7FkO2+vuYu@KHa(n5IbQQEW478~rc z$-+RPr4YKtkwBYKcA4O@M_UnhSmQ36++&CP?DK%ZYaa1?{{rSH;~Zm(Y%aDm~YM*{t)8i2Ws=Nx;Q=PWT2JQ4^z z-9#K^iet?31k0Rbjq_|Wa6+ay#^AM&1QLufSx`tS?6b(_XNi<6Sq-jZub5=yIR@t3 za|Oaa!`C&?^E_vY86IbzS(ce+jYT%O%|3e!jvfgV_7x%u$>$r0RTf!eg>}~1V2e$5 z+2Vk0hOT!c&|#EaCfH+|edah|iGiFgmLcMUugwgd#MR- zpyPson0lo*BA0AkJaiM^73}F7 zMW*7|k`CN?lP%!pn+WbD@#$Z1x&`WuI+p)m71 z*X>r`WPdO*gMYNgY_rGapX}YOorPUzf}5wTkX_cf&laO+w7ZQL4C72P#XPetvd9(I z*eEEp6~bqAm@v>e5wdo*Gr+`oXW+IvGRh?;xW+6SEV9W8gBJwCNp?BK0n-fKPNpx) z7$;d`VOOE45c#VHx3`CkGWIuzjWf(~@9$R1HJ^ksle=5E;^ zMkWn(tG*w%bJ}mC9~bY`_gC?~0q?Ayxw~o474{jphkkdq)%WWUb9XLS(F6L!u8JCi zcag#e_J?t1nC0k$`okJ$AFMv+-afQHEOL_-rjq)z!O&fuYDT%k1d|Wz5A%ohGsfW{ zB@k8~+aJaXcXNnl`@;;^|64RJjd|vt zrX3?s@B3Tw0%znN`Z3NurnqpTKP;3KI?t3MPGtMT4v(?VDuefQO&DQ~ajrbOKP<8S z9Dy+SzuMi)N*QB~8P=KS$ee(9oc+UkM&dFy*Z2Sb6`CqiY%$9=iwr%_1gtZ7Z-Fw# z9+Mm}!{GBx#0blrWrNc>8N82)8RZgFTw|VFxkBF`i?>%Q8tk#nK6@N6a9@Y!1${q$ zXClTJVv-SNIK@1ZEOVAMX4&LCJ6xx~Y!|4!P#~-o6tW6yEOLVt?y$*ScDTnr_ZhsO z)5{1)uCyhbV2W{OIbfX!Y%wtJkaCm*9%JbK?tfh&rO;%Sqc72sC)i_)kt?k9rP^`i zWmd)w_PO|Shc96-ndK&nJh337tg_8Idu%iG02yZd0q%e36;h}o!aSGQWa5H$yfE{)?{uXB->3apk z1%;$Sf>~w{EgP71cG+g|VN%8zLvIxbV=S`uHi2_>*?1 zHreF(`vt^__q+e0M_GxAC{HlK9Mdc^$I%Z+ImfE5D_7WH?1Ls|mObVfc(iN9D0i7= z@I%Jo9!nfsm051Dy8oe+!}Ad)JBK;OC{7MOHYvZtofXg1{bUye}Gufx?#zq%d}siDsRC#<;^Qr@!Vb9M-dUSkK6R z3-Id#=022h1u^~slr0bp0LVDTB^S1 zuyFYYR>Xr}S_zN+#!5KyXBl~-GjLLh89t+)yL&S6BpE%cp1W6@m=ou1?f*E8f0cTs z{wcuY?tlDWuE%i^{aeQ;OX+_cHjW3*`@unn>6+*L!Eh^Q^eI+0a(#NxHj4+q?4G-KTBoF8U5!F;CRv@4WVK4dCi~oC@R_!Z5srk<`?K5*AyZsp zg>4pE3I_^(PTxd_XUPQPtTDqn^K7up12!1H>G@%g%Qw?L>sBzuRc5)yBG*~r2J4(0 z*N?gJ^X~t%HBgaY_U0zy4jath!rpP@mL_3+ih;tNrAi^lBF9+aIP08Xi&O0K7zf;AET{clP0VqYIKe7Y zY_P#Tn+(3dSz?53##!hnq!f0UWuHYR? z!9%Q^Qx6pYN0Z(IFL72L=9+Qr5ys>AjFsmF@<I z#|-ybWZ*FdD2m=c;$1rm&BovkvvfN>X>Bs5FG6!5?=oJED zlX`=kKiBIy zI&z6srl0TdyxN|=zzVs{8u!@du@?$}D~v2UD@=0cO5<>q6&|q3*?IGEjiJ{Fte_B8 z*kpojrn$o$dn|FERR&&U1sr9YVfHw|z-#qmn3H)KWBp|U;{3~P0rwXyfU#G&O)RXx z&h>kpNLc13YizU0iT7y8&L`bp?ygyB$%;PZbaS*WQ07@;?6dZmyI-`z*E=&`vM`pe zvH-5I!5(|BcmGGfZooGkWk1eq`ANxmssL5t6X7&Yix6!J#H}YHi0qB(2uQ{VP-kU8t2*M z8VB59=>O;)(YI)guVNO+8aclu{H|DBb* zM@pIE-0zLUKAW8H3W#gFGW%X<;m@A4#RdyAe{mWW<{4RWy_n?mNf}{+6((6{iY?Bu z&y}74-{(!oG~=hdM_6N%gVPT0`(^Nq%rV0Z=b3-M`@f)2R~^t&>1PLI!xER;OBFto^|%v zVszxfu*>Wv7ls4Yj$RmsKVol#7ltubu6tpa=fVvx44d3$pN-2d_*2aKU4FrzV)i~6 zyD&_0{D#^e*0aVg3r&TALXYK}Y4|bMjd@OtUl>-o!S>wS@XH3BEBV~^JY;p8a0%16HVHo|CL&+2ykGU``vo`BF2kF9vVdB%y zz!Oc(HtSseA1VCIkwB9%P9MMEFBVJvQ%u156IN2U_iS?hSpxg4Ey-%f^m9$X6C7|P zr~Y%sVUgi0J?F84Lh$qMCllNiP=mQed$;a1GtTJibY$}lI&$NUR`vz;WdXDJRugfF zp)bn7J1mIfEOUdc!}@n>$1p=*a{nh3q6#DLx-iV}7%Qx@#ZC6vVz40tjBvm>BNeG- zlv$=&WSSKgS!anYF0sop2MzbXp%D7A0p2YGOft(I));z^!^a#$U-3#_F##u7VS;s@ zV2ed|xxxXP41LvjjB>yP$KQ8hnEtB!pI0cUSY(wgwz$PEcNyF;@%ycu;SX3b<5ht$ z`XOh43mkCs!!mi5>&QHpS3PI^qXPJv3^L8+$IM$etWaojpB)a^=K+IX_X4V!m?u6i zGhF(FKzYFKVf~tcn^w*QOH8xO9G6*Qg;j2UNbnjj6YQ|~Jrn*=!kh6C<0x^2AQ z36yicw-C;EwPTmzpKJdIfpFxHo);9_e{#Kkq2kXnz-?AI`WF#$oE^?H^h@oTWa^}V z*k_B&J%M+e9Y(mrG$&3uBZptJ%j9W+{L0p{kWd)eGZB~0itN`8;nfZ$)90n`H!^a; zL>&K{cAR2|GwkyOgF8~s2$vb>8dKb4mOCtRpB0Y&-TkjCO#R&oxXA&x82YVDFv>0y z>@m$ga~!b5-GAzTSkEpGIN-{^1oArp9@ul{hT8GiH7^dszjq6+S-3b%DJ)*=;;_u* z$i-ostMmy|f%qjChjFeRy*Mm#GI()VXY$$?hXYPs=b|4(_R3|EQ`hyJfj(TbU1 zmuZHsryXZlW33Pp$)7~R7;~3i9Ojt3?BcM=6gymJaM!E&a_uU16Z&*gZ8o<(tO6HDs1~ z&auooYg}iO4R*N8z-fDYpNqpNm+vQooPLmYoOq}VpK+ERuAbFLTpX6TG9x2r3id#u zsbZa7HW}E{;8FIDyUcO@aToo(ulmOu@T`H43y|6WClL0Ysr@+%m=h?co@<<|T{Fhm zV3sR6<8YPjg2K8&kAWBH&^G|XOfbgdOft(1=b7gM%UooQ%WSgyLa9IRA1qheDh^m= zV%`>UpMBO|ba7aST`x?1jNEv*~%3r-)6=Cw&Hi1m=o`|GVZOI;6Da@ zpFp_wetXHKkEkEIwjY&2_SxpvC)5Xy`a=aKVCd6Udgx~?@ES)0)w+6~_^k1-akLN! ze9nqgR2aSH(Ln0+0^lAi46j=`kFmuv``lspT1NxHFBq6pOtQ!vw^-qTbxwRyf9BZd z2E!wTqk)kx={O=nW;o6~qbzfZHFnrz=_-fklB0p$uUj!w-xBx{fo|&0T~@gH9fy{! z?>ZAlj|Sr3vqjwbu|T-d_Tnoj zMtV*&r%!p#z-fp1dNRcXXU_ z2KR@7&`}@3xIavCof%fIvp=kGgH7(U&&liV4$Jl?|@3%?5kiWZ*_p$S`*pV~bX)ZIzIxE~_lRfsh$H1+R`g30UepuBwkG8cOOBt6b zhHv8#vyf6)eXK~iJ*(q{$e&;$Zv2nPxyv3;9CtQu>x?kYC8jw3WP8mhD?E6LJ!U&& zt8V8#@ig^3V3&(e7r^bk(x0(k7-kis&vc!5;#oQ}^&EQ_wemTsJnv?VPl)EpskUMIhmsu8B=H^R{&-}|Q3RMau1#H3_bDt4usl8Rj^d2&)(sr!4Md(YrLzkPhY z>U}?-^F9C1J@?L?KZIZhv|UI;$|)Ge{)rAiJFJ5V&<~Sg7fglyFaw&BIsdacuyc?P zlVKsufW2!Y=8|g0DZ6r_CV7jh927CAWVkCFauhiq&yf8i=h)%E#mx7 z=fIDV1-oD#?1ye>T17DF$rgFfhoZLkZPo}xUM1D#9gKm}6` zO-~cQq?A?2K@Ub5w7JL#Ghi4N!?ZusV^{=xU>&qv#Oj7AuzD>8!Zd}&2YX>Zv{cf8 zr3^i^!xWedi(vt5c!qtal!L@70xqWIf1yIy^&APXdmRl*VUDX=q|oyMX8|mMEwBdm zz&bbx8=&P97B6%{KTLrEm<2mv0qlB-k%7)vIR8zT(sB-xVJ|F(39nKC48kF3t0R3G zQv(ZN`D>)Z9@r1fuhY|1_6?W_b2cy{umd*0ZWw?e*aO3G5DsnN{I^`j9M;o9*aa(~ z=}lS)i=gFlhIk`Af%y$I5SlkpFtoz}EN`TtFu9p>uAriwG!XW~4w$r?kxZk5`zc>A zNQ19ru?9Kq>>Ri|XfgD`8rTL~U=Vh|P8fpSa0vE7+f@_*6X5_%gTpWfnh#PQjD;02 z9@aqz^uq+$1(QlS=;xsKJsPr{f?zTnh8ZyX5Iu(e4`>MNgdv!9m*v6^8$v}Mxs&xwN`SPXk$3k<^^Sp5YJzK*GeIWXxM z^_Fsw(Z>+O*smzydNv|hEci7If_eS)0CvFS8#pWeNe^K!tb^JAq5>Fzwk*~NOoTl! z4Hh0}ieMY`L)$lu>@S&8SZe1Wk%MIDf*CLk=EF=_40B)=EPxF#>suNGtDx;yELxZX zQ%^9rum(0jKMcS@*aH&=IqzX6wA@HX208zo95i60z+RXI&HqCWp&gdNBv=E}U<=HK z9k2j~UKq&`K4$5H)tbq}Rb_x9>Baq7))9|4W zcEJGb&*l8@qMrA11>v%z%uUmJefLF|@-fm;f7KG7P{}*aI`*Ak2Z5Ti79C z8Z@2ry;cO1VI8c8p;8VyI2eM?QQvFMTM2+EFa>78G*|#LVHwPUHP8)PU=i$qB`^dl z;1H~Vw%fRtz%-aQnhwAMSOu$Ksh;qg zXb5z`0+2RyqRfY&6KtR81fb7DGR@Or!yKGD0vJ+9#DVBplRCVlH7~ zJO#i8=)8-m_!$+$B3J-@unq>GA9lhn*aQ1vA2i*~jtA{<7$!r@x!-FUFdpW^1Xv7{ zOF5|GAQd*i3>bjfum|SDL0AYa1@r_uVL42JRWJ+I!UEU;%b*X|z^=)RB7=#Tl1OspY z_P`-H2+dQ;zl!tU#({Gciw9=GJXio@r%?cGgZ*$2nhI%{gQ0~A%z|N90aMOn4ZsrE z11sPltcI5RSQF3*y)Xp^VAg%5EUxJkfKfD)3?cz0-j9Di0fMtA7#1dw4$GnC0j6v= z>98J_LC+j|DtICJi@1ElG^oHFSObe-J*2OW#a@E{unOoJhq0|#Ic9D)_l zyo9NMHt2^A*aZ_|KXgIU@0coRhnX-L=D-Z-hWW4v7Q+%)TE#&H2Mw?q24EfRfnGQW zQ&X9e)htd}25pxS2Zx}=Lys<}0@x3W;m{T2hvqc$!yrulJ&W;5Is{$I=?FBXbN=^p z5SvcRA7b%AJ4}Gd&~`NyLI%bC8L_A8;}itzd{?dL|XZEZ73`UA`i31a!b;SOg2;5G;cU*V91ghAl7%`=R*; z@~}g1FbIoa7py4d{O{$UP8he+;xe|-+n55F zdMAqv4&BWndmO)jg5V&`fy1x}TJE7B7!T{96Z&Bi?1Cws!KT@%m zgM19vDtZhn?3haetupidIFl>Rr`{_tIQ}zJm!oecSh26hn zq@m)W1AoGYRizwQeop|j!vHLUJ<#?L6+g*bLnlmvDX;<-L&w8Z2n%2j^h48AG#Dns znqsCBCO<+0p$B%rIyeYJu+&n)Y49jR3u|Bz9D;Q)_Av^4nnebaVIj=23=^suVwm+j=`iO7dI(!yq(N1j6)#aC%v?{p z(6#Ive_>=xIY{K745q;vm;=o(Gi0y``r*JU^!Pa%_9_=07_K8-=-21~Y}ml!f=WGW zWF2ebO&SD)umg6%5G>wE#no(R4U_{*eH@f=khF=pfg#ur^EWf3&yx`r!G2f)i@X#F zhoI>NMxu!dVRwupiby)9YM2pdFSaG51h` zMX&`{z_taaO0_NyvKBJe8@P>zIWP>1VBv-I1P;M|SddJ?^;`=UpVHFcAk2XkONfK6 zi_4cgwI126}crBEL9TuQ~T0oK96^io>*CL6)eDG+AC0+@F-a}T><7p%%)gf>#~ z3PuJNUC*LyV88e!1;Mf#Y1k&VR%nM^zhQ)6XD)LM%kE?mZl;5<0H)nThhTB(DgqlB zGS~onVGr!Mk2T>X@Bvy5>sC`h6Akk)MbHhaU?FUP>5mZKOb4J7<~&NzVcKJ?0qBPP zun?NIaJBpcYY3KlI4I^|5Vk;b8G$hTM*>X2T(v4{h6MF-(LWm%>NPYflrz#bS6 z2cZ*MeC%-036o$7Oo3T29Tvb$SO&9T4a|crr5qG+&;g5J2zuZUEQ7YUIBj4etcGc@ z2IjzeSOi;O1@yx@*arQu19rh~*bjT5X*(T-b~pe_lQ|gTAOo78WCWlM7DETDf{CyJ zx?ljN!5)|i2VoAh>|l{WCoF;~umono3RnQEVHvE0HPHJc=YI@v%1uz7Q;Sel*hQ+j-k$IL8gxRnd=2tO-u;VYp!=&fv zP#bFiCPHUvHABNe3M_*S&r<oxStW-!xX~OhJ6@sb2=TM0nqjyfw1QTDsE>D9L9&) zumRS=5RC7lCqYi5zcRKv)C^Vd60w+`&-7G-&>cf}!gh8g!7e2@HbkA~rFMh z&3Ty9Vmb*hdB$li09~*LmN`#r$z3!IX21~4ho+gQwPKhCtAq~&(0e`&gZA0P|COB* zR=`?V2OD6ip99O>)0*jT%ssTjHkbu_V6pHMPxI5tOcCsXh0t__3SbKCg9Xqrj}e0T zFaQH^NbmyUx>xDGTTsY=K>{4fewh zX!?lr8QNh8Cc^=k0f%5dG%uth&<3lZ6E?uI3rkOHgB*A-q=1hZ@=NFeOiHDo9s(|> zrOOP{gjK^J=6nBJ@+zK9Mr)c*a-)reH9J+jF!VRSOs%n8!UpBLV5;=?;{?j-%osq z(+{S>Zdd>v4^R>8fnCs9#1z8<==_}XzlDR0&zUP&1k)d+V3-A4U>@v%1uz6Xa0oh9 zQ_&Yp9V~`ESOo*H1=>7}1RR9UW90umYXO$PVptBVj+N444jM4h9;O1Q6f<;vtl~%L z0rbE!7+gaSV9H|@3{#=$ORKTc0z8Vte$*bl3q zshS4BE;s~j&oc!Bj0nt!C9oLwJz(m*y)8G)yf#&s$ z40OT@SO5dC8uq|?I0${vGDtbl3437*?1xz}wU+!a2m`RAl!G2&yiCRa!v^sRJ%t^w z(J)x}I{tT@W*g`ctbUUo!1#?+bdo9CbXxPn7BBJ8)yx_QGo>&e7Pe3k9NtQUzGrc6 zqa!e}m8pfLE)M)0q`@wj3HxCVG@YU$K1Kkhy+zC6;C3p4#XIQPX-33Pfv|fg<-i`; z1$$vX?B7KPhUnNH)&_L%W$57$bpF8k@7YI7e_&Mym?M}0J75kB!CvV6H>-F*J%i=2 z2zp@+?1ll@4||~LZKeViz{E4mbvyAeBS`r$8+O2a7&^oGU&z4_MlrMvv-7>f+(REM zgGmSI5ln&oFddqH5UhtoFaVuDF|shFl!Ns5Shdh} zh&h3&odm-A_gOR=tNsHDhQ7lT2)mBZK$FGf?`BA0@+Yi?b1bF;m;y^+KD2+z*#h%n z2zsG?l!Y%SQ7+_bH9Y_4Ae(~@VSGUWqb(-qG3FW;LO<+-gD|;|mYXf69+(3Yz9bH2 zLqE)iT`&OcV<_h+m)Bw{KEaTVwU|0#GIS5p1L*r7 zdJe_Ec>Vvpi~8uVOy`tLKWAF(4BbiM{|^2OU9(9Wo}m8p4`ohFCOYujO?(bq{dSfz zCs_oZ^JrG4o^xF7m)YZmV{(WxL~H{8h4MCOyvJ*@e7%3HTJn*S7BhfbRj`QB6AVa0xf6utMjKTQ>-Fu*6vMO!Dviv zzq)&gGSfPMS+RGMW*3nw-&S|up-i#GkK)sh`!;D^&~o?NV^zoJ%FH-~{q0R!5>2+W zzO5dePIeDw;=xT?FTJvy#GHXykJ)!%lNK+^JodKQc&jpXDPDEzCapwxU%yQm{L6|x z&-Tiwm(A;pSrVfeCa&bfCe3dp?#$cj+8N4aOT-kl(dwGZHfgCMW9I+PC_Fdm!Jjs1 z?l>~G2Gwb^ltmNkF+B;J`GIQ8(s#sQPk&1}U+vmjIc5TBEwP)mdNC1q>uF*lu821? zxf97FTF@?h{^dj}99wO9KIVnkTAOYs@&9z=74(qeC0f~WtL*LdPvEc zw^^$r%5vKQbzC`PTZ`F+X%fSz9vG|U9Z-^^#A--Q-K0)SP^LtA5JeYmR+l9xi(Lk?H5CpE{Luqm$6R z8Dbpuk?1D6=-SO%tf;E=U45*hJj7)GVzYY2sZ6zTY+kXMos@u;v_<`qVy)@eh1hk% zzMB!eOPLyn*M}Dn-YTQ4=-6mhd*)`XR~`R;rQL!`xo)%OQa{P6oNVnTM zutZ{G81RcXX?g0NO_h`9CL!~FwOQ+%%QD@9i##_@d`)=B-^%G=S|BkwB4qH(nW_=FTO~73D zj(YTd^;#ALhC(Dn8<&P-i~=u<-}(^#EO_p*OCyi56dm*V!38IF~bk*Yi7y> z52C(UE}Cg0i>6j&d_>OLjCa*FD=96AS&r!yqc=;R-YM1rOv|IRNi>2v7h6D#!ez<7 zM(hi!zA#+qx)MfAEQ}>GXC7wtA7mXgZvKnPR102gDGO7*Znk1iWc&1@oRn=EZThdh zB2}c9MV3)a9#9L|73_V*<0GWD^QoU`#r1(_kTE;q7TQ!%{}bD1>Vn4J-Gi8K|=frvR@ znm)|f=Vh6*q}hv^6fvhs)64*6M$Ac^5c8EOch_SUVuF!>@f@{bxc?8o8$a*=@CWd- z|36<$f|;|AO4ZyXHu!}96zTsd-2W-c|5MZ>Xoyij@IOVL6uXm@sinrTChmMJjqS#U zEjuKd;U#^D=IQAh|2w^tbmfIcV+Yyr-{}LSXRD3+-er09ztf}2CvxXf)2JR@ATDGG z58@2Mnu##I*r*MQZ6&u|&0WOpO9^IYEo+Z^M2m{~kTTEe!*sT>h`4-PHoU8@U5Gh= z=?XMzVR0gUZCte`IwsMb{f%6AFi(ivdDbTGHxuNpNm#gTvFTySAD;Mb_vU8u~MnTK@tH)=_d7%0L#_%3{(`tsA2 zGoraMGzE}7>UoQ~Bg{m0|C64IrnbJTHgfkCSAtppZKKvE%zf&vCCd5HUcBT%PBHbe z`;}>G6@Th>_Rm;zSoZ&@QPe&_XfJ+;$bLxAKEXk(=R0|Z9?`>P%X0fDCW)O!O)%8NS5#3Tmmm~TKuTmFGXZJ`#R{bD{;`9OI-Z~F6@r*3; za#Kx*@Dd0OSSb8>=>4lwwrs!fw7e{#loqNw zzC@XFz7I21YvfP4oc$-Js1rZolSZv@v_4waa&+c7UgOg7@d0(MOF7?)7arv`R`C&P zX&YTRQ<#3U*H|ys4x?(@6ozxGmp>3g)hoov{m8w9H5I!TyHD7wJM^_>EyV1$czN-N zxl)?7qJS8$mMzYW+dA}Nitfa0i1liU`iYwr*YYU0&SAXR@m_6E6xrUP-w#?7ri!~w zuW?CRbx^M-x)U>Xf|onG%U-XX6(<(eFji%-)#6;qAQs%R3|QeFE*2~Riionu``ccZ)h+@y7iOXlR5 zFtTLr+30w(JpjVWs_EKgl8k;pJ~#(ql{z^x~?jc99@k}_)8P#v0k_j z=|{%O=x%iVx+a#0Q8%&&DU)O3&*Np#^G*E89HZ$jbZpI8osG_Z>8$pkYirNyYINT# zO^j@BVF5?c#W&eFtQNoG6o`^-MS3Pq#J{d z4z)(cDLNY&?_-LMXb-Xn88o6}s?jCe8FZQ3hqn16GaTKGY(vW2VPx6PCap#0j&~Bh zd!+6d7rLmeiI<(S)9Cy?ED$-U9(2aO5glEPPTn7>EyjoJMTTYeZgfj~la?VH7e@C4 zo3u39^O@|7$Ojhc2TCf02NK74^^+%Fgf~s=In1In$-I*W@3zrH8EGN4 z_`@bGNv~7HmVea5DXf0G)JQDrAy%(cBo6&u@5n+~Q2tS7(5Tfii>?i48b9xz-qLTZYw8Sw+Pmw9#=@W#7?AFipm~r;#O6!G#Xit4DmAl zBx8njf7hf{8MTUPx=%J~)nZ2N(X&||VJhX>kr+XwYe*zkiuR%!gfbb!i*)?Zq`8eL zMdklnoIv`NqB_qsX@y2dQT8A8;nX{d%>0RRWJl*PD4IB3^wC9yP0d>0D7~W=q<=J0 zZK4H2m5goXFS&D;+Q*{eEzRojOL!^4aanY;Jbz<)kpnT!TKp*WgG<;}htZ+fW-UQ# z$6WS;xU)JH-ETXq^UwnmoB3r2BYz1x93M%a9E}`0SC`+4?E*P$kEEU(-HSF&YvxL; zZzjV?hof1`G^8VuF+OiZrXoGlM`RwdZpKL75@egRnH3{?Y(aI+6p7zRHE@12yOLf_ zFNp~WBXSs-H+w`n=COw7G;1a!I2Gxc%K#ZN4_S~nB1@2Y^O`lAQ7bC*0-^L;QK|D~ z+T`e7WKvSIW-$sHM#e7~k&X)(8Khm-iVQCtNzFs{UN|C4kildr?G}`Gkx+WAsOrTd zp}okGCC!{1de?`M1+Ee4n9m7t(MWJAGIi;Q%tIzzJR(bwu_+^cMGd25t*E|BMuw#q z*>mZL97c978yN`)cRg*XBQh1~y=+A0A!{!mktImw3fTzzSd=G?mAsUd%yHh8B1P;G zLZx5TtT|;zg<+!%(=Q*a~RuUG&1{|X8yLG`T-lDke!AU z`=OBO8O{7AiLv5)Mf8ehElKKObpG{c(;W+`>zB`)-Y-o*UDPPQLxD9!8g}JgXfSnoJ#cp4F-7_yPt()|Q7(yZ5Xv zK^GQA^yFw{&Hc?<72C2nf0334b*b+by=d>F`uQyOD+_XF8P<64W1f3aEX9c^5JkX^O$LTAr==hrJjA;r0QK2d6C?S ziE2gaz#IB-iwj@$5}qh;WTnY#JTlmXl#3eK-K&P)@EKoii?ma zsBK%b7Bp%Vq4}-NTCIL#Ayh9asQ1<4VgX7!NRAvjh##Lli)i3%PRN}o~G@O#bTjz}L`WL_uJZCq-j zm$DPS&s9Qkcc72sY*v7jvS!J!r zdLfNdMkKn0(zl0Yq@n6%rO3oPMWS9QszE4OsYtwQ3(wh%OAoTmkb0%ath@EpI9g~y z_6ccJiYhJ;O0P7P)BPSj^nMYFtV1>!m7)^wMafE$Ert}s8;wj^wMFbfdZoxNL+X_x zb4s^pA)`{1y-X;*(#zN-QM`r{l|~~2f83(kj5|~zTgsVKd6h*fPj2CjD5I;$uIILB z-Lh6>`8r*ST1DQJY9>xDCgku7Tg1B<`bKy;tLLRHnn~7+bk?#+WxXQx6@Aj1MNvre ztGd*Ciww3f>&6-usj00jQ@H^ni;yKoy$g{gJD9C8EUU;HoE(aOnfzBzdfA~Z{6-bK zfX9ngKjbqhRM`fC|1UKdJ7A?hrd!Si=8&|E$Q_NB6S2BPvx2Ws$ zc!w`cnEAC9t(ZPrmbdVfsirc~nnXwzm2+0}CQXa}zNs}EGaoa1>NzIM+7>mpR9PH{ zm-f+Ct$!4OJSbds3(s`hFin5oswJ2)C-VmB@0CT?Va&eXt^8;k=Ec%Xy^1p+w3Q!N z!@TK$c)N0uwFI;F>#bV%Xw2R6NuC!o?f6z+EMXo$pe~!COo{8p^bSb#jQWp!W%@Y# zw^EPm(1WZA%UNqDq&claoqxM>-nhX*Y0NjGY#yTWzLVxMp0<_DsGJgq*>O^uD`a^= zOxO3)%;mwDD6j6+R;^YvZIuxf7oW~;!jLrAs8jEtX%#<6z19et;3jDJ-_l$!p61=> zw$F#z^`kU*)4sOd3;<@bCe1@K()@GwPt!Id`%xleAD}0ggXc)| zxDjd1#>^Tm%`+WpZV_*i; zJtG3IrjaqyTOk9}F{{Q&Gxwmn;z1*DFjjgzTohAmttK!lPMT{Ds_Snv0$Z%oTWbW` z`Utd5kmmY>EaY6eeGM;{+P7-%Xfc!r#V01tdtoK#fRBWZ&aLXWmC7a75`<~uHe#@C&xg3#GaHpgO;R@`8(`(JG@nL=`TPCR4 zUnR{|2i4v8P_OUj(pYIkO)ztTa9=IWTrtk$4=~QS<=08~MpjqPUjZr7=rJrC-P9eTOusal(lY zMBt^}E4@iFuo`nPVvgg4TSalTzmrj;ji|UjqMQ#&^NjkhyOe3;ujfkgh_p_sk1~%@ zF1-FV+td{+m6=g_h|WK3Q&$U7jtD%yON0hx&EzsP`ABfx{_e14m{Rs_@{yfrdlgAowK8(zOnJt_hQ5Sg#a zfOSSdd=|G^uWeK3-$_6!qVshb@PrZI##8FIscS@lg2;SR2COy$e0b)DZR#Nr(2Ho> zBm-6&0p?$_%`|RPr`<(B5+bQd2Ha=_WaEXKx2dZ{KnbF)MFuQ40_yR~w{25*i-1l< zrcVYeF#^JPvD>$)Z?47yE12 zIlNa^CdZhwIdQ(&CLXO%U#v{G`G_h%w#|6gY9mp#Pggo)@`!SMxlO#{A!@4H^#E^C z#bRdlZ_~OLQOg!KEIz5G-{M$Bc=wc6ty^3|CwCf`l5)(lY0|u+Q(gNzR(8^P(zshj zbraPyU7F8!sz*gsxl})(medWI_(Yu@%k1>@3av(!HrpU zp)_aktNq691#aph>0a}J(M%s^|Ke6&FEd~dd?0TxFwbDn| zgG;6PwGnB}#>_~OruDFKdx2MXNvl>Q>bdx^ywqa$UnQ6r;L{Rg3_XnYFZ5{z7DKykVK$fgv?{XaDhsV)((6XO#j_XMJmau>sF)Wr z2?W`$@M%gc=3Hj7Sh+IJgPFO)r*+N5d_euj@0GvPxFdlxaqIz+D90hFs3N7 zWEAF8e^bY;Rpw1hx|IPpzopfQde;4IWFchZ_pkBsQ^xqa|EA7=l+TSQmTZ$EfvA0&W{)A;@gv5hWMd9KcTkIz+;|J9Gw+!AHBTK74-VL2%^tup1pk44HnTbn3kr;p!#CVbz=tip+v z$+ltKo_Bnj_?)R_Hw!$;S()_0V-%8lI~_da)6zwy^ZzbCNPyYWCC$da8=ujs#SDJv z)5HfzE%W~&&ac^%cs*k3CL!@t#z-vukN=@IKBinU(QyZNc_(~YY#ip%qhgE}mMcrG zZu~svAxq4|`d;y&p6Tju|DcSs){^3hOvc7uW2XpW4n)6Y+^HY#759Kst$60~(mT-0 z%ilwa-5S4=GaXlabjh->S3Uj*ZuIjoYo^Q4^`96Y2QJ5Kz>F8`W8Ei=^GRh<9A?RU z8Ts`m>iSY%iws~Yn5pB4{Ol9`_5Z|FH+$03x3r)bv040e3X}fnajOU4oGKU7>Q9aP zTD+3WBK3c&PJ3RNI`&Qqz3eS@#pA5uun4$X7PfMvu$Ux*ESaJ(^#kq$)hb@YShF$9 zu9Kx5{ZwDBF=5Oq%uYUT^4rR}6Ob9dkp*rTDbU)7-<=y->Ys`i4^!jr;`F;kmN)G) zWBGeA^KOyNb0Z4wlBFGslr~pn46l-fE%{7N6=vamvb0>Iv>5l@^beEPeJfgr%zh{` zcAt%nj9oT}dGOPycNimgTDKQBvLH_|qn2pV`v7I%zx=&ye; z-Lhu+aRWGvn+6#EYN)~ zH?)}9vcM#CZ;LGOWTe13RuNaQT{dxfNPlT##S86_1+EJ5q4$G)++!8{4raj^@jPnI z#6E(m_Q?X5ghuAWL7d|qS>O{PV}jE$tKXF+HinGl*N0h;Sv*F)|7B(F1Z2?%vcT0N z1=_mthmXht+i8s$L>s2(Ls{T)g4M^?RocfEa*h5_PH{HE{HZLjb)-D2f?st^mN)uy zqk%q5%a^je`JWr>Ir~0dHGC?Y1wP+3wXsB%G{sH++h*8NajBNxp6C2#DFi6 znJ4l0aU!>3_|=!n0>*t|R9}MWO_c>q{=%5Ddd!5&WeHb&p*F6gdc3Zm%iI?mxhI$( z28FkYa#%k-vH0N$t=Rd=>SV0utAtPpdVVr`N z)$E9vE$V`2l)2VEVutULF=G6=1&JvqCidR#n$MzFH8B-k^*b4~MPD7_mN%vszYc#m zN?mvhALq}1RxwA%d)U-IXy6ULmtW(71R?2bV!D5j=8az)*-J3vf0SmUG`*NX(+;Ed(fvkbFQ&&V&0J~5 zJ|u2)rP*qj6H_s}$4PVCKgF7TC6AY(h4`84wrk?c6PA_#l(+BoxH&Ix*W!t@Jp3

{c~N1^HlGnOQG}b`+OBm>CSoIh--sJ0mfOT`d`H|4K39OR^7o63b8X@< zenIDU%`palpYDrS2sT$S{rM|9ifH-KZ@A0pQJgWoxS@}?i?25Ay@MA`<>-MP8FkIK zYHqdo+%IO?XDlm`^$33&$rz%EefY)J9hybV`)%ScAQ^W)jz_rXn7D(t26bOvEifD6 zcNklqdO|Ghsa8Bco{5pOJbS|Uc9FFfx56$XPo6Nc2QeMfq=dPwC}dDVH+I3}aw zA7yrd!+H*t97mrHM*46Mf-xJH_5PZ+O@ z@q#xAzE&t4oHy&{9%Wdq3&@jb{io<6t}GG`l84Bwn$9&<2%Hgxp4tyPP7-DUoP_K-|@&s zRv`6EN53`74Py>e$Qb*0RQ%I2q*cAQMww>$1Dj-Jq>$)7BI=QDbkPDmOcw%SuI^z-~$moV23s=I5s4^DdAWD0m` zsAzUzOtDtu*0t`?+RV74Pa2zi5HrcY!+5Q_ z`lNd373KUmytF;iJ9$!nd2LI0f;IW}4$Ubxs?}j0JXTgZt=YKg@9faTm;5YhSe^eW zPZp{%!>j$qcSEDTS698t%f?WO?lq;j^%W3^ne)Y_&yb0_<^eBv+ z=*n$I#Ka(GPOV>S5!ptIzh|bu4zR`ki4oo8*E+{X-UV;^7%E-1l%i5t1BMi z-BrATFa4VMim>ITAvO0kzEK;*jQ`qi+)>`ZUoA6se%k=P;~j=m%>TnftX7|rpw$O!U+Wx$oBMBdT0M^vvM#DLTdPUwqly$0DM$XT z-vy4x3*(9JZtzu;_g+^nu!ZrGf1+Hm20lAOxyO}x6Q1G)ZS+p9LIfTb7Y+Se-Bve# z?~I*VA&zD8PwKJ_JPxVGw9nb8Rf{&LKdGxWFbUn5oeOqq;#$)6d+Y{jf+ftO&$Ua^z!pPEnU!b%c7^SX%gT)q0 za8dD2EkmpWb+mdss`3(RwlJTjaM2s<7=}Zs^UO#v<4~HcIUk{r2FNcx4xt zMX4(`GFSDOzO6g82GNM!QRkObs;9}^) zb*_-^N!+$OaPx30uHU8E%)~AqZ;Y-@!7ccebk|1QHr$NgNcTv@9l%YzS-R8WWC@OE zDeqS4u8g>uxc#?Fw=v?D;C9?8-IEd5i`#IIbeCCWxxKg*_euAOh#Ol)dmohUA;Wcu zx6y5>q;&p!rxqVadnVcB5-h>B{C=15O}%3i^(8pT#W4Fwa6Gch_+ZGaN$MFdXX=26 zery*%O#xR*GvO~>z{_Oh25IJD_Lj@YW74d~3|2(Sj5o^c#B5O_WlGch91mKmB4tW5 z6|=lLQl@UsR;$*t33^B=tl6cNhyq$Y{ z%!1c<@k<ch=wmF|Yg>h9g#UE?)um)=PkX){;ToL$mgZjaL6zOiB!?2+a=Onpgb<8}n3 zdknYm7ID{yTW8*-#l}+5k}1ZN+uCpoZM*pW5ZuXAjZ;hCcEY5Xf3{0298by>r0Cm@ z>v^`s^LH69B(HGbE@Inp}9Fu0QVa8Nr7Jn_WtJnK@Bcu}@e_RF~l0oJgPK$5#pyr@5L#<4xwAxZJ^BEm} zS;%BrHY0Lc;o2_PrS*zU>i7(!W}nEPOn$N5Kjl={`ot-PnYEOe6OrR)s;dV0TIq{y zp8vB;e+Ts~e%&O9E)VbGo2Tma&+wEKX*(s)@#QnsGlN{|yqJSO>@vO=ymn@kTEfc! z%S#M^c{kss)9>iR#IzxOVzXXJ#!D-w#t~wV+HGumxzzs&UwsN<4#kLk*WJZBMwN_{ z*`5$ZuVismf|ha|9O5#f|%gak%H2Z85hf-wUL7QaC0sZLHFHH-%-6NV;n_6w*>e^?#rz8 z)RBU^2{K{eLktSGC{U|->x=7A+Tz{5y*G6*o z;d--0PB981XY#LQ%u1Ov%7^Rt?QZqZ4%SijtE|6UL+V*@*f6rYWcCeoM1AaSW!jjuzeOsrg^36v^$OO|vf+FAb)DBuCeuGg zYK^Qu+{DjEa=MXTq@GjssqlVA4%7BeX)ZrIaz6b0K{;~EI% z3u=OZ%G7$K>B5oJATk9hQ~Qvyi$_w;Z}QR? z8L1cPx@aUd9a)Hs)QdDw*F%^TTut{6#8K!&dx zNliy4EgwmBBYi&~Ni9bXAS3l6yD~;ngGkG@BdLAJk`*JV<_3yFW~(nhs!XMSwH3p zGKwqY-u1ym^)n$2jCeKMKXHIl%W-ZjWX$57Nhi8((_?fj%{DOo%nlqIz;`5-W z9G#QDN2{7l+_YJ0?z_Ak6+v|m@8Rz?V_q}+?7h6XkyE;2kLHUZp>>Y2q4_ZDpW7oo z2F9mMt*8Jhhoxy*IhT9Qa?EnvLEJvko!q%{bgGwavqoeTdzY<`7(Y_ac|#;; zEJ6LazOkY$GG`Fe{i?{RZ|bNrl%8>!%xJ5|ZNU}4ab;P8oA(-n)s5?VbC2;dlj4rL zxWUJ>Y?9s;k%|+VSbN?*TA`WLi)F>VnD(tBO)f{ekRweNXMapWGk0RU_Gqrr>aFg| zIX00gdyg!CGUbb%V}hBep1snw&SlfoA7bJb2c#P%V{O^Eo%^M$&7m)MvPLjn?b1Ar zsc%U2xD`R^p1}3;^JgM7{#|K)9SIHNmK>1oXSn)azJ+I-2c`M(oXB2|+xA|h-&QxW z2dVda%N%vtAua+6rsWVzDH?91xZe8}mpWL>FFj`y zPAkO?%u*7g>&fdIwU@l&+3;9Y*QmYf`~zHeZMp0f9vsu?y;`EkH9C?jp_P3#PUO;S zBqrXv*QimOeYQsYbbOb{dwO=HM)GD%i_|y)cOwZSK`Qfe73scFmG9U zF$d@E)jAhrM#-U@lt~N2q-K8pQwg57Km_aWf7RoAoAw${Z7yD5 zMBBP?W4AIGtR+jXaK+QA*zH`1-ruV^^yQW;$`C&YX-mhqUAxbCLvO|+<7IM8A8!AL zdo_=I=dc>>`e-kIxt=m-5mmdZa^3_?@7H^^u)Z-bjx@_^-oYMxe6Lm_#^%|@`U6I* z3)A;M44Bw%mMl@n9pUMl8`FGBnj4m=tNzW?ZoKS&OK*}(53~g_>wl8w6D}@J;&W%1 z;ZgfE@q>t#lbHJJ?F2vb6}3+jKe}gGd69bN2y>o?nPlCk#f#p5eUWil(qGC~lVY*& z)5K2+S=KG35PciPbw@^JONx55pJxwvc??7l=?-4>|%A95ztlHy3)r`3u=9=?=@@L)H37mIntK7JTez5Wh9 z>4@yVZlCyC@4`oUThxWNW$n{463J6~sTk+WpW=OW?CO$zT0jhcYbs-sD=yf$j8m`!<)eJ@rzh3ZG~ zhFdOAe#3-X76i0xajG8`zaOcey;1dqB`gc5Xa2zo=tc}I5AdzTAOE4ujWGx4X=Xrt zIzqew72`rXe;v?VG3qmq@OjljwBxpbmSpItdbI5x$~wx#x)C+M3ux)0!u9lBzrPb9 zwPj?{H-MiT%VlCOZq?HP%{zzKsH;WeetK28RCN|9W32mW)0TiXIEu7c8IdPwxWR1! z<5yg7z#Ukk*yo0E3*QR-ug?o4nV19o0(^b0S7sPbO;X?H^w<^9lGW?hG1q;>)CTCg zSWv4o)ZL#jAl1aAAJt>T_r`t5{!m25bR(6o=pw&@mdbA-h0!Vh5)&XEwnsbKIaPHz z{wjX7EFD>fEHZw_)Q#*qE6b72;{krpME{l3dSsz4zgeP8o*P8^k@0jU^3TPAD8z@~ zCQiy}*Q(1tQ|8T#57LbI{r@XCf#4*37e4p-OBJUDm5(Y=_bj2YCCEBmiXRLUiJ`NJ zok-`;_S3jq7O|E@tQ+Z>Os%i}LQI$bAvd2WBWb_po`(NyrtrllDr^Jzo!9I)PQaDd z8&B}#;@{z1yN+gxrEpxG`nfVI4$Ji$Y3;Z{U2%qA@WQj-CcP)JjQ!PCk2`!feG&WX z4Zp-K5pT)yX-$n62AO5#^ojx)3#~9 zmM6+M`WyX~gslWKb?bgDEFw#9;)ed&N?x&i!8>z4l7@Edm+!6QsB4dL(domi*}Gqh z74aK$)ZNGEiKBx>6Wp(LL}AYOEja0G_P6c!DultP~{^d8z zPPgHDdiEQiw?2w1E-tnK+<{LhR@9Z7D_zGycA`G%o|LXN6W4KkzuZ;x)HUDG*b+?d zpftzbVwhgcs*BsTjM0?3_7>xu%zlrp{?c~73BTZRUeFNIf(nlzCfJ#u35&bwjgF_ZaW{Oz&w2$ zgQb3O4!?hj9lEt$%d}z7%4d}pSI)B>;_80CXpnwENJkDM9U|-9w;Kx-um8bzEp{B< z+S_G&>T!c5?OKaNxOXtXzvRt&%+wd#wK5TU#hq&74}1tHwv&3_pyk56_%6{L{k|$4 z-@Ub6^NHS1zMJ+ep`RYy{_X9WU9_N7xZ>TgTHKzU?Z$hJjksb=CU)X__O)v!E3uOb zM9JcA%W8g~W_-|Yyxq9`9(CMiW$FaHw!gM(;yppjntMd7ev6ogU)@9N#68yu-PiBf zs`2grYUjuI@NZkiqTmso6*KRfc77Wjb1kN5oV5>kV6a`Q9gn+Xm3n+^<@s?RFkL^% zIXG6RuK$XQXewsmIYG@9O`!EY`C{IKn;sL?a>T~G8&}*(+Pt{#grM;t{=@^ug92M0 zuI~b3^`%-QUB_V_StSQGmnio@#LdR-x+G}aR;+%|STQyQxA@ASmL+13;EH!`ZEd(U zzX)n3F-OaOr{6G5QQ!YsiLwolRPgJd@jm+rlJw>!bTR!m%Z7|wZ8T(J9&TU0?BK(z zN2aocvf7Fzg3t$xR{0Gd5FkQQ5fkSKh+mV2nUIbcYvAJK=n zPLE<<#1P^s$$)7-J?|7R{*|?Mhrn$ZV!Fp14LWsot*!-wziaLIm}xI;=Z|Y`xm(;h z^SipGIu0>K_^FA3DLX zx&J1Y2SS(pkn&sOAL|5ev1|ENMm1!nAEC#OdW$>JzBs{zl80SLs$tH2nu@cS1_2C3 zzopN|JPA|{LOceqdW)O&!!`{-hIev{5|EYiM z>JDJZ*tdGkof4TfgyBW~@WdA8#{KY2_>6vd4m`6TUI0%T`_{-_0eelr4m{|#yha*} zJ`RkB^hxBN^ow&?9Up|W4oRK#Nd1v`WrCt_h457KaMPVU^x%K# zkI9n<*?8=MZu$CKb}1n{CqKhB%|m2=E9nPr68I#LS>|3TKElcMjxta2m=ag3^4_O_k@&0KeJq3F)xNv-v^Jud-2C)ZhXPIE2<7W&QG zc8Tg38IH6Avils2Z$PLW)+HcC3x+}DAg!&_&EC0928Jd*ynYIyy0^sms%WyI>+>+Bg4 z^7}v6eUQ5nT61@u?UL-+{0nQxdH<;RO}VHI0yF@aD7YQ(F*$m$PX8Fg^m421zs&iv zfwLFa={qT&DmU|iLQ#FVPJhd`87fO&PdU_6M6#uFO@ChH+Hf~8=LsSxVZQ-ve2{y1 zfmzGz^nT3g=dJTM^M>mLwd6b46vgBhbgz{Q%==!Qy;$J%7fc7`gZjT;XP=Y4XxR(a zD#>%vEUB|=B=8MrQnQC&1#JHjx08ffY&qI#ML(-!WDA7-BdzWe{wtlJfr2K;! z;jilSft2Y`HKojjCjF+)_Q_OW2~^%iB$Pt){#d6QSM)EXpx@)bl^fjs=Q=xG48QtI z({Q_>9e=6QgTmoo>O4#NC!y^%s%KGEXF_tI^>3OcF>-T^mHTbpMvCg&b#|gyox53g z>gB-Q`^Xfj=Bvs#4UzSsj$XJGor)1 z$LjP!t$Z}q)(J4@A7rhB|0dA?FqH#X*g=bu#&@zpRZdR_u=XReTZ(4xi>6md>7d4) zq0l9&uf7;*6$yFp^3SR8!rd^I?#!uydSmPL(AM&j%7ugu z;JNsEyH-jk`eiZk$+L8z|6*BkO}(8W@!0yZnM3A5i-y+QE@@BETU6}EifZ=6dV6mY zaPt4^D0^z5wRhFq_0o`^gQ`6n-v^ZX*PwI*ANa3LNI?$IueYnD8yNgbBw_A6`0|JA z^&6#KuUPpulPcJ`$LjT~qvWktTLSZ6Sm`(GO^w^C2eG`9%;KM@H>)2}X-AqNc|T{X zt~;5ibT21^t^hu{)iihUSo>5x*E&HrLsi)U&wa1n4qXX+1L*g12?4OOgdiNiF_qRH zDS24MntDCZ&Z#t2H}MoUe_C(nip^b>R`Nec39S9udVSMSOQkjE27JTn1ElyW^v>g3 z)y695?DBd$OTt!GTSx;~WIUcK#*kX{ukOByfK^)k9*w+$*Ip{Eeq zQ(13!OQL4}nv|-J4O;!%dff}{fQsFOT4=}bOkOqpI))me)_LIFJL}oi!o+zoq0Ui$ zL>+s*UT@guZxdz4uQ6_L#@|fY?b&8V3O}^Eww~W^!o-PfY69k|0VeLR*G+BKc9V<_ zXx2N_JW1SBP&J?@c9OW}dV8lBu(n&tr|2MI{v-AJ;FgW1Y-we5Kr347?SiO_e=^%B zg}1}i?eBwsLn;ab8L{3j%KTmGjP5VRv*#Fz8bC0em`u6RpQ1h`PDIhwR&RUKcyeaD zIt!an01SRkhRJAO_gl#W8QVPN@J(0mvpq6nYTLoMA^YyYEY4Fo46MyE^xc279scMeRjI4)m6Ik#rRG$Doy9&owxu$iiEJ{j(zH8 z;kdv=Pcd>q4jC<88jP2ON@(#{_i=Y7biB%bnQz7Abu-_(XP+GvBUcQJ_PCID=k2o# zL~jTYQ!9WRXlTJcZb*bq{+*uJ!Tk9YoOCU7FHM5Gnn$yj?bAnrXZ}vr7Ec&>?pyox zix<()TpY-VtNJ%h<2(E8(ks<#15Y8cbLBqWHBCdScvoPo8|YnSa%%xF<$Hm#v7Zvt z)%%!;sF`D233BC+_i^x1rNr$;&RM(9-Xd{c@;iM}yBJvYvwgN-BE1?*^5SGr74)1R zDyqxK9BaZEj+&eyBRB4o`!Bz>l~aQ*WdG0inRDe_BQCo!*}$DI?6bQhw>wq7sy5(* z7rwa9&XQhZ?eE#({|0S9EdB~8ZD8c9rqdYh>44|`VV_>hP1zY~^gYaEtEofOCujan zE7`#~0Bime*(Lqt92m#X-6g=3Kkw6X=50WZCAe#V<$DZ#&A>3w^_P8I){gf&E{+q; z?9W)q{dFHdaR+QsaDp{sP{83S;Yr6E`}AAHlM=5V@^bXqt$vsF!$E-|o<^Sg{2V#@HwRlBnOyPOA$&S?my@_mIABZ+NW19sejO#wZPi_WU~~; zY6T|@&Lj^UXBqC^A*@^wK9sdVwM|$AK)#w$E*xzeUJdrq5!HfFgweZ4z zcnH3@AKn8m=!d)hOTPi1B7sHz#GTHA?9BbWe$>JXmw+?jQJ5G z!mXAj?$3(LJx`JUWWU|WPbzVPNn9y%@w)w-nzO#FV(`dDUhLm*=ZdfCTn)l^2(d8V z%NPBmhk5o2mW`hf&&zA}+pakHnO*XQL3(0THhGzdX3^XDOykMR)mG<_zzt&>fjuAW z?=>Pw#uvle;q?h9FZn<9{^!P&FBs(hyI=nv&Fo8mTaFG)N()aV@|-ck+3;Fq#B_(@ z;j9L`^lJFw*OjrjDvZs(t$|Xzii~yTXm?lQnugNpRSVzfU&U&SdD|ze-YM zmpCCC9@^ZXzonhKSGc-Ds1V-#Y=iBUq_5bkYI#gz)PSgSyBe%z$${JB3J_NQy}|Bs zSx-OUzs-}0>^azAC#hN6UR5E})p?0Ro^-c1*fTuX+VwYUT1w#dglb^>sRq5*H|y^b z@VAl!x49hy21LyWV@4{N{H9|{fG^{K9(SXjv~PP;S8GoR)Hl@7>9tVarg*BL8^<=< zE-Bd-XbB%G55HnSRPmI?UX5914JGir>PGqHjRU{t6(C~!pBm+0xN4k@$iCMa<)=23 z+=Cq6-6)F;C8tCWh^qK=qx{;0S{;dg`Av;>lGOAz!j=)&?Lf;n11mCwJjc&#aWc*0 z6|Z+U+C>u0=(o+v+NANp}p0s$S7ZFNED``&rR$W!EYX>imAAe*KWY-x{CB>AG@Y{n|$R z+%>44MpeDH?|?3Uk(`lQIi=A|vlFi*Kejg78A6-5ABy7r_Y~a#&SSR}# z^MHx}Atpae7bke)2M3!#~>zhj3-K=&NBmN^6C2Ew}Ah_+~+J!-Y>;#-9vu<&DIEistX zs=B`s{@4Lgi^K2q>Mx{UsD$Uj3uE-V{SflX=mT;GmwMNq7)M-U57-{_JQumhbHF~w z&xOcYfKud)YY*5Cr;=l9kb8z6ke@ji9hel?gIGK2fW13LEh*yC;|XrU0sE9OSAZP$ z9$;V0dT3-|(p89#TMt;BqnQvlBDCimuvxatR4guxJTLcvO*K(Ld-(~=j`;`J57BZl za#H>QyCcT>WOQI+TqSbtBM0RCh4LRnZhf4jndh#n$-L$0Uu6wE%B@_8l`9U|E44Xy zSj<0tz|NLh=su!$%QLD_I#qf=&E?2F^(Wbw3orS}0e&U`<@rZ=kGr1t(sCQIr<6w< z*B-E!Uuz!8i0H0`?tRgCNNuq;kLCNrFfjP?0XywFR8w163O?aE4abab0d(a%2lyRjbSYsd+~S3MDT!+1-*M3r=0=$WsOni1O|r3@N2$AL^|| zcMi0w%FwkRT5~u@HV~Hn`zE_x614S0y@gQ$4DM{w_bs0=-aWO@*?%I2qnXx2Z>Cii`?MLZDZ{4+T( zaoYBgwZpJAHBI_OV~h5j;JStuzPCw#mu!C&=`h{d@J)YjvJ+(aZ;BVH!Gq3pEv7mkvUyb`Xj`DQLstx(5*$2@qDa% z$bcxTO46RT+`m9ehS%{`mrgJ zYN7uybkfKA14d#0Y~puYi1>6g^;zj8()fOpoi23l$C0zr(B&OXy5TP}Ry}#pHUDa2 z{{!78q3XqC3AF3^W`2GEYJDv4TKLorSo}c~zZeI6SqyCD^KI$8JRu&fJ4t!Tqc<+Z z<2vGT%EYcI5|2U9q7Mx{0o7AUPaeGBqb9phY@EghB}0$P$MzmSkJfcI>FuwWPa+ut z^>>jVDYYS==nR2XeA1*pm!6EK+Jba&9eZVWll}q6xlq+-d7<_HZn6th(z$4ZGbNrv zV9%!}b{kNY?{3_{Q)im=?~lI>RAIQb7GjZ({|FT`02R-+>iEGSh71!Ydfhl1V)iK;PB2ldd&i=v#H49A@ zJ}~#oCiT;}&ILeSBd8!bwu$P}(~%khof_55&jb*w73iwC=0WFO(X4CFb7EGaRRYb8 zZnkShcdJl2#8L%qzp~lR7J9;1a0j71F@~N$t&h9HoN>*%2!?d)B8bZz$`mNRnIf>h zH;uFZ1;`6s&AJ{fKucwGDKzJ5LzhDROUYy zCYctRl1z8{FoI5KwlgK_ySlCM@@WGsE3uh&2x~%9>dC+o=)!B7?Zv8MT0fW;7~!dc zt-IEQ?*6xqs5=NP8Db)u`fnXNtSE^FFTN)kO;36%v$yMv=5(lxx1L;R5>*@Ez!fK=Iu7vK5^g|o|t*V4O2yBk1Hkb&&s*_DnZ6*Q((}~ZP6l1j08h2Y@ zn5%TCk#@6bY~^ zqB@3qS)`u9+Q%E4Q_h%bo<5SaW*VcjpqY|`z}g80E{Lf5pt~m;14}hks@o@-w62J# z)}mUTW$0R{Di`3I8;pM|qMFEnvHV7(x(%wz1z0fIz}F(Gh0xhvW1tSI$^|&}D@L^? zqFN12zsb;(P*pBK&lJ-t&H{BeIf{xg)zFw8(@g@SZZ`gh0Ob>%SYQ{>$%6czK&lh5 z@s?)xG=EsmNlB!ii;^v6pD5Fm91@SsJ^J7QER1fq zB%%QWD)~WZO(6v%kvq|&j`qivj3XjNk>qHLmkxYx>dt>Gd)vZ ziL_iAWEW2sf7|#N^B>c*Boc##-!WlMfl5RM0%t#Ef}HgqeI%g}=-S-OE!mP7G}T)k zVDVPQZh>zC)mK`%6J#+$-M4P#$Fs*3BS!tM+0MA6BxND(f_vcSWQ8;3tV)BtUd(|v zzm9i^bIv(+Y&fn9nD{qoPkLvy9JvTtJ}`1VcTPO3^vJkraHjK(<+oSpQ3m@-=7)YZOs+tT?ETqn!lG*(8BcKQM5}RZc4;XW1t+)co+ET{sM*vjobi1TQpu z^Fg~=ifwSL^3Ru?qBn?kc>6(n zhS;dXhFnVSaiFsO4+rg2vS~0a&Z*8Id9tAk-#nmq+3E2?yMhPp)_Le|z8YP= z>2U-7qYmjE$McC!y@m-vLlY0_!%+>_=%|%`g&KO}AxlLk6Ty4qA>DY}t|9ki;$8q< zc*`Mu5@*A;PCfpL$CO(Qt%LgI=qs>&x`8&Z;sZL*Aav&)hjay>GDM1Z;!;lS+(hYq zmC&Sd>=|N0%Z6s(ODyRRoM)k8!cz#{1XXQha+1?3zMEAuFzS9|;5DF%ZX-1P0b}5d zsLDM%J- zGta}wwSPLq?R#23^A@7CM+GORHsT79*Sv9v-bp|ABX_)ci0?SGT!ZY}cgSuwau;%9 z6X6*-Wg6ugBz{KDMV@`^kiFg5D?#4--bH&=$n!cP_Qu2_c7LeMsnlmv7N;*-%SKNB z?1D8<59;1YhxGyI!%~7QxZ*0%>hd1u6p)T{BXY{ri*gt_ciLgQ+&s^`l{nvaQ7%AE zyyGwj3``y%m)?0%u0igZeVDrj)N_vydH0;d_Cl#g(Zr(U#=!7F!1k{lwu1t8(i{$!A%OwUUWj@ZB(U44%>++I?pOT>}RNhdmcA9^?I?Q)Jx&b-#)B6npqcl z4ZP_4hCg|M^AmbBiys}f)5N@Wz18qQfS+@i&bGw5!}hwHfNyB!xWH`*CGfO24%?0R zagHA*f&TRe93iQOSMNQn4=~RhMxXazhLkR7_TNnz1gNP z5Y!(ox<{Kq37F_La2iksCASY6x+!S;B*<^=in z@9N*m6)dziq>w&n&V*hlm^_~Be2AQss4N?8 zjb|4#&T%K@SQwNJM&FA-1ubBu9u0) z%MzAMV)CE`PX+a*#(N}QHU}DknJa?&aODXu%XpY0iLmewm>h`r=rLq+8us)8nMq!c7mUWTeeiXmvb71SpI-xRBd*zs(Bge^(eEGlfm5q&ep88O42loMD8 z++uyvEvK9jLlGVEp7|qIuD~u}2|wOD(Vv`r$;*Ih9!*U=Vml@O*NaWbtuCnZ`XhQz zY;FcEv6+cd%52O)S%xumWmr4jWJfR;*pW>5l3%Z)s%B@U(A?A`{5~vn$XF}CkYe@T zO*y6=QNQ@jxwnK4l+Gb{h*Hd0sfKcpKdv0T%Hd?;m0GS9dGrxG$;ds({_#iT^`g>G z|0?6%4M!MKwVa3CeA5vbZ`AWr=`wQS9G>SMv0IIt zgY5d+5xd=?{riw>?k79V^GalA!4WPgmFyiI7ew|xe8jFaKSAWkWgfQlqU=T9RC`2j zA0d7tter~(jxmM6%DN-H-mRvSG2(e6yjf{34 zMCeme#pNdtncPO$Ge&bzC7PZF(Afpq>*^UyqTl$EbHG z`vqFZAE8BbKOVSpA*i*FfBM^~T6k?gJOtm_hf8=R@Cx`;+>$&Uy_-|+rI`Dui+L}6 zQy(rHBDwHVc!5gY@M6Th{iu~1vtF%M`TtR?F=|QH7h|{zrx39kYpMvg(QT{EC}21O zUjwRgsfOk>8r3@K;n{lh0R0izGAdF8C39J=f%_Ig3Vd%wy~$V}lmm6XV=SMD7cb^tbKnkml68C@2miV->q7KO4SkZhsbx(HN}i@8 z`eVYwP?=_Va-q#f=mLnFb1hX#^?4=Gz30>3)T~S!noRpn2y*tt$w(tA6^L$e{i{e4g6Feo=#c|;32qbekaDzNAWk$?5;g` zmDTWwKh{%8MIW|6Te0(KQ;6X>1t20 zbO8E3GohXb%J&=s)6N++xf#zr zpWZzBs7_!@MAZx3e&td91H#ecR9H&2$Z1q30o9_o6xFo&qxMP}0P>-dc(GbE(7>&t z8qEeHaOWTcJApa_@)!jY4V^sRWB_nRk_l=RP-OtH>v{vX0oAOr99llq(8Exb0l@4u z1MP@v2efB|q2n`627H~~W|V;ofXb>Dnv-GZGn!uK26l}z@YRTFDYSfop>0sLf(2%0 z85lD`=aoAM?YQx%{v>Ad1gq^ePVwGPYr4s3E}5V^cv#icqxx&D4fs}Z%7Ye6Gn#v# z>MKw2ew%?OBdV2RV1}WCCz922C<~Z3)4=IKWwi$yzSGcUQ1$WR0!E|R23ir-9BA$w zL*Im|QUUhdW8mqCYB{uGo}tN;OsN2K<{LN*s3On-?fSZ*PeE0+sQ%r%Az75x zL_c3+|J?6%^ThS&QN3e3GVbB84{j#$MD3PkLn|LYYWIlw`C30Ct_!;O zTSwVM*Js!(kz1d{s+_5rgI3i+E@KB)egCNK5O`LOg{uj;C-DI~gJ+KF#lY4ZXbTQj zg}{=Z9<{56qFi^w1?3WW_g1n<8s6E-R5A5>6uNQSQ9W56<28*m2<`eUO<&@=2pZ<1 z4v!V{{}+RAFDeaq$ft4VFm8uD_tIjk<_jk#>hcg1m!YwBxj~8$HF?&3uStd}ef)LDk?^0Ck-=p&f>1U&{eeKeRNe#a=1fpVOvN z{v7l2G(v0KE&9#Pw41RYml!w}F>Af9#db-2+n_S>PRNGN7}jEUd7#m^T&OHQc+bQZ z{fXW5X}Su#E1|QewAdjD@60r7$9)tgtn028eZ$41TTLoli|M8BZqXlw&NtMZ4P891 z#oj2@YR|2v+<>R@TDVP9DolbOG41Ou`ihE%TO~$vyf-%cVVck47JdOK@B%juA>^pQue~jjxVSEOXjO}RVDrgHCe$pruN?ab zZT5#PHu-SjPdbGfbmzfCGOIW}JrW&H4?MHfgt&Bu2{8pL?LTd?=cS_koP2nzSIUj> zbH8fgg0KrAI>v>8IaMvaPV!2S74STGSaNy&9b!c7o8>NHJg#ZsOILkMmIFEb*A_ch z^mfe@J-JbB5ZH5|Mei8y$q_6I-GpNJ%EK*owY0huic7}Er4&-sp%&JqmK@U`lY?CN za%-Tm{{`>0*gjd6=HF@USpDSiT|I4bq2RikNR{ibciCL1EFCStL_fbmL z-D(#|uj0O2^~xFULTK}~t#+Q!SGl3+M}grPuE$tR4{N<_Bc%%EOt?!{r%!&>#3BTB zrnc(i4J)9kt&5G;G-4sT7F2be+0eWZt$N+D1F8;46haH3YeaV|wD>sFP}frWkdZ`K z=Sww8-H6TPt5On!u>~k?OmC$nsJD^gXD?!koFrT(apCi}F~F)DTkSM_M*d`9C{F@_ zt97+CNB7vVVQBhIt$fq0u7yf3Vw#2M)i>4VAeJCb)nXxH`NgNDh}$ndtwh|5SfG?+ zY7xUXwOYxgf$K(eAY@HxwbLUp;$Lxx;kod|1FV5}P&?8er@xxoYS)lCLQprP??g)R$#-kN!7c^9#ldeEbptWwoe9zvv*6w zQ+s}nV(RDvglE2-^CA~NNTSTGP0Fe%vaZ(^i^x~ zvw`7p#owalSgmYasUI_sD@QI5Zetp54f`XV590F8#AzIUq+Qk==SI*lbnjcO>~pHa z7?p_5w<$%LdTz}%bETXonJd+|a{55s+E$F1v9HzMWWD$-Q>SvoO-dYkBZs<>ocn2= zl8hy}R`PmUe-|+7JyLo}ap&On!@G}5HlobeJWJN|tw~Un+gtU=bTRi32R@ZZa4e^O z#l5TFX^pu@N>+}pdvf6ZLGRi{s&1go#Dkx{;RkyXd_1bX=3P5VUi1#WSM|d3kwZ1S zbi})MkGyO;doOt^_bT^5r%rv>&X9g<<~+Kh?YtZOHc7qfU3<1zkGW50|G+}1=iYbq z^lORr+W_a*%3;3w@7iAG=gzfgsymT`&`rhf>b?5TuUR`dFXM51hf4bGckQXPWv6?- zp8q7|K+DUBtqj6%%83A7b$j3iZ@g>o<=gDXC`QC{b?@qP1Uv3G6Sxp`akGi%q6Mbi zxSpaG2jA73=5In}e&O~)YmdCEr+}RctoRKq7>a@3HlnYJZJ~LKS_#eiC()OBdlIVZ zWC+^vuXlA#o$?K8(j9!Fk?3Ot*?3HkD|^17a$A0sCmZgA`=pF_p)C{Q8%;%!zMu<* zoxeENtB;WW!VhnRt3x>(zM)2LPpv4IAJeb&U&fkxZBh7LGR5K;{l>s`v84#XP1sX2 z>bOe89uf5wgq~bv=l>kD{RH7$B(axMm_BGRv|UoVK^}j!6&y#dCNQ~tMdB+M`6tqZa6I6a`*8`mQDs~0d zVb{86l0S7y5L^wWs4o1e0)bcd;WF$vR#HP>Jti;auZvCBf}LZ1@hsuuWj9`Sqvo6? zAxKXV7Y1*C{TR0cSx;{X@YB)T__e$Wd?xKYhEGYfCkOEyI_h?nd}5q?o}34|(D6x5 zNTreD7znJcIi~N-Z~2C`qnsBRu(Vyr?ClcpVH9N#e~{z*l<{AV*(E~Xybzr#a2|Lz zCnTQblk@`Q8F*H`on)a}sh2_>|94E?UgV5^Ku?h3(tp65n0iT@-_e)fdGuVpOdt%aIUg3DX=UsaaMo;wHpGb(gt33?Y^1DOfpT)>{|T zgXq(uL@|iC8_}ng!-$TzMOg~iU5PjwF-@8-cRG|D+>p#8(eo{TA!U1*#*9EkSw9N5{C8PG-#s;y0?3`XiYXvp{-J z^`5T)p7HT9d$}Zf42f1fa5;2w_c8tAbS9MF)Js>t92J|x3_j^hq(TfVMl3{>rXQ7O zeO~FmKBgSjeCC+dxtS{kY7u7lNCwJ`)Qz-PBx2*-Lk@La6&UXP5pnnr>9U?U&iCfo zh`SMIsEzT24!pD?R>=^#_I`=^ZPx@+2cos`JXtRZdhLEI`Q^Y+m*Y#iO#$y?S{j?X z5VfkPHm&Afz;7O+wlLa&X(UalRioy(%Fv}`p{VV28t`01&GBQ#%J??Dpnij)Ow@ zw3a7}7D=mvs?Eh`D2QQ3^-RQI4zxB+sP(NK^oWc9H{f(FA8FL)MEam|)KW$px&o@U zdx7;C25yb0c0hgO4V4~WZ7h}!h)SDi;Q5HE7uuL*=oor7(s-R4xN@?A^EFKJltOcE zGD%tuRolJ5uBis@h^Pjk<oGAMh{erq*0fhR_ECXQbg)gow~5J@s$BLCh2)vUZwKV8rF9=^ zvrC-HP(m2xEyvsRHy&pn5M}v-*@@cD6K!n59Zx0nM#SQF5#RX=17Znc#y{HZnk%fo zz8Xm5mW{wwvFYpRrQfI4YA?BnMICJ{8O4h`jF+^3wdwOBn;+2KXC*qBC)?Prl$)77 z;w2BUh*&tKVAOtK7+QMzf|B^DLadjyQ3Fa<&oIFSW=Dne9)V=O%F&W%=>`Ub>`d#y zKLv(7Qi0frc_qB7D%U@Hg|zSrd8Q{7 zi1mmSGM$w=*)@Vy!OoF>#~>e%^5Q~v4H0mr5@~B_I-^ttcpZT;pI}omU+)v;t|x)$ z&WN_&OJy18L$1F%#E}yH`FREMro@o#yHY=|MeevR#8ocVUnisAg`74t#0w@RdqlrI zm9Qm{^+ZcLnL*;qHykSxBif3JQIZF`GZG;c&yP0;#*C}*6Hk=0P`;4Y;^t50nKe9b z{!WN*Gp)bYaz{O)A9dO3stXK>4bWMS2=V2e&eBZe?DUYmPW>Q+Jgr3Hstl5Qy|s5c zKSdbELeyyTK(zvKy%B z(4f#+5_S1f1h~>0(%W8=9yQbULDRkxve$^}QlZj8iE0F{0II`Fwa{j0u4Lib2dvFI zSOxX~yKW8XF9A=W+V~Y_uIU@e%G*q|&PcR=xRviNplha6Y!Vh7lm1i&SP!ffI0UH9 zepZTVB%7y0Wy2sY@8_~Rg8|M?a+q`=VsQ@1RI`eFE|*~cpc?3zO)_-{=P5?sIS*MX ztJs$fPj>}$-q%9<0;6mu7u(6jtL$)WDe$)pBUTT0`?Av=Lgd z&d{d}bvvHN?6ZchFVMYGH85qp>K9+i_YWIbi0twkrB&89cLgT8asxDK$++h*rQW0j z(W=;Bv|f$`>w19zHX8bxp#yWEDZenZ$@*$F77Ly;^2vx+HCh$rhT7JjMJx2Yk%v4O z$r%e=i5KPaQ~@Rda#%iQI$b=h5~*glrk&oP!tXS1;Zd8DV!^p0z=g%i$_9 z$rulL=}mxpfqn^b@FG&EW)tbysQ9A^bJ8N!ZU+_syU;Ba-C5R0uLrJ=4a2&3(G$zu zFIkPao+|NN&2TF1cfF*76i@GfZhFmRPTgWX*;;tvj1H5nxEEX%%XEfswd)R%V{qxq_<__N_fwaj6} z{}~BH_R0#OYoOUe-AnZ8HV?2IxKQBuC6Owd`M<2&z&dE2@h7?5h2~d5D3fu?`2|Nr`sZM-_m0hFB@YB$g=jHb=nG^%Fq{^KntV>ot zgNk{$u`QCCLL#DOeTiF{SRG(iqfah)5$7QmTF1xxhm6ZZEJw_VB#D2ehCkRb9sj7c>J3_F zBQS{7dP&z3R9P4ev;Mq45I?b!fjbklQQrKh%%_H0dv9X1Gx1kUOOC2cVxcyu2F3D!n8JJQ zQL<7d!Lh|?rK447eKA^ou>i3Maiw*9fG*LD0L z6jRcvT{1FW{Z1fhBGPgsRc9j^{hZDqDdr$H%6VQcQGV(%bu>J|fu}G~)w@*~X8-Gz z!03V5@am6QS&Q;>)>oSX!*rGC;6c_W5~lQRv5wzR*oeN1BS1nmDvq-(WMqCmU)fZz zF$>Y17kiwe{Bj^;^tcq{kn6ba*P2A{;-5sgn&)Ajv)sEaojgR$9(Y`DGH!lMw}zA? z<;TnaD|uevIj(POc~b@Z`})9`)!>DnGb@osbhdXWQqg?BWxPr_epy9Jgr|jBv7zIf zwX|34q@sCwUd{8xQZE+uelC@^k>@>MgzNz;Rfm&Rf}HbZh&N&A=U=X0!SfEDXNtY2 zmQqE>`;+d=-a(y=I^OGujKn$*Uf&NdhVSjeRkMMI;d&+%TZ!lxaGd>rnHa^^B91?`NLJ$Tax4p8IVUzt&&>6u36QhmtcfQuKzSwNN#Go3S-;W$f=M@LR}q-on2U7;&xCVFzsX znB)4UI2E9o0>EcXB2&b6Oc8^|IN5%No`Tj0jW5y*L_e@3>$u%6(2c6vbFYP_-*8;N zb5DjwhLX5g->XbdZamHgr24^`a>Qc9sn!#8Dg%*9kyL4(T&m__opgxZai+FEJWHk4xn5+7(L5YY-x8X;UF^AA}W2goff%%nmwp#8k5KoACqBTq6bn#E>a|zGW zrcG2 z>YIwFNBo4rQPMR?eyg2tU~neoB)U>1GG(m<>;UGdz+zK&5w{#kznb&pATGX>aDFx&byB5F8-th_LukAm_)}9-D1fP(`8g4x@OVh2qp3-y<0Ba37?JIDfLO+bmD_% zKu-xBT%>kp+?7D@y~p)3Wel}cPKf1Jvpv&~-7b`?B6cTXS7t{EiD)-MU6KJ~biJV6 zd$Qpfky2kIc_61we9)D%X)IEURzRr>$=1^5z}2zoe`1L`NAgGYdpU?+#Kn4j*oDV) zm{Udh{^dnkihA}unwDM&Rw9NG)zrphj^vG4_1$;eZk1e!d7M}cBe#p8>0djpw~;nL z)vUS#S~35)e%Jfz;}nAISzG>tft2LkpPo>q8+H4@v|P@0h;8X4T0cEujX%t{<^>4N z2%QH5S;K$zQhZc$vWxQ<{7L5|>RT`&eTHKd0XE;aAthdDkpE_!!Qb;6hR1{vsu0#6 z3XFg4Cj5xYKKVj_%8@HWGMq-eG9q;M(7lk8BmfiJVs76ZAX~a0`**FJci}069OJbMH|QP z7&RjsIR(bmXT-Uo=#AXFZ!$jPtk zh>-klU{w6ZtJ>9;s^j~QSaSrV$F!?EbsdWyu~q?GE_b`G5;?3SFH{LREL!DmxAuex zy%@pkX}8X!AKimvS({`Sbm5?OYtAvKCxHwTM=_4g;z$`x+z&}+an^M?LMPOpKt|9GKd^Vt*zo{Ova!%%2V2{ zGvZh|lmdDWN98b*Esjm8B>TODOJ!qX5Bc8F8$G@a-I3?y1;RIA1%dRLJKG#JoGq9F{HA(brWJygr z|4xNpni<07ccO)hTl8llOD4&W%6c){aCaGv5Md=kd^k(3Ugz{B8;&?$5ijycznx+>^SglYeT zW@V!5f`*~l2)B8^@|#s$dt?G2!w$ z`c_uJCwFJ5bZJBpSq#`3zIeZIB zsy5UhR3cC}>A!HOY;h6cDum5Kx8tD8q8y;2()q8zgyhzKB3g+;GYYDrHzG75c z6HVvdXgubhBn5a>S#o6xR|yzxFHX_cHB7D;hp2%h>GsFu-ZotoB|Tgpv<=gjIRp<@r+#-valdBb8u|X_BSznm%0WS_QoIJ~Htm z`nSaS?P`YTu#X6R}Z~n-FwH? z98JP5M6dY9cCLs)Z{$2{RTsm-@|!3I>9D?>YwaS0=-E>UTO5mTHpP|paljd$bW1z8 z#h|xwt~L2%a%ksm?RGm>9sapY$Iq3eSZmNrUOc^bjgf>VGQ7a8RcVa&*$8V88ZZ*Q z8^;+O$y2}9yVS*7C7Rx^nQUo9$Uw;dgltJc+rz}ivEp89Js>)Kf4j9y9E%qadvUD9 zA+_9{!Z&iu7qqKcwqx+U*5uPXt>kGwj`&QXD;sc*x_hkkr^%1Z8SUydx8slZSZ|6( z4?v~!`FpH0;@2gXyK!XYtFVSzi@V97yxZIDaL9R9b-$cwevt3Q*9gpQ& z>;FygT{)zgC$60jm;rneCd~lubX7vt@D~p)S+XH5wJMDtf`Im|Keh1S117Rv2=xf7 zJ|(g>5z8z1+C(f{dp{+q5}-0Ye~!!xn86LF_T%Y1o}vjtrQ4GYtwuE~iuAW|h<;5g z7TVA7BSsxO!nn>K*9gWygyb(dqRIn_x$?8*5RwlD1_%CYsXErDl#~(qMv=X7yFmJagd9Xfr7$g$S((=VO^V6>YopoMI`A z=c!U`sW}we6}0t=&jZekAdejVcqulfl$W-d7rnTWoqg1$YJ0~jGdhO~5Rx9GfqWhq zH4;a!{FL~lppXbp8i21!Gp)(zsg7ZQn3C!!vpsQlpy+(aOetJ^|KdT|jCQmGhbsFJ zD(CR3s>zS;a9)^QJ5o#Wkn&LP;KgbMJPH5f!&Cztdc`pmzp7hV9;RDyftAVs-mYt2 z%6R&G2^3G!Sk<9-={RZCAKrdx=;e6u_7i#)JPZHRzQB+;RKFaCrXw)R9u+N-n|7s? zI=PjLjUY?Kr_>_&7G2);h2ZPpQhTHzWz{8F-UHu+CDtXw-D0T{ zCABu`yv@oVAW5CbwD95Hg+)}O3gO;|8JTT{F+UEyg8?mnxc&J#Wuu}ifbp{8a!sQ1 z1a1cMuNBXtCba+<#BSd#^l5H7283pOj2}=oDn5j^irUg!C2FH4FJIDo8ZF&}i@s(h zyl+>L4)-llJuGQL*o{)(unRS}R(+j0h#w)Xkm9?7XlLM12@FBA5LnBOO3p28S8s|W zNAEQ`nsNgHp+LhQm0XHK-gq^kg2~onrU6yqs~Z6mqvoV9 z?d@IirV9n(m*$hW9bWRk50@&N0#8|rbqq#l<7oRy*{H!1ksd6y;-gl4C*N$vUxh|- zk!dH5_!A*tXc3NS!({aP3X2Z}R`nEDQSWF-a0Mu=L7@|c_$?@G6zfB$TFEhG6XMTB zz-LngjI!pPm7ib4&%DQ}=)Zw@J_tBc({JJj86UsgdN$mTW&?hscjDOb^oF69$64l# z?*1lq&j}XCvOPa%3JD(2WBuXGhLJIjDP$`TSSd3*LFoDBHOjKx@1It{|8%gN2fuwj7 z4%HEdF|q|=z0evQQk|#d-b$B<2}zVBT;|W>E`-!)Mz~CZ)dR4I(pwLWjg74f?V^EeU;y$tNEFm7Df_By3*Sx`^Ax2!m}WTjDYHJ>m1)*T^9GkW zCocp`6eQOoo0%Q>D}-MfebEWS7h{k0276#Q)b3;M9c&(;eQ9G8?Lv4FN-Agl2qhvU z;&nHUJ$G#wo*IJI_lbab?SThTVo#4DY9>Q8!j46hA?|i@Q`u(}BXswPrbM|E-qnXo zT^2*9;A?O@-WbQ(uY$6)F^$lvzTWjtvNt=jB|ISZVZgaXXfb zz1Y1uWAgAagE**+EHv8atw|^7@%Emu^7b{+#39!&cVNGQRVBu*{iSh>0zzUYgw!-4ZzI zm-WM_h*_6V{-r4EJTqWAVJ<_#XqpdyHl}(r&0;KUU z(uqnOd>H8HV?g5L*W60Jp5PXKpEf;_J~RX^Kv*U;4@dqd(9FAuzo-b^gk$`F%7(s> zT;?2E`~BW2mCQ;+doO$?ZpT+fS>uz-Mme27XjdQNSlMScBw5RqU(ltwBz{Z9FI@RO zm~L%Wepg-Uw;jL9wV+G=N{W16#qTOAgiMVq5JCv!Qy3cyN-od90u+R+47@U3GLVMUQJ5?WeJh}gn&j=n zCGd23rg&tR)FW09^xNgFBb?T}-~Bw%I>#&~x)vS%dJPXD1QN|@0~|}lk@#c!d2uA+ z*fp$dLUc8bwu5D3V@mH~ta--F(yELwEtQ0nKGQp%5}z&<3Tsg4o9UVNYK1*0 zM6W|r&GSkOjZcI6p=u~@go;W&G#RVCaz#RO&7~Ak*enVw`w1=AD72w4xd??B_>$T# z3s{Mo9|cl(Su`u*k$8B-3h_`|td5zfyhs0xZQCtl%UJvvJznw+pOP|<)l)x#c;Vao z2_zR@DTy7r6!mVGzwu^gsQiNnP1a%k5E@cw*=}$h)<{7 z5=$@7{u&fKD9k}2IxFJMHJ|#8usK3i5Cw*I3Z2ShJ)MH)AWRzt?ZTlZCShpQPpIoc zGjXUK%FSa}O$4FhPFf{$Ay=$_Bn0PfLXOP6wexjF) zLX}uWVRCCfQS+nFmrK+tH8(v1LQuzTgd2BrBx+-ZT#Op8GEvzvR(8>NzD1(mcCFP0 zh|XP0nXvyfw_+isyY})Nsy6)60u^^7dSyT?ML`hosm>PsFeUv2E^WYWmEw~*U23gA{VcPYq=@&8|qECIc zcjCo#4%~r~^b4uQ2w5nl@gOqk6Qxr4RFpW6F+8;jVRk>3YT-F3(eDrUh^0c5#J7Vz zJgfbmawOo<4UW{rMO5;B{Aa=o@V_UE>|WPTEQ(Rsh{AakqPLikVrrm!5$1fzz7y^m z+-i@{wOBvcd;{u2RmWcdtw-pDCfAx6N?IeYb1G11Mq&JocnjiCqez#btDsA|@Rkw9 zAKoHIwlW{45y6uTkL)Jp7~Z$i6~ND-zs~3{rtL^(`QSxABdgDI?jvn7d!Or&*d*jc z4i0squnQd#s57IIdwzC#p=Lh9Vi*NEq%;h77dm|#QZc*(o%0xp$D!-Z85h5(NmzO7 z2~>`McA=Jwz_uPo9dM|5efAPf8=%RX)?Xfj5){hOj{hk!z`YTjzA>nQuR~|fSC~`d z=+!W#MvIYB_!iub9r4mdvv??E_>_2@;;0wyF5Id~l^~pwAa5e3LREP;LeC-O3l)DV zRVj~Zk2`wl7DGk%ywETX`p&U2wa_d-IUujKyAY;|FolFK_FtZ;%*SZhDC|KYIuC~m zuLPQl5I+?MXE)i1ufK><=d<6eL zKDvyLRX1O1Kf9=Z`+0D&ulk1)ghC>bM!=W$59RP;lvMvvgHX~>OoQ;1D5;l*VT7uF zloB7OYNMobEgNAALc=Y@R2)nQhfncC`+AkuRjIvRmP0l0N<7b*W~?aNu5Ypd0o^QA z9Ljb96y07n#I_Gk1bT7FeLuVc&&k=wimG!VZN*w9R35ATD07)k%^sm7z3%m+4U(bdjXps`?98S^lQ|7gjF;H|;O1zVH2vi2a}cYKY7qff>Jsl?OZZ5`j{P;yPI5TV>%@83dSTQ4 z7nwWw_7BkOdpXH^8#0a)k#jlAsveBi%PCY0gSP@NEUoOI1L2qx6v8=*Ga*S9Lzl+V zI5g0Q^J?g3jDy$fP667{S6JpH_-;h@wDmzFvWAp&r(#f~iVTwNB<)shZvA(uwfG_) zOa!jrQNggCa?NTI9?C_@;0)k&T|pE_!E0t8vLzFuI&Ah^<4{Tb%}_O$*g>Vz8b~xez7pK9*4UVC*UPtq{UuCkvGXO z*D>gNoG#Hi49!&=L!I=vBC*>X?v5RWH;{N)Q5N`J1zXs>+zqYaR}`)P!-cFSk$)0{ zlqQBiRj4?N|NYC>4G8NO0OK6={`;S$R6h3x;`^N!5Y1|!?Zfo(FXb+9I5C{^|3~KI zH_-KdONX2k?dQaZ*4$_e?&?3nK*kvo-FcHkqfnnk@u3?6mihI0b?9qLBcI9`!DrmzD#HT;r=ye150jp-b{HGf0NU^nKIR~zs$GvWoL8qkNg48 z?C-CyDUE%U2scys*HR!KhW%I%DrXzCwT@VI%5}xE%D0;n1b6qeT8CFU`drTm!5aw3 z+g!XBf?<{hacC!w|8;5&4DBjaM4%C3hl%06=Bd&ZZ{>JDM!R#!9XJj@CEJc+ zFQ}jqobuO`Y%|F!oW{=GuBH&QAZV2!jKJMoSx2xBfoEqfZaBt#Dkn$H3OnJ@`Zu8M z;IO%xWuVa_S$jWW$FO&ia8zoRySyo1q#RKMTM;Zv(1W1HsY&k9U=l$bLF1JO5=A0p z5F9|z)y8`EldNrvXoB!Q6@wriiOoeI22J6V&vSo*J%Vj671KCr95X#-ai(=-GifI= z%=8q#&PWP+f4jro?Hz+3Cvo{3iBfSZmzG<(i`e`|?jm;LZF}SX^Zb!pXY;-=p!4tT zX4nr>lr}A}an|FE5@c;~Fu$=hn`Ovlmii|(n?3b}<#`jiMQ$TGhJX6D{OLpS(}WyH zU{0y`Q>-P5hyw6oL_-R92*cdjN1+MSRfN&Rp!+I??6J9Z>MayGiE}_Hws7T74ipw( zN$LR_=6hUf1D~d?i-;QF zhrY6IZQs`l8!(BWli0Oq(SUD$+Cp)!6`61MI29a(WqS!a`e$i%Bt%ImE?GkXkeoUo|7Emp~SN1&dti#6|zdq9F zO=*H4HTTd>wh_7#!@onjLeQ3boMq3MKbBg))o24>py7}VNh`x#eWK9gILpw+lO$5x zt30{aSds`9TwG1m44;K}V|)MmkJh#b+m!2v^G~FNafIULS@W4c@JH9r-CuKMXdli%vatwqAPP{%7i;v(LZD6;(y;Cn{VIcv*1*L{K*}Yi($!{O#XjZ6ss*K7OB! z(b{n&Kc+cRH?YVk!o%<}7gu|=!?*s#nQG%WVI2QE$%ZJ_6*5XjnS5m&!MH(2@Vl%( zWHf(|4I+#k+rMAf9R2+)c;V}vT4{<_5tH!U@Fs`n9%GNg2V8Mf#I((=UGLH>6=U`j z8$GS5vWDNazwEj;P@NMix6$2vBULNHBk)eR;_6i7-XH6PcNgJtc)SQ7gdebZb6%hn z2L_8In1&C#xC)Vhr^Xn4@1{9xf5=b2G5mYS^P5x3wwt(V8)seh7+V4{oFt-vQ;*!O zaX);xNaCc;t;U^XlOoCv86^)gP%wPy2kq13ZT&4bboxEl)J_&03t)FAZ@0Lh!JF)y z%{50Eo6j&CC&n%2^iO ziLrJUMjuA2jA@K(WmG=IbS0zRHuxd(%`ACwP8l6WV^nK@Xvu_e7(N&r<_F=>FwVXx z5u)~CE*xBn@|3Mb7n@-aBA0$8!!>lW_h-+}n6?cFR zgKd6Z7slC+GlP6X8{yQwSFY*e2sXR8vLA$pNw}+5EA|hOYbV~e50Ps>hPhJ=e1%b5 zBy9t{Czp0sX_I)Tly(xslsJiIOo2Ygas_(?+x!kChI5FZTPcM1?>~3;WRlmiw>pJp z^jZyZjxU|X@jE!)G|?M4$E+xBXU_eT^AOznx#jO<_E`X|th4GiiE#E$)CPg4PvuXi3Y$WmgmL%$| ze0Kp5)o?(GbGrbw@C+jJ@FI+(V$5_=9*SUZwI!hBD`(AWZ1Qp*5#T6;t{C!J4DBsd zq@b!St;6qieq3s;53oGS#Fzov2+0p$*KLSUy*j5Pxph)oiq=nZ&YH4? z>MR1dwGV->k8tCv=WP#C&+h$ICUy`qjjVRbIr@-u^lasgmJ7!57bXMc1Ngc#6KXS<0l7gXAc`wV*oG66T zP8RO2(+1y;NLRs|_RuNz;*{^9s)J5}G!%0CH7V371g!`>;~4gx;5WI_;g~Wu;2gm* zlT!pIiDRZA>_fQ&Nt^^uV-JD)WawwVStwBpx?kmC!|mrgA;+0eQkB8XYjLQ`;QtKt zI0kQfU2tU@x=28EDAgl(1F;0px>`dm;~QZdySUQU!j}kYu6kjd%70S#&+xc*7=ss5 z)~!wcGr!#G;USdbo!H(J-_!M)_sW2az?Ef^?fn*IBAV_Pwgz!(mJ27cW_T5RiiEp{vY^Y5w6pfvbk9&Zd|~bCbK4|M7f*f zEIbQ$w^`*8`WYoP!zYBZgrm33&L+Vk33Tqf-yU`Lk1D>vz?6h{dznoBO=If~#WV?h z|1P{(FTv{&=}TJGfo~h9V0LJLHz|@{L5kqC;G819KTOC9ry{z5snwA&Mt~VQ-E(v_1|!kke+MeK=jB zGR)gGp-~D~B>OfvN%M-OibUc4Bwo%%F*lnjhqhi%Y!!&tE10ZPoK+lNrdW5~62YpR zR>{4H7e*jnBkufD-P_?=_c%; zxrHU|{~?Y3+!NN?ew2Yq%7fvrtUO_+Bw{U8bqMw$D4#{pqh3+^O>0z18=gmD zenB_8k)5gG=bb1R3;hr9A``rw=26(Ia(y0N88}feaL3^l0or~ekFqj2n-JC5iOo`7 zQ)Umm3BDcM8@kszcq3)&0Gt%4x>rvr*ZJ!hBT}y%QL%BZdJK*7n<#u(V??)>lhBqT z>IHZNk-esSkZA>nA0n(dAA4t!1Yvj#&5XjwWtdkhpnDa@g6i-VizUSYj8W$I(!h`C ze>g)NF2^{-K<8bbd#oAhH!~v5A}fKc8K?dLbQ6Y2oPoCEbcxC^Wexq9dqJEDXn6;N zJ)@A%yxUrqELhEn|1y2MpFzH|4{PL1lT_S&X~@9iBh9MM zSvM$LdToBu6|VUq@`Jk@ECQciOAjOAmPG_B`=Syi5O`}(n2j+tSZ=#`1YQPT*+xnm zc6c1y`^a6^js$!B?Fj1t3Xr>hteoKN!z zhB3~$MZISoX9mL`T9;o&wPA)NaH~toW(@P*VrY_1iZda)7sIRy;?QnMZsmN&2)0{I z?fbgb3h<1-h$#Aqo$sgg9~@ptVVCs9C#(l4P`1=@=0D0Wys?|G&B@$+ z8;|ojQgDtI9F=C9YTwTo)QDC#gWA0o-a)9tw=rtFG0YZq4BDs62Dq*bkj&lMDFlfk zd>VcLuIA$G)aYhK*<|2@1ne3hn~@9Y^+fheVeH~p>ebPoBe^g?8#8j?ClQ_V71UXb zMvM)Cm*gu|xD3iF7gq%D6#f1s%qRNUZ4d{MHL7rR7<}i1y?baAPWkQ74h%D|O+uqM z+n{BWMD8b=c{RZrxSheesh&#c*wK1>YPMglSk$q-K|(9qA_gxo@L>2C%$*l;CAtGT zfMMTsK1?g(9E5Iw=8X!~DvZF*RjYQJ+kGgGGe#8uAhEL;W;vLKmRwBxLN^?^_(Z{b z9D!rJNC4OA(Ll;w6C2lpaQbD1=Prt1$;HjthcCX2`jpawNr_%c5BM6j zY$n_e88w$MWqyr5)sJpeWG{xeZS)3fO8P)S29IZi{*9{!Uz%wW|VADhPg082NdHFRED7$N82UZ2Q`*z7}+mhc>htzfO7?=6%sDhvn=Or77*7VurbfRBU*9Fh2cLo_2VE zlWOkL<2X%-Dx6B?wi^fGo8VOr&)qMiig0zIHiw6?z0bd8#a()}_ct6SRHYLtch?<& zZ>AhWcTwsn2EQV|;KfmB#+7k{f;!yXLhnjg{vl?{@rL{#Xj_j>ouyuKjsZwN}^!t*WcV(c8YTnF!+BG!8GMEe|Bxpde@-!(z3_%b<`8ODk z7-t56-nZRsH3Bvy04rNvc7_xOibV3Jne&~xlm>C)IHN@Ih?>TXLHCk$WuH(X`fY9x zmlRGnDO&F)sSNY>gztAIU|wmIv=&ZCdjl+t(}TlES+g2jsm)}Ta1PYp;}pjX%#4$^ zOEiU+MI#>tzK7p`pDa@Gw%>EDh1Za+xq-y35%Z7z{cLqEJ3?rzJZ&8^0J z$tpw?J#Q<`Lf7N$yO&NMxvVhH=2@;5m(kdIlQW9bQ$*AQ??hzY%gEXW+i-tmow}XQFFIu#=UMBIaL2Lr?I+Ge{!0znXI*h*|E2!a z*Yl^RTI%S1lq=oWSw`rQ_Atpjvv{LNXm{WHPn;P!7s(g4i<)@#*&ha*S6 zzyOhPXg`r;jNgD(FF%JKV^-^DfQSY$_(}Z*6+UP~zq9T1+TK!Y?{sg#Y8s_};Tvhy zQLgJDi&&$iYQiutg@pdZ#TjQpbR6SJ41dFc{QD|3+aStK2b{@v5~mrF`iy3}+y!?* z;Slk?6z&L46&KaQB{CCl*cMqcDGJb%qX}pjr~bRptr+IrjtsOPr%QAyM?)E|ieDxi z)ZhN){DGp9#}Kq3VCLf4R1rZ6K@35w1V@SpvIq_#*oVM#9K$@SpZXs6MGHmb?T@oY z$f+v6k7~AvY7o^FDt&{;+ALMJh-v{8pc;KYpu5%L9sB{`rJTLh*=2ZeuXPNafBY-?Q>e~P&m!aEE6#+Q#5sw>BTU|Q z$1sc6tRvyKPwRY>#8^){@8aj275CH+$#fd=j8YwSQdI>0!e&KI9LtH#^TKfsQ5HLT z2ImM)*8`+Z%Ft$i=&#foXF`-P`Z6`nXYBB;CL4oax=jQyn{$=zVpq{AJJ?F zij-~%)i5g4NvOR)2sH_hLdn>E)|!EyEYbwtrwq4~2657);O=nEYV0W|bzKa{dq-gdRysUD zn|YI;a^C4``Ux-epC+@g@LsUKg@0uRaV0^5P6O*MT8-^J&CW8s#^G9QiU;89;j&jw z%?|mX^^^U4mLK^zYHzmN`DH)~aq}Qu?jc%3#{Ydpw(=j0*}=m2 zL3lUHQ6(9~&_`r%njoKruabTOI*Va;eAWhw72p`wVJ68`Pu*31-lOwn)T3sty&0>JH^!4yshPU|noV*!H?&~d%| z1ry`uyYq{xw6!Jtan`%Ja_Fb;VH`yI?%PG4;60qzhY2FXet(R^>v4$4iW0*l3Y^8? zQ^Xm1m_!}Jq}E{>W=A5y;R87J$GD~@hgmn0t9Q?CCL{gThK^&5#Yv8LaeTuV$D25= z#?0+l1XuAlHsS8ZY=$o=JN?olLoTz3)K|Tae01e6J^CG8qs~|g=XjA!rr{;`7G{!x zXH~jsN`E?+L1Qk1v1v-L;}abBl-+9&fYP|fPUZh4)CV;iW@)G-yF@E7%v+Q}?^z`& zoKev!8G6_hgJyA<&ep8PK8>v|S3PMTDA+w&fG;7^m!T@+wsU4ct#Rdtoga>bp26S2 z{3d1nD}UGuJMzu^uA~NzIlKZ}Cn5L7K|j2Wv?ja);n?B7-|2+UK*y1E{h9|UsUoq1 ztEnk`<%yKt3_k+bVoP~yGg9Xm-TnpKWKZHW z<7_)ln?^9~bx|qBCaF9B2KeS8A;a*UB%UEkIfh-3`fIK7->}3?7D}7t z()h|aH8=-FW$1dbF#@d^DLez64tJk{IJ|6xs{EEHUJTP6(l#yV4omP7M5f~fo=ImS z-ytOx)ljI8LMcr_(jIsQwTYj^Swyt5&D7lEj>tSW%Ha4^B7GSAS#~kaJy!@v2PS67 zScSKLEd;H^;R_yYfnb<5RN6_nOY~`Nu-w*;KF*aITXM6wiaAdC?~n(e<~@T+XjPF$ zUHA_?TZF56l|B>4{LzyuLpU`>g0}q!9xcKZw8!T58Z?PhN3k1!PhZ+hbSc#PbKANZ z1Q7&X2s~{V_V2I$i@u68A=-k$r^_y=jzgP?;qEho@K7%4B+e!r{%#vL-l*N@)c0(r zcLWC|AnUx#nu-@j(2ih6g3cll;s`nr_-82{0{eWYq1`zAjiEKG&*m?~Vw>&}#EIdI zO1>Avbc7gGa`Ry+TTxKdloO`)1Suu9-w@(TIf8Q#T0Tbkx+%2xp7&Z4C%AH!eXFp_ zJ*4n{%SoQZ*@V+LNAfUglidGaYu6mf`->#6eGY#Vo)pU$_wq4zoDoDTFXL+Bc8Aws z>jdXEYh&;fiTP{*Hv$;;Hv^z)9Q(ckXIe)jnZ&Ta8Sq>qDa^>>?(-UhA15*2T3L5p z#eL3sRcZJqaSA~deB}fzJ`GgQ_K9~|#{izDZ`0>;#boX-P;&)ny1u7prab{3kH|M<5 zng_J*{c-;2P@(&u$9bMCuJ%@X#bv*0;IpWpJW$PLiFM=(XB--rjBv0X*wD zVs3|{&*zUa<19mcRRmQh^q$x5Y`HW&#saH`-r?4lj*m}+yIFET5wYymw;71VI zKVZU{#yLgOTHjQDaT|!ODB@gGO1zzKHMf_w=3`^i99ftmj*6VcIgYG}Br0<5rl<0J z(*2^a5J7mB#G_B>euRW-N$*4dYv1tPw5Zz=4wo-dBhuS7nk135?j~KZxwDC0Z6X&` zyB1Dj=kLGas8}n{y;`!}5$X2eY@hAew+Ht}^iuK#)hXc4A}Ocg+bO77sAh2@IQ#xW z@kPy5FkHhesx4Ww8oLeKd{sSxGbYtvk;^d4%M5f9r%QAk!(KRDU~9SgS-0T`1=-}Z zc-Yy_iXk`--)i$3eI!Ix>xWl8?5tQ)I02m2Cz(^~9xgmTSp>BR_95_W#n89#Dkh;( z)ZN7MKL46hE6~JVL(du(4A2^AuDdG71UyC3`Xyr29K(2SFMovvy7O4!mBqW3)+xdR z@D>+W^al7Qf|~Vm1gF6zQorwn*B0S%c%_Rg=pfun&<%g1$lhOaelRwa{W8CS6xmnH z!1;4wrEB4tX&x*n!r-sy5HdP`d&2Vk9V0tKGsvh*^SDYz^Y1vtGTJcoJFc@+gxLH$ zUhL5&aKlyBF^-n^&9O+(g|6)?%k$L!i>@1A$R7wQRB9dfZEy`Hor&B+XBvLIh(6>s%w6?ofQ ztj5#K&4I^Q_2@|U)QK~*B=f%HE!IJRFPU+`^WRcx_4TvqGJBfcp!Ub}JCn|1=ZhI$ zkK3K2I)Ssfh-d`fgvh+^p2pdUv+EyZ-GlnL3f1~%>ma}%TrA8ZT*nw%^xaZ1(?!Ui44uQ}H)mj1t*TB!@k3W&f@r& zq0xUZAO4cP=g<{gZW>jA@J^8B@!=F(6|s%T$Zu&z#90 zJSu3io>k--E*<|u+5ImXNCry&U?avXhS`9fL^n-(vzEH-jVoUm>kM-9P$YC5ew_6F ze>)M){&^aj71f2&dl4H3PE>W`+(Ih=_fgLwCG}z$bred{yycSW&;zeTWENXVoB&Sa z8Io3E=+RSk7K&4lwDMxsONdO-LO4x06H3~EVU|~MXkE$Njs9M4VF|JFlBcmW$#M9N z+j=kZB{)8=vuwS=Sv>_`N(N`m-8kCI3Y89Fw)4LW4-QiMB|qt)2kO z^zAr9(6*kl=JGC-nrR{kV(^va67MX+RbHRN!z$+sUhgcDLaTax{sV+jQk{z2nsXX? zKlz(AN)~4rXWyz`K9962Khp*hrVxl%XpQoT@QO7`=Ov5?4`))J0!rY-aOyq1d=k+! zmv_NZ3DO99T-=N+cwAA;vg&2FNC#Bp+&)JGybqDtERNtD!8t`%p0ONFLQmo}dZETJ zODAZWT$`MLPcNM|a4qr{woMRT;w6ecY)RTIY1PEuPrc4rJw2nh%#R}PrueC-28#-JiQ~O05SRNFK)B|s)#HPa~aki`Y zt7!yL)2dl$grqC`lZsqWhX$RbX4y1}vy~LvN}Z%; z<0kNOn+}PpEM}b+g;Ex4S+oyhZ5b6FcV(dpPoo@z*I=tJEDT?*x7X?|;%{Qd*aI9!_CFp}-v zL^+DY2{_!XZ-9@N&Rv&x8YBwa2MTz*!`*>m@X!nAaxYI-=;cXi`r(HtPz`qOpLh~J z4A(?oa{1NvoU8-m98e9^!Bw-|iY5(D!`)jqOYoAie7*XS@4uO?%jT?u&!U|}7`*m< zL1_fq_X38g=mCs#%IWJBq)%&%-Oy}Z0k|&p%sKl{5#83TPm$H!;=R?wU!MG6?)$eY zsP`50@n_8yY?uV#ZAEwkyxGN7&@j9KF5Ah=dbGUv1+D8{Vr3dfTvLP(!Yf={0aNgj zXHj_{)jW-0TzeS@uduoRp7^twV}H#xKGev3hchAC@*MQ~QG6UajN|_==n;%7{;T&Q z&+Kz)J{|UjI3qX*MFZ!O8eMtKxpV@x<<+mYmX&bfdG;0Vr6KgkpEqZJujJfUt6{g_ z;=8q+hTW2DSe1DJUD@-UL~)#KF40de|Bs0pUddH0mnco5n&&$?ed0eS>LJnQT%sUO zb1u;(|2fe#x=s@5-ljT>lOmDMje2YDa#r~&E(eIrTV5fYVxqQ{qS${B^*bUneWh%X z)mlNr9#wq((No`LEShlmDGCp7FwCo95olEv=Ss8&gTuVS53R##d`|B=-}y7Xl9gvtq4CLN}u}4_3eXO1=)hn(tSnpWEy6>_l@);sFfv%24uhZaQ%q&*@#) zdeoJN+CPI}9Ny-fi!II+W>l=@i!?tLNsjDWt=xnkTK`oCh7m3E@3 zKw~~yl)!1hsjpNeFeu6e8#B-j!msQCvb|SuZG^8Zj>#5&NZBgNQH&WD85N3>LT#Gj z%Z*MM0_V~c)5`K(#6G{%6d6L);B-M-8~lZN2b)cRb_4&OQ`KOBry#K>Ky)C$~x&bG6USX6lyzV^C1W{Uh z5ZG6x|GOylBS;kCN%#ody@(mNxpk^a`yV(Q_=_rbfdy`wL;%3s)fQTcJeq(JY>tt(zg#+^0!DRs`4h}cnM&e=L^_#}UayY{uL zejpQzyahbT;gclmR&maLxiwE5&!#o3{kS#qv}5f06%*McX}WQ?i6$^KjLuF#`_?## z-*%~WSVw2qaumbotDQ4ns`I}1(o(Bp5A$73fcdPhmSzfY5vy89yZ|X0Fzk4*qZQXV z@%A)Whjn!Ki#RG{5W^HE(aN$Ar~W+JGX0{tGcgr@c?0u5vbs7`_zNl|YpZk0@W2MU z3}$P!IZT@%GlMINa|mZyiBlLu)l@hI&ET{$C_E(>lG!P!@Ad3=;V@J#^6bT!(BVTi zxv;dK!@id|+7!-uoYrdYA^Trqucf@cm$A2U4)boJn#pE><7CHuJ%*Wgqi7iSsj ztE_iY?Y!jwQkD6}(bRCLjniwzt|nMV4GkNvrxVo>EQ)c5j4_M}8K*H!`1qBSFvvCQ z0%#E9=|TVE1rGHE^GBmPPz-(u9#v0Uw_YC!xZvz0Z~+(>^sKiYP`sv#7$GvYV%SeH zHlI}z#%WvwZIQtp*=1R1=%W0bG(;=k$O(h5yi-yMl6Dlk1pb%WB}fDJA~q#>>SF6j zWwAgO{Mnz?qa>bz2MatC=Cuu>s6onk^a((|I zyIc`q&Bac+4qjwkTT2$Pi)m>Y{TQZYB3mdv&MD~H9`q|GK~*|{AOVl6g`W)C!Nb7g zx!^w!T07Pev*D$jTp3{u6Fl6;o(Im1Xh?_asdNIm=@QcdoO=wjn8-M^>qTf=pk`2n z-pqKHBif&%ap)wD|HaT*40G?7hNf|LiB9Ec@GZ7>RCFvyW6%^%c^%arzU1k3_|uQ8 zLbl+HPd9E)U1)7V=s&RG>8qCcS+!UD>MDZ2LCWD~t<&;ALm1AWERM6nnJdja2B&aPCA&Q`e2>c=BHRoej z6$z4rSD33*CxCw_>AU6Fo^=m*H#ZGdMG%u~$I#Cw>#qL7e&^G=X7$ z1)hPXvPK$R z#(Ioh7puWB)LhlU|7AJmY8C}+hIcBN&Q%oWfSrO*Iu%hT5gd{FrNkb_AlnN|y>Dfv z!7(qJG~kqkkT82!M{t&k#OZ`DlEUoqBydj3Sx?Z@80Is48E6@CxG8QmqWCUI{XL%Yhq8Rlu1~Il^lrOz%?o2{UonN14?Gf1CMBxP{ z&a=ud?|s3Q%{#c>US7CM5`l+`@J@Kp#nqf~c;Ir{>QZibs$2q%q)7y2Mfd{zG^Hv- zll!NDS@_8&DosGoULxDSd}!w)h%=L;=0}bR=mBW`%h4t=wqW>oUr~6Xyziu=UomIh zAZ5>MnCoQh{C}j?@6uu%j^UJVr28DfXxvDnO|`IKq)6W9`>kC9f!EHRVZ?E{d7*Vs zpyhRQXL@w~nRuZ!A&>|=8&uzVp|uR~gkH}j<`vv+q~66<==J&aRr^fC<3)G|9&>TE zkN4f&DiYK@Z4Kh=bcqzS8NRg$kHA}8TtPeGn+VDmeVB)FMsVu?oARF)-3HA-r{2Jb z)GL`gxng6RZR8NnQJe|M(-`K2#i4TiuW%@TKZ*xtujnl+&%9yI{({S!tE_8vxc^Gi zM(bLat}JYy@Ozk8i|}^%w2P}MG59zE%NyyCV=jT(CWTR7{Qp3aYP2sm`daC2A|izZW6lq#=_0o1^8+B$`zrin1xroDSz)(yfVs73EaI`8-%yG^s0I@Jn|-H zG<}9FiqnI$Owq~@p`J$Jy}#0`e-$9SWzPNx)6JFEwpaC@*XnC4JeS`0aScSca?Gn- z0eHs6m45>~y~XM45uD>LkrH>pj~3x^_z@RZ&_Vbif^N8sVy~x^gFx?1=U6)c8wLT2 zx^gj4`F?taiz`wPo@nC~lF&2qmN{!)M#WanS`$Vc#>}7T8I$OmaJGpqy&vP3(7*?1 z44ffod2s98nSRYI)^n{HfxfGq347mjHDRCE8oQ>j-9`uzEy5?^5f@j17vSM*oc8o} zaME2O)w~wIsR$3j>s(wx+u&6Moxhyg4PcbN+A&N&pX9LUHql{at~VY#*qwwjeBzz1_L+U0q@A z0eDWngBF&N#W*ITt(`tB;}C{E39vEsAy!fCh0Qw+pK@{4I0GLeaaS`PCgl>S34_;C zI~P~NW_W^x$4KaDdpG5fvHrczM3Lg~Zk*QFK%*GCMXQKIx4+jOe@ zGW{#{vlyQd9Hl;WE${4f(M4nJ#K=bv^3SCA-z41#4P%VOw(d_@TA-DTgtdGGYue*(zttt@b)WS3pb zQr|~dE0X5mGOu)FpTyQ%j4zJh1W3PfD^I6?iPYlb*xo10t@0L%HSA=hI_Dk-rwEWD zn^puHF!Cy|hR7l~;^L}L5wcgfoV@vrTch1KRpp=w2Cm zc<fENk=2`j<`ntB`fR(pnDo>15Q}C5F7Vj^@)e=F6hq1lCd8YG3 zKk_=B=x1DERIMfCaQjJo;A3>I_ff~!QSNpbd{gwwC={pQy3zxW!D|SkCeFPMnSl4e z3%V7&o1o_9fizA6XICpP4@|#5zkUq_R21m9Lm&4T5*TICOd(I5B0jEn;hJ9Pm#bOs{0=l85qwtM@7=jkKJClBRGYQRg zKZVoeI2G+UAyVjsc@M94eoof+dWM=b2VYPAN@?fw! zIwML9O%vx?HE--K^R53NJHkZqR(qT`BBv4WhOQh-$|qxUtLu$yp2iXME7{>y44xa< zejX#5=ky23@r?}k10UiHAoSE-OA{_|Kb`6(?6rkqr)_TScoXW8PKqw0`@>X7A7u%D zilrpZjA$CevxP}(=f?^=(g@1-k8$UTz|;P5MvaUlhS|0YewxV;JVFMWJ$*q5k7t`J+zlmP9a%pz+NJ%3_5r zkU;>~kCS=X62q)@LOrw>&V*<;hQ4ffT^yPqh63kiY<0##_#ybp(IqFY!glH$@Pf6v=+{g=qyGn`EQIuaSEpV9{5SPdtfDOZq;8y>um0svp;xr z=AWyrv2-ubGVbavD_ue})k98qabFzxJohA@DO`Ltz$=UJFx>0nYVUUV5<$&*sjGf4nBwpuoYwz^ z$}j`g7q{ubJQ{K6sT?)?_etmo2^-%^gd-Sc|2_*{R5;PPz4Ww7%~aPj|KQAsmVKU? z>TMVU81*s&Utq80ZA^`keQ3045ZKR{!l5R-go?rb4Sz56ZM*>2885tM^&pSNdCg}# z?Q5Fsr2XG%;TFnHIdtGRE?yVLx+4M5z(XH$%$}a`ae3ABk4}0F&CyQvZ@Z)Iq zy`4&ze2Eq{4@#kdFU_4fptAkrNo$^?YkT_hv(TJW*~g|7{0O%9!6&WycTkBeAgq^x z?tIeP2JloJn6vi0gW00uW`?1Ty!}aQ^c}sIdKMFN){~O#zKzqig8|oloAYwbqkmm( z{uK1{32lDd)BZ&|3P;T%@yCDV&*rfT8waSaxye_BN+O(sN3gwn2y^_sU*gYx?_l1_ zlFcd7c}`=P`6c-!1|3dgJJdTsDR@v)orR*!n~#-E=+dJGCN+ID)7i66VJl+RaV5azpSDk zO$%vTbZC@Av&*{Jla*(uib7Ig|ew;p;@%ueLgzS#7Vx z7T?3kndSJhgeNi9z89nC4%$%02!<(?@5`)UaSn>s-8pAHfZ-oc7S^Q`;1$Y#xVUhcnd2woKevM z471abMcYq6Q-kcItF5NT^w)xC^;KFD94S(d6nupAtsfwe4D*$jICKp4xK72j1kzVt zHimAcLc@iFw++4>?rx(fJTgqrQ|xw(ay`3DLA!BUJD>+J8t1qm^>uLjQFX5~`&xgr zXJ0GT!K)ih_tMT%hcV1zEq)t=0>}SB=w=MlC~2r9yF|BQ*kAJ)pc3Dtsi6MKZ|1LN z)mNhk>JTg|SsR8{KpRug&8VfwP4BAUG&}-#S2hFRO5&~$5haFUp5TSP!nOwLm0J{w z*aqJzwdRZ%PP9nKen(`!=#awMOA7rFl-1Zh*!H-+-9B*eS~30zV{CC(S#JpoZ$H!E$eqClI6& z)PI;^ka0y&E2a^gbaA!O5_~}k^`J2@Xh#_$iiaq6p`y@YNqgW*YVMtqI7-1Eg<7-P zIZ*!^hHVxnaF}W0BgAaNu)nzTRi+c1nUAnM+m69U(dkY)%(eN-Ne*v5oIhw)iv@?T z>=&}L@G$z7_g1Q1<=0psPLmBm&rTrtQkIu$n1SCevD~;32#|>R~(zm`&FmpN#yH~ z5%c2|SB4q8S!fVvpJ*+HSqO!{&KV+xyYbrL4T#LbK8_PoiY}6F!Z1@r8mfT1p#JT| zaL=-VyO^~Qn7TFNv>|fWEdt++=#*l2VDLAs)~%Ilgd@J`{P{uEn}k0TsVL@;nFR;Zv z!IZj}eD{5V5+;e~u5>8LkVY_pz%!2VB*xm)zs%3MfgEa4ikltB^M7MCev)}*>Q{x6 zz!Jjazapf*wjTHf%PSnd635>{IG!I?Z5TlSw@yhAMoI_ZHaFxNDJy zx1iyx0qhK7sGn6Np-rgOKHkA!uU_%@$J_2^rvRNg#KsuTCUi|s&bgm5^~1NrSDpjY zt8H#Ic2neb1Zp0N{Pf4RGYGng-X#G>L7xuZ!x9+5C<4!bl;+w19YnpdFDSo$cmk3A z^(Wi0w@UoKT5bPT@(k4X8{&M5fZZ78vtwhQVt{7wCO*Y1arC#0RF3;G3R*BZ%!USn z#!nLryzI zaaupim8cVWis;_w|HA4LDEXc9)cT)O*3f5p$~p$%QuXvd6|C)Boa7=r3LkKB<=+GE z`<;D>zcPsvcZn2q93Cse)9|Q^E9eqDLeM>*qu2`w27&x_Ve2qp!`9yy_L}zlm}FdB zkz(-8zh_;rm(#iV5gvrgNY2uaWQ=3jdsFvwK5&Lat4?rTmeGN+jL~}JL}5!MNph$N zABP`saTO&E-%CKVXXib_;?5;fO9kMaMR)_e-Nh9&3~wXo%;zcYQ4Iaor!E1VM6HPG zEV{Kq{P@F+n|m18(N zT_P2*AHKB+Pr@ltUJq5!arh<$)iz}YXAq}rAN7}EKacs2O(#STLCs_scc?$kJ>?N1 z4-?J%*hF44pxHE^Ylcy(JD*wHv`UAm&h~&yrl?F!YNT< zGr;Qz%9*Dba1uCO*Hd8`b~B`GIw3ls0_bf7pH1x-Sk^vdt=-SjwgqMljMlM*{H#>8 zEGdSI@XGHpC%Cxk8-(`}a8v=~E`b6@5yXn{9(dHn6)*vh5U{?N%UI77`5jw=G=lCY zn4b}pPZEKNu*CboQR^VUv-yusgG9c^Y=Co0vdE*%E0VqYD1Xoo+0;p=qok2d;_QO@ zp?Tv-*#*9D3x<@e<}s!hy;%{3Zhfq<`Fh|jE^cZC-$Y_{i;d$r4K9(IDh;o7aV1`Y zSCV+o7b!yW6g^hPY{scVbd1a1h#YWcLVXRMhup zRxNBR+|;$SHUXQR~~e3&rllHVY%)I2{z{;Ejaoz%YM*diF+EIDL3bNt8rl zeR3v=xcM)I{b3y5P=u%9wJvT>HN5gKc0ai?@E}j;Tp~401H7aN55pI!;>zp1g0{nF zDe03pQRH@_`z=-JNvFNi9PYu{B|0F=2W~5p&;w8M^Kk-rxBOtWl{me>rZn;+`u7s$ zL)+T7l%JQ%mO#*5gpa^GTwGMR+Ydhb>Dj&fZLTJrD0)n`Av4DMci zCgC-3_v&*T-T-&6KGX26F1<>#1dmb(v-k`=M1#mVNYT2h=k48+43a*Q9?(qt;_q6X z1Q*}aXPl|m|6MM=H}_Uv2LZ+`Py9meSo6pGs6eSvxVlY()aF&zJG6n!%x$5bT#>~Sl= z)58(78RPpIdmcCkp}r_V)qA`evqsw~Y4BnveT z)W6q>rRziP<2Rw7vxGoBApu6-{hMicM^OG1;vPV0wvi?s%EwsOoR6I-Qg`1JLx=*^B=o2&che;uu9B$OxvvK*$~5|MHO)`&Uv2qTbEn&PJNx20 z&vWoSHm)fR{emr&^QhzPWGTbEAr^;LozL0011dxFL3J8hd4A!ET!L31GOy9 z#xpiXy7|sc5N9{e=peIp47GdKi6ZES*N{?;nR}tG2cCehY-HI9_#pz;f0Y)RQZ{igt<$q|rQx0CP8*SF+#t@Z%0klGstfW<-atY{5wFm+G(56epRc#SFE~ij#S4g| zoux^f1!PT5X1SfE1-NfbVIi{cvNd%6uQ7JK2-K+FXAytuZ|u`feT}iB<1-xh5WrMv zW8#-IBVzYi8gaP0s*~^%5^uYcK|{E_)2^2D{mK>`L{N^>-fX(!ur;9+9Ys>aNU@WU z=7Z_j?b!B5>zxDJ4pHLmP;)C4_%#c1oFP$Tq*)C{p$cM_O8q#}+Y3)e-}-g*ZBYAZ z$Z;+!I0vDAax6HfVFV^mCF@6NJ_i_p9zxx%wp|`(n~Bc>)=fhfp*7H4?^5eW;iuul z*xvh5=U&b6d3LX*26xe0C)XBUbt1pv@?C^?!jmqpHjl#-1oRIP@PJF8GdPK0ZxOx# zrzCloJq66dcM@bgV!vO@A>fRwSJ-MWUw_QJh7h zFRA(ycUyas^vsdk`7>Vi{BPgQgWB&p*WczDChK+i1yR8x@a`hK6W-zCrX}Fp*U=K+ zV6!aZ5}1}i5H7+O;GrTs3*UNie)mwE$}|fA7gqs-@Xc^$G3)!^=)J%*P0P$v8c)-U z=;C){l)cz#&q=g$xLETjux{SkBcr08o*|<<=uFJf-*HP2%rArT>VfY@WPcq5CvXvS z$32RHp-WCh4C=kexsLvBD0dxwQr{f-J@W`UGxvva%FwB5D`&QLIO&~Vs^e7Q_=m~D z7@8E*Q1Z*0a#gw|cpd6i-fpW7JYt-@X-1+3o7=-Sf>WasDZY}L@t%a%;xyjtu3S_jT|QO2Hh8#5O{4G@0xm0?oywdiIOk{-H*>_xDILf5 zzToTDwr`?1a4|L0yCs1WTasietB1W8ZK${;f09!c-g$Zjd}Ybi=mDEsLnCAtzl7D3u4++eA8Pjnx(9v; zzVdX*PQXVmYiq-E$SZw5N8kjMB5#sU{*QZ}L1iOyXogYZSTyBV6{8PckARVdI& zL~2s+jbB~)n5W;-*`JQHgITTjak)56f|ch_<;*&QeF(~x?SLZA4_c!D&-Rzum)k32 ze_%R!S$<=wfc*|%SyY{LR5zR@(^@0 zj{gW1L0ix~lL!=S8v>Kee%A4*O@~A&kex*os{EEkyD>)fw@;hC-CNd}bcI%BrjZ|l z*I?&eCgH>I-FlC&@pfy^w`s%E4RjJ+Coa0(It=igzI5LHgO}&tzS>HDi}y@oC%GJM zEWBv+!xJv9bCiU~H`+7a#%Y|rE|ChEf$w&4CH6kXC6UB8e22P@ZKAF+HvKoVyNuu~ znB7M)dN4L%_>VRgp0)*oj5Rtp623ptad8eR+4L*ttp}7WeOZ2mly@h}$;;*~PYOZR z<%NO~1Z9^q8}{qBpDEr29V?<*LN$y^e|dFd;1t8aB~twx;AyyfIEQV{A7SL=EFkF9 z8ehO?YwnZMo%mK6~n(hTv&s6hJG2QUw)79 zsn^e+snd%L58lEbTqJz*&9s@0%)Z%~hab4b8Uk$Sd`o^&RfWjoEJ9q|G^5RR%fPbb z`}ES2E|pS`pmK9f4`GL!pCRwM#oFw#ykW_0OC3`tvLHIC7E-VSHXWko+g+d|6&WR&pIP%lqdqX7Tjw-yGC zK0%LuE2C6`ns?+2RI?<4ig$1Vf4~&)+cBSeCjIm`43`kpxwsnCx5yN;gC6_?B3HEM zN0uOrproDCj=L2(E`?v39-jZy3 z7kdVp4nA-*f5VYaKMcNaKJS$gow_(F#^E*Cxqsq=@JYD)qLYFzz*p`$so2x-viFm- z9&BcD!bfQE2Pj+wLkp(s!hdBVKT_ED+W!NOIeb#(;wtq)XF1Xj_kBBmPHaFDgm+W4 z3hmTv__E%rUi94Zs#{;l#{yq{L&(}P-g{p8)(_2}$!gNP_{&z;IOm}D!-eM{_$0UW zA7<1eSX==}Fw!`Y+CM&TZF!KEh<7n0G5mvF`AYSu z;1ajn2u2@d@Qz(ao0%kgNYc%_s!0wX-&2@u9DWqhmLK(Aw6|hq%!?gj4TE?BQ)1Qd8(*~c{8YE3v`JKrwEV@@*5qq@YpTOp){fAX6NX~7!^^(K$I zjpJ0{_0Se<&e}6G%Dh-mYF=1>VOWd<>jn z$pv+jA(OhaO-iP(wa^{mS3Ktopd~BN(0Kp0ie!bUv6r^Qd1X z;O!4OgJc|Mdl69@z8TT3W0V7db%Ts0j8TlWr(H?Z)iNYG3D;%V`=hw!nPv(&^y9(; zjI3H!a^T1F))f-$Jen^sofg5?qjcJ7hI_|Pn8@@s;jm{_Nk7gE$vj6fxTIfjb^zM+ z(EOQ0x}Xg0vo`#aqep(uJ%x< zTTlLy%)>MD*4ke&bov$;I!G8g>sK*$)R1ZKs*?C0Xro_|)#jrY{&t@2;f3D%#SKhv&K{_OKs*Hp3giNbLGC@Y_!4UTiFhKmTM5ey*MfuMYH zk-aE&(~s}9ZUA^r{+0f6oOX;pMUfOE^HgCbiPBXiX$1AZQ9J&NB)VtFKo|a%uU4CR z`BUO2pON2Ys(Ao@{22?@kfLl}yOW2?H z{O`{(%fGd^(tKZGkPzX2)0+Ay^dwFT&bAra_&~{mwNJ+4ss(FQ#%2%YnW5E>(q8V8 zC!V#cWQz8xPgC*$B{zdC1Eu~}7t|l33Sqmb>)%LG)y%>2RV5t=MwRR|hS{x+LFJVH zj;+wCio*6zArN0#3bpq%{CE+4#^K5`cRe#_pAQ2rxbzw^3G^M$TsYIr_F0MdmLBUc zCGqt4L5<@lkG%z0^zno~7Q& zXOoyC|Zu*-(!_OLWYX~wV3yndz>G-Y<`4=RAmKmAKAb5yj3L?6yDvYzGts0 zX-0C85S~d4)20!qoKvC|&!dRuMh#kn(>M!_p2KOI)92dGrUT*pf4a^GuFC3s;N-m^ z1{LM4$P0>riFq-MYf)mOycWf^Y+|E{#S$AOmd)FuiGzw7OVsy8?6{=nCKV+WTde2@ zHa6Mjl8PoZH(6tOLH^u|l8PqA@B7@#)q5}R-p@yQ-tT$NzvrCuob#Ud&-LBM=cI)b z=^|5dIBA;d9xGD&j%>S7jdpLdgb#Bbr{4LPH=t7fv(1`lKR>u(#Gn!{18$ZsdF~@} z!Raf7x0~2vCWYB4MKjczdV$;fVxjoP731Bc2n81kCnQ?&MQ)Y&F+$cfZ+TNpWe6LE z>_lK+DPFaHjGd}EJNWUo1>vLCQzec&O3zP^8!ySSQnm0X@uK6$JM8GWlfqIt@h)$eM|haC75q=S;Wv?LjJ#uxz{nPNE!u$4P5m`P1?D zu~Hw{YMwkyPz!M%Bd#eX5toBt%};duuMrdE$D*X?=1rXxR))f$XqF&M?crU+*rbW$ zqYX{rlAZK-`E0f{gQSoEw~JeyyGd;zf#{@5=yuXB(>Ade`_?v#_u+rLWm1?nd!l1> z!pml3<~z8Dj9g-%Qwc9Z$J#3e6=Az9MxcG1tc50eLZV6OYEbBcS4d&bE>W+cXtmFo zScZc08D(>5bDbqvB`1|3N|IVFyac7RWB9JhOKC27BzY9t%E{(q(qwbp{4gQGWi~fI zNC>G&!Rz$lb%y7ScVbeKL%c=H1x)Vnz@@d<>%c9SxhFgq;(;f_WvMHjVJWTP^*R^g zbVKx|edFNy@MYY9d9{xlFcp_EGWo^I(jr2VubJ4+<^O}%jC09N+FzFEA~(X5NGE5U z%V*ZbR!+E-=m4^L!^5%&OnoNe*>JAduib85r#AF&JKyA{G@JV|QfjKt8=TWlG+V0M z_to6<9#%&sw1Uv60j`3}7P*724)CMPR})*(EGVC}o!?R~&q zdgQwC_O~;YRNmlL`#+Tl{}w#jr@T8JmxG-@BW@~!cP{Xtm&J+q1Ao(*W{~%Y#sP$b z2#Kw?F>6wP>2V*#gwGyYNz)5<<}o%A zqCI)z7TxLM0~zw3?dTA%_vEdjx}T$1iQv7L&_07@E+;F6X52w_5v;X$1{X+L+@8Sl z;Z9m$2ibOi&Z9;d`SeNI6@GSuIxg|6SL3z5Ku9idtHmO;AW%-WhwpZ)?O$N1*g`BO zf@K31`(oRIh1EX^?l9glH6o-qnt$k1j`O@n-y-RFyr%g z`!KU%CgOX2^znqX=u7j}z;nu|_*XdU+OmlmbxA~c z@_2&&?*a_N55N<~x&Kj`=vnj!c;HxBP+RQb4fg)sBV zj7y-8Ppo_nd4kQOS~W$xNZtI+wrQs7&5WXNa4t;< zd%j`tv?Cn)hAh)7iSy02H73s%^8T+3u&s=={}Pms(EQ(ROH2*hm;+7_6r(Y-pV+o2 zyhd}6wfa`0l_$1kn9Mq!=)|@a)=GWcHeyWQRounErg#8j!qVPxGZrfx^-A&N9 z+m=Lx{fdQ_S#9mnFH)aG|Er%H_Y31WijQ#2W8yL3dGJcO zd0bciNVB=%#UyBr(c*U`Xgp>3oO{PyZIQ|HynDx5{;ucmUjCY2kOsoeFHoB^v=ycU z2y4$Eq^^!WB_zEb^G?#1X6L@l6WT%Q$b7D-f@^XZC1N+{ z+zB}Q3_Vu88=+lpTE7oFOvZ$V+i9-J+T$kYyLgq!+JmN@9gs+>*MhJ|1UJGFglzNs z><P$H#u4V=3Iqsj<8fYQ(F{a z>%u*qp{6HlvFe&A?P}9#7v3$3wm$GL+9^t7lKRL!wqC7^*Jh}aE40WdaSpuQfEU4ALb!OKa(F#FORB}Ha{L$9uHCL?ovlr^N>YK1Al;#j zC{48W^0T!?3!*7>oWvbJq|9-PSRKIwosbL}J6!rkg^K@Jo58&_E^7H#0L}x~t93VM zRuyxOmKk36Z#n;0qLz5J^p9awlDg$$McucW!S(Dp+B8#fH~sA#22LYFlzh9R@*36x zoZwE`JwaF;qb&$8{}01Pt;*5ns81iz&QuLCINI+25IIJB#*}fC5pb@yB)svcOh${e zDywQeS4&Q_xyRQ9Qce!3nJbg#4&hS1O1Q&K#^+I-0-ung%FfdwrrKGj?2B#!dsJV_g5uSkTKcpix!kdU_eNyLgpOY3&)>^P%^f5}R)>+8M zc5zj->abwH!ee+4i?+&C-iNL90;xJM! z(5&&1gTZ}D4A|+I6gG@rky>Y!`dpw{vXevfr1VKk7(WI)10EK_CEXmjX8?0tfL}FA zu=al>*z!LT>>N*U^@X&weUK`OP=IjgLQHS-V8K{zmNm;0TuBFoX}_LTI0`Fc>26&p z6sl(?;qLwzt6gF8e98)nm}y;~2FH|Y*WbY67arJ=q+7JXn~1plA}u9*2nFx<1_5$N z#ON$89zGl2j`GrRw*pUv2afF=!ZYA;pRo$Nh!sV`=WNzZV?{CaMetyjlt~GLtoKu zakN|K2&(bg0;}_z;GrSy)|JgQ%QqA&9?fEe*W$HR){zsw>%Z~b!^C_wPAWgj)y;Hm zMMTcGl=}?z(QmX%Rl{^G-_-XltILhroYKan^mal6n^SDs4tE=HH@p)b+Pb4~PY4$) zSZ>B!jJf^KCVHLvV%ZLwly&IZkN%~aXJ}`c62@re8I0id<{mXS0gG27tQ27wVRHhV z)Dhk@*6p39)kuOCYjTJ8sHroxrKZM+9<_QVs*RI-)b^R!*cREN4$jnenDWji=wi~X zjqOqUFGlAu0xcP@ViNHjZqBTU#7MsgA);#5*O$Cc2|dkmagSPf zPZdvlp;Eqroe03x*{HN5EEgd*5$n&^QX)KwJ!2hbs5?5UV%0~pwM$K|S>%_@Aa0vY zb0m|TWloRUo6N8fVe=K*oHJeDW05kahn*^Q_KVDpm(8IHql7M;L-Wn2-| z8l1y2vLvO4hw9bVDk`<;QkIcn^PW>{FQtV?QqaAWRjvCniZ~acHI+=}YU@m+*Y~Is zb4joIdsNUyp@$H5iIAB~^NQd?u%?hz_3b@sZ3?9F`xI7$;+15cLguc#9^T*ft*x(_ z$GX$J3R}<9W<^+5_3#x)U&vb$Qb)*%d1QIuPO`jAO!clAtg zel2&fT0|i`Ra+6Bw5Dfl)OT&#lB#j1XAOl-rLMN*=Ty{ugq=UcQu9f4J!JcQabgGu z=VRi+!X9;eKK;OckGIs%PNKiwb-6Y#q8-4r|Li5qhOb=CDkk|}#?9qoW&~@R441VO zA&t6M7h%IR?RVi?RnJ(adgc-?#P6^ZXXkdRZYM)?HP(5bdnO%rM%FO+h@BKH;HU-K zsic`+|lFPM;`Bl;-I4oxH8&7(<~r`GK7O72st4_4Z_?j5E>CyijeV? zw;yqH5uy1C+NewQ@DR_A`&iOMU&*yx`%Y?dC6^hw`$_If#_zH}^{{86=KZqjQnf6d zGLQa=)Y7Sb-k)jlbdpW@3$;ks)>+Hn?(yFC9xr2tF#nr zaXX#Zuf|`|%qiqP1`0<-Gv*y^d$lBvkbSkbD&F~Sk8f9RJX)nhy9dj_>(rJ|Wee|QUlLOuMjI=Mi|I26 z%j)$CypB{fDXfi?6GBsu^{B*a5SAfii%^KLL4;z2UDsfb-3SM-VW^}IkotGDH4z;H zJ?zV?Yj$eWRpWOwXT;7=afp+4%%f4`GBukie~8pFX`hPY;^X|)^;z9ZlwP&#Ix0VMX0JLz3Z}zRz5Iv-LUJ@|E@nKAUev3$FV<#F-#M+<`-GK09cdEB zkC-#z%*=OuNF7I?*Q1|uXpz>#*505A#EEh>$_K2yD$zj?ZA<7?8yu3+%wDy}K^eLb zj*8HJaj);^1Y0(6i;9!%B~-EzVOKFNsx6^K+vIGCmJ%P6*c&v%NJcp>)@g87gg@10 ztLW>sBx}O#-k=#udRz;7WwS~DdeW~!*l<0D&PeW6d#|TtZ3ssY(mct*l@YU6KgcB` z+>Pu%YzX!6x;fbH22$uoSbGDt?YOj8HQ&IH?VH=nJqPvd9K6qES=t;^o~>7{%)+ZS zA?(Rw_K8mE>|Je7cr83BV0@ARf}(=+_fkK z&b|_H6ondi8M6QIjy@jTH_xL8H)0DB4kB2?=Jk5N^WoQ&EK1PqKq2ZTsUgC`oAB^u zsl8*3YTr#&7pYfn(k_k|<~+-!Zl0}AQ$sgtsU}Yv6>VhQl9?^um9y+@5=gc8s*TyS z`sfvyD4Pz~ekDOpZT{qzpRlm=op1{#y;nWvq&Eb`76+O4L7Yq1F*+?kQLiH)&qu^Dw6Yj9aw}O|F~JxD}0VgtfPlT0%C%>{jWWw=g(w)mDXDR*13JovkOT z{JS*s6n7cU7FMf1`9al%s`9&<-Bh=tSMC2UUAdhAGiA`o;k@PA^`^qxsPJ-fh+fGc zTdu9KcHhzYRy_p5ONITRtLfG9a!ZmcipJ-z7_GdbfimY0Mb6r}?QCvvnU z5jl7Fj&+@(-YwT>skJL8c))oUwQJhT>iN8T&%Qp)(-G^@#R5B=vhCL_;1y}l<5 z#>*f!9W9>}7JYB8+I$;6CTVSOUl9ezLY1R0hZJ2W{Mat9ovVYvH=ypqbK6Qnn{}aBv;H`g`mTRNmLil=-i#_>A=JSLjhHE?0{-jowE( zxujElKk4MM^V#|%Dh#ovZovDF7hL{Gg6%(Jzj*^@yPfe;kFZ^YWEUkv2rqGA3AOGn zI!5C63Fv+h)$eOB^IHQXdY869Wv&z#%USkHjO*A$ms-ib>(0mN1S_>g)~?5cYas@y zf0C;;6c*-Tv79F+T5K2v2YlROd3jpojHJ!n&x4tz=;MdfCIephgx8W>#3E4FYiHC$ zGk?|_bTyoVb{l-z&wADJRk)84guSb9bbiKIq>sdm39Z^U%#2&dU-$0)fw7$PE6BJ4tlk9=xk zopZMF{ML?Bb@uj>a#-q9m~;jATvLC5rFU|+@CUTS2*QRRP~-wduZ6^Ss^IEM^SU(3 z0UxhH(p}Ubb0mDGBqMBT&=AMudbExx^6YMW8PZL z<;~D@y=rhZ>z1w;Xz~J5iL0Z01GJ4J$rN)Ryu+k zTE`T-8wI9V@8f3cG+SD9SFl+vL};vGD+iu{>^~d`?eOF-#`%5XjXuJx_ffHBN3rI8 zlqRf~p!=~x*fDzZ{Zu}=uU8$qpN3B!q>(1Gc12Z>tqfy z=zc_7^qqH1MQwm+Q;(^&8?;%IDyFLM|4_epvhCL_cYw`6QyId>QH}3*`e@KXQ;bjz zFPwTThz=ZOdQjtVQtr^N*<$ zF3OjSkoX{ikZcizY!IOUVb_DqIg)tbhLsdAua^5LC=5PG@iYYMkBQRe6L=-?$GD0S z&er~zW~sU0nA-ninyxtRn40?#F)Z=N)XIn0B*>h8OdWhk`t1zTC`KqtAXYIm{(9T7 zu?lV+#j2CV+SKp^oHqIHNzZ$jOW~{(3j8pAvGDR^L1SA+Y+fDx_;QN(FfCM&hUQPS z74gaTV?q8{Dq?$)9U*w5_ZC&>Pw-DIb|U_SQVtM7t}Z?aE{9N~w7#ne_LTup5_@PFE>m z$aG$HY%E8;^ZTl4>atDRMW&&vDE1~6kLlN9qfPYlVg%DqSzfrVJI0mernj`jv!q4c z_2jtt*jT#S_ohB$a`elry%y7WKgGbd8|bH{tTu|WP&h+fGgqIkT&0@DT6Ck7HpsxQR-XGMZ`;rk2ru6*tqH%a~LT+oN`64BuIpGgywR3TIO0x`Z&u2#{+b^$B7m9W5^Q- zu7{4P)lbk#s}VLoLH+6wnnh?r7<__sT8k;h&(INJIfAvlIJkiesI>WY?vbFd{b!h@ z@CioJ&qzc=m|G#P7-8db?xl>PcbJpS6$FnWG*{rzmR0zIr_{W`3asK7cSyL~b)ju4!$tNV z(ovG&VcUk?cGWliiSx_1lyPNv~Ai7YsuHa*0K}Vvk(9HHKpCg zW^vdz$AXriQre8SSUCE_myYK@B(vz>bHVuyokXLz?EWu?(3tC^PX_yY zNudSJun;aObV>@N3<{kAoq@tKfBO8j^Uv1G&B~K>Tb*9rhj1KWdfr%Y&BZ#6XlB9d z#~(FVRmC20{TN-pit(CsMxQ!S#bsWYxo^zLvo(*h<-Bb>8w$gd`}i&*Q%qK5UywOV zNVMdST;WFcsip3J=&9vQmZXYX*l!q8Pc{{YE2>W?`yjSM+(KS2R ztr|VAPaWJrt|OK{9!^&Gjc&U@IiJ!T5eXOcjm4VAH@cqU2JBF5pE~jsJ>g+u9xC%Xc60=g9*%{IM{FaP08ED0#?WRIliVoG6BcTAC8-JRN{X@_U^d4F1( z3V07`fr7u#kuK>A>Uh!uCGf0EsNpYY!v=)xUofDHX7>dRTuCA609_7V-pVxzIdomo|60 z<>tPiE-3w=4MjV=hP!S#_+THdC^!1Iv(hm_I=Z@Pu1-bE>MZ|_rc zYp8JkdP-Ttt-!+%(zZ1e*YXo|YP4B*$Cmd6O-+(`(Lt`E;quVC{}5gdw>&`;`yqdY z*TBo+t^j>;o{jMCpY@HkOi^zou;G*cjFxJ3>V4iPIQ?lz>%_G)ZmRm!-ebJm)4btg^7s8v&VZqO&cnFA8ecoTdB3&ZDV&8CHD)gcv=Y&zi;aI-&e{tEZN zT?Xlx-(!2kfXBgeeB5>_DM`pqfFmS=)WZq4KZ{%1E$cp?z%C=Sg_G=GLCwGP3Ms1L zS6XD6^Ov~4Q%UF6Nw5H8v0!83?G_$vloHG=im2p&oA*X&V7?(Sn-XVD>TuG;-; zELXgnK_D7QdngdX>YC?*`+(G>`h9kD4R}4g+<>>ii{Y68g)Ttug71C~*RY4H{{zqW zakF}#UNyVa^*5IEF9f?W$+r@&!J`Ax5nc-~hle&@3w*tSekZ)ZfP3J%FZ7j8$iRGv z^_xM2IC!Q(#&)>PfIH!_2D|`nKE=m9fYhvnfFTSMTC-|+mjSPbiy=ex+u)4`ybHcN zlwVB7!vs`@1cID($rDMkSpvAFR$M$z>1sB!u!MIMuUaIed%+>xq@x z$NXGRf~|vnD)D7>>O6gF^~)?HVut$EYcFe?CPjXu?)|eqPvyVDc#Hgo-v0`#+1L|( z6RuaC|6+6G1ev`eNh3tPO7^iQiSjCWq>o{vSdCr!kI)+nZgdA`aKSAonHs2TTX?_9 zZs6LpJffdRxZ>p@f_)8ITG}w@p+2(Y-)!ZDaA~Y+cxObvO8gBa%ADMJE;3D;GqjqV0C#Qk_M5>u{ zlu-mR+~J|~oDJRv4>Y-$#{q9L(9eT6`1Ef;&38xy7Xh^dgs$8w$9bb)nZIJs zT6ktk|Cnu(`sp@0&n?Z`d~4ig!3oHyiymNy<}&Ql%YpX6^7)cpO&obMH#VO@N(%P@9gzZSd4n+H@ae%OGot`3%e!w!dmn z2)tkwg*+5mP#8qP)Qw=>$1Z{S@`-isM011`0-McF3LdzJh#U8D!CpYbP@`mcSWOx5 z9Js@P7s2fYyd0inz-!d{a$YzuF)|rk&<&)lyVaFU-wB4R1{46rCkvg?q^Us7T}FV zXhhhxpG%^a1^q$mB`J^d3!J9`FMtzqf_@3S!GKr8>*1k;xE@~P$d=Z#R#@9eZ~o#h{OmExELYd_fSLJ-l~|%B`_C>Mg0Y@RgaJ@LLb6r5t6Q8_3;;N zX=%)r{Xq+B$*1-!JPSN9AK@+VbaVX9EKkt!REi>;v4>oi}(1> z7No_bPfVs{gh>!CQT>OsWHme?o$G+NnN4g6*>5v{_n{fusiMEZr5W%f_yL0)GvF-- zJO|!jkWLYNw~vbl^&MjBassrF2u^qnyo?ghJ;=Ja{3?3mK`tYPuIiW9Uu0$f{y}b1 zIj?3KJc!>cL$J29-JZG-jq&v5kK{4>U;JGN7xP$7(3~0lYVQl&8p`0r&dI@cZBe{) zQSi_g!&ak^3wNncTFL*#2jr6F9W64x8km5B{}5$2$~7U%yHPGZ43skY50UMo^a2C! zgm)P50(iRtFM%I`hxY$!cq^Pnzs#Sn*D&=2H24Beap})(@ZIp_@f)n~Y7SH3HQp7+ zbnioQr8y_@{MStEM@8^r16~d%g$ezx2A*rc8{t_7yd9o?P5(_35^@ueY!G1-9vi}? z2U@;m5dtq)>z-yiBtK6xmpWj1A-d8&d2puzcfm6ZcqQCsz-!@gAzV633p^V0W_PeA z7)J0usJgp@VQ>Bp-4mRh@twehj;~)AjZtTK=wL2~$A)m}?=|p95}f-!Z}OyuC`d)S zP)G>j5^)$F{WO5=nZm8JkLr8!P%tfU@P4QZlU6v9wQ`dc&2e-8@j2HbpxDJ%&dO(On7N*D)^HQ;u5v;lX*!+iYo`^F9uDj;B(67Td)be2Qh zv2tXxmOF%dtu;t#ln6WFQVRbevSpGftQsELf;M=$0e8S%20Ra5;Nwz0-ys>e2*@#r zPzk5RK^cqNt%cjENm?g!vUXjtf+QGiGKG~H@Fe(p1D*lTH{dz&Wd^(mp6TPKjU|1s zoPgBp`qk7An9I@;7Jk63tAfRhj}Npp**hH*+q=eW3af;hiS9on(MEVNJak>(4li-A z|MVe?_roZ77x?2b#jcicI@}Vjv_E7=Ci8k6;)mSHtIg{7{xE<)3-O?hXfC^vd0~>g zB+D(WziXMLG1=l${c653Y>P03B{=)JPkZ{1GCJUm@S)S#>$3CUl}r1BZaa#;3*HS6 z?MapJ4j-3t`3{LtOF*kZgcf*%0q=zGh6heAcGB^{cP?dqK8*8fLwM~l!_{{4#G({U zHig9*@N#&x0k46N8kD3F?lIu)@Gc(@zI<^L&~6Z66y9RMEs>_MdIN5Q*BEdIT-xNc z?a%UUM&%Juf=LGd!6L?aGkx}-7-If$4$Wl-onX0S;5$rv3?{tym(nZ&)0r( zHTQpQM{q2|1X#PYWEHoI{naOrXwyxW?-J<S}88AM?b zIq4$Z;pP3j)Bo~6wb_%);g%JQrGLQ-Rs`mkFnN@~ZUQ&|i=;+x8&9e-8i(;cZ*B|1 z^S&p`pm6m;#;v=5QvVETz|JD{|=YKzVG)WJ1pG6OZ zhq~!ecq9C@IekybS$Mg906eggUR%MN;5po}9s5|DlO~Bu1pgs&BT9$i zfrSt|w!_;g{mP?k;*X$^>oZmV)2x>pj+wH_9aR9LO-VU~gzyY0 z7rbNx&oDyvXY_)| zr@8w0jE6mkchmSo;*x&F+&+Yn+`ppg0jY^I%a~yb%lb7H8={-!?_m=&p9egCzPxJc z%hq`8n?DjlZ`1ug`IPHP2CmFECWx^W2&Gf+=U&3l!lCA~hi# zk)YN(Z1^hs`zcC)lX`14Q^N9L3|3dq`ev9f@5H`L2oGO5cy!nDrDnH|0?LTy zKcowGCbBAjh1UC$`_h%a!%SaNEc5H^{(i+QRQ`IfOO_GelEkP%AsYo#7s5snYTuy2 zBue8O!Hz*3K*21Gg2M5yZ~!9+)~|_D*+e2=ixm+zf2}P@+x=#+y`=KaOXy$l!hj*^ zk~HD&|0B(>dD7Ifk9Hl=R!u8t4NgJ&UCwOWRjV5KK~<89_=d*`x?Ab_-_Slg|G-Wl z8vY{>!HstJAMhsMXsfPB`pd-D$V=uT5-x@FA2|pvxaiw?IqOP!`}MzC#_F&G!3LB_ zZWKpQ3|yuPAB7LWQ~jy(SGZ*ko zCR&#|d4gGd%Ly&bRPZ)8Sx?Zy-3TX6VEgoTmVBdJ-Y#noww&bPxfC~n0`DTsO3MgQ zkfPamsXrASSTyM)4tN3)_ukF}>(aMxaY4vy!ftgXoGgM;kd$lT_7Ht(o)&l}DQBPL zt?U{U0{1cPDA;YdWO$Q0D~4~&v`l4}d*~!aiF=1CpXAw*$ajOcA*H~b#7cUXaqul& zxC4bap#R7~h)Xf?To*O^7NglaSTKJ}zq1`8%9yq!t*vun)$H?F)4&t_>F`%d=!75c z#Bq$_Z3;f%846yPy+gZThfTMcx<2UNu~O#)=pT6ZSonRJ%V=fbUVVu*`NQBglGI8F zkNc4JK11gl8UMgTouMx^WqrgQyfgGwrsR(qB4_9;cdeWO zG>R8Cp!S%_qs}~_PMArt7GZ8U!r_PkwKALnm7g=fZ(Hc=Os?|=_>2cN+=;L_0-Xa0 zyj?y^bw9!DmKMIhGIZVm6XB{3UbTHILciFQH+4WAjnKE4EawlX4U_dH@wN*Gg2s;n zOE|8e4dIo(H;6owF=ye0fjifmai8W2C+y;s6RR zliIqNTP7Zt9(iWYm5hJuz*yw?Tkqy6Iv#Nb6`rE=d}_jgT02EgnO=PHz*uKM!cOF* zbUJn7z*xR-)3SYvZZ|oS29)Vcnxg_?;h7{cgs|~U{Xy&DOUWf53F(I=SK&%89Z*qG zXx7giP}xzK(2cM$N?#D3Y#SImp#F6;OOW@X^qHoHlmT^IR1@Y6sI+K(R+??zz=S74 z+*g~z@6kce+E!QwVg>b2>4W30t&F3(F(ic#z7^<}! zftSLmR*W9GnzNvBAo&jyZ>Ir|{tmV_;7RZbc%Ua0@1No0>R^mME4&(oKJVL3(dS}i z`xTVpTt=}CVYLWCHZS9MBr{E60#{mfet(LSq$?&Cu>c+ik0u-cAw@5N$G`)7z3^&y zm;tYc4^gsE{Wf^_f`QTr0bK-i7(^I`x57i`6T*veZ4;@D~cxVGi z@(wr+;A^EKPAmr2Er**8cny4*GKX5d5$-nN?eI_E_{KtHlhV)pemj=bOMQ;j!>QD@)?F@Mw5Cvi}e-+u}<{WuLDvnx2b7V88H| z#KGn%+&M{o`Uc-7-FLn|*OZe!pa##!3%k+>_*|v;758th(x*;tM|(GcD=(1g?kWb# z1^SBcoT~@Mn!Jw>etUs_sj2O1TKhtVdd5PW`Gq-TZzc1ojJLMlO|5GV;Q*(2r^n{MBl)C7!p+~n*`sD5+5|1 zsWKMm(W*OEk2SS{PQ+5+ zCQl|++=okUm_~;l;jDR@zRK#kHn^Tr+}ax%!Pkx#x1E#2oKVVH)(*4-D<@WozKKes zu*-^vbR!(H>JOT_uA^LWv`5Th@!|1ba~EyMrSqf0*^HLO1M0On)Vgx4oz0U4RkNqm za_ZqU&v%pdA39s6`O{^Ja*+IVR$s2`2Y4*(oiCYkh;8W`*H&J9H~bw@;4ws%T?_G$fMb$F(pY--D9 ziF2`@5?=2lM4kK#FHNt!SU*3!Y^j)G(@S!9bAe`_VYyXywS%kV?ey^7OUd?P8nX$7 zV&8MR?Nen!PL#ex=-fnoR(ABw!O>+%bP+uao{a22gb%}G;6r}MUum%D@3M1uGrcJh z+l(R{B;^G|1}T@I>4t~)$7*;N+@ZFtk!Od$*@hDsPjzJyeYED50kvI(4upeA(yj<6 zAf<83g1eBEv}HMd3Le-ig?GZk;C5vHA>0F(bVBvbIn)>)SYFYOgGa(E!$MvfvJ+53 zK;WyD62S>Cx^-Z}`%?w*E_k)SH2f9)5_s-+gB`8#YIrgHbb+`pA>*x{fc4*{-(5ln zM8o?f#4F7!xao+xX!s9FCJwH_-G0d59RAtidCLdX{!6$zvE|UqXJhIXgzVWkuHqFm z@@z7wL)br?K7HUex@xk%V0!ND!PAeV)^;0rDuqu{&pyp2k}Fxa$H%M;RLN(j=m_|_5+&L=TlQJ)l(z-IM4HbV0o5`d$G!*etD@r#X5SIw=w<6g}IRIw`0=P zRP<7OWAr`Pb}k9$AgrCs`o8EME=eIkVgR_r}9W4j}k%#QzVrl2Jk$D z5`?w$WE#AW0Y481U4B1pav4P}S2gcgfzU{o- zkTPGln%b-AHS?)n*>)Bflhn7*;kMqKuitO-R8#iLDRS2iJniNBGp4p*(ACoP$0NF* zVc8s}-nxMW`~EaN-c<1{emqU*E9tvQ&W;BdL3qqg|8)Ht``IZ%axJkJFcH+(4vdZX zim+(`cFcR8i|7SpWP5>rv;ft5goRh=i>#g(27)$Rr30DQFhkT)oh$IYd3B6RwJ4lt zg1fHJb4+C~V$3TEsC{vOZzOH1Wu19-eARikM&HfS78W>-Sx7AjF1n#S16~amWBU)u zJqO+juT_gOsuI0B+T|eoOSJEw^%RwvPA`(P>~#8A^-FU3wbaSw*Nq8$KO^afOh5#_ zmQE2z2y9ZD>iC??x9KdE3io30tLPCG2rEVCK-hd0mPx9|h*yzdUcFQ+C4ojtxLh}% z*;vR;0NBVG>Xj9IEg}DE_BG;O!8%uCM;AiWLiTStP8OKTeL{*_zmT$4a<*|H z$}I@Z3z<+4zamEWJx*!P&@HBJLaZ5d^vqXJhqxpp>s1O!h-n$Z{tSI-Y2|OIvEN|) z6&u&AWgP>L4&jaP7I`~(nRJDOYpAiAv$@ykDOSsGgXfqe%Hc*m6@?AgFd{Qi2rWd?I7*Z+Fg89bakYE88Amu)aR=YN8A7hRcBVAJT@y@DWmY zY%z(4y@6X2!HKYWjh^z9gU*x1Nt8pJRTG2Mp>N{18W@{GivN#(wFKg7Cgu`+U*}uc zR~|L4aWMkk3S1EQMn)sN)quCdo8Y0H&ke7GhmNFCc#Q$KJje>-ErT5c8v$ho5gc%r zLB@IT0t4=X=fF>|bbJ-7gga01sXil1!`2euAfQgY^E7Mkmmbj1R{1wz*hXx%_6B`X zc1`QVdfR`@JuL(7gqOer8&Yy9fNQPv;2ZP>KWH_G*oZ=d0dI%zHsEewf)g5K6kevz z-O9^umWMDMQ3KmX%4LHWQkLc{Jtdn$O-RFqLYV=tgs%_bm1078J_)AXsBei#_ygAs ze0A~$zSY`&BiFC_e_#^5k)hClkaiP7_aCvW21un?g%^6$ZIXTj9&QtnZHIFXOShYYx-498-?ZScbe+yQU*@!+Q;@(5@(h~R=_ zi=a*>1+9eF8Sq+ojR9|gYe9Vc#g9$`%7X%Y1KI;GHsIz*xMVWmaqxTtZinX>aAzq2 zSq1?G@C*Z90#7yI)$k+(UJs9jCtxlAAwItio&Z-l%UQW6)6e)|(JT{5`0n#HT%noI zbUf-SM9KI_8(PjtD?=qJN1wGO*pNPZwGhL|j-7BLJ9^+^$3RCa#WO#K@lu#yh{id*I5ZK zIKtq#4YyE^z{kC2ML7u>CPV`~b{oTZxQhWPLh-*@Oni^rM*oAG`5qTx&Z8707hh8H z1aMtzhYq|VhNOOxFb%W3}^7ySm@36C-01#q(gFM*F74NhO` zTMhTXb6FkDxJ{p?x#*O!?Z zKcP9kPi5Rbfr|f}mDs0PLGF1v5D4bi452PgRtl~4)3_&D>~gYKsQI&T-6E)+lM_M< ze3Vb{=3%7j&w?ut3Ipzeml$yKW*Xms$HB>Mf_t&UbA3G6PdN#28bm07XBzMl zIQ5#4K{Y(tfY-z0;7wH0cZ@&9)kZ)I0n6mOEaQh*q6)E6iViW&mC69?7YJDFEok_OdE z5o%`*s?B%m@z(0ugFz1|ix;tPW$$nHpxS>Y-KjWvPz~P6?BAX;sIv2kn?G+*ZOqqK z#doI-2Hl>J>C1YJfCDA3|iCJiR4D1(>};oQSl-r z3kKERACONu!VwWF5u)zm26o+o;J9L_HcjsI1#_uH7rcUqYww~GlIHfiSVlx&fhFX@ z)FPesxFR^3Bv%ek3gL2lp$2Y|$g4@kbtUPpX1ouj531(XtV-&y9#m5cSh9^=Js9Mb zCC&CK=6?h3hWCYVvEeAZn*=wLU}@&UiG_4*XErn7dGG`S?t;e{@Je_XJaihVg-bu6XMJP4!>+lf+(!pa|_S?v=@=qV;kPWD1e*Ap$U z_+sxo6bj*?*F!FNZb&wwUkP^_@LG7L0dIj*ZW*(|{;iXMWP=DEc$@(@E84|?$H6hx zgo@eWqZxq}8()Vx3Gf63_|_E#@Gf|$g-YO^2Kv?THUnM{ZwyJtj^)}S38*K);rkIP z*FCz$+7yz23?Iu*R-E*WJ@>Fr*Ak*2DHWkWLVTr{?SDxzw8$+e)P_Wq#_NPv8*mT2 z+#ntEFPP*E^yA<~J|5htb^`JY5^}u&!!n8++(JJt17 zjCG7_jiOb+$>s-$+vTT4yKxRnsH;#HLfVg*Rh>6_3pd@n<2%LvD>fQ#9OUQzmfk=9 zshr6Lu*jRddCs3)!$}S&b2m^vC&J1Nn7$B!g7OaX20b#n@urE(49Bn8selKzpp2e8 zxE8{tWnJ(xQZ>0q-X$5j^rhCE?BEonEzNuA?%7PQE~>Q~;h;-Qhj7A0XX|sGS_^1a z)&g$S%}c%0GC%V1pdOhvf`$~ue~6q^%eo96SX?Pq2Hfo=j|aI$J!+s(f`SKys2`(1 zJ`+-C@ujS?Q7DZGQIM=hQ3x~OmgktnLvj>-8@$_qJK!DgKtJX{KM#HYUNedP)gSBE zM#SAR$g}q9t-ILv|L#Nj6{hrMbe)G-UF6-$0_Y)b=$79aToK8)@_DWg40tWP0B%Od ze~9T?;LAubyO+0BA*t&Yd}E0?*X#g*XdI)Zm(nBfCaj$JPPB6*TFOSnCLB4 z7pt8=(bG*8x3MPp3H8qSK5NB|Y$A7ke{igtpBH(pY8Drk`jXPHI|hRu(Go-Cy+nh- zrIP+bxCL%$YYn9rg|t_7|;JLcBylP0Y`w3r{^9(TJhnc{eN zWRRb0668CiMZ1XDw3;qmg5_fG9#pT1(0C6cpah57bL02H`aXYtwy$K`%Q>l%jg7c|Unclt_fcpW;?BUBvwGpbaxfs%8a+Zg8SdeZ!lMme;)X~3jIdw`sQFe7g3kmH*gHiOglf< z*IBFg4F)~%C41b(n{rmBo*f?WS3MJ@nse3HGJr1n8| z{7HSy^sJ7Fj?VoieHmWIuRDLnWLC9Vzr?irZ=}DO^bdbP`jt!&l^=2e>iY?&%1S-Y zwEmx%i2!Tak>ENMP{fvIoZbM>OUm; zMiiRh$$rRR;qCAP@W7c(xch(TkNyvR%Uh??4_>a?2r$aPaXP}OB1y)1|3lw3t{+;l zO1N0#G#~%OZ7l&>NR4G#+5+E=sj@X$7a%Z(W`!R{vs%R`X|q+kM&Gt|Gd$%3A0@x% zo**YtI)f`0AzRnim6rWyFz9szDY>JSwl?5-@Cta+se1ZM?}Aqw=vTsb8t__pjV~P; z9=<~|ZXuw~AVMd+-hg}H4Zei@$#|c!GXH^HssFHas=~MTp%6GtO6i>_bfLhrZnLZ- zD4aIBZ@#ER!Ht4-I|`i!S+t|jjl#<97{B#ne3l3eM;V3Nv2T749%VZny#yhxnn9J< z8$75S6eDRri_Tu=plZBeJHiPxO_6;Jk{zU`A#6toZ|Y;T`+m;YdtouOgQv5T`-6)u z1}tymy1{_gz{3o9Biuvcfz_9SwZjjS`^u+yBxRV0{L1>f@A1aO@1J5-;vT?qPf<(D zAQnXkqH#O25kF z@lcwb6sztNO1={Vb|P%vDGm!E+scjW?wz>VKF$UuTmS)CP>4S0OJSEN95zsJqR>tXM?`_7CS*~G!T~A6Gt^HCvseTV z!rEu3N$TfbVg6)iJF^WZN1&xmp9e1wq|IwkFyf8lJhYFr!)r+=l)K@Y0Uw2z__%md z-ys=W-eIj862T6)!E-2a^Rqk|UHrwwCNGhQ@Ib3e#Av6{? zrjYb5yAK9D13ns(qxAnAxQ7IflAvk#aXQm({i?~G&^}I%?B?1c`aO0=hP@#?`-T8r zU^?IwCb;Ao$>W}MCbb~ z@kTiLH4%#ttb6pOOP${g20acS#vMj8A09efqW{JfR0wyVp9If@yX1=s7pZsm=$BfH z{u^v#u|zp~`Tu2~xE9mqj|MA9#$71n81P|uRtT4I8hwcSjHA@NmPd0lQ3x%u6NS_e zF0EYvPk`FaFsiqf9PS=Dm3>v>EYGs&ZlJdfoaCXZV90*d7b-lyGmzks5gG11R5X$Xg2 z;Azezvu7+ut=q$j`0_gadQ-dEqc+yDG_;3%c;s!}C`Ih5(;eZJoENBfHt{%V*I%`m zE8G9h@Pma`+YPS^;bN~*_|9;T+WewqkMP=y`jYIVNKepkkd`PvjFUIuHSp*VE-5#{ z!y>Uqyu54m64fMCwe}_Uzp_vdETGum_78d}3e6~(iV(aXp00%Eg=ovLuZ25NO501L zG$O3#JxEj8nb=WC8^V#jSiUmK+aSD%?GsW|Sv@5g=4^AlY$rscSkLQ+O=o#j_REl( zvuU)KDTDnS8uc+As4wbbH|HGMgM9sml(-z8fzs4h(9T217NHE`F%b?RG`~WVCB%5x zi`%r2J+Zh~^(1RK=b^Q4{}*mG#v?m<{7fMV<4;~b`DgvS$r&Fprx1AXRmwMvU~M4% z&_cFoqv2lTH z|ARaJ2hSVl$){33hwjITi+}=Ztf?&r*n1Fp0UnJzMrp6c%5fqlM=^$TG{LLvs}(LzfKAsgo7fiPxA2P zZw6fr!ooLL;EW`B#)>AXkKW&UfvS9i7fRx0)6Yc3g)sOAJufSnf;6$)>`wM@J^zku zyjPybTN@2cWD+(9{U-EF5C%~*SuQ2*H@QzzeW@pCsUV)l+{eZ&3f_GY8z&WM zt3f#WCfD{ADZx!B2I)exI0cvVf7D_GVekLxOXJJt1#3#jDDUTHKfFM#`jF>_Wz%*_ zBdiwYRPnJqR+8ULxev@EwPvp5+6mCqDjN?bztXHvvnE~U3Hljo2Z`nku#mZo@-^#A zrkhheLGQpiQD{UV3x0U~k(vA!UY+Uybg4!6a)bTl79RaBn2(pr;nB4(TlB>E+WEnS z7wgmxa)}2YfBt3JJ_^dYTDgyEn=i+S?9&%yJ1?Kulkz-F;&AD|{zGIJJOiHNhx`?T zR>F%((E672kE_W7!5WqkTqZl3NuO{5u#l{O&s^F4mL54hdC|o5Txb=*$$dWJ3Kt-m(E9s+DK65qJwlo$cT)q>Jv* z&Q^D~^3L)wl+WLvI;5J>pYa6QE%?q;)OXFC1n+~JLwE+f6E2PGKO~(Tc-XRu`bBV$ zFC9_y9nxau1RTDFiRBM;;VuMz&wW<7og`A#$>-R1dg2ef{2sTQ9{UHzhAS73{|C0f z%z2)%26gfe`lYJ$kNTXnygNNXze6Os*gt3CnC}@I9nVkx#PQDwAI@hC{gEg7x)Dx@ z(2ii;kI;m$a6iqOa~Jc>euicd!ruK%Z^L(c_yvf4zu+y9kuBPJDzQxl?mZs0yp0u4 z?R_jM5F#ozc*e@Y)y-GaS5yC_XPI^vlhU8KXfEEwAovrTfVQ8K39kT{vJhAuE$|9^ z{>(%1U1h-yEmbM`l4}}x;Jhrn8r}w%G2}ml*TYBPr~SUKJ=@@sk4&5ZyT&=@37(*a z35X^_sE?2SiiS4eN$_EV3S_|D20RDe2|ryiUVf5ZRYU+aRww?#USJ0~1y&^wg?1FW zA7OwT!1U`M#S0$5oD~Rz2WY%egt>o3SpOIX7QtLjD~gbXF!)#cTZRaURWm2okFZeY zWZ~QR>rsTq-X<;c|ueu~7*hBBHgOvRXDXsC(GR?}DatvQ}sw!rXuAGq1FrU|!ff zF>MFDI)qEwdGI-B*Gly`=t{y%@^2+{Ckla7k|zp1h5Y&_Q}m1aEpBlHPjGj*yB~ zT;kxVIs-{k$r0go#!nHnn3EHK!!@@Mjkm1wwD@xuM-j!l-W*0Fp^AZZh|$oA@R|q( z+i{177-5zjG+QSQeq<*#=)^%5?DDANo!mUCeU@JM0pqgZmk1wnk?$f+m)RWF1u%Wc zeF(?%-jGG%Ezf&+;n4f5pq(G`VUgGuFvH)uLG8R8fj)xJ} z9wz;SR|z_dm1+@o{e#&$;U5?;vH?^5gQ$fFt3~KTAbdfZ^EVR>mltUc%MamVI2YXY z8*i)dv+E|64G zUvMZ33Rw}{E(<)Lh>Q@*g5X0qbvFxd1KK&(N_neg>F$m3*R>)~G5s@LMzaG?hD-cN z{Y-dm1ka={`S2=ulm43I7rQquh#sUQ3;MXWOK2Oip6sKe;(kp*_b?*7uh9N`X#W;G zTg8+8Dm$J%+(H<5jV*^||JM2GAMoY4#tznn576j+eaPDM!N!|n;&u)l>{pMIl=8dx z)0<|yjP{*u%s=GgEB9OBJC<}xmwcGZ7=M#>+_1hC!>g>iKIA4z=37jp54mjZAx4gD zDHODe-R`*Z6DR3C~VCJkCQeIPhe6 zF}nP(?sG0oC$bDaTr;|DEkt#XHpG?{Y_< zfJXJx(U1Op<8jg6cd6OmxviSf%LXmvb8uPGN{?XV{{UKURhp1tBp#*_Fj(kfJ*MbjsbaT#?88-#W#%0p29+UQPneI9-xBCT7M;4+NQ zNv(e4!dWtjTQ#sBXYE5sAy#C!kHZrpc(zpUSWE}0ZT&YrGlb`(e`5-(zFV89C#gkrvneb z+Z}i(yd{k5htK;6XbKBZ8^>{YJ^ah9ui|k@*vkl>OEV|KtLcXqhv}-O8N*ie2*Y_G zZrEBe0x39RnAb(J7p{*V=5>*H(vBXs)`} zT>3NpcnT((uWmf&_;Q3mVtA*^c&vdpBo14NpD?=1l7@MMB>SR{q~WlKTEtYvd)YF~ z4d;?gD!g&-u=TP;Y@Ihez;gIb2VMg&J0U!O>4+wH5uCRi&P(Roqbok8A+r~RXDBs{ zJAs-npnRXo-s>c$(5I9*CB^pe?eFo8?zy!o;qjzxdx%#7FS8!_gqz)kg|+T)xE3(% zV4;m6g-?P9;BokahnR1JS9S3 z8lw-MdI}?XKLf2A&({5HRGLK7n!Avtpnw0yl*PVNho{`TsawdF3m#em>AwIReQU{o znKqMnHvE?<;Z9|0{g+x6rVbzUsy$HL#KySjd;$_D(8y69F2PQ88JP%cp^0gzyF%(H zO`LQRMh=DT63r8gRtj|?d@j)@C|GDTY4rdK15&WhSnT3RH%@&(Q}Y>1S_d(AeMX5> zPoq2s=$AA+mx(7E&j#_tpD}E`aey6hR~o5&j(O-gbJ*JSIWN*1ID2X@*PX(0cJ{Ef zV3N&j<~OFc-~b945nTFY5}y7IGM(hfg*p^MM_)b)*{5QwP&oCAjh9&7FPNFGb8P8y zegg*61CFj-GHku~1?x|ICKdW0#V^Kl+5ZUYSvqVz`9CI&?_0yxNB={o^jxAJM8~^) znAc6>iOXgvh$jipdk49{>bY>3=MT31W#fsPFE)=_>_ZGKmkhq4(_Kbs1efx<&R|Mk zIJ|k2$vY@68s5Cutl3_labghrbU~$H!Q)|$KLTUt;i0yFi zr7R6DB6dV5NJ-)ryNuQdE`~E1-b}<7UFOo5gzpU>tWdAri!qbW%0~>H(UML(`UPQYn~N7 ziD!MRxzt~A`P3@sp2gbWz>DF<4!im8`DWZxR00|?y_O45m)@Jkd=9)0&S09dtOekO4!jed z>%jZqnTlsq9(72Qj1!RR5Fsvu4vyeblVo@tHQ~j@^DoUsa78FdqQ&s>%chpP0zLr$ zvIuHlPzU#rPJuk+eX5l=lev^eCM#xQFq1E5#hb|#VxU{QXEKGD3A~)uWUDg^#S$g) z-44cA22WF(UTfPm=JXlK-(;bN@%hp>v1nbh%=qY9l)2V9d3qIrhlExw@bJ^g(+9M0 zdmLFMT|wq?CO-^}XD{U9p(}=`+-eOhaT&&y;VYp%-ryd1=%yr{_UTjl*4o)*;l7ep zX*Tx07fWqkg_+R z(Coll;q?x@3tsKO2jD&jJ_#>TT(VO~F;4us*fdJ^q{rk3y^FZ&ID*bkC}!Cdj~mb0 zBTU{ng=a-FqoDr?MnNgkUcsGs68~Z@n%}Z|Q%Y#1qZms?c+NYDR?5F&*t-2F#%({I7a@uHH-_gfscQjHJ_-R7clbRmC@E=56QdU63q1Ip?hi61cqY#ec>^r!3w{PnQ`Fd@bP=6>es*r z9C#DF$AP!QI~5OK6?+J1b%-zoZ-Pf&W4m&=dUeoGg4a0kba+J=*Q;VK0i|I9YPb}` z3mtd`JU4>Nj=Bz>Nz*Pk&OGhxcA7A<#C<5VMsSHZ4iCT!4D0H9xEeb4%#FM`>_Xb_ zKE~5=<|T=P_lJ)siB*Hb!2Qg>M229-21Y|7U7EgOY8OqSne4#hFJjjUkKE0s!rcz~ z+3*QU5^7=XAp@5Z!bMa^I!-wOy;8)v=Az>R2z?Q;lTqq~ccEmzQMD`y^CD5!C7CM| zYaR%ntfF3gF(&Q-c6>?f_$Kg>_*sdQ5t@>FADV+GtQCd42g6%17lqVZI`Tp8Ud&}3 z=)^N?p4hyHutoD|%H)T*h(s-TNZp2rk_r#~mWgoJC5lHjO%gl_{Yah;k8|L;@JWh_ zzVxv=B!glCh9c@98Wr$CDf;mg-H@UmZ?1`HAZfl&nZeT^JC8S0V#bgwm7L%;Q?B#Y zPVM!s?=Tu1_yF7ukF4^f=4rZ=;>cxH{CBxxK!0$Wb^5N_RO?-@d3toS$#OfNB8q46 ze6A(>&8e+2PSoxQE|rYSa~T~(+$t%=Z(`#)-&~lOunEH~x#~kqWd)jPD9k#6)oBRN z)lOtd;ecO^6MincI@ z7qTVkv`Bv;=^OP-`-QA09e7rB@i4jPMAI8n`0((-QftraTm=Qr;Mt?16G^7_VFvh# zWMVuL9@;IT>5ot)2`vu`^?alKayA^WxM1Vq$}sDJH$-r`nj3=GlGwVFDAoX;mrr7$ zpF}fXzqLLt#Z2|P8>S}Nc?Cmy>r~zcA9LX2@Bs%NcO}NefhWVe6hHk?ZKN)l1auG( zYKC*+`S3RQptUlez1{y(%rg`7D0tSP*zCOVx1;B4pz}|ra|0;kS+o1t?`}TXoDrFbS`6$RPeIuA$(PXz&n!D!kT#XTxj4IQdJ2LISG80u(QYOU98I)W9npcoV$B zfw#kb4!p-tK)FM}5WLKRyS~q2@4%Db(sGdnO@|jd@LYHi+#eaCn1Diu2o>-Gc;tPL zy06d=X#L3aJK_0Xrmy;6l==wB`!c}pPT}M5Tn8SvLJgwG0wu$p^fR@7c!9`2pMY$K znw2_6;O@a!=r??Ye(P80cZt5=p=JYL5n=KxGKep9u0SeWrdfE6xicD~e`x-RQsGxb zC=ZEX_Y40-zve6So4!K7eX4$(eXqYqMX*+%jzyATIi*uqs$m?-GvPAqBY8etrb#3( zh0C;x*`~YJQn@IvIDW2)w-6T;!ibXm%)F{54$X zI5cf4+(|$CEA$Jse&o_#4sX~teC?DqzlH!Qc4UMmxY+JU-VPUA9J;Q`-m3>LV`Hba zwASSMeG%91W7}9J7n!Fmc0W3`KZ=XE)P#G996W09RKVjNWfOO%`9O5x6KvwnG%xoL zJ~_206|1?pkixIPhe6jRVhw zS32-~czGDVQkjfW0!qRH6t998I`9T~9z3*WG9+8!Iq(YWrc?RAe^t79Of&_w)}^!4 zt;VxG=-HjlU9EOhLw6zKZ(7Y~4HD&7d}Ai>EYt0uh{#BqZ~(0_c;pq(B)s2&#}_+y zT`JtE>$2g}b&S&RE-EA-paLj{I;245@J0t-1Fv)7O>i0{tOZj^ryVX`S1d^@%X7uq z<_XcQ(j;ed$r(8?rOh(e*tN5Eooz0Rl@VHFSkJ!2qgu1SVJ0q4Zkjs8TZxeXcS$z- zknFqQt|qPzzCnkj;@R*G^Zbhg4k;8~M}-}DIlL}{7m{)fyqW|PGq@=6{DRux@i#Yz zH-R)|@%5w(r|l0N!Ykl)4!jOt?Z5-@iU^)gI-T$`cq?DLz49D$(cGb@!V4iv@g-a@ zz{{+;_OBGk54&`q!^Kb1(_H+V!}Ur&p2TnBX~nbRo91b&+n%0U==d8LFAh8v-sr%y z;dK!_lkyb8tI24u46*R+h@3P&!i{w z@IcRxu2G^B9!dGDUq@UyV?o##z zanDVybg@#H+Jo?M5{&HGI{2Ui55W5zcqhDD@$lK%M?j}TgmHMA1CP6j-hqeOF&S#f z@FoZSOn7}5Cx3~MPe4srfHtgf+Hy*btKj7hya8U~z+2&k4!p}xK%PUu06g1)Pr@@C zc>K*=EIRO1xHp1lQ{ilQJUlANT6quOdidmA^CZ7hA2y-r)Q9bG-G?Nn4r$3AxKkGn z!JWF$b&Kjk#*~;Dbx1-<1T;pJTzERX&VlE`tKp$zAsPK*xJ(D$k2HUJjTRD@nG4Tu zMmur=>Ow(ANGO;2JD^i<VnM6rw1rI4_X&ENkVRBW$ zohDraoLM<#sI|f)C!KBT;nHDQyvy;L<>twW69}O*Q;HpbD>n!!<&(=XGKI|fkMJz+ zBAfJJSw)L8faYKX7oASHtA&N+Jd^L8o+r1Dl*EUCcrJc|J8AubE0Ok|#~sp!mhf^& z>J7KCn{?o<@G1x11@}4d0eC4~(hMF_%1L+$JdehBDBE0Qm*$OZKECq3h^;*z%UX+P z$x)QH@_b6$hP2^)ma>9YihaJhbZ+@e;de7-mb8{L&Efpss{PRF1$@LZ@DedEz$hpE z5}SPi?Ha)I`32@0fA(urYd-V?CaeQ@{g4Ukz?0zK2rd&N9Uc$QmM?fMJFGHlo9EHP zm(8Ag-ox%krpM&CVlIrfKK!=1EOw$}_+UTZw##Mzur$Y9;IDt(p;V++;b2VMuyaNq%WssrzYd&9W4@O=cthXtr{KMr?0 z@HihgC~3;j86~4G89wH~GvNacJpVfc^g0BT!n+)J6}%&Ymy>Y=ytRYDd=XDBb?po< znauUn9}{sWWAY-#WX>NLlNYgL7{qhl#XN13|3`U%=!>)X9KPXVGd`vS*<%f#kMV!! zV)NX@gk4jUZ1@SbY8QFtl4K2@wc;u0;zA&o8Bp^kd#PMDn4Y)7<4QvX)?qjtcqe?~ z&2ar(^!wmLB)Ikx^ODuoZ-*;Lg4q@92OW4Jyv%`@!;2%h%%mE4!P{*9zQYE#>7A(= zx$a;MaNtSs8V8;ZuXNzK@Nx%U3@=e!jEp*@h7|-9Iz*_0=S6U-NdTVx4rcAU7&7;J zToQkm9bMCVQ>#>XCslIb1VLpqyr+3(zb2*E9+h4eTx}3}h@oc}`yeT@nkBNPSxpH;!o~eE2x`&zXz?0y) z4m=&66~W6XaxOf554P_L^9M04AFv&9$|6_$ajcP2hWM%GB5-1 z%zt8XuHyDxVT6JVu5lFdBDiE3SIxvG;?}DeG*yEP2vYDH|C-ts4QP%JPUWreK?mLi z?~CA);{d!H-i4nXQ|+{ECp zqYFNX?v#rg_z;{|zrMi_rZuc&g1g7q+~2~JNbjuVCSWnr-jzICQH^KL)p%O)EV)|d zJ)X5!^J#L*C&LHptp{%9#-aTyci9gxraz%!7Vt=4IYJWxpV7~s-+<7Jc9yP(IO&|N z@NRgK`aYli=H{|%Fa;CDTz3tbdH=&a7f&9Z-PbV7T;r6Zh`Tqb(e6c-n8R6Z>vtlQP!hB;E}UCuQiX0 zF8P8cyq2ex-Tw=ZDiti=NP)kY$}8Yw4!jON;J^d$UI*R@?^65%vQvj-+($r%Lxgd7 zYXq0gX`D%y!w)_0on&>dreP?IwR<&lsp=p-JICbb2#dk(Nb8DOI$Xwx^|E*h@O)lO z&)4BObq&kQAfDBD7Q3QG4l>{m9a6sJIvT(j30uz7;hFFOBJPqDvZ6+;=<7(_H*Lf^ z?>c5_vTKByWG_T&3~$E%x<>d(1NyEqW+d#lV#OZRpimY&VkKTr9g1d*SnIDR;a)s1 zUynVgm^s3Gimg|7^Uz~biJ5wF&aA0r?b*U|0#7?SR ztgX+>J&ha9tmvIbQrjD;?f8-5ttUCxJd6oOA#p7k7R?#4E?z5r6i+@vQt`Yjo^m{U z*J2aK;z#5WqZvF=@vTyxmQ6Wo9vQqs3#7~$2{7oRf+_LQ0n zVjGV}=G(;Yb4@$}cwE6BWrhX2iPvCMx1e7~%2K%{R+8dT%n56WdnM(9^$c z(QLdG4H%(oN32;l(@gEfBi3a%Q~aGJBi1H7{)W=<8p}8;+=dZ@N1Eeucr`q-&uZW` z4(T+(D;;<{yd2K>J?2nh3-R?3P((ljKRJGc*n(Tk<C zNZ8l>q|EV;u~fiid-^Ek!GT~NxVfC;jWn5WJCQr?R06$om8&eJj?z))^S2Q0P6wK*?v1@>FNeQ6OwqrL;O`wa&ZKY?8^qY=%)mg zaYers9)M?r@MQd5@Gdf1@dH+gemv{NGmdBb4`{Ti$`Nb#59F59U9{d0&GY?n_l8$U z5|8_t%P`>lKXeFBh7a8{m1n|x9e6&x6W)9%6^tMLQg}Y;d-?R_;1A7n{OR|F&q2wo z6D8r1qrMNG>cGe0$?&+4%=%@)i3w(?{ zUo{PE-IT}BzsYAVPAvK1_(XRNCN`K4 zu9QDOgrXWo-8ysWyoLwE%P14i^)wZS2PfV$>zH`G4~|$Lt>Z!C^xE(kQu=mcq|{Q# z3hw_@qfj65=BcFZTu^TsIXE8jHUSwE>F|NNk+2)kA}Y=d&2*r&$UrS-^9iVK7x<9fzLBI^M-x&3YN5co#XA;Cb>c^N#4e zR~eyqo13G@UPJkAX80hU4fodajh5%xjUmig&ql88^^t==yxMrOMh`Y?=ya|$~<9lA9CoHTv{pfMQlj~FNEjA+kZ#DR8gPwUE%#AW1|a& zlwBC1dw3Lc0tKG9wSR)*g?lK2?=4K_Jv=5`{#JON(xrh`ZkVC4vz8wUV5o^1F_eTcQ5zt9MFVk23FM}oSSM-fT2FdVZhlDcW1r9tPp8I76_JEZ1OW~PQ(kK5a0#Y0j zYJev>@K(6TA%iZsF(m_L0epzb8rjm5@P5BTK>V-ydI>zT3sT{o@F}wZ-r|r>A-u_f zm&5CI`iJJ9G*Jx!)eadn!OI;IYKNCN@E&-f&cJSe{z>{n@Z9k9{dR!sWv-&cGe0 z&B710ziy(qcJ@RL5t8Ax4m=ZH<-qgdJ_lY3FAd>#{?a#91Qdk?fb6Dgfag2#R(OsB z?}BGK@Bw(*RPHw>2}qtAV8p+IWpv=F@Hhva4L2NkA)M87%JeIT55C0(MC81zA)wD8 zLKD2(fw#k1r>CUT18;NSL-0V52m4>T!1XGolz_-w=H;|hsd+|^1Y!|$tkb-~yK=4$+YGC_axEL#S7yD# z4sN4)+QqV5MAp3=^&0q;PJ&lP=u3H;;H)CnVw1g6`g09Qu=*a^pVy8?WwGtm8mT%UmdY+`^5jv+1>E%ac^EhjiFOUy+u#bLt z*2cpv&sIX)2u<9|pqZ3NTe)H?pFL`A*h&t4cy@1PpXxnqlwSfQ)(ok&|Xase}jXTjsNZqvyqKTZ!MpE7E_ z@i@(5oH=UEd4dAC(?|J!7K!R38Q1j=pU#{$YHfOg>zT^4Ne#{Dwk4$YBsaM8Ge`MF zWZn#*Z|%pwi^w`}>(`08NIGMcmRf%((pdN5H4TYpB$ z8}YpHGg_wqd`kXvCSv9Vqt=R_^X12+?~d}Lj`rI^GLPhKA!9!`-E&KTF5L{`)I{U*(Xfq%jKxm$#_}1>PtknEmourJqGb#4@Z-%q zc-l+XD?z=kt_n~BnDaDhqQB&6B9;dAu4oPyu*P^y~3_j($uBB{8hoqx`-= z?smpPx(1D}NVIq>)o+4d+N z+^nc=Mk)cF4iU29Z4SH;9&q60@Wu!(Q=kT32d|TkP!I8+_`G>a>=>*d$~r6sD|FlQ z=DcY44UC@W89mu+89mSQlvUErqkM&QX(k(yv=_{j=+>LDKQExscMGa7aAPx2CKLIA z^Z7E&=nH%qrtj8KYu1ZcJ=YzK$rrKalXqkOUgW`t#`UA}no|4r&GJ_A>t8==t!|~K zN~@U_@+Mo)ODu-nNQp0D_G<3Og1&^YFWx|TUSj_d*f2Wffs(2LMr{O7rlt+>9wMIl zO9sV+ceN zA*Vik>6DxU@br3CfOZCa|HD}Dc0QS_d}LI9{=r_m-)(2@c5fZEqF+I!5YLiV=;wh3 zn(!5dN&Ys*3uJM}qoW69GzAYSW5W?CBbjWVF72fvfsCC|}BsGX<{i{rov?m!d zuW<|6`x-+kM@ftsJeR%3ZqxNMdgV2`t>kCn<3*aFW`z3)C?s~6m&{H0`DoZ@Lxm`e zqmTqIx9*t5YPzk%Jn!PPUyM$zi9+{wP45J&7py(&T2OW4iyf1=F0dnEp@E$&z`S5jfQDSLCX3{GSC>1qR%HJ>x z3zdf%4J|-eCo~_Ayb0|1%ulE(X@p+CNfYNQZhiC{>{U0~i{BvHAf6R(@HqBlL=-7o z@_(2K@Dgk80iH5>=MD3i#MGz42e1^c9KDpM$e)Kzj&DE^r7Qx1M=G9Hcs@$!b+YfO zz;k;i!zb=(tjIMc`4HlcL(3xR48UoG@E6BPAtwo-kk*FZW4I-!YHRoio|gFV_vW#4Cy_(VQ7#dx z_A}$)lh)F|vU@*cC!cTD1z5OunwP|m1=vDFTd!8LjeT>cxjK61bBz2yurJ7L8I_;g zk!y~-|6raSUH&{4_zzg@&KKDQSeF!IX6F8phap_8Ty#vcpL8hvqgfZ*_|oXXyl7=# zkKAR>i*0G+QYXs#*1c>oiguaa#DQOhUyc+~%D4j<`CqY%*v0s6dYNswczW8IeqBt+ zqF0y)T|8D*`O4HbEdHET(1BOLOB{F|yfA|2Q-%OMkBpYQiRmwSm8{R%xNvqUA?cIc zzj$?&rw^7cqTYMnG%t%8drjJY=?!eH{*txv@Wbp!#s*N#=&%=L`8m0ow^-|%J1F~G z=J|``e-qw2($5uN&|eWe6J7@&dY!Arw^_2K@mm&! zZVW{?o)zMW`yGwg%}QDMyQ!nIoYCQn;F4Pnyo`v6?~p<(o)zz4{Q8w={`4dx#)$hp zwGb*Ez8N~#8hgidFGiYTIjT^1!$VE14BZCB`DF;MC^Jyt#l~09pgr$=mwij}PBM7c zT)Mh;=hQAPkBTv>9C!`f=fIobr4d}rLp!{Pj4pl;E8C4{-FwtH^$(2g_jt}f|Bq9% zuA3HPs5Ha?yc(t3-=`rcjrHXF?0^coxL5T)w>&f7WLdK}Y{yua z{K;Gro%MxFtKXwJ|IDED_Ao;J%$~;E z$2!$Z1}S*9uH_4FanoarcoBL@sss=39$GZL2I@oLEq!N2*Wlp|eSEv?FKm<=kv9B= zJ}TKmqJ+m*?HN57z?{_crnuz4nz^wZA7D-xNnP^H*k8FfQTw6XF8QL^JZXCIj2I*E zA(c9j1iiaSa0uzt-IU4QPwu-hqP~8uu5Q*&PoEiM)Db9ez_+^h*Sd}`RwT@LXVZuk z@M<(?_3><7Bgqu8uUuYxf;CpY(KTb7&~9Ld{$YbY^OTEo{)TZRX7CUbkUuNNsDyj5 z1i?diDZKh)3^%`k6g;GVtKg;o;tt0iW@8ziC3~n&9iFw~nZ&bok9n3melK^)(6`Fg zZ;JOP2OmBYk39n9H&Y4_q$d3$bRz_C2Suo1#K@p&5}_5JtaObCQJn~`V3~G8B&1J5 zhWICOCPf(MUmSvcL|LcqH)mNN`08f)1HtXPctj&1hJS5Zu+=*e#Cq5veF$j?ozgz( zJl5gEEE2=-9}@!|`J z9(xKq1rLRba`8_xiWeb`f096+2sts<@%tHgAMY`;tIfq0j=aedDh|tI> z9h)XXE2pU0U!WVrBWkG<(n5WcaeHu$YzipFDaMV;iMDP@-g3;2Cq6J6qx?@)RT|No zCD0fYRXM~X1pO`_H!0+;c2t|bUj(%Ah#J5GG8 zQtKDB6a+7BhX^?c(txcZ_yb7Ecmg8zAV|e?q}&M%WG`;BgiInxH)Kml89GvlHVJ7* z$j9vzA!P<}Xs~t>@)^5c+?^s+>VaG;LMwtaR^ef6exo{dkezl0b;}^gEDKS5{$Uhy@E`mWZq~UBcEat}@OdykBaxvO)qq6uX2F*T(z!K6Z zCW6aQd$!vlQP%EvH_h7dp8@lgsIzmFHrh~+&Uj$+G1k=&Zk}$v{x5Tt|K#YCP&G=VuyTk;I#}$v-St&M zp^_OOAsHeBw2&e~hZd4WC}HACYCaKa{aW&hl!gV7Hck?u1#{uWjTfO? z3my^1w2&ZzhqS!7aU!H4WZ~K&We7zGc52-SQoBi9qelxv9w|w$mii>9&#K>Re)on1 zN+Dvuw0I^$D(;vFtvaMngaIwsQ)65Utr8;r=f$8YJxa#hSp2=S;rw!yO5$tg-*BK96RUgJRpq14k-1 zC_fS*e;6VED?>r`%XnsiA{<( zUn(-Yik4voiYHWtEd@%>_I%e)sO+FBph}fZN}mcJJNGghC7+}c_U=&en_g7$GVWJ; z6?dudzWpklwylcqlmg2wz0{4lc0w6jRDi2mMaXzU$-ak_Tk^7UCy!M%EFDmKzNZv- z|6IAQj}$NcugWm9Qps&P{jt4Du5Y`+&fjpKoo5#yH$l0jN2;3C#VdEhuM+P4m2z9| zQErLuf{bi6hALO6gx&2bJa4O-B`LaV+G-W=sZ)Am*WaLSY4$IsDL8yjDusfz%FU=z zZq7>Oy3Jf$ulV=M_Ou364a+`XVe<)Hu)K|`B4c{2_;flwdT<)cFSPYjT6E27rk!nr z3_YrQUsoBn+^F1=yOdl1s;bf8FO)oCDR=BSRe_Y>D7nT`HEbzVa*`hPwSQM~QH%<2 z_MfF9#@BV(1!%ioDWudWh4^3U8m?1v%0}gOZ&!NNzflEho2F(*h8`=vmsEKFZ&gcm z<*2UAxL5Ile=FBtZ>s5)ut8S=hNk`r!HZd$I2=eb77 zIhTFQu27Ah4Q(3~_bgZOCpO!%-xy3(5y!uyTss#3Ds{_Lx2lLcb<;L$!!&re;uEHJ zA5?DbBGsY^+F)grDqjDpa>uvmg4!+3`0HMw0{Zu>0N*wxr|D7Ku|~;0Ju7^=CRskk zGagW`=Wi;0bG0(rB{wVn?!BsoeJx6EdrY}0GHqr2=Ul5mu;v{zbQ9@OpHZ#C`**3X zXuW>Etvb0)$(0wXzAf7t-hw_IFZW?(s5*6cn`(MH4SW98$=w8w96hRwZU`?>f;PQ@ zi&X}V+9apEqz2!FHaux-)imr~ui|Ijs@yg`C_P)0o$%=C>w84c|8)DV2OEfSRZ`!t zRm93!swLbFstKDGUZ@JHM|a(^szANEsgpmx#15a(UDR`t3LkhxRd7sq=|rPS-~CPh z3_C)bUcGA1Q6(JQbCJ!fSE>Y(-%|;=^r-IoQ1PAG^!C1@5_BD{x+3lcrQbiP^jhCg z6>HQ5E%~L=FYxP8nYRBbJH!4LRRYN;s0ht^b!*XsD?|5PX}?N1?_-tGpr>=e z1^kc!N4@USoZNG4x%M!Xeo2ukfWL9G?n6DwGjvN->pmVkUG=GPhH_JaU89%RiAPjI zZF*T9&~~6GRu!;rRJqN1pU|skL&?>4JipPaO=9isDj~a={LBA|Zo2O&L$Xt69MFrB zYp1eobvG!z>W7rua;^c&x^>ymeria*G5D@WtuO11@=e`y=kYGnid z6;D?Q=WkGMine$@z1WQFmI>-7J+AuRov3Q;d0%DZ))gtJQgUgPN^kI4C1ac7Yznt5gD&wh86RSMPMjGSnD}ukEtqcgQ_Sj<{W_ zt4cpn=@@gBTh?A;=WnFx1XF^WM7(VNMEpQ@S_Xv=5lKJPtT zrPugBGr&z3xMo-bDJIP&FyOLA6YW zp2z*)R5fj@Q{lPVfCXz@dB4iIS+9zvmn+%t{=F($**Dbm@aY7as}&!7MkSc@S0zvA z0(kUd(&*Mr|ESVy(@ov<%=vcS3EI+S|4haA>E*g(vt0nck$SjFU_vj8JDXHO<#J1p zBTpNqz@)07M^B$dEjM1LGk#pV8Aw_bFat7nJcgp(A?qa+`0e zjK>~Vqc%f_ms#3U-l-A@=rPl#m)T#&t67tww`ODiQt71W0+#4$*P(Yv8B$Og{{`Ce zjp+>1V^vMdbYBH8Hv6@y4(L5$<8;+>Y08uu6Z*m;L!07+S5-lMx|29miz()QOa$6SQVtO zR_S;9lslxSyN{a75nto)vOSZTswp${#=(aCbG?^id)stIb&J)sbbYF3OS`sg)w)T2 z_o;+?b;~ttL*>(5)2YWyFnyoDQbq7wtK6}5%B}f8)ucc#o8_PAnm?_=`-he5)0@zV zC8|K(^HjXSyHt3A?$WkRY6rFRr|ROgRd2!khThM2e4(3850>u3)P^KSuUdn8y&rn+ z0=w`-|5JVI(;JS;%#c+L4Yw|sPuq|B4ppFF%_r2wDC1x6Nc#V$YM3scW^uH|sxApe zsQygxoqF##s4u(Qw1G)Dpu)4X>2A?C9(=!18K*RSTP5`$Rnhtj#3lc}n-%cfs}kte zJCv3j#mBa&!PKb@PRHL>f;+QR0kialOPb!c=j)Bhq&8rwPpWjQZ&LC4A6Du1j^Wz# zU$1)o+VE62E5*iom2t-p)UxV&NF~&Jn+gxMOjV~cRQ0;A8#kz~Xw-HgsF$YKiZ(qc zn~m9O{V&jc6JOtD>t^WrUmBb)kE#rdmn&0Rr9V@RdtQx&cY-aZ6ZY!qTd4!*8|m?dZhl`P1UBiO)m~j+f_{`YIIBJK~$Tqnr>pN>dTBX)u^x67c9-2RCr2> zir4#q*4GutXjFVq7r1SkUx5^Do7?o|b&bAd;?og|D^x-rU6A&>)!wdN*LXrVZQkFN zUWs0G+OAP@nx2k%dJOpVA{FrKCZ1?l1!?}da?>W%^y|J=$$3wxKDL{Se;JP{?t4JF z1v-9)-Z?dExmWM~yxJmWbf}gMrsLnKuS(ng+Q*Oi>12UGhcDqf`?11*zk+WGYIo3&K6$j%|9*QB@YIXc}oxpI>6 zU-6PEVO5G!90+@4fxgzWqUzr&JVRdxWat9b>#f_wHdR31&xqYeF4$;uu90zoqz6QRmpvNS`BSg z;XXYp3SLu#Gf&?GD!fmHC+J;s$15tlSFa7ddY0sA1Le=wCbRe_YI;=bh?)9ow($*> zU`B~*(#ct>1u8q$H1Zs$M}4p*^{6jdrCKOWUmdsUJz&2!y~#J)>G+Kly_)5|r81h( zrg1`BvNm1Qz)w}i1uyCX=`B^`F^UKDwP9esl6^Wu*9}SzwrHa^NY(azgf)Cvsy7@> zdfj&E8r8n9G73f<&{wTKwR16i+60d`D7|LAj2n8ewfE_QoHu*ZJ5dY$9oMV-f?t#C zH@>Efb-v8>ueAVTX}-<^*p}{VEP%4KUta(1#rI=0vIVU*qiHe4X<*oNsV;a{iX{cbvcH+{yU| z&OdVQ;_Tvllk+Xkw>i5x-{E|h^F7WU&i6V0#QA5=Ue3R8{*`k#XCLPt&JQ?0Q#P!?XIyfR6+K;o!Q+OeYHk%W{q|osZOrFX+DuSgVA05G@V#mk= z9hyl7P@bg?Wg;IN!KB9W*k7n#HgaMFYer6rV2H-tAX5`mkYUW@3{6nj@ea%z!K6v$ zx;!+luoEJf6j~l43)S-rl*c#)N^?rTiz|;T`e2ffFmX@htkz>em>ef@2ARn6%x6jj zlcqk|ft@0^!a^fUCZ|RyO8-j#h3ZLyr$sQ)J3WF)Mb3y|i1wIM>E(*3jzu`3nFu}8 zfh~4m={B<-JbM3`R>s=>aWkZZ%p_x#_54NqmslC&`#jd<_xC4Q-LK(GO2L=14`1$z z{Rw`#nKCUaIV}%2Dl6G5Mlw37g^Ob!QHIMKV`MCk%BmzNt|QvW^F(>dmUj_4 z%}84wBU)K5Z?uum#I5kqJU2}TndjeDtwm*1nG?};L&Do8NBm=1TEq(A+S zZm-K)*0XO8V_wQGhV8q&;@Qw6s_wrt0oB(^_VFWA9nNW?GudZ@8+e)<|Q; zTvTHhz?D_wjWMqA#LV<$xo~-}UsjB<61fa{C2|>Zp~sCIYh3M_fjb>}Caw#47OsTG z8tYdJbs2ZBj)Bt&=w0oZj!TR3JsZ(KDJn%0oFO%+k{+c69&mZZ`bHz$jg32f$ECm9 zcV3h=cGdnkD{KCKx7E?P#kC{w`+XJDcBEgizvZI)Dq8n*{&z=3>x6fymAn{xK1c)Z zAtf35l423YIvqjUQ(PICbz&d&AyZE5c_@>{6?-1Z#GXeoi66qgwC5r4kUfuNV$VaF z6k6tSC=1&2P?n00*z-^(6|?PmC=A;3P!_c3p-gHl_B@njBa1x`WzEQ9&qEoaZO?5M zY0o1S#hynpZv>Mjo$tWJo`=SjLW?~QWrys!Kxt0tcX7p@H^3xuVd9EC59qNVOb)T< zK_+rBXG#QN3wLA+4g*X1ODJ41r-amnC6msDu>59{rLK0qH3*G&)%P~Wp4f9 zR@H0!<(nIocPa(--<0rU53f8o6mGJXJ-Y8CURSckWfebr|IvqMy%rk0S>hbG$+vKJ z)E3)oRX@LFc9dl;>e!dC>9bP~w<`Zk%=rIqNsd}%9r52SCt02jK=z~ilB2d-8;{$c z=$|$tLw#&Xk*68uo(ZD`yItn_4A;&J`|~F}-lAFzEJs$I7rSai;fff#0NqE2#<pY@|##z95{8NDwvqJ5*vT$*_{e#}kv_%Zee}7&mTZohPPx zeX%S{QMSHl`m&-Vf50+{4_GF{JSr>3E0Pg(fkgC@@VAYY<2^>FQ7qA;Tt|7y&P%~< zJ}uk+nw=31k1`IPG+{i!(uzjb5ndS#u~{zkIcP>P9DFUvi18amy2%fo^cfKZ#|GDQ zVu>01vgwcThJ{P&EHlz&;-hl*yp@Dyj}S#VF-8F`DNC=kW#zR|vL`Tn%k%6mNn1YO zPQzVqCm?IGsL3Wl9I9=&tV>JxFZ9QC*i~R(7(;F_m#%ai#BK4Bp9RRGug4xPuw!8cK=P;8Hbo2U{Rm!@~bZ6{k~0w_Qb< z|KU}1vn7bEp=f<&4c+#3#O}O{cuj#l4Wz^~LP{(vL}Z`L2rF@v*KlXh5|YjfxP@WU ziKe&XhxSoSrd+o20TcbT37@t1o7E)PqYOh%P#v7!vw zVj0M?C9_8;ZnUw*jyK)d;+KtZ)=Yp>++rtWm)&)bSB7R3uI$*S;o>mMm1|sh1O-E8 zmW$qWT(NdDjl2t@SXyV{s*KmKib9%YRIQRw!>C*(p;48UtN0@K45H*+Fx}t>66^>Y zDL@*ASPW&=s_9U-arY|GimtqCm8wD7a?y^eT)!&DD3(p=@?vT(1ID&7^oq-%CET^h zj00r5WkUu~lySH>%8mKDn(|Bw*}+qDYSTjR$tw|FSZ<{8mL2Tg8ZwZbzuh7;#Qt%h zyl5kCwNaeLx&|ng|CEHIlAPbNW<9_El^IpEpX@o?`RMbQFZZpR(oS(%ub;Soj`iAK z_pLhoN2_it%Ug5X?PY6Lm*4QiHP+kjPHa5w_S;tfV0Fo=+t@-Fk8(=SNM-Uly_}Mj zFge`T{5|^?SnrSQ%bi8MYi=)JQ+C76<<^5E`!+2SaLaYq-M*$Agt8IlY`; zk=Pj$_qJPpbo-Yv#WG0DB2F*oSH!f7vHF%$iD~Vg{n@6|if=CutB+V+NvMR=%lQ=v zB@!=KAG8`d?JVpeiyafTW;g5H$y!=3Cl$CPjfud=}3#|LE zJaGD)%7rS%A@_E}+I8iD(~b;&_cG}6UCUcPyli^Qr@< z9~t>Mka6^;o0E^Wimp0v?2&ia%d*j--L|qzHa&FuQC8zs2NLE~j$CG!Bj}FJc5k{R znU~yU)Vr*qs}95+Q8uX_77V%x*5ga9@U`_R^#vQbXj?e zNTc-oRHr#>rJYOAt^G}`bxrpExmL5Jk`b+@e9%p)jt)tsF>Ix~Te$uRL!}WGyO{^JHkr|pA~!(Z7?i;|L>*I37=!s z$PD7BQSpmDin7~caK!=7tl-yLi*C8WiY`2G){z~z-e@a#=qGftj@&`D6Ny31@)HBjAI3((e)durPJ@@-{>JUfVnHCOH9}9xcY$hASyl(SQn&Qk&ZJEmI+LrZ`FhHmo6f6bPT6NW$ z1^hMegdp_|hoDp{@F93RBJGZHHFy$WjT?f8Pu<@L~+p^NZ z+!KWN0ZM2Ofwsus2BFsxn?WE2${uFp3(qfb>`(Bl0&gzl-=U+^pj1K>;wfOAKpzA7 zc9OcSAeF9_veIDuG+n1mWvAPs`je#nnREQHV|U@t@NH>5v9 zb|3P?LFz8*(j@QC{tgWmhxATB{6nF>Zj_;+BN!8ig8 zzXAUU0u!K6LOA&(9|?LU%JY%-qLD+8`xHhakouzn<3KwH-csn0PzAm?2^k!6V@?u;!YzT(C2n z`W}VhJCR=t!6$amBUdl%y^BR>&`A6pK!ua3dYlQMl7=Huh z4sa?Ky5EJ4r$IZ7@>RCxy|8b61@J>Cc@_o-gU}3u9g!|YDq#==Uq$|JU@IZ)LfnnG z9Q+anumX}F1B2%%Hx~Re$kU%`7#s@$9z>Z6Y2xuDKF?Z+qBt=9j`Bp%k`XK5jogjf3(#$SeFC!8-<6Q>33GEk(QmPJe)Chq1sUTmp6v_yS?$S73hB|B&>*g!ciy zN@gjCQb}JJ3_mRObIG6e<9of|9T3;WJ2Qg7!Vqx1sE~I6|*Q-#+l( z3Aq8FPlBQ5D7OGlCm59A=fisieLWlWpMgCIU9FLZkk5TT3O|XLP_hAxb&-}JN(g|$ z2na}ckzH~Hit-@yGs@L4eilxQLU|7Pgm)P9xLF>6v>Lqcz{Uoob!pfGIRv-$vSv(a z4-77c(#H`GLvSd{^^t#w4jBn3_!>?;1ZCHOryEiUs}axBsFaJ4Ukcu9kd1Zt84_{yU3@Zw*5ixM_lA2ETv34q{nKZ|4+ixSD@@R2u`7q2w)$AVF#21LqR0s z1Yp%L+=mKpVr!^cto7jE2zsKAqaI-2vc~ry|+ysF{=#%gu zuwqsy7x}T^8&29>IP{#%|GQ!IZ@Xp?`Ue74Fx(ti8EF0xe1%Fx>0IRBh9et5JBQQ- zN20;=4&q`cPoaSagc;!}>b}6VHuxlDLzeY7Wvd#3S7>M!YbTUbh@ZgQ@087Yl?v7Y z`vpqhMy>4d6y%4ose^p*7f~S(nEruY7xK$t{21)HC)$!oX8~A(T1f~%ekcrGg#kYZ zb%aneD147fmjUY!Lz6&Hr9+31jz{@Cd46GK{)Dc-AupjVc%~x%Hsq~(sQ*Jq-=aW! zC_GD{DZnfg$SQQJ|5*ENRQE|;E%!ZLh>&L zeFymK)tC8)a0iV14&Xkd55sUS1qVaP6TttVpzwYU;qBo05luJ}_*bmG(3Zl%tCB%@ z2Yd~|_cE|7RqL;e?F6QS4(XC=%B z)&y~YPi@yC{|}tI0KO>X;iKH!$B0#lsOLTm;W3D%}bPy8?e6wZ4gl5Mq>O9=gn%w`yUfK4k*qk*-D;3>rKX#6bF@7Wc?Q<#)bk7+4* z%VBdqbRoE{U;r<`SO&oRSiuP(W+C4WO0IxzhiYVgM)@r0+o14kICBc+TpF*1@^g^; z27F_|lSXG3qC(3N?QlPJdKzGSZB|b#FO3UR1LS}65r~B&?b#ytg8wKKd;#Si;6ETr zcpLN=;K*piCU7nn_&(~ckMdFI>q|#hLVuRX$@o4@P?R)9KFD?i1}-7q0><9-csufU zkbWy`_X3R!VA>jv{6m`P`~ot2A(IY#BAiHujTeB&L#KNLgeHLb9oF_nIz2NDD4COt{5|JsfACF8>&A*adYa4;kcRu+4V60ia|`wG%m5kCd?1L8VhgHRp_`EL<#Lvw!&z5StQ1Mr_f z9|ApjaHa>G$OHX?v5WQ}h0Kjm@-UbKz$jq|l$=An59O0k@Bkc;un^@bNLvDX2Ff}^ zW*X$5Hp)PU^6w!x3w#SeKLox_-SoNQF=> z2uud{BACwuk3+1B{9Q=@M7$39{gAsGyvI>)fw&JwyF#WO@M4tLg6DnYLy^A^dXK5?df@a2?f|)#F!UhO!zlNGiv7^>0?HEJ zgIp`wUj~EN1JQzD11P)>F$&7&g0VI*2~Pl%&;;qL>`ym%Vh|;q2EG@(ji9tPbbSEB z-H<*6{AOUA!1pb%n}DqZ_CE3*kY6PGi*M))P(m9RZ$sr$o&zNj;N3!cIp}NP$X_rz z6SOapehL0!D4vH{8`vSF-?6r$qcLTl0^W+aH)8PYPH%KCue3{nYSg5fRXzhU_olt&@Pu-R5q(H5q4Ae#eSjX>`N2MS>@0<Cm~S0Xo=(vW!v%ta8|3W6QpWqu%($TOmO;9G@n*h5T*hSELBA7(0qB1T`A{a|VWiu@a2^cfQ632)33mYBfqW5SZz$aadN=m%UKkq< zT%HTgg7Mdpj|TsH90MYM0Qp4dwZoIh42KTO`^dKB5cegppQq2lav5qmLyd&y5IYIh zn?UamtP;F~kUoO+H>mvv^j6^C=%Zfb&ce-!bYTVfZw3D_#QEe~3Z4jUAGfv6$5#=a ziQfB+4!nl+X4Lg01RKGLTOsrd42C03hGTwED&aXQZUX!S_@4oG5AyzqcDMsP7f`+n z>5tGg1$s8fmEM;yaubZ+4{$mdZub!q;h#X?jrbiK{WsD}py*pT;6(+VgzO*S{hYLK zQ63Ekf2H-Fbo5b_JAii8wjqNc8$eqqzYnQzNP*(J!T132t59;3PSi&_2Qh>K_rlmM zaOflObVbd6fWt3A?r+ei0^g7F3Zxa#w+%dl5f_8*4n$@k2#-O%EHO zY=<8~U%|pq@JMK3*97u^!HEK3XMJQ|20agQ4G{yuGn}-qR8A*BcL+-O2*ie9+RHH! z3#Qv3DB%h496^Y!-B8fcIJC1EJ#z=v^VxLi+zD zWRk($1H?OF@L$$!J%qjhql6taFdOBC#6E;f5tKa#e%Vly5G8zp^mfgfzeB+DGi2U@ z1GO;DTA;iDc@w1m_dLNwc!Mq^`!}<_m-H+P-MoD^CSUi|pJ4B|G1=ueNR(aI<|U3rTOuKbw(7r7n1;f*b zu|8G@B7bWwZ}R>lZD6uaqwOfqBK>~v$!%z)(vsw$r-D-a{qB--tFE(YN4SO{f0FDQ zVfP6i+F^0Lw|D17w7al$0lnDkH-18x-(;hy+5JGf0UbdNl9X$MW`?Esdy-oDd&{>a zw;ui~2xom%FNDxnESDqi8|M3zm;2;rd7f(>;tlVT;_ofnmK^EL{1kp2pyd1BuTP*G zV_K!CuMHvCNBu9Io)YTKkDeXS>oA$Wqvb>}-RtAk>!3eFi?8~5UzwQFyv|=Jk2aPw zYp3|jyDBDJz~A#A?L&M7Dn6i?5ZfaD3+w^0-^v>^cy_?FI3M~Rxts5o;@>QjoVS8%hb@M@b6|>pV}aU$r(t1{f~&u zN;E@Q&*g-Iz*z*1El@6kg|@V^nA&eZdOLFMNBll$o!X}-$)aZ zRD(AR>5Y^TEP&gS)gp}rf zPs-xbuIE71E*DlMv<5jElY(QNQ;Z)65V6u4?-7k_3{JQO{&>0xIdsZWD_fU1P+@ymr#an8EJ3k zZ>FzJ!1EEYi%dWBaqx2=wYNZKich&G_=d?U)TTQnZlG_X=mBE=Wx922)CH%qR4AB? zINx(%P}uOH$lZ-7;RnQMsD1?He-Wpm{2|i5r2hokNh;6uap9b|PjPa0Z}EpXGL^In zXwwT;3P8UVa+m2qee!=UuDZuj70h!Pm8kZ9r4-bym1g0mDwugl- z;JL#=>qw7hgO-H+xAtRRo39-N=b|v020jK;B;sB;SwXk!P|2gfqQN%_4oSFI z8S`V99-`e;$jZ16LYhFG&-z&%tT$jJ6iiX9L=^?%p7sHDH!Q$pX#2V zs+)l&5r2lJkHXxIpjV2I45whe5$Ky(l`y1*h>4)5QJ1iO4Qv2CDfP!T^d*RE;Y!Hd z+X2s`iF?5IG4tujOZb3g$^S%5l7sm3sgH^AK6&ANfpT-8zXy1q2G&cCb*@;HCI}0{ zFjVq;NWQ?z{*1I1=(Sk>-N*XF;7@?IW#IqY+kSg;m|tyKHr+k3t^NV9ErcqOP5{%l zQ1ThdwO2`$^LDG@m=|Y@D6BaG;1|P+R^ZNiU;|3y&t4t=>ONp zr{2i_iMR^1QLwuMagd0#a=!-`jv?lQbPli`0^vntxP26OJF1!pzI}9g0n*>VGZ6H* zDD(tUd5Y1Q{B=N=@EpsMk7m9Ed^>Ad(*^tAdFodv-Gk!ehy&@&d8A{27eFu;4jo3i z5al~W5qVakY=`ThI2DFd!Mhpx`~AEhY)kIYCKLJRfk{{b{%GVgDHm@JT;7Ch$^Px% z0-uCJ=)aEqA0b^Q_7K9&j^^G1Q4gRj!a}<0gMk*2a*fwZc2$jG4fr2 zms7eE)9r96543GC*O{7{0t=$6>BJiQ=n~QIK!1olZO}8P$On@5hU3TTyIpV~fI<(F z_zlW`B7RKce?u@A`G;Y=8F`XHk3@Mp%Hc?>5hdKt?(dGYF)%Oa{SbcxZ8~W!*@g#d zSwpRjR4BrqK;RF=tyK0i8HM%|488{50$?_rfSWokluc91={62bd6?$GHZIO>>9_TrU@;cI1vrVs8{ch`NDEgiC6JyUKz7A{~ z1lB{a5@|G;%MdU7@J#^T67dJ%kAZI`6rTY7DIeosKvxGJ8PPu({1Z_9MTl5yu;Z|1 zr^yJ&nh2&l5et#8XO{E7!SxZ4>me2bvl33zQ~}ECjXJD;;Cldk^$?$hOCLe&2*gD2 zW+EP-%r@}vfZRdw#~|$l{7&i>-9Is31U%Rej}nfs;e;sR9~kIIm%l@P3FudmN_ZUk zb<8V*X~awe(0aglAq*Ub@hM0f(RpF%Lpy7L)q(Mz;K53Wn}Cusv`4xZ2Ethzfm=av z6CC;s_*@8IkNodcJOTL-;CF&&hf#>xi@YlU#{lSPfmFg6@ZF|a^VbjZEg`p5HkW~5 zx&sV$=nKKuQGOKZ0Dxnm@K2OSL8u>UwE==D$X9^=5@@^WOcT&qs3 z77sZIol%y%s3u&)UtI26HvrrWp(l|(P61))#+uv<;}Y%x@1rnu0%?8Hl!9e~awF-O z;K|6}1-{$B|32u?Dv#Ux9SS?4&;d;A!1OxeEnqqcCq4rHHR6ll=}E()tUqYCq8tD| zJ3IxxQ;0u;wg!d*(P9b6OUNbPeZWePPou6Zd0%l9YB3ejH*|)AyWq%lfN`wdI;L+y zNg)i)qH>YT1?@bPJ`b6*#Fqif2JdQ={{r3{^g%HGD`I!Z3_+SBJMni=b_k3Qfhin9 zw?beo(k+N~7!Bsn>;lrUkXZ`)n~-@Iv4}OYSuUb{)TdJG!RrUC5_Tkf1KKp`Y>@*+ zc9;vm4sV)EUw32Z{u$UVu)T;h9qC2teHl8N(8r_TE2Qpn`2R6*4=_7)@G%nr`L8K= zvyaLCV4ltL4e<3Bd7bSoDESt`M<8%71ph)>A55Qs`FG^&vf>{g-xT;j7{4C0&yl|j zYzU$RSA9$h`o&Vp~KG+sd& z6h2Jjzrvv`H2q^xHXP9lo^OyIgy3bQ?VzJIct+CkR2mVz?}7e2bv}*!PVl~h^g0^# z26RjbbdQ&6gVGxoAA_{NkA~&2d7D2E(5h zz_%C`TLc*it>HsEO>)L@&!=U=kc?4QwjnYAC%1gSUcrE6S5V-$SQUkPn5z z?ueg3W(9O*BA<@5HfXVsX$#&Z$Tx)S?cy+EBR7qSmsL>S2*h_07ee?^#Kuri1)gFU zKaKKSDEbiC8N|oH?+0W5P{$@Hd>`0*q730H#HYY_0Y)X<2-yhm+>5doHa`ABelbMDC!Hv&x7eZ2z7;U5z;U!%R+ezWIQl10&)q!ry&0UcBHn;F8%{kp7@0D}nJBD*p)p`; zgYqXZco$p2R`whWZU=oNc;|t>Octh&!)xPCXz@H4c7)n^=OV}ca-TF89T(ZhIVD31*_c$Rf;FrmVz2(i*esL5y&FH=S4{wRY4@+tV= z#9LqNWAIq>To0ReOKCHg6=l2P+0eP2yDd<0eC=EEAPTE29qCIv?U0JwwV=V{bAh8F-Ii;4&6fO;0_kzhh0nbDD{0GC>S+4) zy`=cRHwwdvr^r}AkV`-bHv^ZRO7yCJZ6r(x@|S!heK#B@V%9hp1Q}D+E3^i7SG{5@ znpe}&^Hh{`b&02Amrj0*J?*=P4Y@?L-*lI8V-iPH9gHAp=kv?tiVjB{9qv{W;O)^X z8TVc_xW8vYmv-)EK!f3Y#yGVZZD`=6mb^F3jYeyCs1mLxo^)o30dmM6XSAacHmM%F z5wgf%F+qo)&F@j%ZABf^;gG?`d4U2)?@)`lt!=_#8pt@R22yDFH2DjM>%^Tz{&U2O zU({x}#1-WS;4(O~r%N+n53pPR4+`wvq2ti@v=$n`2u#y;?DKWPhFP#Y>hNwF%}gwo2kjr*$|N^zl3x+1C9D;mYOR3}X@5&k$dG$z_mS zw&z9SS&yljeyna2R7RRDW~9Fvn0B+Z0dAIoNabgDS1Yn&=k->q^QD^96t>^%7|-J%U4hi3`(P&b*8 zX^wH#8o2n7uo8j@v7GO{48O~51vzSSn<0c*;iJ^B-O_iffK@T8rbF{+psca3hxs(H zns{W9t|W3ElkgJptab7j(Ty__Yp@#x>H5;7ng&i8Jj6=M(bkO-EeJnSQO0;}vLu7z zvWIxTJY5RpS(}80;o1_#{>twXN8N}n5(YQoiq0DJ18!F63^g1HUJ28~Rngc2SVGVV zf@>AxrH$1<9QCXqzI3;)Sr+je;FG1#f=<;OH!oA5tf-46A=>=K#c#M8F4?De58``> z7fp;X$RYqJIPSDcW$WF#`w)u<0GVz#o+Azh$FVa#~ za?Rl%FWa`eNe6A_%KZZje>K<9=EN&bwKBNIyVuQkfI-WT_ z+WOToLudtwS??-wFI!=?QSP#m94COyz)ep+SkuW;>gh3Dd$Nqiza~EED{X}!en$1&5{_=;=$q1J? zc>Vz{Gc3h%+6e7zS^*o8qx}bfAO?qk&**wyvh(Zz+%zqLZ(THTwg&^kcPSYY4;&FNUMD zTt@RIotsuC;xpX64IU--Z$j)vLewN}y5jnVZrw<{$DR%bkUJt0CIA;lQBp6=Oc z#M9&p>aSf@!lv13%jfHewJZ7_@m#Jl_9pS0?2PVGn>tF51^>HEf)!q>HRDFrX0K$S z#0%?d^T>N85;_1EFI`J&4wNy#rP=Zv{hq9PMq52D>#~%`YAmCH3~46>d4?xpCGnsz zJrd@z*|q~01Nrtm@bu}`&V7vBu9wyQa#doTBX^SHJopd!L%+iSMvzx(Bm|?4r5Un1 zY4hZA_6;GPI}L&eTiNSziVwBo*J->{JHvY4*0!ma(c{nFSt)06_i<7KT|0Z8w>C;aBRAy&b0m7sCaPwRb)F%PNHbUhHwK+0!JXpG8#=E)m~q6opw) zj^%3~`QuWxT?@#6kofsXz1)lbZRf_HABWrG9LzxU8LyL(me>kltY< zz9+TZF+{IYTg4jnp*l#l)xs?u>AjTaI2IJP9x?as>XVu=QwMMc2k_0nrO9?WE_B8N zml2mZL+5cOwap_Q{jB2lI=#i{!RdZZ&3S)F`Q6shCu<7)4T89PDP0{}ONYL4;jJ0$ z9M(A9Cu!FT#`#|^AMzqM7$}>B2;icpz@;-Ri+cJ4H_K(d*qw}91{9cW6opx7#oSTY ze(6+{^g(;W>Eh0@((t=1m*Y^p)!-pkh1=`7A*z%66`Rko!W}m_F1!=8LiVgG2QH2m zozO8;+FBhvM||l=+A#J;U#F+?M=y#rjG6SiA#hX__wE+fZ2Ex|D9OT>g%G9stec2m z8>KCF!BFwOD)Gc6{S6X;9+Gf3@k>K>xhPWDN++IkwG|L-skvNzR)HX0l^L%NMN=S$ z0_82V#z%>J4S$#w^9A>Ec3~m$Ovf?(fWckXQQsbced{Y4NLbm@sLtm^`xUs1h4NK3 zTc|r`kT_a7vZkZa28RL1)Qbl$UAB9p?n(0GRKi%`ZXuM`*1k#SVQVf3VmL3Yrr~F( zsNlG+oc3P)DsY*NIleW6f%grL3Jj^~=q}iyDbJG5jYfP-`69;=yg_eueC%&7T7WO*#Sa!g=!- z4|9p1&(^kYTQ?BQ^pq)vI_?$4(WeXsF_DEA*PWWe*bBQAMCib|i#JP1Hbd8n7G} z0E5Y2d0tnmXl1wJi3hCHbK_Dr-wfjAaWXuxij+}cEeRKLvEd@@|eG;>o{( zcwA#07+lV+7lBLvWasMKMT418N&dZ)lT7)b{FPPgPZH7sbd|BE*FV6eN%I|tl9p&m zv&cBEueT77ezB(Ew}Hz9%5;pp65wuG4r3h4;dv0G3!(?>UDX)z6yX~2#BgniB89EG zSWJY!xPx|?{XIZq;xq2j(^eX1Vi<6#z|om`cNrC#R5S(zaVYY6uR)55CsEPSPP((% zKRJGg?C|H}I^$Hyf9R1ce)KNUUos1wqgdyP~aA}&jwKe;&OF!+y zBFDXxSc8X6v=SVHWULaboen$=xb#)_MIGhx8NGx>#B=50Ed})a?aT+)7-k zZfS#J>7-Qra6RDLZv=ive0MB1D1@qTlUNsk%TUa7?011Ufe0S%xPs_l@GzVv9jj?y z5TqJAztZK949>ds1u(!NL#5dKJJpr>ckIRP# z1ZjzE$0XZMf%N0yqUV3F9qc2%d#tWwS%!*_Vo@~xz(>~6#7}_V%t_y!Uv`+&R1`a* ziDyl}PAz^UW7XlBT{6~m*gxdXeouEN`>uQ=tlDC>^lZ2>C~wtB=t?}OV>44OGkODykI6OR>%O)^8W4IQ^}q%LdVTcj=%eeR}RpQvX31P6CZrPcDN1-T#*vbi&i~@ z)vEO(@lCI(p0ykZ2NZW(33sYM4h24@K>owp(Dpgy3*gc|QG9@9Z+BJ1T`zf!hH~op zhk7dZtNv@OShHwtw{mkig=LT(X+?n`4HsQcJ(U;yB*YT08mM@zXUKqd?ukHUe&#uD zT&|}2e8<(=v(ysh(&c`WdS&gQp7ITO#+qHN-woc-s#>wa;P!&<8f3h@-l}>~+b6}4 z@d6zPGJ{GTO#$_C}XJvm|o8tm(4EeL#hZ+7P_WeTQmr`^Vxro1@xZ8?}(`hi6 zhTk#UKJpP21-_+cuSB-rC&b6b>%L%5n=gqc4OPSPf}n(u8??gVo73-KP4ls}NovKDe^}()n>Avew+r5eS3zL;Be~~C0Nyt(^Uu> zQa1V`M@RPoE(0d%C!Ne$Y>sinL;r5#`DtJ$_k5JaL076e7)b}8BVSQY3xmucet`Iy z9PLNDnU4XNRjXi>>WL=*S@I{=*L7ew@e9h|)XE=LQ(&r$_i0xtmUT|LAFpS!J)7L9 zy_x1Xg>?Wf)jfZ&x*Mvsw)zpzX*b*Gv8%Vy?4Gw8Z4Iq}b(w~mZvNu!WVw=?Hjc7s z)vD|geQ+Bomlf?;`5q;IiQ^gPbHGg#JFfh0l7p__ZaH2|E2C`mzuHWd^yC-f35V2& zbo$WnCav$Ki@M5Y6K@AxY$ZCL!kv`+)?*StmAQ~ndd29s*Q8Wx8$4L8*r(2H;z6J5 zsCLoHCgQCFn|PicbYt*#qt}Hi=&P#Nb8=8Szh}(Kb;#!3uGcKOy5Xct+<#*mBU8@v z#1BSSm{oCFeWXdNHr7e$;h=h|CyNV3An~=IhZ{Ziqw8+KF)_MX1&-SsgF%ocs?5`Y zXKzHCWk|SJk{bC^P3p7619%Z?52W{r$0gSs#<#?s}j<@R<*{$GHbnXoy?Aa);LC2sMRfH?Bk9-{n#U&)Tp5U=vF z#V^V=pSvr_Vm{5$ilc$I$55*NOuLD_VWk^>tOId1+hY}QajPUo*ZEvOwZDh_M-yuD z&w<}f@upVq8-m^MQ?|UDF75U+(ocwoM(QG3#>?R^iD$gr${0D%p;c|`kw=yYnLIJ# zBTeI5LS|comzuwLF&#KY3Ldv?so9BrC=fSB2T#8SDlv$7WLdZY>>FZZflDL0?D;_h zbICucvbRABcxHTncx!WwitRzDSJPCT}GqybuEgi81psqjbLA|n+; zE|+tvH3ibo>WMYCmf^QzfXiN%<9M&(7K4Xa3Afc8sdrINk>io)bmG@iB8=j(@>hoZ zVi3$onqPAy6;dFjLg!8>9eM+}4B>Le3GG9JhghYPYC7}{^_)4N6|-Me{}Z@d4CgJV zX}HTRY@#5S@wCj}BvuS?Fv!*bz6kYx=MJJ_?b3pz34XFo@X(P(#SQ4J5whYJK z^BVCA$GUWsdi;Cnxhx)TN;u_t;yPCc5Y3!$+=_1+r?@LC&-46^o!p~Y&UU;Llnq>F zdF9ytMrpYDi!ZZ@XYdBO{7$HZBI1Q1HBSwn0++rizolm1R2n?2sg>clEUlDh_${tc zookD3Ch~=ugx5U5H}!7Oe1tl8ZDVJHX0YZnJqL!n+$2^W*1=|9kn|?L=?_(DUnGpT z`R~(xrAk}Vno2x(ML%OCEyN^NGV$sOdI2N9C@ewjN=@C_Lu*!bJqTu%a9p?@q@sXF z^~|2iQS~|T^Y7hm6x(kdo+qAOr91cqL&e8Y7)CgN*}-!*wtkB`w`mJS+^xFpdu4CR zo5SuFq+SagV5ADQhE{vvGM+OXd)8=!hgp@5Yq`19Q?Vo5=xNOfu$+3T9b0&=@(;CA z2X!+75je$4*hEFej(a?>63;%+y8 zk7)U$WzFnxbjbkVqS10J&?AA%Y*;&UnNh|0Y=!H}V9gkvZg6`YP9lGLP|Y*XQq_-h zs>8sOAOyic>A#&=MNKwQQAsH}86k-++z?|g2#yxtYhR@)|0`+$pH%YtPGRd)>bYPV z5`{z(zB2-0R;J@Z(?4EoeCd&1hO>f(8vvIUI%;2KcuwBju73njX-}8qVs;$4(;OGz zKgL44`SqFb7?&nrVZOiLqc*@Ui!wVY?E#l)j4bX8qT)oX}X zb?k1CXu9G7Ziafgx?;D%8fj_2J3W3wd%NGKY`;Oe)dbMiS>iG8wlg~8XzMqlv!NC4 zc$=ivNNuK^KUGf!`G*mY8>zVcba^ar_~y3Cm(_G`J_ROCYiv{mu`(-wql2u{VqMp4 zhn_Sz-Y#@(1c%jtRql8t?h5s{j+I%6BcMNPY$a$73XV20hWFC&4!L&f6H03Mts;iw zYM@E1R={PN#5q>6;pWCq7fQwK(N-L+LRK$I9d)d&apYf0e!G%)lRv@1zkqnr99>)O zz4I=dN##bzt-XWY4;dcZ`*JK4kJ4887TsCx6T63a!t4m+Z9n>4NIdahotc@Of%}PH zxOl(e4Ap+KP60>DOtb>*^_PnN06~Ujf#adgfKl23DdTj8xOh?+O}sowSIKCuP+!Oa zq2UBl_kP;gbN8@LBj&MO@RClFAX;4tTsq2fjFSxp#|zxPA2&j#u33%>DOKUv6^_x$ zj9nQs}BMfuj0q*BuV5-JG`mlxrOP*uKhiIuJU)Y;@%54 zgdX+Puji?#s!Z?6UQ^gwAY-z{JD`eNnU0ImJLM5cpPShEMIzDw@GeO*1N#vm=Wbz<~}C>*soQuef4?) zxJ>t>8*BD;Eth*n}%dGBns>@8)H9tZp zh?N6e%ojP@^95>)aWcjcCW0(k}9s zJMOOaHT?Ma&T&;6XK)O0$02>P>cQ#CubDBqiS90-ft>76gZCr8ig>~9aD!K~_nrkV z{gAh~=Boc8`E%tBDTJ-&FMc_fc*YhPzp%ZDgg;4$c(SplVO%G7<3t@6L5_FHB8bO3 z-dN}lTqaUXb3JYsal+hW_#5I2?kr=;kN5(vCDnW(m>uruKv08rpgh&vx9j9%67DSslyr-PE7IM4LFD zE8ld*n_8DXZf^_()KTx=Fk^gpu)4MLHJy5?O0*WyOpN21#%h|0$Ot!_V;iY}7q}T} zbG1<-spmuLNphSAzE?d>t;(G`#;Ymtsd+@~KT!u*wBvHLk-_nfiDN2tHF!g7XW(k1 z2jj$qVZdeJWpvld@5M?ZVKnteIv$lSRDL&pm`SHtuJT*!X`q+}s_|t0KToOfLcJ`#L~YxMXTPs|mVKM&9pa^Rb-HZgboq?<-a_>%miW)WVHZCK;rIYv z{xPw%P=MoSYNCOQqiK%SZzS;y$HqSwxHL!7X&qaaSnmgjm(-Iz5Iwh>GiyB+#W)tJ zmx*WdX1d*e`wWf+#c^Bp6mY3P^bzf{aJJkpz{R25104)v_DtBf>P=R{-c#Dt_KP-6 zfXh@5PgF(GR1|J--0E^TI)Zw(KA;9lIe1fumv+*rW1pqJ#E|ur#fIX)CgBB=K1;}! z`>w7CF*Nru@udT`2NQ^YB&XmJ>p_)n$#h&2Z=+ONV>O!3elH@PH&OBI7OL);S@lXu zP2Z!_$$kX!74f|-_26RvMA2p9*V@iDYHZ&cPSGa4(7mt0chcwnXcFmzgstfYDQDj| z1wU$mcVr#w*Q4@cy1NtA1=d$}X{<~y;=9*r&uwj>cKQ>K;nRJ4$lR!AtZ>INl4NlF zR+M9z3PX#_{`KeW!7Y}9M}}3TExLy3ecHV=Swj4bE6lhiKffoTiui?! zC8lhjWUdguG}~oxZ6^G-=TvDRyaVU(Fw)?d#*vPznm7>TL!{7^D~uvEya@|{OAo9) z+1r%!xV>Z$pY&aOgAZ1AYaQ{uopto(5PzQd&UnE+kHvRz7ul+}>#6NvedXOxJp3nZ z1N-ZvFNntu)uCwL4ZB4ATAxUx;F30lb%l6&J9Xte2T$W9Q>AWJ#>PHIps}k3yLI|^x%s_Hmd5$}U>p_sN$$v8(Z2F6OlD?e8zUTX<_UY(?5v2g4F+|Z0>+*%3s81 z$xC|}F{?Rn8KNG`R1XJ5)RPLlnHY%wxaKmn$}DP2KsF8K zxC`|R)uk3|{p@#-UIZ@HIO;gdl)#)=adpvwdO@AD-Xp)uv37l-`kPt>BX#OWVG)*a z+&rbcY{YP=bi5IhLo-?Bx@y{QMmL$R^C4!1*Jw#FfAMn)z{RbAas3U#7lo~M#9QZR zH|?#Z0$q$Ae0dY?Fnoips6?+M3j9=H6!G-J&ISmeqC}&}WraKLk}V`2<+v2uNIkCa z#UTvXJSy5kfl9}j>@5mR`dSZ(33TWX@oPWoE>+C|{)y3pFCJge7AjZ&t@GsH#QUO2 zg2TRbkpj_Ke>-gJkr0^s2z~%Wv?37GJ z$o~maPsGR`Gh@IYLo@CfodLRp%Q zwNWRv{mRd~xMGwu(D=yUI{WOpwRnQuf#&7@|K9C?TrO&+y+!KUgIeYDYTEjM`0fL` zz}h$LzayUdMqk4jLtlR;e(CE@2DcZEw&t)ZKkoE@J?m~TOIvDboNioYwBC|*mKpF$%&sxHh=L`xFM*4jN%bh zMilRNJC>XV$?96{6zwVdNyfVY`g|d~S`Tq&sIk;MX$z;+)>Pe362L8C5b@oQwlU>g zf0J0Z5zpe~L$t!yRN_(P+EX!H*A@epmXCHUgqsxaW>q>a6ABFhKZf|0c3}|>JY=TM zK~nP^zbN-9%~U!L6jj7sj!WZODLPP!98a6O1DF1dTcPIzb7ct+`T|Ea@Zp%F9(Pk9 zcL?iEchhMg&M^`TPmwl}K$Rnx-6IDVR z@>{pmT%vjze%!xzT%axj8*1UUTECud6y#{TTenkD;Xm3znXLESR21YmS}i1h>8}qN zJptw~e!-vk`QwoWu`lr7c8Os-czShj;9f=6z#Ft{)xwvoaAWZaK$@VX%50*5TuJ|>gKW!hCcIi?Q(|6TPrSxZaQRv}e{rD}`qoYl=Z zmq-`e0+->P?HDz&5v9r>EHl$4NQIu`p#)QRYHbWWQ^fLq$=J1+IYn zx$|_4q}EqY_ZWVBl;`*Y`55^lerp9rH(u`IR$EB}mSZJuF;|!LM8_-Q@xW!`?rgr= zSd7twi8a&k<6G=0*VGeE^e2GJ7>v0`TRKl#dJ^IR5-NA;1Z~Y>a>5wEC7NR>!xgXNY$#jnR1%!BKRHge<;36iY?3%pK*XY1&w6j_Di;T#_o-LKj+x&DIJ|OOvDv!j7a4W<4NfKC zqZeJd><0z%ug3qctE(C0PvNf}+5M18!+DO5UP8Rs?Aka@1$ZuwYv+EBaE0Sk@GjK{ zncpJ9hrD$2JL08rI%bO-Dd7*J2hYqMpSAhluf1@vFx)VoKmBG8???(% zJH9UJ4_vyr%HHEVqwZ?gVkEg;ju+G0m@CsHBZD7Tc6@?0mr_ZN-`HOYTspJB@xvu~ zga~WbGciJf8t}Z&Ba)?hPo_?E7_$uNL5f8jo zSNeW-M+K?z^h_`yB$&VW^$zm8ci+|8Kp6v-B9#(v12^j4lG;G=qrhb=x5i}}!0zx9 zz@^cPR@asIiEn zCuJ-5H8V&$bshsQV|%A#5}qf2=nlP{N#bJk6ZwlBH#kBcFm~P6&KT`P`x!_i2x6ev zKDE%H8&tr`8m5&jBOXsY&#?hcCZ3e1Hx{BA&sY}LUK_kvnj zEcd7SYy{P8@@7r{Z%IE3T-;4`x@&GDT&2#KPqbC+%lz7lwACXQXnQAeT(l&9hWGjG z2T9ivzt$q&IJKKI;TGUxJ>Onw*eG=|cBO|0b_t#~ld@%eNPK}jslZs2pzS!u* zQ%lE_f=9`p@kqGg%nDS2OmpKupVVCWg)fA3o&Qz=@qTrh8+;SH;XUF#_*?H8hKm2W z2wd8^e5Fn?`~1@c3^J7x^Ry-H!$Nb#hgvh<>2Fk|vT52Z0{8xR%-R8h)Yx*2#Qg@xhcm4<7)R}a^&u6N3{nFJc^OqkJ*5sk3(fuG z?rAJAh07ln$@C9Zgl- zZIx}%@t&{htaJ+Wn4&9P70(V!i3bL0N84YuK0-X@h3-a!{c|hpfSXU+`PEz|_2&T> zN8{FuqdpUJpAo>*7)Lvupn){6)*zk(qmuk_j#EP;tcz0PO|g2>5zRfQD{wKKxXP!6 zVBeZafoSvLA3h+Yr}q;-dPqlD4)KS9OU;ftuFIaK0oMv21CR;D{YA4BIZju10XIJf zabaL;dJAF_Ej&oPe7z3FGn}*!(?F!-lJ6jJnX~1N)$$kWIr@~goINJ)lk;ky z%cO1^r`678wFA&PqAkyHZSlK#|MX@<#V>w4R=5P<(kMHBP@gT1*F@qauPAQcW|>Mn za=o4~>kP~EBqfghg;83Aa4nG9ya1`;unr$#vs@yh6BW}`RPVr zU+$hJp2QDl3b_J&L%b>*r%So~&*RMU%M_2otN_P^XbfChB5{2)2;feaHm_ABXUL&l zKsBxF=&ODPhc?H{Gx5MhTY0ly&?Wy5*zE5)mn%5W@EUy%P= zR)i&Cu=$IB-<7FVyf9vSB!)d0wOsMFA-WmlaT*L)+-(Kks{-a;E0isyKt<2CMzww1 zd(6fiL*Z%QQoSh0d3z7}tK)P?m2$=Tlz2odaR}qW{>|MVjUxPBrDG`kLjyUE_Urnv z7{=!zx9ds~ZQRAaUkDJJ+bFp#=;q0Q?1vDkG)x&qKr*ZuDIK}uwM_}gE_y>+6Ek}Z=)4j zny5=1--xKykpv!g-mD~(%-@4k#xTl&DB*JF($^ud^`Mj(NT zW>8>fmX7&;tie3PkAHLNSWh++uXYTIcY#aGRTgUnB1J#!TjxkP>R6Q{vbY^MnmP%% zbbkI2RTND}7Z}`y|5B(G;LNoi11>F*-bgQr3jI~!N#JH9&7Y(-%cR5>Dk^duDPE_d zgRizT8mPxQO#D)%;_-CoL*h$E>I$}&_}9SYFcve%t&2|*3BMZx?r1ogw4u2ei+Duq zG4?xM*~|S@tS4}3*gVHeW+Q>i>#1pkH4YZPSCdWOOAhOA@qEXG1ESI@nt z2D`H;n>bzD-j>}2T-rEcsQPCAAE6hBr_4dWARIJ*@$aXJUvS(jJPzDUFUMCEe*;I8 zxvfu6B8OmqI1{o`4KLl@(ct!rZtaN|E!Sm#u)iT&U4Wa$dR!}DMj=Q;$?tke`zlx2 zt!T6pD$n5gs9S?RqrocUuh{XS$}Fl#U9S7q1y042=EKfqq@J0qgQS2Cd4P*UN6o?Z zzYETp=D+L|QL5^Qj@^oe>dAY+#fOAgtwuB*{Mg`l{O!1TT}eF0fnTEjoEbIyr|v4_ z6<)D*{6CO>Ac*10@ih&{63=uDs`0>OU<5opz_?giTRojdJpB}|SP<;VT8Rx*^jqe5 zbi;p#%-Iy!o2d(FMlDs;hj;7>KS?*h427*L=AL4@aVyvg;{T|&&8#puUU%U~NJ*4> zj8+2VzXKuobB;Y}_;Ee$xUaRH{AK)wsWV$YD<@UON(m7$fGseKj6O70_`=lEU5Z-Gl+ojKCCH}zETeNZ z?*rt|a}2YyvS6oo4)y!T+;}}>*zl!~W6Ampxb%3;54tEBzu|V%HR`tOzM5_i1ukxf z^92(71UeqL=*fFQCud1LX#o6=rs8g^a%ndMWU=ArQ()<#Rt7IJfAN1IX&}#W^nIHA z<!y3+^b{@FYtkPlF51Y2s ztjBg8O7<;l7x9G8wE`LHmo*XY5vB){CO;9Yz<{ zKE4#1M*JXk6^+()Igj1^3GoO&y$sH*qXK_WPq^cOV8G)XcbC@a@=!=cO_X32@9$zX zY$DzqxHLwdZ?}PC0P$$YGAK8sq|&WVYcHg-H^)c?AIlMa||# zP}C%wKq4W;WU~fEmrb%sRyNsXcLM>@jf#q&R?&+FEv=}uQnfWIDk@b}th8c_ii(Pg z7C%v`Vrwf^wEua{eN00CZ@;e~=gvJdbLPC~%v^C(enu537s6wtYN6ImqoCXLoD5ec zy_njMG&XC2LQ3%L*20%B#YNjD8_^F7o*r(0ywRnUt~sQ6eCl24c0(HvR$2Ft1wJK< zxo(Bb?q34m`}qVyTqx)V+=kPFB*9hP1nCm^ID$h3l;+Ew1#qC=P-Ep>p06PtMDUK4 ziXwh&9LndXO42V9`0BxDQ3tCycVb*7-DGQmco%M>C0fe(qqxP%U`=m*H?zk8JogvCC!rOXl3u zCj|Y&*RuXp^m$p}mG>m5!!a`7w**h2w)|g6`!(0`wCZJ;{npU%Q%2rbY}EE0$4>^q z15^%~&hf*eB7VWx`I9JN>3D&__kJ>&5IijKgupY#9?yt}^Iz8k9KV&hA^mOuoWVf+ z^I>>ETQOQj^%a2QS&1DtUTZ$vGI`WD)D8w%%GN{4-xm~t{RmHSS$00neosu6Yw#Tm zAN~&0bDF65i2~nxH}g-uz)ur+=5@nqh@Had=Lo#$WNyDk$hKw};y27!P8*Ucg*HgS z-I~|11mMU4>otY-fZ$vscOs}w!l$S`T)w5H9bc373s2#tTPH^SEykZR>a|+Gz4F5T z(^<-uA=nRa8mM+zLf4&4tnE20t@T30x(tSw_auoZE9g&fgMnx;dHI>Q%sM{RBPjZP z#4gxCdH8#QPn*xERk7XQ1irE`n_8|qmS6Z*;N_o=Ab=YBiJ)Y0op*o6aOLn60vx#L zVxv=Iqe^*U^R>(v(_~HofoGh<1DYZXaHGJDub5^#xgXvz_$LnQ z@Eq=?N2YxZUw9+*i(Sq1Q?hb~ycKC;rrIaWRv_@rb3BAc9sk2)G1$w3dzo11@Z%39 z0`tyWe_&Z;C=^n`*pWG(f-`Z*OZe``LIAu{$}P5Ep9IQEql8c8jaA}o(md$@E@^YX(+*%9&br^RwH_nrR|uL;?NYF@_=)V)WAaw!F>J(D zdGbpFUvmd5pY?+6O@SA+X40TGiLTu*@V!F2Y9^S`A5<)ks^4Q-)P5oTX&9pc4z9{+ zM$sGY+2zX%E4Q;|StyM7BvyIAwHL4>mO4+`bXJ^9=njhZxtNg}>6bFjLg_3a?X$n( zK~IuF-ze?tvtab_>y-BQO8W))@pt%TGM^e784lmkQ&%qvRsJY16kWqFl=o*$uM6DR zlSKfP3*0C0*bVFpl?tA31%Bv#Uc*%~(4&9ORPOu6HQ7rIm{K_NzR4r*az=1PMjB+jb zyjxxv9$@KjDq%#w;}?w0TIe>Jbka-k6lJ%yfn5wGFmDL9bpLWfvyPD&e-(K4gDlgP zV%`r5JgbJM(IxPI3I0`DBs&2R0&hZ)aN9IOeY3os_E1^y&;0A7JyP^1*d8wyW54`{Cps2{L{!-iH(JAS~oqRTd&*)c1%7xDi^f`JA>$Q+ zPkZ$W!XT1iybo~XO@oTV=Ggg~ujRoMxd%;A;)GxFst&y2dmf62_E>-;CAOxo;10~R zYsME}A@rRhUjtYv!#_h>PuY<}kVCMF_{$^g5V$H0Lu5e@3A}4QYv=9K{@D9@pu2zV7P9dGNA{1k#-Zgo5QWGKdGcV&BVrk)gV_S# zdNjjT-s=*g-$nAYpKPYFR|4Nb5O|@N=}{?ky-MKeOPT+a^j#AXAet%`&66z*xcqMLf}64D&C zfd{c)ORtRtIMTA;AKiv9NV$#4^cLI`B^Tv^VWi&-d27-HX1Rs^7#3zV6jDtTi z5zB>$-wC{R0K+$Nzs6}WLx)cUhuMSue#I23{{uHw`tU@6qi@utU7vQowBIy^x%pc` z9TfPkjbjMX!|06XsCr_BJe}lc@IHBKjlj#_$|4Ar&BK3PMMnjD;3<-$P$S1H0#Da? zWUpZJEo7EX7jhgDclkL3rhfdORp5qpdbpE1$TTuE7vwI5{}UuGgel6ZydV!ESFupGO2^v; z(O$(E=Dk(pJs&9anl1ZI;PqN;emzOUzz0|#ZPpZLIlyrhHfoBt8Q??=iH@6OOiKjM z{+pS2*#du9+UNaYG(l8i2*X%7XPJVu$`8_%|9Vkg*qUN-tCy$m34GEtT|#MEwhn*B`One!Mhlbu@7r^(q5;{l~bwF0Hdq+f9Poo z_i2;>9A}>~VLZVV?^FrA>+InKR|SKM1wLgb%S}W?{yKp#>>5k$GmfRdjJp{QUj&lx zz;0u>aX#2z?07GpKZKw1?Vk`tTi-g9;H{_7U&beB1%~_{o+53^l`%6tiSeno<((a; zGG$irE5_dizH&1!)&Bnc;P~Gl7C6?axejLn9LF@Rk_E3`1aCIAhh8-SZeaLO8V918wlD{tSg&MIxm!5Y1p5-t@B;n|XME`7H{8M-U#>1qg4RdhaklQ;lQ<=~VIeC?a z_7s34T_f9h0xIc0Q`)C%d(J*--%rl=trNjpAn<`hS(mSu)$U|?iII8cSv0aWWjw%? zyfEn*rfZ(OaJ|6C+{R(d&Cu({Q};i?Xl*=^lw3C%)u|@rCt%7 z$;BRSE;x76TM%+;=YakLa1_{jZL4?K!%VEA5j@E?$1u8KFx0-zyr0YMQ%1i-tPyS& z_NW&`EB-o>Fu*_Q7ZdoJnY_qF0`CGiuHHdqumpaazzxldTrcn*vXo#WL@JEu;Q__2 z*SNVQ|F<%;%~J{WRw3X_fp0kBDuQRq1m+4n^B3H{TGWP5;E{*3sC_;DiO(Lw<(t?n zkGDyNWg$L>Ux&bbS1vYBUoyGkI{Eji(^M%P1sLOx002cJHfAZvw4I|N>S6&o+*j=jV1 zp+@9*=H)G75WYa~E_GO5Td{*_SR_yT{f^h7bl(K(CQ~GR6u@!vMVbhoPViwy&pck! zLK$w6z%ypM;X?-^e#89Fk|6`Cpbhdv=Ur>f(Mu<%O!zmdgY4Ux@B?Lvzam^vkE0Bs z^szcfG(@ z4x3K@u9OA3Mc}IoSaq%A)iv$}I4B{w=u?u|S@arwK@%QeYO7i+SlvhPOk=Y~)zyP} zy4ys{O%goE0w+?Cu9dK60~}Xvfr%|a+;<+wZ(IZqNN;GaYg}H~HJg3JL(J&LN`bG= z$R-5kOhDr%!IP!s;C=^i-090W%+{A)g8q#sFDh+jt?nVOw~d#v9T;Q*%Q9 zNpLvY^2YbnvP;?@^(fD{x|JDXr7*-iSUS45ZD$R4ut{DRATRXPunDLZ6EIZZYkpuN zFBrrxoQQlEJQbcI{Z?t7SdqZ@E54InYE^qpPq#=fJ6cbmmKnl%nYjN}e6_r_T@&oP z0FKLDznBGBnf59IP-GNvdk20MU-Z-HzY5h_Fzg+yo>O33AP0SpHk&kLW>0dUM-fpk?}*2uf<1q z@dIPpXKZ^_&H0nk!RAVL2QNtnMcPt)BzTNDJnbG?if^U;L5kOEZIgNY<4mXhjhw;p ziEIrKc<0YKwh>V=G67C9r}4}`(E_HF4gQ_Z!QBX6zN=+OXh6z#3sc=eT!y-3>c z)C4Rg?HAs~3iexOIO7g(pE5RUOtw*8Shb3k*%}dy9)J_`UF&APQ$V5+zILS>9tJp0 zd#(1lg{9IylROU44T_6Dg9kXXRR=u8E2y58(lo|B~@2pXpL)Pr7N_9-f(s_nHOK-YRCvb<**2fp3y(woZW$rf}~j zc#6~5tu4fF<*l1%FgBmO^)&I{R(UJt+`NDm|CYB7S6xZ%h3H25lRTM?S#0FgE$mYO zPWnOfsisT&l>^TtJW5*5Wq8VX_(Z1S`r$mTd4vd7L%R%PfgoC4$;-EE7`Jbt_7JCO zS(-bfedj$q?M>X=xO^y2U>61c1MJAZ4R={Qzm?ZE(!oIc>9f=ggaBI1UPIdPHF<0A z8177^%xYxm56cIQR>>efg!Z^rt3xa_g#vGQiU*e+JcS_YTXbQ8Z+eT}u#NneaU;MX zFi9Dm+OU2hFZ2sASydRkkzRlTf6W1SS=w)ZJexXJ1KL6D;hgq`?t$Jh5(lb&X4P58 zU;HRcom@rd=?`eJPr96okcyc#uFjW|JLKMe1te>&azt;S6 z#pGj#y#WKki&CcECta++995}dETlgnzapqsO2K2LIpfOlsb>Yc`Ar^Zrr6FG2@B*L zHUDXkv@boDl|(Cxm+@&P2iSV9^CxM)@fzSy_^Dl*+tP`c=F%&Nj2ie16LG;8Jo#^# zmd06_8W`1IBzE6#l7vC+0~(nB8#NW)MebRv8NsJ0(H@qkyEXspE`e`e?_T=XWF+fP zVvBdPq!0EAd|Dmz?k-uj?**Rq156)&S;EsNJxeT9Vr01)hD(G(xcrI0t{52@w>@YF^wPX@4+{MP{3bU5kJD5q0L$uG}k*90^%?f6c z@NS{N%Wvl93uMrx07t%=atHH`(&8(m{md2~b5fRXmB90~TOaQNIILdE*s9s5C;5R9 z)54DJ0$-@{(_f{7Eywaew@b&zJdYg=H9ECJYr_GKJFi_qPt`fY3jmJPYSpSwuMzn6ZZ{RT3%p)4 zw%-CA^B>t~+(r16w5DyP$$(RM7UvHl;^dvg4~(wAGF8-0ZxO%|QRa)>u|jl_v@bes zjDbJ7_tJ<6JoX+Nl6~~lFqR8^<1WOX0xF7d+yW0!DqA(p`k278B=Y7r1>_3s0cSfL|s2Zz?>%jx#jxs6^l~&0V-u;ME%ctwNzmCFJRPO}X3v zaO9q>6}-@Di|B5E<7c5)k7vKXpRmWH(te%h9lxaTJCzR1VlTG`g62+KW7(o+R^S4{$X8h5#Jt+PQ)0G=;&&DFSbOh2i@JUIuU^-&)cki){6K zp>%MdjJ7#zKJ_mNW9sfvm^RPv>Fj7U2Br0e9tF)#CQw`)ZMBMCmz*sXOi8Q@5iN$;FR11%J%V4C1r zsQK5$(mqmiIxW4aCeq`+sTl*jUqVM_Kn)K&VdI=?JoJG1KS$7Vp!n5 zb=<*v>K;xu3w+^KClO?!bg+^;Fgi6~;1{6$96|QDYfm2V3u+2qRV`j?&bjv7ibvqz zs0ivKYYC;&i=PNQruoB-ukesJoi&cyrytE@yNkY$c@;cG>FCisub<0XI~FnHNBA$J zN8rXY>_jWG{1oAVQT>|L)>iJscp2b0+Wo)c(JF6iCa@_G5{fDDR%ZB>i`x1?I=K0E zcEi+gzY=)sz1(q3+W%AFu^*Ta%H8=%;0wRuHA>)#Wco;JaMUQZ7| zgtR5-1~`&#t+r7+=#M;uee$*7m4ps%WCb`WI!)roU{E$HPo5f@SNZ@tjYH$q>1n}sHsu?R<*t@U>rB;JMlc0&jansdB{zye5&}f=Y3=XmT~NoG-|&vS zwNXC7UL-g_lJ?nJmhm9L;cAF$zc*i9Il1CTdH>*c_G^asV+6b!w ztm}8mTlWfl%2`th+aclUgD9G(Jt$9GQw>i0yyv@0(5;p&xgvQt3)&<6;BQ!M&J@Dr5*{#i+7`*V(*DpdClCf+9K*Pb z;d#b^{~b>c)ZiA&3p1}{{aY^`-z4xI(+8VhUN<@PbNDx|+(u1#j@!WltiFQZUm*i5 z1UT+`ZglQ?0`Bvr{ffb?Y%7Her)K~jx@PzyXn`hYvu0)!1Rr3mZ118mmiFhN4xsR? zi=F~uHL3Xxz;WDk3K3qI!Y>&w02~QxT1P807na`zyXUDIzXjHp}{Qtx7l#$-Tb}UJc4dWhpVY6Isv01dk0|GC- zp4WY#w0|DpC>;B>t%rX}`+XC60?ImN{+Zi%k$VZ2H{E>n`tftm0WdDlq#aifVuik1 z;29yN>UyEWMFL+f8;zC6@Ob`t8Q?*-y8VXC)MeDyNMqp7*uW^e5SEvBUBx`9c=!r| zZ~LCd+$nQh18}lCOPCAP(mqT0AwJdY)KnI3C~=z7K`0IgqTSNLrmvU@TSdKnB8ZAK zL-j9d|FCuy-En_mYW3^RBh15D#*HBWr-9Njm;pBTPp10)5_#?B6t|xy%uuIZ(_E4^ zX}{^WoGt4V2}}YUBeFwsfpx1)?^?lAui5ARJ88Hl8|g{btcPJ}_!|TdaJ;*(6T+HT zFBFwS0r(s-+8Qau+!F5Qo3u=*407nMR(irptK!O}s zF56O*1lxnsOUA9D;DobY5O`z-%l#f9#w!emFIc9Q6AHz;AIS?_9?2(op-kg5fp08k zs%~NvXnYND9Oy#L!yfQD4|GEvbL9aMfl~#(=a**!{zZndD~G4BatOb$QZ5{t#$e+N zc_IBnrt4~%*(`zkUS_sfDD7X$U_3K#XXT(Ah+NWKm%v+?9$9%$klG6`8J7#T9ea4V zMKauL0glrOE0Bz;ndC2`xml4tM+j3YJKiv{BV2mk8IYJN_bp4&bWReq1Y?J zwL?12&;ry?rM>SI9_T`8f7}~9?JOyKR@W(K030X4`zljpIum+p?J>z3}Fl8Sz z-xy)0qjn)BhQa5^mLeZ&6CeFKvqEF;!HhU;yB#eh+CW>)!}`?IQP}-xoYxb2;&$%9H;g@B@oZ zpx)Ka|A4m$KOBD1HUrOr2RO?;FEIJ~3AO43UX8b6z;CUHX6tYwbbBun~7fe-IOEeiKg3y=Rry4?Q@?vh0k?ihHRX_l^i zR(1-&aY|ju;ebo$GrTxI)Hxguxz>nXJBZeYcEo42N;gH7D zJk9gz0c?PZOP3{x<^h~MG_3^r3V}RUXH0 ze2nS!shi~SVT~Sd2)cvHc{3lqd3?pu?{eq$Jxtrx()l=nue>XZAX|j9a|Pb{04Juh zL}@ou$@v_4x@s{?;25EKgTTL?vXro`kX{l3UvMw4(Q4t6l>kSY@6=TKeE>%iX0BLE z7?c8dhugziXp3}EI*9zh&E1Q!l9 z@Sr?cEVBjfD9eL3xISA>=Jj9412nw!F63i14|=||udd0XmJx8z@D~(#=J(9lD({*Q zc;TfCSLYe7XL!n3aDe@UJaIs~;Q=}^_1dMKzZFE=>RA%hjf2k#JbfK^pd{o?fj526 zq*ohKTYw%8a}9-bY46gO?T_+8>};k)IZw>U_<#r0sh#dP8Q@5{n`MWuP*!6qz{%)n zdwUC{ePw_LsvMVVVSKn6a4DC0@XmhbuF~PDq_mwfnSBlAwXYEP@XRqZx@j_#I|N?- z(IkTJ6a)1jz>x#CYaH;jw9mU|0<~w78pg-e9(G<;84!s45t8BzTlbm1p7Z5#RGW*6oi92FPn0FYNj;ZR4CFd zI;WXX4=^?l{2v;elJ2Vr4tLCJ6{NQao|RwmTvds|uLR!jA~#026l0t!irclNK94T6KUl#RJBpi_oa9pz8 zQrMw<;tp<~GKSB0kM~CPg68Z!%`X_kZ_P3Aw_TR(1%RWX*?)gG!FSW2hVf^Bd{#jhIiFOg^XYc@LmZcpEeiaMxM!hcv@X)Fxyav9A%x?_EOxI$YwD)QM z;^>dLUOk=y|@Nbg#D<`99!c}X6 zXN$m_2C+n~>(Ap)W)Q7THu`N4p=7wRO?99qW`2D8_~6HaX2tQWL9$qKj4!11X4P7- zr0wIS$jag2AC%!7FYxmJoJB3mA@PGh4_(bXM4qmC_GE$%l)+8~INI?2S~#}9k$Y*9 zo7)TNEm$z0^hB1=K;aknYWZs`J}%e z1wQGI+|wTEY4E2^n4a;K)KV2;j|3(|NqDDpNGeO(RR1qK7D}h)3Op~1ms))>_H2QV z`H+`X#mZiQqeLCl;;-#wyLX9||96$xKNv+hyNyo4mD7dfBT{ z{7q@UMfRv8(*ARSZ+w**?Ph`hKzJYrSH`1KEHmhTnPRC8|6phNkm$aAcz`x?>jt)w zTLn=m!6Bol31W*NTJe1WwM=JSXG8_Q_YVvo2x zgwJGQwRQTmKQqxQpiWPNHs~oNZ(;^iHLT|gd`ku!fXZXJuWEs>Y+$&$d8`rOIJs7B zd2f;S2QOfowt)?kv4-12?XxzxN9X|*ku|f|x>uHQ8^Dp8_1d1|-=%|%zu^uBip}_w zQWf{IdfXri><4K-=}8aF2ofu6WPMMkc=nk6(v4P&TP*NQyf+wr+?io41~}5MU)L!F z-``NQ?ou5;nMW;mPT&{zC_I~xtzq;t4fBhc<5GVW`0$;RxV@+s z%!=ZKH_0|&DWfs|P5napK)ybkF7TnBbNhiWW)Wnjz{dd`87529pm_j?b%xJpX%~6> z1yRu?HiXky%#F(gzI_)HZnJa{5%|sTPb7%4VAl(LS23^50%_l^;2$EMS}5xh&f6dl z*8F7}HTB604+0!Ha`)wKmUv&#iC{(9}qm-_quIJ55wU* zRC4#C+Mjt|I>^+b@z(@Vzfr?!K&o!yLxHCc;t(rc#PDAN-?NE5g=&Eh{St{fz}Q50 zpQW%yhJWY41LT)x}#7)QmI1=TM=59>o_9aGVJB#^7aiA`M2gI|>-8_2*zhLZ`&uTqG_^Fn@hPGO| zY1N#>`{k{N-(#gTMc#T)^`f14`$F1xzQ&_c;m@&u<7w>F>Ov+l9M17;w6B8)NRI{2 z^CIR6T^9?Y&6-WWMcS{s`!s5qc?`d>M&M&Eb}QYD0`H+>FyKO^wH}cNdDrp+sTAQ> zfp2?_gM%hnxLpDtKAY{{LeVM5f5q#Nu3d9H3*b1hDU!-A#c@La#(a6uIe-%x44iKK(j24{B$yL)!ZeGllkWbK@R?f7{Iiopc;Oc!=;oSfYv7ivXuDeeRkwnOln6 z^S&V3cNc3p<|o7WR^YMzr*eCt#1GOzp|+IMzUCRP7fD|$6eRv^Rv4%|@^>nlM70G5U{YBN1+I zHlKbd>+E1M*ltAP;r65v2{%NdEoUa8_+L#C{EwzcV9qt(Z4O!2LJ!~ik|*y{bPi|y!z34U%0t( ziMKV_-X4mSbtdD%#^kJcv~7Ofe1E`ez%zeA#E7>vnN-Vn7NOgl|szH zBz52^#J}8a3-Y+F;0z?A0l*$CgrC=_nOy?I@kQ(W+%LR6D;!CN;$E1>vfR$xj>5o_ zoSJ|UZt4tF*7=%qb9g3AM&M$fzbdD3iMjl-4j;VdjYgvJ`Q8R^JTEV=IuYt_DXmlB0u^Q*@yCt}0$#>Q;wR;XG& zZ+3^LAkf?zZ3#5T0_LO7PV7E!yKlG|dpx5IUa;pcU6s$8nXO3P!xc(5%I z2-5(NoWV$Vd8jhl7>txeJ7J1m^QOlyP63sGMo6!QmN-y}MqS(#jNwZ8TH~QaYc$d{ zHxz95cse~E>e{u6^(~l;?a)wri%6?{8um;BHA%+bFw>N*ofS*3^_S{ zEkjPW6H4QN*ZkQHmzU%FCE=tOdPyp_Ng2UVBCw<|&=hKnFN@JUywP}jC_XEgNP4o> zYUbqQ+sr()j>J4Xq)0~sSgNd}F%oV9av{k>O-N@W5n3Eb#zUb%a#@Th)r%iaPz(Vp zz9iRc7H=9c6FMrr$d{iB^i6mQsE_J+2;`$Nlt=)_8rAbEE4=e7s%Fi@RgT4huP!X` zh1)_v)6{npx_f?Bmq~Kt>BLd{J=qcbyVhR{qk@Hj|L!#q83#0=k(U(LR(J#6c~!N( zn&OHoU#;+ywT5$H4QXgKp-3p02$jtCMw>z<(deSN@OPvp6)@&imsQo)RtAFcw#HyA zP)%b{Jb>@>P-sbkRf8zpw0xLwK?aU;I zSmZhykJpA`z_G`BJU~34DbVE4o2JfyCUe8>bAz2A2q0cwqc#=^Cmo8R_b@;xU>N3w z?@lx`-s@+6{lamlBNkxqiuQ1FR%gs>lte=9O(@bKOR>S=bC!VuG>e}YO^cAjGLq9~ zG`51m3pvZb+%3q=v*yQ7j4)R`F&cGAaYLds+}!MM%uOJ_#zSqAKf)&a>WWCMGr6eF}I z-R940=^m1vHmQ5wYra8qEoxYHj0j7n-vU*%F9DoLhFoERi-Pf3bts;Qg&NTaVvnFM z&2Kgj>#kZ|ckv=hy( zuN>1oestZj-Qh8HBhukjbTOK5-+iKa<>rwW!oM9xv~OPqj3_f1pa=hMK6+4jIXS4~ zs>` zP$FK2o-8~BT9QSAk(H*vv&g9g5e~)!p!tcI^jnyk6f}IyaJXfD_I8KCN*~x z#w~Z6U%_jY+hEMCEvpHjea>eCT@CI4J*b@d{QDb4_r2{ z5!Bs3uUYVP77mYam7^U7UE5X$Y=}-J%_E%C6sXV7p25u9*tmpAQdLz*WU;A2vgR+0 zQ$yHFz*#TPX{TXCJ6V0@cY@93^`S23M%zM-?Mcwb4D`=vq4)AH$G;pjaQl7ADR=vb zvdThPqGk+C4dOO0d-{Q43L|>?wM&CBXm9p=W`61-pivWqPYKZ%ryc*{z{rs~eE*J%QJdM%Vvbn*;B5+E}jArtU1E7|{Q4SC85spjz~lnIlGa3CZ^ZiP?K%Xa{Z|0r=-ej z{egzEvNDI41Yr#LUPKT}wAC^oe+FvG{PX6NmCEFtywhhS;Z}``0lo2PB2hhwgVo$l zkD?=Rax^t!Pic+nWXKfdd!eP}Ailuxw^c zu)PHpxcR`dGe^?uQ8W!+H~1R~v6r7bJD)XL_9FNeNiY$OLugGz$&X9ya$#L@CB-kz z(yc##InD@}o1ACjCiJvHi*yv$`j}=~pruIfoU~}^aXQ(UN;E@nFwd;o5;z%#?+>;a zeWx|5{GJ?kuQHCQYcjunEZsc!_ZdUr9aPLJHmeDAr!BeU#C&#?-D&_?kKI4=*?9oV zv-5}$V36C*b^9lpH~juoqE$f~!rdCX5!S}(DTCO^>SM})v;&K^Hy#3QAX2SlO~tS? zDj@1fEE3)-2}3F-6o*iQoS_+=GdhMS)f(g&!ZXAC`l&J9j*%)ElQ25yk64r^V+@Pcw>ZvAzoS!1zt+7$-#BVwRz!BBf1yf zU)K*=h!Q825Gr?&i8=eZ3#S6~2-6_!%CG7uG;e%v^f+kESr(Wh3P&wO=ob=WK>*ll z{%7Af^T4hFDexHxSRe}<#(&w=z(j>7r_k~|nI*s=NC-_4G)dZUBmBDc{R?PzKBR@W6HH&wJ317`=cG@kN6Et(*| z{O!5PC&A><-@^!0%NCeJo*zb*F{i+s`25ULXxS%I@yP5v0R@so0j)Vm6Nek)A>6>M zfEtX&VE|)#mXgFtIF@Txe|buG_RV#f=Bv+7W-YnQKpVl)FcJufqu7WtA}R-_d~z6N z6ZpF9T?T^fO~9WDK>$ONw)j{ z=(E$zXDvxKu_49jbzF?HMPXCl<*;+ z#+$NcZq2xlJgXG|gQ=%*p`J2~#qG@)tg+(RnZF%)I! zQ_5&a_b#sh=NGuxlM`xc31MOz%;x-RPj17T8oEZ?jWRIJ!s^q zDjf}YKuHfsERskU)?~%jI${qHXmTi2SV@^0rltxo%B>|w3#6r0teAnbH(rR^V|LO- z@tNe_tcjD;aWu@?+_`n`sX#WbW_vlwnOmT2FyweV=9m|9amaj_8WTo}*UVl^FgvV1aj!MHt5oZdMdZf_Q%9DlxT7U@FsGveQf37xQ%%Ckj za%7wd7liV#$#i6ulxs1l-L=JPE)loAT(kS70vxwPPL%^|1$Vtd^5WVmPoTJJzPR|d z%vfxi-9V0(GIi}sFv&8v6Vfth?MXpoHz=+KdC_)tF6j#okS0e;KZEWX9YoZOXQ!xwn6K%WZ&uz3bD6oQgU>~gP3DR#4rH5%d z&MAT9-}I%XaU5#dcr_`$A=WWtkL8)|+s?yv?QN-TGvUuo&~z75yv-4++KvI$2mS`2 z)4UDl6Fp33m5jl3He#%R%ppuZWe?F}Lp|9;|5mGG8O4Uf1Ag%*L$DnaZVSq+YC|n(wr9=ea0Qh2yq9Sk%M#-} zCB~$&)oZk?MJtM8+A9x3Pizz_E$h!EPsVzXE9k&pHZHRB_$k7z47s zDeyByeQ+jbdR=W;VV<=mA4g|Jl~NC0D!c9YE;&H>1b?3IQQ zF$$Pui}~&!rk)QJn;T5V!<{OqOB8}ka3fktkwd81h_=^;LQOTH7Wl8(@#s?IFEi~G za`K#6eQzUHdSF}~i$=nY%L47N1sqVR9kmSh^0T{-LeR$sm<)FY=|9EUwt42g8mK|( z+p#V2(l{J}feIION3O0NQjwM`=clZ+O1cwnObx?~K@WjHcqh1n7^Dle3IA-V>tND{ zt?W#G!o2R41ytM7z&ZfJ^Rn5nO~CpQjF;pc%!98?)SMibHygKH9kuJn*40vUv|uX9 ziL!7xI?eG!D9{#6T2%*@lFPGJ+KNv)&cuyhcolJS?0`&ES`MCga}ah)18t#XYgD%6 zV#~UR9FsPYwwOM`EvBhs>qeMMw~rizofmL~6>K+uwtaL7KrFi{+O4#<*j1f^28MPZ zT?{S?G&`R|>=cC9X96J~M7 zIgU71+zG*r5VR2Hpg)#mtCv}I{QnjP_yji!pS!j0WKxpLb){60$7;zRT!KTU{Zo_~ z>?TN#V_znL8#v}i2_JaJ6=m_dHsUVA< z?PW4S8B}SgSGZy;5%MUZKQgi<6~2JW$TG9cu*wm5Lo$dP$YtKZoU-|W_Rvy`M&e5X zO6I+SCCqw*|K!UsFa6UA3t=98vLE&ja|gz{00-_=_EsX@Yjoo7Lo?(e0uf63@djA~ zRy(1)y(BkauKv?>+Np(bKa9ywbNrtNrkX37VT*$-z3l{B`CK3(bPpqQr&>{ZeU-IK zJXjwRXo7?+ubRF0!f*LKvW3=;#VDnrSh5wgofr`RbdS+w4tjOsDS*GvqA*Hm38sQ} z^Q>3Tpak3Wpn1uw7vj20IupYud`i~hdKpu|eCXBuOnAj@@HvR`njgJ7 zYP6awR<_Npa;Z`CyI0T0Z4$L*;Iu1{2|U&O>gka!@Z6F-SOHr$mTTgsPs(y>+_6gU z3_r=6xp>Eks7CD>dZ7R(4*qL|_i+PQW(A&CQwaO@FV8M8Z`&~zr{{;b7I%47Z6QDR zWV<+AI|1mIHzqsvj3rh?HJZWK%DwoG?A$n)frll$Bh{Tphy}go#@D7#w2Qca zA~9;}g$!;p?yJlRK}Ij)H9vf9d>!-${WxO@3ME8jvKwf1wU~z{Zd+@1-kPlKiz?a| z0o5@462Q(Xfp>1z9uH$jUhOLhD+P&Ii}+u1V&*x29$f(VCCE~%!nhtuR%OA=aG+7*2i3J+8eoKtGcI8?9E zJZx^14HZ}jh}R0eOQ0IEBNEDQHt+e%bQ*(R#-sQhl4uQRo2qLn{KdX9G*K81iLz3@ zrd}XJ3PUKSS=yQq_yY;5W1=yZgi}`StF?g!QL3X5Qu)eS0Lgp^Ln#JR0R_!6X*b=- zATR?r;SRsz8;7r&qIaSC&C2$I+ZLuu63X{N5B?lVI9M`}YxRv8GTQU>=aEH&fQH-| z7e838nynIXa}w*%LnVvfX zMLpQOC()q_cx-0iLUuyo@^Awf!9i^|E-%C-Tyxfa=ZC%%j-mOQ6+2HO#k-hh>~i&x zU(EPU+O6^Dl3(tO#h@QhLQn|FjM=BxLId*Wl6awgZjZLXDp;PEAM<6DaMU;ocZMvuEe|r~$R$ly=11XCWg6!AwE#wH*a}MmjSY?Qfcc-D6DGrBE@mbsBMoDDQ#79JhSqYl7G<8Y%CJZ3M8HGU96bl` zB%zESTnC3*@E1yD;bL;^uYw9d@@K6==eihpS4tRAO%Ol&^ZB*qIYbfv4B}SX>SFd@ zIYhPoxllRQ6mCrBcq73?0@v24sV%OKhnJ8!S%x~G5j`W?1{vq{z+trI9>0f*g4kIy z&DV2qh@eUq(f$Inv+U@?>N&NAlW9t!h8ycXk#=CvlxG*cl zp$w!t8vDovQV%8Q_(G{LC@3fuZi#S3j6cYQN+_6ACs+&KNnNMZx#4m+uwU9YP*=Cy}PmUTi+ z3-HA_v*?XeQsozc-_#BpSCAqE7pgVXxF`Ycx4Z7kO4mDhj2zMbuG?8yX+og#Xj%1% zrNF_16qPF{?2;VEdf^f~$f!rPpwuKgL({GG&8sO3w1kqLKqEv6oSLRTo$gr*c-6L- zGnU~-X})8lw0>5&v)Yqq@0A7sfcvEwJHc_9JePgvBSun=P4!P9s!T)1&KCi&yasZ7 zrmB5Y5T4?T)NvnW%(zkl%JnfZ(DTi3v*(SW=qW%s8bmhaqoF)PmWPDL*52p|fSb!=ef=i~c*mEi$?rn)a`roVZ@`D%fbeep#r zi%UfBQlGN_M~q=vS1L=vR^8A3);EgGhGUuStuwX2JS#Eils+)edh>KFWv~f=o4n3c zvCFp#VEs}-Zdq+YcE6_A{2zG>XnoC_=VN4Pn(<_m&SD@5x&&iwFA^56Ol z(TEIoo{$cGLGqPPb~poa&6rUlf?h_AQ`;JD#(gmY_zPOxx(f!9=I#C{E$u|d){$B? z%jf8wS+>-RUYo?-1S$80mV=U=vRyuR5n6wZ4QB)y2`&)K%q7( zMN7*$RhnJoZ$LJVvLLV!cVfOGzJsfdkj1c096(JaR`{9^?z-?Ipq%qf*WQTYDy7m_W?MdePe;$iRc+A~zog9QleUzP2`y(Et;l;2I z5jEOz9g8(r$-(wIOw;`LTN4*RFYI5>jp9ZW70JXQlL)4Yko9sRnfslpj=fqstOZ&~ zwxsdD%+YV3f&1TZFfwfAfN|?K0Od|6nwP$PK?I&Uqb@ui#~rw8%WzHLY=*~uG6Sm4 zpk7Xd4+1eYWIb`I4zb{t%9QQ^l-hQG4kvbyGhJ~L@Sg2mIf7nsgk75%N-EsCTX+X* z-)QHSJt7OI?eW**ft3{2g9qD-+nfBsI8}J@%#}t5W9TedcRcKSK*}!AvPlI7F&I14 zSgxW@m(sLL!cA=GVcz1_7bta{w zPRna{y>k-pa@od6846i-R}e_0PF`bCdj#yK`O8;MHMhP~j~wTkTuG(8+vhlWG(;6N zhf48S^S8VnIwK5cLuewz{k@K2(W7?7TI4J^3e8|#{yfsgWWoMxpoH={HxzFP_4fQ+ zB@VzHMY|`S1E>iniYXOxSY>!LB(%%q4=L)kgFc9HN{DKBxBgGv1f*NBMO7!IP zhMFRhk@6oZp=aq)h-E!oQ~?R%XI#r+E%AfHZFHbjq|N05`|{RC&YRgz zf+yQ5>BVKl@ujQ_A-LXHjg6LBWv|Iir)-H+1a&p#a)@v+K&~8!rdb4(GSapo>R}%O z`V_*!0xdR5D{6g#>UmJ6Ky~8I#51oa+X@KKav*C*1kv;wu8aA^yX02+3#rD^pGP$n zR*c6>PX%w~bBn!!xup~m`}1fgM0U6xYwEJULg`-q93FthOHgu}VOhYsnKkd845#(S zqfWGk$d$P)*voV17zA=AA6abmWUKo>V2F?*7}34+y1F5Y0E6=7a!QHsP}}o%L~k9_ z=Q1hoRa`r#@8lL9h8u5Q`u;%k%R@uW-@G?=w3Pr2TfQTtmFV^WbHd>Q^N06dr|n`$ z^tG6;zCUvk4A!6DM)rvAB(Rh*Tn1AaZGnVhd(zC@a|s@jfSq+~U)>+%v|V;%6Ig?j z@vt_jHDq!K!L?gB`n+0WdCp?CgP~YBX!Q&II7s4lNB)bM#p4PobzVWa1(49=oazi# zMfto#X{Z0)meWG7i3f9h@4XF(_2dX^z*|#kG^b?fuzD_or1*yv8ruacrzZ#FKu*Zt z1Wje1W8p6!fX&HWCk5c=JaUjye}4MYc^wF05-Vku ztPzmt50h}X4#bF<%*5Egx~>FbR8%{Tm4cumYLGbO7*${N6MF=2Wy;M z39J^|S?_9VZ6*E|L%QZbYf)V@uYNwLUcAsn)b89e=kXO#Nz4T^NKLx8k>rjbXNY4Z z(aekw#-0x&wzZ&LhORtBi+vSyN+y9hJ-@@8_Ce+7imK9p&uH%B@&vEB^n>x2amBA3 zM0IkKX06;hK&iwdhKwK;biYW}gZ?b@nGbHoEpJ;N<4RjGH4C;s7?Z3WT@pfbK&v9| z6gP4J=mHl&>V=alNGPxDw+m;_fj+>T&|cET{BFBcb|2A-B7$K!(Sd*1ZNK@8mlS0Fre-gQuMG- z!!rqCkB^m>Yqo@T+6SjVp=5va(T`3ULzrRfyZ|?}RGtyurG_7VBnKPFxrK2@@Njsj z)2bG7Y)U(GxT5FeNFf}*&V`}C<_C|=;W1c#W-nGp6O3$r44-`)xcALryg0HqNNHy% z;n;f??!Y=w;#nr)w1Sv9@Z*!vk#um3J7`ogulPuog4!#?BKlA>QxKhb!?9MlhXnZv zault6_@khc*9anC))f6IS+&Sq{8(=HbN%biGaveRES_pszP9D$iEkzQPT&KdKA!eO zp{>eE;Jr0%aO#9E+<_F_;L|QS$;|kqUuGZW8+5}37sx&Gs&5dIfy5DZohu-JK&M-A z=vd*%=0_&)2bZ7V(P$IslSpkC@5hjbc!-YAdcoFU9}I?`UYWl-P_2shIN3M9=6r~| z#onoHAwExM9jBwGj;PdD9=M|B;MXLrkHpBO{T!+Iy~-1D+HkK?m$g$pax*{o!k)v_f5j$v5tNFN0q zj$;t!P2Y{^?tvq_a0KFfk0(&k4!0WGDqG?kNS6sa{FfNiYcBrlaFiE+4%e`N>kR+u zQ%AXorWjj_KdqcIDn4{xZC4I*d{j$p+ab(5k**V_8*_vk2|06i>t8Rxa>qUbEs&H) z;VQxp@hZZ>`=B}%rUA)v^2Nz1#DaM~;pnW1RnCdysJ&BZx|E;A5{}&f9JTWWCokNu7)mT!W~ph-vnF-zHQ<8H zoaq?SYZoy2gQQHAKvAUP=4hyCh&^^n_j+gV)#=Q0Pj+jo!CALQ*cr2qP`6vm=mMi&fzmeu$wW>t8hR+QGW0&axlg3-DhIUMTT zZDu(FdPs284)Oz)mx)kLQ!JSXn2&sxi6zp&0rt&Wz`+i+qAdnXm+N*55LVtxyrnJ^ zZ}mluV;?`}nt5pQ(`RLE@YD|GWYO%}a25yKgkcewG-CAt)oP7NB(W4ws{$cWQoQp= z83~FZ4_;S)A{Gr|VH{0Qs|6ujOU=8BAGl;hN(gBW00RcR8o;{Kw4npyVJKP+K#lE^ z5HDUnE#(mdTEb6*;FP%KkWw`=v4!Zq`B)(+eqAf5I83VP3W(ZM&?JX9V4qPbw``6f zakiW=o6(5k=7%ceb^B|F^*&+=ml5wTmd#}Cv-E?b)cevg3}i={nO{(K zkhaT0)Szs00`6!X> zGdaBk)*kFmL3>98O8&|~onDm6DV^ub^A(p=mgP9J=?bMk-xh3TRFvwn<%(6c+P|6C z&bK{M+Qu?!O0&6_BV{Q!#$kz);tBPdLm@)HePlFv>w>FVXkCwN++-!uh3yA%YQA~( z7bB^)eL_r+iPhW{$DmtIp+4lb6wDi>a(gs-l=8A&Ip={D&S6Bas~cmcUL4-N^}f1( zc(rBkdS{5zw-04Wz(bU6y`UzQ>bP(aMDn8Bgk-3z6b zLaAtV?%xiaRj|_+O`&^GCBSKpk_+QBTzcnhi0HlDWMFjIU#&h5W!^)vg=@6nmBOgS z7SI#6ldeK&Shx$ngezR2q{ZCxC0%sfs~iSaj_z58!D0Y~2QRF2I4)W?9C@;GjJV8Z z@Sh{PyWj>dbL@ct?z8$mvg-%wGjheT_T>L?k2#F)iUZ^Eei%{rsO?q!KnhC*Bw@HY z7MG3M*~irY!9xf7I5#Zrbl)197{y*KJ&@!Shra-Y84mI;qrXCpnCYPN8O|#s*(^@N z+xj^R!aB#6Q&kubc_gfvH2->FE>2gL3lCYTygj8c>;-jax79IsuX)zrMxp%lUPN2a z9JU(cU0208upa3>NPO^FM6K@FnPG%*-f=-Z7-76prmm{OZ2g;Ec*!JIirb;cT?$o| zdZ|h;UV>h?f#78zs?5ewnuqs#X+_*Vb+s2^@`JCgF^84)R5Bx0f(nRvl|)x?g$>F% zi3;8rkEuhKL^(W9co*YA^XjjMn^(O$j4lT>_kM7!neo-&R(KCCF6WdURbVLP;0nO_ z_yLdHlTEvhYLv7%O0s#F{Aw9ovl&uXr+LkBU!93;Alqhys#og7m2+}OTI}C=`?_O} zaP@tYJ&$-fe|y58>MavIV9oHbV2I&Sba31@q*d$Ns>XGDj9y+-+-_d>)v-teo83`F z?L%jA=MCn5_*WzG8@{n&r=-*rk^^synI7rC(K& zysDxVy!M*tXb&4*dQ9okwgcTwgO?=KRKZns9K~>r;e{QcxVo>Fd&is;ofOf^*0id% zqj8&K_g7=__^oC*DdB?GVITiBB{$WfCB|A(*=kV! z!Vwebpk}aa;l;0ukuUst5iz>45M!4f$8TRgiWk_> zg~i!*a8FKcZCPF*$J$xTg-%kCd*!3Ia7SbzB~lYA*yo)sT5mGBu0*-R_fcLStPuHA zu1zA^1c1p{85brN*^%0^3(a{47Y5+5%l1>3j(8A!R?FcR5))cJ*Pr7$+3!p=a3)gS z;sp0*5VgUZX{5!{Z}(QZ(s7nw<9^{C&1hJWEF8(Cf>OvDAZ;3eQ7rhYK`c%9u zoDO$K8vAqmNIcnTNb*GRT_^$Z7gAGFavX?R*X~<)Cn>3SJJOPf0zB|pq1wgH4-3Ik zNTP?1emJZgmp&sA5qP=#6GgJW>9{RNNt`3JX5){pO>q)J8T=9kCJvm=P49J-YI{$4 zWo-a2o4^6ktSp`4aB1vKCy?i!Z%)CgBM0wWVq|?(g#3%QzRAYrR7Q|*m(Ay7EN|U9 zLIYK^CS&Mz7DgO0Uj<)g26$2D^uF>Hi0`P@GSB$?@i+#XyE&u8Y~r86`Zk}OlHQVU zZILN9#qb7}oGQkVU@EiDelN>AfHD6BlHUsSgjbhp@a&=dAngB7Q^;}+cC8DxE3i#VwI z+f#?QB1()c%_ZO7iP;8!HtAp*uJh_D``RkE7sy|`qI@r3!E2J>a z=P;~KpcHhdS0yn7d*}Orv9|hzoY1vsi zsmHQl^Ox(gZx&2iXJ8GrPlR|m6~#xT9r28P&s|QAdG?->-G4j2ZoE1AUri~i2UWc8 zR}#+j(Qln`iAf(mg0=B%RjI(uDwHn3EQ2l$d1bDooUL$)_CT}daEl#h)0ejBiPei7 zbA>ZI_z9R%SQW$t3HZGTb%={zvHTN`j=?|z&%j3addP6R`LAp7`*1-Zrn+Yn|BF;k zkW~erB>6A1w^=`E?UqDRK^9jfN_?-c&hIzN97k=+p$jbIycw?E__Fmb$$vX3%pYa{*VRa%|&*d8#=5|8P1l&dN3HdNy=I<<;xV%ClhFqp!yDWUS^P;g{m9s4`yrS50zQfoF#RK z8WY6Y_GV84d$zBhQBkHMv`Ciw#vC-cKxrIcATSGxS)8>j{sQ3~ir$EGP+sg?G|{az z-}&xkngx{`xawFqX-XoYA%@OD&gOjT6CXewnl~u2x|ASt{f)N_ntu&)PDucZ~q;f;utdM6-WL|TxTAgXNlZ| zcEZA>+MWj?==*zlOg5`L*S?L0ydxMV<6Q0`vnu3OhoQap7ccM_9)9rxnNZ~dSxopy zFkMR$wlc#~l~2fZ?vf!%LQyS;EmMvXvfe>l3d!iaRf-*2bypVit4>FiL!;r?9jRof zb!Q4|@>mY4I)?+_2$$gUp#3?iL|>nAB1e^dClXNdV~Ex&CU!Hs2U4+M{aqYy?+Ewe zdVfwMx$Q7Z^S$q<;!#sf_p}hu71fYJi$NNIzcEV={1JH6(Y;<{=ruEc7>Bos*}(}+ zhH~*lLI&HDq4?^rV>Rfa2wW#sf8L3;0PFm3I1K?acgl0UD_{NV@s7L4U} zSxlQp`yl8qkk^j_Z4=RXt2cGtJBi-RpC}~y^uExXN0mz_EY8+#Nnn|OrPBV&h5oj1>Pk-xFanOZsbXp z!L>Kmr-?xXp~%AVrC5mY$g5XfcwC0vc57%|&>3L%@aMw0>T>7`KA)Mr(>I9^aN6g( zwL%kpZ;-GdH#C`lJ4_i&h^vS*912UZB3_$C1%WVD@`!9!hpH&ZI)LE9T6pKx@)u+* zCxDlZcm|XW9zD##%PMUr8~4TGdl<9r4`S5!^+61AP3d5le8|Z)1dmj4o0&h}f&Al0 z+E`_dqPz?Fn4vPKBxNMsN4l+nK2B}4wZqkhO9Iws*wkt{OpnAZ1LT{|$PwnlKT^c! zFC>r9J!bisjkOX~#_rE;b$*dV7X1h{v9^Jt;q=9qzG%v}<%A7=47lx+{3x2e%20BO z0+!O!wBjJkch%@^Tk+s|0;PDC=aA&P=ErQ|<^Gjecen1N6yZ%6gzT!;)) zYQLg5-*o}8+Y<$`OflAc`>3=MUh*%{n~(!dz-|sP#t-Z{;vmLiXDX#EK&A5fOc4-k zr=0wx_{W)GplQJElT}p4gc&<)&MFr|=2=~m&W58GpE?YylcqIXV(Io>91bAO%e^ix zOqQ;3g$Vg{`6PBf*=*4E-2k3%u6_i7VuUW5~a#N>kik_oHBBtXc~QIn%Rc9MIUxpPB<#C6pxM~_N7 z8E;3lf)k~1j&w;6I8cwmX_2es8;;7ScSt-8(&=5&mxolIN;$F}6hD-CtLMNsY~TYn zP$8hIoR922z?T?kK1!N=Sa5VCak439ZPsCQ2lgP{gQMhld(1wd1qFqDG}SR0@LvMg<%mO0blPmeNrXqau4$ ziov2Ct6~r?Mv6EnrBP08MASjOHdtz-qK%5)XsO=y_^l-KJ9}|Im*V%o)^8qbt=Vg5 zXJ=Q((F~1w-kPswY7WUq{_52)b&$$$YKpI9a^C7kO66y@<|~~1`kkC1rts?Tf^G3` z(dDDFGH1lNs+a08(eyVE=9cL@hFzQPU%fCa7x8frPkYTNPV3Y&&k%0`I`#bJ%Mz8n z=JMTG;-?^IZC?@BIZ=tPxAzi)fDTa0Pi@R?e^d!-F z%QaLTWO0g{cZ*}GE!PnjsOk8-JC5IP^Qqf5)ZY~nzbd7kx_=_xyYwRQ7gXPT?&-(B zNxi@%uWotgS8qa6xcUSm^$pPa=Ukp>`FMgzU(Lm06nFgri+YUUj4gXxb>fw=t?Ta?mh-c+Jmf6hJbv58smmV%$RBlzZ?eqy z|Kc$s?~nN11pEOj^FHU*u$!HvYNj@w>&M^qJKW`$^*6pOKK<-hzVbNn%RT39?%cMa zem=FntJg30>nD>qe>vsWUxcsjFsgs;OfMyI*U!a|+t(jJM>S75@)Z3o?&_Y4pBx=p z{Ur>&UhrF@XI}WaH=TXF_>+b5Cu-{D5AlZ(k8(~I??^fC>?72lPLVgN^6XH9af1G? zYyE4Vc`KWFMu-o0KFV4D^PS5#sGsmm^{Rs!Y_o}!<0<}FlzPC+XZHH1Qmx;f)d;EM zRPyysSH7~KzA)>_q&}`##4dk+wMtNLJHyPAkK?DFwf50nVhbz2jGuRE^-iqzSI^)4 z*+Vwe+r-RT7T+44Z$5>2*BMI_wz3Z7Ip9+*s_!V0--+NgX)z4DzNJk6&C$w@eB~B@ zc3BVE(Pul)6|b;j&Y3S&%a;MwtNVDtQ*~H-x0L$ds~ac3(&`ugUo_vpD#C6TRngDcLgsyz9ru$r{4fk*|Lb|xjNADk!il%pK!GLnakRZHd}M?J5;9$^J-FpK-PJo0M`{1ZEiduk@J)Jm+!IBl6!y?n)*%C;=4;`>DqN-nO&QiQsTZYFXtI**{UV5OkJ+K<+sM_yL$1t2+KdK zEZ)HJkl-BsV_%a@T3RHlRF3&C6Np@s-Gpz}nxF#Rn#=exM<~46VHsy!Oha zxb-+2yq9nJmE`IA8B}=_^QmVq+b>@-l0PT*PF?<`C;c+L{7ZV9eetLC)VGrKF-K|^ z;Jdo@KS*%G(=UAg)4un(O@A-_eel}5AlF_r!`xHb_tl^8G=IHQU(EV_t89490uXr;8c5Gq-%b#lL z4+>GQTd2FScEb9ZUO#R5wPCC82gGmui@z$hxsUjJH=7^XYvX|AY%#*C-}05e`TeRR zUUrmvfltmna|xAKBC216_amPOI`HuQ$^Sm7! z`)yvmW5eCpee?Q#HXbhjd&g#d?~QGnpW41r+Z^oJ*e?II|7L%G@t3nt+IPd<+`0FL zx7pfHvddAxIofyQ;N^+#v8Oyo`Tus)*R1kHlkJ%m!Rr`v2SL`GHOI-1Rn>TM4P3kg7UE=B@#6fGz zgYLj3?kgHkWaCF3Aa2=g?~U#II5=T>Tb<3f?Y(h;z6qkgx9q=dGnU7>b-U{!|RT;z95wxL zTg7qqSer*`c(!eBJ3yTNbRQA>DY;ahe4xm_PF~k7azcySuBPW+n?rf#Vt#L14!oY) zyKgvZZa!@3YN=t(h;iRzSx_BT{}WSC-L;`u;riSTSq`e2=&O0LHswXjm+!mr*tPqr z=C(N4UYnniPYp36cWmA&&-i;{9_w{zW{6mza{a86xm-t9mEt=_hQ@T z@8nviRsTczjJitBClRV{u=>~PnrX49g80`yVj74Z`^#Cs*XEDqF>c(>Dci2}#8sJe zS1!@j|HQ$>MQ+=CvTP?tZik-Va?U?gKY4cF{NwE#58J#&9%U$>hvqcJZQfr$chxCv z(@&o3{-!G?< zSiA=yG|%|8rwvycosg~cAcxQUp1Yho<(1i7j~%ls;ckPz8g>2{Ooo;+I#FNo~rWe zpm?;2b^H`L+L(6YiMnm`WO+ZuXz$n@i|ZG2YTtdu(Srj->1%Qx>RX5*T^$_-HIdcT zn&Zx|1I1llK;Njxj)z@$_DbCp;246jb z#e~|vx$^+=FEe}9L9jB!=&a6imnVR@>)xg(mr3P3_RyF4BKagU=cb3_A>zJ?8T;w& z;-;wStk%1E&~1}n%62R_N_euVTQ6?P9=nULkMhgoBjnc}wG_AOXMW{Ct6Q}CQgYB{ zc%Ybr>g%SOreev8{g52Go}78+1TZ;8lf4qTZ;*HEzxQ_>PyBaX{QuYPBi5AItG)ie z#s3li$ok*xQs2E&f7k)KzihAj@3ySh;!VlU?%UM=aoXqXss5uLZ>r-j3p>x%g$8wS z&(rRczX0AO@4*A|7o4wiT1(f*cdocV7uw5$KGUPS+Cy^psc%pXBJvpRJLFfvGxAY# zccy{{R5<3V`T#k(bEozZ`S@Epry!rtbo(*+nLpB=OsH@p3MKjBKh_&sJIya^KoFm zQV=WQ|LG0^dE?vqR=3C(^*5?J(I)o~(H@d7o+4b%zlaLq;krYId<2il4}Pj{-zD$C zd*t`QQ{igX5@T^6gL4?FZy%!gKPS@Zrk!`tyAqG+GtZt-JzWkUsz) zlZQv>oC)~|J|z$DN%UCGs4)A24w{n(w`yOIp9Xi%tv>1Qhr8sxFX|jGp+d9Jg&KMN zHtlutA>1dA@6i|5BtPv-Iwyc9X6%P3w5Y?~@HV;gWgQff*WeMk5ARexak?nP)q?Xq zc#nLJD@(~A_?SMSKKbDv*FGS3z9a9Dn14AH&P33V{91TH?x`Th8I#|4tv>LC{9xov zrOWwmhM<9<8Fgsip@Zh+hyIIp=e+8qEB~(^dzU=@voqDI^446fzXFB&T0yp4+^d5c zh>{t`#-N3# zlIpFy1cj73q`RG^Ze2z``Gr2ffc*Tsb^DzBM)=Tpf-TYL+q%QZ6yUW|dqLiXPsnQz z=o2c*gSH3Wq;bcbJne;0y9>yKe8EU%jKX9UoK&_Q*SpH%U*N8Wqlb ziYhpD^83Xf-j@F~$Xn0U?vslTtx@fpdj=l^Lqqwab^cpu&)Kkf*9fRy|`TtJ^Z3UvF7d?+qJt-k>k9td@ZA-TJs z9?KDV`>VQrL4NR^+Q;PMyR}cwr~QBTo4Qa^hXH&_e$`#N{hWM+6J3x$c#m%HyxB}r z{rqvp-_ZqkSx|Gwx#(W)9{J%v&|V`y9$qIuaH`w;+9UD^$4xp^2!5nH#N?O3yX5A;J#us4K6#1*XWCc$|LkY_zys<~!gKat z==MYMZNJuDkPmR+amB^>Z%5FiQgECQUXqvaDY-fDoP7K+J;V!g=PzRY_1}4mnT>kV z?UV)ak4rv>d*tVzqTAQVk2zU;o%|%U_l2wZZ=QftoN1Ff%+Vnr_al9P7I|NM0J8k2 zO@7Pi+M|{0^|!!*JF9{UxcyY!Atv{5fG)W?aF5&^I3hfJUjyjCU3o7d!4)uZ;*#@pS<&scd8R=!k7F1 z7##xY(1o|iQ+S)a4-d&RcvSVo8KBUq7MvU&lMmrt@)5j8UcgiGv2rp0`c#;pLq=Z0 z2jnw&PCkbZ$(=Xop&Ut<^WQ8#4~2p{)ZkA>gY zUHF2$2X`*4PU=3~CC}cF>htepuz+lTI40XO+JN(JSA_y`{X`6Te^P!I877=%YuCVIZgo2$y@Ltc^f_=58(xQl%O!C zLI*w}pZ%4dbS3%W@75cNDfww1)IKA>?=tPlf(rF_>4Ni@)!Ey8zjl}WflRwc{@~lS z*DUU9U+w>|MTa(Z2;QZyxI^yUst*v8=QnBZlHY%W_Fl!s_($05rImu%|9?Su=#!VX zY0t=S!GUw~gA3h$NPdYtAvym>RA_ufcPPj&!WE1yJ|+JYa-55*L)pR|b%m?>Z=QhW ziaqLJuDC{SuDC&NuGlA6S1c~LxpKY!%oPW#f?R!$x#E_^BXV=aJ@W7}J%>{A=$nbY z)qN`D-_@Rx*S?`WC(rKDJ|sWwZtWxTo$w-|!bvEMEj}e5;)I;Ps*Z6RS6m~neM_HE z9lqTEUxlCsb(r9UeDVkfXtIA(A0Qw%ceGV?@%kSQ999dCxup@gxuqR)b4z1#b4R;d zx|n}`Dwtb3BzG^@lW0VK%R^0lB&27P-0NkX&4_UjGpl%oTUY%@xPw z=8C%(?~|Jg9$rlQ{}5jb#?;}YpXfU@Abp+$x5o<2ZCUf>F1a_1o3eoEfV^c642L+y#< z^;WY{-hv1n8ssrNAYZ^k@&F!_J0HZ?0_9@#lA|Jxr=n#?14)UK4`2-%5 zm+&t64BmSi?f>T}q}0K=P9L~W?!q(j{1)AQKz{e<^bq7r*Uukkey=VJmj!j9&b2e` zBl7Z2?FIQ|f3JN^-hxla4^6(VJCszo1RbUppOIg2v(8zN*FLJf_V()B8sZKmbt;%! z)F3x^$R{^rkdI~0_%`F;K3gXr4 zXPvJm!I1rt+6#+MEIuWlH$;w{fAg&h^3Z=>9W&KIuxIhQ#eIth!qxmYPr&}S^|EPE zhXK4zKK_7iACeEzJ|ZvRot5kLH$fp@73B3hQ+Str0q>E!r9PpQ+?;4e9vz(MpUvdE z6!4Qyi;pc{T6{|G|4yH%mt0aE<0c9Lc>s^eL->Ha4WE$5aOZFIahLo54hlXBW=^E= zhACO1z33(Upq~f@8{+nCfN5PkcHP7J@c>(W}PvHf*FxR! zO{qhQ4$ix(C)$VC$1z(Efk+TwU;~ z!*MUr-X!1oJnaE_KhWMHzx$81x0kM;KhELk&{-DL2|6=eK}_ELQytVLZ@ol&kNiM* zO1?;r)gAg&aQ{SmMt=N@v=7KZ^!vgO1H`SP!<=S@j@>OUaz{ha)J2Xyu9 zelP9+hr8>7D+=--bE^+^wR_~np4tQQyFKkK@}swDZ?9ahzYY!@t_tb|uKm5f;vTuV z;*=eCC?|LK)dwDte{c6h7YZtb579m*zhrOi3vzQp&ikr&F2)5k$xZtpp@JE+h}>L3 zO#VIGxh}c6fF8NIfDFFe|C>pXQwK9AhU8{WjL6NLn30<+o>x6_%q{ZXU%hoZ_tUq! zPVQn7HOLRH>GnSPwFhaB$n^<{`PZSs^mlsF4am)`&dJTJ9+I0$Jt8-gdMaJcf3wWY zEt*k>E@pN8is~IQ?HlZ9AF<=P(phu0{+3s~R*>s&dBx<*D<)rFF}b%|~IfP={;b8M$dcAa~KeBtHp0HE#C*^@H_+ zYgbmU;6`|z{4#hze()hWr%ir8+K1#x?a{bmDjfP)?H%%q5Y!_to~qlY3MV~5cNme^aDal`9AHe212_|MlV2(q^Uo~5197Hv>To6wykJLrXR|tF=D;qw zIdEg$<@`VJ5A+rL>jmNF%9`Zn00FrY7^&?Pqq=#iT{myw@& zj6U#yeEU(_^G(|SKZrXqqz=cU!-V|CXX~Jn+#Fy^Zt`bK*Uulv9Kg-0V|fw|;E|gH z)X2>N>f|OrAm5(+p}v9^7jVUGa&v%?+#H}we()dZ{2sZvfFz}YIY6J>9AHR(AjWt^ zZVph8oBXl%)&AccU`8Eo#{uT#<^T(Fa{%Xq)uA-`^@@w}--a=6R0`tv0x$$Vxj8_S z+#DbvzZR1^BtK0Ky_|m$70iJ<G^AF6XYQh3rNa5>&>+7b?vvjKZ<5~)56O>#N7Ci|H_LB|JJF#ISHM&9qY>06FVQ|DzXYDI zxmtg2Lr<>m-&JqX;)&YxtE*l^`{*N8pP{{XP1U1A^-t4$^42r(`hP%$^qKm=E%E`p zO+JK&0o{~h>%JcZ}v z1Ne}a6_=3C(cRpI3bSc~= z&)}YNG5^i-%TcINhY`F^K882QOSn%yhd0+tpgL_WihR669&F*+wE zzvapcMVjMu$vxp}{r9MF=KFMqlstm>$?I3>_8EDO_5l>CHZle>-N*7tLqo9bRcN9ET}u?+@I+VbMh7rupm!y0O#+kld%VP*%KVV zqe2%QeDd3`(kIj;f5AX|Kz+)W@{@t`#|Q{)JRXWkLKCk>{V#-XZUyeM~;WoamAtiuOI>YW|xiV2LY8 zsl$!%jC_a#49JhciRR=v+K*SR*I)J-ePxqXLEVATP^qij1wil7D0XT z`{4uf>F0FL5Wd|1AAgfBOsT`p8@12LTQ_KT|Dk$iB~G+KZr&f@S3PkS&(UACn$?1H z=D+F#1mw4WS$m7zL;E)Q2<=1i<95m%G5;bebnny$=#YO3K{5HL(CxeALwJuoho{oz z{5Q+*DijLpaQHv#1B}V9K>G>#c3eP7ei_zfXnWBi;&YHpQC-8)Bb;fLXSGU1VMdr^WKn* zJUC2WKu-Q=$Qc^-{m+LP_hjP8J<}>p5BWOWBM2_>1)u9~0J@OBT9JT)IR2Y9*Pof4p zf|}$RPN+p*+^9cnqD@{RC;CU)|9==kF?E=sLzjFGPsy)FPDbv&MPJxp>FWB$dq7bb zE(_}U=UjuJg1mwDV{#u}l3$CQ8F?$g+ves}2tTIZ`{jJHI+p){AdkF-1J^9xApazC zk|q_}2nsCTCcgne5qX51j>Ws$SNs245R_7fE`s_NACUhua)#u6bAeud{gvzW_ge%FRt2^GTy)6EJ@|i_tVue-V-@Bav$yM2^9hq0`fMzMIOOJ@*OyEhdf667{1*9_fY6l zhdw+bAHYZCLwG?xf={ZRIFG=YPOAl{K!+Lm817zIz10)AM_$5x@~Lt$|C&^op+iV+ z-q#zE&(S_6KLi)nBVV9>DqYThv;3T{o^%;?I1E8Kc@6D{ zTz^l&ffwW<+B=`A4nYL>$d5u!oxIb<{=Y$mE`nO*DZFj*h`fmd$K-wFbU#D;e^W@Q zLx7-+e1M>V#fRj_BBwBJ_WvUUjZFdjf8!&upOe2ALC*EnvFxF}OWudq$TN|n)_;QvLv--T3wS_2zzMa< zOSBKkXYlUzwEthA(4!9STlLrv$ZPPNya6ARH{p||tLt~177FuaK|cS)w`TYqj|F)P z-_^RGtqwtsJ5eKFpnaX(P4FXAp9-HwP(a>CP>Vc+hvYXQr$Zj%f|HmE5ehx>e?m~7 zyo>f3c?!?T3*?NnulD}~bSS8U@d^1?5HuyvkuxJ7!50-5<9`=|+#9N6IYtMMyoA@u zzl|K9e2(@_a_29_q?YrqMTIGXLh_pIApVKS8}OL?N66`s2WX!PSM%RI0Yelr>hKE$ z<>XzoACjl=g8YAwGg-M_e*<(VR|R#YL->q*+sXP)EXc=b@7!1&$`bC8?{hNt|8*)X z(4j%@UZfA)BtHlz)FQ8=eVg2eM+p@ki=ddijSgM%2%eG0@PWmL@a6u$fdd!Rp^Km~ zc^_VqKN&eQ@*&#Kt1f>34+ZD{RLAV82=d5Fw6BrR;SF*hIZbl!ujEjQ`4>>3t_tGI zGWk&mipT@B?~u3QUGirjCzUSezgd1UI`pYS3LlU^3qeEj9PLNsBlvjD)%rUILFHOO zuD=O7Ovz{PIr$$W$GNFGl(AYLEvA^2uB9fc%BXX_L3nKD>$c z{~-!p>JY(ugGYN#ej;*4%EkOQ z%g;rJf;t$Vke`GgcT~NlHRO2YzWG|S?sEN|f*^mrAiRwZP4WodB7Y5XLh=~xqb*#m z|CkD|Lr{;rhoIEr8TlKKlar^&8IEZGZwduc#C`iZry0Bc9=G|^J@-~7Rg`d_evo7xvF?oRYlU*F^ za!Q4p5Hu%mA!uQ7_m=9dz6Cio@-}kn2^As~eDW_NC?M~leT%#g56SODP6xi+{}0h2 zrVa(XNB#{2^~on_pOH`DdDRo=y9gRp3(f)^3Uc@DdQMEp{{uNw@*3LD$Q#PV{991r zCkS%CP#w!Qf;{pFUMK$*a(wa>?VHl&{5Q)lL!m_-evhD#e1!H9c>#~f_dG@4x!#(q z^*2R_bgdwl-wd9SAAq2o-2H2PfFZdDFUTK#3ikgKD){J7k_Ye^`C&Mr1$l(_&aKs< zjN#s`wEuq+g6h;EMTZ7?25*udj+_>Gj`nTiX8%7#AuexeqVNTRKO)|DOsWI?TyCaOaEFv3vzi$RqEgeT_Va zH|3267_u1=@GkU9LY<=&l!p#|TQv9lR*rxA=hkFOf4O zuZbMB{zqFBFi=u_dJ5Huj~pnY!f5&7-N8IyOBlT0jy zDf!nBG$&6Hw6M5)TXiT)X zh@g!8i3rNc$7nw!FX08bkDN(Dg#|j4%*daOpar?Vn||x1^X2ML8u#GK{r~e3 zRHqI#9JpceCi#ny(;{ymr(N~LF@>mFaE?V#OztD7Yw?u4jhu|UsdB{p8&IK*0}RPu zg`k2wM*FeFOY&2YGm|dozgd1=1kI^K3U_X=j^*nRgz7opDFn31>ygKpn!aUpq9l$@~Gs6y*Bvk$)FKeewb) zlvz9{|4-zM?x6jDiJ*cy7@v^O5j15-&dlPArK{_Aoc}?P`!Ch8bl;&LAfCnRWmC4J}@fABmia_SOD> zfS{5(7@v{<5rP)vBjh;a>QEZ@DlW#qg`j$+Ab$FdpoYbp;??jMC9wVn_@do(^PR0JeNrgUw0*klF2RNaKe2AQm#k&a=K8c`|e1f39 z#Rud!A!kTFL(T}k-2a=xm^$2sppx8um!6DMi_gh-BFFh^Whlk|A3<)lu=E=Fw-MAJ zZz0FGctHLGl_Ta~n+g$vLW_6Ee~J_8lJ}6)vv^;+od0I|Ef6%I4g&<`79WxC{u(_r zWAXwylQmcC&lIL>1-bloAZSiLMbN_H?wyq}b{>J88o6^B_W$)=3-b7mPktzZ0`mH0 z`iff?56Pc~oX(xJ{|^upQwQTc@@FHcPaYvBvv_XY?EhbgpphwH|KCGUVetuh8#z<* z0di*Ki770o@M;9PJF8<^Ajq?Lo%{^s_~bL4lQ_+-3r>st90Y~r?z{EaM;4FCFG5aF zxtRZE`85!fQU~K1`QIWaCvPEVXz^m*<@$Rcf+p();W2_ri_gga4mk_*K60FYtq!Gh zwf;RSzK?QjeIb(~L+j~xfZXHKNBa^Aor2uTRaf1j&GiT&qGj~IeOQ_)X^?~c;9^5Ct1VI6L4eeVN58=!G|78g3P=^MBVvG04-;bO=xsRNz z>WO0td9~nt2tgzACV~o!Psp!9&Xhb*Ib#0Jwk(Jr%ai8_a=%_3%N9<^vv{5SGsy9! z%lU7XUmHP9>R`M@eiMR1@(?+Z#p5+s>+cH)>a7*z`il^hT0A4a9XUC92RXxCU9bOw z3U?xCLLMWiwD^qtF61o8yU20wqW!-qcz0FD_#On+$@>UuSiDJoFLGMO&Hg_}P}>x+ z|2H0y{|G@bd4Zg+#Z&U+=LpKEP$Fnx@gezdkW-M)kTc%e6Q`uY#%cNqI3r&mXl`-m z8`UA(6FDBa_guHUxFZLj=VZ?~%U)Ieqe2=E(V%ZB-DSlfM^1Bk~j{R9JjM{z2qSg{%2* zo`4yGX4D~vFUYS!ko&FbaxKu_BcH(QE7$Aq6A1EG1-bg1DLORC=kON!^~edyo%ie2 z5s|y^$NoR2!sijxBli%LT0A4a4LLb^13AOQQYgs3f}ja`fS}UiGxDz^X8~XC|3d^h z->#0OagY2S1l7r7qX;p2+dmT&+Lv3VnduT0t&9 z;|=ot5Y!}ZASbYRoBR={-}OcB(xc%S^$IH3W#^8r1nbBm9Zi}`Ps-)RUMQ-?Z&CKjKPpM{(`c@sH{ zb(ibU6x{Dr$M`J>s*#5Xs$1MAPmmLk$0A3q|JD`-x&A})6hR$!oKS4>9{GEb)Bg_b z|1$(-)WLX8{y_wd$cM-&EIwJfx_-yG20_zhL0-T34G09yEWRNB1ajQ(R)?}gj>n#$ zP^ZH62=dA2Xy3GWi~RG*3CZ0n_3B6>OCct|4M9EfI)YM*XXIZ&POg2m|8F8_NF9t9 z}rE!n^UgXrtd&p^Q%cuBq| zf@b7%zbOo;!x0D?l7|QyS$s_XEaa3`7oY!uplP+R^f~!+5#)ToI+iJNT#MJp zk5xHh{xztOBgnUSK>l)^P@B9!PH6FtbUFXc@;ebhUFuLGsAus$`Kibmlh2VeS#!1i zOkuiKkn8XD2%3{SnO+?Wi@X0`9h!5HQzNfu=KVjr7S#Ip$uC4uKpxk$-^mpGxw;xYN>k<(Ky=D%5fGX$m7 z!FWb~8-j9j=Yx8649PusvF>vHeFZ_2^@8vQI+Wx-d`A9tr4LQa=_iuS#g>-9H7p}#7q_4i@~4anzcpOZTu)~jYj{u1Pj z$-NJo_y16#hM+0=%MmmuZ=n5xya{*js}Av>A*Ys5p@j~0@;2NjKM_Fzd5HEc@(w(N zFZcg{fuIg`=%PbR-h=nZPeo3jJVpDg>WO0td9~o2j-U~FA3+8A06rmqJ#wbxL)Bi) zzZn$@1TDzVMv(iT)v=tQy+>Zc>*N<8$CobWzgd0}9*s@vFhfv_{A~yd$=!$QRS;Rc zx8`d7&2fNqtsvK*ca;vx$lrwn=j1-x4=rAhU;aAm|0h%k5LA-4;4|{~;e;0C5!yRH ztPYuR?}tgX@L>eisY8sQ26+l^lK(w&TI4y}w~d?qzbQnffc^g`5fqb;5Y)AJN`3=! zGV-KA(0~dhd`Ny1f(r5l+K%k55ug7;p# z@uqSy|IP9Xae#n2bl`3BFXF%vc^BTrck2}_adl4ULwf1ctHLm z^6_E%01Jz|KdO%Le#ohjH*i9A?W_I2kAhDfY6uF*TWH@RAMLGAG$cO+Ih~4&@edIc zR|?|KWh1CZ{$vF8$veo&$h+{I{3w|t=ii75DLNG78GJ&13{GfDo}>MYd<0(zSM%RI z0bht9_s7+-9HWCrUc&3-FGY?|K12KF%JuqNpwLvNXa*mlaV)6 zdolk8R0t3>B)=L#1$p*i{rbV!;wAaVkTa7m=f7EgAr3sJ4#u7Pt7G|b1bO5Ua%vWD zthri$pFmJ^tsvK52SI_w+vG#!MC37YI=i}F|6MAK5R{Uq2Q|)cWgCAw*DY@gDgz za6*0Z4stS!=Rc$Ue}JG7b?70eu=s@h#mJeG_mMMOx_kt%^2RNaw#Z&STax&p+{+lOY3qb?wV0=jaB?J}Z@vE^T zvUs_2z5aG0XtpZI)#rpbp}EDKpRbRl<9rJ_9(jbE+Af~xNz|ai6hTe$E`kD!x5r<26_7uYsV+T0t&9<5TjNB4|z?AZKB5_m|Zn4&Q*+|7%oe zBdBh1pZqmAp@2L>PRruqFKPdOCW1QDAx2Pa@gDhGkkcpcAty6#_W!1kn*#R#Jp_%& zGXxbDpOC*3IaBf^N6?H4#uwyQAjo~7I+g`;Jd4-Kuhu!@_y4IdK~U4;E%F>E6q3)7 z6Inb~F6O^kexF59k2*Nl>h+phJR`paIXQU^Im30A>(3O5^@8v_5Hun85mZ`yMm|B# zf;o}f@tVLO6m7vujN1Pv<% z$EhP|MDD}KH`TH1BgnIOo&2ph zA)kDJoTkNF(&hX&%kN?Yh16k)pvdAe`P-4xBQKDXuDM!&rjV@_a(-JKO5+~+`;b%rE$#o^f6(i)K^=@Y$*)9E zi@b)Mw#6gkX8->o1jVL+{lAZ(uEkUGtC5qDw~#X+PfTG*g^wbrAde6hPzU2}^3NhDA|E2BWAW~~ z%k_5?g3|SZ@G*k=79Wt`jGQ6)6gi_UT&@2x6>ddPNxneP)Z%mUFCoWyusW1pu2-4+ zAnpH6p++6nZ>-$Brve1M>Z#ohm{j`8=AQzIWDr>=dq|2GAnI{W}Z z0r?m~EsKZbKSWNa;$r-#2#PC(mG{VhjG#XG0y&w*bMl|b96A3+RPa8bmq%go3HdK@ zLR0bva%L7^2v_spJOO`=Aoq9Gu?!I8S-ejETjcoUA#$24*Xz#|TC0Luf4@UeNFF07 zvUp6s+nM@~_Q=yuVE>=)QqUbT@;wlglMir0LyH&Wdm(3%P+^3i(&97n9SB;GPmtsM zzB-h~J@|6}zdwTN)M198hQ*uY2O+0L?);;^qwT7T@kb%57Mw>SC?>C=eb?eC`D2ii zk^3q~9DlH7!EuJ>1aji3>Aa6YA1M`7^^`MJoMlGl(kTe?2JV+xC9K|cQ+ z=Pd|wcdw3R13{j}>*Q}mj!zyW2x@Wx-XgykK_PjF_L0S7^0y-==}{p@P-^jv{89wv z+j8977va{oU;(1gpsPX1e+Bi{c*g&09ii?_&s zhZ73PQ{+SzkClu0Z@D@1cj0c4Ft`|Gqj&u+}W!- zlut#DM?OSOQnM5q=2bi&5ajG#9m^hqT=EQFBY!1w z8stN?_l2wZZ=Qf-6awmSB7)lFQ?w5)-XT8)Io*}(^|wG!Z&gss&v>8wwFnxJd!N-~ zoLhWE{<^cU{~uGqN6^ILQ}Q?Bgy!S{auybMlkL?peiMRf?~z}GoPO04CqsvLF;5*WfMk2E4t4 z_Ww;3V(QR>cgaI|M&5xB$h+{uxY_@wD2z=3`~M6+BhTS;@)6wIw|eKs@EUnCL7_o~ zk7BYk$){)^SiDXCG2}$#bDfhoovjN_mpn&MO1{7e^~v4;qvync{4>ZIDi`zLEWZXi zjHp8ZACrF$K_z(`?Wg1&_5HJ#qr_1#(*C z9poe-72LD+nRdv>2#U$u2C*+Sp&a~oU z{O1UoRSGL#kUs`N?*7%WTp-7@c%8g1bL9NnChoEWk7Ww0GLLqq_Ig!O<;cEVy zC*V^M)T0g!1f>?w$d5)&PVOUTxN^PzOrcm6)bjfy1Wm}B2r4Z;BYzQc7UZp)u>W@s zsE%a|2k^*Wil91qi1rPOH_1;xPAj282SII%N8~3XC?@YBr)%*PzTE$xfuM{!qzD>V zd`NyaatiVcIpeB}{XYt2wcxx3K{N6k?dKME4y+F4#mMo$TQ@$l#BUimY*qv)M1XG4tb8C*y26%Um>Tz?sEQ* z5R|PK);uTwErLemW8@STpOF7vv?_sE}!pgMVooQB1l+E@Gk!x7Y?4jlxw zEgq2{ft;AUi=1x7#rT^-S}8crGZ2)KrwAHYd`SL>$SKG(nIq@lc&mc&k~~1rj6BB) z%`NUcqB@i>M2;t1&3`k-BLvl`gYgFWixJc$A0sEQczfk~{k;r9(W;;(Ux}cO#k=Ik zBPS)FA*a8KWB)&(!ifkPk}nW6viO+%WaO0O?&q;1N-Tvr`D+p6JhD2LH3Yd9uaS3< z(||Ac{|yBB)WLW_eink-6^zH^Hz24- z9wR3u@4++jk4%{}N6#CJ)iROCG~h@_!XMYW-(aNYPe+q&E@(J3v$mj5I<$C@70fIWKf?9sHFX~$wll$-<`4Pw&k+;#lAP>KY z{r`jtM5&f}^>;K4oe*C3}(UPt=|c~iNV ze@!a90YNSDHiFvZ5j-M44>>V;5AD0s<@`6x&lFPXa1nws@(e)(@*F-SzXUnOnyd9U zLWl8ML9RdJCHZ9tnvs{tnOod>e03-{W92?v;6)8L0#%FL{QJ- zee$0mXFy&cCtr8D{!C%CUJ(9E1dYij2%1=YO8!5{nUhaNj#~eVEedk|yHBW&@$Tp7 zM{U8sMo!{Up^HMD{OJht$p>iP zBp<_D`ZHN(3#)dkAu#SRKn0?vbB}oH}`i_6^}`{+lPDDYU3Vjt*_| z5j-M41qY7FCurYYxn6%W6w*~eEx*$dl#x5P>p3wXufd1pZ$wT(?%$s1pfMF%2r9|X zLC}mmLi@SJokn%YEYybWLO|NjO-5p@_NsAKUi`DMsS z$>+%FS6zJm9}0tN!FfM|hUDHq>meIid`$i!wiRr+YvM-4-ho5_>}xk<`+rk#pIjZ|yAV_(PZ3nNxKDl$ zasuOK|35@f%M`HxHy)Bt5!4|skrP|IN1pr_g8Ec&{zZ>jX7QZ-XUG|mH;_|o?c(qM zQQ=nznv%B>G_&}E{6XZnPpJ-N7df7CG5^f+Gle>J*!^66Cw%e@K~0Od$oE1{xbAZP z7YK^h3u_*e?}wls`3yO!#WV7n$WiMrr-C=uS3IB)J%E%{ZKOmpMhvdg1Cn>1leMOJ`n7j@z$zP738F>@!=j1K8^HepItNs6p2=a7c zxhy;AP$Tcd8|0@Vr%7I*eNb^R{xcNXm4f5E9zhX#{j2&8b;tvFm;4;$q~xP#iyS%s z`c#M!G$ilBN8~AdOnxB_T#^saekxqefAa(!qA;fpZ%2^x2i4^_Mthfh2CtF-4RRVQ z$NIZd-%@{7P|MGO2juTYP@CLC`_SSY^8UHl|97d-Kv2)(ee(C?ga+hI%iZRpza^T7RZcUn|JR`Me{{n(0wH@#fRkohMYpV znEz(^jS)1a4#rFJyAU)ZpCV^&ap%ajp_J?In+WpO3v&Mdt6r})i#NzixpZ~?;&Xlw zG+h?d^JnRE^8Z4RbJW^ciY`6mxE8OG|2RQVg9;gfe2WLR3MX zJS;!*8rs(_?vs1S3CMk!Bj;a>3IPrfl0O1L9r8BX$K(;bNB%hE^o6VWZ=QfLI%L$r zcuxKl1dYg3+7B&WkiQHUHi0kq|4jsy)WP_S z{Lc}zAa5hbc}8^zjC)m2oYN6huNIsRf*RyKc#}LvPK!K4`!@MNxtMnjC_pt1L<=9o8?!cP*8^%d`!N8&&b`0o?LVC8r*y4YG~B@YoJhDE6DX1 zz?akPE+zRa%L7^EL~l{dLveiS|whq zMy)zxk*HOJR*AAefFj{iaFBu#%H=mR&+|+&pWki&+1GhLbLKpA<~b+ln|9msyIkmv zT=+`82H&Ok@!)H{zCjN(&_dv@dZP}!_K)(!-Rrmyzo*_OgtzoQ!QeW9A$+giXbkuD zMw9D!41a*$XD+@u{}1&>3v@7F!5ey`H9Xe)I1ekoN^`g5>HB|#-l$dzq`xnqH>zL9 z8}P^LeOmD9Kgla=|Gzw|zb*n#)EoKmmfom;9Us7-ruP}b`+A>I>UsU!4rqZ1Iy_5n z6vM}QquF(Q1)u8m$;M^FpTqa*eHQRR?rHrk5vb~oR`5gW3B0KT ztl_8Borjl;`iOcZ^Q``D`CZk3iw>R+T!o+2>ud0-dL4d2-P`hf{mnJd-U?)&|Fb>s z%l_kZ;eBoU@b>4VNC)r}!B6J*8N;J{zE9Tw41wC`>iSk^N8}4E?07W6+Zrq z4BUV>?gDZU(Qa z&*3%o1-!1lga@7mRtPlI6L?d74R5JCk1W5Mwt5BL5f2;}fv$F_!h7m9xc@wvp$>fV z-}1`3@YZX@hq1FH(J2$`X#*cbxEk&EYE~pU)%Pq{(IV?vmHp?I{5I` z4@=QS@b=f`$;R-SUO$6->Gk>gTOzR14$h;>PvGkSRrpY^Z@}&PHhgv;d4TStaQ^om zEd%=Ku+V`c_{qO|UA{Vo^uG|Fz#I3Lf#bqu|8ZO$cwPkZ`#NhKcm;3k6I8UH)llOb z@(OBjPZMgw&juRkBGBBc8wQm+pZ1X|bR2`Y~%zx(J%B%wOI zuGcr=J-xmQclCN-d~^Ok_;>Qo`si@=qWA#b`6uxRUi*mn5bo)HCM8eb|5P)LOM&#S z-_iCQKGi2!!O#4Q3|u)-p1H;+#Ov_!ebX7u>aT&oQU_?koo~vk>B1}7jnZE}e60zF z@S5Idn0j9SR=u_R$&IGy(9{ldc&yha@Qz+zd2D$me7(NDaan(%c4%$_`4b)gq)c5G zKD)m@G2GL32p_*%W^M>?c!At#jKD|}n!@Kc6Y%H(a-Rg=_`kZE9#@`;re0qU5U6U0 zCcN`N8K4XI_4<&$Pp*&PlOGkIs2At|fd=O2Fmv9Pzls&SrUO(SUw*QVUSESR^#0AV zr~m$scIcD?&RhrR!-sl(1fS~+P2jFxAH!?6&mJtTzZnAcJdmz`xTn5^H`Nn(TYU}h zs#jX+%w_d&%g@(wkbiM>|a6l?O}pF5vP1kc1NW(Ho9u&*8XFD9>p9L2@7O2|+m!>5W?G zkTj%22fow+d+?RsCxm5KK~;Gx{s0$6S$jp$bPNh^WPRv;L{I?ui>$}^F*Bg zXBwzHu{;xVbr-%=ufi)g$j5FCp6K=U!e#$))*A4NK>nakb0|N{HQ??FK-LwKw{g3r~*;+ymTQUeoo zSgB9pYxNjj`CWN6Gk8^fUh?$)*EO&x1=3@=`V!t!uRW<;q?6y5fjjWtIq?YYW}emG z41v0KaGqQqprzh`kJWv6MH3psJL+-jdHvfC80ki_M2Ge7$rDuD<%Fg>a2r0-0S53y zua7q_>#w7M^(K(7zoEMKl=8p>^%lIR572|J^Z`cj+V2PQWD5j5eFFEX<$-(ZE%-tc z3gHd)DZHikNdg4=+M)im^1z{X=)z<5Av{u_!)JQ`wR&;>cMr*c75%T(MCA`;hHCI5 zhkh!5MRoXY^#(jrZjTW;yPlqno7Ud~fjxO3 z{e6M!_zK?C>l66CXUc=E;htV!dwM$KS^e8o+Y@+MV9Q(j1RePBBQii2?$32b;fMA5 z!ItOiZ>q~?xE06}m}q+p?_7|N*BHM1q71x*cONU~i3ILGQ$PQmXOy3K^$q1kxZU4>2G0Nf0l86#4i#-j@a9EX9b>rjHA!>^4>i$+xt;%q3M&if z`QI{io>`tD8=!U_Z^C1Jur55X0YU^?Yk7hJ{OXR^XQkmp@YW6DL-_i3;v@JmxqrI; z5m@Qe#qi4Gjb$~WHjP)J&;Ek3HFo5@U zfH8cbt6;kA+4`$#ri<-B>H{5M4PR+O?z75Iw$ST6c;oM7hFb9Y6W%AE|2+i4xpWBW zH^~!^;PZc!>nHHqKZ#G_4fWZxaQ<&=V2%!5^(EX_U%?0JYxq#zdA7}5zW=2=od(<@ zkkxp4G*hp_7wUERO5KAymt-cIa5vCE3xS$?2VPh2!W-&7yrtfUchrLs0(DGxaunnR!-!J_4gR%9h!OpH?5jJO3;*H-h)nCvZ<^XqtLn z|F#1*H84Ymw)!02RbRq=^%dN{$Xst+*561wIETyca-#0SWA!TBzR0Y@6TRMpS9a+6 zzllI!r>+GbsCVG@&1V;G-+cP;^qbGTTKfS4_RZ%QzIdW+y)*bs6I#NXPm$}Lo69rW z{TCUys$QJ`Bkj;Yhn99|!lxgV8@1u~-A)&7U&;7o51d$U6qW;yeHRqb_4*OqzIvI! z=X!k%m+yko`kNzQUqme73%yYSw=XE1=a#2>sn@&km3l4ntp08JB^vP1!CA;uH{lia zHr&3@=)$Xdy}#x8`m1Rm+zMpnY2VdE@S!F;g4gvv6L>>ChNs`8$oiinP_eIG;7z?z z0=F-xoLkDTprzNl@Q!-z7M%a>+bjQ1-(3g+rAd?6k(7>7_}3DcqC@*X#AA5$f5qqUy^s5^e1HY~B6tQTfFx?od5TaB+y5P;|~xI;WpI~-0m}k+k=e@m;J{X1Tw&+2;>jySf(-DUd;?{ zQ@wzXhw=)R@F@6A2_y*ERIlMDZ};^)v&!?!H8K27aTmV+Zt)u2?i17zup2et^IK(x znsA%BHhlIXxxNFp`}D*&=YPx8M~BHhN$6v|yb@(224}L_wk$PVL zwgVo}KocFRAC>`H@SWbyJkd6M*Y}F|;8k^h~2+B1UN zj1J+~J`~84jS#RY9mDuWR^dgF!fi(DWe=P^R;A^DbHu6??%h=qZNe{F zk-{5#eH-4%J*~eU0$29P06zSxdLMpGJ%sPLhumiXw;7Ex&+6Z%+NN}f4mPDDxJ~I8 zZZkT8+l)@PJYRnYbgJX6K(_vhDuvs+pTl?S6R+Sk^#s1>9y?|IuMwzg2j_+5Ez?u4 z!1t-w;K%MIub>V;uI{}sC=U>6pn(o&)SGa7mo2!x$~OFx-lt=3=YM;bT?^>>-`-^p zZtv2E+pFxu?Nx^Gz~1Emf!j3G5qzmWhF?~nz*p*1cp{$u{Exs@?XZB`hsP3bpB*c> zeRd>p`|Mcfp4Oi&KYN$Xi^?@&@3I27W$D80RaW8lDr?)G)xW*V`gS07dzT*E-em)B zpB+tjbRSs-9eDQHk*~il0`}q2gWHFP54X>bKHO$Bgxib`UWD_%O=*Mw;v=k+J<)?6iA?hz$xv}g)8SdA|NmJxV$ZwgTDu8>&a})9OR`SbYRPt3HKCkJs~mjKHbKYtg}n z>T~!d^#y#PzJfpMgKy6F7w4ro|68E?(sB_swOxY`pL$DvqdI*4=0@%wy#H$t&b?)B z=l{u1yeSW~EuiQB$_FKpE zOK1W=y3WT9oGAilB;d^8b4_Rtw}h5(=VdZ;E4U?;;Mh8o10{3tC(7dXr@Ui*~9%(}J!t>`(|6VR#X3HXw z-`8=DY7xOLp#*;9e@H@W_-XZu-p^_%4y=d}u!L&xrnc*FOUQ$_Z!ZZo-~;ubg@AKH zHzK$t)P;xI?!he~AKus@3H8M{=YL-V19b2-p$KjXjo`7i$8bw%Qu6fuH*U}(Dh1L% zmZLs{cQv6o+!9*CotJA3!SjT&`b!WvbfXp#{G@tCZ)imnX+kdC5~{(Q+ODVn&FkN8 zWK-m!L;H?eMDT%n3m#hy!7ZWg#%2A53cXDrUw@X655K%qiwM5^JH!X@#A*m$`JjIO zj}VBpJ%(FC6Zqjf$-qZmYPr-ZV7eap|*Q)OUQ>W?~)~y z)?Xii>MqH20QcUaCnC5dG=j(49>Xo6N#{QZ(pAHI9H_yFG2gd%f0|64{Q3+VYj*7g`~2~FsC zm4T=5x%vzq_?poi0ZV8JcYG}(xFwXpFWgNMTEnl22TnzAXhk&Agj~2KRD(CQU58sj z9=!g8l29Y}wEk`2t_E7@Ft;LtTS8rUsO=uy67sh_TYtkJl8pM>fz;>f1GqELjR|o1z3A!nzg_e5zj28y2rp z6LR5}P_6L%`P0AYSfO47vi)!CM>F{DdutKF52?4{ktWoJR|5O_9)VEXJ-E$~55N2) zT0`*N_Z1(&V@)WC5U?p4!DDTY;g-+@eqINj!mp~d>v#EJ+VETJXbd8HN++!9LQ zJ07GpRPyxw@7F*@Z)ip2|FkSK7j6mF;7x7U;g*mGzbzX#tG@;UyB;i=w%{X8s13J- zy6{ljJ-8+0r=HipJ@J7@$iRJcIIcc`*WRWZ5!@0Q!DDTYH!kbXGMa1x`SRQSNJ(f4 zKcqf`w>6*@FOpff!FXz6Rqg|tcIME`e6nSETb9%O>NiVmXHVcUnB`N;HNdw7TlAB0;i3D zCDet7+U~(EAs>GHC6Z7dKGsABxu^AKQ`FTdiqOFl8o^_2kKvZkgnm>Knr?em|K~K* z*>)iHNE4dFEukgcd5zW(+!9LQ=WczdeEzQym}{mLy`jxeY()gOglh1nw(D?9$a@XW z|MORB5uwACG}G)?3!Z2~ZMY@Wg@@Yi6)yWv@mnx{5y;1LuDn`{2wr)W_yAsehn|Sw zme2?u2MS{ZY>FoE=(RHN6u##*;xl+#6Pm*GF zge265*WQqNR(}HomR3Y?o1qar*7g`~2~FU;29nS;^}PP=-CWX4XXxPmjGl<#me3OJ z^tFcImQb>BS$`+rE*Y&ifqeZP)J!XSLrb)&3Au1fs0MFpyAB^dHMk`o$V1@RJ0zh7 z{DLOhg8Q0K8*T}8;i0yB0RlEfKK$@IC80k2tR^~uk2IkOZV8Rli}Qc1Fh&PUXaYa* zE-fPXDNS?+pIZ%;J^lXAe(SXyaGcj_5y35?1its(T0`*TnrKDuXEo%!Gb`$}{#*ns zp&GoY?K<2N^58q)qcsFSqKURL&+6YY^74!vr;QGlP!}F*y9c*~eE5~0(;C|HeEl8J zOb1(mY*}3zXXg3cvIVTb36ZAMxF)q{D1ni4BUWU)(Ab$P0DVD6Rqg|@^Q2J4>coqJCM31RD(CQU58sj z9{kW5ts(fCG|_zhwGfzSLT$Ju)P;xI?!he~AHM(Bw1!@X^Z!ZBbbt;^DXo6N#U~pID5ugL`5Lm{~YI-W;%nr@6rRJ6Q5E$P@ zI;`Nw|EG8YZ-0-t^HWk}Rug-^SG)pWf1h|Y^}PPA!^PbasH4N^ZsH#NSWUbMZ{1zI z1>e0#yt8pxf5|;0(Axy^srT7r!7L!jJx!_yE4w z*`L-}T7N?XZo5MkNdNvX`1CH~6L{~g;xRnBm-r06zMuFq^Q``D`8oERQRr~whKJ_~ zCGZ_Lim&1O)hjsMc4PU_a<@ERf3^eGwgTCRO>NiVwk3P;13M+52K=~s3m(RAlJ(z4 zz!K`hLv8oqN4_Of>cd-ilZ5*4P<;>}Fw!ZC;Fiz`9&39HKX!W=cmh9lAMvTVo&PUt zU}gdP^FNx<9Bv6M;ZCRr4fw_VGH?P9jy^&HYXr`ySM-Kfq)RIzxFuABH?>`d51yEh zoBsPB2-Ke}2{qtd^%gw*3#sZh+!E@-Lv8o+|EBe4Pqy>9GO&*hXKxYj!!N53;O+PGYiod0c#YUt3^b{$@iWMB_IdzW|v?)A$aXiW#B}7bN-M2Oag0kSgTj`hE_zi4`~s>Euk8`sqK2n)AxV! zq73Yn0*y0dI;>fO$PSi7d|fDhhI}4z@5L+8iHFw zqtx^Iw<(SF!ZAAdS7hJ`-2IaH6y8#w!9z`GzHwQ9meFz($d{k!fDX<~iwJHBjo`7i$MA(G15e5xIQ<7mU|J416ZIK9)P&}6 zOK1sqPG}9m7Z1TY?y{z8S`Rv;_q=F??hAHIBscpqMUruYEf)Py2@K6()pTMctrf7){&YQJ};P#VH0>AKlNoWnfre4we z-QLdsv1a62K+pe{Pz~PHb{%dBdGO;ek%SuX;G70p2rR9L;FeGq9%{P>w}gE7!B^x7 zrRyJo6B2L+aOZDyBZ6B(BY3RsG29ZGynkOws1Kj058%Eg6cwI7fBJX8NAhk)MIax~ ziM2h3TS61~zWYl;Q}|K!8GI6GMsox#p(WgTs}>R55=!9n2TDR~cx9h>P|+J&5ha?C z3%7)7@TRuwa7)OeKS%~{h;PpSXEe}42XCQ81h<5`@KD=5xFzJ5JaC+A4aulq3OLTb zhlmg0z9tmGEuj%S*7g{lCzOuwOc1#8P#Jg%-}5l>8GND%&Eb~N67CGNhEmVQFLpqi zq68hr50`=0@TGc1Z&=ijCgj2`q1wjt@tvkZeG|ynpC#nM4>cvB2K=OY3-0}^))0JT z-}7}52({gVTS7kEd5k2~hd0y*a9fT14=Zx>YCe@bQw+y6oxS|Dgd#Z)inyN^ew!Cz@ytKG7}QgLk#vfJ>r5 zddfv$a!@jD!B^^SxFy z@@#y^*G%KBK<1X|9PYeL-u(h@i7w%nZ;?b-@ZH@<=HojF0+wk-2eO)&XreA%-+c|< z)^;6kiF$9t`Tz2ZCDR5v?Cyy-;g)Czo@k<7xXq|b$*ty(Q|x zo7%3zEzw%;!DjijUoV-~(P5zO!7b4ie4>fA=~|@SZBNH{B8A>|Aa%>shwmInqJ8)Q z^$>1}4&h0fXg0nxLcpeU0$*x-3b#aK_|8ZYoxu;N&)<&ozh$~Y2k$m1(gbdaIw#9D z;c2@9Kl@%u$Spj7e#g10foc)R=EZS3L+Mb1pVtqk2He*~oA6lQeH$JI3LOMizbFHD z;odKa_u!}0eYhn$fKN2hAVR=09l__?9>dSSUlN+Ycl?U@6y8&h#W&}F%XEPbiDtTl zTcQcP_716qHT=}COG1vuWxoj==Qa&gN`drTFqRH3+!C$By^l+gdT>j$3HP&hI=<6F zp#EDja2xKcci@-QyKqai5BD|EF!gNw;s9cqM(7Z0dk8=DJCf)Kep-DDcRnE3Pd1*9 z?^vd@O(4t5nP{eSxFx!TyFVlEeg!}HyE1SBKlQtT1l9~lLmS^KT#~&(z?p7f4 zgHICgUB`WR^kTWb4?p=V@erQgKOf&2AaLr{(jkIZ-z+|Y$J!pl_ueSq8&2RC?;t*X zC(i#n?kIs7I*h&~%VrL@Z!(wgk$&E<;79GJV{<$I`x>Zd$D+8j?ZWNIRfR`-pE}%5 zRt<&0FS;Q*GKTP-x43f zUH8#W_G_GbT7Sh<-|<8qn4-g6eFjg|7jSo{+-C*%-X$AUvh7*@cOUwgeBkwVAeH2P z;*NH-M9+BQRe1Z+GH?xU#n^zm>Gk>gYcini_I11iw+HCLcRWlI?ZKz&{deK~AM1r7 zIt(8rHyXhAKUzG3C+cH(tTQwzT=t*h`~O)H$lr()YKJ*|r0wN(d&zAwZ@C)ia z@y+?a{{rdIM~B*Dq^d)>B^1FY+8)A>zfkT!DtY?;YcG<(xD;@lOX^d2TN8@mme3rY zXnO%)^wM#&`dcD!{3Vjm3hupBd<_pZA?MxYTCs#&xTo!E`ro|%t+>v-+Gf)eyY+{y#!sqU|BP z`brsK1V67nhWoFQ>!)z{fE0BcAYfB8hbP)zzz46E0haK+uMuCtm+EWv;{4y#jGR-~ zDI&P1?JB&{mw{{W+tll251i<=(xFifIKC#-gxd_Y;l8#z@O`h7`*-1s+|&B&A#n1z zbm+rJnovmBkL?H^YkLTHUoZC`WuDc)Ex&Ub7^6ckkPZ{Lo#|%qxh6V?Pc+fxmgnow zeUH5J)m9)|e?9j=z6=xixi?BeYk2QX;*Q?W9?TN0!rjN7ko8|fz%upVU2Qku=iVX% zH{qSPinri92jcDb;QViy_RyjISXr+=+!77x+8)5;ACMW1%UbPA6&(HL%t&f$UcbMo#N2poN<47`N9k@yOJK|O(6q7@y-YGN*l29Aq>WmushdNcR5{wyQQw1W=r5*@?an&<>>iN^3GZRhK6#=z5LO6Ty_FG`{d_%-z<+!9^GBTdwKFV6p# zsr%mYhfq`7RrulmB?;Bw&PcotKd0^$F8hyTnYN06EWf#C+J;-AUAne=aNF~JcsqE% zWZFky$FGQoa7%Ou?>=6NbOg5#p()(e>w_49NZa%4_yTTEwuGNQCl9cK`@b)qh;PpS z_GHem{O)~iSKtR0aw8XhEf%lBCx0PcD|!0Jkp49sEt%3L+}?c$?&$ShxTozt ze3HF_to}j-+S-n;<3qU3#0b9985+Y+|EtWzB=x-hxdX=NU{5fE+rV@9wNJ|c3;5(S z;>(T8`m%LEFVGW;uL2l$|+#cZA74ZtZ{zY*Ye(K|ad`VPCz9Kr{85Fe=*=YM+z6LhdAn8Iz~ z7=GwGWq=vHawqY5*@I&FEz1GN{dsx!D|m4zh3~wx46ugB>W<#eYDFG6t-mS)zP|e! z+|`qf2k&aT0WS`vaK9>vwldG^-!j_sy%K1ngT0y_e4>f^@UA8r!YA4uY=Zs+_t{NMo@U;%d? zE53x=yI<#?*1x^uM5o9(EyZWv)_3p1o7%3z?VMkO*AGfU^=;4A-)$Q3wgahKrY*R4 z(}}z|+VGJk+J#5j?!lAvn4hnIAAwVcB-1{;^>pzNZix=zz9u??XFqskzb2<~{$J{a zQ*^L%ehlCBEJA_+@n;Zix=ywSy<}DU9Hj=tz8X z{-5iGV{~X8l}sn_k@^&VRXv7VqKlHJ@4u~?E=z&*$8Vj|1YY|ksf9H>^d(V8d!^MGOfcyP1J*1qD{E3?H2svt0d8O>UsTJrhAS_po0#5^)B2J?ZYRU zXb87Nqm9e@ixq~OKwdoienJu&!B47>;Y;-i+!CF^mj{Cr`9O07EYl_2{a^C#SMUR` zlSC8vY4tTcQFj8pp}hjjvn}#YGM&Snk-Yl_{OX$} zp(Xs_Tf|rJk$RGOR{wnW6&=WYq*Lm`Ezught?fGe>Od0mwme^d2Y*@ujjceoEJo^0 zxJ_vXKG#IMa7)yOk4F0W-$$T*QW6T`WAy?2ntBAcM8|OFNhk7UKl%UteLlM9$LNq~ zdj{YCPDykQKc&8auhf_3cK)|a*B023C+K*Zsq@QHd{z@Sr7paw?J9iVzdbg;VGSPm z8mJ>MQ}^I!mvW;P+Pqf5W}15Gx$(_zU|riJMT;z%5bd{pFgdX}bcq z|G(IUA5O>3*MAj(Q<_j6-qnOWxcw=(CcLZd7TgkQzaQuS&VR~GbkHGE@6k0OA8rYS z@R7C$h3C(o{!?pTmw}@qAj@y(H^hhVBkE&#tO-rvmQV~|1`0C-><pMt79k_Q#@m|T(_wQ*&ekri|f5Jn$wg+%aD1sl`DFYATXEV?0Z;U`&6PmznhGO_q z+cUT&G>7l_PDyBydS3sw1Mb(r3LSh+D1lo-&KcB@wkvQ;$lbWCzwl0yQFRl@t9+_n zheuXKa7(BO?`pdRKWg9qw-MNPXGy37KdRn?PppREmQYC7_8>sOrYM46_%2Ck2*0L2 zhR>~r;FeIVUY!4z3Nv)Dgy!&5yR?Yl7u8qr#A>MQ>EHjYJCXCNfe@MYmapB(c#38 zh!5bNCK|yl(Gh&E?eUi9>+hrvFxd)Z>u;t$h1c#Y3B~YZ4;Ej*+nVSSo+c{mKS7}O zYf=kq_;DS;(YVdrRJ{Us8n&fpVGbWWFLpZ@>9 z2)Ms4uVe*Z>i`LS-*aW)HTogU>7CbNI14i7((szFT}%xa>d9 ziQN)Niaf%JdB|El-|Zci|UpZmI8AH$D)OMC|3@$FBN&;L0B zM{Y<1>8}O6ccb_Ue&~+k3A}YD@ilyX7jfq|aQ^S^l0YR5WWQ`@JoA0xF1&F!@hW^@ zO}q}T-d)_=xU9dO_mn_m6UY;A?k(Pg+Y_|l9Z#-r!!JKjyaNyS1rq2XaQs2yK77^? z@55^k6A$619xgtBSDNBcfPk-oA^hs2q{A3~^fBTS_>lwRQ~2S>ipT23`M>%E3Cz&p zwu9nxxIMuF?mStpU%~f2O*|=k;Osdhfpt0H?0&kq^PA;j+}jba!1p{y+=XAfS-c95 zo|k!Ae?0_tJzqNb@a7TmKK$s5#6$SGp7;R1>t*6m=2`vQGCTZo2@KKU@Y~)gUjHqe|9AeZ1Uz&&dP=+jzxZ?FP5A!z ziMQaDpBHbN+xfqLS^^yl==p#COX59v^_Rtc_?7pI_u=sw@em%I{WS>;5IFSf;t_n; zZ-@`!xBaI07#^J!pTN(3Aouj||3YB(zokPAZ~dY83_kf2@j1Nu=i&=^`$OWZ+|&BA z<=6Tf2_)!H|2y$DeAisuIa@AL=U>Dt@a4zE-EGh6|Jo-cP~8rse)KcqJ^1Y9PtI1S zhw|2T^$OCTu%`3x7nhM#MpVT?DS&NxTO?cW3cF{P`d_yB(LZsJjZ!1{+IFoe&3SbPL;+*f=IKYoAl zDLmdM9;+AU|IHH zPuzXJ1bXOj?FHgKeE34~K78Mc#Y4FBGV#Hd=j(6$atTCRfozWZuMi)?>&L`L@cpk9 zAH%P{PJ9BtE$qnppCT}LlXQsTwYP}R;L%&f=kTNN5MRJoKO?^U0M7sGNCF8uOdc&? zqdAjdUVQe-mfEhstw>#X(~8&J&i@CjdM%*m|AXI@gz9jq-t;%G;a0p2xD{^`9$59Z z5U}cP!>xKda4X&}+={mc*WwKv9|5c0KHRD|gj?|r;8wg5+=_RYds=_?F0Fb;=wQ`5 zhNsn=*TMvD#XE&t@y6Sp)xTBmY&(#;Rqq^b)w_UO@vh*p7H5cu~~wqNod(=XZ*#E&}{WMODL#qJ|emoqAsXwgVPbjSfXs!;7kh7h5&FDC&*N`YZP8 zO(1`TMODKWyJV_IaI5Mu{N(?X>nHHRoAmrYMWEQL;YC%$i>ihfMGY^CIzZqnR@LyL zs(%kvt?dfDC~Ei-D{A%P{NJ;xMu&ahqg4$rsv2Hw)$pRI%N{sIRhI)!QPuFGs^LXd z!;7MZOHrrw=Oa*5HN2>5cv02xqNw3TQD>gjzb(Jw0D=xhRl|z|2)sCez>A{Z@_hXj zRlOC+)?ZQ8@S>{WMODLZ{}?$vC-AhWW&JznP}SP5z>BJe`&QNPV^-Ag_Fc88&*A)E zR5dyjRShqy8eSANyeMjOJO39|Z2>+17gY@}sv2Hw)$raA$P@SBK~dER9KXAC7{H6F zh8I;0KXnhe&j_wX9XMkIimHYeRSmD+QwE6PMNz|xqRu_7KU;o9Rii^u)$p2CHN4oW ze;-Ay?aH=i^BR5iTVs^LXZ!;7uDaNU23sxAWA{^vMFRl|#|8eVMG@S>>UgFwIOm?BW@ z)$mhwsrDJXsA_mo)Nm{6V1+=_sv2HY^&gSyjWWsw;m~uIgzlZ5QtE ze0KgBQiUf!C|=7wtv_3S&4){%jt;e^xCg)XXz>R8&_VGgysO^Y_N@Ldyi_{0w*#r4 zdZl;=zU+&4;m&Ktd+ZWj;xfpIUH-p>E%?p?P$FZqf6oI^U9Gki&eDwyI>J|K|dIFDb|D61WYxuc91I{0p ztJ-;^3{Ziu-YxFJ&;6=+6@Kz-;x+hAM-mD=1e`bAoM+mAUsG?wkGxT?Z^3U<@4yed zNv`jSZ_fYcH84O2?}T(1!^i3?c=gS4ef>|$GkRLRQS$Wt?|h4NXqEzw(|x;m3m*TB zcpHA(yT!Zk1Me00;oZ}zXZ05$uzw^SCh*R$iYIXQH^ja3f#Csc;^>^~_66kLNd4`L<;vxL(KJfuO z+%F!%PaO~+!p8>#35*cv9}*wKTZhG`@O^(EQys$>>NEKK59RuKfWYyo1Qzi6ABivF z9rYDFQeVSo>dv1^trX|~=^x7g6%ANT9R3q=7hXRvUWH#$ufccxsa#(#d*JNXK%*RR zj;S}{tv{0+wcxw|T)YjRsdwO~;_Ujg{<;X%{z7ilgP&LL!^02C^&$M|Uy2XlXD*0G znP>HHQ{DTJ1cvCa>#xK|@R9l$-u$p!KZUQ=<1NqEUwbAUW?O-5{Y}*8@cv)R^$U3G zZ^W1ItLiKG$-li>*8duTy%*(1&YzWcwDal}_@Td(>s|O|^(y@M-^=y2Kg0R|vIgqt z5dDL6Xu$W(#hdW6>Mi*GkI40Hb36ZE&_Krmdj3E3kJ6zFKd0VMlI|SGm3l zZ~U8hE%&tkZ283+sH21XG3n5NchsBk%58Fe3m&Vtw>_(W|Krl3vmHpi{t59ee4^fi zpZ%m<--i#E;vu~Cshj2Ve}I7VY3UHbC+b6Z?=y1!2%e~q;mgZ%{q)aq{*ON^ffyb9 ze;1#@>z@;!!x!occ(ju1mxasz<5WK{fmIR6_P_Ms1y*0f&;K8}-q9aEt%i<%LA(Or zb4A>RUkWr(Md0KYr9%zA>r3Kwc;!FD8}JM2P59A7t`AxW?EbO@+VBhN9r&^TlO*uGs4w8&D`h5Da2q&*+bdXaT-M*|r{0ne?0&Gk=eKo$8eQ9Uc;knjm*2;O zU*03$fbYIXAb}sU`X2nmSH%4Qfzekb(1%a{OFV?n z{#$$i_rDl8a2)_KR_!91ZPP}$uGei0M>#rnG-wI?e z_vkleCOr7=Z+k%&b{g;tJH?yu9d{9L!4G`z3-a-uHUg(>(xC$%+)KO%ckd_eU&s6K zv0fiu2sTrZJ&^?l=&<7fGC&01yH9)w?>$I-48PP6pP1YE|MbHpFtvc5{|`S}Jcc(O zFFu2>ZxWxwM{V&1JlOqo39Jw}`7H4SUVpau8h%0D`A~UAyU&s9EAVUL>A(Mlz?s9+ zp$b2Evv?hTRo#PkZ;|U8aOZjA&D_)av*ma4`4VWMLv%#E4UbnceE>hH9>K?&=n#G;y*^)mV+79YjVAC*>Qnd?^%%aRCr>4^?n`ChHT<@hi93H~MJoG`Gkm!ODn%gM4IJmlt>P|x z*J*k8Rk-&GxxNl>y;9tR9|&G0fd&GH)tm5R>Mi(5^)~$4FKCg%&*=3*4}tR<@aeCX zMEmed>LL7!`T)M;HFBRwd~^Q4teFncVYhaez~|bY!tIb5!!M3x;91Gj_rK$pC9o(3 z(r>?hOU`slctsB$l@D7HNv-Vs4Y`jC_tfj~@o%U1&+4yG~W$cJ}ll1LvO zSC8bGh453~FFr^;uYcPCkK9cH5jr$}P<#mAxkr2iU*1!E3_th7;**Wb`iu5TV7dw9 znIE~IcnohmKzs(@`J>`<_%8JY{PKeX>99m#`cUx|eDHAb1b(^c3+rynaaBQ!mc{*PbDP20B!pDc*#i*Wzlycj@&V zc>9L8=C8C@_Q3Hp;FkkVTiYQ#(e?noTL+HdSDqygFod5!oOxP*BLq&~A|1x?!_OC= z!1umTd3Cz)Jhx5 z_Zh-_x5<4*e~t71NexWVp{+NH;g--0zWb9hz#Q(YFU{@z@9O|73+%{e*xBkdUzZL|c=wuk3qDluz~|cT!q<)@ z+WT9a|Bu~H0zNt9z)e)bOHq4?JMUjqYl*!3OKA%b_+NARX5G=^XMF1gR708!OM&#?g!pdp z7+(7x@frN6`T}0jgqHA8wp_FNTOn{p*RiV|?cIkDk)o@^N9rEj25!M)y}q4#UjH_L zb?Bl)sO=uy-y<{O!|l2Oe5nIR8<+KGJK$&&$k$)2?J>N14;gp@x9eu`?n7nf=J46y z=;!|u0q5_fs#kEYE(0fUyRM@BY(_^qunV^bt_27*wOxmwy|)bP!R@*he5nJs;Wltj zy*U5J3O+iV_hjHc+^!qIm)eft?fc7phGh>NyKr0%IL<%FE119!JV0(Vh1+#Ac=RxR z_wZ_d|Fr&A2*lbUflCL+sc2&Mj+c793%BcQaA&_HLI+M_mAL{f6&kWAp-8RWZ)6} zxcV5r>#c+HgD3g`b#pua?|-&D zfoB0d|L=T`cmsZ3y#-%tqHTEb?%_eG&_iJFtun9=x9bLQ_YpGH5!^PM5&Wi~dUIA{ z>Hq(Wz!R^$J_|S#_@_UZcW|cg?`g`wG5qm*pE=z9h`icG?rHtoJKptrdEzBHgz78! zrBJR<;Nv%lui?kvC|=bB@^SO^r%zDZ4x}?+@2mlz|C2mH6Mp)n4A6on>TUR$cf3eG z|2qhT@01&L;fK-=*)JcSXhMDXiFe8MA^m5?2Oq)tzxr+oMCh>Z?czhYqt}n&?j@O_ z3H;Pg%YCMW=kxD4drnCpE&}<3I{VaT@KAjYud6TNo+h+{pAIym1cANpk%ZRpmb#-q zH(2r73{~KsUSEYzv>ntCIHf;o)!}1x4{kr2HQ@H6SqtuJt+d5A=l{if<%v7!a7Dcf z-#3)&d+_G_#QX4(w!@OA@861IPzpHCP+!duZcjFbPaZ8B(G)&ckKuVjS^dosSZjL$ zKdlKZ;UlXdxYdNCQ*O1AXhPN0^ZK`d`xtqG8ah})9=xmV2Ha+}2|uHWwl^;8&!)7u z3FPa~(}a9@K6U98A$+3k0o-OTf{%YXkYX7jU{g1Rw>6;{ZZoui`+EHn-qrRxKwzXD z9NjSN)!36&;d8yd2Dbqk@I;>;8S%U?q8Ny(1)M@ta$j(IREeY zcL_x3u-5hvenH>;2%e~q;pcSViMgHsck94Y3+VZOpgx0p{~|@|=zpzN7N3%8cj5Jq z%JnsPU^i+Ykm!wC@U^yw@QMyFhc7-Y2`%7yeft0ZB9Lf@1a1R6I*>ha^)vd!@TR&4 z?|)XVZ{?oWpWSGs7q-!%_d+SU4*a5e7rwra7Af4;y}#{Q{kuKs(BBTEZtFgT+qxgX zZQVz3TlYhFw(RruH$uSH{TOcRegZ%EVtIfm{Hi`!48QbJxqkLhod0dz&(Xow{Q`dG zMRKDhyn0kTf!97S?|xml>_1Lj!ClBQv6>kEtF)`|U2l;AYVd`69d0$@!8?KO`3(f@ zv!DsLnrOkTCfe}xktEuIH{K;4bP+hGfgXJCDe2(D&%8&x54X>P5N@9Z1M$uIKm9Ps zK69K19jqpXaI1+C+&&8?aC?>0lBe%~uJ0@^1=3Hyw@N~DxZP+0pXq&;@Ev-e1fJg~ ztG_h@vEInh;UsU!01NF9UZ+C@cdp0)BY0hXLf2Im zZ(P=&o1ewfSFs7?wcw~P;fc1_@P-at(SG(|9rY@_ezK zG2HfpN!ims|D)@ES`Ik2AH?u0I(0L6{jx4sxa|iEc;{2u^=bVr5jg*8xzP%~M+aWR zttK3;4J*32zWWONn!1~LR{z%FoDN(?huu1G4L(r!;Nvf8@xtvxuD#{?`m-}&Z!3_k zzwqNy?IHZofumX28NjW0Be)%KhVZm_W&Mv32z7ul+^Tm1x8j|`t$1U&74Ph0IR9Jq z&e6e6I1Bh#6J5gXgtLO%hgo87=YRV&TU$WS|8~N0Zj)DGwQ}XL@(L>OV=ZwPeoeg! z4~{%RI@A!T|Co3kenj1akJKCRYw9g{<#GA_1E-C^ehD}ocw4;-Kd#<`uhf0`uE)!R z^>a__&!)7cfe;A)lSdG*P*XZ3H(Y`z`X@)i854xGRb>#JPDXX+JQ z&i26BxcU04A#m8Z7ZF^Z6}T4wv*1_`A(YE-y8wkN*8e3N|*3TB*nFY zx85h7z`b7Z<4Y+N+O}K5nZTRw&fvn>W0vB|>cHxc=?8BGZ?!(XPeM0zJeGnjEdwT@8 zy?qF`y?qR~geLHFI`CAzIR7Uah|$453ubWpESSUXvtR+Y&w^Fi1E=~G+4GZfp!ig* zEV1=|O1ECP`$tkkRrpZ72A4x@T7Pu}imex3Y`ySe>xCCvFWk1?cIH|A+cGP*UUVq7 zUU;$f!i%jJUTnQvp0B@R>)i@u>#x{);lqGbj^+E1w{n=C(TQ52kTQ9uWdf}GP1RmK@%OW zs<+_wwR#&~TgZJnaNEMWh0Fd^{8me^2;|G!v9Hm5xb5M6xNYGf+_vxmd}pA)Wf~!1 zd-xD;d-w?M>l2URwuMjNwuJ{%1Z)qF;kJj*;PzWBbND$;XbHD>zY^b^|F7sfPSByM zH(J9_eoS{vEhbyW)rIbu@Vd1+IR9VWDMi;ohvd%UUHH%y@4-*( z68GV|zDvAc_Q0_p7Q=GDsoW?X2JnlTXau*P6^HP}o#Z|vxExs0`Wqu)CzdJP)^Q9! zqfy$-hniwCy@O9P%BSY-V-5wH_W8{S&W7TbZ_H>f_`4l;fC_(f6^;b(FFzw}}) zI&>(uUU;$f!i%jJUTnSQcK$E6UJK~=|Hak|FScHIvGu}>trs2?TQ35|)(bDTUU;$f z!i%jJuIG&O{r~%QwqAI#^}>s-7hY_=@M7!DJssbcN3r#?gMGUVFScHIvGv03XT|om zXZ5eY72dT7LxV!R=>7A8tP@_Tkyjiuw8r5wIT?2XOmYF@oFAibJ^l ztT=+(&x+%J$N9h5deOnwaSXqx%XJ2?=uf)~xZP)2c>et9Kf$0kS`~q8|4V=AjS_gV z^}>s-SAT-C+A6kQcq>q-B5+<4s=?Rlb$GG$!i%jJZa*sqO$3Uq7w-MHZoTkg>xH*I zucu!4wb$s@E514ZpZ*EmdeNcSdf~;^3oo`_c(L`CJbnMg)>{gs|6j2FG1@7-*m~i` z)(bDTUUs-7rxNiYQrm!3-pTu1a|(U6k`{Dyf5B^uU;$e)Ajm3 z+|&Dq0Rl%gFo2&@kKo0r7k*x^AHj>QSG_p@7h5kn*gB5kr*ukZ@VWW|ZueQ1J#bEH zhgCV?%+wQjvGu}>tyec5E8b%3g-b$d{Z$b-p##_8v3ea|Y`ySe>xJ9a+sr(xf6KJk zdeNcsb=`X5w)OVl%`eFE_2Cy^Cq>%d@_hXrJuZQ8E0C=}+j<9Z+j=9oZM{RdZM`FS zy7S8VA0uE}?*wjJ?-XuZZw$AscLujZ@BH&P|J&BPKnL4;mvGy9S8&^U6S!@?YjZpQ z+t%y+pa1vPTY=lw>%wj8t-@{Vt-%A^dg}<-*6YD->utbo>utivT3ao+|N6Y<(m(%$ zz%Yd+?UJ4?nNo&poX_TYhT|gy>KUC7}V_w%!Qd((8wC+j>Xap4Go? zy_4-g>b8!j@FO~#f6W>-FHa^)?EZ{l~Gbw^anP{V)B0Ky~YF!)@#B!W&GT-T~aU-Ux16?+|W>-e81)ZM|c-ZM_q?ZM{>tZM`wvw%(ce z=KOD4?;IU$>s`QY>s`Wa>s`TZ>rG0YzJJ?#*QLPb&jmSG%3HE+y%qTXN7wzw&y|jc z|33%@?=mH}XNl$@?37s3HoF~~wo`&rfzbMKdOYNx-8`?k&(G_=&UMcG zh?U+v+)A$xca=BIzW@O%y#=_H-Xh#eZwcPi+$zKEc|(}E%YU1fi?>NKRxse=E#g)9 zP+wnz@9N0w>+sU8;*FKd{5zv7Xs!Zo`c2i_a4WqXctKy^g z-T-c;w*a@&Tg-ZES$fOafY-cJy511JEWPk(uB8`Vf1f5DJa(SsUlRd)Q@IV_H-D{5 z$_{*4dg1kp^7;sF?0NU-|CXh9Es*Z&j{hfn z5W|axQc5ga0lYnupK6EAGQ5{~;cH7ybXP zf0IA~12*0-D=xw>{I+-rzWIGwP6)Rot(aT?KhZ3$T0o!wZ_yRk;KRR{71!bR?so(3 zZOR6<;Vs*u4gzD{pe}qNZ)>_Rlz~=WHZmrb785mH2-aW=hp*?+x+(7HopV7 z&F=!-rgssZc2;iwl@PG`U54BI4&gSxD{$+qs&IRrSo;t3|JGX7F~C}@2HaY!Cfsgn z+i>fwI!l-O<5_FfT?W$n=XuszMes<#OpmaIsevLg_%I|@jLz6Oa*SORSj+%REO`;6*u7R)YJTHB4Djm8*Z&t z2X3uZ7j8GTJ-ELqomD?^m;ZKd!j1R3tRG@PQ3s6R){0HxL;Zx*3_hPoPRv&>^Y6%) zC9qfp+=f`K_P&=brBN4C)b=X3{ zYIOx}cfnP-mFgPYN_8D>rMjWM?EkG+H!;9!bsKJ_x&yaT-Gy7JjS_Ml^xLNc z78qb(K=gE4+3W2tI0rwh%gMv-F4$jlH~;JbWMM6k&Oe*SMfhPoq$T)JJ*4a3EAT^K z{&kuERRjjQpc>ptbscV{x&gOR-G6Avk&*a zEw2yYTB?)zkAT(cBHV79OK>aIWw@2<5N@Tq;ylSe+heQMRSd9NU4vVxuEQ(3#|^lZ z>gKwq`ERwly&g#1YIO&0rMe5ZyXFXfOgE?xkCVT<`8Pn|jGp5me4##q@0`gw9>eWs zbON`JVo(1I{eR!cj@f13p(46s=+hTANdz^!44;nuKBGoGA(>sV%)fah7qGKX8k zvVdE|;{A6vNv&bY!Ck|W=3gFx!@dEJ>KG79a;OEt=aBEmhg8J~HE@%Khs6K>S!!m+f!!m9mU>!>gw+))Y3%cSN{DAr#ZVk&qecAt8$Kq)v zw4AVxB?q^L#fOJ?m(m-+tzju;J^A-P7g~C=0WY^-lMdchufUh37rrdLaA`o2{Hr6d zEWPk$>4h&#FML^g;Z}OPsi*mGhk99hF<@DG;mgtsUzT3@vh=RGn}5sFyB0|2-?H?= zm!%iJEWPk$>4hhiSLXi=fo181FH0|cS$hBX$CO^U-7Dt*7ybVkO)eh;?AtK`+`b)C zfZMlYituAEl%y`1TmN6zK-mJ?|J%1?Lb!c9rUJKb$5i3V(hG0d*JJ7kEK4tZS$g3% zjXUs;9?>rRw0O(wAz%yY!`r%`0sNHu5WXzE@MYwgJ>>Wd^x%kT^8A>2xD1#YFc z3b)5}wFUZrE4_6Lu+rOrTj_1Wt@O6xR(d;2m-@5(rQ_~0kk-HCUqIKd=SFZVy*;>< z-agz)?*M+WWxsxhfR)}6+)D2lZl!kux6&KKt?6w|5wOxbgInpH!>#l#;MVne|1VpT zt@P%^SN(tC#gcS+46v@(hudSi0B(=z3h+`*mS4vZkF1KoirahLyAaBM+63^=C?>cf3q z&;V|wcL=xAJ6gHSKP$bHRlx0$ZBPt9s~a?h=XHZ-a4WrYc=S|#{=Y!LO0TDf){c;s z-aI_KhjhI@+`8TZ+}o5>R%{^Z4mEI=YN^d*st!3%$WCP36+l5={jo?;#dvGhgeYiBeN&XEGu+lq(Tj?Fat@MuJ zR(dCJE4^{*Y5rSsS?Qf(fR)}E+)D2pZl!ktx62xD1%6InU%eCkzm?t^23YBB zz-=Bk;b(Qaw&8hQao61Xe_K#w0qy_K=z@CioGz#jx6(U+Tj?FbTUL6<2-pTq;HPzi zVz{RpG=*E~ox!!~ZFzG9tn@D6R(f+Y8?*Id=^bXiaIX~-!X!|ii|lcl@;Pk!q~ zKfM+&18MzBewtA~y*7p0=LBbT&6PR);%jAt7VyoMeo!#?gH=sVS8Q3Dhc7fqefUmY zaR9f^2^Qe?)=aC2fPGM~47Uvm;d9-f3VerdP!(>U6Re4^`hWYNU>yVWgMwZIZl4ou z!y7ukJMi5H

x>o}B-g2BJ)0_3gJF+*+$X+~)THZk^Q-?mDY9|3(Pd{2s$?eox>w zzhihhztcZcxJ~a_;x7NK0^0nZV}P|*3%Jd1?}ypswfUWc+w{(_T;`w6Z+{hVTW+mY z0Jqkv0Jqkv2)E9v1TR?sUq--Ms}OFjRRwOXRTaMD<&tzYxOGAZ&jM|4rS}2m=PMloj{j)>`%9vA%u)x6W#q_15y+Z{uvhvw1v$ zPj$M+@NK#SGq^2h4v*b(lKfjBuvHi2X(6%MVXajTZmm@wZk<&Cw+$+!p60);V4{0g z#DERmpc33#t1{f4Cx&qAtSW2n=AX4zwY5Mx|2p@SyV^S3J}20O_w@B`xV2&tym6QJ z%KYyka7R;;t`FaJo%jH5cfmurmFf}PO7-|ht!(A8T0Ox4y9ha4Xe5yk)gIK)`Bs0dA$b2)9yQf?KIB!?jem zybuAa)fKqi1y|u#s%vm7)pfX)>W1?q|Ll+s->D@Q15W&=cpHB7uy_aF&?N1`EBg9q z-P8Qv_9j_SZ#|Is#gB;h;hV?A2k;Z`79YZ`RFB|?f9th!{U0M>wR!@#yWlB2na63l z@MiFxdL-uXy1Hlc-%f!oD5ncF-=PEY@S3_0w^ALztyCA5F7?N=T3uQO+zxrRL1p+h zU2zDns#oAvs;ls*r9UoJL%?cv9d4z%3D4!ERJY;rJ>=AM;o~jhtq6hL9Zg2~9qN6! z-31Teb{9N^Tj?E%ulj$x3m#*D-33qJR(fN&mEI}bO7AS=$@#a^JI@4G@BJ*`R(id= zW=pc&1?S*adh>8sdDHy!5wOx5z^(Ka;C2^Wgde$8PGt#hcfsYvUH;oNv%BCB1MDui z0=K*1DtxNBQiJ>7mJO<}T;`vBU9PzbxcO&U+J>Ld6?EXSdKYeY!4ce#^*0}S2-scl z0B##Jgdf)xkKhyaG2HHgCoKf*E;xqUUGNlccfoV`ROj~sKDj|ofp<5Z|90-HH%cI< z0ds4u@^EXde7Mc;0B)UCA?vN>&u5{S1umUcl7CeMY<}0^ z)>_r!HoqHi>#Uk^o8Ilz)BLwXZS%W>0oGb|;nrG3aJvic!L76EueqCl)>;kL0_ps- z)@lg1)@lT|)@ls5-+-CG{kObU=6{U9xmzR|r|@H%q%(M=ub;yY-XzOe!0k6+ye+M4 z4Y%Kb$?5d5Q)9mYlZRVt<-<4LDk~1))>#$It^c>ys$>D}|7{+Z;T1g+A^fO%6>iI^ z!CRpYs3UMhy#cq@stLE&stvc!steZ*YIzX?WnFO(eptN^x7KO^x4YmW+&Zg~^CbW5 z99wHO!GNB&Rx#Y}f@kodzJ3lb>+g$rcVEl7H20NQtjqn5do{!CAi%Mm*Limg>Wm?6}Xk^>fQDJ-%f$m>KX<}txn!4fm^9=z^zm_ z;Z~~KOPBhy{0c^A8A$8j>JyM%xRvS%Zl$^hw^H4QZ?^Q`avLCEwR#A*QayrOsUE|v zR8Qbms#`Gvb{9N_+g2$5a2dSs|S4Y4W)PNtf z2NdwWdK+$~x&yaT-A&x(za46;)jbTb4eG-W=!ysMp861OrFyh-nSWNR$E$!lC045^ za4XeQ_~71h7d(U814!?lYo#|?L!8s=e-44srzI!y@O>k3pRWImUjSd0UbuD1#TEj~ z(hFafUih-~!k48NzAU}!%jf^g(u)Dh(hFafUih-~!k48t>#bGk%?6eqKJUVpr5C;| zz3^q}g-e&54nGo z_X>Qk9?>eiqh7c9Z>PW()WCo}I-m(}tGD6H(hFafUUTdJm!;PN+W*@I_2Ij9#RGU# zeF$HcUU+L+dJ$NbUih-~!i)FO(hIlJyMRyb?UFFbzk98+F-^M7&q`M3;QnbX$#Cm> zeYln00B)tX;5=EsoqH?2MGUagTY_8ZEyJz!hHxvrm32?&pOxO~dLVHty*0R%-a6b$ zZv$?nw+T-lP`LTuM!=p>bl_HcyKpPL5!^~|4{i@A`u9TrZ>4vD0akj4a4WqdxRu^9 z+)D3c>2Cj%&w6Nb#mhjNimOjRPT^bsT9R=FKR(uy4499=3g03J3 zk3TQ3&%?dH6!+m)dIR|EbMpFD0Rbz$MYxsTGF<1e7sB&;L@V&U>NW9I|8EPbV?a&^ zG~j#Gn{X?=ZMc=*PR5h-Z>2ZN1d`8w>EC;BPgmTB?^Ykct@IAzuJWe&H$uQl?-*{S zH-;BBr1VbVR(j`fdvLKx+~vPjz{WQ<8Sj%V$p`*PJO{V;e)4d8@5hH*=?zvc^UvP< zDXao+`q_IwMYxsT65L8}8E&OFgl{}n|NXBD0#w>*3A zC(Z^u%hD-)zb4}h-c_H&?Y*A`Ts{Gr=AZuRmCXWs?PHT4^&@X?{r_3rW8VVW|62hG;8s8iaH}6hxYdsmyk!NXjKIMSIcFg} z|C8bs_~A>$YjDezI=n7B-0~U-9MdDwgy(d{ZTNJnthfVj{FHbE@7!NzN8fppe|FAn zdJHkZW=9OK+*f8np#QbympFq0TJA$Uk`56uMfBBH-Ovp8{QZFzfHdp2H5l)!)^La;5PkYxJ|$5 z(xv`*UESl^GLY7>)xUr~huid9z-{_@dWtM3Z2INke(RuoMmvwd-nYv+^Wkmv0N%V! zUSEV;u9VVpVSLyGN4XVQnzRZrM_^SW6>DR#kn>KxTn3q{F zfO{X86%XMD|44k4@#OrU_^brRnLzT-Z+udG0=HkUis8FX%Il}_vqSM2JQ^pS=HDEF zi=UAJ3;32Vi05?AExGJS%z-Fsf`JId{#De0B?S^C4nIVy|0Q-;8k5g zUjJ)HF1Jl~Ab{8P??t$6XxKs^&;?cCw&EJRuCH&v+v;ujT>l>Ff0zCL;cvt& z-1-9_Zv8<3xBj5;0QCRXAQUlRzwU7fZtZy)Zv8649jr7cU4fx5sh_~UbfkFp?x#mO{zD-vg(RIZ=_#L|9K77wz-3GP1Ap-uxWZI13 z)*r-hyGAVF;Z~Uif&SNWYvjw3C^%2@&jPUqiWo3gFT*EWWkD5qb%*Rg9X`~*H`YDP z|LS&GP;)(y_zCqke5~G~KU|j6h1(uS@N|dW{Ochwexxj@4=-LOK7iYi7{POw>8XT= z`uFKp^#8>N$~l{1KyZbucn+_rFW^ViJzbui;^LLEoZQm2{@5YPF9Yc$N4J|8~Ew8V_CvOt(!lyTiM=b-7;ZPord09aKKdfGW&lft4;S2Q;-fI7(te}Fx;%Tx$b@;Bw zzR~Sj1Kw3{!mIC;*SF#0AGqbWybb~w!cz)pHNYCfC;6<@G*1 zP!HgTcgqniz|$mk^RI}2WoZd+Nm_;<{WV!Z2=|{NUV#tq_BOY}wTGbpA8Vk20q34B z3u?kGNjq@c<1XB$WwdmuKc4MzZy9hK=-D3k;kL&Exb5)}ZhJh2k6XIOF#@*7Q@HK% z9BzBOfZHB>Kb_4X+u>FY0o&s|-1gXq+a3pS+v6hKPH|a$)&JWbhZtacT!Y)Jsl$h# zk>qN?%a0UqXFNIoHqAPjK+?V5A_KbcP#4sL=XCn@;bYyP0lbnfC(XYR0ye+L@K_f# zfmd~drf{nVGx$uGGf&**zg57RF38)SO_rUyXF2#n7nFzBbvXgNq{}I+T;^Xx2NYKU zH~-q|Ww@QP5Z=|-SKyI)4ZiuFmXy*u0(~9OfDhH%aND2`e5|kU!7X|FEd*j6Fn~|h zM{ry57{1WgPvE)BB&nzB%l_Z8cZLCh4w%D>>Ryn|6-(Y6Jk;0cv)=Nm8VIrh&$71w zZ|Lib@V0sxZpj?QJgA3oC~ z5y1C7;5wQA1q4p&3X1TZ50e#?;8S0`4EHV-58>qpidP=mdapZ2b_zN>Bv8eG_JhQm z@Zn|RZFu7$;vM+z$B1{$t^ePzD~>Fn{eM>n^x#__Aq(omcNfJ6@Y>IcPvEUxpOU1A z5$LMV;O8`n=I{&p`UQN?r)BxMhrKs*q)(rBp8WeC2<*^v@57I%2k_BDWzP!mBj1)4 z7vYxFCFe>0*}1o@E@OaYbqKetuE3M5c6(ZdTT<87JiT*ham(rk+_Jg}x2$f% zEvY;3{Dr1m|N977RuABo)kC;t^$2cBJ%(FSPacN;-?BQ!0L$tr+_HKGALZl}cn{Ae z-6<_lxur|}NuE^7fYLJHPN8>)R<1JKk~D-{l2+iBq*Zv-(u!6?z_PRswBUk^9>_BnlGXEMHsICHT zkDBTY_`$E9Lbfo`m+Bo9hU)}A2Xm2FY1aX@Ur>>UR4h+ z%j{Uot7{<420Tlm3cRD)-hkU4H{rI&5nOgS$-f=~HeduV>l+MXxV?S`pG@S4&f)g@ zd?7g!Y5v>vYkW)w_-SCxZ9oZL`-n`lGTdHYgV*)-^)+|%&jxhX0_g@cbU+twuOGno zZ^|?q!prItcz^LGng1~Y#s8HBP2r{g7N5bR?}^XhXD^5^;Jg1t-1`~y|2uv|3QPWH zvZr8jUIvulgZq)3nmRo9OqqTibL;DPqM_4Pe??oK%pV|ZSD4iCgzp8x3VmKJqD8D99Pte_5Ww8XpcP?s}= z+j6GPll-&kH`6`K?aXeF?Qs!4n#+o-a64r+xSg{0x~KWy(Jk$)2NIt=L(XL%9_i~R z@Vfc}ZX4u1Cc9(l2D$kcAYdz~!0S(x4XVMtO*s;6c)aD-w2XLtcv)XRc?|mhu?7|x zFi{UK&+dUGX$UX=KsKlWFR4dMm-^#bqcK_r+=hF39WaAiPUIh(-5|?}65MvI2CuYq z1sw!zO9$|-zCMQ6)xBbNgBt1uxNT^wf`A>;Cfuf34{i$@!>u07;Zxlp|7YEXuKIsF zXJrX2r{!D+)Zq*DE=Q_WA|9s;>`zKD%Qz^)PXl|5gF(8fg5O0TJBJ@d)15<;>uNAIYi7 z?^_=U^{wY-TgD9i>t+n@$K)YmuRkzOq$cvWBDgUjpF`Hw); z_6%NEpTlj%`BG-jyn(*nhuiDxsi*mG)6WiF0|V^PP2gMaFNZXSNB0)bJubUJ3*DgN zn!EXzyPKT*>RKQ@i6gy!x8W1JuEVG56Zl*`hI`M_fB$E}z};nog2!j~Ag><61N8>H ztRBHD>b=LK|F?NO!hoLc!Hlj8n!{~5`CrWLfOS?SbL;;bx}cf`tp8VUz)O2&!A-dL z4DmL+uHJ#SCK~7>Pk+E$M*lz1b5_TIo?c8k@WDN#P7L5<^%y=^_jE_@w#C)IA|6a1kIZY;8K|wu$$4`@-zeFPFvft$}^JvwOs2{=do|xSOdwoFvqRtw)ca`Ky2=9KRCC}+92-pgm@Z#07pa{M^HE?@a zJ%Zbj7`G6x70=-IYa8`Ou}3dV5TpvjuM`DX(bYk_qBMSm^RDR^@B(6z^MA0NU8>J4~9 zmlMI0StIkmhrn{$z=vmKgJ$rtdj2Wd4UN@H@Sbi^?J2G70Gr2k46qIAz)QNIF1%Wm zIx&Ek_4Pw@>;DH@SYiuk|G(^5!t92Ix}XBQqF#Y_)T{88UA3ABG<855-qk(p!54a{ z`*2(S7@n8qC*S`^ApDY?V_(~An;jMPGTi!xI^6n(A-wzQ8{M^Kt#R<9vl{r;IpsDk?XPQzc>j5l?M=8XrwzB|M0?TyN6(i9O)y}5tE|}5Td3uR zzCd0d!Vesk*H_@hw~G&!F7?N=0mEg$<%nkk=J4@Xw%{ztup%229{KAcouPOM0Kr4JyO!^*!-b|8Fbk|Cj+) zy^FOKH2+RcK@D!Fpbc;9>-!l`&c8j|S!4pqzYFjVO**}cwH5E^ir3)w`a0ZRKZKuo zx%U4f1Um1M6$JWRz*g)ABzf8SF;Ph?(*MO(0lXuU7(Bs zryp=X=OKKeudl$jT_Ufq!pFZQ)3vs8oqsRB)2*Ps3b?;lA1(`Oz#G4&1qa^#bkU7# z!?%6!XPtN8#TU0^#a#rBe&VOxfC%3B+x-@Y*@qpd!3_Jl%mL z|4IlF;|9`X~17;Yo z^=~96=J37u+U_=J0q^Ln@v6x=PX5>_4xb`9ku$gcfAT6hM0pEn|L?y?2KeyP*U6Cx z;N|JhxfK@Rqq;1=2yb0{vg~mQfrcha8D4pdkd@l!Lww=RrvH3&Rbp$fwT9O zN>_&$hH^D)z>nPabhpP%_@pK)Zo_L`IielsN&eZnXWDk6J zVUL`e0ABtjIT8i{;_tUFrntyo)+LA0jy#69N z5&^uRCAI)R_`+-5ii_~hU4F)SDRGzoRsoNEN&;mJsOj}Pghy|Z4Xwa;K1ohx6~6x; zDr2#@##cyYfR zx&XfO&mQJpUx3$dl?^Sz^H-#&EXltT0y}%M$7T32EjS_lS#rIvzz_VA&I0%y_mU%2 zOFhkhn|}WFvZZwli1gey;5+|E3RDx`yj-r9ZFv5tE_Fw!v*vF8^|V#$t_9Lp`oAlC z5W#EO>-FGU|5+|(efW__$PpUAkG-TI^M8oI-dnf3Egiwlg4Nc{w%S{_HH6>T`mex%K~xy>fNR zTR{8&GmnvE@!?1H3kd=Ij(?O5D!}_%VTqyC_}azJ;8Xo^x;fm}0=0m5DsuVuUYMN)!@rT7$h{E#|KTsmk;r2}=~{U> z<-`3q${q*sGe_hRO98(5EID$;rKiU~`BT0A3isdAGT{E|U3`Mf`!c+H=Y!n~LU?lt zeR5HW;FG(_sp-L^hOD>`?|)G$<3N1X|95rIh8Ph4sw`*(AL>J>F?`>D`tC?f;QiN0 zJ%}@&od57e(k4$c0na;7lUuME{Ln2oyA{mg)oTOi3wZB7lGNUdva=wc)|)i{atK`f zo1Jb!dHDH`96BG~_&s@;9KicKWyJ;fxmU@ZQ!#Ou|5gEOnsg-$XlUFL_xAiev10HMAHQ^^tUg?(ChHt#BCDX5i z!1Ud6?z`}<`tke-KEGN{K@aX}yWNM+&Tn@cG-x4^yX{gJ7{cRF&ix2};g~)Vh37se zE11B;`yO)3kJXp`f9IG?vnd9gdST5Cn86!4sRwg-Py2%fJkpz5@5Px}ko5l_l@;f* z0k5q|mxq_Na{2JmZh0^nz^j2Ai2{7|u=JEA`By~Xz;mVZDZ$4tmklk$3m?AS9ib3D zeuP|vD)5@_ST*%z{mTaAzC)-a%=U2h#;{*biW4R~zNh~P7=EA2H;*YDMSBv+@- zS|IiCsO)hUKGX*h5xk=3z6T$u_u-xIJ<6@$8z69Ox6T51^{{Nv2)_48(mjviC-+Ei zIDtoct%+aU%4DM#Xn#J%fU#D_8GP^^NxC^a|6J*O7VumxNDpjs$aTHe|9kI{f|Ij= z_W#H4CN(?{@93=Y;fKB$xa9}%ll!FeDZpE0y}T9?*rV@)mEiNw>nwnGJ}VcM5I*^a zY)}QBf4Dnk$?tz5kUOUx5xn^)+ufek;ni!~&KvN`TjVO*gr9!trh9$cd6Iv2^~*g~ z=4%H7Cg-HYcH!aQ_-;WF{QMDV#d`45x5}+tf8Epk54C9=tOpXW>&0UTpXt?d1i$0o zB^k%?nohq7yz*=Jlk0zs!0bwyPE+{qH^@1j!K0ES*BpNQk7PLuc;y-LdhaFZ|9dyd zq0YS|J1vX)o=qO^e@sfR51)QoRuI5ry-_JFUFwflx~FVuaT#!@)|>x=cnKcqbGk_cu}8-HsL*eeXEVY#slSfeg{6( zi%J(BX-^lyhhLH%>%kX~lw$ zykD38$-}3c`iuxZ*K-`ehuVM?5_jvj3beosnf4qnwao$~PJ zL<)-!-@RLwAHefpOOrRrzXAf=He^dn@TxvSEyK6{p4=~l@Gb9?4-Po-#Cp{l!q0y&?-n$Id;0G87{2k3TJzxzJ#z8OTG^yq z{Jor;DF*aI+2a}fOj)iSbNIL-uV299M@gyn4(NKV|KD1W(wMV=_W#Y_l?RP^c>IUb ztorauTknG5ix0^L72vJ#Ir5RoA_9f8fjiVCxNoxnzJK;u_xcdNO>aCZ@Sc2qFX{gg zD0%Xnt_DB%IGG)Fc>N}M2-Ses%Cg5zc>R0Z+=jNDC;4a7@9aOyk?3GR?xfU%F1)B0 ztq4B;PboM(c<$bkEB$p(^FP+ld=AzFiI?;$H-yIp+0YSu*BLnlV|Y(DbOJ9Y{ehc* zF#;XEzn{YEZFx>GgKxP^-YuWQLw!WMfRD77^j?nsf1n*p?&aBOnbSL-JiM!KF!=CZ zOExrsAAO8?Vd+wTyo=Y#yeuvQE=RmQm&hZT68z9Nq_C9XU47dQhu5bvI~wpa5$)&HLfzSyh87Zc>$eJc(^YZ{R>T1RLsF7U@Y7$ABUFYr^%@bvr&?DkE0_7V zWv8@C)m6Z4VXTcw4elS2BTlrpFL|{J&*EBlzs~axECckKMe>?ePS@c;2OQWYw4b zf9DCZXHyJ_4vNp<+AI&GL!5rZ^sK{LAh+e+uXR)EhrCf z>qW(f&-4x{fKPuvaLXyc7w+ns{bD`Tbqw&dls4c;Uw)(8vnKpdUXr&BU+8i=YwqUXW~L}0A_`3Uaoz26w#(3{j4J~=M8>r?ot_e##qUWxv{ z|8~jtIR^AUD><=%&z~-@&($+o?Txe^!ysP4tUJJq$SeJh{B~;iaim zv;lnnaM{oy+&?56G+OsG|93r3YWsLSkoe&DB&jCw@~5`DBNW2}{b0fr-u+)${tO;I z^MP{xpCb_8C|kOK?|+F*8}C)wY@dvz5ar-~E!BB=te>3nUxogE+a9@^1sKpD%j_t? zgQv*ri||kjR0&@GGdXhQrKiU~`7_qi7%l_ihjl;&UeVWA;lo!;2UUYlwI0;raqB~J zm1`hSd6o44O?dT3GA-Ni3*UQ#+u{y9riNEJBDyib7CaE>i_HdCA2XHOtrR8;0He5bbB1bk9|dMV5acGGofUcE)8Wr6N*xFb=7 zm-QXc65Q9XV3ZSg`EM1lsCOzM25iPsKq_$iN9d|>-yYk;y{(c%^_9Ezd!tF<_Mou} zxW9MrCg-dPFZ`c3x_BEtc#xd34!o<=wF^IZc}rFhA+WbA=dwrF$Lf8!cTx(`0Dkef zY|s#1c!ypKS_n*ZzK-F6%>ww|eUj}lJp8O2(J6d>R-Px$)R+B#Tkp;07_j#m$=(G# zrw^yR*JNiwNgp)k;CsGxy*p+3tS6uUxgdqY&j!3**T^Xd;K$x74M+i=`@eFii|~u@ zl#5ddUUc;)$-goJ`@ShF2;t-R$vLaQ4{edzQH58pmu#=W7g_=9si*mG)35zXDZLF0 z80sNy!i#ze+VJ_`cHE)v!0$LKyBXayX@+uHR`;PGAL6vXguN3NDrc>iSJc3}1z^#9Rya*pR1 zaO}7BS^#f;NRre$n4JYX-mTXHcwRqWlsC8jf3Lp#?OQO?ar4u?_ECulEJ;i+?N66T8ln{Ils-w&(d6u%ju-(t}68E_>XE*Yqkn zfX@b!q{DSj^S`9`W~22$;*re)_+aB!cWNf^ramc+;RSs+Z3_3U-YVDs83H3+!5rSv zzI_3o>c?}uU(e2hs=m9PgZuhT==`sv|KGT`Ofw$?4*g)e+v5OU&_i8-2Y1LVTM^#* z3z?RsrAz(sCil=;unf5Md8h7>4GQ6T{r+zSp3|S#sKOgsxN7ibOE0^11ZrQGXTS~k znS08`sR=J@VQIrV`bf6}U+Ck$Ru_TNUrJU-@ME9R`vUl>ujt(|JgCZY2Jo?N=umvs z|DX5`S-}VcCXbM5Gl3ubl+5oKe)t#UluhAny(gSyJURc3`^pODnLslAo-e+DANn)7 zsCciv`B~P;o@RPS`w!_Q%)@}(N zXgw$=?(*L%U|tJOhyextl4%9*KT)0=R^jJ-X-aGG3sbpv)K@O^@8YX`cZeFRfcyJg zH>e3OXg}YEZ+*+nZd?a`^vjQR-i7b~=ayUyA_Pu7Qj(|#AM6$H!;k)+bV>tw@NaS? zhVVU4klY%z5ZL@#nfGIOyj@m2fj8eL?`X#GjbD=4G=*>drrfB^)R+Cgw@Vf@$ACLt zD9N>eZ``1>;F|0#*!OkW&>TF{r(gN3x4hn;2JYPW*?>3K4+;kG;32ZY0(_+J9T(w) zugMz{CAgnYH#Et=G6F+=V=;u6H5n`L?yKa;RpGJrk~R3@Kb4%Qr=I4&O}~L&3mO>E zEz1g;@H407)U@Hgeh;t%4=#n(*f5+}43yRhP={Y(2QF-652j6i_lC%%s`!OlW z19-tc$N=B}>W9nxA0bftWx05a;b%MTbi2F>+<(LE&SUt#iCosF@V$R4g=lsS`hQ;^ zvCJ{x;7Im(0Uv7v;x)3fz}EtmgZG~)g)VPy{ePs{>s!G3|C?pc0(kDKE8HFz;M=-# z3X1TOF24kC<<3ZdUPj>19r9!(ga`U;rvfkP4Mr92e@8Z`2A@esl=S}y?Ej|pXbt%0 zzskj?32%Qyj!+wZTp!VMszt+284Cs7M=4%h${iY;QAHL^BZFg!0 z@bI@KsfX*H=Ku8TvY^p=AYH@}`7qiT9@||oyzrBkx)sOpvVQMp2H#oH-~X8-(7#4< zVgVm&5_zx7X8Z9+%Mr@K8&}JY<>A#Gm%9!1Ux)sGrafAK0p9y$`W4_C`bp^${OD=P zp)&mBXQTp#OPBiN9sCn%tt!ia+d%K)H?_lo9}eXzSA*~R9p3pZIrj~CyQQVE zi9oEs1<{5#w0-WtFT7J4kS@IP`?ALoe4Bn{qt!#;?9sN{g8{s%^L_~5^CCIaBlwAf zQhLYmlW&uEzbE3W{{M)!&oKrRV>#4Qcu5P+3_jEDc@A%ULQcUVI8guanu)T)A7n*Z8P(rR`O~CE=M* zNnz>0XZmw|UHW%5+u`1~1Gl^$e9N7!T`tf^;PAKPoDJYT&50qr_{;M85j_6OTio); zaPP@-iYF}u7J6?M!|(W^9O@}NuZ_kGKKT!ML_3F{|DrZB>dXFr;}_*ndvCxj&<)DL zE9!ap;Xje(`0$z@xghJw`~Mm!WCPxTft<4<-1~VsWhMB5-h5>3(=~c=@Grq!({M|3CY~3L5aylicOFv!H)mj!+JM z;IAa<^6(4WrBwUyg?<_)cq97%ss8j@0Rx8mjiw^Ju7|V)uU;ibq72{j!#BBP440lB z|K!i9pOfiSSq9X<{9yM#Re1All0-H5NT+cfzNaH4yaA6}FOy2tM4)cJSOSmqTz23i zy^2Qgsa~dg@Vx$>NUM*)B$Q+vz$5)S%@BV2j=&wE5j@hLS{lO_`h|yy_^SV(YXONd zz}Ju6PT_t1?#B#XyIyYN=kUJ%aKR$u$@w3ik?Xzp8`*5{===0Jc>R;I$9Z_HzaQ+w z7njNtkN|%C3%>UM2>6#tP88vXo+>4|1mAdyl;kq};>dyqS2mBd~CTLtv4 zYP&!c1BSP1w!^#nEw?({`)k>t27LVIQYV@#m-!cdS`KM@6>u9;&_198@9dHVb>YFA zWg18D*(c=`_uzvAt>hjo`O`;W>+fs-4;-@f_aKO1e;A_WxDgQt#UAEGX-v)g1k+a)k2m!t3O6?8DFL zGo>KwEpPMEy>hOz0k5a^pa?&!@B5YDJGb83EvF1G=(FSy-n=D9UZ3P&1%YEJJy!;qhB!)->SNNRC`H^)&x&`W^W5E8HHmG2p}%Qqel_y^oP*vJ2ne zm0XG7Cwy6PZ_VBO3-pmme=U%1$sKQatlOXgydu4uH-rcGl>T4@pX)_v3?IKtzyCWy z;OGnF9gi5^*XcKf`}$VP41V-?-{^K=4(~lNDZR;`#kJ`F{f`GO;5D&Ic@ z^+4j2C&`hR!q2`}vUdjG`66jF=J1WY9H9lg{*gz^_20WLo9$iwzD^DvzDp`v9zN3} z(Kun-?QBvq9O)V-zqCE!AtsuqcVK_Ih_S`y|Jk*-POP37VKtO zL3J5$+u`}v`M@t+*KjYW!<+gU(FT0mDShSxKiGPy9HKS?@o&fmb>J61CKsnJeD-YF z;|Lz;50UlY`_9PgTYUto`qjz-{M1LKnH<6o|AE}DkKpmUBpJu>g5Ehz#8>@)tfeu= zfbo0e&`sgTuaZ5O!6R+k=kTc(v_-~~^FR0(*;4OK*;#Pr55#lu!n@=YCm5bsf%~vBW*My zc;)MIM0@b&D_YwBBd~cy?}FhMu9j0Ugdcr?es~SO@fvyk7(RWB+^9@i4CuL!;YIC+ zr|?B6jmZqYn$(PEh=OKp0Dk55x(bJzB~6N_`Y9}BT4NrHp#yV0*gP>YXLmGwk=5s zKhu_JR)?SbA9)L=0k1tra;}+rn*TQa21g{@+ZfQ)0@8smG$*?7*+_OEf{(TI_SW3Z zzp5VU{#qd2)t>$~j zwE$jzwc9^$4ln2tU0jd;f8Re#4fhUbXF;T&3(CQB+TG^i-r?Kb4*2l7J^3`Z{=fP% zIcEh6X#Zb%f^1L`UVpXD0{8`eyjF($`eF4D-uk;Q%R7`61P-5+tgga`ZT0teqL7oj%%+zaL0ci>}fO1tp+UrI7Y@QQv>q31lw51W1q zeRkW&fUf$0en3va5FY7|(vRS?tK|rd*FDY8wkFGDJ&<_r{a4B?fFJsbJjI^EJ?(I2 z@KbH6jB|Ltal2gq7YH=;D;VAl*;$Z#r98#X!Tb8`C=WlYzZdGmV|`OAxB>ltNuTEz zFrcSigpW^4a+TmC{d9X7UTw=M2$wGP!He`4%__@)JM!N7&r9X1!khY)tQtJj4Xwj3 zJYG7V20U)*v}qzRe}yy-ZFoGF+0lVd^>cz<_?BnOiX(Xa^HNt@Jp?*BJ^JwJb#fUU zz^nS>RYQ2?VQ+MYa0G9DSZ9Iws{b!&lR3eFp59!>@TxxZnZhGYt{Hrx-yfQ1JURd6 zf7$M~bdd=p_k^#PE%k29&VoSSYRSQ)kH|F3!)J$O*7)$lpL?)e{{sXfyFG@-FY(=m z7U9vg*Eui2tNLbk8D4&pJR1%ZclmD>aHcD+V8G7blWA6kSH70)LGq^tkN-$Ev<^RX ztsLpb%H8_C`8{L>%~ilHxUIcm8=m`~+=6xB;XCBXXBX}zl`j1g!H@1~$^7mi(Eh62 zmiOWQwQ`OJ@Okxmw}K&jrv1SPzNzmAj#~&+Un5C3fsbDy9>dGpicR5dEkrYTLtj5v zU-tiV{r7to7~o$gcS0UIr5*b5+8n&8(>M<=>Ad%|-txLSzk_VR>px0PO#$B2e@3SW z_w@69CHU~!QZdW$9e24jIb})yg$M-tu2uzp@$E8?tMJjMBD2|i0Jym z0z>$@Z^`mU@Qt6oOy>U>fs(FZ0zdgFSx^igYFj;p$J*!5;B75*^A-XpeqGMx0$vCt ziM)39S}^?=c?O(=7jKk;lZV&sb3x|T{~vj}>{(y|?f(~7h!^19`#m;2LtYVH)Y(*m zpX*6wEW=v|^jE7x1bVuq75L_Bq#jh^TlHVNtHC$*O{zM4_)T|2lh6Ml5NnUtgm*N1 z+wenwDxFLRp3`&Rg%AEPa7Qk3p5&iRzxh$QEcP(q^z%2}fIfW3_vNBBfJgcvwIRH$ zNjF~iH2))=uaosa;&<$i2_)K=5Yt|6P5cSipcY`Z2pA+}CEc1fP6jyIVmS zzV+|rh=xm-`s0n>CrMOU2HbehzeTS1Re1Sf^7l?(?_j5Ynh4bO zv0EEnd!#%K@4&12nXoQ=_Gl?+5j@tfX196>jDJpUJo@l0-;j&b0KW5i^7k!*)aIj6Cc61{88Xu zKZcjTB0Dx|A#h|Y^E-w&e@&j}PvN;2%7SL_;`d~O=J0ADNxo2D_W%1oE7QZfIXer+ z`f1i2ynK_qJ`eZK$sYUg##^NU39{bu7GKv6CmZngy-*sBBHaILSwRUt`}`{p#?c-tjcx^_R+T#5Ge-^WPef+;iXL z_MnXc#s4GowF3{HEjJ`xct`K?BKXE{%J2X5)?DUaPtIk3Es$=>Y5hUL0sO%A+ueo^ z;nPihFBl$ZT^YjbR?HF)8SJRhvXOPY*Lcv;@O zN%V&~@Q;%XWB0uMs`?_%Gxl)OVibpH08u{#Up?9$>(csa(y5@JN3` zeFX1XpAR4C<#@90Y5t%8hD@h;J&^d$nKT+x_=$(g9?ameCfyvqI3dZnfbV;n{{E+T zOE%kU_m>-nJlxYa9DR6IzpNU-_wAM0QGg$PnU?lj(Eo3HitKR-1IquPSq;yfl50l@ zuV}knf$#r>yuP}0sXyM}8cD9>>6do9ly!I(+&UQlOgfvu~9;(S`?Klxf_7*IJsr zT?D3{ev%nJ(8p^%ctxL-_Ths+l|3H7&+GGm))0Y$eu8NP&wpDMG=@+9M+(sdUiYMl zjp1E=dOj6j_5Z$pzh{O4)mn+@WLNTt`y;;yCt6HUkQONJ7qu_UV5S&i4dNaVZ(o1AI}&a9OrI%rRxa~z%NOL_ zbXNhlfWUr?3cll^l3YFbnZr`J`tZHKDt*8J9=*RMEzuBxNlhx$2wu=fHDh?7dp3d3 z^&cLK;r08-5uLUWsOsG!vH>rrU#BUN#$}^Lnvq!mD;u3m@7S8B+=tGr?L+pwPbb-*4)j%9eugu8LkD=B~0|p}<7jKYxKY_QO zbF15+7@mLVcA5WE1lo_6%kd0em`JwI;kCBhTrS`Tw@T7^o$M?aef4s;LAeh4|4=U; zc?>vnne4F-KQfd<9l-l~IWE9=?v>e5G`Idg)M-|-fcF0j?c2-n0~I+EA-t|1GO55f z>XOt|cq^wJP7Q(nGvp(g4fv_Q58R<^!n-%gH=*0`h28~s;M1$!eMIv99|DK}OAd7e z-}iFgt+)p-K2c^tA70Y}HGrRfsNC!hohSLXoPK*{1!D{t=|koTysnR2V|Y!E=oCKr zq)g-4x~KU+)c$A>TgBuTsQa%(7eJP`sX z?t7!#f*#!eZFzkkeo()LJAj|o=K(|bz8mCuLu-UU=h0G1$M836Z#aS1Y!<-%g??-w zetf4qCzy$^`v3VS^b^Y%5Z)-)f(88Gy(Q_qTeGv^@EJKmIryIQ@>Xp=ooH- zf#iDu&y;f(!1GTLFTk7c6)(bz?~)^0f;ZD^O`3mY1kT(?_Be!h9wK{MfuDWKc9$zv zcvXLLu?9c;XgNal#9jVd1#D^oX<)$quljBUO?c;z1Ltk{v3E%Q=)jLW;1}HMyDN9= z_qta~VTo1&_rj7sD(%55`uV;-e5jZ20o>P*_YL9uf2*Z^J_2*?-Nx{GywU2#ik4#bXYi=y zVgc^!^}Y!2T#)HkGPnN!)HO0+%NDTy|Ebckgz(unWe+Ow+8(*QR^c6;9W{7s_e?H} zbp-Z&SXR)0pFSrW+JsM^A<5N-pVZFOia(WL)J;OOIIK@q&6Pq%yU&1c-;PJJKV z4=!~+fQQ8U%x;!hgbFHasi)iljV4~WoJS6<&wNPc=08VlU&Jb;SXE%ZsI9 zDZpoX6)nQYe=Jwa(rxJfr_YitEn`4I7Zk!vS`RAlQ~P(hb6S;MLae$R2kQn0{QITtx8P+vW8=cwH|l zefa2JvYY|@Kx>G={Hqm&I7zmkj47=9?0Ix&IQo+}#~!+ZLbtf}~_|39Li z*_vU%@NZ>H=kSR(APe}Od&+e6-jSUJ{hQ>8NiO5b`QQJqvS)rKkbEppuLS`-*2bg& zANFLAi}2oqwC2NiUX|olntx>kf;)Y83PN~apJ-IzlaXAetMJCtq*T}7hkjm;L_Kkr z|5gFF>Ep5n29*9}yW5~9Jkqb_x8XYhR2>;K`izmQWl zYay`p8o3C~;gR+K@V&>bbUWa^Gn?%LeH5F6kMxVpdG%%gU%Ns2a~}g{|10M#fFJ&p zcmaO?-{nXY;Ztk#v)=MLUyye?!)(Ai_WxwwSK#4M$=)iwpx+Cq!FRt>Hna}k<$jlbhuu8bf$pKTS7Ub2tCSx63peuLaUIR`n`3ffpYm$ri)!c&yyjPT}o;k|QyL z`=5!qPy% zo5&;7Cj6|vJJyB|4oNb0;7xtF-G$fXt=*OvArNVy=)o^sB?YPv-}(CM+#V0$(d*^Z z4B-PkH6!Oq{@L^!X|jwlps$}^o4_afyWuh1zv*_jK~uV3Eoc8fUH2dVUOo2@{N?J` z^h47RorsQp8MEW#w3q;`=^lBv{C&d`q`n#$EFU6~}uC7C2cw0xt3%C4)@ zs*hT!?4mS^YyH6Yob!CVww=d&&(A;a+w1<=>->7Xo@cM^z4t!Lp3MKN@0DBTbUBE9 zkEYxKXXGRNEw}kXwh9_JfgHK>2fXu1{^Z3w$n(EL!O8EG^|?!a$v55f%nIZIei2zD z-}UhirjIX?-?yWju=fR8|91|NIxbU(D$1rp-bU3_$xpbzNq1Z$FW?H*=PvgjGsGA- z=0V!uw05HKL6fy$7AyAu6}*$6Y<6Rf4ld| zl55Hx-Xiz>8F>!>JBB$sTLmG`EJxl-zwg_ae8%JPKlnn~fs+Z6ziO5DdR_7+p6?6f zxqb0mKwdpYyhPqe7Pra#^C-A-cdUrWd$==J$ZvSR%=Rj|`61T-}OMy&?I1_>T)mn{IE!#j%VZ!9&gUcR>29O++uU&RXpA2;q&!>i2u9Qp$+~`VK_sw{MCxdKYa#zTtE0Z7iUbzES$Vd1cPnEp1x7@00Gjtcp~uaOm0m3)0XTh_?^ z9-htW6x?vBn_jvGdG5XPWYZ+?OI@B$I2p9K`O~cR0x}!&fSqFJ@=^`sc~}1Ud2mAJ5N|pXqNe&;Jeu0oDO7 z`IX<2H=7FNvuDYH6v?Z2wk(n7PLMmG_eEO&k4}?ISEddRK8)E;?uBxvtCG*~a=k|G z;_bWo+~xjb@@L5`ZOnsoPMKp)#yy{W^fCu3U$_=3})QP;kjx zWpZ`N*Ik5_4|(n`xk5eigMYStdO&^hQ@{N0srv&8ZdfNfj>uB+5E|X6J$E>C7T@-{waoX>bX{yX92 zv6BhnuiyG_yb2~C+VwyAt}m2#zl!9g%Voh*B6r>w4^1-vyfuNGS(!Y1zFeUS`2c5D zC9mRHu}0p;2OR3LC;Ok@0c%)pH@L&YvOI5+ci)Lu!Q|mcs-{ie!vdtU@O1y?hX0W| z4i-T=J8#(l?}(BY?vu$ClAB-2{i8>o#~Js@kNj?Y3rzkED0uWfdGd(JOZd{+A-VS^ zIpY!e4DYOt$pd^(z{IDZ^@eTJ1DcXQ_zvnx^Hs$U+uhXU|J{09j#1WzEhs2 zE99lq}rjIW=HqoKUz2`-B64Cu&>C_ zw8@9K^>)aelhgZ6{Qf@$A;zXle#{dxCqnWbUKjMpqpIA{`s7buE>~iZdOZJZ`9-*- z5p~G_x7=`s z(`%00JwfI~p1cyTJ=6MgD5zr{;F2HNl4r#N`7yi6b3u{ZU;$Dhzj_B5O7DDL|6`F^ zrVf>Z_DC;vh1_{uCTW$t^iJ^_`C$*r({z3A>G{XM>BM)wHReIOKXYAGW_6Q1ccJW{ zMSkSta;e+ojhD+AcgUMQK4czHa3+5D(G$U7*@G5HN2l~-C5@x}VTfDa5!sl#Ol$kXMF{Jy>`V{}2b z3aY4@9Qk!Gl=lhp8IQ+5z~5*(nIN7M_y$v#Ji?dB6v&;g$blBg^Eb==qeR~Qd|XY* z{PQRX@R!YH@;Y94RLFPzo-9DBrBC<#+Yf^6b>54#(i{0z&egc9J(Hd*r=? zAKCzA9H@Mjm1LY%a`J!Kph-ndQij+)Sz|Pafd}oD1pw|C2YCx_7BV9~}zh?u+F> zi{#~h?w($`5_$Va@<(o-b-Vtb;1x{S23Y?eiLcqMkeBY27Z_FY9)2fOBY$!ed0MZN z`yD)8HYkW%a-(RH8!XRTZj2>GtFGKLx$*4@^6B$tw@weSY#i zTp6++`F3~7(DcctctJ8qJ)VEI{6_DV8%0DN+E@(_$s_zuXhc576&;gbjo&LymOYvO z;jd(}OqYY$XZy8ImKeJUZxJ2%lIr6;yZ5R2;kH18o{~Zd(KbP12F8R8y z{M}E1+`+q9Me+{*I;KSKUlot}`Sf-8FjK|~O#{YKbWCCM0{i&Ny0+-yy z9k4(iU@ciB_jZyep%Qs?OMHcr`R7q^=AH8VT_(Q;{~vgT{VuuGRq}IxEpJ%X$VW$G zMHG9o|M?wo*Ii_co7BP7r9+GS(W~}MuTY!3j3=`Wc?C~S!NSx1n`kWe_UX@M5$_zW%my|LBwFHj@_~1M+oO`tp1nQE(-`Zf8iI!<}nHz8{{P#^f&E3!0FZ zH5*S|qb#fY_*8h3(5{A+t@0xr%=Uo0D54L*L zO@jh;IQJk~OuBVBb30@X+C}mL+8%ic?TU4~{x1V+Ho*G7igts%j&_T@iFSv)jdqvZ z4*)$1LbM0ueYA(<5!z$&5!zGoiL~SS_rB~Uo#BCb@*LVOxr26*ynwbxUP8N){*3o; z$Fhu|MjfhXH^}Q~x5%4lcgWjlcb7e>zW~r%4q^|{9+3CZ9+F3BkI6@9Pst~7JFS0n zGz|eBm?zJn?UFla7s(4~d*mgwD@Q*r`=1X1f*N(GqTL{`qunBJqTL~Hqurgm?B4`{ z-aJTe113a!K;B1tNFJd*CLf_aC7<{J^L`ovc%D3mwoC4yT_i7{?U9$z_A3;W(XNqK z(Qc5}(Qc79(e9A9(eBF6#ri)$(4!6^+5_@F+C%aP?J@ZX?PCff2Q-_mS2FNM;$`62jqRU zhvX63WAYK&(}hd@O#tQtGz9QGc@Axt+(ElYUO?L;FMR-?|F2L`M!QB{MY};>N4rJd zM7u-YM!V}%5TM;7578cw_t74bM`(}9M`%y+bH4tc0L-y81n@k04sDm*LAyv^K-$|SJ7^e*U@f~H_`5pw?ByI z|1Jdq+CB0R?E!fo?IC%D_LzKx_Vk0O|M?IgFbx_4c%D3mwoC4yT_i7{?OC_${}P~L z1FZkcXxGTAXgA2~Xt&6lXm`l{HlRyEfOd~OM0-HqM|(&fp*?Ui1QqH~M!QB{MY};>N4rJdM7y)>N&U3}-Q^(m0PP-m zi1vWIkM@u}LVHX;irZ=ZPbrw7ZH}WMfal3`XuISN+C}mL+TL-r{x2b@P=_+wHS#Lj z4e~nLE%GMXow=vy9}fYbI}eikUpxe8_sB!E2jqRUhvX63WAc#?m{Kr7+Z<0r0MC=> z(00ikw2R~gw0)0)6518=GTJrrD%uV5I@&GrCfXhOxmf?V5p=0TfOd~OM0-HqM|(&f zp*_xcJpLoVG!w+H3(z(v&=A1$h^UtH8gm#6zjCPH@igts%j&_T@ ziFPOcna+QE2W%tgQilNT9(joNfV_|PkUT(00ik zw2S10599gYqo9O#g}jV*jl7C>gS?J*i@b?;$ETo;c9%RryGI_PJs|I+JtU9N9^>bH z{XYUsslxE1CiCBx-w45!I!w?uC(#hV^W-_SU2+HQ;*zKJR{(fR zK~jGuv@7Igv}@#5v>W7gv|HrOlkoiCp`eX+mpnkbM;@X*An&6+B#+P@pG52b5rQdo zn4oQ%Gz9QGc@Axt+(El&-LC%&0M7}k^4c7wc*c5B&_`fCC@%R%gIw7cX1+CB0R?E!fo?IC#-x6}F`Q!qk%N}%{@K;cnAQUd63-y;vqo0OCF%z zBM;FYkoVCZl1DyZOu-24Dft9#^D!C%c%D3mwoC4y?H4I1pzV>D(5{e|(XNqK(Qc5} z(Qe7l#rnUAphF$nXm`m2w0q;;~xRWnIL{$fcBJpg0?xCh5()?&!O#- zJ4rj4e?W7gv|I7dbpG2rU=u-yI<(R5k_Tw_$V0RTc90XrkRAZ=>BM576$BhiDJT`)Ci7pUM2UD z(5{e|(XNqK(Qc6YbwG=PCfXhHHrieC0PP-mi1vWIFKyopDTvS>laJ7zl26b!`0H0& zO*43&JcqWM{*33p?cg9NQilTC9(f7v3V9jr26-Lr=5T4QB=r}3f2X9{Olvua+xPuI z+#)})n=v`^W8iu63uBl1r{D&3aLJ#97sz*gr|h^$ei+;% zKNDUa(fa>t1QqJ=AiPSx-Qlw18u@|nI{C@)#@y5MH|8<~t$C1MNwW^#Cg1c3*>Q(_ zFL*$H47^Kzp^qS>;0Ab){7LwLeAk*BP(*$hd`NyK+#gYJHG(nugYXIYcKB;b%_+tHk8G<}@SO<5=H+`4v*d^Z!ULZdPUd(tr{ud(fGJ!ESz{}*rV`aw` z^5CQ5Rr2nq#B1bdo*8>G|LPR%daiV6kgxw0@fLYF5^s|`cZzq&PyVfV5PLfR?TzKZ zyCvvShu~iEkbI~6#e3wfKZ*~?hnI^-3zzyk<_Zahiy*B(=PL0LdGG`AG5KLX7N3xN z1Mw+&^QXQ9=8o(vo&8)qNA6uOo+q#VQrscm>qc>x{K%nr!KWbj9|?-&#aqS884Ab*56C7KP_=H zTMCl)KJeVS%$S*de=3j9lizlWxI;dHyW|_)dYaUKfr97UDjO=2zXV<)KM?MbzY|_2 z{}{Zoj@I*MBB)Y_bKo`di{W+h@4_48*T9?B?fU;#1T7n2{r>>GO}^f51+#!GJ?Q-Q@@x}UodjtjQ@D_NH`~-N3 z{4BUf{v~)h(vUiAc!!Kxk9;$DpL|>RfZT;g3zzzP9)jT_NUCqX&=@H`R(zuPbdCFR zX0tVcxVbx91$O0=Q#`M@qqyrUK|%2%`Acx+O5_!|M}9QC44<$6eFPQia6Y_BemT5G zK7iNB$M8nhee)=SW;QSz-YG-SB7Y9NO>Un>JLJ3L@d5e4smJrLOFZ_95Tf+2PI6MRJeFYDwAjme(|pOEhapDuY?e?7}{|xFMrALP_Q35G|6l57WpagHuRix5PMARVi>z=!0A!bjvs!N=qugHOo6be}Ir zI;G%ZbeNHU2X20st%3nOM}9p#Pks~J@hP|iflK}Xyg>dJc#(X)`{l$+&Z2f=IPr@-r3_sv%kG_t|`wO^Aw!sA=yV|bhVISU!?BjFfcjEDR^7!#m{|*ID|GkWvOYXo6X>;{fQDx6`v_?9#E=4@x1tA{cp$KQ98Ja7ZfilUdnhp{&vS+CRlh` z@rvSA#cQiPnSb?FLF^61n~Jv-Z!6x3J)Qsd4rs4LpmgXe9xC2byuWa%KfB|>B1o!l zJ~WZyL&ZmmkJmWX|C2R=l;u?Mnd0X6N);%c_m#j=+*Q1wcv0~Ze7^p-L*OYL%8FMM zuPR>4x<4P|dN!DQL-D5KEydd_J)VD^l|lTvK=H2Pq2fKo`-vy>pUZEcbchrmDn3$t zyyR*9*|DE212A9mQS63yK$4cv^p@6+u#dp5kT2D~eYYul=vG z{;w+?8j3d+Zzg6N{2x4uHvEMy@gBt*&*mJf~5N9Lo-l3QhccRXpLk2KVB2a`hTMM zRPmYO=8sAh_)3sh+)>bJXE}wcryQO`MnEoK=!G_@$dop#qfyy7w{qZ|H4O0p4Q(#5sa6D zr2O&^qYB9PfltZb1fP+=4Q?LHR>21z#{2&{3OvoW_E#Qq+1$dlX2<*?)NF8M|9 z0(lgBTK`1~Zb63<`3&xnKkF}YsmtX1!7Jqd0k1wp>;LN!)TqPL9+4f?$zKa^kbfNB zB>w@tHTU%VjoIK)*+F|ABvU8;1~hnw{QdBNybte^KLQWQ5A^>kJMK|%CcIC6J$yjE z;ooFC5&3K3L-KRs{)mDb5sbd)@Dw+Pbmv))&Hpm?PCko?y(tp7(8Jc3I- zCg0{UnT!+im%yjwhr(y%KHT^ZFFhH==llf(Ir3}ZdGcG~4*BolF8M#<1^9gZZ=Xhs z)FJ=4oN=QOel$ExJemKt{4PMyqYk&h`{a+o2jnk!QqDLcufT^(p4Q*T z5sa3Cr2Z~}kIC%kq z-X!-=K+vM#5_p^ZdU%I?1`o)KMm~1iB|lo+Hz5U|L5Cjs74Sa!Bk%#a^Ay=}ME-X8 zF!gx;+wwaD!H7Cs1s{{&51)`f>tAHYQ}UO?XUm?{-=PT1pR-l)5qOUL%kVt;wQz_0 zFL0Oqnd_Y{&;JDq%5jkVE0UiCFOl1)X;1O8;*~$s`rmG-s&uH4UxEXwliv<+kUs`* z&ON>V8S}jL<&0bNAiV(Q&G0t4Jfo8dk3b?`p2=E$VOzCAo5e__s-9SkYh3mrz}2f)YVhr%c1?}tyxPl3;T3eG`b9?4e09q=4^{;6^T zdGh_?4*8qmE_}ZJeyzLL>|FC@+aZttovq%jpYm~*}!}pUL}73UL&`+ z^P(jF1$y+2fR=I zdia3+D0sBwY5kpoV7L?{^>-$GM1DSeOdi4~HUA(p`dgqDqd3DQ@m{5uK(?hD>k6d|5O#PDPC8+K|cTdPm=$!~@`{b&9jaC06c_djFSe;S?($hU#F$zK5Pknar-$SXdAE(Py^ zhvY}Wd*mO2_sLI&56Hg>_ah4KKrkeK>gIAKM&u>Q}M<6-;U*sI{X+N z%-^zAa1%U7emgu*em~sFcs%}pL*QnD#ryvS#fyrU6!%tnGXKgHY?PNvT_N8UUL}7S zyhgqsyiWdRcq8_7{@Xj?(FmH<;Y4_g{FCrDxgE-m;=#hD{?5UMx{Dw!znkG9`Fc;6 zE7T+30p2Iy7d{}bJss=+hyouShUE6lMv9LWpOAkY+n@Rr3=qu7Z-txx%T~d|@ErN( zTgVm4lkWj{;PdtW0SH{`a1^{iekr_2{zG_){7JZ%b>AGjr5tHF8<=Nqg(@Jg!>i<% z!fWJq$m%OSo_~#%LHxQv@s{Fk#XE`zi6`^lmY+S+uF@e?yr+0y@xhX(^=Ee+Ed@#a zSsyAsQhcoVWUWj6PuB)%{m&FPvuqXE1I;O(SKOH?>wlLzT#Lz7AioJ-B>x?}L~gd0 zN$pv;>wkOCFWUg?|DDmHLVgguN`4-^M!pVSC-?V#h8$6Yg45tl@}I+7NmxCprDQ+H9szCAl3Qz0L zSrH`l=PF)Myr_6daqlr@{a;o(R1~i&UQ@h2ce($}hoCVJlJj2-O;hof;%&t{?Dq5j z0SEZ}e^>EP@t)#+#r=U2M2Zg;A1OXod?LPf{XbPY%oI0|D^;L)KI8HD+wyZV!NOg| z3yK#NFRk)q{&}l{*vpDn6t5~?Q@kE~I{*0&*ibq&6>lltR=l%tsXsde!6HbiZ$30# z#Y4q=iuc#JFTXAytO>*;#fOTI6dx-d|NY_W**jHyrnq@x^>%WK=i&49za0Wc>EJ3} zP`s#kDeH^R|9jbBKK5nBE9C2KBMX@-`Ht`!`Fm22=U<(IFQP+({Caqk{9$;Dd`m|T zs7-zdypwn`|84o5jv$~87s9*b*TO^cDZEF%@wRe6{UuN9ZyyAMr64K4cf%v{i{V4^ z|AvpqcYUVpcufAGXX5?;2?gIlhbj55;WP5T!p)P}D#$-ecAO)BIXwR)t^bce;82H8 z!Ci7Y=?dg_(iO?Sg6)*7+x7pC5O_Ag`rl5vGPymV3b~zJRr23p`!#akPP#e;c5*ey zpTC`4(k8i`TrF}tx7y_U$##6xp}tcLO>M zsKX}DmNSmX?IaqKzYUKck)Hz}FMCpdzdEH{pgs?h`=2rY2XBybMX24|3CzJ>hNB;Lw*6=CI240Kz=v8 zn04Q*|2#ROQZ_KV!#(mhz{}*Hg;&ULgICF)Og)}|H44fFIiNcE$?yjGmGCC{1Mn94 z3!g9BZzrD2e_MY0Bj`|v6X5~*+3+s;|AU9*zlZmhJgvW7Um!=+UkZ})dpCSQeg-@u zzXm=e{~LTno_`_M|6>Zg7s>%m$WMh&$-f4lk>3e7=85Ed=2!Z;yUO-+#?J;vAjngP z3*ioV1b4|d`B&LNf&69gqIJ9eKMFy~23Y@xaF6_Mc$s{Q-DJlV^8Mjea{m(uY7}(g zb@Ca!L2lpkQ^ zE98g6t8K@%W#BAeRY@`4&7+{sXu}{%g2PejmI*{@28l`B$XiNpvWY zZ}&2}LLT{E@G|*9@CtbyUX4AS|Mm`eK7tx`_$9nfelxs5z7F0b{~f%waH+qC5wsUU zT7Q3ocgX+c<#Htg@-5+A@}1xzdGX~~|Mw`^8y))Ohr$QsN5LcVli)-0Hhkn$@C5{8 z@(bV-@^8VXakn{lCd8T$R8T83N03VQF43Effg%8Ph z*$3N=;=Q0e`PcAxhx}H! zOTMKi2UM_b*Z;3XP_zNo|Hr~h|)@RXj{Rp8xam!$&T9N{7DU1H~i7hs&PSpFOkD zaW$~#rl6<1xkmp;uFQE ziqA40kH6iq*-)th#q)|gio2^knSX^*9H0LQ*97wUpPu4<#RrNVHVVXR!txk@w(Z@>}5(^1s8U z~0p4Q)NMUd3Ld1|%_?1APK&nxaI?mksn{}+@FMa4^sdy1Fm zF881L5LD(tdj4~-Dqd5(u6TppuK$}HVEx}xysdag@j!9Es|2CqJ;nQq4-}8Y*RKDE zN{5l+W5p+mPct5mzn#^yOt5gXu~G$!=M{HWc{2apRYB|p#fyrU6!#P_$DYoAz5`a2 z4pqf#iq{oyEL`f(4ncDfr1fXLrFdKMj^e=@$NIm!CXn@isCZBDzTyMLBVP%IijNc@ zD?U+t3SYDSpD7*8CQ213o>$z-`eOa>W`lWI78EZkUQ*m!>GAw4uMFbX1&UV{uPI(v zypeb^|GE5{N{5!>ZN)o^2TPvTpDnZQQjpZ2^-%Gi;(f&jYhCI;S{tPGKU93A_*n6Y z;?qrN{cq2BrgSiyDpjC(UUA2|UH{u1yEef3-+DpuqT(gRJ@Wbbzf6JMaYgZ};x)zV ztKBz^)q!a$-cr1+ct`Od^?3eq`E`{Jq2fKo`-%^iJ(>UZQb)_dk`EOhDLz(wvcl8) zo303w`kN_kHdCrV@x0>BX3F~CRXP+DFDhPA+?%`Hf969_o(IYKFNUU~cvbP5;&pbr z{%>%A^?y_Gmf~&2JBs^(5_A<074IqDS9~D8cKshI9fpdJ6dx--$#^{ew*01$?R1~i&UQ@ijaH&5#1dTR(YXVvScNGs6?X>;C-61v|EbbprnuQ$sRG6G zSzoOGoop~4dsp#-;zh+vD?Ofn-pU|;U7&bH@v7oA#p{VD^PkJFp>${}-cr1+cxTDe z`m^O1ECtKu*Ht`Jyr+17txNq6)&|M`O{Dlx@sZ+V#V4C9>;I|JVWzmrD^;L)-a4=U z9UIX4-&MSzcv0~Z`F#EFQDEmpS@DYERmE$o-8c2sfoUk-RJ^5lTk%fn@%-cR3zQCB z#Y4q=iuad2ng8}u50--^j}#v&K2m(V!qfVjtO%0wn<_q2+&o>W0>$%BSJwZI(!o`{ zpm>H{|&{PinkPREADrcAW*!kc&KnHOzApr>>wD_&8&s(5YTQh#;`>Wd($zWLBJ6mKftQoOy!vHtI@31s~rDBe{(RJ^Bn z-&cZx;*sJ*#Yc*d;cM3a6Q#pc@tNXgOQj03zF7a~v%!4q9mQS63yK$4dOZJ1D}(rT zf#PMwD~eYYuO*($e=fhe(xIVvQ}LGK?Ilm^&z4_jDOfJQK=H2Pq2j%@F7@AE8zlQT z1H~i7hl-CBA8)Cw|0ha^sp2!m%~nbkSm*VB-UhV(cNBLOFDPClpRfN*6xcc8DPC5* zqIh++`=+)!Fm=TniZ>N+Dc(*!o_}0^9i>B{cvtaI@!qm0^WR?T{&KM71H~i7hl-C@ zcv^qs6+u#d6UC>B&lERXD^;+yvi{F29UR47#S4lT=Pvi3`4E)mL2~|!q45+iD_&8& z%5K;HH4d=;uPfeAys3Cgalfqu9mNC1yNZX3_r%w(|NBaZf#Q+kL&ZlKkH_DZ-#8O2 ze4_YN@tNZ087rzFnSZ%eLF{?O9mQS63yK$GPv<}10ZU2;Pw}$i6~(Iym-@3qP+J5^ z_05N-u6RT7rsAzNj`e?gO(5(4j^cshUByGid%hC%6(1-bDLzzu1YfiMA1fUuicb}v zDQ>pORKa5XpUVdGvCk{+DDEm=Sn2WnE3ORU*9D4uikB6yC|*rGng3jVHKjvc@rL3} z#am0B)}JlE_ENB1ejUXF#k-1!YhCKUw>C)jZ~BT46ps`iDn8mqS^tlf4im+viq8}` z4yu6H|2Z4b`aiF@qqwVhfqcIHFH&IVL`iW^@v`ET)$W_>>cG?#uPfeAys3CA^?3eq z`L&e}9mNC1yNZX)p3HxHse8-8lJ^xKC>|+3T;XZ`jaCFn`HdByC_YturnuQwS^wv@ z%{)oWuTWlbM{!s2!rbNlGv7gR9wg_#7@Csep5kT2E9`dtU*!Pn|C-`;#T$w@757_8 z&{n*oc%XP!@lbs2`oE`i=qo-@JW_m^@p$}g`HeEc!pDkF6rUM%p zxTCnMcp>(5|9l55DjiCSdy1D8uPj{Z&kjL#5oF4*rg&ZPhT_dNj`e?QO(5(4w&ES~ z58}`C0`jxqUGn?kp-;ii`^(<}_Q;Qb_sP$I56Hg>kH}~6A$-36f8J|k$0O>nH+)Qf zBz!`C4tz@fE%+?!zPSg1c~-UxHhirdP>%ea@I3jsaEJWqW!a8PepKr5{3}rKU+7RI zkKiTpN8uj%<_E}*%j7SER}xR=zb(JR5mc$eC*d`6JL&4=cG5M-yVy>1$BxdQTAvHdQ2Jm;kTLkjHV>XCb|lS|qsx07o?Zs%4+{tj$s_$*rg z+etT~4(Fr8nA}dr3HeX(_$j%aTQlo+{r@|3FxzFTV29VE3drpw%9Edh$2;V|guCSa zvk#OV6e!pmUL^l4yhQ$MxJUlfH=qj0UnK6E3I%UPhbsBk;WhH#!0Y4>!W-mUzflgT znR-0`Z29enphX=HhquYkhIh!n4-d#Uev|CDyX?vQ-y1==9K?PlyhpxXMK;tYKL9=; ze=j^DKQH#Q{)QA>fes_`b?`CyQ{F5GG$G#^J|%xOe6}5}{{sZ(+1Vw}!)dBq*Y z-MP#CXTAn3%!B0qXUxqwpd$Gl@DjN_P*3qPyIucRIKcY9s(4NDy5bGR{iYJM6mKiu zQ9Mw*E53I9A1WPsT(n^Cac!LkGMoNN^w2+xs!44xDPP!%O6M!aedAy;HVdPCS|aw){>(P@xV#g;&WRh1baUKU{WDC;te%vE*s} z{RBaCDM;#Xiz8%1E%Gp7ou>S8-utQCD9Fm_7?~&U%)F;0Qj~|e4 z|L?N>XnQ|9xeiA#qz+$zkH~)kACo@_pOEkIF4^(ax?TU*5zK6W_y7BF<7N+Z<9Ex3 za^#1?^WMUv4bJ`&)_5SJK$sT7auJLIwAi&eCpEr z|55}q>hNc{d2Y4}D({ya{qEZ$?aFEwaD#P zskO=NH>q{V?Ki0f;*0ga{VKICb#QS8A^G#+J@UtJW_|J(W^h z$@jsAM&xgTkIA>kb|&Ptfc*(x{}kI#{R4W1|e<@$2MPVDLY zw|Bss5xCUhDr~4g{tI}Kd>y<*zR|I=V{hS7e=kK)UIaAhv$7~h+0G=bC z!Sm#A|4_2uc>XyQT%QK<>jLsqFo_D}+a4z;P$WMdULyY{+)F%}|F-7zFTwNV{<#Po3Lb&Gre?{zR{SPR32RcOLAA=9cZ-I}<*FQye zJSM*!KG})Z{~!FgbeK{HJ2W%J&Cb~>u#e9vo}YVq{)^9gIP)O6|1I2Ayr6hd@e;dz z|KH;P@Bfz-uP9zsyr#HcSAvG(O~qS^w-xV*FV_Ed%mSrDSMgBsp5pzC$K!8zJjetK zj}#v&K2m(V%9HswSrx=SReYwn*(F;A_QsVXw>PeQ?CJcscR+jRa;U>sQI;;by>S)D z?TxEQZf{(rg-iX}JD0ZzlIk<|&Q&H)?p(>g3c0;;Rmtzg3Dn4U@v;7|Q(*604f40) z@lEn4;4N}Hx7vz#d?g4J?W$eM~aWLzWDtABpb}ja;o@D zar3-v71$HYt@L>Q>1aU4h_YdinkPRFMBfo?T$Ok!IB4xcNGs6@2&8( z{`xC|r2GboM~V*>A1OXA(E8tAiHXu-s`yNC^L(WW<}UZ2`4HsiL2~|!p>Y&<6)z}W zWVh@85(ilSdy1D8uP9zs+^;D?UGawEO~qS^x5d}4|2s;DK=H2Pq2j%a$K!7&T|W~n ze4u!w_)ziDDo^I$cvTSlMDeNOGsVpdlq!flo&S6X%qtxn#a+bk=IVey1hoh>F7`=zYE?V-|#fqL6iI$@D}+#@U~CE zQ3yKZEqFkFIlN2$Kk$%zhtuUid+_=C|7{5R)Zt3_fc#N-ME<%nWCug?qu`^g`{q9o zjI)91!6)Q*!KdU;!e`{$wdH`!3s+S^JpXblgZOoU;*R33;swQvi6`@)%dez#@DwjA zUQxWd~T%2Dtc zc%J+wxI^xpDcf<$JMaSepTvDrq@eUU*-(l6WVlCuAG}Qd^3Th5D&&25HT8J@+43`I zNrxJBcs;yMejdC*emA^H{;wU`erws2`F}2g_Hq#W1Mm*HEz3ahuHxYePwTI@B1p=w zulPXmNb#ZKqg|Et|5)iTQGBZSOmXwCwhH9_Gr!a2=0S4)i#uRmaYu1i@dCSD{}(yH z`oE;Or+8WM3i;k&kjdy*DfkqE8u>5ab@Hd4EgNc(zX{$XKM&p#U#$PHL(rxUJDejs z=#U=-56D~aF8Sr~Fyry~+qGLS6BzRwbm)`sa;_ZEfc$Oni2Ne>ko>;HlleEI;00fl z9gN8jf=|eM@G1FC@EQ3(;AS^k|2zL7JI=*H^3UEGUjxsR9|?EJPldbW_Qq9MxYVBw zii;pU0P7{iJ;lq4SJpWG{6Zn*T>+@t%&&c;pJ(+*IXJ`8-&>=_uZFrvi zez-%vdmuY@$?Nb!;>rGPnSBmHkvd!rFOmNZ?vZbEzU;V6{sDMp$;J7U zlpXY_gRPFf;seDa#fR4I`rqzgWCMEtf2{aK@u}i7^7;G!rkJe)dq6qG^NKr)yQ|$d zh1G#6Dqd3DQ@pHrCG~jz+w!w#T%`{7;5piO=xyhDB(JRqOIyW~e)gwOwk6r30b$-f@?6YxIyabK3l56I7kN8|(eut@9w ze;^o9hu3vw2V?Rkd_w*Jd`iC6S7bZ0xu^F(V_t>8yeL}*H^Ot|#fxP_d2$c#kT>8i zdDll!py2oLBKiNpOXORBRSw7_|2KGWDzqj;crH{I6mKiuA-CU< z6p(NHO;o|Z(fZ$hby7$j>{loC$oI#F`sDVTlLq7`h+24}wPsx4z)k!l7>~}etJ+f6`zac3{ZoeTZPj0^<$sxx#p!vq7zVM7zk@fHJ(>Tz zeOq?iTn=J?54=Tw1-wnZLr=ETA-825tnjq{x+{XD{6fWhiuV;CC?4%W>wkNsL#4w= z@v-6)#iw(Z`_KGNH=75^`7iE(X3uOD*aOWeo>$yqx9|VE9N_)`g5pKRONx7n`(-7l zC|*^(rg&ZPhWKLrZ!c+6>CjTVt$0WAAmj1)+Z}f^!NNnudy4lJAFT3Z{za>T*oTUb z6dx--QG6PEI{)n*&|Zm|(!sn$sRG6GiaQIJ`m;NB7eP{e^PwpyUR1oKxVOgf{(pH* zAn*TI6t5~?Q@pNt!&ic);w{D7igy$b;Pdsr9fGdXAym9aKL1)S@{{o7G|0MdZbcAf z1M{r!$g|myd{6j@+hb)WQn39Mvf~-~8{y`q*(&J3bL6+d^W^5c zvVAA{P2u9F{nCEovUQ1Cf)Xp&zGZ;?L+Z=b-VtzGjpbm;n~Jv-Z!6we;c5K` zD}to{yNZX3_Z06dJ}4>c|48XDRD7iPSn4g<8R9^$OH@TDjq7{ zQ@p>*lleDT6~rDXJ|sUAPeLQ|U&6=ahkRe2v?j5q^WWY9y9lP#A>Wq{GxCez=H=Nc zc*YOp@j3F-;rWG2{cZk3>EJAar25Q3aF_gR@B;ZWeB+ry#Mb}@Z76q zLuK;Mz$@gBz^mkE{8+YABj4sH;&q>bV-YmSe+_SvyVuBuTIBD5x52OnUMD-Ql5g=d@fx}RGpzsX6kLlA4e~esTsG7s z|1!Kq{`BkR@on-8;GI{{`hSZ^It0|=On8@k>tD#@L-H!TNB(Vi-@0A@KmV7qp@9vs z{yzmCk^dP!B!9)PWIH4B5I!dNx4c0*OepvUd`iCOjq>;z`I&IDSGEc!@ErLoZ%Vi0 zn>+<4OJE%GyWuYRD}F5pR3JYGUL?0q_odY1`ESe52Allj-D;2LxokZ*XqY$ziC0DMUP zFnmP*hC5_CR^6nJ;Z4m|SH;bro>;T7`N+%4Owk~iTspMsww zsFS~JEE{T&`|u|D1Mn7kBCJ2joD_ zE3;MbKk!`Q$^5tF_ln<3hdg!oFx(*@!d>zw;RW&oC$jzGlBe}|8iLYNkksEjaF2Yy z|CJ4u$uEXi$n8R=y4I!sYiomK|E8{ZL-D5KE%HC&K-;hMvtx7kALPtB)Zx4Efc!as zl*f0;&w_{K_Db}u+x5Q<`Zl2V{|AakiVqbZkfZhh#g&)Z_VQ%kP^AO4MPiKS>9V`~rBH{EzSo z`6nKh?NpaNng90V^R?w5cKh-9I=TJ$e1qJ6dcH}%(NuQaB7be{Y5lb+upgiAklT;X z2jt(x4!Yzo`?KsgB)6ZQ?|HQTzZ4z%)ZtF}fV_LL>>whypPnC*+fUDr<}UXiV?RDW zo(IY8#~AzZ`3brG`23XIetLdJZa+P5_RUtoHU3xS4006MkI(1H^M8@YJLCb}CAVc< zP~0ynK}m5>@v`C-#jE0r^}jvRn$n@Jcti1~;;oFw<8OD|&IHETJ6DI?etbS4-|i6^ znlAb0;34@Hi6`@~N5L~5l@0aD&xQ}kFNa6uoBUO_GbH~cd=z^+|Lq;{R|v+`;mp6u zh9>0e{h#=hd`I|<{Ecw)s(BSi{hf&*w+PbmyA_@%-+CrHcF50wyX05E3*^6@Vf|mE z;C+wD4oc)V!9DW3;AQgd9+&M@$Pa~AeG2TIt440`Ty=7L<7$w91v_YxUj=W$=j;Ew z5VWa-y>oTQ?ce?=M{JW_nP(&PCzS{cNz3lyIy zK2?0CxOsJ41g=AAHUkqUg|M|33ZsjXXN(rX20xq zrg(gwdSEx*$$K$KyzU@$>z(I!wxeITS7vODj z`}hudQ6BG`E(NwjNM6DY`sDWU19A_KAClY0k5Z54pDn*KI!vg8y+Tv+3LbCv&yKx) ze2%<^$2-fO%zxX#T@GTeqeGG0KE6cW#N*54_VE?+R{Z$1{%RE14t4SlcF-iZk8hC& zczlQ4K0er=*8d?o45>r2Db+C|Z^6gpZTN(|1E0=a?ms3#Fq;SIjn8!9<~20N@Emy$ zo+t0a9rA&Xz@;F97s!Y3BKZhjA|Jy&@(J88Q!qtPA)mpkkSB zJ{DiB|3d^*>QLRWosPwfybL#$?2b$D9JvF}XFMMN90Dg3B>(@9?ARsG!wcjEc#*sa zFOgRgPv)OTfrk!d^2$zfKo#;j9$zJ|!E5AAcs=%X{@XiX13`m2wBb$i7Q98?f%nN9 zH_HhO7B2Od|Nn%&3!GbZng4$}#gc+Zpj<*hnhv*=YXHG;lQ4x6P$3Qo@rH3gj8q|r zVie(o0X1A!Gf-(@SB%4oq59J(iUAelxN4SVHQ+AB%W68_0L78{^#pw_Z0o_vL@@$A`vvX2biOdXX{S zUT5FpIFjRzXZk!h#yf{!=fs!CcAKw3qgM`RfLS?`cWBk{r_ZyTP0R%?(@7~|amuZ;2hpiXs+Tf6p$x;Dmx4wv=U8gu;jV9wfOJTxfO8RL-w z4_q)h)U83C;24h%;zNd;_3v)K_`nexOQ;We79ZouL40D2X9hey##2A+k3Kz5AB2k}LhyZ8Si2R$gc zj=}vuIY_9DaW}p`#?yoN_84~?)EVP;*6l&Me}b)8VOj56CBMz?tO)rT@S;DjD!i`n zra!l>&KLa!YIT3!{I)+2Eco-J!c*Tj@v{ELdz@_e7iud!@vr{zk;nXbjNHahH|PKl z{JVdl(BSR)cn3NPci+x4-r0ZUC;bI_3XeXe#49}TWB>Tbk4ydi&lZ_=SNMs4LRaC| zPyOSA3XcrA=ySEV{>#5mN8!Om|M=vu6#lZioqaXzaKHbSmD*#>;e^S1K!peP^pDRe zJh7L5yq(3qf7#&BG1__XYj^g}gZLF*&&cx%uPfZz?9{QH?Z-m#zGE5BE4;37>s|g0 zjgN2{fA^%zk2pMDSGe_VML^+sKW^r~?&mObaHS%k@Vvt73b(E*_3!^?HI7VyILvFD z=M`R8xRv#<6Zg11BAoXeBfPF~>uNb1I9L@m9_huCVh36GsSGZ+gqX;NG zukgCUt@kSR2i#sZ$4Ww7;nw>U0fpyBx%~X^V5IA#jv=?MRRk2CS9sl*oB4mgBB1cR z!s`mRa!P%}jsCJJP!j42w?3czEX;nt0#^=)_i#m5{j&nvvHaBFr{ zz^xPa=eCvicUX0WTQ?~J3ePLN?r>Run0xvp^Qql$pS^9rwj6!-s;1E-(}C_Jz5y269Exb>y~6iyEvqr9qc z>sGhWXna!P<#9eZ|E%t~!;HVY;L;lVk^%lNw|RCL7Q@v_3}3Xk4F0k2NhkDK|g`Z` zqQa{RkCy!FBo&^u6-W4P|3YzvrxhN&$G=W`z?a?st4f0PkN$;{3ePIMJIcNLfBc{P z1&Ru9D?Iv1|2lbJF7w~?b;$Ss?)5K}Rd`+D!B6?uNgHm~-}v^cDhXEEzfe-)WrcUa zNACaePx}iL72Z~Oc;3HGdO7d!zw&a2jEnpTmcqmLDFO;FE4+Q5dk-JGhKK)I5m0zp z;cbOSKQpL5e*e$AjCb~d^5iYAlaA*CEpMbSL`6o0L9{RI?eDFDi_lA7*{vUXL=os0S*5CYjYKK41 zYJ7$FU9kSPAMC%zPU8-9{>cSI;jLBv@vVSAZ|>sH<2Js($AhS=@C3fU$N03u3koj} z__F(d4c{oFKy+{a9#jc`znI}MZR0^zM^=%lDBYF zdtBx}J@}b!vkN?j{QmEZC;Umbx_s>_yr*#MQvW(V^8tlfe@2)B;i7*+QsI#=`o|Y= zF=728xJ^e14)U_XD+;eFytbV8_g{Uv!x`{~!mS1W9w#vO>_AfC`G3Xzp9vLQt;oB$ z$&mLHZsB6Wc*}jgQp|DoqOck`Ydtl!)1?tcHrr@+FG$uJ?H@Swu$L4V=S zkc&PAxjk14!|H>3OFDQa6d8qZqk zt-2=O;{{iHx85oqqvSp8d-4(%DS6~)&LZvK|LMqM5s?Rf<*jP+*0cUR@ltQ@8DGR= z46c^(ckllpEFvbPclR%pz?xuu0CP`X^W$dzt84rPDtIS!DQ-Abg@^Ethw)*B$AmlU z&ul*?SS@cz$-_VO=RHgr<9m4LL>^uo*0D!~6PRNrq&1GWR3q`f8w!lnPvRX?KYp

JBH=M~;K-akI{ieA|gru@0J$)5)j{yeJi@HvBc=l+j5ZoJyRP;uIy_Y|JKz&}2Ch{yL6-QoW0j5*w8 z7d&({!R0Z9R~6p!=e8B!;4hHJ>NPEOU%?~&<6B4h^DY)O>%@;S@zQ^@{pbi_Rg+f~ z9z4!pIEh`rIx&p&&Ng~h#7OK69>7SDM-|>Y!D|rXL#Hg~&iog!+L=&Qc>L_;h0OG% z(X*f6q$^_z$Sa5A{(ln^l1LzLVhYH^$9fGSw@&uw&Ed#N|F`1|?+qQJyo4i@@d zObvM!4I(e~dH?=TM-1DEJbR)ym*kCC`t#f-e;&f(-99lq|K#@oU+td|e~mw{V&o3Q zJEsgrh&+PxV91Sr&d*^uR_`!DcoI)Da_bDQq2y_7WAccMkkfzX0)ieSF?395D7=j! zWqc1$Kk|roRNIy;=nkO!0g z!a0SvF+yi!DtkC5qAQ2zpM2boDcBXyf;7&9|G_UP6%=k^HzjePmBC}XxGO^Dzl4Lu zbI9icm>Tj1riQ$Isy9O9h1dD>u4#~2e`cuv3uk^94I*z~aovyj5T5s!p~n&MtMUG# z0&bt{j)Z*e!Eq9{O#%(t8M`2fqnEsb_?NIjF>fRWyubeiCxeFbrfd2rz>>lCf{(mVP*6H35 zO=He7;CrEG9q{uoWx=>thrA2^W*LdW`6r+Mh35(Xl*k zMCW@`Aiw_$$7x7Np6m61yr%Fl9^V&WQCINzUV#w}zSh*2{+sRhBpf-%v7A@2k59!E z)WQD&bt2PV2gs9e7;qVd4-Lm(+7i9gbNn7dUB2Ao?}Tvb9Ui|Kya|36cyaKrXqXPW zysw|}3f+r@#=AX!J$6Am>+vpl83N?dtG)Oa5ns95z5mNl?CvcJtN1=I;a>1a&f^x= zN(I8?^}H7!!_;JNcDeNbU*QOR*mcN}44wu519+z3#n0eKu7h6%UO+<~?#_SkV_u;t zJpE!H_xQWPYg;@X$M!2hfV{fZi~kbh?ZQ2tV;zpt?7bd;1l; ztdm3h=P|{3kJ}a<1$%p>g$lt10YO+7~(fUIIi%7!jp!Z{+sQ`LJbI$r%>p-+{X&f zC_D>pvrrAfW=i(s|R(M3=QH7@<%=$4WUixpg-!WKRaTFp?C_Jg~5`gcTl9cvRtqfv{O~ zQs3KuF(h1vp^hs&q41=_OAz+zi+&0TN8urnR(M9?S%p_1%=$SKZ~AYB;!gR`edSSz zyrA%+!fOy_of6{h8z5YUgS?{fs=_l6W}O=1zuiAS`tx63?r;X9q41`{Q&)StV<6zv zX(4{QJIwO6eFX0Rbaa%2uEG-#W}P15H{#}F9XV*Ix&PAIePh+U- z3U4U9c_i-tEYyPV2uGnQnKt*;R(MC@-65C$vruBQx46iA!vxFv0feoiym<0}!h_@7 z-G4a&On#~F(ll8r(#^;356#Wp6cuN@Bb7?Az=wUPAfd4 z@T|fUH+oaHg!_k;L&6KV&*v3hPA%^2OsFae8T6R(HN;2x?pWasaGMEDILLbtCT}7BQOt2$;hp8YKmXn34rl&*7-|ai z5Wfzq+B(MD1>^yR2am!1es(j94kDb z@Z=aD?!OG)!B8NDgkNECr4^o0c-EiWRts}XfgBR9z#ECY!V3y7D!k+9O8?FFqd*A> zmvA2|yrS@`!fV(~mzaP5-+k4PP{*pSE4-obros~#X}7*J|1BiE1r2H|yrb~0!Yk-8 z>-Ubq{r}zQu@&{UA9+CGL50WAW7Y`` z;KXE|65_AJiCG@u?)b|vRYn|xag#4qg{L4)fg0j3MUU%#+~_y_9KxFl&p?<0EyVAI zqq?o|j&P^{<^*IyS4qf0nDITtr={V;*RkH3NDra>e}z15TXY0H#|V!=nDHURryvkk zcw`wL%zt#5qhBosVG6_$zZvI8T;U0YCvC;i!2v>n6ypDYeVkT!M&a23ckcfzl*0is z!cpikSugG@ukeDxi=*7ze=YQw0wpB$@LsX3@QT8#zFhP(=rILqNO%c^>k4luys7Yp z>9Fa)*?tsgA>n5j>bAl=3hydBg$~;k=po@?9GTW}-aaM|C_Jd}#`~Am>Cb-%3D;w& z!wQcmJgV>(gjqj!9Palou1g=ZC>xz-zM z*3TjSZF1Ec?!Ww)!`)}aFlU4m%p zf(lRNmKQSdA;fRQ!4+0`jl;;LJLOVG8t+@KwyQ z^$KtMkp~nWRCq~ro&K8>kcC1>I2i{~Sm62*(wkP; z*B{J(3JFJHsM8A1C_Jn14&Fzwe$Gb1nK-%f3NI+UsPGV;5v*St#5?!@i}9Q;qY!yT z;Z=nPAj~>7#6Pr?cmJ^JqmJRx(olF);Vlfc2n=5>#Q*njZOQz%eI4=($qMf(ya!=V zKz^$h@mVy;IzhIvS$}5x(Gf5XA0AYA1P>?H2_gP>I5ETEHXRW-$fF96L74F|#2+^t zYWb1O<-EWD63ZRV2qYDrfG`D8h@Zhwrxl(#0r!6X|@{kZ>AAccf8A)HotM&Vh7m)_@2ne?9m zIV3!Zq0TG3pzxx?8$)6FopV#)8Grd&Lc&Mz(Mwt36@^z7UVt#`+chMFAY4~?L*Y$@ z*C5RLt$uv}{(mfl+bBfdQFvG36$rCV5AlCl>5jjdi&wgfLjE0aEV_Wgg9`6qH?d9# z@k#gmF#2IXhwzBPqY4k;sW=pnIx)n@@l=cpclvKmKspjiLQ>%&2(wNK@!yq(xUaOw zZHtbK=NRExh1ah2ri^uRi0|-Ly^Ig$zp%{FZ);KE1qf51g!p-UtXEce#a0|ug;yX< zfg0k!F4O70>I!cRxO4w!LQ_e|L74F^#P9E_%Gb8SJEPp&f89~Xuv7`c6zC!Tcy~LQ zteCeZ$OFDy^n<<*`RE1T(PW_z;u|<8!U~TlJZiYkK+nYC_D*n zvrq-X6#qIq%PZ3BnY}A>rM)WabrKP#g~%fck1D)?-=brk7~iv}Hb=0EM@FpbJ6Jge~9Ri3abVCv)${}aADJ_+}KItofcQQ-~zs~D_P zLj2FMw#q{;{imZcbd2(fJFM_1t`2veYk_!T%Yt&_bqK_2My{{5ehppwwQFDfuTg!ujNa0)9tGQ!>QmqCh- zIJ~jzK$rqC#J>sKEUxf`A2<3*KZo!dgej0hd;p6pt?-P(v%;PJn-h?QDi9{mq0o9f zBk~F_D7@%#+hU;>gvm=@f>p;Hmla-7cy$>c%zp{O6sRHL5v=OE!W#;2Dm-K3w^1n2 zLc)0vZY#W_@UFr`@9J+$=l)ND9ujuLsFw#=T+kYV>9EKi;6&_J| zRN)ysj=lP#A45VCJ&r3pq41=_b2u?sKV{-g|IPM$HF}&zA@YpEvkEWeyeVUy9OCUJ z-ofPIATKDqsPKk+yOoZyP6_c>_P23={>#f9&iPwWcvayo2oD6DIyJ<94EKQgDY*aB z(NGea3Xfgk4K?eu5TC=r)pohL|IyKL9b>$!@WwkmVbF;y;X4omY6lhdc9M^l_L*#UM<965>z9J)o@cio&a> z;{MMh>+AOK{}hNJ;SmVO6`oLdQsEVJ_>q7+ z{<7LrNZ5>_PAfd4@T|fkI6sEZ;R!tCSidCkPXEmbc#Hh!zRD;> zUQu{e;T;S$>(sn>+j?9|M@>05hWq2@B)M>5JUWbp~vx2 z?(M(CsAJfqq{3?ura%huPeC~C%SAuq>yRJGQFsTJObX->f5@=;mX%j{!En=mv;CM* zR1$g+W_$_pzre$(tndoB&4el(n{3p=ky22aFd4K+!%N?R7N5Pz%q+*i8K`}co3GD<>L z;XMemP7d)e$J)w|aCiKrS%ndY+fMm+KolN$x3^X(P(u7^*iB_WZuBdD4&haWhagOW z8sd*YkLwC=2zUB#=8OqVB_RS~#kMyd z$OFsxVE%*49R2x^p~ox~Lj31&Y(EOrkkG{(*A?DScvImeOtDRY7816i$8Cjo6y8;M3?n_L-=F^;5n9>=T`bK}kZKZNZRcO7Fqq41=_`GZZY zpF(_9x;or{=`n{p7#W3U6&}FiG6L=^hxjwSDYmV=zr!jhyr}Tp2fV3-fK@{LuW^2q z9WMPh+mDWll2BE63c{>YLwo_(`8v4`M}rRVrosylra%kvpGJ?{KHQoAj*r94TUX&R z2veYk_ycfoSsT5nArEZC{hyAYl8}Hf<3osl%w2KvHLUQ+kW2rW5FI*3c?QCak0Jg9 zZ&h1yg(t?jyZ@5ojzKRvcn3p)6yi@pkJAdzDBR8}j?neqoKYZ$_-pV+BCqg*!i#<0 zzyGsP4@WY235C`|xUBGs!mA_P9e)|Z4umOCL&AUHsaRKdL*Y$7ZuC3&%!dLkB>Wu0 zZH0Ff-c@)_Zq-iz%?U_>9um&QP+MnuYl1wW@SwtD-gVx#SSW;qkKq6bD?Fm`sKO(j zu+^_WnEx0O{+;_+;R%H&72d#ZV*Qkjgu7%K+*exR8HHyR-hwde=LYf4{r@KPIFCZ) z1%($Cp2ASGP6_evoAB-*R(aIn4un-vcvaywY-14^zG{dM4WEiK|8-x7d?Kpwrot2G zu_qw^A2Gy#0+02!;b#4r?MFvPN$4uP1Yy?cA^v5<9*f{v-Zr-B2*5!eRCoo#j1M8c zg!3c3ocH%%WVyqcx2VDk5T-y3@iz@;UVgbr;fb@bSeTGh5;72Gdrj$x?`dQ5>9 z;y;caw-w&;<)Yv9b;#Rt^q2xY#P5nZwi4cABo8P&Xt?RW*?vsO;ZjN-LZM&d^MJ6z zBMOg#+bq<;$weMR!rr)m#1)=Ucyc-K&wl|QlT#ptge`m=D?Fp{tip3wV5ljOL&ERT zk4luys7XCrWp0* z-~UI#tMQO%E4-uduEI+YX8oQMFa0;$?*#7SbG&^_9#D8t;SC70P6+XH!||7MAWX;b z{F84`Dm<$28ieOiCx-aP2i(z*`#6k0q41=_dk}U7Oq~?s%UIOub8!EsBcmi_72bj{ z>*NssN4$Z_54rT8j>6C}%8Lr`K$vw(h`(Icm-{M@b9eqLgZWQDm;xmvtib_NR(M6>RfR`v zTtFyLL&A0Fab4jJg*O!*8t6Lre+sma@CiH>+Y0X}ysPj4IxO|Q{ntZ62nUGuYHu-; z2NWJucmtoHdUZrUgoHzJ^9d_FqVTA~YuHV!A2ac$|7QFB0zHnS5P3r3Nrl(2s97h4 zc>B$GBaw!KJfrZe!YdGFogCs1>M!d4{O6ZDoCCF>@S?&q5FQ9PbxMf;2)FU8u^Q>9 zC<#@CmoUeyQ$zd=K6!+RaK=sk=qkK` zp{76&@vp)8VZFxN#^AOU@OM~2g_j_VLRJXz`{0=pR(QnW(tor4m=IMGau8;G4Dp}C zP{$RXAh(f_qyxNy4=~3;0}*0y)HAkD<;hyrA&nYjFQ( zp&s6)l9y2Er7~^qtE}*f!mC3r{b!-Td%RUjUK=J@*4bFqb%i$+-W=!d{tH2v0xcv= zVvgGi?$Tnpkp~nWRCuMY+rR&_PzVWc=i^x65rsz;UPFi9 zzRDecSxGS@e3Xx4g(noARCwTB-pCE>8~qd#p2i%f6`oOeR^c%`oLE06@lOBE3HWJT zGV>@zUQl>Z;SmV4PRWb6ts`-Ols(4?uPD5#@B|Jn)~_M{7tTlz=D)to(LY)m3U4Yr z2I0OyzfKGBZ$O9Jw&Lh0ysPjCgelNN`~jF^>%9JAbngFj1O^VXCdh*d@8RHLdU5Kb#RW4P(R z8EPhEm4pg}8J|P^%y8V~7mpQQ0JoV?go8W9Zo-55T-y4 z@n=A|uJDG!o9E&F&q5stlebXF#!=l?ct_z~mz(=P3pF52-g6Tq{v|j-tna+FCpQ}IIGJFuPD5#@DP45 zf%R+WRN;ZF*8vK|5dT%YkBIkq|Nc)$LPaUGNGy@q_SR*8DB&EPjShtE4<-x+hRh~bByp<))QuY3-QNdsM`wf zEaQXu?=Exn=RcA4gelNN{A;netk-$*qfkfYcSlA9J{akx+P2;UNec0r! z(s_qV|IPNJqo5=d6`q4I>y!|Gy=b_vGP#+5_f??-ysGd5geg!%{BF4G)qS`#{|z69 zX;f3;0n9N4T8Q6>dq7*^ooU?vnb1`ddiYKV<9modA9HM7;B8~_z>rJ-=?D%TqdbIv z4~+34#J?N|S6JbZaqjNF=(uCBC}JPF?!rqct_z~g}1y8+ZF|SNVspX1Dr1xdb@x; zpzxr=8=kP$uQQnc5E3@v<`Y(UMB!0|*C5RLIU5PjVW{&8FDSgI@De`rVg1q|-nsvO z5x3hi3XxY7UR8JrJ!YL6;$O?3|EZ5UhO^&LcvImqT)j(~Ca@Swtb_&||$LWuu9Mj{Mu(-DD#JgV>( zdd&D3;vaRo(*GmAocH%%V!6Y~NGiMoVG5)We=VL7X@zHAkHx}-tddYs;&X`K8&Ac& z!V4}p_dg~SUB?&?;4>e_mk@s$=D4iz$`~JZ;USEKQ{SEc5)$6Q$FagI3a=`>fqMY!+chL?K#%JR zZz#N}@Ctg&`mKI^|Neh5R&^VN$U6$}D!he*i*}|j2@a{FB@SwsQ z5N4ea;$P>Ew9yayIfO?P9#wb=!b1V66GQw*aAL-VJN-8&ARP%MA*t{lj%wCPA^vJU zjy-N$bYwio2+t}!b&WS=tdm3hP3}<3NaUCC!TcANIV4(MMTJKoOo0;OH)E*F3a{9T zqpI)(geg!%d=kQSg*OJ=x&JevsU(CT%=i}K{})5uR(NNWd;70D>gbQZ{27BV1$v18 z15QjU<*fj9D1x(^JcWe+gm7Bn8HHz;^ZxwDAWVTA5`K$kL|)+qg%=fGO5wzMS5>sHk!P{o!0fh(s zxow5uSSP)9Utxtu6dqN04EzdoAntJKzuA6tB$R}t!c*YKVGX4fo*}o9kfj4W2mWSU zO!5jZD7@&yo%t`p5ylXe6<$$zRpB-8uVazc-+=o+9StR+sqhx~jSy%nyffs|e4H^BqpF?;< z;Z23Nz&GGA-Bx%c*a&7S%v4oFX^|@`7^KZg2Iaf?%e-bsDy-V zSVU!oR}@}Vcn$pKRsHqn^q@ZK81}89@TS6B;3r^_wtczGf5+D$zxk-}9{6oIh^#kz zyMR2P@Sx#l{h95@gb)(ic$$S39#MEy;W2Rg@Zmtq=Y4RHClsDkcnbW7+y%>dfB$8c zJDg@^6`lkC0xm3hg%=cFd^7I6vHx=Fj ze+rAVJ;n#;pX`D$hui6{!h7HsVUb#I@pb`uz@OVz(BEN&z@Nqlg%uuAcvRsrhfDv> z_B$U#6h{JiLg7h;r@(K=l`Boo`+tTGBxDty1OF+G>b$}WKHQoAqL0JOe+m2$9HnK2 zR}@}Vc68>hD5*Z>yR6f!n+FZfxm!lW~IGdKprsM^xtehI)X|<2>egjW?_X#6dnb) zSttfa3XjXU!V?NlDm(@L&i*3p&wqNk!`UPmg=ZC>1JB{8&MUl-w!OJwLQzR5f!~BV zE-SpE@T$wr{hx(uu0!~CytAn*yrJ->!du`UmoXmhzxJ5JJ)}Ac?<%|pz5|QYdYd=W z;PUVP_&cni!b9MH!4!lQ9#MGI;nIJz{a7f5gpCl0D?Fj_q{36+TWkzbnhx-c!m|p` zf$xeAY9hSKo&FKMU26a5$c3b%i$+-c)#N$ff_+ z;%U|%I!1X%;a!FIz~^Os4PP_fE^xTJ{{rKVK}JyFA@DOX1!09p6mCZqM-2RT7@@er z6ADi%Jk{s@`~S_D<1`Y;GYZctJO_R@9%lIw?vB3!m|p`fxj1vG(X_Z z{hyA4l2BB534B*vxylN!jB;=PRYx7e{Z|A3GI~%~cthb$UoQGBIR1(rv=!b_cvs;) z@au8VS(nK!F#R{%kB)$G`0${@L*S3%VG~w(1l(pq6b|wj_TuJDG! zn`3;q|5|XIh#_h#yrb~0!h7If@al{H+r8BehZRtGP~jo)FXEgCD?H+G(Kp+V2~i~> z2ELou11qlZgu;{Ly#J@*I0pw&THzUmXBD0Ue|}Kkng6_x!yG^bg%=fG0)G=msI2hH z+j0MALRCqqf!~KYt}DEu@aB+9|5>OtbXeA%W(Wqaw!%9K?<%|p{x@^bIpc3cF86kU z;}{4B6dqJ~2>d5lLt%y65ycTzcnth&5Qr;0q3~p%_wWBK6#0-h667fqT7@Gvt?-P( zvm<;s{_^AY`1KnKv>t>6@^z79+HuE`fpA^ z3e=ErIk%a@8wzhKyylIxZBd|wgukH2ZH0Ff-c@)Fzc<*gKbZd>5>CSf#CnIf7|8<) z4=TI?Vb%%RNVt^mU=$uvcvRsL2(x}{5bxaogILvZ6e3S3JgM*ygjpwr_-9vm=bx1x zbqvlw`DeKlo>h1N!Xhwyy@li@!;T?r{m-GJq>%s9$^uWq^LrNY{cu?V~ z8@)O!(1G-gxc?uBxyd2nQ+QjR2Y&>-06vF0Mev{CKr6Z2-2d-Ji^{G;`1Rlw@M|Dk z1%DHSYv6Yb_kjGYDfsDf&<)N%c?iLAG6b67??r=J;71I%lYBP~{A!$}9q`wBQ*2vZ zIR1zs>VfYGZq0gg`Oj!*0Q@raI0(KGBNTGD^xtg1M{rvWBVlh8ihy5;21UV-hCmGb zG_S{29Q<9w@fV>491mltli)|AK`HRHn1VF;@6gZ;_^Suc8b?11$8XTm9QZAm%RKnG zn1TZMXK-&Qf`1;oG>iNH6>yZ1umTOLfWHE~N{**!4gACCKz+!i|1%J73>}vB5E7c; zD(?Sj=~~Ff@2Pa z!r=dbMHd180|cVrKSZ4v_}eiO@jmb0|J!I$0tx3}B$D7;A)EsLE=DK~{u;z*z^{IZ zJO0wcEF6pIaSr@2Y_mN01?X7;d>SKB1plGiF{59CV-W&n@YkSc74WZNg z@CbO`hT~K?3gB_@BKRio68L%GW$^RCD+6wup?D`8RU~W%uYtcCybgXPcmw<@@Fw{C zz4K2#hKJ)uB(%YA2k(Fv!Mou1fcL;ZIpk*kKkY4wdxsAB{a^6Uf(OAr4;})qgNMQY z1w3N7(Kl1@1302c_%V14{Ab{C@ZW^ybJzq@E-W%!UyM{EP{D&Bz}a10C)>L2>w&>5cn^_ z!{BX?+g1dQ-*^ry3jPdu4Ezt^aqvHaC%~TrPdZ%sZ?@kAE|V!F1i;ha5%3K7x!_sw z^T2c97xUl$&%^O%Box5k3SI=i9J~ac0WX8UbHJVXufVYx303fG!E4|-@H+U7;0^FQ z!JG4U_t&49g1g{oAz>?c8@vSG0sky`7yJS6-jIv_SK+Yk^LD`_-~sTjg9pLC0UiSX zSMV_S?G8sC344GS!1n?#f*$~00zVkM41V-Vcl>24DsY^Fgev$M;5G1b!0X^i z@CNwBE;ss3I4*S^!du{%gSWvy1l|F^9=r>l2k!}Y`fs-1&2U)%?CpZvzysiO;6d;^ z!9(Dm0uOuKwmu6-#B*2=f=9t01CN0}0Uihc9e4t~nt@@HF_J!872` zgJ;2C0MFTQm}ziddGIyh1@QgBi{P&SFM*#9ULJ7g{(m+c6(mf9SHa%_UITwWcpcna za@Ft0>1;i4gOj14)_D$UGVCV%l!A?_{z{B?fs0m3+mtj@b7^K z!G8oE0)GlTY`9r}X5N1eM+6Dm!K2{MfXBdJ1doGTc-Nc&w^zcEgkueO3j8GSH2A6D z8Srz#v*73Td4K=q;CLMp^5CxrFMwYTUIc#!cnSPw@bYJH|GyQE3KBj6UIj0K*TDY~ zybk^Vc*EspYgFNAx(?xA0&jso1l|UJ9J~Ym@8DhVUkV?bf3geUXd}V8-`fQ*fCs?; z1|9@|DL#4$fv@qnZH3`j>p83l_ zFM-#=KMmfvANT(X98DxV2;Kt!DtH_GA@C0Pcfq?uF8%*6IC?{e{Q3>J^;vHh{2Dv} z{#)=M_#ePS;LjWG?!Pb`0em7F0pA@w3ce?J416E(IQV*SI|0X`a3sMufTzG;37!T& z89W2N2|U~9{rmsfaO9AX1kZy{gBQTx0A2)tGk6L7lAYc0m#HYj@m3^Mz-Pd#;Fp2d zz~2pC2fxbYM!x~a`&@_cCb$jW0-ptMgWn0>0ly2pE8OY7IRWp1qlbh~gIg7E7km~x z0R8}Y5WET=^0;k12uIj+SdW88z@Gq*g8wIY4E!hHaqy1A2lJnRV+FqPkObceJOv&E zPlK-k&ww8Yp0(jP2#y^1!QgrDW55gGCxREjUkP3saOeJiG8|rSE+_*LL-@aw=k;5Q7p%zqb-JBALq5rNNxTMu}kS< z{PW;J@GpUf3^(h~Y`?F<5k^7{JOchb@F;i#JO=(acpTjRF&qgvTHs0WpMs~re+Hfg z|0Q?^{Lg*f-+x&+o!^xk)+31#q~ZvFPf-(Rz} z{*F~U+0lem-Q&>sQgCv`TzF#LQ|rPj|I_`?@f|L{slLy#j~06d_Hkm*!ah;#dDth5 zy#V`FVlNJDySm4efQbo5+!5F$_9X0c#h!wFp4c<6r^TLyeUaGnu-_>50_;n~UUY3+ zdOsszVx`xB%f+6AeTCRlu&)$*2KIZzo`rp_*z>SIDE0#E8^m55*tQw|SpgF}c@6l8 z*pskt6?+Qy$Hbn2eTUeyuUCb4D3INJq!CevFBkwFZKfL zzl*&nwk=!E8G(s2qyYi10jtEGguRQ{Q?Oqq_6+Pj#h!(|kJ$6D*NVLW`#`Z519P_7 z^G*XM1x&2=8gQuCldumLdkXf^V$Z-nPV8COCyG4}`(&{fV82T2#nrYaI3-|W7th`# z_9X0c#h!wFp4c<6r^TLyeUaGnu-_>50_;n~UbF#b1WfGeHQ;iwCt+V9_7v<@~)0Q&~9?L~lD0TVCv8t@UZCt=?z_7v=oi9G}R4zXup-zD}u?0dvs zfPL>7OLlM(U|s?ycJmr=zu1$ow~0Lk`wL>v!2Yt>v#=i$dmi>9VlTjc^bA|(0AN7^ zCSK+>;Co_E!hTHbDcC;{dj|HCV$Z^UO6+;qKNWic_AhJ!ivWvaPwehB;J0E=!hS~V zDcFA$dj|HO#GZxyoY?cQpBH-pw*7YjivSZ-(tx1XfK_5o!rn#fDcCO)dj|HNV$Z_f zN9=jnYsFshY>1ea5qlQ)wPMf1{-D?k16!W|#XW8iu!w+J zu_yNO8t@UZCt=?z_7v=oi9G}R4zXup-zD}u?0dvs=-cM`U)os7L*psl&6?+Qyd1BANo)&u+_C;dP!+xXK3pT(d0v2J?znE6MF{s z9b(VIzDw+R*!OId=l=r0y%MkpdtU5`mwOGkU+hWP+r*xN{ROdSV1HTcS=bMWJrDbl zjq?0o0C-da7GW=lJ#nDdfbWSt3Hvdzr(pj;>>1ckiaiVaDY55a|I`++0PqX37hx}o zJ+aPfz;DH#g#C=zQ?UOi_6+Pli9HMZIkD$q+s_MF0QkGui?Aoolm>*o2CNc$680`) zPr-hf*fX&A6nhr-K4Q;%w!Oz%0Sg}3<3O<&VNZ%ZvEFOIp<++MK3wc6*hh;!1N%6! zXJMZx_WaP6=l{t97KT910kIchPl-J-=`~=J*psl&6?+Qyd1BANo)&u+_C;dPyS91$ zzfr(~3&g%e>_yl!Vox08HQ;iwCt+V9_7vSh9~7{FfE&bK zggq|4d2g8ebEXJFqU_AKnX#Gdcl{pbHZ0u~T(uh@&Q=f$2l#B0F) zVo$=}CiWEUFNi$@`^#d_!hT5XdB+|+{~r;sfPhEEUWC0M_QauH1HLErB<#n;o`U@Y zv1edEDfTSvr^KE&w)_15selCp{6g$S*o$IM9OgCPw_;Dien#vm*nbpz2KJxCo`wCK z*z;l!pa0JbSU|wv#a@Ixah5b7;x%BE*psk#5qk>u%fz06y{Fi-u=f#rK7!}}S^*0P zI8f|G*pp&UZ15UzsMwRR4;On1_R(U`z&=jwS=c9vJ-@;B3Z5)r0RgWPdlB}O*b|3) z@tee+gnh2qQ?Snydj|Hj*t4)N5_{eTc%y&?*q4aC2zy5Ci6guQTrTz`>?_2cf_&vIi zo%Gy(Ti<%asw-ZVu)0<+zI1>1tflW;@ujwP`cv_)W?=Ds^O>N!TUiI!3`)+-oz3P;`E|>bx?kaip!{%PR?mLyU zCf4q?HM;wzy|@0vUUksQeIDO$>kfO>Q7dr<=cGw}^eThF_3)rp5^Uf8kqH#>Ih zYYGbQZV<6&S6bVoxYS<#`|^Z!;UNACH?BH#^@S4OUb$x5V_X00##QU=g{2)^pWXey z-iz0*c;H3p&$H6bYvi4%3Ax~TXB?`|IK-x$ad`2%GalG3zGruy>K*a79s4fJy}zG( z=KoLb0h0UY^B=VzaD~@=z$#v|aIzzO!vB%{=kpgTyY-WYxz}88Rj--a-^o4HC)YIC zl5uRWw2s@pa^2y_f9a)LI`TEY^7YnN`p`P=Xn`_VVy|<84j%-ihs-+e5Mgy$=k1jT zIx*`9G4Ua@jyvE>FWvgNn^tYIUu6~dUY(x~9CiHM`;V}iIr;DIBdp?%i&t#eao>su zGDle5d&K_h#A$P(n@*cMY2#6If&UH6z46XN=i0KWcI;{`{qPY+3K}wJ{N2TL0!vOA%RBTi$c_(lwW#xzv_DxbLF$`azlP zfHdS55emHf__+-?9<}wOH?MlReTr0*DorQ*zc)G=Cc#uG50V1kK7P(^ZQ%&3YFgLX z*IIJ^{>19J&i>BdyMe2Zoa-Dm;AiYTXId;V-N21|4tvr$$XYs3G*`&d6-|3-eQMK) z=uNKZUq(c`fjKEIqO$FaW=H~a(pVWDBW{j@z-u=x4aB>FJ&tn3E2g(Ax2Jv4|CPi+PersF_`pV2v>Dj`QdhJY z_|ox?==UkwaeLbD=#g$mzuMQ#m=!3k7g1?_e|Y<%|1~u#diU9$=<7~)MZ1CZGA%N^ z+bEhD72RD#w{|=G9^GNCswsAM~+oKW^UaI z>!i%lXPva+H)k$IQpED?AsM{EWhc1mv23$uxj#6(x_FkTwfyp?IaC-@w#t5u)^xs z_+H}drTZ?m=020#v~+Xh?4_wcPc7ZQyS4P0HP+HU%RGEj+O%Dc?+No{lz*Cis($pG zRi2#tthD9u7kBKtHTwnGz5B+W*s(G4g#1d<;c{GUdsZIDU)wnG#6oG`E%Hy{s?IC~v)GpT5yUMdCy(+#W53u6;a&+zm zIX~A~*3~cU`ziBJHt+Ri>aM|>$G;&Ey8YB|77{AV^!*iV>Vn+^3V`TA@5 z?+QumOvE2dUef{@>pIIpF3#H85<5+6My*73*skP@k2#? zFA-m}?Ta$xfBDgC9xyS6e_T3drogq2y4l)N`}6-i8G6Zg|CHPG#Xsflvv2&}oTtpZc)1<)AfZZaCx!DgI#mBsb9&*g7Wg{xN~QMS%5gbLySF;gF3|Z_OFY>fL0I z6})t;;EJ(=@0Wtl%arXhQJ5~QC`_-G|8A4NzhUJrx1G5;Q`@-towZGyH^&ZHDI+)- z1-J2;F|CAX*&LqV%KWhPZx*rkRWc1Xije$w>uh0qSNYEqx*~Sg=FPQnq4PxO&p-60 z;pnkWJwDV~V>_45DI;`^wbZ_9uzD-U&dtj%c&RKDXDz(nT1s4CozT8!)W4JKzpn4^ zoS$A=y|OU(`}{!yzh&S%W9J;7pO!=H>Odkty=H4=T-?1K!zqThoFnr7O>IvD~-^xGyt2*BJi~;s5V}|M5!TYQ@$WwB?;N!MaZX3%I&-f0JBMAgp}nRb zV;bO0?`Q17+S6s8ce#GWnhl@1Wo_UC>-O9re-EtKW!KJw2R|ISKCu6a>*IF@K76w? zD$jiG;D?|7;=vDZzhKWLdB3pq3M2gSJ)MSczhHXF=~7?zg&9` zwoSm+v4D>a0^}ibfcRf|--@|;Sw!uB+;eGauUE)vci?gDmHTd!hxV3$Y|Du3`&;De z2HE>&1p7VHJ7yZ$dG#Sq=WM5Ur9tmD9`f+hXCLzL_D@OgZ^PQZlipcw z@78SllJxF`gI3M0cu9V`El2a$4wl|tIy)Vc6=b}c>CAaEy)jXX}ZRzGKaqVeQCq8aU(7xhqYt-tpvV zogZDc6keG>ZNtv-rO06`9_ZNi!_Qo2Km2N0GjA1%mLA?tRPjUp{{D(mOXF zRr?3|duH?DwRdekqISESf*W39y>6F%ZkgV-`?cwJiT`%_yS>}Kw@gp2m^|DsZE6CTG%}0LYrTd#0 z5q7?AsI5NWmg)7a^_Q5~TjlSYH%DrLmk;X7*SBpx%KpY~2M!9$S4)D;rNf*FCMmr+ z@(t4nQ*^V4pDve?ugK4T%H6RVcyVg!X&If>E94>~>*q%E*8kvFILGY#hvj&lkyG`2 zIaLp_z9P4uqIpP7r4MrM1;3IJHb?bad$t^{hgc_=fT{Gcb7eVpUFV;rAs5S&Y~Zg> zmDkUe<>+<&f0H8TyMDPJP8H%yfjw@SzDcI8{GEv>jKJBhU#@af$>Sw|5aZI_AuzU9*=J*>cT-HD^y8_`l!&`;H6So8?CZpWCrDzs5S@-xgNL0$X?Zj(y{E@(yY1 zTfZppmdr*s4~v`3W|#Za)MdxcU3&AebKhQ@pRUPONb|4XKR;dlKm6OpU-`fMFV9bx zmv-2?z=8Scl3#(B{(q!>dt6l27XO|ZIP(AmdA~d`kP3tNKvY!FVJNjMsnN8wETiGRCWv03Z^V8Ev6e+klrsrt?b^)8PFQkZfU4YInD38&dkX8{QW+k z-ya9g?6vmVd#}Cr+Iz3P_ByCw@+hGa3%?DQgKroulzli_DAAgYYcB_1ku8)xku9`A zqnVx1R+qGp5WsWQ0587^Jb$g(SZulqf*lCAT?JmU-fX=2 zD)2VIX-9IU25M`~MvT@gBUAz*=PGbJ;3F>wkIj=fXpb0_l?M35lMC4c+yw!hm|#r5 z_ZEgWVXtn{c4P~*7w>|EV&|&EdR%wz{-CBm?+I?|D+*~kGiLxS6=6*-MS$=s6g{;{ z3ri6RFAEqWXam%O0Rp`3I00o-xZczz_{v zSCX#yv|FU94u)Z!HYZQ8bu(dah}k$6h<5KgCJ@~#z$=bqW9&*=Kt$*^lb*-#SWKO< zZi7>$&|A|2F_i{j!=PSg+>DLF3)m#sur7NXL$Iz4yI;KLfG$nBX6OX_3=HZt0P90( z){3^QA;fME;&2}#v=_}ZJYdBG2roi65iqJWZGq~`WSymjX5$;hG2&laxFO-*3LGng zIX!rtF*t0UIQj)HUvXq$toYyy+~Dx9{&0&3!J?bU^^K!a^UsKHyud}L6Gc)4HF(T& zvvKQmvyn9wL$sQ{l3#Yj=LFW{IeSy2iR4*4+z@CH~hSpWZY&?ca3YG2)P_G59PhPi8fbEM^5=t+-F-|DC!E9XQ z?Rn~T(|Mgm2sC1EG8@bM5H5zd&46fJ2|jF$&<4?&c_ldLYp0rx)BE9Z{YukYfl440 z06|=`WzZ;7K?+GY$(2RhnsbS8?!96jH`P<9$8yIJWxvat%xUMrA*6m(H5;#MG_|E zxD(j*SsqNWBU%}2@Ml^2MIMsM;Yy|HMPOmB0A>Kdr)l%_9>2;^d4M0;JzB;k`zwx?7~B8 zLoq@A{y1|kDTQIWns5fx{yv>K!(d9F9eTMuv{ryQfyBXqO?J6FtTueV>2ae?sTWAp z7ptbYBp`O!x%vw58=I;Zk{PKY-K|qF>`XzhJ0jB|j1)(i z-nr`$Y>J~IYc*g~Q6L+|3fQb;(`8n5pxzlDh>p4B%f{U1n5lOX0_;^# zx73?^iYq#e9Z)>PQ(H7cU|N~D5VR^v8#r&#|Q z7ipU8rDQXZLV&sjMD=~i{B%6$R^v3rq~Ej|8kP70JE5+Ms*P1}k8)5}ZxM4AXJOlo z+eCFK>Md)rI%>cwho*)`taQv+DbZ@DfR^}PHdcd;Hs!60pM|*=X(oxc0}hqUAA#p# zFR-^7%O?D`ZDOuu`j35rO=PZ9SaLhCBzI2Fw~}6r`+j0Gt(?n_Jz{kz6SGQE?vg4~ zJ~VAh)c5&KiBWoI`2eF6H`kU{Y_EA7Y_BL;YJXX>KT`(#mRcJYLS-}Zk`d@!BE0==bkL#VE(Y|1w-gyihQo)X7 zdyqMaL+WdETaHcFJEujdYU3(c`mvYvPK_y$IggFYw`vA5>#?c$ABFz~_#cP=h4?>+ zStn}sO^&CTlNPLwTIQ_KU7NmWtUkRQEc7XnB2p%39c{hSWkJ(#$9uX=H9a1!?SX)# zD?+B{$l|9XSj19y}Chph)wh9!MXY(lR>qiZsx*J@>vwbwvC z$_Jp2)okf>9K-e;!0f4rpN@!OS#dJ;^m61c)tFI0e9#S$6*4+B8q#WI$g96svnA4- zf3A`ZEK;Zz)nc)G?rFV~=w&FFX_f6ohqXnM@X6J8ey5g1J4dHie8BCq0#{`GQI;$hBr z**582XRv+y8tK0wO{D@{)VpjZXo_`63{e4bx!x6w|HH6mkoIbTrD^rnMn!mYav(O9 z8G2{ELdc~JX1!uVZlp{<{u@+;M#G=rqD^tni!@54{}?$dIF{`bMaiFT$WbCt16>~mlXjxtf14s1Zf!lD}mM7 z0oR(Ng(~DDb+-i-@fG%jw=mM%%p5G?_{#B>LA33PXp@D;_!G!%$L6sc8Oo5sQ&=3< zmhrlyidfyRaVSu6(_$K4_6Nbn^!s@Y2!y6D=F`&e<bYO@QL25POJ4T0F9T=`!rV^Z~;nu%~;`cZ_7`nE{Yx3;XHF=JS;Z{vE6c!a) zsgw%6r4NOAbxQ%2Wg2>G(+$gCHEQ(FEu#WSQK$xMwmAN)azYtp*-anjb)gd7t5K1E z4aDpMwdtz}ra!Ho6YPs>@(==fNB2E7dC#GM{?-Rdtv~xkbe#=!?4Ut;yQmSZfr3FF zDBu(%NoSjf8qcZ8(|!g-0)k~U<#pk3iI(`m??=}~k|y)Q?gER82f)k%oNj4WinP3} ziLELN zK*>lNEs!mJ4T|O%(n(hbtgV;f)*a&3Ph_4crmPI=?>s z$bsJ$-q-vae*d;`cyp%Py&J*Y2F8-ok*OC2LFtfU0!_!;AfJZR3USf$N)|Uj*B+klR2uLYQy| z(qe9{)tyZ=q&-NrywkASY`pbOGGZlJRBrUCyC6jnmmD29jI0bDSh7oPke2kQj@5c7qn$Kd9KP`!k@$rcGGc6v!&1;QMg5Fbjp2nm3 z?Qvr{*1C=ADXz~#rnrs`oZ<@Fj^$(!Ehja#>WX*Q8iR3qFc&iJSz`v(_Cd5(;LfkJ zKqmYHa(^a?Wj#R0Pgr%+f|z_1&W7UjV5Xvp4Ev`Bu{v7*-4RXOyGY9}{HA4%M?=Vj z3`mw^s5tyJE_(E#-)Kn~+l;O97zb1()?I!p!ilvVe(>_Qu@ZduF7d(FxS{YYd+9YU zO4I0t7e|W!eht10F4EDcgI$rR>p{6>T618&EnvGeptRTIS)^un);-@Zk;1p$TC>ywrhY-H?Li|f|wlr#uJRUX!eM;@~Xks@a`R^Qfq0(Lyr8b!o9ap~(^BKQ7X)*Z4a zantKu{^Z|AZI1s9!+qqU`!!T5pO>fP0js2YoU< zgwz0AdNx!qChXwGn;HXHU2hUGFaf>?k(S9|fRE{$Q5T!?y2TfaI`1UOROOf;D|ni` zSk5A8a1&3N;%h3Ok5F-VsRpha~JYECXwM+}SkZ+=_6Suz75BvUu+iPHlp$ zT`=H4g$7)M(QM3x%w96!yl^|<*;j!#%rqNm9dV`nvRll?YXA>87aHFuZs)5 zWo2u%$4vkEJjy5Ql-GEEe~jM}-`kbqo-?qd!iyz*a)GA?Q7-qc#_G9!d*rI)^^h7z znL?nGZ4I`eXHx@&*nB3ezzAN2Ax|sbdhCwA4vMX-m&`j+76mFzegu?GBPAp_wyt$R z-#Gex1Kz2X^j?T}_=s5QyA>uJk3^BrhmNC_%C-OjiJiMK^*T_X4Zq2mgl5Gj_D0v) z<@y~qRLb6tbDQeG9o!kr@7-9AU(c2{sMsu-0`O{?U{}y1-_hGjE2RRYkz6{DMg9&OqDTXfq(iNDytxna_~uDg4}j9CV78-)(x3NFCpR3nV;iNv=$8(w2&Mm% z(zp7hOP+;nhe+wK^rw?4&u&5nfdH0%fL-Y+pqA3#@Jpwq67V0T^tb)eu??nl6Q#d9 z2`k@7%LD}*|Nj4=B*D$@UD0*Et|FOn{OTT4UwwNYb-k$#f#zNNUvkntYk|k4 zwG+c}C+6^-()@SMGaT(nd{&`n1Y8R5%@yoJS=Q7m!C|o~fz(g-z;iDpP?IaP0b$&g z2pq~4@*go9M*w~}G(l^MBQIl2M3E}J6>4gyHgeo06X09W?-+wSF8s0$7`*dmrz!FlP{b;szEUJ0;7}v~eb(X4g2$bR-{6 z7Qsl}?IEl#ZJSIWrJvTV5FD7~=)`)Rx!Rb9BegT#LBcUeDB{>T(-i93(j|o>P%7hx;j=4^pK@qC$?OG_22qxK+Io3hQ4P z+$x7j=5+rdx4Iw1|K&2LDv5=!h28eA>EfAP93Q_HyA_17j;vSA?yJJ`sE_QzsS2z6 zxHx<_7o9mVj;*2v<`Y<8HY(=iP~Q6LIejb7=ewrWE!(2XM z$|^*3&9)bCwC&MdgXtqF0L$H2Hp{Uo-ry5o!v0110(fV2@$aQ9uk$Cbg zWF8Y;R`VnJjgA6lZT!3V!1Xb)wWp`U^GD0Z?}2|@v6{`=!+}r`oAm(C#-xQBolP&o zJE+j>B{UPbsqiA0ga0u`CmGco7{stPSkopW{b~H4ga4cG|9<=z@&EBeyli1stRAxI z;O!3ZI4P7Z{o*(Gteyn%<9E5)ahhP3&0x0BgHuI-J5c+i5VrJlam;&Ms;SJ&Ko$aj zZ_L4tE&0}IF{)bF(yVl5uMT9^LJZ6F2a8ajB#Vx$8Lz3+dr;5x>)t=4_O+Eb6f~$W+=;eUt9E(U~zizbOO_ z7>=h9&k~oZ_<(>H$GG71o{1sp$0iR*KVA@;eqw4EjK?xb9Li}maeVcGd5h9=Lcj@Z z!JGk!*jk|=7Q&oABaOIM1n%`gw4PO9DG5=6cu3NbP0|5@cWjbbPj8V~`(Bb+Ng^t- z;Yln1BBxfhw9M+*CbRnF??x2($KTRHz{TTUsPP^Il#cQo1PlviWL>@#@1Y!zW!d0S z4=Lg(D;HxLaDKSV?#n_O8mnjLsAMeLf6xV<$GNR9UBbD|i*vhoVBX$$F5Wkw=k_H7 zhlWk`uO3w;?QzOvoqG$+#&x&H)X^bNHZ%}$5-rz}`Us-&6KP2*VdGDqpfxa-WbFga zAF^Jkou`cx$^vqP$~>H5Vg@CJdcpMIgTpCq?Umq($e)Wd%qzh`zhMlHFi*M-S1h1p z9L_MWM1bZOX!LTx&xzV*KFSoEjS`O*`Bu* z`FgNjuwk1(AFB9$GfozY5q!t+`(&7Or~p3e2>8BI9$>8)z?{WZ=G+pEIqyf9c8XI7 zo@99)OK%nYQC6gc393;;qzY4CQNiV>WX=^RI7-2?*P&2HGzzO~%hjIt6b=pldok|z zQ+X!;0@rGo6UQ8RE9EL{iKa5IO)4->DsY3hK-F8rh4NDhXB_l`L_7t=2ejsCotF~7 z8f}Y*_8^J)DnH`nu0sV>oJtxm_I|)kQ?AF-RUfB+ub_pil*#v<5I_Dm$B&*)5=t`! zh6Q!SHay#@OFrO)va~3n2A65b1W-EAGXg)?FtO+db+nkdhdV4^b3z=@%JHL|(v)xo zDu?>1bVYcmJS5)P%GGhGQT-~tc(#?(4ZwTD8hs0GiMLkj#Sv{>=`g?gu(lLlOApn{ z#tAhel>(VDw!#^pCw1?=$zn?zmlKcvf`D|eNA)fAKX{PdMgP@Wy%@Tei!%KJgv$RJ zS_~kiR~7Rrm{~Mq+g>hR{{1oW>%E-8^uciqlT?WMV2`Lb zHx}CNcW67R#|DOuHlPk=SnSgIZUO{VYM3qVg7R+h zlxO<(YURbodfIWTr@YxH@0sy^Y8P&4r|)qYaaGw zN@<{8_vFbEANYtHA&)sOzVZ>rPuPUE5b9CzujWH9`qqAQ1W~P%Ljn6#l>)-h$bQ~G zjfro31k;VlKYwzNR7d%?{``pYS_cW;z+CNl_`g#oYZa${%#9lJZ4WhAZ3cjLVwj zB>vt2{>C>O+o(-|Jp|e$T)TfxlY~m@^ssb^X4lgmn%$5Sr&65zITs((4H`X*?pSqf z^bBhTm`97PMcNdx_H%Ch^)o^2yyV>FB_i|_`Bus5jxN7$l_ZFVJn+(u{qU9hm8

%E`_ThPaE z;bvJQt6;IR7gzB!+9*3yu@%&09?s%9l!29Pu@E<*BR63Id5g0ugHd8>&gp9hy{zL| z8F%rP@i8`IY|NEnOvW~-gGpG8J9*c5kG0WGAS(xUV{P8{`R~FeqG=bw>t7%UiP@Tp zpcETpHw|Ea)@z`Q&=%)#6P)ZD+hIwPB%=-M4Chb;YC^H7*p!&@azM#TG02#kKt*rk z93tnp3D%_M2~KNiB+Bpv=-4f1#ZK*nI$j4leMvXW!iLb!G?HgYM@;vL7bGKYrB}fe zWxaBerzr~Bs4!EpE3Vpd$k7cVH$gm4C}nBHO&D)ku3GkEDZJsuPI96*RY0jK0%;{3 z@gf$RWQ&ivQi93Y-u4?7(+X_&2n?3b;Dcmf<!xkQ_VI!)?5TRyUK&j zAafR`Vsog;45DWzQ3gg!LZVld^qZgp(AFanZ!;J@Ahe=%gZAL$nLxC|81ApZCyBsl zrJ0PKPzTciX?s!157`=BptM|^L7m7tSYX%B-~wp*69gdvTT?-}YJEaE{u5}8ce)Nv z_DM)+C;~Ab0x47fG`s|w=N4;=y%`64#XBI=w8nCP^D&^3GsZWd^W5N~9z>3}Lkhk~ z3AhJ!*%D`<3N8{rk8R4uhR_LuzKZDSLmp(LAa12s!DJ}egr;>3s5gb1gkT4`&?{=aI*UEf$GV?X!>OAO!#6ZcI$q? z`eO`NHz+L^mTMi}H|i`+KZApjXJBD-%m7~xfv4#wP>M9!Xn1)9DT?^)MvV*u4eAm^ z(G!Cc3$;4WP^V#{UgIfhGHlf5sG{F7QlIc7H4|292cD&_#Y}zay9bq_C1bGCjzf&B zrnFe9&3TeD4^#CDPgP^#s`{&7A>`~b3fY63QVK_@H~nx8&ol1etHrWpRxwx`@rHFA z%hDdu$qP)@#Mo;g*sMJeNQ*F9PXSXuW3{FvrmauLZiFx9pb`%f!+FBy>;a|a#%`?p z;|w-%2Is-+A0Y_w9O>8?%KbQjk?``JFJVw_mTj10t1#HuzCuKUC@ z#Dc~KsG@m9&hO9(QlgDpV5l!)L%J`SxCbSnh6CjVsDc~Vi3y3@)iQM>aJP=9Sx+D) zDXD_`RKX-DdN_NMXih}*t|~#?A@sxTY)VhfvdX%chxl12F~n&sONT8th~YU{n)Pnb zl67e!E2G{K9}&k3B8XLx$=D2aFbajV0ib%BjY+V33FhUAaRvwM=b-B!AP8~Un(}f2 z$$5Aiig&sSQuvzvIFCWCW9Wk{+{+_eSxn17Y>Sb;hN$&xB9^&~HF=ObohP|hc$AwE zZCsCuIGcFURjkAWa(=lsTjEqy!C4;Zx=opRmeq==)gqo_Tw_;`jjLLTUNA&i06DwJ zvt1`{$}i+By5p)XCxm%TMH;v)X@KdqxCz6E-E6^JyJz{zJB9RggBrk--_S>^c*AxP zbRhbsLJ=loOVq(w6w)S?@)b5FgFOh6mKV#lUbH&U&)^(9)+|8 zrF@NzNwfz;((?JvpnYUN*g!n*ENAcziV{2W1X|!8FNYL97gV<)JF7uAWZ`x&$v0Ny zqTs@TOoM|wM^@;CWdY|Su#&^+1U9zh5GLXXl;Kf`nZi9N0W}zO9NuJCj*F}6uY&nR56|Ny*hrcbA$}NU9;MO{cd;tH#9~egLey`9N)&T767eeU zwk#~odN*hcJQ+m@Ycn13CQmjjOoeQq#MILc7GAMA$MT&)2+=(M8O-O+ zvwjA5A&N35kc_9t&4r=DGDxBNlm$5}t3hXE;by}H!zUhI6(DTimuavYWo$4e$3|^} zDq4tra>rq%hhN2WqjVh3fIj2%!1ld&3ipppwV8-hiB+7H z-f$1H5G!ay#Aqo`vToxhCWIdU%5&{8D5FC>+5Qea&Be3rHayv#NA&O5zAcQvaZHSkP^KUcnMloW+IM}RI^4)`9 zpoS`e%WaU;H*~{HYzQrwiE~WbP3H(++Hq3+RWJcB<*;%Kg&eG6rgj8U`&gCU zAd-`V5UcoZ!W5RJ{e&@JV6r9vsFxy;*%6#PgV@D>B1li6C;C*#PyD1YSbZoVoRz4= z)5Njfu{pvz6vAt33hrqv~ddz^@TjZxQV5nK+cDY)CG0C20!&7!P{i;k~+-92`HnZ zY)OKW;71kAg`Y+!&r}TdBp`z-SnLD!hKR|27h^35o4q)%cspXW&*q)RQ7nabsN`gr z?IGB#U9sEe0?`g*xW9m&#KCee#5?z9sDt4=^hVj(k2*!y8WL%c*Xt=lxQ1VDL(+f)*Tk;%rG4{zF!nVoK z#tnFwI|Fup9tXwCJ*dEww4pGwz3fPz>4w?a5Lz=6=bLt-kKd3qN=Nikp9mB1QVy!v ziXRb2=^2alSQAFm4|lREJp-R50GyPIya|iI>8E(h`vsMpnjl^kjFnzI*I0)zU?FQAOS?R5Y~IcA9rD$?*!Ch#7YNXn(PA;84W3U zh~Ercx)@D#4@HoQdDxto@glJK9gt~q9_BYf70rQ}UgddyJSh*fs57i&4RO;aL~c_N zJ8s05IGrcDXCOv4QyO?l17_l6l+kgXq!^ThN^YKQ>%Cx(3P3&0q9h@XaxoTLkV&6P zKRg6PeaBm+lpsX?CiDX(ui(|zdFG3lTNEfhgA z=3ygX*<79;U4s%Nq!-pf6-|YdoTU?Z*pe&oGm6HtUeIRr{nJ+cs|6JZY1z zU6OVVYg(;KSgU5ulO`*av{~ma{(lgz%hWz`ht8p`I%eU&&ca{q+Ai{6{1V!@ef#EZYfOFRsvV@>)b45zwWr!k?XC7v z`>F|oB$x%e;1+^~xI#i9tCmg6uI12jYPq!BS{^O0mQTyC70?Q5g|xz25v{0JRx784 zXyvsET1BmrR#~f}Rn@9#)wN%>8d^=QmR4J9qBYf;Y0b43T1zcdYo)c;+GuUHc3OL_ zgQ|7ZI%#2AZ>^8kSL>&#T7PYT_M0|P8>9`^hG;{zVcKwQgf>!}q)pbQXj8Rm+H`G( zHdC9W&DQ2TFEnGXU{i&VM)RWpN?X-4Ai_p$$=d|YMgm(>O8z|5Y4tf&R?t@f%)35a-AD!1(rITp^wiUr4}N zCK3`0Nra@Rr}U(5GLk{etP;n~N;E$^&vbI~Tq`#Z7xVIjH$MWa1gl0VutOODTscs5 zc`S*Fm~)k}sjCuKs7H*o0deL=^q(e-;$}#)7D)3@mekh3inc;mY^?6snLV+!dt>hR zCFG%UQwI=v8c6Vq;XMYXF-{l{-I@sHoDA!oDolg=&%pheg$FhVh4VW)Z#jB@C0oyG zURSS$0j!6FY=j4GCPli3i@#6U&j>ikAUuqBdK6t4jynF69pNOKQXDO=7Eg<>CD0OT ziL}H~RiyqXqnL&E*D{J(Xwk|jvWj9B+Fz?EW}T^jEu)x)_SZ6sS!gG;m{kQDXXUzgFpt|IlPZuGCq=wDZn`qR|=*Jbptt4Q_Fw3t)x|Ew9QF{ax8 zbu&@}b1&vp`#)+%Y7Fu8zcJJPn<`QR(&&G2ru{d~NY(!LXWD<$jMOOk^uIRK{+ni` z3eknp-!-G!+J90;VSka}F{^0gUnF=y8L0t*z349zJZ2f~{EGySsf^D5MS}mwk*5BQ z!2Z8!MsA-nQhh4?Z>3RH60!eD85RGJ%Bb%Dtc+A7c9*}GM$yV>^xrC@=ptMD9$j81 ziLs>B*6JX@e_rGKOPU(k)AS`Q>;Kq{^d+opj7=_3M*b?&m#`)=7P+6RNMFKwM_=Sr zHo2e6NMFKq2_Aiu`?-wtB}{Ku(KorD1-8C~=@LBpBKPx1(`C=+dtHPUe!(rqp&W2Ugi!9YIKSHK+wJm(YCao%Shkk^)ib06Ag&I>+3bt*~bf_ z(*S+fkKFbnS9yJri{t^S4+umrBmXY1Z*tLjK=d;5@ACR47o7)0uOj~{|36icU-qoh zR2>;a0fFdc7O)feSh*n0vZQie)q7#AWRirQT{zWc81au~#M&J1LeZKQgg`_iq=w+nu^LiPL z`H2Zc-}vv7m(;7s@MG7HUPXQ$J*poFL}8_R-yK!p6->0ecm3U2%F%ILEe z1(tr4Q6v)zEOLOQzf_T*2?cmSfGerxqG2OH6beZ2=*lQiNPa3*Cq^Olj>e7rRLEaN z-J+4Ds4DVPA%7K(RimM$s4}{ToAS?P6u^qn$|yz^b%0WMXHZs1_)(TGy1uV zy8i%_|4>F0S^!YStRlS?iILbbi5At2{8gmZW?}^-cz|#Rno*#PM*U#m0m2<H zKov#d>F8CY>WurJ%jotG${n+euK$3O0m>b-iauxoI2p4U1*!-Mu11Qd0Obx)>;R)q z_XAJHETaITE*9C08vNkgfhr0h>N>uWrjzgh<_=U*xS;yGQD@&w)A?jn83hXIF2?44 z!Cyv3AH9xVME)|;bx%Nm=l-b~;c@ty(MauYt4PHLiCV$_QyJ~lcKxM{bQeVTLHt#u zt7pG*>i5Gb2{faqDhf#Ob(-q8O8#0#lYW>feyb#A86~CA0%nTeDG5|jz~{(^1P`oo z0k6bgMFE?ms&HNX4`tK_3I5Mzq!-e_XcAnnBHb;CSw(4ota34{NR29^s9nx)m;AMi zqIS9H0(+j2?W~XWGxrC}6kht*Fc2RFS^ucknf%=vAcV@_DwpYx~b- zR58-E_0Kea8R?sRR2j95G;IS_q|0mn5~gb>zjD$|+rYB#uOgN(l``t{W0Q;Ci~^Rc zzl;Jr;P0A|zRO4Pfd8(F)C7^HtGbK8W1(oehf6#H_@WXD7P;_5@<#GO#8WvbOGMV7a`Hh z$e;f3^Pmep3I6}_cAnwdRn^trD5yXZvBgFauzy}Qu!0G(fr5>q5hWsELoq5571X7G znqmX2V2O!QX)48%#Kc0eV6RE&*emFzfQn~-^PXePz1G@$Kj*yf!z;Xh&p+;K%rVBC zYd<H5eajeW#R!Vh$1+9=VK?e@hVr(B7;S4ajYAam0UVLY87)Z>`~QNGESvOBB{H~%@G*=c%@*(iP27eLZm)O7%9h%G17g| zzxD4M#Hgj{?=wXVEIM!{Cq#M^N+! z7o#ynNYUem2!Wa#=dj>hy%mgfkfsn8-U*73qk5zTMT&CTxaF9Z>}HJ{5EC{mPD&rOBR*_sv|L6M@|8@t5q8+z1Y^y8JE zjKm0xkfP`NzZBSKnB(I=fE8l@seI%k9;xo4v&SqWZa^lG1JU__Gtj_DPv6mndd zX<(#s8jN=LRf=L7SCR5XIHNg=&de0)q;Zoj6^t-X)Jm-wfe|4rk{q?t6eCfjmE4q~ z$N14=OVJ;CZyuACkL!cc31-2g5uoKRX`jnRC_2-{NJ}|d?h@2mitg&m-4y0X9rlME zBrv+u1f%0d813R&?uEYJol@~%r>~k#SIKSn%7BK=N6^jxhS@4=7?wvRG%U4mPAU9BytTo!mk7H3I>~kbJt=v}Z zz!rneOamjf7$HU~C&7sOSt!!&>ro!$WWhDmBu2W9eWhK$o?w5WMj+jcE8L6`Nv&XX zWgolUhnpNtG5Vr`c9+};)D*qhFJ$GP3q{nEFZL_jT8zGzT(2jW+SW#z`hZMPYA_(Qbb2+? z5F;oe%J12|*@9f+%w$lb5k`-zEI2E-g3*qCh+i;TOwp06Q}kHjVclY&nSX2d_p^YSgG; zbjxO@VW2hjczDu^5&roVnIc6w4oz6Og*SS+Kj^?e2SwDAqR1Zak<+4DoMME;IG<{ii^AxR4Mw#$y2QNE@9pCY zfzj$F`A_zr>M`J|CM89LwD3g?tRyws%3ro&jbx12aTJVhYqv~lxH+sX7=6=r z91N^YyD;E|qK^+^M3CRM+ar%OV%$4Cra48a!UzjK#R&UMIbCD)_Ay3I5$;(xag>u& zia76pA}n}Nlwzjs;E&6c<+0%Gc9rCAX>Zty!3LufvKY|^2qP%c4TvZ@-u^<3fW#;q zHvT$d7!+Nd?7WhGGG-dD)FejdS#>zZ2yX;N?8^cpOn5Baph(_G6ycxmSVg(oVV`Rs zzQ43fVD$B@Mz`y?&GuSS^p9qqiD3Wh7;WMWcT6-eBFQU))fDYHQ1qUGqAN^{c>7i; zdX?AL|DMcVPceGdAV$I{lKi#?+N0bVjWBYG7+4SVAop}L;H?NddlV9o1W5gCCFyiX%?n6*JC|8Tj zG{-1YM9WQUR4BqfU)dAocyjqL`zMF}CgTW-?BflZX?2z>NeztTeExL6D5e_Di1&^X zqnjH=Kl7OeMJlfgMMSWmh&EuLC^Z=U(sCRRBza~##)v*BFuJd=+YqCS(Lj-XB5e?( zb)hIVYP230?P=zT16^UXG)2kP2n*iMw1N>+Z(fWljFzS-6*a;M*H~I9((=Xoa75e zwY?58B7#8?ZGb2$A?-hNt9XSCEX0UCN`C)Hd#w{9CK~pcKZ#PQR7PJPYDMg`Rw-(@ zwUU)Hq7iDv=#{xMqA}9Ob!&yNWEf$=h0&RLop!yd5jwc)1I9BgvOE?%f?UKjR`;R^ z_bl%eVnp26NK2GL9GkfsIYyTaGmWVxXT)kAG2)_$3xS)v#g@T7a1f*OOpKrij+ou_qHn|6^i=0pFxgx@A+=*P={G{)&vz)&oWn(u5HatYGvwe?=Pyi_r~DiX=t_qyM&A@qhYXIYyS_ zY@$8TDka(Le;N9qLec$wq$%plU3(vt45CdtrXFfkF#6}bXaz35u=0}vExwrT#_8?HtqI9j2`Ruc^)IuexXP!xhX}@ zu!34*gj{j-_T6OFW2n*Y{{4nm_!gtah?UzteW8XJ1x99`OpG!{nIgUd!P1pGAyIU( zixCvbVb>IW*W@adEJso+7_l&u7!`~FNfuie$@%=cC(CK7)fAnRDY}_a^m7|&P*i+T zuBMaCtJN`5lHaUTj$>!rW_{I)qA1#cXS*|^c+{qB5k(*C6Bud7aXYuqrBuQhu?6|6 zfBi!t>;V?BSjderYAGr~ZV^S{olZ~QPDW|8WDD*XEuiR4E=Ei} zEpD}zJ;>J_jI`6c1V-$3RV+~(J;FaGvKB_{%b020wqDq`6h+=ww|JRxbb*TzCj6l; zM*~I4)Tm%|W5GteTW~7?Bjoq(azZy#fAgd^Q%4#xWwqWp7kY0^3G61 zj4Kq```1{MDamhVVuW=_irgkIUD6FRPVvl>k>(n@u0jHVRrmMPMm5MsnOg-a8} zNDljm?ug_Vk>;z1%IhI_|L;J=5$nS8>q?w9ZHv9iJ)sFf(nIqBBgcwAyXN$ozj+ zBW@CzdaW3>7=58Tc?KgaHe$4hB3h%^m$ek#wM#lA5k@S`5Tk+-CY;YKabzouE*fF9 zUEb;!iWI?WiuQJj!d)xKXNrtHhah-`|S+4|1A9 z*zs<`NpfKHz3hzcW#7KS_aH`K^k!=Wm}x9-|2&@>X?3sr=;Ja))RVCZ!5Pska^MjZ z5#?|(D5}NFT#U$aI-iW%NEj)GU0`yh8-dzlBS%n#e?H&ENKsA{$zh*uzc`5) z-E^aGrj=jVOuJEEW27T9_7@>W1QQQM8>6 zEE;gN0Z_z^5mLlROP0ZGrlCe-j5s0U&}wB+X-3>dtbE$a1;>P*M{{ieX?R6aEmNY7x|g(bZsN6xkP$jiTBY zshYl`->lob3j;o;C}}4@hY=|aj3UYJv;ZTO(^Su*=zc!Zj<%RaNE=h64qVlwiBU3p zjlqr+p~u-v_a!hIQFLVXPEk(ANK+%E6$akvt$n(77~!4b>J2d>s6Eo3pW&ZRGpRw0 zYKqu|9N<^hZ^1t&S0iOPiY1BB7^9OjMk2tmUyi1i93x(SVT_s_Tjo_2s-6 zagd02BFM3Ft4EsOnkBz%ox?~MAT>tx;IVQWVPyXKxPDBL%16XVVO|ue5xAR`j}Nz9 zNGfYroDX88EXTS;d0*ZrF#1f!XbUeW10yJcqpQ1{7)6(x7>OeFMTE5f%Ik~G?6*Wp zjN3ceMAIsbi&tT^UAMDi#AA|z5r=4qks{bm_7{QCb9|MinO6FspomUsjv~IGxn-YN zrOaW(iIBu-b&QU3jIiLtOq)ZKeq$`67}$=2;l2n3OMK2LeT0MQ>_Svva3C3KSh;{}lDLZG|ER zRuV>9w$WcJ>x0oY-UopZ=1Caw)S8(VwIXL^&vx$wMQXSaqo3rFc0a!WVx)0biFZPb zbY*lsJ4L%s%4&2}o_b((g5PM9({x6J7-641agHuZs4C}P1O zinj04?K=$kJVtE63PulHh|%6AM#Q*ziU{%xDN4R7TUU&*$AEPlv zr+FXn7C$sWj22R){r_qhVV~wP!ayHuQ%}Xxn4*YbqKFI25Tlx+bg|8>&-60k%ru?_ z)EHgp7=7DjnlRD@KNF23v%u&HEJhU zVnhTh7;%PFi;*sb5F@;ks!6UQ$6~}I=9;3^s8K$#4>4lhHZMjem>50XX4)b#;vkV0 zJe<)NhnR*Kach>vD47Sxf`>I~#ppCMPh2$3ixFx5^Me?v<-Ub)LJ%W$LJ}jHa8Yz~ zFCTSD^rkL-&~sS9=(oPRWu~zUInL8OF$|2za)HsqT#Q(|^3`i7I&q+go?G=Jc^@%? zqAfQ1_R1AT(e`24McJ6zmTnOl*tra6>`M~IOzi6vx8W?eqs3bS0h}AvrnKSzXD~i6`h*9G9wP2)T ziOsDJXoV3I>vP@VHuXY`*xfSIR4qoD7e#6W@J4ElYKo5OWx_>~T>zv3Bc>V#IxxD* zZ=QfNlG23H105sfI7+1& zBg$#|pcbPkMf5=-Mye(`^T!!cPIH3q6eYtbEcg^7&Jh=3q+OYOPpstTDI$c01y?y) zC`wYJ!06=@F$#=$?OZUTSW@|@ZJ9bDiBZ&(Yf*Hmc_Z8Zk1@K$XIf-AVI+%9Cxp~o z+|?MxRC}>MWDJT5|NCW@}=t}u!=>r<%FKln9c!D#1hpH4Y0j*!A$>$sjI zzfTt!1w{&JLD62_AtqOtLVFZpk6^)$sI6YK2@F{&xzeNz#m6+bnaqsU9{ zG{J~12A`ADQcli@2erEm)gniUAx1O;wHRTssTMEkUeZUD(@2Y;)>4$1Y3jL^)Yx=r zs$rmy>BEEzqlXUO=&bGn6Qe5)qfPtGY^FWP-^a=qEux4ohtw3=E;SiOd(U9R2~mrY z+JGrW+JiCEYKjo+;^O2=4ow==mTO`G8Q8!;#0gWMFh1ds6|oIR&I(>#IP2ln+tkZD~m!jCg(;7#)=j_K$3$X{Mh*2atVjBB@Vj6pnaL>Hz6-69!hZy0Fq7y0GGoLSA3UYykQV0o zxh_|+Yy%^G?QBdD*KVSSkQNl-or9tWrpjI`rxh_O7}0Q-;t})AxgsH~RFm@*ozPJ9 zQL7%Ih!0wEu=va_NsZ_xc~U|WBT>XIr52+?5xcMma)f;yBi*vQXKFBF z>aC6u7Mz);Mqt3m3+hD_6^BhHB#Ib&P?UrbNsT>+4$j6H-PER9i_w+ci~C~2!(t!i zPxwXAZ=9mrS5l2XKU>iKY!lBzcLEAmR*ZjL~!K7rg2=AnbLFG!__8 z#7hCLCdU*#R`)+(#HA9866|&4v?4}e#MGnX=7c0L;Vz7u_{G`u%L)O zAX8-DKQT3;5DJVi;HzVVc~Y%3VAN1_ntP|!DEja~QQ~ufEknM`Enh^d_&DFD z9^K)b)G4uT`*_MJt;UEPM>i=k(tQZuZNM1`qhi5ZF?#gip64mju1w{#C`yeQ&0vIi zQmrI|t(hh<5=MBZMHGE*2y%rYPS$Wn6x1K&{&_J*y6`wRi;;?@!06##P%DOAG*HB@ zL?dmm*j`az)a`GaMI%rsN?Mr7Kno*IEY)+j7@coo^s5yx`iluhP_(xR&1*UgxTJ`S zNQ%c8X^0UNVZc>yn-uZ>RS-q3_-vbLvf%R=;dH|2@j+l0DA8Cs6(Fe2?sS$chvY7@(GU0O=v6vrY#EET# zkyC_sniHd-h#&94JyCK8MQMx?7F;cNfTXFWPUyl}jHniaqYJvHm|P)8Q;I%dVsw7@ z>u&RYpeXt2wGN1gV8ZCt6-JVxH82_|Qjn*57Dafcu^5GShN7e#rwi?p({v&f81ccR z5F;?!au6fjb69Y#+ln(njCjm*#%dI$yu*k>fKO{J!bnMO79*!fZ^Or8#OgjmSo8si z5kc(_eJU8SnMaI-5$$B;G-et%AnJqyBi;-IMnRG4=cjs*)2YcC6s5r$g*l3;w*L%9 zymowp{qzhNoo^V06!AV5d#w#eOA%ebc%bRZ4ELO(4ruLl^g&0P)Mz0W4R?gJD5vo~ z(FXWLtDI3#bb?!OQAEN0ReuBP5iHq6NMt>^G9N)s2;HjI^4fZGGxZDAMmgG1I^Z1FmZ}q)4w9<6aT_tW}D3{|!dY z(D5cUYf*H%%T*a^smwHOIVhiHp7?@Wi;>Ro8CWt;>bRqNq!9{=K9?={Y83GuF#G=L z`e1a8FJ@)2wVKZuEue_i{5(a`EGBZ;ZoNRF5-3Sc3o{vLVZ^Bk&WP4HQ*gHF{lOUquuEj`uuy=Hdaa!4mB5teY zo#_=%$lgiSWSYlF=1F}(o%TbF3Pvg?m!>EU?PQISibZ^n`hY1$Di#@7j?oN7+H=qw zN{kfcbQ{TfU(I3yqjTJX>(HbXqmZMsGe&9ziWmh(^oF8H#nK!_=XbmIaD-qD-iYrX z6^#CG!07p-iKZl9V?;4o+v^DOg(5ZFwHQq)N`i=Y9()5o)~Tyw1Vm>x7_}5>4|Ybj z;ByqwE7AyUorYx!+y5FPH9{dqluBbU(#M2Cj1=TriWKF8B9)W%NIRfQs)Pa~%oF`& z80^?{fYH7EQ@isR%~7Q1M?Abm%{%PZ1nW*|EJm1~Gfn@h zZgPwf8;rn67Q7WBt>r_E6y(;Aq7;{}>xz;3fYuqsm5?aHJ54FlVqO$!Dd!HG{eP%Y zltTCNU*}PlLymaGCX7@qN{p1`>bzen>a$#o6y@5HhVLm99p0x#jWS03x?^DUm;EA) zUS$}SN{MIIC8QxnRL`PF23+N}&d}(C-1MaGqdwD^dGi>ZkTFt@Q}L+xLYisZJxh$_ zokj+GaL;iaK#(gG+5HEP4^;`3BsUc!WqF*D8t$nWacm}v)CcgTzvztEl|=|EeSlGv zh6Y=ekV05Va$_+H`^l{=YDPfTR`Ggo2xbCNHJ`;Y{6S+ z#1%+@v}^WG)l3^GdcRY2hrVSE1 zMQ55AMH^5kN@0z_=#0vO&tr7@F!frDf+E~=c&Di|VxI~l5#wy6r6%noMv7r!!C93| zF~awR1s}&W#E1}f?%>HAhp5J~g2z#m=5?dU=eNrYQM^_O-@nX^K*#MoVL~G)4UW88eL# z7D;XijFzS-@ezPQjh4n}X^N6}lc7dSW3)6y_WPHW8ZC{{(iG|bBSP5H7%fdvnpz`v z^VgXerN&+_jnUE+C1v>yI@8vNqSW0c-+xT3(RCt5Y0h9@hhmf#TcdRrqh0zZ_Ajs> zlzFeeYmDl;479IyV*}1xA-U^Bj{j))l`eL=N^#sfw!Y}gT`W>UtfDVcsd%RSoFIKc z?VL*SD0ltEZfwA>pKO)J36XXjr`uQSq5}^DuKN&$H0<>kIt~cxHh_1sx*-xnpYLLm z5;3l`#s0nhk*nPG=LQR&qE?DMh;kYRdu+kEdgMWMG1z0d(o&YrC`MY;mtn!{u+N&~ z>@=Brb=udV(Aa{vF^x1omaFMV8(Z-3*XhajlOY)FPjzFA3M9eE7^5j8V~VDXj3`R} z<&To&&#>P^8Dqr4wPj?C(Ug%fMN>vZQ7SoZ3dt0sF(o=gsT+YYB^>eUx-z0%LrF5{ z!zWQSr723K zT10G?#b{}YlHcK8Y%8^Eh0)R!rM8=#POLw&80r4!^OKo&U5Qa@)M#mpmZm8A#S$ib zJhQGFF-m`gnYKP+l=33%yooisZp6rbe{X}&wDqA#$CEPQ8)~Mlj~J!*cWckI+Fo;d zJ$6Q4o*3-$Nc+;nUuS2O{H+h`)Gtm9_E?P0ThkeRVNHrYKl0c1{p&^6Xz7`@J|ivp z!;@KSWEgF=rZd`dO=oo5Rh^Oj{_BZ0_2#TmjnS>wbVj$Dbw>42+jkVwJc1=(lM%tb z-2Je7Vzsg5OIM0uc~xeNe91u51$V@>)?nkF|03VJMNDfcB4ItKifQ)#@uz;#SPV81 zYv+76Iq!`4UIG?e4@$JOZ7Je(0}Ecqw05MCu*`y|e15B~Z7W7>F<7SPT4~N1(HmmH z7aMFs78ZPwzqaq69c#V^3%;7cKGA;-V>N^Q0ryT*gIy?ke}@GRf2~WBi~0Uh*>t?F z>sQ7gad1>HdTqCFe`u5SBgqreK9VVV!Lau)6zRqchJMho($$tE@yz-Le)+-e2U(sC z1{gh|DV1uB=nTQ=@lD#VW150G-f5A)W)Ef*rByKE98nlO$IoxIC#f;QJ3B@OT3NT% z6loWxmE2rRv){i{R#%d%H@CGj3XC4(=Ss11t797OSwU`5OhaiD4~_0E3hzJSCNCC-h4B4QX6-K%MqYKji+MA2)lF-m+2i^`~A#NCF( zh*C*swJk=BtH9_V^WHxwsu}uzC$S1C`dQ_SbpLZ+%2TiG{tHHY-9=(VtuzJ}`Q^ zzwOq_?RNu5TFr0dzY4uabpcQ)QkWM-Y4>V(TQE|Z7eV)QS0^Dl}LPs*|uneT}yFV;!)4@{qHXe%-6Q?MEmtIC ziniAGPnmk-nHCro3mzRd_x$AjxD(pae%Vm<^6%fr2IGqhG2)2^zUaJe z9-~4LzXLa>i253TEsF3xa!w{jDW8x;+AkP|1z(KOPWiRKyYdCen4(h+wAhri{yLTz zr*!uIDO&EkuvWU|D;`o-Y9sMLfU({EG-s@5BuzD8RALxn6pcWQQKb1XMnMrlO=pWW zMPqLi6#a0eOM@Q0)F0l4ITA)M=w4^Oh@aZ4Lt35WS7yYhmZC43)I^LczUY4blKz$U z1jD}nbDlxMLjhfIFUIJ3{=uYqjHVP_-#+WWhaDtFK@l;IAU9BC`|rG$R|uQONaxea z@^zBqy@=Aj7W0bo@=kgUpfhbbBaO76=y86?ZTtT*M*F*guKNHmI?umrvn4h8wk+=A=)R{nZR z`~GJ(MifFHw!WtoBQW9YA8B4TX6LOJjj+anxiOje!D&x=|hYP zVYhSdq*|$^XjlK9&@qE|BFORS(FsM#%@g*Chb8kEZR}$7=)C_Y?-SF0mpdVx&-E*c zUY<8<{4v6;jR~+htM3G|L zm?CwG-|PM`h*749_pguj*Q=<}={~U}M#6|^X*i>T(dX@V;IK{&Mn;h?gldZZ-k&8g z(iT&c$Z>-jWsH>N*T(3S?449A%~5o6w%}ti8YtrXcfv@8K#dV^6cxk5g3n>3ERO{b zir!usY>hO+JijEyoypU^5fDX}_Nm247W`@cw4_+TRU2E7QY&Jf|IlH;RZX_O2!;wpGTpwXX zBPc?O*rk5o7-=aYq_q@XV-%(L`e!4`Oe4ulie#VlgfhfPAq_DCBV5mA=ABrj@SG&i zv@Awy6`|;PzDb#-DA`9B#u)Jv>EtwBEY=udp6CN682JT#1i9%*D->xZ$F4*aC9Dw` z@x9J5MrZodBYvQGEsSc44zrOKjX+Bg%_1@Eg-($#<+T4V7Q4mhKHdm~Hjk_8Wn?Ed4{`CFd!(}b|F;PV(^pQ8`Z%8k#})D%%a zhZw1xqyhY- zUYV>`R0O-m^r~RA&43Z*G*ZORC~F;8i;<*g5k-8cNX`f`DipDhqgDDzpJa`&*RcsZ zcd+1d7|{ov;uf477Z?RaCCaZOMf(0N%aR%+(mWVF(BFn*o~V_^7?I_R1s_u+=QBr< z%12R@P@{rTOf^|-#7HrWA0LlKfR>w>#?x!ou3)sUiIGe=#Zq{qph*6isaJ-Y#OT!I zQ;lDDoMN=6KawtO&>u{U!aC^)DKI*IAw_&CHp=OiB7O(U-ai(5&8Mia&-^;mKMpeu zF#;n!O{_8c2Y*BA}`m#vNw_PG_K)BOWlwHQ6we~?ZVd`yu#A;f4*(TDi`qj`+9yTxJ)qpSRP zt#>go(o|DH$Nqt%VUAjxf)^x2ea^hmzyC zWh105!szEs)<=p8MgQv80pIXl8d3yBtT^a{_~i5Rl7WUAecjb)j1d!yH{a}a1Ebqy zXT(fv#b_}_`}jE%eE{X8IwKx)?AE2H`a<=XB{2G8Gt=Jk#hV>#Sce zy2QkY97n?~F`B_>py;PL?eiXpUltGd3`PGuLs1e&_?}2|v;p&CRFd2nBPhZ>%YxGf z)MCWf(G=z1=-z2hKYH_##_vBAYxHpc^g@`YBMl^$C2~eAU72aK7*!N0hTUM6B3)T) zq-|niv{j#?5>QeLjFjfb7`?@JAvH!{%NU8G+G6vwe1F#6aiD11#$CrQ^_tY(Vj~Q= zN+n4VDNPui=e|c`^ljhRN{o=AXV}_)z^Hq#c_-~jxQL9#h=C^G6BK>3qUcd3MoDT! z1Ut9mr<5c{+(aTqV~nuiQ;aAUDW_|SK0Zqk?pd3ZEJmqOqo?K&Ci67KC>o)_NLOz- zqcKH?4Hmqn=)1nU7e)KoUu@GS)+th>lJ{@cMGONY&MT=WLyY2BpAhz7ldHN|k~e}P zu0Vn!rXDu}cq6_fp`k`aedE;Oe7?3)vRs|i&hcM&1f&1WV#H@dWUnPfTFGD2-P|d< zBA>FAkfu%%_gquNPnydYC4OW~7+q?<2LoO(x~~_HZ0)BQ{cI2;Fj6@!irAzqqKJWY zjt9B-m;twumOQ6vrqvkzt)Es>D~-j7EH8{ma&t2cits(fg12H66urpADDCAZ0xAS* zjC9{|n0?EFbqcjo5u<_;TMRJLQjRNP$qY6In%}UGeo}XB%rte> zHAYcTmY@bkaz0-lD2kzmGvbRP5~Dvgihk)M4T@A=`}^lJ{IcV_W{d(O+JNvyh*81l zcin#*BNC&6ktm`M3W~nvOIyTfOc6iMG_(O}!(cQ^(aGkWc#gXoMMDCyCJrBkP0;MKl6W_p>&FT20ZNyPvJpjlj$L6y}IyqJj}wZijpWfHQj2 zfYEPyVZ^VU3nP9~Q(|sWQ7F-zpIIq+0 zHWbtk_8+9XpL0aXZTo-pNNN;m{st~aU<62-X@I1ehJgknKvK)i zRMSku8?_X{kjl;khX7+s!k z*-A(gMFjam(GC0qk3o@w{D-*zx!5rJgxPEAfH6kYiUlJz+*6GBUV;{Kv;nFf*O8)> zF=C;5j9YNkO7j@K(Lm!naOwjpjMjsq{rvMxvfxMdNd`MGQVa`>I1!k`2qsvU!(?>a>{bBc&@Q1m$8fxwU`N|wO}jBeQRb) zvZjddW8sYGgp8u(=1DJ@OpOLH3XJY-dR4OA)4k;mjM$e+j4w>m`;7j~{+YE3qgjgB zmod^fN*q%ZaX+bCys^cwpRYug<9AROVYG1{J-4Qsyb%;#kSXHV&Y|ep*%uXxerFVg z0hbs(i}$agMl#P}M2>4Q(uRW##w9kexQF|NSCbhdV+e|<6+dXMM`FZMS5JAAiVsw%xITmtbia0fUiHEQ?C`wivV!?GFFcu?j7TJVx#rqt8OgR-JtyGtx z=rp4!p+-6sVy4l9bM4Jclg0j=AEaIFY5vak7s_(6bPJ3`5zYsS6y<^if&{B zjTon_A4~h1qQo-*cD9kyYK$)GXam4#6I;k`HT2hk5d(`Ol&B`hVniQwvQNFBh#zn) zBhB1%^5>_Rr-IQ&oz`je(~;#l&?U*uixEqVI>>RR%~Dn)O%&~yDSDNUw2$PGmi}N5 zhcMV+^kf$!P6UqfmD?HlNF>CF;*hBqhbDS80!D?RyV&n#K#_W-pa_SJ7|{udBHWWv z#P{F%4FHl_Y&wLIO!$5L442)lFyab?nf9Chn;9caIN!eE$W|2bOIV0eP_$R$i=apm z?50Lh3XJ%DDx^sET1ozrS&Uwh_hf7^5F^iVBZ^+`V)Q{5BPim*$&?~1r<1Q!&vuNW zn=BX|=*8l3-uIB?bY#MTwlHE>c7T6w3iliqTw(-8{Io}*=#6=oQd4BV|H1u-`e}9; zGEeFQgpr;N-95kf+0QLFNe*We81eiJ-xCz=ZH>T~B5ljG3)?Oz(*B>BCX8sPx$tN) zlEqeS6xHI5U5tbg^<)G!QKT65^OcBl9CL@mMvkBeLe8Xsa z7o!>@?aAbw!3YD+vMngm(q6mNOS-GOh;ce)(3L`choTP!# zmHjUqBeI;{1SqHpBl%}2k_p$+EiASuIxADeFYWEs_@XZ)S0m=tO*aYyzU~+i(!fZ4 z(8b2cJVjhi6Xf|-9mP1rXe;}dI1d?Pqz+sSH)6Dd8|(x9%Xf&;Np8VwjMkr`7s)%N zp`8qaO$ggH`yR}bZr;|wXcda^PI2`{Ow&FMF~UFF@BiM#J{?YyQ_BrTbl9J_e~6Jf zA$|iYiY18=$3_LC8{5gE6xWoQX|0XRzXeP zC@A_?rf4fKC~Jz~=&b%TM$yihqV#M#nx!xzrF|jqFN9I#IDAoHq$e7w-!Zw&V-XT6Qg9cQNak`!>4%XF^V)F7|{rn z@=*mf6kXXvk)j+F$zcaY^3RvAD9R=ih(P^HZ%-=mQWVtz>ze7+L;}dFp}DPpmVNGtwCm z6yba7AXg5J7-B}iwBOOqK(L>yVs}Be>s4=Hr1BApR4qc$ z&I3i-l^{k8wM#vQac3`z67P0}k@9{l%!JXl14g<4K#TxMY5u}KFjCK5EH)G&M;G)^ zBohura3qT0$S6t~qrH8i6^z($2&1bFBMi9u?J-7*U{_^|*pkdsbfHm18!)CQ2_usH zwZVvUMNyBtCs9kt>)_FI89Mha0V;9cI8K|&Nk=s z?SUe0O`s_0+z2%SqZ9iFb^91b&&d-_I}k9^GWF^Xj8sgrY!gPYZk2bwazc?pnj#n@ zO%&bE#OVIXyGdpmCq#kK$@UWjm%DkQnvCL+i$-=F$N6P+gV8_{H$*|v8#6^%@aubH zq?pD?6GboT5>t=!fH6kV2ni!yD{+ccJEO?*EK^iYvbK%19~9x9OOUH6veiA`Khv50 z<138b;pRxrD5}N4NR0r;NYNTmE#iBwvY#GT4-Q2v-56&B35w&8Ck<8N^M!e>EkvXF|iqtEz z!r0F(_zXqde}EAS)v(~Il@?+28h-;f!pJG&U09)rUWt(w+cGtaqA2P~-~X?M(ZRDA zUFb6{vK$zZ_whz_LP*WoeN9mewU(mGO^j^+OO^{Yim4`yPU`nDj1C#Z=y;n~nrYcQ zcUR^dhZJ#yq^$p8?-UnNq>vUArL*mqO9LaFAr*{ND+(i-C)xm(X}p1z7_pS+b7L&z zqT#M7;zEeaXvCJ4!0khJ;weq(4gpOe;+Gf6k?QcJvByr z^P$FwW$HyHHDfVK=6Y~O(FZ}1V%(G>?ZFsnHAVD}d!z=V6W73q@_81cilW1O>TzV! zjOT^K!Qgb}`|7NaoW478Ra z#uXHm80U=<7`>&!=&TB($Jk8cIs|9Lj)V7L{5aDTBZ^0yk;Ldk`-??l!~z3~!h)xm zX|6^CMl9X6*X2!jZLq;e*Bv!Rt5d||rIw<&61r>h8a&i!jFId!wUTbV=VluInJ+pQ zF_JeLQ&buOQA9!gR=$4~7;Rr+#07xFh-xun*rqwl)fmYeg?}z$REAnmq@kvPc65kQ z8YY_NmBc78LW(%gC#11%m3h9v4LGj=XaiI{LJ^-^;Bo5N#t7@U*!=TGc1+QUb`Qrz zT;icEGYvHYqBt}=#y+!JN+rF3lrwrnUdr?QG%(^zk#t79rB-L8MyRET2iYuT*|>_L zhb8kpntEy{r(%SCR+4KmQX`~eGsGx@9L|W#NIIkM4vYCM%o)jqb30j_QR0*+N}+-g zjX;YL6YC-aZHiG?Y&xN{ZR%;a%Z(LGISf};Iwq(KpV02Mc4ltPUZ!X8pt z@bOHe5kib8p2ir7BEB6AMFcsuN+0w6KVrm%wJ5?p4;1nHx1mN#YKReO9*kt4S}_tv z$Pr>hl9RzM-l%j!x6dYgOi>KAllv5EL?yt|O}h|bq=_}fNQobB^i=akU?hs(k#A;M zw&ILL(S_Y_vH@4UEnk!=N?tr);265H0#c02d9M@trrU>t(R%xE1y9Pz6u|_pUHyJSEUa1u$E#`$0-l?8x zEk#f8A1R1>Qewn|kDw^E7}ZHl7?I}ZF$y`tKW|2s%OE0ar;9A10xLh3`S1TS>5@*)eVZYkkv?wKIk*qJMj(xcb#IQQ7azn z>(mq7I;m7*-Bz4Y!H68EYEoH$N>Q=kV~WB(J4LBcBQVmkOy%>sVMHIGcarLirWF0N z_2BaqCG2w~xq?yDMyeJsvfskcZnvIk!bo>Q=VUQbu@n^P21H^03wc<%O)9AoeP1Yez6w&s4U=501WMX6#r3NFOo$>V#u3jZZVZoWH&Q2b>?}nzi&0U(r2o|lV-Jeb7^6qn zOxwSIO8@E#BTlb%KvXa~zrsipZCxo+kSEF;MagfxLyd|UDai*$7;qhE7ctU>P{zod z6MGVg5fnXQpa}O|C}P`IoYAgb0wXS;QKQ8e;d`PF;CTAg+)jG`y{;IAH;SpYxo5dn zjCk$%Nc-s-DB9mB3Mu0AGcy#WA;(4S7*eDIA?$Os0j<4`KIlY~8ZG3Yh&EtK(Hn*~ zKm)B%o2J`^8-9 zqeimNk>uK$7GlIfVqiqARGbkPAmN@xkxY1@NK04M&$8gQ|F1E6yFWk+jF@^+EESBj z=MYAJQ8fZ%iWKJYPI5+Lhwa^BG6TH`qXN>ayLaV@Rv^+$Qv^ed6yrE$s|T9epwD!l zcJD-t)5=pn9Gb7G_| z2j#OYIA3sU#YkuP3@mvkwMtQ7(+IKT;H>p3dprIwed0u5F-Cj`EVA5c7!`_6@WpI+ zBf|Wu6eZuy&tnwTBEIJiZl6>wm7u15nf$XT;?#tZ#_|?#6mqniiP5`fD6;p@l!|P@ z&hP%uXC7_96eG4^V5D{27$YcB1p7e6&{&ML2YZ7%r`#zex7S>v0THf8Vnllx)#O-= zgpn+``hYnxDio=lEY7H=C`pahAEU_f!f1{n^@LepDtqU${IrysSzk*R495$rbxY#C`!zMShdA280|V>bmnNH zO)0{Fw_-G==*Z*^cc{@kMw)1R%j%`RwcDC^f^gzE{6)Nr?Aq!9LGlH3sF zS~1dEKEz0^Qbmz{|7$~F)KDY~KBg$5JYs}giK0|vq*6#2G4(LvEk@A^{qVxg`pY7->7F+;Z154d25|6GpO6tr*?gf88-K`l$Ud(L6<;F^cd-!O)bV zbYjMcna7$0h;)X=L?g++p?iPT1{5(W7#(Im;8ogyIg0qoDkDunuJYH(+v%{+U=&Gi zF-ElD)0q~VFr1MZ?y)n9^NteazS^fojfPEF=>w)1DTIXupNdhqXTA%*h$3}D_8U+s zXSpdxO7r~QZ!`jNWXrh`7%7I`AzN^EC50k}T5$9y**lF#8Wg2_x*EO9et@`!NNX}V zBl(`laWT{N)Cj5J!vSgo<}rG*VH6g;!l-g`LN(%gdFjH zTNWFT;OJws6sc2WTzzUV-~&a;S7|jyk>eJL(d+ZnTQt+4NSl;JBaINIP0Ibcq;rSZv7pHDCcsN zCK%mg8H|>uC~X*wmZpgB9~L!Q8l$Bt^7{|ov0|UK*N1=7%fea{r(4E0NJ23ZGFUu_y0VFjI@7Ui&3hl+H|J< z(Zwja!QQYlZG9+8Q9Y8=T5EKjh*6rP{p(hY(jQ@_&4|%gyRUR#wqM%&qJ1HhhmBEQ zpPh28_^EDco;Wh9ol$h)gL(3I9wnx|e(1o9cdFAq&Pbokst z6w@9un5P2Tn4+l#*J?kO95;!fm#QS!`xlFf7^!%wvmBoh(N&}N9GqXa?n$RcoTG^& zK4lS0IYl|`(`bzdYUxz_aQJxcjpc}6?`gB#*kZpRS5L)+^QN{QYEPWFCwJJ%>ql)m zcA3n*vBe%kG$!PI69dl5z9!^#!)1WFfb^E85CW0E^Lw~D$CYwgggj}IqLxFqee?(v@}Kb`%fEurmYV}soU@~ZGFTj)&1lKnrZ7J zM#t@!1VFDfQB}rHBil2XyKF`EXK;l2(kk-QWzRUbnRd8%C%v7gNL% z0}I~9w838|OJUT{Ouf|%_7QHud3aLl$qFN*=l~CLZA@z^dPI)}*QH6^k)+mO-_tF4 zEKB5#SgMsx$F2H(O|aU6QaAl!vHO)Dc0Xv6eofKqJ5lr{t^Jd~Nehg$ZUv%4eH~XP zeb%k9x2H1%qjxk*+nOR47*KT7LVr!!bC=G(|8}rH1&DQ9jS+jW)iILq(L%1Q+iHq< z%p;1nuA=@xQL>vwC3Usnb=ogtL{b+R6nEHT1k?sF$ zjM#D`s@BLQnkIUF~Syr(f6yu zs9^L4Tet^CU(9E2S{Y6u*o{jC5f#8fnRE#TKJy4u?pKFnWxCgrx0^T8i#F?EZ@wsWS{Q z+RC47C(a@VH5x)#tmMi~TZoZr!w{puh%1tyD0X3sDdNdbrYQN;o11C6@F*AsNE~9T zTC6bgdNRt#B1SDme>)r`6^c@e(c}GD0H-8HjD!(V^u3|G{_Idq3!~TBzzPe_OOaZP zf}(wg3ll|s7o+5tXo1mR4c1A%s9+RQbeF+8>6-08f9pXx9Se*t1`9qOX}Yh!Nq1Er zHzxP#lJ42U8pR&$BC|%iRf-dmz$i}aTZ~qxXyb0|uY;l+rQy(IJktWB%ZH9TE+a#X z0;6KV;~0roA)GZvv-n>_$vvhh#i7u@<*D}f`GryuBaWyMqt_1gWZbm{Mo}#uIz%}= zQG%l2h~K{MdQtS`qCJO;x7J?=Mdv01EiT@4h!kQJjnJuP z!K0pRF^V0=o6Lg8xzapEN0({l_)2R z9b!}{DpAh-bsDVEeTR-3^Q5)hSdOmWFTf~M#6*LkLk9z17-9<|itx_+8fV|J)D;8;l~!wHR@Rk23Nd`Bd3q9>D^m)BJj5b&B5Rm$fm{M3H^}r^YDxh4z7Y-71I_ z!q6*OCm?DuQV8PVD7Iz7=o9(WL|1L1D2^5vQAAMF*&-CBz-Vla0;9jH zFxn>{Yip(nqaUuUm@nd|_NEjm$UkwGqAW$pwCG7DHB3F8M{L8m@Imyrddx4MC@F!C#skJ_6MywSQ+#MV8b zMvE|dlsljQZW;l;YZKlGjPTERr{L(h`I98_MnTc*nnpl3woXwpH3Fm`WsEM%ryEJ6+$<5^P~fkF-Axc z_PG@!Fyc#}P^1ucQP2B0oYNwT&dC=1zR8muZy;r``AEzX7&R2>LyU^@+q!p}qX^^k zvOc|ZFi*Tr;?tv3j4)5wCw3)MF#@CSG{q9HMi8TC8g`XEuH7$=JS{i`riA@o<>E`u1g z82wGgh=Cw}_K>h~X+X{%xMsEHUU%MTbWr0CS_ zom5Uv#VFx>WWm*P7crV*v`I%FP>T^y6cxk5g3nQ;C|^_b@$lEla++ouX`Y`F<6cSq zq%Z;`Rg1z%7X0u1X-V-$DyX68eJ)2FEYT~~6*gBO_~)RAUMVrt0I6W~;}yhcj1f|# zS`qV%7)2Yv^$1%KJt>1Cyz?&Jfa}G7j5LKbr05|&u#6(U{}&hmk;F)SP+;_Sf7@2X zs9?l5pOxffu!Evo3}S@uQIJy`P&y-=(WQO5#4n$*PSH-bVx+ZvV5C~9#YkB`DB8+f z?kPoYG2g>g92UHyDA`9sbo;6h7Ul_zkfU0R0wZNPEpAIpJN`+jOL;>+eO zMt5?IsFaEr=~NMn*kDMET8j1`T16t*jZLoDq!8m;if+~=W*Qis;H#8%#fV=>C#LCk z8ZqL2UItv{{zSlX%=*Rw?mLDiyABuK23oeS% zH~f1g1tY3OFuJ#kk(P4Qlf`1U7=6MU0c}gd8S$Gk_wj?XPfjS>tEDIzXiUB5`+k=< zN-ah|S^4n_81YkkpY^X8G1CGgdFNe>p<0ZT^k1A0I}jsL^aXE}-kkllC`w>-7yEZ( z1C2tU7Nhg&dzC@$X*; zMhaoVNEV!0DKOI2D`F&!l;j4C8j5hw(Ff?AB#*N3*NikMqJEYbC8i#Q01Y;up9Ld* zlY7!&8m*&S5celTYMu1(3C?cp8imn)XB|gG6p(vTuV4h;CQ7j3g$NAb- z2D)HGJ*lZyi_!J+)C)N(6m4TaM!Rv}Qgp6eRR={0W5h&bVv*x6^Bl)ai^7OzlzF6=vMP_``0*q8X&S4Z& zO%@w5QViqA$0N!GMZB10c`yI`$!x;85eRRT0wWn{rk>*giD@MorgYLx?+4tX6 zE3J(YpB$~l2#nMk@|<QS|1@f^%P6C_24=8=uHq7mN;C9V373+=|i1tiWz5+QENU zTtO}J`Bz}g?^G{NqD1Y`g>>$G(SiOM%0sdqsaSFElw%IVHb*s zVgI8ZJehq$k7A~2@hXfynWtJ{RHhmj{dDCgE4SF__x@9Rd^aQ}T20X%8;ZhR*AyjT z^!aR!gwa#{r4M}&=K0FLRFieq#}`SAE;KR1IZ;inP0>Mlr11qA`~4qMnCvqcJ!2t8 zOsq(9RFm^!RD#?bMYv~KaQXnmD1{pFtwv?}1Km8;Gp)vmffX2$z&jzZCScFLrJn!9wq_dkSxIhQ zj1`&APNQ}Z_W3VHJfe}kN>d6oz zz5*dJx~;{qF-16RD59da`&X$EQ;%a4iP0fm90f)g=uh>ElCCJJOoPG=~u_H?>j02m{S;*oPRs$G?sQMyjZ5 ziXzIDpvI;{&gXvzit3XE4ND)jFec0S}e*ZYeh+k(aZ9vSl#TYG1(VLQ)C#_1Z6-H}P#MI-?M6FU0qxANC zCUosEDiq@?b<8AdE^#`+q|pbfJq8ixj;Tp}f{18d8LN z<}adCDvi<2^QP?L-tK?SG0-sJ+Wj-pVy1w3blf!DG18(} z#67c;Qy)+}BftNMERO|`Bo{f2rK@HdzDMRMFk-5yGm2xgLea+NjkqHDs8`r>My%!$ zBMzE)G4S>N>wNz|Y9sAAb~LHs2kCy{Q%x&3~%!23w`P#Munn>59KtzM--`3;;jh1V*MIl&qkZ7$H|&y|F0?icZLvuPiZYidfthF$#(j z=85yl8Y4bQgBZ~X38NeOR0AVf>>8u%n_PL8^C-vawot^rj4)qQgdB0Iy|*=s4@h<( zE9dho$4FDH#%SA&(KigE-)4-8FN$iK2(}tU3i229m)S^DF{!9;?_Z}FMH_I0{LrwEaZ$Lrrz!>LS`^3Np2BF;hj_~MQ3#S z5akc@AU7{YqA2ZdGi@!5_H;2~>S=SUwd|3;=U}GoXrS@)O|dJXHF~Fi*k~<^p3V2K zm}y)kjxmb7uX1r?18FmxdTIpt9n=b=hNABbJ-3D$3w}}b^A%Bav5OI(ZcH*p1*6~e zzwX0;ON{uz#1JF4U|05FbZLVT6lqV!9_&Js8t&mf^OVMw}Ae&z;ZpZR)8Jh}CUN5zYsS6y|Zk`rlq!k966mH(;#pvbc zo@K$+2XLnS!~V<3pA8Yhz-W(*(S3cUUC*W(2Kys+)ri3cqa94HwAiea1CUkD@aC%FI+ zMeNJupEvI?;W{?aLDD|GDB{N*f4=g~m76A;Y5c(O*?FrkV+2NuVCS0{DaQd37=^u7 zlD{yE(P#Z5HbK$D@}5i)>}-=O#W*f&gQA4IPVSBBL5ox|)^bMDzXpMrRjVp?% zCnKm;6eUxm$a2C+Neww_F;bQjMzYx3`L7x~MjKr{p-4w&tS^4kiy~rNp-4;n#Ptsm z?5sX=oNn2)kkz_X5e$qX$AJ+?Mo1AeO%ZI4BCcXtaeUT&&xE3stx=5;=1I3oQ;ZbC z=)keydwAM6j0TEy-LdWzC9aj2X|6_&5eL*y_bo;wxkVW5IAF9oMca6kimRW1#u*afwmEh)oA4X^7D#{q{}~YdIZr*Ayv+Ax5|-8Ubo<1+}!3 z{W=Y5^b6F;Fyg27&NgFIe37n$a6RYuVZg^2Ev5)}4MpmM&NiiKC`toHYNx55g^^07 z11zU;9Wus99k?29#OTl6U|;4BSP`QmOs>|2qO=-D2W9i5TB$5$)dF;(b4t~jMNG78&FX!DesRd+9^{+L5Ua<)Y7_Q z6b5?pP9|I@OT`;O(T$va;hPbi8A_L-WZWD`yHnnf8HU6{q_lH6}|5vhK86=(t`nj*(U<`n_+;vK93Pu9`i(!W93#mBORNuQpJLgDbfW9QqHibHqZ%VX`o+q(R&KJOVh z3q~b|2_sB6Q;nafWUB3KBMpi!uP8ccph&)mAdh!W!br_zvDaL@auqF%WWd4bC0UG+ zB4!%inSmvWw6di!Qr4$c)HW50@J^zLm)49lYZdwZAJphgHn9RDHQb2NHTG$0X4;4R z0*IN$VP%Ms&WyfiYkOsR+_R=06wxZl8R?1$ig3@ONPWO*VPVgwNU6>yA21P0#p-9al6g?Y?Qq^)Z(*Q{gHHY@XhVigdtl1C8H5*urNT5$wc_k=g(z8YxX;#Qs7UDaU~kA&uhkrhcp_F={DN zNaLJQVnmQH6dl3)$4ZUzi4bChc~Yswo&Q*jc*R^})KU~7Ok%{kZC;Fa?~hNGpRYpPbZImo|Vi zBxV|WvcTv~_M17M^YW5X35wW)_)POh8X9SH6tQpBNPB62V9FR_!5`_B5s!*A(}dAM zKK0m>j4{%|BIR@R0aIrbQ9dZz(f4g-q^0BiW)b^bl3a}uheX(Cs>P%H69dBN`tFTB z>L=FBG^)j*2otWwt?p+<5x!^Z{y8@FLX2$ZmIjPUniodOa&6v6jKF9g`^Dda5f=c= zw73GnKLPxIyjAC7;Qb-sn%dL&kCce7G8L6OFCv*cB zqlj{m_whzFi&|qqQ3{M=sTxl3xFo@B9euh>kI>{JOj6;g( zl-Q&((C8G6qBM({&7>lA7wVe}*4 zgoGH?7^&sP8PybV1;j@QwUiS@yr+HF&@6J4_?#|Dji>~;00@k**h=$<*pG?T7)4NP zF@mDlmJrn9mPj#dpDs+eDEgPd8*Oj>x2e$;hS7zN(TV=ZS`%#%MtnM?#)xI=$tE>p zF}j<%9-I;7G~OAC)CLra5;IK^j6E1Lt;UFn)?#$PEJlSQLfBZ0#uV-DLytYl9(@0} zR!bnTG zDMb;(T8h3g#QnX~phkQ9Oyg2lOE+O8Ihw;LrrP7}+mG8DMNBpMqO z#3&3nzUXf{d;c10M3O(&F)BGu_L>bx!RYV`qy5bpab#2|VqDEpMDbX}=m6u)#VGl@ zE!0RDu?GXAFi+u(T8!{L+UxSBdrXmf#XYJ%V4k8B81Z_k#fY25zz7RIFGlh`P^4RL zb|q7aw(eVsIBIi>Qr>e2Bd-L^gohZ>P{-PpPUtz67;yn0F=FkiG=D>zdU8)SMe;`B zpNkmbjZ%w|rkW<&i4%}plPJh2&FMb_Zmtg z#0ZQCVKPrDC#PbBd&Yw6*-4>DjZjMwL5`8eNt=cJ^=&wR^581XtOFyfRbI-!CQ zjlh7BQ^dg9#z31=6yAtV=!Q-a7XsV}*!SOCj4($x>JJ%VB#X^dt1$`_9^Qzc_Mj|B zSFHS|8fdi`g?D~&Z*rA}HHk3dnh|RxF%m{xy9pygT42Pu3XC|tjgU4Lqe2k{cTLfU ztXE8If?wK(<&#Olji--}`q{OJDC_>l_Mg0B;UjV@x1xBpoYB4Gpu?veN z2Sz$Z`byrG1w~A~)hWV)Gt%t$Pg{(__sn4w-YC*MV#M47BT>YDUt)wDjVa>2BtflE zbj8YZQ&+NF!AKx6)qd$1eWsG4$odUNZorGZRyEC4G$So2(w2nh`h}t-*Yi|YBQT;= z3VR*Shz$l9@lrs0k`^QF!JvrOZ|q5sqNx}`5mS#-C6=}(M#;43JpV3(Fxn$yL?6Jy zEgEdZ2#n}^N|GDTG#Vi&!aL1V#J7W?h#*I+l=wWr6eH~O97eL(h!JTXj990r5h!9L zijX73h#;qtRvh-w38ns3_M3Eb7{yd87|{r@Em4atj5M&GJE16gqX*eZKVCWgQ5>W5x@V-L{q5;-xeOyI{oBo1+NtEHPs0Dagf0bBg%= zLuOheIbJ3egMFqsqp;7>2ecTe5#p^g6v>3oQN&_?OcAd}(i9`i)0`LuM*MmY_KB7| zFd9>Y1y{=*9LXDL(XnZvC{;6!YB50CtbdK^6>>Di=r2r+Ht&D6a(=R zO*su`^fr%RTs|X43oy#QXI&^_>J>3cc7tu3`x+yzc*$}tM(pk*gvo+yrZLriJd}?* zT11RQ5#?mWG+oE)hWd7WrYM- zv@+8Iqut$t3nLotz=)@Ze8gT9$%2n5BFf{Qp-2{7Vw4&+8Zc6ln-?SOb0oQWG2$RG zC?d!eXA~6So}HqUce@26EnQVV%Yy4(DKPrDzhexHn0ir97BSMELlnK!eg!HTfiXop z_ley+=1DVcY_X$UT!c{p>HO}~nrM|2$r&kvL6KryGtkmd2R*gl&CL_1x7yhjU!-L! z7@dox=+gT+n8R>W28L?#i7JVSx)Cjbl6cX(i@5* zyi+~WUgL+2RMgvLiqr_W7$xhlV|%ZOC5+Sv%we>7|LzWu5Uko86^j03py-8_7|l~; z-+x>SBQ@N$7)>!!dCfZyK3+};lNhZ=5e(hi^v{#r97fuM?T{__97fRyTlB@H6>8Q7NjFjctnTGFSrU@gtr&f%f&#yc7LDBo|hlyq>N(RZU zeW{fA=0izo!svjEkqo%(wa(D!gCsQfbc&dHtZW%*h*6ctrYQP=u^4He8mCIOv`tOg2P2NnBu0K9;2+nD(ug-f5yDCz z&>Czg(m`Ta@TnMudp@&EntEipcBaLl5WfKxjldWqrFnkuHyVLBvei(FF#oP>!CPm< z70B~a2I<||JdI}>82zPV^y#jJNLw;C9EcH8lPjfRplM|v3_YU1r-@O-xS%Le7!{1} zWf;kTFT&{FCPvW)6pU($b})*{&^Ar)oH1%f0DEZwYOI7r0F-F{YeAIsN zS6NOVab!#0=R#I_J}fvCAxB)2P(S{oeO+A~eQHEeie+m+bdNrAT==3XMv>!K*)q|_ zVsx)O^%jfKy~Bd*{o{0|5yHYeEfS*&qopZI8wR7LDYE^SKdZ++uZ7Wei!sU+ZNDZ( zw;xfI_y|CY(H;7abu~y+jPBTvFkhp%TSakpTmOB&$K_P80r2aLfFz6 zElp9H&NO1!T4FTDXlaU4V~m!@XlaU)r?60?r7>EXqU2A{wB^`PGi`k+vi*OX)38R@ zp%|q#X4)THj1rd}SfdR%)7FQghnM!F(WlxJW~ zN80yCN+W-rw6~SP=1%`if5plv+5M`HJ1ll=%M`=z?^kiLD-lOrHAa}nKl7oASh*>v zXHgC(j8;lJ%)7FO~`~LL?pK0quk-qa5CVXj(mZm6i;jw{d+5(DdUo<$Q{Wwv98g_m97yM6fO08m)%WRvXG0rF=Lk1OCSmqt8z)cyUIF zJ;zRFp2ik@EJo)|EcjTAzBsYq*|4QEjnb+t}-iMiK2+_A}zI zt5$7Sn*rB?BQ|9y&HM8K_d~nHvhBB{RT=jA1Nq)9s>#+F@goH%`k_+Ule7k#kJg=( zuO=hLwf>s#C7hh>PwK60D@H8cvEYjhHcNLbcpc+fiU?t3Jsm4WkPCmESeMcGu=`zX zuweuX-X^(%5ftt07Q78|EkzIVsMiF!~zbPHz;BzaoR8 zH#F5`O%a{pZIkO&y(pN^7Tkdk(-{BF?w>|`}0J$Z0*^C-KO8D*MUh$(eL~NGD`b8BSVa^;B#Wci?E>R z#gnj~sEl-tD2!g>k0fOc0N@aNj-prQmnD@LrM#ODjE>AtOKLG{F*?exxw!zSFmj3x^`EhhfmXyQ zDC+vK;GD8ajFN6Y0;7$5rg7~iUsS{>FuGnAqlf0rzc7NLkfJR!MGwnoNS6)%T92IX zV*@M7$z4-!xC5g&jox~&;Bi6{7$G&xv~30p9v37*QIykiMypel%9+X78U;q59Uct) zf8O2)FpBDG|DPaY)KsHJO%-)f)TpRYL8GFLiW)0wUissyv;;^X(Lf>z8ZC8#phiU- zEt=F)O)IUbMF=)!1SiD{{Y|GiUG4>}CV#?|py4<1;&R z@0~k$pFQ`SbI;7gyJ?n2?a|<*&Gxs-$g;>c!L73|>HI{E+{i7_cv^kl9tTM6z>c4qYnoN3{*5(S0ERp2h*JVa&l;K6MgCtTKiK?;j zZF$tJKc{I{^!eU|WwYI4StPe;$dqGKsrK^S`YI!zMb-rGk45fD5KV77$%!N)#nb3wh-PElv2L2CEZ&Uu{Bq>Z?6WqqQ`_f2=G(KR03yoy0BtoMoi{#CR>dN)cBHxwE zb$I`~uZ?^f`MzAxzY zHgelhtTK`bYws))C(L)`0xWV_2vHh|6DB6OrcTBxqacl}Cl{-X^loTz!h(*RF1U#@ z`fVhGI+jIK9ar^HERAmQUL|HD0rO`}pPK#AW>Vhea-ru8sT#!ZL>C2?LB6tDby!LK^w1 z=r~l3%zAPcfY8YL`kFcIdGc^XGQ2f`J2<7qvgmH_c}Y zrP0%ohfL_|zt5tFJo`DGMaO&3fC#Y2-3N^%vsLD_{%G_Q&wl<(#CFn%fIQd6PHMs; zv7g0ul9+(6j?}_-?VMI-_INaEj3f!@ts|C3qK+Pq(CBdQ`JbC2fk!_clw`X1+=jZ6 zm4AOqi=EJX79F81lKWqu@m#P1?>_kBqcjrJNgg+=mXYQMsV6_sGoCd0R>IdoWh5NB zkO?bR83~Kz5sktkYd!0|0z;wTu$c=*zN5AH;|gChvdV>={oQ zR*I$3^WFo6#zl=M$>f$tkM^OFXFG}YB!Q*A%1BuBXOBg-kvtPg_ZK(K-5CiAi8mjl zQDJ0ZR%SH~Eh>%TXEp1ni87kczdeo`;Tl&`7U`WK@+K^0Q8ub5!Xnp8Fk0Z<#i6TU zN~0^h^pSWPX*_6v`CyM#MiClCSX6+4Ey_qHELBFzBDpP1@4^xH(r=+cM@9WoF;{ibyHFJxi zx?$D?53f+fvS_k*pQKJ{ zuJ~z|M$@r-ByrA$m3$iMEsE-dS>s7)BNO_b3zm*}*(U<1)tvXmlzoIj`e z!D*q<-QH44LK-Dt(HA_rSll#CXbiGQY$u5a2#Z{QPO~dv)|2Zyr};F}B{^9u@hu}^ zkvy(5o<-+-`L*(b;sh+x8*UTPsFXR)Mg$~0>C;F;i$bHjJY}SdauVhCO>9v{K8u!l z5dmu(sb%zrH>oW$?qg_5YHDJOGEz58UOsMJxd@9~<}9B^^HD}>giByaW;L;mEREEFmRV2Lk*|z&R!hvH z1>QZCR!1InB;!5?0ipqNt(|qcoCL63Zf0MQS_$omo%b z9x85}C?j$8<5=WIw2=grVrg_^fJRq&*#SpIeSM*kta0c%n9OO)qO^p{NG2?Kh>0xg zS{7}MSVpeQX;E#o4;nq`#YlSC6)E3vlG@4fq>#qzN%lJKP1M%LfAkwwcQ?*FzK0AgbM%1GR>&rwD) z>n-W;C^XERBu~(C7zIWh9P#$jFd74!ql|<`rBM?+ zNTUP1wR@$}Bb3mHfU?MU)PC>9ghUw$izK^J!jo1R$$i%-BNx+X5&z<8Bqp}dNY?Ky zjbzr7909S7BVOJ!MJ@L3Zp?VKh{vT7Mw z>)B^fTEyFzz+SM${~zxeM`{|$+Po+u$!L;W1`0fNqz3lD z$U4Uhs2X`8-BOQ8y5uJ6NR^SK;)^os@|2OVNO+|FzVJw=G_jvyk?Rpjques9>6|9U zQ7nywNWO`!%IIJxN+aHYrpid-MRtWl;z55$8HoWdp-H)!U#B!(CzE)PE5@_Z=s(8N z$a-l?Bk|;Y8g;RhCUct7NaI10jCc?%ITTESOEsJD{L&7~WrKt(-ifI(pMo}7x6ShAz(j_?wE5$0KIs(+Hj6_{&3hwz{@KKb} zhm!e^JAj?hocKg}+)J;Ea2 zF0wI2al!hqNbY~NG*VCgAA8h~lfa~gjI6I8q>+sVv`3WDzF4FYBVFRS*t4EBrsPUE zK<J=#NIF%xU|e5hXN9 zSLQTfkuJ;r-N-tJOldE8Cb%r^YFtU8MuW)#araFlSum41?M-H^cp6!MUqjU5hJEHK zBQe6|J*fS$=+8FH?M7xbHI76X9pWgB{0G%Wx}^G5Xf(om za_CN@c|xL$WHm+ON>jZ_O)Mj2kvQ|~DWMSoCN=GOLL)Qa9`q zb5xQT;dZq|Z6nE{6=igCfJMIuut?%X8k!c{c^fQp)sK_KHpx`e+>a4nSW&E=AdQwp ze0{szDprrBk!6u}(v(G6OlcwBnIqAFL@Xkz=%S0n?vcbwjZFrX(OfSgB=Mk2y;(1w zMiN+@7qOm4dbU$6i{vpg8lF~HUha?+N6uG9y#GV;KQyo?s~AB~PUo~F@BJRlUgm2R zfkUOyB=6=VJEslcG1fAt35y=}l#yfz#400Qbk(&md4Q9rj9f3utubtw(>{C&x?n=1cRV*vI3z5x=CwNVmPPM+%E+>4s;-l{-km%`BkRYB zGO{!(^pufLBe~&3{5Y|Ud}XA;=}UNqs;1{^gxjCeEQ`eM5ffZ4)|XQnsfjJ>$kOOYPZ^03Zds(Z(HQT2YRaNl`><%Z8SZ*C5*JKqBz~MvBe|t) zL}W2_kojnj_2V>`O_$Pixm8^-VUcy?ghe%;uWwl-E|@5zAd6g~k!F9$I+!FQ?hlQ` zcnZ=e$Rc&ZBnB?F)6t%N9b}Q@2ubRO7Y}e_v{7OjNw$*AX+Di4f%?b%QyPgU*B^^s z*awSTS;Y_joXLn94NOXyi?q(P-$ddlbreORP1a1BlBDu~$EHbY3v9$2LJzex&-XrnJr zqmqd2WP_7-QC1^DYWIlkq&aVWS>*07jbzrdS#M%s>w=mnBXPrI!ir~+tc0B4rCI;O zXiP}n0cGP#s*G-O<7o75ght}axn7d3cxwBkk;fu+!wzwdOj0BKSDre0HezAl$s0p1 z<)5%^vSjAYT)XOS$p%Cfvz&(@La ztBhP-P~Be|iSd+J8A(E-*iNd9u8Wz{G}%m6RQs^V#oyONq9BcAQBIVR1eW4y^d>}$ zr;$dDB($i`ys}7)aLXdGu;mssQAXm-i!u@;ocq5en_E3KHI6Kej)>6cmwjj?L^{P8 z3XNWh(C9mnu%kF>!XkCSghkek6T3*AG)Yxd79C_hc0C%&%_KgJBoR%Nk-A{X#4g2; zljqnh4Fn$bu^pm}ppnNS2~8$qk-T_EX1zo#ay3Orwb9;bG~T0;nBaYBWLYHP%WL3> zF1YnoMvp`txd@AR{#wK|k~vMCFfpF?heq-|6Uk{)W#qF+CM5{F4uhrFe zg+{uZDl`(~Nolmq%XpOR51ZR@DKnO(k*<@7GWua;PAm2@fMiaSl@u|-MH%VBzTDz! zUHS1c>!GfMMZ3)xF3GiGU~3wY&`8W@rIE%1{GgG{Y3j=hjU=DR#<;Czq&IU2i(c?d zaA8pnQEs)bWhLZ8FCwJ*(V~oa{;8#r1|Nk+8WR#4y%eR9_;RX@WLDGAq9ocYjpVl7 z?|KHdn%H)|Oj)!k;>y_!0AZ1+Bb<5H^TRBSG|nwFQWINfB@B2-DzeH*X{0O?NB&E) z$R)y^h(@}UvfniN$}Hmkr~hv>YVqc@ugoIXTg6Zsi4mTdMq)s}!>p$ffp{8OH%wV1 zDVA0l#j@xWSfoa{C?mNm;91A@X*AXm8vUF(O=+a5*D|9?l9{E^n-LmmG(cuFandY{ z4vHuvb>oCZUXqcgj3il6rnDivD^Ql>JQm6QkLsmKBATVq$pIR*d*-#IU#l|G3?WfQ zGV5t*Qu6%cStK_x_s=5hgt@AXWYrdJlz>L1D5I;H)B00J;)F>QJTZ$T*~}^ge!{*Jbzy^iNrRFWzjR9ZREjL_Up@O%HQgER8f|B>6$&$y*x9Dv1V_WKNU&TP=$&ULdMLX)v`n$oDmoAo3+Af81USCrthjR(Y8 zMw0(weR)fxbG`K1;G8Bj67$*jdUE#9nYeFJ7PUq7D)zxC?lH%BKEV#BG(HE z_%u>=R1A&AL8F&qXr$@+N+Yp)KHBrKrBRecs*1!iQWvaej~d_-4N$u%$f6;}6&k4@ z7f&MzD@r_QUo?`iqGgeWCMC~bEF%d{i+ycbWKHk@i(Jn%ddRz*r#~8Lcv^h-J~Vrldrrx&7$5pG#zZ6jsTNasmdbZ=A{ zjb^&iDNSr=SB&SLJ?h7aDv~55SxOUCB+;P$XrxY>DkHIa4vDfz(~zt(vQb54k#DpwZcK8SY=k>VBgqg-Oe1+^gBsYvBDoDiOz^(SD99ptNQIi}C7z}DcS4J}GiqE$u` z5eO52f0JgYk znkCfYVm$4eMiLK@thYqUNN6OF;*DjIM2-5gNFxG47V-Qm&kw`yiKWr~QGeg3(L3Ip zCW*STT4HIW>L?M5eA{RqZ^oYPO=@ZvMOoxVb&>VtMHyKG+%BbAWu#V*(8%}W)Yq3q zd!I$8c*}7T4G`;E(vZ|L5@jU!gUMTUltr%GA}QKP&1>=YtunfdBK;{NS-}t*Sra@l zi^T5HWnH-!AZT9;i@Y2mmlMWh9Gk8a0y0qIKrqk$DeS&SQ}qp^+L#)`0evkw2@6 zi7hnJSxslO$uY`E%xj&lR2f+oi7K+zwM=QsqC-3b+?Cq^bmd<{MnWTb+=491pA1RF z0Jk)fyBp(abQ!8hGU8%cq-z{j8Tm0KxsTRbMw0XjizNTYr;$7=QVeXlnOf&GjR?ik zNN&j1n31KCIAJ>LX>hXdlqS}*I&!fray29r(MADJP7G{W|CgZA0bWGN(nyVPNuKmA zBe9KaOvq=EgePNJBokILFJX=hJ`@?$gMsqv_5J zXml?xAolGdYhK5)NTLD0b*-W4i`^J)q$H9wq<9*g!ppXU(Ew{+7kRg@j`6a{ghg_v zfQBYxS)}V=!lL&g0d7%6%Z;mkT0|Q~Xe6_qWV{7wB#&iKW%LMhn$Sp=c)Vp~U3r=GV39okHl9ZE@L-{lcybz6l8AsRBT2DV8j0N#rBQ%In%5}GNER`K zMQT08DkEi4$Z?fM;>oFj?HflDp;j7gL>(ofk)73iWh4;+S#-0uk>nETgw>ZtUfjs_ zX0-<~j(i$@lbfv7yp{waJEt9NKG~xNxUQ0@c^#n<(I9cbWKNU7q^hF+SS0tpX=suu z&FUgGjbt4xmPWPFz@vKdV)fk8hekmbi4!Ku$l6Y^EP6i5A~C>^a`#FjF`m?uOH88{ z&vr_zjFd%hL|G*1O0g`G^bXh3NIbdVoEA%?@9}u~cpAx~tEEvai-L}tvPhiyge-ES z`bZ4u?Exb^NF!M=Qv>=_W<7sSlf_#NKg#3PEsOFzWfWwQa7c20#03);-4~4pxP57K zia9ifMq(G)InBm{hI+=629<*5wY*D1o~9ry63alya=e@DWmB6CXNCE;HR??u6&S^m!$vwM?X(ZOOb>w^& zNy?g7Mj8`J=3N+lSmb*5F^b(I-uw{HG?J%PNPN=LNVE0T4ZAc-BUvj^%P44K3ya9%Wn^h|FpB1%d;E}++$kavqo6Vp7K!Dg z;q9O*vQfp6OliMx@#OlWkyt&K?}J7qC?jYT!y>uuOm4Ur16!4mwVmRpwC9am=cSP; zjbzqSPtMM1@ifwSfZQ))V@C2gB5OTcM=q8{8WEBQFNiWyBRt9?dH#dWY1Vv>rI9>f zt1pejc(PG$wTx65Sr*C5d&GL$8;isQ=l*Y@ktLEEN4nB6HX)59v}i-r)16(O5iT@} zXVH&PMh`g;J9z;XN$R!c52-Q|79HvaB9p3$_LoNL$&2-@%1CBCO=h!GnswwYi^Kre z%vxU=xtbzmX(WD}RYpRiA4O>-=Ce;DS#DD|ZIzchEi97EXHiD|vq+pU8xN4%+hCFF zJ$Sa;dpMd;BboK$l~IsJdT)5VGLofxpG9Ij>69iGc92E77ADUHuaNbB2`gDYO=u*u zn#P1IjpU|*cx9yK^G45;(^QlFWs$Xwyh+W)@_9P}jpS~}g}i!3X!H;?vZ_cPKa+q) z(ZHk)J6ctw`9WemTQ@G&x^`_q=rUA|-YQ@hO8V01mS{9UXEdKimPMtW39c-X2=@x_ z9$4#wNpgpB<8bva%zP8G?EMu$$b@XUQO^=7Tpk?)MQGNSYqhEkMc}TWJ2>f+UqiHl~s5uoHsUN2+ z|Gr(MVMSrl;)n^Z%Wa8Sq|pFaktaMHJof;9T7EE*{9zmxRn{%NFvMakai zk474x7FDClNasDxjg;kmyLc~gLuHZJPCBKzvbrxhAQ628k(5Rn5%86fPowD(8fiqp z_xF7kJ>y|73F)Z)y0 z%E*lbmVz|W(4tsA{n1Ds(*GmpImgoIyo4+g7tAUnb>re$G}5?2BR?`JVaHe+$#SYy zMq)boG!pY#!ir)$ha<{J3~=@JgUU#(9?K#Pa7Qg8dH>Jzp4}sJn$k#3@OT=jFW(Q1 zzA}s4;G7mqBQ?R}X=HtQQAT1rDUE_G(wLC4NM=1T!ef<@jR`&Be9!f)aI25xE;gl+ zh89&BsV5io_a&Lg5=m&JzFg2Ul9V)!2`P)zdWuy>jl9Ch^=XvJn~4%BBbl*M0wE=N z=7aB~i87LCkFrSSJXs|X4rv;i#Dm0c=Ibkvy!|F34#L zNpMcH*0Zq4I&%H9NYcFjY+PAz3(jfQ2@_?c5$<@)NR!RfGSYZJUu7go_By5Y$0BvY zCb(W0JTZ;b36tl7_eUd*3CTO4Y(zk2wIGYsnV0wd+K7P7v6Z`v=Ggq#VziO2%E@Ah zuZ+YtvP60-Vm!sqX+on_o-)cYu^iG>GFfhwRWQ*s){V0hTCVG5Gg=Z|4oNgMpnn>L zp^+@4^rwtO)yQ)L_Qs+|VUe2PZhti5feDdy-M*HQ+^8Yuv#KkhQ6d(}gk{~hzV@}S z2*byX#4i)iX|jfq?A;mOKaFI_lMy}+(>e{@{dKy^jOCxc^&{zG? zNMb^=sQO~Wda|~WB-yHkZQU?yf(wgKN3NGjq9(Q_(zyv~<5;vzsr!=v9_Q4`~{^9=ujlMFAT#Zj_@OfV}x+H3X$J5BN zXiUU*>Yqi$u`F^4KFWqS>y)wk><616&ihI7P+2j z6pjX!5*yeur~Th3BiDu={}<=9FT*0YkDsQ2#eL6d|2xXa-PfGCY5%_~BiBodjQ936CZzFz|69w*{okR{S7wnLF|frA+xMKt&BFXueuMvI^B*FA zmD&973fYo-i81S)apTy`cAN_?aGaOUbeyM#@;T%{0ry0 zBOT|6BPfvSIENqZI9Z1|&b?oAoUJL2lZpJ~P{$d9ymW};T!wTW>^R>+h9bXDcAP5Y zN(4*Q*>I5KJdETbgOR@va-0^V8kve*j-(^I4s@K~A`LG8t43xbeVyM@Av%BSVl>gyk=%=K#m)LVkz5imXKHksl&YAajseND=aF#2v%` za*)fA3y?FAlaQm46yyNpzXKfS6QmpILOPKSq#bERRwK)hmyj2bg~-#$_mC>&0c19E zH&Tk+f#f6K9)R6*D;r~w8|-CUO>X8gepn0`hev4M{~(kYr>aV*mI? zxs}mjDUXXoZbOQZ`;ng@jmT!Clk+M;?7Voj?h(fXMG0ISC2X+%XdIoBt>V<_t6C2hw{-r|%ey^Y(x%y}66*erCO1^;Ot zb{2!Xctvgt<^E&xoY#`xC5iGzr!(nKq?BCl{3U4zOKj&j|48a)p)KTmn)DCj$YTPM z{s|^KCdvKGIN6)R&yTtCdMEqJ>z^O9DZD8>d!3E+2B~MI){_`-xNTPoJG~ z#n~5)xIcZ~zh3#>r5oOBo4H-~Kk)vg8(#U{?35u#c?D;u=z)ty$bp*k{&@RwH62Ia zGN@+Nk+)oN1#C$sT_qcrt<$*$qWy6|_W>6i*gELx%hXoeK}XtbWvAMz@Z;dSXS<#B!7M{of`HcITSA3ufe(%slt5DJ9d-EuC3XIIkq{#15R}g%Qr;d*)Ly9O+AGJM?n)JV*jAIzm58@L z(u{2?mCyDxss@rc7y6&S%4^3Imdq;756vjJ8#Oeoq@XNRSTM6-SZMl0cy#vkiDi(d zJak#;)cgn$+%HS5TPDqn@T&BNt4a!{=9ZKcJN=z@hIiT-!PA!B7_C*xma7eTseL3?2+mTuHBuhFHI>YOI zh_l2s;qTEVT)iIuVxnz$7c*wo^qZz$F}bXycvgAAsG_M;8QqHWF625&y$MeTSxy$Y zpbT%nKV;`!=yk>RRZ6n$e-p0%Rm6M~UjJh{YnwRp{KP%89fKf!dYx5~MVIA>sF6`6 z_sqER-t(`WG^?!4Et)iAM8$}y7o0EO%yrYJ$%*f=q$%_nlM&e&I`52-_kHLPXV@Zk zzjiMEG|{t&4Zw+_Bj)anrO~fAbee5G^3BQ-JBap>c8CN1=<~s&>zTv#VBZ0C`FTV} zR3?ovrNu?%S67tlXkAlO%+Knok{Nf8DJZ?6;zs#tF^C+WIcZ9H&P~_O(j9DFH>0Rr zj^siU1>yG?q6wg=B+d*wH~?B z>_uwsY#ICenk(0hJrPscjG9yFTr%m<3opfSyb`$zuLx{xdTia;0}sO2ah&fb{rbeF zC2eERJff!Sjj_kood4$7J!d%sQ`3?TJmTm9gN{7rfP;?0-FK*lo3*IPOh88cRIzkX zQ%%_)#y;rgl&>~nq!MXEb|Qtd6zd}>`$W3SzT+)&cCiPqu=K4sa_t@KKjKeEHx=AC?(TDwq>oRe6enC=d&mu4DaKbp85W` z`;KZ#dvRRe;TL5;`KsCV=&L4m{;Ov2W3QSW;BfYhjBJNEmdSPx*vzp`B=xaZn|`rs z+!Y5j^{gKE%cQ2(wc~n{h~~&&)6#Y0?oD-f9oKFu2e+G?<3S_?Y36hO3E;`?CUjc6 zsXL|J%pTfqy7`>TXXo^GGjx2r2_xCaXe1NKM@o^M6R7vCc9V>xA-#Ma24*3pliSTA zWIj?mx!pCh*=Rsoklq3cPNfnOLIxsP$S5Sgtljh=i;=C!BBb^{I`W-%(*-(UCsqkI>xc+lq+L3KYBjT_xgzOsodegK+#{Xq#)A)184>+qS@3!$h z2Q`H!kN@nb)34|-IoTbisvjw2e+Ff0=KOoig-uKD9{>BpZ)@3RGB<29)$6yJ*{^If z&Fi+Ak-4pV^e%H9qICn(B|nhur!D-ZfPN z-!%)6I%F}@jI<#g$abU~*@ZX>O+DZdOngiQ*pT)Mwv5o`Y zb-lvd6BO=d->%4hhm)ru>Bvwd6B)%xI*`;s@0!6#1~MGUMn)rHBp)e7W+PR|0;CRE zj5H%{gIpS6W4r92vCu&(3;Arf~48WKh_4}I4x zyp8`YKo%j3BioG;l>IG88?qG{hDf;yNPa|QTk6@*QdjCU9Qy9V5BH33dbsD7pWk*- z-be44(tpHCE&Gyt-Z43MzH5r_h?RQwrB8piY1;MS)g#>U%ilA*_fw>7eEIm#g$de{ zGNlRjb6!?H5+C@=`xAAb|8uzefA!KxqALkrS#aB)R5}zdcGLLHv^oNvh zdi#O!Z8`3g@``h&sJ1ODD4r@?f@fb|Rx;(zg7UKH=jph56<$F(KC#qssOo*bZ~9%{ z=6zlb;t*$s?qf$NBfp?@W`RUP^Ut^>Be!RM{7Ihv3wv~W#@aJoibKi>3=RQDlI6yXS$XOlq+**kN384?|CZ-?Ike%6f0p2+d?nfFdS)Z3*yyzaS9 z62U6(4{!F|`}ER1CP!(^IH^xgj3j?j`6MkK{l8p}R!e+6_REg)EmBj0`^D!KmXwu8 zcHA?w2!9wFLIlCwabsl7$bnV`cZD({C#h+9Iy|`Msb|8+4JatDS^P|xSC@N#%IZ_g zE{R-_vKg=Y?xHF3eOY$rTs?a9O?;kSP*z5y%QheRI4pFsSKwqJy!RJvm-S2eD=i_$ zM|kJ9F*jXx{ncY9j&g6k@tT`&xJ3@V)$_w=x%+6kynG)`@2h^%^n#LE<^6WgbrLqfl}?PHO2G8!!JvC>PQRIX<<@1QU89M z`04!cr57h`f`ydH1rxQQeyjg+e)yt81J!GK>cU44?ytCvR87j`;o+ACs`wm&?-Qq# z%$!+JEX#%cT(nbj>Eq!MBN8?+rDVp`z16Lm{&@I;#3Z|KQt8C}lIfF*X7qdFgr_Vm zrV3x$%)NY1a@qVv>W_;3;b;Twn>mA@f4?UWG$8eBx_%r^clWonKg3gJ(a|r}-Pqo0 z{nA;Ji;Je*c}79Myo&E`-A}?_#{%hJEhHS=U~li-|C8mu5I**dy`3!jU3f!T`9k=( zse37&uxrzpbxMmSveYS;gz3HVu{hFQ^!YA+TYYUY1zqF##yD!{J|Ki3vP;dJ5 zg8ZUBzolb?3OR7Xn#x7twDkT?RP+4f;q$Hv6c3!I^zPv$Gm7^{hCscV)`Byb*>Qu2X_w%a!dS$aFlj%@2c`v`^+is}& z-Q(eN66@VrGxps=&1a8?FG{QfS+1K=zL##-oc%<9I*{~?y>xmnLtHRLrm1`PJ@wnK z$nEppk`xmE9qs!o;=BDy^@`8-9FqM#VNLbVzLY{~{aN_c&!&P&Wg;w^T*CC$ z&qPsk>l5+j#*1I-n+es22k+mo<<*CeKefMp#9Vs~jegyoQNAy;H>Q$*-S{OFCrz1B zP+C55s<)EZ|4FTjhTR6TyK;VJW~OiM`$oKHX$Q&;@2_0M zq8^hGD14z;SoDSM06%xnf({h&f*ba@XDJ5`dQMW!xbKBSL+F02jn${v6WkF1hwbs26Y9cWx4|XPQPtnImI^k)?>SoO zM^rk~>(PiqOKdwP?z4`@4hHc&U90y^MAa?_gXJS3ikXuLE(iBpH7sof_vgccdnZmRFP}7}aAL`fiBoFcUKBnw zhD@rVwG+Xrs+jxkw+cD_R8a#wt_uOv+;+{?Ym6A(@ePRv*VD#cOF(nm-R+epjoJ`#n!t$MnOhO1RIVy?kU{Z24at+VEvBO{0Pe~`cr*}56NE3*k2L} zJ-zAUUxhDz?%~X$TanwEGK+4X@O^jjRY^{HhT~K$xZkAb9_WmE`hL?q{y-=7nfp!l zEeASPU8RT%rw{J%1s!@@{|N{ z*a@VjgV`s#rU7if(lwcMqsQBnoh9(cGsj|ljKxQ;O2U;_FJyW14nl;MZS)Mx ze1j_kNB@DL1$Tm>o06QxoqQ!==UY?+x4y$y0%rZK($s-DU^CbZc7mhcuQX0BoB%_h z(_LwDz|mkSxD~7h(>~w%r|V8|`fD2D`z*J857HLkwns^Zr2t zVDU#Z0Oo#71K?J$9<1o0K3Kl1()5B(+8mQPmMcx?g=%2-adS*9n0&$zdTNvEV3@Wg(;35iwi!PaCI&NjCFP~$2sWAH+b4bad0+Hg)*6fU|T)~!BGVi1dFH5G2P(kqB$o0b{f8u4uQjp z=a^Ekb~+;fwv;k*VD(HIp1{bIGXmf?Fc+M^=>by#mTq~#)Pfc5513|`jm%#?U^>Cw zU@tgu>jNhJTYT5AKR}WfBLjxPx(*ruNBx!tz+SK!9Jr18U>NKL^WUWYx8X=9^}*q9 zQy*OT4)wu-UDOBj{``P(o7rgDK?7j=`!oQSe?S8hA>rR?0Brl12EeROXaKDGCk=pU zyXXM80PF;Jg1unqQ|jl@;eS&f+y#cg&i_y!T=*IF!Q9Uu;00)G4Bkxxpz{R{fDLTAJaw+A1cx6v*VKW#j^b{dRyG=so@=_mk;lw6&Xgpl>)5#_1Qw>xHQ8YI*XNo% zu=02s02dFY0kHi<>VtV9>Vw@wsGl!CGwOqlL#Yosr%@lwIi31oM+Wu5WcMr@U}NMk z8URbrrhx)_d=3qOz30*Z7#cwXVEu(O0M5>$0dObS3U0lG`rw3-)SsH<^nf97cQ*CG z>MN)Z4!x54VAWOB2i>%*X@HH&YiI!6b}bD|VplpQy<*+E$V~2CsH2_O{RV!zyDGBG{BC+sWbpCnnnXf zTtOiXfFtjq0kG;$8UWjhX#nh%)guZ zVEH}Nzr*EaN&J4a3>x44h?`UvuOZq`z{TDTkodi=U!Cxb^$gp8+=(P#?^ChWcQ34fVkZwbTc9fo>fe z^M61CV9P=p0K1>3ffDq=3p4;${)`5|?w`{DICe1&fUQgD061(J^}*T|)CUKyqJAl4 zZl*rCeGT=&jCIrp%U_{B*t%h^YwFm@ZKDA&?bkFQ1%6KhcX6U^Gytalfd;@jFb{0` zBMpF~-=YIx;dbhSyO&eRqsM=z0dV_AGypdLlLo-hzi9y64c38`|D`^d^*Qyy^4-)gXGHc;ADlmMp2-GV z4xDH5z_f$rk!#LZ=_b!Jb!-egWS(gS+rcg{|Im5HnZ?g1Wu6Iv;lpSE>^htV4!!H$!t54w#*Xn>8BQ)mFpA4&t@ zj#Fvi9`H0807qxh0GM|<4SG zQ3uv;rU7vD78(GZb{hCDR|JN@!e7z=nEERk0Gq)|Fz+?$gXvqT54OHXeXy>J`uB6i zf1*BE^%v@cwST2PxZwSHya0oZ-ha^mxOEo|fOVhJ064Fg1{k64&uKvL3mO13oCi%F zn3D7$S0E&O(A0tRj(*Uzf}LO&IPka!jZ?{$Ze46bVC6fDO({70lf@*GGooKC#wD6V z&(C?;l!A4azHI8j*10d6Ua?rUxwjY>7#KkcK{AVzR;7-Aha%IDF3%Qw?_ThLL8l zIBBWr0+SC|YLXw~yC1mJWP<5~mYOhF=N`1wRI-tA@KRF`HXO3lbbwhYOHD7>`n9Dd z^e`Pbe5uI+J5raLQZRhvQd0|d9ktZ7f`vyfHQiv(F-uJVDfo9 z{tH}q{!-Hkrj1x?oW~gQ3zwP=Jb>QI3mzws+`2Fwv#!}P6 zj)hk&HR&an9m4+!@tJ}fVodG0@Zx?Pcs5wRV^a`F8U!O0OmZ; z2!K0(!U(u*)cuSR0LQ+>2t3Jm^D-jFTQ z8;tV|9lxN#WPr^h8VDe;G5?|lQvv2(++ga!;g>d;b};#}2Gav>zr4Yu*YMS3H<)a2 z-jxle5DbrMFxB9&YZ^>5=;Sn*E^ym*4JNsk4qxA3GQo@+8cbL|-`HR(<#TR>sh7|H z!vhdIWXG5W(+k#)Z7`u9aN_X|CI_szrNNYf-C-V94yI3NFs|1vXLBXb@?Fm5 z1YqN%4WP?IL!Se4YJYw4nwn$2L91tvcQx* zoETg*Xql-4=N+-kbbv!oSZ16bF@&csGnwFm%w;AIEWLP{sRlz=Ei>(4&JC1%ju9KT z%w&Pt-=-aK>mAEX54dnX^`GbWpR5J7c-Y2DhHM+;mZX@Y%~v z`XY{>!+vo0dCN^9IQ;zOrW$lcEjOKD7U=wxS@nM?2hIZv!PW`OP4iD(c1&Jwde|{E zp9X)1c?@QQv!~M$FuRP7fL-OwO$V4hYq{wKo%@%Yj29WPxywx+nE&8%Qw1&r8^F#d z=%{>NK)dyDx_m4;tpL^e?lEZ(x*RDg@XI&k){=>V9$jdH)Boj2$JnEoam0Mp*#1!(nbbpDxw zV8srGdNJQMmnjj(;sTt>EBY%S|_!zMF<$=I5ET!sLRp4_IL;z(%kR z%uiWiI>3x0SD54_=#8URm`u<~TVcXr@d+!4|FMyI$_mp8b_`u%y20dASD4hL%;)E< zFxg<~a2f_vFQj2G2W$r$FI!=H!HTPBxPcB`O~YU=SP5p2U11u)>hZJ-W`=2Z8T%)# zFj-*r6kY&V%0_0v3R4U2D5fLe@DdsZx0S9iq2(xwiWMdY?7feM!P?m?Og%Wik}Cwa zKfo2PU4g+_9bxfb-jF5NvymD{Nxq-lW6Ld_~)74-A17;K277Ij|6H z1xJ0v1%hrp8|kYV;z5n30-S$nqiFzhk8Ctu;OwIsjkAU!JFd}Wf+L4Cn&efS;M7Kw z1@6vhG=<>yVU4C1Y{_gi?cl=Ujiwizoz-YE=-7mjjV26^%x*MQ;NVe>rn!mV|L$uW zO)e)Y{AQ!c;{>HQ&=A;rQ=@4GGjkhFx8T@DlfIUb8sBKL!Kzz1F*tNWqp1cPzfFVS zqC7ed=1rlaEsWe$Iu14$(g85%&PG!SW=(H2^)3AV3uiW(4kSAp$dgOAo=6ZBzuuf<55CKTxridSDi~^KI&Z!?$xnu(OML zVCYYL6=3lW>Vb`5>ITUBKJ~!fj~n^@Z{)k}Z=U--SEsRM_dzRGlhy~9=+2i$SaDi)o%fXr1UwOvTL%4C6=*RC?9VB5{BOg%Wd z$X#W+*k~@H;4k^^?pbAW!QA^+nM!cSL#s?HxZsghrWaf^f0fDj6%8+>17O#WSD9LH z^oy%ZJJ`6Ga$t8eV$z;7r&x@N(DOh@M zlW73!XH)KvG%$~HVEJR5=q*n4BqstpYMM+H4d(rj@?g(%oDg(gpko~$Q`^DsKYK+J_n|Z7O*9PVt!*+Hbg1-|CKCoLU!`HNdJD(F?XPj--_dXf4S}I; zTp>8BlM{mZ+quHuGvr;27+Alf$y9<{ySV^x=gub60~Yo)ne=Tg-|@eiO!hWT{2v+w zyZ_r{s=?AdQ~-OEnoSp2d0?|iW`vRtZZ?@s@c?o8OJu84zS@k z>M?RvCpMe(KhXZk%_bMjI<47MfvIOU<1MqXKFo>0*;RB19R3(5lKo&eSp5X` z-eLduxBxK!N$P>gPc@qgaMuFrfwfO_#b8Gb^}zDlX4fRYOOJj?MQ{h03-Ip8U9+>(v^}yt1)B}gE%1S zXuV5M*=So&MbLSbo`PwcxI(ZQ>;{wDxxzouu*?Xl6O#k947)N+{%M1K8=|BDnSb)utNkoV(gIgI$lTHr-&>qnzk( zd^L~LK``eD>VeKv)C0p{6`1wRYEutZgYDqFA5b6M4ko|PSGkb-;HV!_|9zSN>u7)- zV}DEoVDAew0Ol^D0Wj}H8UUNYHC15C*VdYLuovtGa}Qfo@^e57vRsH@N_C)EGMc zPc9hD1Utv9bxoL!;oqVlSPHg+?O-?9RYcGK#g*MbN5FEh6x@0DT2l{Z+(W})CD;Qt z%%%J;j)OVisCkqJE2}9Fwt($m+LM$A>z{Y2@F@-dj)GuvHwVC~kLU4r(#YVCNw%rW>4aYKsZ|hZASCm|Sqw)h(t9%)61};5IO|mtR9(i^%~i z@>@(LxXZnx#Wb){UeaQ^WJehVKjU*ni^&Fe&2BNJVBwq=QwJ`1q{VcC^-odmzp%Kz z#Z-VhUT!h zUT5;a{KqHD z4p?tO0|q!1DeFxb9D2ceQ!jYodeZ^!%35!F!Q_kAo74jaIPI6OH`(C)QR__}SUhpP zsRc6&*7JM}%HOfxbb_rjs0XH$(Eh*yP8iGq+rdIGt8~4oa@knKMm?B%*Lu?q4h6fw zt{<%Dp&T>_W`a4-(m}8RtOV14NIkF;>;QLyyl7#!=oVyeOV1<+ zg<@lI2?fFOyD10`pG|{c&a15^6n>CiFFqpYCojVK#a%*kG!_#&2vetzhBR z8%z&anX|#9A4UT=ZZJ85-`Zd*!CiS9Og*@J+6L1JHs8C!q#jO#-`!xc!0nYAOdeSA z#0FChHa@w*G=pu=(k?i7QfKabj@7Zccn8Bj#*0*wqK7w{b};i9+B=5*U4muk* znoMvYm;)w*d0+}y0p_<;Kb_xy+v^)mCp%Jq%?ZKqdsO5R({&#+l;F@Ft^{lWTfyW{ zC=Z4|qoL#YIqunL>cQ=YwV6&Z`RF#2dOV*`XfwIs?laqX7SsSIZFrk$1@o_IGreHf z|FoG*mq$pajcYR{{4n3MpUvT$`x{ z+kV_;swua987Ba<*R+`)u)M9!gid5+Hno`?Fzxqr1WbLe%`}6<{?umNZZ?WPpx{Zc zbtgRro4=qSSnX^w&0zX~O{NQMNZw>pLo{^QCX)?j9?R)W#SkCA z$@G8&PuyfeL-?7VvdQFvslzszN^s%1n@j_koJoRVr|ihuWRg#&BUfxPSzzYXn@l0N zD~E=`($O>w?ijbpIH%CTZ&ME3K8bSRu6)XY>4lq2D>&-TO{Nc9oAyUBF0vF#xmK9%qK(M={3Y^>g7^1!Sg&@i~Gj&h(=Pr1|hPM6XF zuzNY>z{M?;1KZmu2X1?V3p$+>e8fnB6aLGI!J)e;2X-91*>r$a?%|t_lR=M<+H5kx z)?+rCFxU-NfEmYaHud1p6Q}@Ig(!apBsz`q;QTW;n>=tw=4Mk3W)9zMTEU#G&87!* zzOmV4oXP&HXcx@6cC)DhM}Kp(X#m~)+|8zojj`i5o7A(o@>@5XY_MU%W>W~}7i>0l zVD=DYJ&F_EY&uN$)SuJ$n9D2BQv&jLgJ2#t3uz5Q@1zW&&uodhA+rVD19ZWqJg#u=P zx$kfR;8-vWhQU&B;Cq{S@FZWwpXnf&{yz23by1NYQXzAIlikCRgRTGKgy6PMxdL$T z?#(829^V-+#0m=z+G47}VTWuntzg<=TTCyQeBu_9c|KQo@)lD8?mBggX#gwE+G4uE z?dNPU=@;;`y98GsM1;Itva6+*6`Yomz z+;Q_3(*vg6PPq|qXWAB%2adjDi>U@f#dHi@R7%Id2{X5ttP3e$PRGEuS+oNd-?PQI zy=;uWcZ20+e1binsW)W% zg+8D4qwlh;_-MN-=RfZw@R;R*v6he2dxXj{#j&A*S^1lRd7NEl$1e-QkF*p_ zFnWv2f-Ea6bG0O>394*zVdAo2!2TUC3!*7Aja}yB?wpQ<4op4ivY^kY=U*1ISbx2C zkMdh`<+32h^hYiW8q9q{JJ!Eq;72C(i1_Ii$(V}PV~(ug2rQ<|E;&^;KIsVPxw0kB`q1iKs)6VL0gCQ z@16)kkLQ^a9?N&$e|jP)GI{-ppv7|NWH99P?N9o{1eLt|$)L#5%*mj`#Ydg=*uDEc z&Fd^LdYzruoD8hL62J3g(08Hsg_A+_iDuL~8Dv=g$w`mhONbjFbg>%0?8MJxm4<~~W$Nq9Mh##^UZ?GBUIDNCtpvKf~HiItvcii-J&6EA|xa($+ zWc1#f9;3H5iA|5uYna>&daOQj)8q4gpFeIhNOAYcn?aHB`AtvFJC5uy_G~wNs`jtc zj@z%+j{6n;GxoqoHa!JzNshSA?k6|>?|(u6QwCzRzUirVGy9B;SzX@@s_cDn)6?!c zG&h40XTH1X>2~M)hnqo`*%OkouSE`p?9t<^DdfnwgZr-UVU+yV(GkLp?TzjYXJpAsXA@e95W*xjcwJ*Kfzt4>T04{7^&Ik88+dKhlt~pSbb!Y^shMbLE8gJi4hp z!>29}nq0i%@}SRhSNjE<`Ly;tdPaNp&uY*3IrnF_=l(2hocFPt&v&B>I&fxN2hRUg z2Ntf;fz7@S+`3jJSlcm!7x?)XD#FOGe5@xIf2}>+zwuF@2e0qC{|oJn-)hgX|J9z8 zL+xMa{4e~$=YYCU*;8uv|IYwS{Yi(MwIAug!k=|u^)K3U{jb`wx$pHCso3AV&hFp6 z&h5bcI0&5zhTOlwDbIwP=q0Cu6eq?`1^E}3l;lRIf~pHMH$D}#n7YZSpwId6sUZ9k zo93pcf&`atb}GoSeDhPD0r%cLeky3Nc8gO%m(5$A3P#+#)u|w}XyC}Hpvcf|PI=bb zjBk4?=rB1UA!cqTq0&p0?DjHZ@eVR#H7X&l-%&zr-AO|1-dRE~b6O@P#L-3Qc<8PY;{4qt#Id`d@+i0K_mmj7r`?~c_dDhJe?jv82H++`dB-bpDu^@kK#B1< zbF4n}R8ZsG!%lf*+wqz`6$}`Dq?!DSQ=5yS5$$R>9&5V1` zQ#p=5-^7@Ffy%wou79BlvzXJ4)fbgC6dZf88GA#SeVMiKhLOnA`@-xiB;tI}zfwCc z7Yyk97G7g!2b=PBUbnd_Z=f|@dy@*8@zKNjn@HD1p};{Qkez4F$#DDKU5caw=%D`gfVKcEc-z$ZKt~n_uA(YHNPm zD}n+u_qZZxF#ez`JTdJZ?(tUy(bw6OFTTPP(cUp%dPUIT(fk!YXqcB?;Yn!6`&Cy2 z8Ae}wg(sk$|HIWQf~E_HYHq~ZrwsUdrDKBI%pCmuMIBiG?<;~9mrlAd=O%sN?;Fhg z9^D|z^u2vJFqhb1`+?n{$Bmh;2b$ggA=EqZ<^s`P^>MKF!}#Zdw|&P zeDLX@%k6(Y?ZIIKKm2r%;Mk*1dtlfb(%k8w%DMDu&k0NTNvDG$t4}}e`CxBk&pjPv znS8N!JoJjwo^X`FYu&G`5^p{oBpG_gY0m-Mr0?^GfDJ*TeL5I%`3DAkyUdQC4)UBl z;YQ4Eo(@{FMN}dTiTzJ@-V94&Q4l6Q#_?aNZ=|}0nsq~qk!P*ng1U>F# z&IFNnnd#Hc1PL~tbtcHM{rodQjggn03A#*PDv@{FJFh+yB$;{LnIO--(i=1s9DB2d z2fpo05PA>a;fAcf+YQ-#-a;XC%P2D<#T0%PjP? zXP;eW&P#-C#y)5%uXcaVFvoRPK4^DFFDQu%lk70YKBqY10%QMbU?#c94BIU5I4c~n z!F{$lwe3DU!f@3o`l$+YnOW|zToMcfHD<5Tk((T_%g~4X6N*vxnBX?k9J{CjOkS%$ z;{y|5dRO91TyF_JY!m*)fShKL30677QbUjwv^mEfC;n#Ok0^P_2d8uClC2=e+KqjP zI*;FU%k#m09^dkOuz&5|YRmJ%?sJEn(W?XE9kKq+X@c8 zAuvAW?|u`4`n_~u^u7jQ_5KFn;sXu9nHdB8n;AdE0NnX!?Rj+809<*b0XY9?190lG z2Kboc_4utI&f`zq3NoB{%2rV3PG&1;@Ypj-TR~T_`mC*B#D(W<1+kh^Eo=p8?!RCw zC~)&dTS1L$ixT6~%O%FyS4iyR-uquEF>b$FV%&JG#CZ7i5@WU~F^<1^D;RR`Z4&$U zgYz$etf26A9k{#V^Xb`tuZFC=UqYX-i9V_wYoAsjZhlrGEVd=i^l>*_bNwe~%I%Y8 z%CRfVludRy;*iCwwEv{@zjUpP1*z+FVE7jj;NGvykjuaJVfmj@YR0+p2kjXhsR;Mk z;_<(0&!sURr2lCZyxEmOn!C5UGAQ!s?XL7VulwEEhv{?ju2*`j*ZDt^(6Fvl54|!d zv+~F*gBF)FR|Z3lvR4MN&o~A7D}yW}OIHRJHeRb8b8oyd7_i0gXZ3sMl|hQhl`Dfh zqwl&hsB-T;+H>L4?#u9J-1l=O4Ft*0$+&T4P+<5gS9&1Xnw_{Z=yI!jWe{37Q${)J zUm0XLz9V5~uXke(M-t)s4bKI!&-%TJaFd#rHpdD?Sg;apJa3XZ<;ToC$_jB*CxJkwldo^4h*V&mZT7o7__Y;eGB z9(?=f>`V0L%%c9RG0*9j>d!tKY`;u@9)9^bA1olqU3$(F%626aJi;_Lm}8qoc3I^% z8yvFD^(Be0`bziNuo;>`z<%--1pu1KULyK2DZj2)(u$uu_boB z^%G0X&Pf$uru0XpYkGk(uK!s_#{Z%r+pIDBR|&CvtE++`D-3^4NpF2skm2m?RY95C zkGaYN%m@EO)9%1$UKJ$1Zf{+BRZw8=O;>qv*?r!ARnTW?;yqUdk#8t{-Ho{Tc{k$D z58UX$>#qt%Z0=tb#E+`fje0?r)tmM_sO$~q=DncFjYuyTuz!bM5c{S#qC0EHl^^$l zDvz;RBy5gvSZ?T9f(Z=xd)v%saBp7&)cmL_sO=p4L0aXuKb z$>{ebbi4B&XtpV%=Yu?#rp^a-*4bk59_NETVFEn# zsFI8XlXEiS@NwsZ@DII#JV8RN9XcOmx%5;CG5vH2aq^kxgD!{9J|B#@`COGc?ydOw z5@R7JF{WN3F;2Yfe9-0~FEJjw)I@${Vx?D|50Zk#*T{^?WoyatH(E>f-(=?8I&4XP z?EOK)aW22Zl5p-_=Yt|ADoV_q_o)Dne!!A&rK$oyG2`1@9pt!tTVE%`<9G0tGA!*x zeIJb=a;K|k5BW}<6VCs>pzgxNldlf?j4^i7jhN#e z%d9*_J4T=COLVyPEMJhr>a!)V>4wjh06QdzYG2617VDRn zl)9jS3&q!59YjufBYExB9-&sc*SRsnuXke}e(Tjild-q?1|Ck7d?U{lj#pVpxyuF@ z-)>+=-(ezM_hXu4D^~}FgP&Pv_g&hR1od}IfU)<;@U)+q;_kodz(G|9_CI6^nE9|J z;KWCi@{B}3CIMzYVNDrdx1=0>-u=#6^Djz(6JM4vmzq}x)q|hEezpJpCz$)D88O^) zV@`hi>Y%n|tr@=HMr>J{o$q*^(eFx7=@Z{GfYLU;@5U+^`yWfg&QG*cq10t6sS>Rd z5@KRgMI_d^+}?5j*cAt#=Od_fb>#Xv9XZ+4@k(z*=iQj&zVxWhm2HV~|EHGfoS9uT zGw$~75iVXQQ6B!8y~Mp830~#rUs_7;4OEItzcwCseq#+sf`#82uxC^K&VW2LG$4=v z-hiCF-hk&Ft33m9`i}E(GD9+U1OK`^MU{9=;GX z*<+8Hn_UQ!*QgvbEOi7$!TilNV2>3EWNvXGNV{?8mees7F@V=MZ!H0qZ!5uz`c0S- zD|fgMv^x=_2jjM==W8*s=z zr|)Ip>y(lSt}@NZ_=TXrO?J4)ssXe2*4{wf`k}%$@~G9 z;Ab{Z!VS2_7B?SsA&BnC`2We2hnZ!Y1s+Xa2)bPR=L;UGwiJy0+@5);iLn1Lud_Gn zKELqJ_i+7KVU?jrNUS8N3c>~qr<8~-Hr#OIQD*7}%X2d4;^Vx|g|vk9+j@clIQB%> z8E5F124;+#PclR99WpRSPreY;n0Ts+aWQkj|Nk#&3St8{c)A%f_Y8Z0;dwVc_?b=i zo@woV4RzHTGV`9Hnkr!#t)XUueH_WR5_wpBf?w4Tx6=uRs zj<|ZMlI_~PuQUTTnPr;=PP|HjoMnUC>~N0*PQKc}zjYtRnO?TU5*RD00O#1^(KnTJ z5R4yI0RykU&8A_8X&q<0p64DbJYF^+m)~wcR^D+T7&7)Q1O3ikc&|h`{sHZIhz&N_ z;m#2gWdEba`(K;2^f9FqR6Z@Eg9~-LlM|mYgQ0<$;>719#v`n8lPxCKwP%~*-<$Cl z><#9==s0qwArT(`vZZq0?G5i6eqQ`f6K828Nd3WEXj5sK{F=34lP%7F-TML?9C7>` zmgah!kVz)LX&|Qm%Rrp{mc4RdOFu3%wCA`n#^kqEmZ9&c?4I+#A*i}==$MYovBL(3 ztbSMK|7U5K=Ps)peb4Lc{EyQAQDQ%EV=gf)(VZU}(CdXCnFxnJ*5B*%KanVBI+o^- z&i`>i+l95ul!S99&G1i-;e~60EQc&GvVBcZW1M}C7#S(~Pp=7*3|(_gkmCv~2R~o* zg>9T?kIM}G*%C6&$^JD#rX;8eii}_Dd+gX|hneeq#T|X%OzvJ2l)8evV8n_4_5FDJcJuYV z{f{XYm}iX*wwc`X?Sbqt@;3=F$;khy0F$gR%O;ELagCwByWbyGfVDqfJ#h}X(N9eT)L@mWIOno)q|gJb}?wN&pzjGelZB& z@RCrA3C6}RdUo7(mbuC{cRAqfEiZa@{E|?facKxqWV$k92 zgv6M=oy5j23GLs}Oc?%0Gj_umi+-MEofUSu!4bC@yU`_~XiPt*m}8bjF0sl|PtX!f z-qp;QX86XJgw~i~i&<{5%-G!|z!|o=zyZq)-Q<$c5k}czimOvf&tt4HbPxTQ;@~Ei z`1~J1BrJh@UJQ~=YY|B8}DY9 zgyM|ftfZqL<3gT!9%Ge#wivyS(sGU?<{7)W0hnf+1@>8E`o5NsS@wCD;qgmCbtZU} zX@;luD+%I)3Uh37nH^TxXM^Ee7=Q_m-OrLR$^z4@G0!$T9B|_PW_n9Y#Uxjm=LW0X zWT_?C5p+4?fO8Mf@m4CsI9C%Y#H9z?JX~h-)^5NixBs6+8Jq-Y_{90 z&=U>JLx;4x!zKPVqdmlhr<>TNmWU&6vuXlEHaPW+l9CCs&yW$1&D&g&OG4|F!p>MSY?G>HaTRE z^DofBj1RNJ&WjDq@Jl3U=2I*(&pO-ea=@xej4j&C%y7WN3`L#)njkJX$_%?Ka`L50 z#3Z|%=ZGte-O&;;&0{QZmo-LSrlOo>kBc0#!swk;f+=>GzmxMn5|mwtzubU4#4eXO z;t|H~tRs`0$g33NEOMT89$|-F4jKIy15R2RCRk&Zp;s7>b8JjH|0{y73yYU3@m;)O zFv%_EIAn#fB}>9N_LyVnA1oQ;TxW`X<{5sa(lgE$v+VLPM_gyD^pBVLuhmM)J?1#| zDg!dfIt%P@g?%1lBxa_JGyG~Z<0K2rvc@voJi;C~3MP10{TO5DHO_xpFexZ7$r@MK zW{o|z8M>R}!#LxwH6Z6$W{wSRu*)_F958Zso9}fh${2Gz%nFaZ&iStknl5y>$syy* z)^5uC0uwAV%f{<!>0xPBP!%k` z(?Be9z->nEYg01L@QMLB$t)LHX5w8c!#(y7UVpbuHf`yc;0m+cV3}>!7=DlOrk($q zVB|u)qQm`cI_9{+B1fz<_dX?Lg+m@?^#0yTnc~>{Re}>NGsOnW?6SoXHyL?=W6Jmg zN(K<5T!^l^0jF8!G8?S1%N|GEXC&dB?gMVXDW;fYmaz|7duG|>Dtl}&^gshM&ar>B z6eU4SP~@&k7?S(T`JXafN-Zam4NsGyNy0fhmSQDse_xVDh6E zOF>PLaiPfqd#rHC2Ez}wYnk9av)ueQGiUf?X3hn6S>}jG8GDF-czj%mxyC%3EOU!B zjy~@Av<1`uZpPeaBq_5`m@!wGW1AJOe9}x0erBKHPf75f^=FJJCV7}S)>&bbb?&mm z%%@F|m69O(P`jN8?l8-6U8YR2!FjfsXO9DhAEuD|6M^;u+Ic1K4+6~nmHC(Ws@x)XO}$=m|fTZ;g*gGu76%X9%GSPta6tPj(631UUXBiE#4ED!^Gb zInNG<96qw7!B@;6r2$i1Wu9GDIkjOxCfQ|^p+_0;s}g2|DaQUoq8$5A12W1c7uY+v z-qi2W#$%MzUpqMef~=s(J=R(Ix(vC+AqNaU#?pL4i8;kIXPDyxE1W)Rjk&}Dn~co4 z@3(A9##-8QmsO7b+xc%Fyzp%uILpXmZ6d~5WQMEEv&|~E+2X`^ECG`YKTc_x;3Ctk zvcPp#*k+TVVP5c9I?r%?6MCnyb5jC|jWImasVY;lc!HaX&mu_s#7wiz?c0+(20 zoo#M$!1e!8;V1bWz$9l%Kd>f(EGsOt$>Z#Cn?q)PD8WN2#02Zia+78DS!3?F0lCh> z!F5KSZ1erdfShB7H5OTF3aWw*8{B1=ksq5OXBm5ny}&frSl~7*O#DQ`OtZrr`&?o8 zsZIwI++vnv9SL)t&8Is5#|1qXwmIaG;f#it8JP1-v&;gktgyuEy$~o4#z!sO;eVX&XDj2x1!N}7k!Z_twpnB7awTSjJZ5~(XM`+W|?I+ zSZA9(4!Fxw=vf9nZD3}Z;S%#~v&udjjGi$ta~yGnv1gkZ)7)Z#;j?DSX||bRkB8~0 zgHWAu?woc0GlKCg19FOGCRt;fO@^;@17;X{jeKr_ga6FmdF0-7t z+60+qgUcmBSI}eV`DS`ShRiae8$VEn9Z1XY2CiC23m6>ZL%(3gVXO!WW_@%}KYs_+o z<(HI{{AWt!!X(=V4LRTvLyL|NqugMMedf8xGGjaXbDmvRIb!7J27IYK!ZZ)Fz&2~# zXS;Op!Y_2-8Y3^WMoe=0mj>bn>)d3AQv>Ze$JopDV}=73Irl5=xysJLbq<;MwTa|a zhzS;0$_lE2GMj8L@f*jD8HWBvL&n))h8-3;V4bmD12M%RYmB|Z{g`Bj8TOgy9?P8n z?ZuM6`%&uODh12zvCq(@&h_sM%osDwvd99fTw#MdOfI?c{~Ca;q1U<177zWw=HvAB z_QEUeEhcz;uVga_s{bb=F8t9Ad4ydyIbe&SS6PBT8;AqO+%WtXzrOuE#R>~-@d*1o z#_+36@4>Fu%o;6l^j4k%q=YS(l+_3MP63mcE z7MSA^R@i2fJM1xfiSd@5|5-tN*%~p$0`ok=DjRHYpIuIl^@9QD8F{_RFwRwGSZAJH zRylbi33HZx9%1ASD!}9$oc}FB&V}(C%al{BGszZf>@#|keh_}6k}}Q&8{7_?5f9(g zjEXiTqiit6CbR6a%w0A(cC)_oFNg~UT)MfAZ}Lll32rgVZ5Egs?*}!e*<_bJhHqgY z38a|kBCA|E`1#Eexut%bx|IQ$=738qMc!gf1W8Wc#tgi$$T%y^u)&FI^sP$bLW28DGj~TFxylMR zSm%*D^@9%E>~sFkmgH?-XN~aNk2)~H zIu{t`8ar%r$ZbZ;)-a~@oMN8yEVIZ4>vy$8JjT%5C3H8H zaQ$A^mPN)^yv`(B%yEwuM&mXmv+Qt#Lmp@NU1rP}hfH$f-ul1G`A-TeE-bRiDtl}) z^lqDuQEoHA%zb3eMHaZs3fI_VlO1O6D{&SWdyl=tG}|n&&)R#eWq4Z2T$ts68HOrm z%s6Yz@ED66u+GW*8Hhy=xy9IfEzSKU$R$>|!8-E~(4I~9Iq|@Qz4bl~9%N=L%;?A_ z3mme-#6KB;?T4tu`)#VEHRS9=Z8{!)m_5Mutfga*U4|cSLQFHXdPyk9D2GgO@e$5{ zUa%@C^C)ZVvB`aQ7<;6QImZ$6jC?>p#yR;Y6=LHtD#SLc9G{aAa3gTF?P7aoYyBFrxKiIol9)7$u0*Ras2U?;9ng_COO9p7no=Ii4x;s zw%B}P$;<@XE`+OQ`Xo!iEVEo?nMc`RpIs&n8IWs?eaJa}vdzWAEO3uC&OXK7VwD5# zF!Es&d8!1tToU929acD*QF<=2cW|Adk4WrkO3geoY_iD6(^Z58cDThMlh3f$M z1?{=P_Q7=yxWmZD`~&ATD)2Gqe@c*Zp~?z3*kqd>Zn4j)*GjNv?U`VOS+23bUDi1B zIs-Dp0hbv0xb{r4&paoVRpR3Z=l=~lxNw+5RvG?xr+^7I-Y7wCvdC1?%s9_B*ErzP zo0R+$`ZK}f%rfz26XP0N?6S}LTZ~g$vsnZQMi1-2X%<*ujor5zhy(UGdYc)2QhS>> z&S|DtV4mHwnQ_1dM{hSEqwla}oMG%!D#TJ+up}t3#TvKSX6T(}#u-LF?Nl(y73SDt zk$u(~SusPV*yj?%b?=}|aFc27vB0T!IsX;G{JX3<%j~hrA?pl(#%^bfTTFA0IZnS@ zX_;k{MfO-@=(7@JoIPf^&mz~~qcYrjkCJr{UT|T+NJYobnK9!`GsP`q5E~q^`yrM4qD}r`9wfvhXPI`rlob>N%dByoZ64=OO}vnc3I#qYhQByBOf)O3)37h&B&J}!X%F|!yOhm z{%HzdL|$JZswDONbgI+xjEon3Bo!0_iKaMT1pU$Rz$br;&-w02*%nYj5C1N@ga zlnn#0%p5B$vdSutvc+TU@;C?FWawMg_^a;EU1m7`ANCZdSmvRUpdqNR%i|nzp(%lu zWA_amxxpe=kD3|#-?WBY{x1o0$moB2%l($k%bou=5Es59QTDzoQ4ZPVvF{s)rENj% z+e*^5X*ghxOFz(&kss>F6uVq!M#VbJbHplFk88*AAE^N67*WaQkKLD}pJ>lyM|-Yw z@NMV6B?x^-0+%Tj<4m!_0t+Y1m}_iti+zq5KBkl>O@Iqbv&;fFSm6$v3~$ruTUY*bd{Ee82P^TjI(`O zKkhQm@iWFN38n-M&a%w{2dpyER%#}hI%{bd-BLo%vc(Pdd5j}&GV(v(keKA|IRkR+ zDg$zYHD+0A3swX@);VO0;U8GTo*Qt98J3x6jb*l2WAwbld5i<@G4ew*yxPn;%M4do zWS4aguXg@Bf{6c=e8EHcLys~ob$ zcwaxxa>Pu(B-0-|MlQs8^jdp?BbGUPouy%hZLV^_Ek=Igv@p(nrWpU33Ngnj>uhnv zJ|}l1+_6`fV6yac0}6&Lv-b-FGXG1PiIW4F9{kMMWfEYTEf&~ig#*@^_?7ns9^sH} zMo(C}UrUfZW;ym7{aLCB+Jf+|4%}w+q~8U<)qyeQxxxYW8QJvu|Joaz7}^8+C0O

m0Dj$Q3HVR)?T!CaA!eB6 z5ta|G|4{`v&o&qTq#supIW0jZ*m2;8P>VX7Ax#>gCq7BJ0k%mIr(RaGs7Ye zv(8nvc$9t4|HZ&(?IFflWQuDn@dI`m2E%-bZd-2YmC=jS{>KxVA4#$-aNIN*SDkFW&Sct?AN8((z8c{gNkK?VCZS55_a?4=Um z+{?7%GV5Gthr2JAK;QWve}xX$8i*O@SmgMnI&hsGw%O+%!`G?MlEgW~G}Fv+nHARA zW{tU$VDYtXz@=pav&la982*LIyx!*GVP@H8nPYFTrcATTRgTzY z?3WUIqk$MInjm|O*=vzExy~7uT7r2&mj#Zv%D6SIGsPkE9DlQRjB&t4My!32adw&E zE*qS93k{rNn?(+|#>l`gvA107zyArgT*z_kuu3q-CTH2>5<|aIdd9iV47XV1*jtsJ zOYE@BK94c{YySphf@5z}LC&zi^xK^OieSZsCO6pQHisPddiXaIVS+hkxxxaEvc^p| zxyK&EW&N3DbXVd`u*EF5S!Ss8b~g|t*k*5prkTCIq@$qVLXj07XN!IIxzF&P4j+^;7ntS>3v98*!&Q}G zm3?k8{C}>0NIxE7n(H4nQ66KhB*=cmOu53rK?8>V=*En4pDC^%QCc2jnVTP#D0kRp z%W5Cy*kYM|ZZN#BVvKQzX|B|b!}WT}KnD$6XmOKW?s3E;pE1L~DHSu^WS)JN z8TqU=vV?Bxnj|)^+3}M_gwtkTKI7|GbXOu*N)_ zEV9Ej4%uPU-%0kE;6AgAe?h{WV}tW-vs4xg1VVN4jUY@ z!{`miLPMrF)lea(S!IDOuCvb$!F2RF0;wQ>~MvBHW(fs3pE*I>zfC^{{?LqGR*y#wPW>LDss?( zUC#fv#2EU%HM_-_$8IIUx#MQU!H-pd`^?;Wb@Vus^AGi8ERF0jQ4`)n|LdrQO^cbR7Byo8xxg(=o=@BHTl z9T&n^TT@0Exr05xB=gL%!U{LoWa@%M4_;>|Dq+TXj2ZS>WN6z!OtQr)yFA8GNiY<| z?&!S#)PT$}$2C?sd5y|&mOXYDx|17TG$2z~NKR9=+E258qj) zf&}-NlLte!T&>$PufI+{Mx`&Ml_6 zd%g3Y6^!l4n6s>Lo=xWe=tkTg*?j-tJ^ZiMQX)G{9sInnAJ_k;A2--!mp%44Wc=^? z|D#jE6z6VmT~Oem8iKPT?c3qHUgE{tC|4Ho3;|-AwS7*98e~l>}MA=vLSHQ%dLZ*4Oz{ zN^5%?3EW*tZ>yn>`|L0>Awe#(t6h-;ZZfI;fH{uc&cK{ulWBIi!Xb|_I_3Ot3sQpd z+e?JgEb|Z>Jj^yXIAE8Ndq|i`#_w=lkYSER9%h|2cDTnO$D?L`Pp>n{)E%!2^7nN9 z^Ma}iRkqk-pW6)I%X|5qRDd~Vxxq4zvBoVnxyufdcfKwd@em_%_hpjFNtI!SMdt3J zU%aHWf}RUg|8SkJR@Z&ndK_W++c&@DVcJSBNiFCzcpr@BW5^z4+ApCI#Y4|xWo}x7^|28Y0k62ItM&Ft=$9diTl~? zoM)B`_bX{ASahMn3Y)C5!y5anbHw)jEzyI_;FO&O3Cw%Ou<14bUA#E&u{o6K?I z(JIRvn>@lE#~xz|lg@us5KWp9Q_L~X25St@8R+134p?U7pWTRY4w&NDW34G;EHlq0 zJM102{x}0Z)E;7-^GrR|`ELlaE(}@b_~Y&Rg9hyJC_@kPI^ DAn6@O2q`L%rf$99k|FQ8|<-@)&9|D z@Eq+KXO@lUYR`Q(nR=e~Tw&-jO8$K9InOL>&o5a6!N`RMXI`L$T;+%z#^#jvg-!t* zEON*?S9033%Mlk}q|}e~e!(n9EOX|??$1?r*i#HC=u*F4oxy%9kj6TtO{wq|B8!WKH8h6>|koZnMtWf(fz6A=emvvimT_ZRVd`vPOcc3zM%gBPQAB z0!Pfh&OlGG)=aVSdL6mXDl>1;kBjVbg(DteuSwVw2c3I$n z#~I1^?Z!Aq%rIPZ11_-20voKd%Q^?#W#nll^d^<%!dq09O;)(|R_DJdn0lMia*m;= z+og=N#|)>Ok|L9=@(>$bV4DT@SmuyN7=DKSOmLTJ?lZ?o+5H$RJO5Qd%7qqd9B|0! zyvn>?$ys5ZYb?@)_ll>fw{mGk9@?^vHnqehuds1{ck3?aB%)V zW`@r<)0z&`VhI`JkV#H{(SXb{ z&lQ%+f-OOVv4&D}kD*0t^(C2dhbitd%RLqt{jw4>#wO$JFu^|i48PPsUy%T7%y5Hw z?tb;){0j>IX$EYv&mqGvv$joZ$-&nQ!2PdVLymnzWjN08%Pj$8Oft4iwg;EFw2#1SyL9jtpnHDXNw~qI;JxJBC+pk&#CW8lqgPu<>Iz;3g9XGiR33pSYpxGmKqo228We0$Z%H z$2P+q72_m_Tw-)d0!*>ACCCfLFH<7UvcY9`xy}(gjJ?ucV49&52IK;3TxOHWlPYy^ zog=O=_9|=7BsZAh9*eJX{*P}O(1l%g8M$0XW*B?5k}=JrEHHM;DPe*wrrBkV18y){ zP*EnByF%r-$}*3#!5y{>C7Y?ML@q=*-8;b%xPwLh(+dEXM-&sW49#e3q~Bf(u`kcW=wN|1s-ON>uht21MV=iZ0XJ!kQ>Z$ zhh>gfWB4jd!#I09#L(+)ZkFPLnjphAi`-+K(Vp|nHICS1V~uGyf|yV~s_2Sm*e!RgekxImZzf8999LFC{@-&}NGJ%rgEPYtJHUJkBWW zjK0;4e`~KC_&Wo$!a9$#!`0tw&&(gRf1B$}vCBM5yMn49a=p^9$UbWfI~^-~D#PQ< zGW>rk!vq`5u+2Ps95Gb3%m1h!r~afLr&-_(E1YG$?EL2h9T)QKv%nFH{Qnf)abT<0 z*Z}aLyEmwbDS{%b2#Vk$C^G636#2Laii{#Cf+Bn+K@k)|5nF9R5fniYTm;tyMNCab zSy=CG?p=2mpMJzv%lGSFzo+l}o^zh_oO9k@);6KHDdE5#;1Omx%hG}Wwg*^bhsPLr zyMeAVFz1u^S}D z6_%J8N{o@fl|Ca*ZSd=A&K9 z7?X!IWF>f|-+1IruN*eGbh9gmT`qILIwSA)y?}8BZ+@lEkaO-?;?6C!<1Pzr!P?m} zEE(ul24Z+j1IBN6rQdW^iQ8Z4HyvHS!$x z(0fgYagL5_$I0<43&Xr%-i0d5Y_Y*E+Z=G0k@xw&ekToCVxApVxyuH}?yMc-9B`JQ zWlM3FEB(f!3Np(a%Ur)pK|{evL_#T7nu-enbI!LzOPppzSt>vQNbDtx-Mk7$0Dca49F7O zY_i85Lsfg=#S-KsGn`?Gi>z{;EwInLl`v}2qb%&^5g3!^WW@xcSHkTHwwvOF*2HJgSp z?laA~S4o(QtZ;)(Zn48X20rUFy;^%tGQkwHTx6LQHa_e8cLZ%0`s{H$r^KJrfKld| zVvSjLSmwxUbigsTImH3D8U4I=uhovDuQOAI7c40gZ1X64pD#Fvf>2FHjPp1%++v=4 zta9x2D#R)FnPd11+A+Zv)0}#Py}(7*d5j&l+2;;}UsRzts%$}UM382dMHX3Mg>}~1 zVj!;r&NBQZdxQxdW18E{ar8|RV4PJhu)!+Z>~p}WH#`54b^m4)q}cr*GiHxv_E|f) z&nCwgm5dV%eA(JE%p;6(hiR7HA_1~Y*7Wi;(pQjj|sM2NHg&^6=0J! z#@;St#@Rc#&%jq5BZfK81Q(d*B6D0~iII1xAZOTNhJA*Xyl3j(j7!dcQn2DehO5kT zjb*mjV4H1r*khN0uNnBAHXB!&;&JBLXO&~`vUE(b&%nD4{B?;k$)$oIBUomhD=f3Y z2AgcN#U9%Xe8bF32IdM=JjOhGta9`{2Id|IEWOvj8;&*OtT4qwRge`NXPKL41|A7%0Io%dENHW}AB)96a}NGj2GhOmdYu_E}-LVsA8@|0zMo zg+&IwqeF(-WP&4~P$5pU%w0A(dVv8MVUHUZdXIe98m}rbr=FwcpaftmV}fw{sy+YJBE-dT74 z6M~U18<=^PxyJ^NenqJ`%K_&YYD$oCmYHIOSx(ipXNC{jDRp!{>?6*yTN4}$CKe0!?D{;<# zPo+309Me#6{3lAyZcB+c@pA(nH?vy$&XTV?tTOgHrREGHKa~)Z zTw;zJtgyo-3!yEg5hNM9MCOdM%nX~%v&Sj}zc({R*ky{rpLr89#uAe}&K$d}aGy=4 zFEbu<478m86+yV=#ve4~c*lU8W|bwjSZAMG4F6n0j4^h(rQ<$JO#aa^W121I*ky?W zZZY}`r-q4N6x{fe&Evub%iLj&Bik}&lpW?7_@yObln7_inTw!q2 zz>KiRI7hoGToA+sCC;(VC3d*VKI;trN+}s*pGk)Qs>E!t$`%{kW%uCz-?aO+{u$#e z(_CVa4HjyGj-btb4mf_LOn;-4OmdMqmRaI1>x}M5lr@Ih5@3}169(cQi`-|0BUfq1 zQMMSn%K7gL;w}V#>z&RBlZcC22lge>nWAsY;Cc@dpaLWcfsAlClZK-^@FT{b!X4|~J_amKZu zVTu`Mxz3*FS`7W(1Pg+=U~JD!8E1(ztg^%w>+G}5@MVtS|4E2ZrkP-l8CFW!|>mf1`o8p4WhzZ@oIs6FcKM##w!*=UID~gbuzgsmPgvnZL&XE=1pJ2G{E7eP+PivPAke z*ZXyR;0JWf^|H15yM#V0kpn+s0F|3#h9#C*Wt9y!xU^yqaE*EWH&`wRf*8jR(Xsq_Som>$0hi`D#{pVnP#3vR#{`H;{3M-M+7}48Tf~R z8Rf<&G-TugGh&KW7TIEreQq+mr}T_5f1yfnnR&KZW$csMG085sE^_`O|7UYtq=XDz ztRatn+JKzZP89Q~|Q!vq8W^391+?lHsF&pH1k zLE`foaEBd^)XaXn38k8DsvNGUaiW82Oe&*<^>=WA@7R68*mCx$^@R;n)vVgmX=$ z=kb=!$M~fZ-1h?eopD$w3lf6r?`6m?>ug+RjX2&hz<<047-5o0rkLUGys*YgY$p1r-UxdvcuFF84hheMtO`yiEOgMEtUdj z1%iD8a*JIK7`)M0{sX3g82G1wSZ0N7CiK@~n)!d}cUbUB71Ug)v&kkq?6A)Pg9eBV zl$b}E<~(x;*Z-}Z0aEPnI0H96D-gQQ1bBog7MW%2dV7FrHVT5=4LZEZS^g%onXwo+ zF|2cq9hPo%Vi*`X%b#98;Wr)4lqrVKIx#FU&F(=z9I(ugb~Q%1$pm*;_k8}4=Xsok z;8|w{dV&~_96sSUAw9?(M}sGZ6;9k-hlkGc*DrL$O=j6=nX{uOd={jRZ$Z!3+2a-m zuJ18)SmI}E&*@ug&+IKv`1v2faTjXrpL1f^X7AP-GBsufK{H~C8_e_QZOw#Dc6t1E z2Dqt`hfny8M-yR&W#)P8jwk%a<5~W@;)!94u{)g@_L;v^;lwa_v$OoeLIoJQ%L%{X zsN^iN$qIMaWG!N52iF<6`B{Ed0mTrASPL7_&hUZ zi~}YfW59DP4Ko~jtmm0zolER+WLiaTT`=I|l;YNA$SjL2ANT|_<=T@Bz&?XxuFn{N zJ*K(#WQj5UOiRYq=NNz;25uw4=PEg;m|~B42A}Wwf?!6_VElYDXPu$jdSkuF67cAp znQ;8YX2N4^aO@=#W1PX;`TC_2<62f?>@mm1m)XP|d8NI?Ci@51U*-IV!!pjP0AsJ! zfU|Fr8Jlm@@$GG{w@ZXe?~n*-+(3|_9Z9Al3W1}0U8Va6C^jTyH7Bmq{gcK^P<=Uj7e z{srm23-|NgjVX@(-R|T(n_T=qC1d!XGUqab_xJ7dUrNrz!1FwQo$E0j?^`m~|6@X2 zyFsGd9NNqeP>H}*!z`z6bk(p>7OV@J9J%pT!#=Z&JkT04&11~5$r4+vvdsoNY;&7E zb{Tk(bI&k$8DpPG4w&Kojj!_aKZ22)Ts16nlr@gA$yxT8p%3x)cfqb2CKwu#7{{68 z8mmkl^4x=U%ot0D&Gg`FR+$K1HEeN?eIC7O;i_TuAu_wE2f2ImtA@dcs>tY7J~+@4 z+~O)96ln9Y&JDIWdbWY$I%1sjOfhgv6X6nDTxOSB3_Z+JhE#wXxAGjLg>%eQ5Mzfa z_PNOL!&Tj@?E@ILFWLmXJr;W|}=_7L41KeZau}XhG9ka*`GY?R5rXOhOIC;d(rVaF9*SX9- zR~USp$}z%C#<|Z_L6CTenX~^09dUX}ga1-e#yS5;33298IzIUN(U#`%I!s8IGv{f~ zv8TG8G?Ay7F(XemQyyiDT?U>Y(W4UO@-vCo283m6)OD=zw81SZABj z=UP+78F-R}7-e==A}l`7^IUws3UHgj8JqS6mV}ELn~(b$=f5dfIA2Fkc6?rFMjUyO z8E|V(M_hcVnLWh}U*_C%ibWP#=km)Xbl|)Jo@(u1X>V}vRT5_J)vl*h>a{A!>g!bY zzkU7Qg54^ZzEFlwQz9mrTeVrZ!xoQTWbL1BfQu!-M%4h^{geT?^=TD2>b>w8Ysvv@ z%zsY5&yaA*20v@uc;3=S@Q*#pm1>aQ4>(YhJ2{xwVRESu)*O396Hs8HH& z-%x5szbQfHzoj28eA~>P?fPFl&+HWvdyd4qHZ3Pu;sP5iEdABYo-32T*%Vx0l2zup z#Tv)2v^hD);Hqz@=_ zN^W;@SbDzmKXJ#C!+{I?486dny3@&Fk`?B;#xjd{KIzwSd=uh;GZ7tSB)}YlcRM)@ zoNvaAv&a;y%yWlj9y?b*+-CRuf{Z3)_Cf>4PY$cBv%~(wP7cE_Qu>D*h`C3c^nqbE z;nYdLE#tkxHv1ef_Q;dN$eaY2WRrQ;6Z&K0ypzMki#`9ilfya#N$m=P%9Bp|oG%Z~ z7=Vcxu*b<4N-S%JjIqxoqc2uc#$Td68|-ms!N4z*@av7k zu{Rip@i(6I_kRQlL7U5qX7F-*;VnwXv9~H2rwi^g!vPl=d488h`h72xQyrFxZ0F~uYA zHxur%$pJfze&FP=&v`~(En&vF&lD#zzk8_xTxe~b^dVDjTxLexVvietFz})^W}HVZS5i)~$TijvuK&@1 ztp3UKZ!zGuwdMk|-1@VGx%d~)arO$&z18^-T`7~dN`QUtGU)osjx}QPgp9exI?E^B zFWQ`EEEVUjRdSB?mHcg%V4!k5`fp3fEPEWgPKDpDl8kYQnS!7s$TNJs4B2Ln0|wr~ zeWm5(4em2FwARers5eY5*^D>o4a;0%i(6;)hKYB&KiV6%xxgO7x9ItO0u^AA(X)HQ zLS7IPlv!c(;KnUAV3Uz|J4T_NUm!4pTlIWolG3xzHhWw>N5>`Y#(Kjno44x?Yn%?d z&*i)H{GNbu?y5Z(&+QEd+&#DF@Bh8m%qBd*>fJTu#64ur?7d|AJ~Ly6NA9fy&a=r1 zJB&{DhVf+?YsT5hSQ0LuZ-#8Je{h|_6{VjuQ&wJPhOE!K{!z#Fl?G<&)jc2E z<2~_O?OA=jCHk2AZ!j=ZZ|V)ZER4L_%s*}k7JI`StE@Bj77sA`R-38f6ns)en7T+u zpD+U^SYnn9mf2y0UAEa{kLioGyFevAr6Q~{e}VJACMdg5XN_&P8ThnK!U!W5I!;Wo z#v<#iFz^|>p0n(;!SJfJUo#;NzNi8`{v{Rqq*L)_19R;w+I`Y_PSiEHNXN${!r1q1 zF7`NJ`6mXv*ydq{BR_SWkxMK=Rb`mvJ}b=pOvh|9@F@xY+>&yNSx&Ra4(kQM>Mw1w zPuty_9^llkCBQNVOkXDB&*+eKj&{tHJB+M(pi7tbL=0%MxRhYfP|l_fx|fL-+6;R~Y(=>x^^sp88`gdderM_^uc&cu!lvB1LK0xo>QgHCE$2TW2n+IzahplDK5ZZ_e^w%_ zaKJT&zHQ*oo$`q$UbW0J`uS7CDz|DX$`1Qn`hwCoB=RK*u>KY8zhf_bUAyl%|D|te z=)y7^-21i$-&Mk68Zh+(9dYD`68xUs-83`ie=IQuj$8X*pqd{+EaAI$Wu@II1X$1w9|g*lt)kdp;Jr2E>{@*slCDoR~hFT zQ`}*eyDT#KjMM)8FPM0y4mimH;|yJ*gp6{U3C=Lhqs(!ZC3e_6xc)5dxy9Jee4RER z=UC(dE8J&`OV2K7AZR^X#w{g$jsZCHJRNiI1*eA%1~R989ETSOdki!1bMFm?**o6= z+0ySYA1E=K3~zZ6{m2BEVu>X-*#3$8zt`U- z?lZ&6?+Y>$)LoeUl{MnRug&x_-;RHy^qgXY(`>WLz#nvYnFKiU2LrLpHdonWv14K# z{|kyKj$W=}EV0hOA3aw%cwpO1FIO@ax%6ipaht(EYWNpx%3bC;V42w~l#p!>xXsX? z?4`e2BDPuM$lt8>!F2|=?JY*Q%tBnSB1mzSSx)VkF|#MUP}sRjf`3-2o`E@awamH7 z@Lzm;WsKWQGImCZxwNM}n+#tefq$6*ms#cd4bFe0YqQOC8Mt2;G z;MK!4cUa*r>)d0D`|PrKQv;u{nHXi62_9#bEf%@Y8uK^Pj=kMXPD>OT_wgA+nlIgvdc9Nc>Eqp{74ZI)jZHYL-1Vc=7oH<5W;t^K4$=<;EpSzC={9C4s zbBQS~Gs_hgxylOHSm!!h++dfP`oI7FlMAHI~`D&iQW&dM?byWPH6P zcz_!md7x4;$UY|++;?0VXY@f5W&Vi7IQ~%2v&%jM4|o4Ro_mCeaEnDApYl9ok2H~j zATDSz!7h^=FvZXfX2vLwGsD?OnF;4u<2;*OV26wBbBV#BN;1L~#<|KA*I393)&)gw zu)?iJs|f1}4FiV)f%8;`M;~Ji*UjLxIT|4{)6=?lUlQD3E)K4%lazD=GIG{BJWn>rkM`2$vb> z3RB!+p1Uk_k2Mybrczvan)BZmG+hWEIuvLz#)YR_Gmbq|rW}8k`-cw&;*7DH)-iXV zD-q^qB^o>wXfnn&liX&8J?1%JnStj?ghva4jv&iE7Z|*$L>Ob_`4VB2MaEcRoOLGH zVv=2^IAEHgn;i;d7-g0T=9p%lITnh7l3<-xcG%#=3v|dFgEv3qFPNGEC$k1%@#PX4 zHPd--M2^1765QfYVEWZ&$oZU!vHlv@&sOT!8HXFJa*K_#4;2D4uh-$h19_R<(we?m zW<1UkXBRC2r{AKZkkT{Gk+)i7)>-DfrED=-lsKbrbN^QM0E^7L-GJO+o9%a)*f|BI z`hc08V}>8mkW(CRnxR|URG+X`%wFJBu*SgHp}^XOO3GcPxq6WSxO}np>{so9+eoaY z5}f&hrMRtxm|^CN#w`e%Uot~ZtZT^9m(B2YHs4oNf_rRm{j2r}<6qNp_>f;#RUt;c zp*=Gku*KNzm6%EHZKwc~-?V2q#}?;V=n85L8Qno8zGH2;@?9Nq?0YJ3M>GAgOnLMt zI^f80mEsr&2lp8rSAn0Z1h-jY@Dlwo!xkrg=6RMGzmuhFIsZAqv6cp$_=N`C+;rUT zd?>KkHZV&pGxb|*$Hb-9?k@HMBb@G-Av3ISfpyj{_guvLg%P$G=YS~&{%F%=1>=7- z0OM@1@+S@Ms-r(!0!II053qTKJ-|R$W$tFzGs;P(7-yCV7FlAQ>uhm@U3NI&O5v|c zcCH7Q@Uj2{C!2-C-iC!yE7VGx{oUligvB{afq~ zgZI);XxES1+3n}-4yzm)-}P7Vy#bkGKjL|g-*tD`xwrFQJXgc}SnJ8%VVc|b-yOCX zjqMKmEHN@E0j9Y8fZbu4TMu&mzK-ofc86I`v&c4Ej6ZbOAFH>i8M>eM2%~H}R^Zb*|kP$XG{S*Uo zozVxFz*DtnKjk@A|9jWpl9xDx57h2yCQuN}3*y{oj_GG85!ar%J8beeJB&O_ML5CW zgABk3$J5#|_H2o;#6DXLAMxCCOo%aNxWp>AS?C{sOTdeZf^Hq@B3_aA|dBLvF{}D{SKm*RO#93CEWrI1k znP-nh2I2-{m}SOTWs)1ru*E#LSZ0qk?y<=unSu@l;q%S-VM@gmCz<6Gi=1VRb8K>+ z9WJoXMFtEb78yKGe~hutBu8GavgbMf3vbY|3th$@ zBl9;Jn0u^oCU0geGVoXxVVLVoaF02Ty-B4w&N}DWWsBiyOSPz9j=aSLm}Ya@`Ck?E zT&OYdI1LzOkEsLSs$<6Nl@?R%Gsp0MsTdQiGt1=LB+iL<=r}ziPg*xImb8NB3-Ku^# z`zfd7sRm?wo{#L;yn|8E^J#bc~+^vh;=aGk-Y zN$@KY<^oI1ebs%A*0q1Si7~|uR#^L*rR9;r*FA95Io+`K-1?@Oa{pVFgpqF>;2BEQ zuvs|vT{Gh1C1%3oKQ|LD{Z2)mX%Aec#H?KII_LhR63lG7{w!br#lT#>nz}g*~O`k^fUUZZJBlvP^LP zpDN41z{Gfzq31dOtAgb7WW)^DnP;D6uKe3fxXA(Mu9ML7CCUt=*L#j#b{N}Nu@@*Y z1VS-uN0nKv!3d+l zYy4oL88X8-^IT+=4YoOUGta-+sbHKFOmUJ~9$}GFEK~&Rf;Rgc96WGyGk=M5%nWBo z4Zs1rT)Kq;UMk_Ub;vY}%&@{N>&&sm(Oari*3vP~6=t{?x~4F!2#(xJ0?aV*GMkNI zwix4pY0jTxAXeGn)~!|O)7x-ejcBMBvDh%Jt@%P0pt!cg8CGRheym}Z)D%rVCj7g=SA z4X&`wDtiS%QxJHQ-ODJ)&XXZ$S!9O|h8`mkj&r~$LvNN4qnu`f^UQLMWwzPi_Ox;S zM+N>%CApD2IRApCpw3OUIPnAzE;=TRaqLMFVeiQ@=SIq=dW)Go%>Zn(!HK6!ka-5* zsz1gUIjS<8WR7u`IDORluL@EwG&svPHyE@u$I}{e^w}D)^E{h}$6jEDMTuo3z{}g&7FyZ1Tt(9KR)rFwbe0nPQD=CC@Q^f%D6` z3(fSMX0&Q|bNM2Pa=;wx7u(dF`>Y8v`Z*JOmv3h4CcwhDpeo3+&E+ra@ZEMPBV723 z4!O<}ci3R;t7gbJ10|<{Va_ta$+}W=ku@%{$z^s9?tk6$?{WSI->{bNvBux>088w% z!r*(o(HLQaaVEd*d8SxoniXbPXO=DI*=3Ev_c=Wc?K#aHi{J75`)sClLC1yqcRjf5 z#lRT%nP%#H2I3-XOdOLSXBd3H(lW+Hrdei@RaRJIof~Yi$u2iJC631EPBpW=!HmBI*3$%Sy*P70M@mweiwyipqFnv6_6%L&`A_Pv zYY%<$;QPOz?!q=(++mkJ4jB5Yfi6-ZCRt>TgTG0PD_5EkcNx9db2}!&HCDLKHfK+$ zXx00H5!QMVtQKsJT@Sdhe2q==DVyosy@}wirLhbDxv&?avI;2j26{u*dxU z&iMSl&wGW&&kP5gW2olM#W=T_;poE*%qiA6&kolZ_<{;D%)!GAz|7Q{VTB8;+LVklo;c&b{|lmz^#JpaKQoMe$sS;asiclL_CzIQg5h(&5XZn z?VqlK+@IL)>oLwe3;4DK8=RYrqHk5`5 z4w&P}vQ5V%>zrYWbL_Lk;CEE+{btO@2PDE;*&g6NyPW>8N`BXIWQJoOai5J934G7_ z&wbRu-!oI@nERLqxWFd!>~N8N78yKdh96fMj($R-Tx9Fu`UN`vzL{TWVhl3D5YrrE zj$xJxf}^V%GWAIv|G;r#ocqi%a*>iU#TJVkaF5X+de>j9V{Wp{k*dTw#XhGQY^n?+ z++>nRKjr-A1sj4o$3E@Fzy(HrZ zf5zBihJCJm*7*Dlw4(r;m?}^W9%@=K4%y_t`dy!DC0~s#aU+As5!Q5vcXNZ z8To?tKUJYGN|d8tbpA7fF&FY2XPKcdX}}6Ym$<&J0oPb!^ve=toq?bE{{Iz;@EG$< zeASHEV*kLeNw8%CU)P>nY;mNp;f?llGi8i%CYfM{8{f1U*<_P}h5>&ebA}maj1x>U z#T?TtF~cf5-%&}nzNd1(w4}!*#6tWB9uTat!^jWKc+;DSNyeKx;^vR+4Nm`92fwoR zOta1+mwqBat{k^1f9<)SN`(7tGjoa3|HgMyMwny#H_m@qka1!D=Vr=0n_OatW%jwv za9cvZkU0~~a-CHkXN#Nca_*NV@>~7=N}}9liF?2H95cUB$x90w2;!F-u{~<&Tzn^4E<5*7-g0T=9p%lInJHZ{@^-WTx6HyrzP?y z2{Oa}HO_xsaJ;Vq+fKpXWyq2LRU)?7;KV;{J~kNnv#t$!JS8v{%67q8rZ zyUz_)xO$!ToV{M+SC{}3EMM>ZX9b%slo=gLq$?4I*=L%qz_r5~+idd4jjkQ`S!DRH z5@CW+G_{m5}FmymD{ldG?uM=GLC)2J37`B*2NgT|11OuoswQVf9=C2!a#W z4jYWI%j1k)<(tMmJ;)w2+-07zs2TDIYmBqWIrg~2&`A@Uympx8u?KjLYY)EGA279- z9_D(_`HwvO+F{Ox@kb~Lqpa}=TTHNbaQ~6l4x^_Gz%-9M=2}1R>-yt#cv{C#lpuRg zl?b!X@ch*#@EnP9qLf(~AwBNryv;1RZ2WREolt~nHFGR$qp*kh7= z%y6H1j${nTG1izlU+Gz5@QkH=;kCmoo2(QB3oo)s7@ae~wK`&&#TR>kt8B8t9yebi zfxdxWYGAIvT&1`>Z-BpR&j=@8dF?RHGP4Z4N`IVWooNNB>@FGjI!p9!GvoaG3~;>;mnFi<_ghPjuDHJM*fPu9M^%n9pK$#@_R0nN zXL;2`5B#JF-r)R4E_Oq(!zznaGh+Bt)@W!(OmhCyX21$7JkB~ppYc3r83-Kq*%3PC z24f7YsQ_nKWS$kSu^u>F2=oOV7p6X|gBu+VEHTD1lU!wnHRid&GSi>4sTf?hcW!*x zXG54V+h3FTO%4YtU)P><-!L$zziHDl`7L{5{_SoU{mYLjCyWgt-tC!i#JoX3oS?t)%OkZvf-0W~* ziy21$=sB+c$@%XJQh#$SZm#5~48YR05*bzcJ!{8f|8#CSIgr>b4*MuZGh^i6O3NwM zxWEqA89ZBs80YwPCc>kvaG5RcU+4S>Zh1H`f4v8}%^YX;b;t~xEVIup!yy%5jD03K zeuE0ppCI z_x+K`!-2tFJ$PG*+)am^VVX7OxPPt=IWo~7wivv7-_MZR{fysE;`iteQ>-z|{d@L@ zH3p*nVUvZRpd*;Ow~~Y{0h2s>pZ>7OG%E~G8i*aX*kzYv_mkM|-Di@$2dWrL4>ACw zMNiyij4$MBsG2SQU4;uzD6 zvB(+Lm}Q&u>~WKkyXfbUmX<4z(r-b~76c-8@uMZciSuO2qmR{)8;>*4T~*|XGUpuI z++px;_6Q>!eUkQEWtKG-x%gyD%+ymY)w$jiDc8C9-+kZz1tU+Bz{KIe@u%A?tR3wS z%iMW}hHR&;-QCUnIZDZ?=jwpPj6@hc-~D@dFEGjk6I_3xCFR_UO@zglsO&ve{G}?u z>1@9+><9)~Gl?qw%Qa+}X-+W57)zXDm2Gyo@CpOp%e$OOZZg9z^W0;Z)p@1nI=gIe z!161d|Jc2i?3FrTjTxq2Wgu>`%RUDjd9?xWBVi`F{up5;RHtC$d&IDLt ziEFH~&IXSa1Z_c!J#H~@Uo&8syNq$bBu5q`$Pn`!XPHsfc!W)++2b4o_j3vu<|1P( zG0DP;AS0+U&*QAJ%?7vG<_>$@W#Ilw%P{vD*${I5)GzANS4)g4D^dmBSxWt%aaYcgcv(K@QnaLw;Qf9dHaUHY5 z8b>aWDC?{GnKDpKg3Pkc^)IL-XY0;??va9T$e42sJj!PKmW+Ai+e*wSRyfT%XV~IV zb~(!d=NNjlS1zMmWP(dfbD24=u*B7GJO5R|nhOoCv(4G>NF<>nhPlWXx0qr4`x4;{ zTWoW{Jx0#6Cm83*4=fQw%reX(Bdjo55Yz>8>~Wrf$Jh&ua^pubWrI~_er!OlGVoZ> zG0enI48)_%a{RanvCJN~7@C$Kqa6LI%CImdNDIc9;{;2bWR(dvSYnUMml)`AcJWAMMc$QWUlafVu+=inD6%IGgG87mAw-ubTzVvl$1nB?T97ZKB}vcv|Le`Ur= zr-M;Oe=T87v&0QHIq@4y!7`&yFk@zzZYwz#*yPx6CH%yKwH73vXziJ2>ry4=@|F&s zgt*NvlYcOS8K;6N&UPfiE&e}SX9E{ineXvQCmCR52Bkzr#heloi&k1G z=|(vfB^6s#Y%&wow6RG=8*S{0yiUa?6}wW0l8UXVXaSjYOp;M1oRU^5wrFFMlFhjr zH>pV3qNL9KKIc3$?B2V6KJ`8S-}8UoU(R!0<`95cf1@BU2U@SB05AoP!6KOX5$RQO z&~S*Rh0V}#6)gc1p%13P0L+H{un-QxGB^qw;J`2ig4U185EjGatLYM$4--GZ4`#qt zSONpk11pC(=;vS@jzd!}O?#LGU;)g4ZkP+3U=eJGRWJaX;2`wEQP>Bk;0UyiP#|c7 z)}K)Tm;!TP7AzcL{^xU0ickXUU>$6REzk?QU_TsyBXAT>K*Kfc7yeF5!6cXl(_l8t zfrYRTmcdfk02^Q{^uPcN{JoNukAp#kaX1c5*D`NEr3GLz%z)`I7v{nu=z>+S3O2z; z=!IU`2ZL|~j=)Jc0j+tAnIjYsx?mx!s^p-IgJ#$OyI?CEgaJ4ThoCV;0bwFET}Odn zGR%eFRX+8umz65E;t1TVB&w%f-n^tu4n#Nagf15Bg}D&mxDS4 z+c-6Y*>D85K+^`oVKVH38885IVLvQ_L$C^lU=tjNUN{B&py_MUgNbkwmcx_+))81( z$-yWGWzc$zCV|ax2)4p;*bYq&n*2Bgfc>xv4#6fEf?hZd`-J`t88}%NCaD-4fh}+h zcEL$F0FB=<|3^8na$vZLKL4H!;2_L}_7fxk{jd)fOi_?RrV-45%`g|X!XoH{RWJaX zV9O6w1SYE#=w`YK7Qso_0_zN4SE{2Nm`?gyO}qsMSO^nme62RXRyYJxW`519({u&Q zfa5S1rW?Oj>tGgafjO`X=EDK#f}^km@@)=7IZT9gFby^uE5GKIY6cHNA@ssB=!Xrk z54OTV7=R;i2#&#VI0;R+(Ud2D%`4ZmB+P(GFc+r4BA5=VVD7B1)jn7NM_^GU2a_C> zLhCOWl`sX?!z|bY^PvZpKrgI=0oVdZVIRzhqChYUnr>$h!(=!G3!&XaggZZDzLGm4x9A>}>;$92)16AoRnGVy1Bd zO%5kutKcHy-^uBFF)a(tFbgKa{5va&z(EN@Q8G1y*-MFV7YhYUfrT&&7Q=j421}qD z*1-nY0-IqMY=r~R2S;H58t!J=!bCU((_jc@S8_1UK_Q%iWzcjQO$`%ZD@=v~m`d%)A?iw2VfH%hF&-d```o|frhorCTND%U(?4h1=?U1 zOoRC_6PCd2waouI4)PFMU?J>+#c%+Y!BOajhWjZwOoZbw7nWtxBG3b?Uwka!_Af?03`j={v=U}upLoPZ6`b`b@Hsc--`Lep=f z_-i-R2$tCCYglzDHQ$5|^I`ktv=mHTk6zAt0kdGGor8Q1a$yN9fOW#Yk`ixb3B8Ig zfc|S4WU%ad2AR-rAfXB}gjuj0=EFKz0vll+Y=JGX9d^MkH~@oiw1WAckWWpShRHAu zrowFK`#Cj+g*Q?oSPX|?861ahXsTjR!DLvlftG|tunLyKCTMq1k!rdOX2X)3NEhba zOiNdjkoi_>P(uJLgLSY0Ho;bCa8Ur*0LP&Rnrf*LOopc0m}amUHo;LCfEmA_hOi7K zy6NKE=}PE@Rd51&D>+CmqGqrVj>7;_c1s`033l$&|1eBxSxb!S{Vg^nXmXFp&O>b2AB=azabr%u!#bR@J-DBl!pl@r|)13Y!&uqS_C#h z>lSJXv*9=_gj28#HdN4r&{Rc&FrkJfuBVG&6&$D~91gjuAWW;HK#xQjMqm-_|6L^x zLU@>k1BRgWQTlufT>ukd7IecBI1XE2@gvk2j=_w_7;KLb4#!|CO!)&X3C&v>BMpp+ zMhXP&kCPwFg?(_cl7mSOhMypz-?LFrC>d;rO|YSm{4T$vEhPO>hW$;RNi1hU3%( zn&Bk0LhIucaDoEBs&B{`hQ6f&PcWz^=>q71MR4#0vjOHz(M50!CM#6n2mBP~{{#nB z2%aA)Axu|E5SE{GOigT}1!f#m)1Y_eF|`V&8jtZIVzyXO$J9}n0u4_xYhW%kMIYls z#Eb>l3Mb(>Y=|M9rzlA5F|`PWVCz%N|49x42npt6>JZF?O65#|)gN9Q{2%2Fb z9EDA=Xx=e(04639@fpU#d}<6!U=f^vEzq!l7J_Ct02ARTv_ZqOgfBd%W~~99w7!m=DKb11wui!f+IhLf6t`YRVre2+V?})9{17Wyg3^ny!J9 zu*gREa};1X>A{JVW8DAaAY}zj3QJZ~!sl5BUz(L>!Y6K^Lj$

    MVPGR;0EXZI z9INDDl!L}%`o5hefrYT-PHG0-ci{+2?;*T{Spl=550=29Ur|6<3Ws179EWw#w4HMX zOomM`1A1UCY==d#(#t^=2Y%QD`=A#Nz&oP=4>crPsjt*`_p z!aA4)TVM+8g6VJoX2Q`<=6@Ck1}}XB6Jb6~gM}~~x?mwJfn~59Hb6IQg>^6h8{rUa zf#a|hnqHx%Fd25i3>bvDupbt^Qb|oYs6rTqO>h)?;W+Gr6L16?N@)RThSnXd7cd1T z!YpWm`7jNZzzkRiGhqwNhFvfZ4!{C9TFF5n2Zo)TRA3@3gK5wWvta`)gw3!Fw!#MJ zgRL+C1F#uv_oZ^-~=!y?!Zo8U0?!co`f~Xa02GT{)Z_r^wtyJ&2)Q=_^@g#T>+CHrz`yw zbQ|fwPz&LEN#8>OU}@zGWW0|iZKn@m%69A?rqinw05){t2=n)naey%Zi{Kz^fXVv^ zhmCL&<^<^D*NOi+O%JPJ0A}=3z+So(Cc?}hEeI>KIq-5&1xMgu9|`ZLkKQIikoo!! z8N)1?569jmK{yVFVC!Ef@EbHGOo8q}5{AA*6bPC>p}=p_rH2{yu=rE_4v_8<#>fHY zf8kLQL>TyjfIg6E2 zRz6q+Ct(xJ{(0JflYJqe}|PafpjZ5NaCOlroa|hcgk^f6gEJ^ zyVT^=j9yp<(~^#>T`&_4z-%}Q^Pu5<(t(Mv7^cB8 zm<`>q5H=(o=l4Gxv>-GF2;7=D}Rp49j4? zlLEua77j)@7=@-!=+m3%D_92eVGvfq0oVkGp%;$AJ~#nKVDrsnbeOKYg}#O9uncCw zCfEQ6V9BlIGeUfrJ;MB-;-C=0=pq6%!v+|*jSPf+J5Bd@MlsBV6R-%{@1O>-Ya?(L63+X6BRpBNmG~7)ChJs1he5d?1E__68a4Z zzyKVAhTqb(|IM^5r@*iadSMXu!GX;T)_*W9VHzx~q(aaGTcH;QpdSuZauBGZhMzGF zVG10CS#SjA!!cL_Ct)4zuOlS_8sbAc%!Ng;3|7Ggm|II%!3JphA6f)f zW^*vbK_PUx=_^2MNeLF*W^0H(k)m<8Q1AGW{}I0{=~!o#!-w80^m z4#!~@G<`uqVKOX&8PNYQeNe)IeG3V|Y#0!BJsE$=0s#wQb^`^2W6=5))9eq_2qrvE zOTk7s4o4JL&~awbHvFNlnKAG+T?(_|*fZn<%UdYWF$QPlAE^lkt*{RIU<(YuF4zwT z;1C>z+0WAg#|eieu;c|Yf|D?Lf);s^^k7~q>A-y01q6<0nO!g&HuW=G;0Wx4sc%!@N|mPPAOlvtLjrIRdWAhe z0tSO0#gC4>$eI}0GJ<8FG z9ZRj{h@D?Pafn0jZdM0oATA3i8*g+hwG1Mby|-CSB?r^p0cFE3 z$I>}QqSgIvvpP(msWU*3vVDVNaeO+ueQ2|qAd-C+UHLfMG0#$fIr+2AYPpb~4=5+r zIp$m37!5yc=5w!zyGgj(ae-3!Pls{NAR$@t6>5_x$CCZw)H96Ot#d2XJdw;Aq4O_N zX@f%F2P$xJxoxOjSQv7FU;!+G6RBO(YL?eoSqM^lqb*EJD=>SpIpVSjM z`_u~6Dl+-1SI;Cb+^(}4P0eO4ii>Dz^D0!IK{@LR$ElV<;svqIBHn>sWy__G`O)n- zwI)`m1Im?`(+){=LH_&-wE@}G)~l?)+_4}IEr8Y{w9a0ot&X-SM$A}H!H1v`cj}2n z*-3d|L50$Nxnq8m3!{Evg>r}_;_+@-SfOT$tnU{^R-BhQ7AVPAIE+y~#P*~LW#tu) z1r{SSc2R|zNLfvH_s&wr#+`|l9Msk&vIO_`Dx0pL z{gaOQR{my#p>%zPY7_ovzcEWmGCNbE`)QW(t3;Vsed3%KHHMj$TcIqw)NxLfjj|43 zQ=x3Qlp)?si;Y}cp--iGZ)jZ?Rf`P{n&_+cbym`9hW-hMTzPsTwkFa6=8!I zNjHeFEAyP<1$x6Umev>Bg3N%9s~m~Z6l^@df|W%%>uSfTOER%re_o+B(^Q7+xP}?c zMr}}u=147|SLuSNQV|K`#1)REXEtNFoE2(15e#w3;{S$J{xdS@tI!LmooOEVX??$V zO*(q}%@yh>KBi?t=imPs#-eKq@GHKB(#PYsFsN)>?>NUIW|FzILLC}(vI@0c`Qd7YN zUQ!Hm4_lkFJwbi$aY8n{wUM;YRCM`Js1s7RH{~r7XBxe zFSD5?484S7(@NRd(!mB(2_GW7UW6|fgL3Z`j(KP2A!jNw+LHett(5S3!gEA4#>U26 znvCVo;0=p&gUSgC7F|l~3?f!3U;NII7>7%GQ>B_M;vLi3#EV5c?*}4&ZVez08+YtxD;(lGU4kAv3MX?O^A9W_)(M~rcJo)cU$BD-fL^uBj zeHh*NAM^?IDN_GWT_AEzHYodY91CX2W6_5(Ikd;W+Qt9JuKz!FJGLkjX=(BM|BpTP z?{;MYtFZ9*iT1u$p0YR=|HSYpC%h#be)azkZzeqbDc%;s*R=lshx-YiB0MC*FZ+Mt zF@}1YJg}`&Emto1hcnTHmDF6Rwktop>zrpzqN!Rjr^LE3lao%)DbA(wh@~xzNY2Bi z3q_Jj+|!OT=D5-OdKhvns;2d<76#?V?;U5v_|b>=SE>^yDgVV{q*&f^&bE#rw!BfP z_K69nutaamN}Q2IP(ng2N6ArqszHusf`-t@%NF$2nhcZ z6D1Qp7rjY$b7A)J8THh#4-{^qL5I7^;LP;4Ok zoV%S%;}CPWAL|$5?Qdv%FiSb&5Ep4Bq-eU8RrWf^{N;Jn$u+^38~!Crk-Z;hH+r8) z;a)9;(?qIC-^c{+mI(w&pb;_cUlI^yPMyp8*I%h`o+>%XUC(6BL#%t7nJSul>l@0Z zYaL7D+=wlIp|IN7S}gQu#uU@2c2dncN%`bO`lA_p;xN--rt)K-b8&nEEt&dlrJ5^> zclb?Km@BVyEV0;;-QQQLK_MS{Q{Q`*A|_7BVt@GNEM@p3$9xlYDMCzFI`TP*6l0c8 zoAsCtm<`G!*RzkBB87|}WMe$5CmWY~3frR}WwP6p-?HC{GE$XfwNh!z7mF@NrZl4M z82KvAp{M90au8GNwOeIDLx>G0RjDI1pXpf&nls-ye<=||GpbaU{>VSkL4)Z1Bb93L zOy#Q6oy$$9(m=*4bx8RkoAFw4qa)7ZMr)o`#ULiVO>gS^Yae2vsY=gzcQ|Ln)R-!M z)QRVDa-MpZt%Z3Wt%({E>cRuFl+1kRX-u|qGi4NM#vTx9o)(W^YFw3?C+0=e0Wpc5 z>31%PL(a8U>1Tm;2b2>xI_Ad*5q*f`BF&BXDnIn$I)OYMU!|YR<|=oPYSbXj5lX01 zHf?aMh%!>bx>Ku^whfM@(Ww|C^QzRK^0CpGJPWHlu}V21g32+>zpPe6%Box02Vo7| zQO!@LVedjHDVD6pOYQI5w)WsMea0(OO?N?z^qR?H{YR*Z@JGbbj zwWM107?dxCGog)`?K70PU+8A?y;|s5w~`N`9!#HdOF+h|Nzb+uYBL#wSYTWU2^ z%NKL_0nOB^i-TUF=pWtTEmFCnlKwN zL(1%5I1+`GuT<0JTEAjVHPOI&zlww!p3-_!t0`vYHe$*a#xyint6tf$3vqsWI#E{vD((a+()oT*S$BCqq$>9&N+!@c@se_HDXF>UWxv-~OBFQqv`*rCB{ ze#EXN7i~!lsU z&iSNTEtYl&yXo+BTN{^(Qv%7!a2s~kr_}WUk)TmeuKALU37ffc3~I) zlTMKSZtT);r^7wiW#3KPLG1Dq5j#4BUG)RYkyg-X<1*UqN5+(H+A#anh-t^1Fw}%Y zU6{!;YQk~dn3*$cSdm1Xqdl0p#z<%ov-sp1HD3=6VR~joOe6c8;i!md!%T>-;hT|K zQg+M<%mm$ZVUET`Ot**|TccWKzL@>yh#AE6&yJWO%=Wk%uKToATO!R$|)4!2>C zudY#xWVjtWW6iYf!mc{MMlB9cD(wEuY1@OHc;U1i#CBaYZHKVE>!xkvnRNao)3yye zJA2x;V>ezwW61nm*nymB+l@VT)wJ!wPW)L7e>6_7ZxFlg+G#t4o$9C&i-pH! z_iiCvE~S{Mx6-&W*pA(ITO`A?)g4q~_55eW`qS~pGy8`)u- z?~DZ7Fv~H+vF+GpcSnLshICI-l;+C%*Sik#%WU`ggJuQteeKOS*xB1hsM}2>y#R`RVHS~wmw-S zc2WA?0lVy}n#kV5jXkifCUXAsVB4RriR?v!!vC2XE`9X)A?&=CY1_y(Y}#`*;-X(m z--d1U)To29Z%jg=>#(UQGHjJcOOLv^KK4F|Ot;ep;>C7|tKtdOH3xz8yRLj9R|;qo?n} zPCB!e+yA=l#vV$o6}JrZ{IMrjk-rQNVh7Wxj|>lC_n%X%*2!>VI_am=95UR7U36|O zPuKMH?AU=d5j)z2op^q&I;A(C8*>6PGhBUa>wncoc7{Rhstaq?aeb(VFbx;c8M5)u zB@{EfkF;TrUtBBKfM`3WZ(Z0s+J%{JuMMAA+?ef{au#_oQ!a^^K}-*(o>O!P({^dZ zH2##(Y14*jyR4S`R@(fuW42<-xGv0;?1$K^{OuI4?>cQ;7)K|3VAZG4W5i^82baSnElp;>T z#tc@+Tf%0H4Kx2%235F|v9oTgRjtx?VW-_rC(A+M#y0=5RyFG3(H`vF`)bueJ@p`_ z@z-H9CWP6A8J>a0^O*3zsa0KajM%UP<+VJ}l|u}>rGgmpCW4f!uW{d~Z zzLilRy@S~P$0PGOggK5`t_MdM&*yypWUbOx$#agzS!qnVhtj zJbRHP=f7xxliJk`u5nFwcPMR$F*y{oby2&xsJd&nWAU6IPW4OM`QxxS9o;@l+{5i~ zo?)FrAEMxN0^b4Zq>f*51L{H+MZ~-XCmBquJB9P3KF67gx5i<#x(MvMzJurG#Mmls z<=)Tp%6ingpLeL@8J?-<4P_;Dv-BetJ37=vAs&{ZIg1{-xkF8kLR8<-TEUWoXe;Va z2WKM6TYZ*t#J-IkoT?DFzNxf5=vZJyOTSZU&x?DS+QaOAiPOO*0%s$zYahY}s_=uFb%lQEH7t3 zk&5VlsY6-&dpzOOy<6h~}FU0K~$|2z~fsyK!9=A%5 zB-Wvv9UaQbKj2}LFlug2;Q7l`#rN=ty;YT!gbtnggM+hT(kMvkA zJBWAwYp>zw6 zL5#6CrN>O&!!m_ven*NYm>Hdns4Hm3u*RU(UIfWOoccgI9%X85aV&~$|Em;^NUvtR z`iG==h*_~mPcGqOsWDTuE!_*9AqnHcpXHyRf9ORvoJEQX&;uWp_xbdwxf*-@$O zl#ca?w&PN4J0KpPFN$sbMhegCUe;l}>c5lXHm0cgMy6;EyV)rzZk3*?h@z#n{FAj;EiBD9&?lx&)g4b6*1xNqc#7+WLBy{4o$A3LIvLd&= z%WD}e&K1$rxbfyrwaKJB^9^;wocd*_IufJTWe~f)v{P+~Ret=IV2Y7c)u{$d%2}`J zW_w+y>eaoYTm+|X?Nnl)cC3hL#2DH}V6?LDS?AdzYVHf2e3Vx!WQ>v0WOa7(v0vTJ z#4g$0$wz;cyJ{V0S%Wvy<+Wb!{!!WkZ}T?7s3X}jf!fs5sn(lO-+fzuIkn*;UO=>O zV0Aj!$wxv7q35-$4>zLgi%zv&w1oPuvhZ~-NrH$XZO6F5Q`u1@(wZL z+P~=UFWL&k$*@x`n~iwuUpPa4&J|bzYWss;wM4{!>^(hxBVwpd#^3gy_7Fd&n9}A( zd$l{3Ra|L};be>Ps^UFL)7JNRYwjJ#iZ};zz~WU~g?QjSCH4}EQ-C;{;8nY#5l_6Q zbhof&sYfhX>{T;_XXpDuJWY$eOloTfm7`LtN}+&Sii67fKN2~~$qKN_t2QxAOqYG2 zZ2F_P97Rk{m*R(-c)F6j#%Z+H6H;})S4|cTefwW|5&2wanx!AL@KP!y61nw5W#w~@ zbFAi@s8x~u=3MVp#e0mV_lK0DKF8_G_;d80 zhY+ummJx%#@^8w)*B$3s#txnq zBB{i8^rS51cnthiCbga-bW$v|g5mI(*NbHxMjZTDCbgfW{JA7WO+z1hm6cv%xwzi> zhfHb9$I77>8HmM*htYD)ujq@yhEL=U`4^nv zX1^jgzMqKEFh54rdI-@lOS$TK$4}#maT+~ErnXi~&Ei2TT_{uAA`8}!IF=+++bL7? zP_HS(T%(>^`t2;z%VcUB_0)>dl2^#oxqEnX=+2X=Z9J^? zr?nq(>N=U+*264Mg^V(4X1@LvZR}fYcQ9w1GOZ1ITJZ&li7uH|+hOXd?buNpZj*_< zua_;VfJ(I7CKDURWB9Ico5_MDY@~Tg!;PjF%#w*Xa$mU3M)WpIptR$N{WFzES2>r* z;p3_dx0y_>A936rZZsl_iz1Q3gW*Qg6N?g6FMCiHET@=_=_BD58_`?LjhMAH++rj8 z3}{E}Y7DoSOv_EZ`Wj_g#yh#q@I0e#28+Rl5&gWDiP-XjOzZX$ebbMY_>xTOu@UWD zX{kpvcxCK|WbB~u+#zFc)k_jThS;!EM(-Y>6U5dl?k)yMw~W72#?L`a-z($yjOhD5 zwDx^6`e!otX2kqAW$eQ;_8?+OpNxG}w!;+S=vy-S+`nsukF(uPGrldO$10z*OvM+V z^}j1)&*Sgd=wk)d{udej!oSP5MNIlYifjI^uT*ZTnfk#i%F3OrZ^jbVw?oo{d+g#J zznEb>>Jgiwl(Tj+{0nfJ_*6O_kWT58*LdU=vD?&~d^ov3mrgXkmQp=Vjfg(>Wg;c> zJ+%9A>2!nMMo}T0QjWi(Z1FkHiB6)(iJ@{HFkbm2Z*JBTq5u0=)Z!@m{@cUi%*^Qn z(J*6&E^hd{z8khqp{7UgP+OyM?fH~*WGpYz{)$eSvqR08iFkiVdxg?kfS9^*hdLs} zZ6VGo@3Ij=9KK76#}WOAB6|I=q`3aSm7}}Z*`Q_qT58Y#x3ch6w0l`CeM# z$&!QEyjhCZ{zKV>qXjLeT54_oV0{=M7sM&I6lZ>>9Fi%v*GX-|XG-jDaw+A!Rxh=k zpD7!6Q|wH{!MQtBdkmF{9o4qw)>6cgMLX1lS%^#ihfV6m&T~>IxNq4G)ky1w|JgX` z$GHVPB<9yb{)&(OqZJSC1!wF~)^~AboNymLXY5diPkXFF8! z!va$+VsXB6X*6w9l)po~&*n_wmqhrK{#^Qeg-`iS&SZ-l)l|4c> z!w%IXdO7M#eF+*v9QeZy9vbSRb_%$kEz{$S5&TUTeyJRMfgg3CWuX~pEYq4V>8Fp_ zO9##Gk=nidB_jQn4r=a8Qr#$2?F4~3__9=Qm5H_^=C@061NDBG1sg4}U24}# z$0@`*uN2pRso&N44Q;kdYU^ZeauCfuh|1H{MrqhWb&yK?q~B_pU^8OQfD~8KkbAgY z6Z}vL%cR#BUQNSNT==Da7XB^G{ST?lm5!N+gI`H8_DiwEFN$gZRthtfKksuaG*Jhe zx`UTCJL*_2+KG~b$v%bm$G?yZ9zMe-?NnCobF7H=VT>Ag5@A&*_rx~Qp(pRu{cFEa zwp`^{Ad)PN79LuX#ke$MYDsSRLjSd!ojMrfgwNi3J(W}}&1JQ8smCQZK9bB7$&_Jg zKC#kg5TEn};d7<<8B9474oh=6GN$L0M2$kHMv|$=$2?E^bW0x>KJJCW=i`U_WN>N5(p=V!X-#RVN6bHCr&?&DebR5lz?ZREOrm6JuiLe|e?z?0Dps+jjCNTaX|6LR%2Lj^%L`O#S<%O!uGY729mY ztcQ21;-z>~CnHB(X892NpWdks2yyjS;xg-8Wqh2gvMEBcS5Z%LYt z?RT6z*Un%{s^Wj2?NoyzmHV}T^DHjJl=Pjd--y`uwZ7^%BKk6R>Q|i$kLg#)LBzfb zq_|BNtrLjD7w=S)#R9ePIJeoNS<7tI)cO*dLe%ZT0jhnm3Z38SK74ewssuSzu&2j%*LVnxDxvYPg~nXm7;uVh}$@CIL=oZ-Viq> zYPepW?NbLtJ)NRm(Wis)?<+GVX}7%}@ypV}u*FPr|U-}OnT<*FjxrhGQ8to$A~HB#No=$m|Mzc^FO{7%_|tHp&_T;$VN>`mXvjUHk-V(Fnq!t?$U%7#9&Pk(^TZ;MYY7OmSe#hE3B-;jFy zM8gx*@*;_dGF-?X?9y)jo@Mc%=WX|?9&s}1{6T4Zi=R3VBKCQ4HX|O@oW;#AYr=z! zqP?`PaNh7E%`?ZDV#z^m?D6rt7}Upp)RM52BbN61)Dh7;AO5I4hPL_<6W;Tw1)>lS zsr<}vsdK3XG3!GLEyO58lrr@ULn!GXT4LD8rI2tnDC_Tbo)(AZ`@2sSzZf+|oust= z*|Bta>I1aS7d|z~F#XTYVI$6dbhl`=yH8Tq9(0`hL@(oJn1IPipPDT?{=yj|;5@6X z4l#O{nkVY8dnSc=%8@ds05xIuE;VBo>bo(0=*<-mp=42X}Y+h8uu_K zi%WL#Lw(#gMk!m~<_B8^LcENM(NLx>QBg|Hla9nWZq!NCMA2lmQIVAW=tI}+QYS^Z zo}Jbw(EZo%Qe9T`?uc$l-9qZW*rg7LX4`F2ws0rT;zF#tlNJ`@yl5r%0;f&+>>bB! ztA~)rdv|g7l92nOqmN^ZWDi%*_4Yw2Zi}Ub_PWK}5u5?v zrA3Um9>tY5UK)ou{+<+9o0To^viU?C_^Z@5nU!ud5!w5Z)b^XBlrbU;vEdUb#?FpX zl3qo8ga-apiq|4)U73TL`wyvZLoLTO4l(U>DIS@vv<;9En)OSmt&F3ZGR^U?rFbvm zSiq4y$NVUha?>s~L0j+RBI7Oxz2Tp`^j`{YiC0b>rD5HOp6_<)uZA3qSGK%|=og+p z>{63Olf=%^#RUtO0gL+W482+ovR%DtK-bs zXvy*6B$bEXbDU{0H!wR+38y$$+4#O=MZ6txBJowVTy*Ebx%8ZPuftl5oSh`)g$Yqg z^F#D9V)GIyZcGUK`jN*^dsVFyNp#~oCVg|ykYem9VPEs_>D3id-f&8k{t^hHb(Iv` zBEAL4C23MVfp7ielmT&IwG`K%D$|W`M^0NK3L9! zsgHAtcS&*PB0WtPqM=AeUn|9C#O96C^WH^bY_5vUyjyy;X^ zItJ5`Md7B7$w6=W(=K&*ma=b%Mc$2_`N}SJP%QFiFHtsL=Uid+BM!Z~i|0*=hEc@-N`VW{_ zC(~X0oIW~_dIa3B^6ul?d-!!dKK2KsPb@xDHzJOqwmc-0o0+VvKSUAwiCDEoL=-!I zYi1KCn0gs=B{7S;8G4BIFG_J4V*fsVgi4J{S|btL@tMH%i8I3qDyS7pv_)>4aQeYd z3Gf-j(tO^>r=Ukq$F)72PE_WTwDR^>m9|eEi zY%6KtV)RAQ=*Oqd_o{N}FctI=ma|)gE#h*;@)Xk(ON+i*FQyiKZqQ-Np&U>wN|HwfsZ3O_Tyv! zMEV?B#Gv!*Ip%*V#rF}lE+?Wr6p5JmG)oPpmSr10+L%Ke|A!QxN2K0~)_T+AbgCZ=|Zh#y9_oxEF5R?Jsr_S4+be1?8Z+^uGch4IiLu?0JQb`pbD zG?+PQceojFYrxXVbV5YdngO-^45=QMg^F)SZCNSvKPr61hfkv2w1?qrk)SsAadKm6 z2`;1s#m>o+^ei(xd$)dOox4~&{b|M4R{c z?w&Gb7j7SyI+N|l=Fg?6KkmdGYN z@-IzTOdZEcMUvXxgJJwi?vt@+GD>fBF0lNO>-=j>TC5?&bZeJ7APR7;IF0xmw$)-C==bp7+%A6N&cE;j zVsXsBO!41K{4b$P?GmT=+9k@i&w1Qlj#xIoOXVwUd|iX&v}-s&YWmVH)h{wx!gO*onw%-#^f*mP-p>_yUMsgIM!M97dAROh zN)G>W>m!}QG~Ws&QHx#=f1{oNVOAw>dOom z%zP3u#hyVycyww(EJGCEiZaba?7zg37Hy}@w)rBaxbY`^vaqy>-=3~TOtcQ8mZ17( ziL#(-G5d)*wj`2g=AQ^mmQjz$s1_G$2C82~J#@OVZME|ps|V44#%uZor$|p*3;R(U zR!H@;aNZNBrK?_3i^bA@IGlHghG;oQ?N=6nBS9GlgonNUEKvshzmCb18PQ6kiIv=Aio5N%dJ& zv9bwQ>m^cD!miDz&6i5`G1UG&x~nl;iVuZd$8c@GT&k5KRk0-u(j4~nqT<>D-$Bu_ zw2I$wx;Pv1a)qS;xdFK$nl`)obftUTab9#D6&lHt?Xf)CjTyQ@BqUB`R$>_PWkRu$ zgp#&%frBhQVP%?my0YnO$9Yi+6fE`T*OV<^@)jQs**D90U)jP1Xh$wX&J*!IvuW|7 zJ;bZOL*%IK**aONu(YDTZ<8Y}6LkpHY9``ARBfcCQabOiMNDmUH{;ZgsYUIEQ7R03H*VOtrB5p-AU*fQ73xlPcpt3)` zruP4YpiY}|Xo4G3LBy%y*VM*S5YJA*{|!f`_Nl=5gdMColdtLTW^P*?c#-<(F zdh9i|O3b@0D_Fa3`E@BpW>z+;^^Exs(S&h`w_+aZbD2yYma`*<}jkT0-fVQZ9Hd> zn$N0inwcurJ@MHi>oB_S$~|h5Hqy?Pw|x>g={LQ#M}Lra09E|9!9-(}T)#&xRqovF zSTe_jj~~+;Pl^Z6j-=R(o?f&^ozT|lb7c7kQO7s#QOiZUtU=Z8FB*3-On$XTtIJieS@jb5_x-m-Lp$lgyKYrj`9^XYD z4eU{~Q;4wqJkkEz&)+*ahP@7UjkD*&lPDH$at-c!wB9rcOz zT%b+*R3&$c-#-~&W1U~ptrnh+e=R{tFF3NIjFfTs@@}PVikA%QaY?(fTOA>1(`Oed zN2i!DgNS{3fhw8fddczMla&0|`&v1P=UpK*L)5Q!ZZr)}XyE&^q)~$*! zLYlT+Owsr^{h`iA`d)j$k&55Q)^7bR%M-*F^|O?tCbe{{tzunyX`Q~5xu{Zod$<1m z7A{0E+ow$rX8*Jq#2lM8Lzw1{aNH=PXo3#fPZi&}#K<8mM|tFJ$CBtA%o5CO`O`Q* z!w)l0tOB*`I1T=WWfh{|Ip0Q%9ocq&$6cP<2K^)Zq+XGTt}W_cW5a^wVmWw zQ?(Vsu8*g7ME3n^`x&@)+LhQDPIi}wrD=Y3d$jIG>-mz^ z@+oRJajyU0ULZ)NYg{;wqiY=>dzpSy#lDw0v)0cK&#&y_BYF9c`E-R)m19$jo_zpkcjH1w?JN(MQnT)X< z4AVxx_{NL4=q$#}*UUu|T%BOGVioIwq6sE6^UC?oc`5yvS;hW;`>>l>T+&}>i9`2` zX}bS17NaUoIf3V#Cnr;pK;ys1u!$Jxesn$%CI&_U<|t;7^2NoNZp@U&h1qePBiV#i zq*+?vAZ9COv2x`pJih5=Fk+R8z3yd~lXazYMLc3khhKFqL|n68EF0R}6@K)*K6+Hl zx!5a}qj6kcq7A)G2}Rd$y;7dG682NRze@F{tE6g2Z8C}w-nVqN?pXF`>jy_ z$jPi-_>N2U`CMI%3W;4{m+Rmy;gH8Ckj{)WA3qR9Wm&$P!+R4 z&SmD-IeXQ7k;&F;WhOox`xZ#`!aPm2>FJIUGOYVw79RkLut`UbYx zRZiPnF}BADnXvCw`^0*A;09%VG%H=wn=CFld-ZP|Z^~CTMYByWKrFjvufFX+nlBr; z9(5{zul^Qw?a#Hd%u)+tsgp!!k?71Dx$+XPQ6rjflj1hSBwmk>JHX`MxL2;J8S|Q2 zIHjmLKkQSzVjHyjW_?+WLk!OEQLBXOXSXVA)7ga#BNm;}qxyw-*rjb_R#^T_Kc3U0 z`b52ZZlk#`rjB;hk~KYiR2y~qFKBPED=0=SJikYO=6Ee?^K*0!;?#vbs=EIz?$DL^;$_NckSdsB(_5Yd8`e2|8WMLSZW z?dIkyiI$gbQIDc}Tp&LLTpo%hJ1q`t!&0DqTNT=FZqU3H<_Kkv~W z*c?LDw(*UqV_)>>k6cvY`)g-%bSaf-__{}aoFlpsa|*LgJ6&0g?=sep^{Atw0gezS zvhB5K0V&-V$j3}anbHur;osia3 z0&2Dhc}#g~j`K`Q2(2qAz;Eu+PL%2eO!x~)BnS8+2ja^6ltb4zm(H;x7TW@9oe($N z7w(5S<>>yDfLgE$y*8p-eCQ+B1yt``^qs#^wk>9r9Yf6jWk78g>&LB|^l5BKdXHxx z_XPCoxY%;##BAr8CJL5P6;S*1^JFS!ALgKD#(RiSS{=~m=+SaHLoEHsE_XnGb7tOV z<%He2AP%kIp@3Q_`eof_?Lkqz?R^&NN2sCbg0{`!_&LbM4FPp(2J(lSl}*XSN6Xq8 z&@c98R_Lpn2XV3~z&A*6+=$5PX6;AxZwu)2Q>kDN`vHsNAT#FKfIhN!^8MwjoGU6t zGZ_CA__qyH0zG7;tm7~Le_b@t@PE+L(fj^`o`dfD54sDz<>kP#f6G`5jebg5PXv8l zSBlOR+lV>F4;VI`G@e)?@7DCYZsQYn_GsJWdBH=~TWP5s#Ss zCZZM5QY}){es413;ZF$=mh#tt>LzE?p=u(C-`XR(5u1cKuSVNhrUYry3B(-4@IO)B z)W4F#hXFNLjHBf>EStQl6Nfmsxt9+tBCf1e7AA@F5TdKHSO2R8t810@Nesh&#Gy~9 zuBg_AS~=OKPz|Agnkf=JgsN=;Qa@w?IR3hRPT%I%=ab@HzM-r-7|XCQU$we;$npQ8^>Un{WB;;Q!b|k%^Uq?mDwq zEf;IzmfwYSs~f%bTv?;T59>>u#gAH2)yvUK6cuMBBPvwMl=na#I#R()gdv%Kl_8+`PmpD z=3%blM|$<|TP)nFtUZ%O0xj*+Uj4^v>$Ymwy;c`u(qWYkJ)xH?+D9{lX7A?`WYry9 zf_%cXi`%b?3vbi9|E24E;HoUo#*cB51DrfZJ0%4LDkcV|B}+<5nx~>Tr6rXG9w;d- zDBVv=H!0cTU2d{+i}u*0vZV4IEM2kbCM)-P%s(6j^(1VZmV2Y+l9DCwn|q}_zwdS5 z_c8f1KA-ZwzRz`E_y51o{oDr~ITSP!SbO14>vS3`w_1d()SY&XHDz32f>p{-EqGdB zJI3#{gDMpkmgO`Mu<){-`s~W5K$+0FQ$C`Dn!MAll(|9TI;+6L7zK-5wNtmUM!r3e z9W-|>bj8e_cDfk7=S6FKJZITp71!_7qr%D;^_hSkVBrl$@s$_J+5h0R=uv8mZ>Me; ztuIFV|6Fk4%{%o^6MXfeRsJYN3(LEe9FXch;TO6h)dMT<*r{jL&;5eEmgRg?0IV(C zsW$-M`Gp#N+^|je81@m0YUYvtS4N8acItCmvFi;jgof^?TqH^5P}NpypgmUMcgz0N03`hPRQT)ESBN%XfuW!gEW5PItS zJM}x6)R&}f$<;dUT6oKkcIt6$)k}KX*bJ<$rTnB&8eg&!KVyp819bg-r=21(D0rD{ zWw0ClF&*Md1ST!1@ntcqZeuTo2jALh??{4oy%Oc_I=FxLPJ53u<(V7QdLW^SbVLpT zM_4aU2wdptL8&IZ)0Rv6o!d7=)74E1{<>4YYASlwWL6=x`cv{C7Tuk%>cPGS=sF&) zYOhk*YCE8q6qJ6k^UNX$t;L9W;`OBV>h1@w_y_rP4sh&iR_28)qdy_ieLK1A2{!w+ zXyHMtzuIX>q^T{6(i&*i*M#AKwnb?(G<`%+kG3bHv>WP=3)+6MTeQ*G_5O`$B?R?- zM5~~xo%o=0M+NO|QYkiWRF%?Q1#I^Q?P(I2yFnk26P9GWPjAqz+8u#zO9|Qz3F@8( zE3t@VeafUS6-_buG@4RV-PzEpi9x$pl69O*q1e##lmT-ygSrcv_qs7!2d%gwsPk(1 z>#FXIX#wV48DtX+{~KSAi`Ixfc*`|Gy?q<|hHyDp=|09QiW`Eu{1(2UJD5?x+#7@T zT8YCmZ>SlVrxsX$Yfv|~6KJYcS~GOpZ9(0^C%*$9)CUj)Js7--v#ezB#(GK>Ip-gzohu2NY^*Ig9G;Qz&T8Wis5~O45bs%O88ND z6W6r;dBLR#^~hzLDfJQ7r73|+-QFJZ^KI&jRQb(~a+GhP)qW*+Z}g*?v{kCO6{rqe zKc)`N@b7|lx~krd(cDa^BHwnr7vv|i^u-;$2NpOInk6%L2IU@Pb(@F4F}a^J6b8w6 zv9Ron1y3csZy!}$a{e&oA>&g*@p0y32ZDACmoD&T#vMT`?*nRWw=DtUeLcuVzrsyecp`p_z2% zo($SG=UP{c<Cc ziD|cImvx%g*6s)z-Z8t(iSs5kpp9|;gEjHkU3QOT?(t!U$iHfQhBKf@EdS$Ciw@0Tn@uijZF6)b&@6AtXNh5tUp}K20K#2a(*Kuhs9OX|B$!e+htd0VD2#Y zXj~Jxa+Rd3@3mb6w$8n@Cm z>IJiL*ZnV%g6AX?`{jJE`pxU(kUZMGOP|7@$~Ups2Chj6VyC@>I%7Jc9^|Y)k$NM0 z$&H#nfAc&S`DmAV9(W{h>7+8`oDYY_BlH!M40vBW@tF5(J;QXIqF_Izw535zcsn{A zLw9^mLzIzh``hX*15z zbuii84eY%MPierL-%(XzQW&3Ai{2kF{z%T}{vX3Be9st^6Mv&#`oyJ^j8os`)~D+N z7mcYy!|}cM?JPzC=d$0PY4;&`&9C3L!dUy|N^c!dX zBuS2bdAUORrM#B>&RY2}nUV{v2oqZ=F8g=-%|r!o$DiKUCA;ePdM9}l(0}xOTYf^x zId;3AV~2rTPP}i+Z%#P3x9IIFW!wclYCe-5tB_ByGlSH4#Kl+dk>lZNq7X*zpRq^%Hi%3dB!M;8?2$!H(`W9HpU05R1`hv@ zh)E%sB&pL+?^I){Ck*W0K~iOqm>DEjqwkPBju9hb()aDQ7fW0ld87{6z7T+D*rU z*^d>xM16tgNk3;q%-VnM)-NDp_woYdwFOz$mK$Yribr#ud+bve;K}0AH}CG7d35R$ zGE3^}NBh()n^y+Vn)E$(hS24$x^MBuk}ucpv3KMG-67Qu<>hiAy#9$jc8plxet_vW zFPHgc$q_NdYq+oSCf<96P|5%K9($>ZfKf?kL1jhb9=k8j`r>8``5Yr+R&U#5H;L9V z(UPMHKH}27A44~bAyhnFd+f!dQ7JGg2_aN6diL10`gQl1!gC4x)E@how4hlBRBz@F zOm%}D&b@ZEbgrw~RLi);y6E(RL{ErEG0A)N++ub+U92pP`=Lo0d+o4<_Eo#;J*IO$ zW8{dK=4k9gHM zl5(tS?~vZ32_A-*#p!qZ-N-RDd*#k8^{zifBK70Fw#Ph|#P+V;Yo9t-Kd(jJ@^kDu zl^hpDu6lW|RbCLdGC@-0e`Bw`jVzag1X)BZ{Hwk8F=MO@x#l-}*(y_>MEBKK` zg8z80?KA!($fci=HuK!;BnSV2{zz@#hn#h4uf0OsbB7YJZ|QCfQL zJ~gY0_QTQ*rzBF`Blq#+1t_0BY^`LweM})R$+^#7dZB_+cIwm1I(Yu2MtS!KG~zAM z^J5_%6{qd9(=Nix?hp9c#K1Li!T1p|K2NJvJ|{3Pp$DOFbgTTJ%wO(gDN@D{wsz<2 zvkRpM+1g?DiR4#YXYbQLD7mE5w6qZPD0HdR$>p8ued{P#+HFR2#-FUrM7H|Q!}sm` z>>U1a&ia#HXM2jFo5r;2{(l}+4sCmCphwZ2Cb}!3YWdzQbk07rPxU8#9;X|4>P`bc z{gd8N@{XdB-Mx>)C=%A6_3JA?usyKPE|XcdyUSX+k5BGkj`DrxeM-a}k7|Nue`lY* zqoFHeCGyJ169Mj7zRzAOqtdbuRok0dm|R>@Y+!!mVt2VZ^F5yYmyu6NNu%yB?IignHRi0(3Z?r z{q6GkG$Xa8I2y}S44it5UVi`6d{O~zx}w!SDv2mKruQx?fW=p~>Wi13!N2-I57>T{ zfg8oYdg<-XEd#r-DlgYvV`w)sTDi1`puRe$zpe5CeV&m1skqd? zn>A4-bnUgR{GK$bbA;0Kxf`I)>ss~8##MjU1|q->d9C{M>L z)d$QO9pV?yfHtc79X&L3bE~~g=+w{j`xCFU)h3?!Z*8@Y$?$p)Pvl6tyBpendn>=d z23_@;s)(KxFU|dqR{cxPZ=$MRa{Hm3^IG*Siyfco*L5)On2_EFIr*8c+zr6q!dAUG zH}$w4-6O!d`&#vnNn6KFi*a25^@j8-#Kz<5uv$V7nb2O+DnIz}#rs?~f{ye4R&Guw zio5ZtK5i8FfPo#yqvh8mcwsBQ9fR(t=&G~Qz=)&m!JL?y6S&mV1oteaxP&jl zh>8TTAE;us9H=7!?S0tLXP|N_*poh%&h3#_e!&U@7L=FD8J=ROr=nHwbZr(YA9(`3 zkCF;0zxO0+svb9i)0edBPo}%jjr^S14lwIGt@^hlzv8+HIWFi(V&d}uTJ2($;?Gr+ z8J!KRT4tg(<8!R453-<3D_ixikKZg*eTf7uecb5Y^SMsg=q7046DG2YM3;Cad7$%` zx7zs<+vSGx!;s(=-!-v){&ThOJL)1jsg)+Oo4Kh&B3lS-s4|gl(~@z#W3F{jo{bdtc~e^#hyNm}Gs#g*F`N z@nj`4nADnDWaGd14U7UqKQYjK!X%&yy6st$tW-^vYSVM3w5CQ?L#WoTHEEp%?U$$m zn}0?QO8kp}Dy=D0)opds457=R{-3gs3q1Nlt6i$9<_R6uDxk+Q;cwMJUE~Hj)|sg8 z){x`A&|au2mJX=;G!J;}MWgzusBR)sm(Uf`m&Qn>z5+^CkM=_we$lFbuYD39z*at#wS0QL_y$S1SsEPnE<0Yf|d{i~%(h)JPmkr$r^~*pgnNc0>hi>_$sRU0;3{=TLODP$z43p3Q!;}oLveBrv zMZ*d~7dIKRA3;^g0O$Y8sGf+bri^1Od&^K8s!9f!x7ql2e`yk10iCwRBsLYQN(Pwn zYXhf7Ra>CWw~c{WP*pO(Q$SVTbE2xQ@$}H|7+L~VB?D}4HvX4<87&#;j^7y7RYFzC zK%0JR=yS&G=qBj8t)_LnBD$*Ags$CY=w?I5diueue`id*hY2ahc*)w|x5_WG{fnPW zb|MyTXFj1uEO+GuiW5;CPh9n-+6Wla0PK6WRlo8S^JiVE9bZTCeY?bfI!`NE6hdsW z_Q$e!*^M~&{Z@XbQNCyz#Q+;bYL_ZB2kV?xPR$~g6?GRw@V$E&lGh4sZ z^O=;(m}&iqa+M%XeyKK_JcYodE^=QgwvB)F-9int|3g%T-h9$J{g@oSCw1LNTX{<_ zCGSMa|0}aeT_pYZXhA$G@xVvXBY|-l5p*g(rk6b{)3PMfCZWun&ml3HeKI<~gw~+l zt1<>ES>S1a`aUu9%V(f+#y_rx1a==YdC-qa-rr5@ehwAYx|wICeUnV!a6S!whfFhVa)7Uz)$O~ZyLmG03o}m7>eH2b ztj9H(nfwW3Weyt^>c>ui>Agm`NvtS$G7$>)@wkiSyC_P*%K7bbB+&v}^H9<8z+m zdM3FKp$`-FH;BbY^8!huQRzjRCMq+(l2&@D+>HZ1mLJk5S>F6gRk(yIQds(MI}-}6@+;6gX@bs>HBW#QLUFFBPSgjT*9 zvVF3%H1%I3lrMbU{m>0>hwOSeOtIXyGRFokA2pSV_#Reecdf(L+sYNd)!~pmSGJWu z9pSY6o45dv6l{2?ooSHu?0z;(tB}_%YPZ8N)>9AhB^-X{o(So6Y@EYsX7wr47@)ok z@mp<}n$GT%ny2}oEq$gWOQ7n|OC_}StB^i(^IViRKv(~tq3=a$7`pcBkX?2uc27W6 z9yzY0J5Szk%cdN6BWb(tY-rhp{kC5=52iY;#3$ID@e<$a$@}dzJ_z>nqm$W2PPab1 zg+sCp_^IJ>o>*GqBnu>8!_aA0?YED~j={%JwW;g6iq<)MzrJJp`2?qxdnH@@z{@k!fDL~zaLEOxDBM-x#XAgs^8%~!AZI#YIXn03 z+Wry#)yIbs=!SiSCGBM4h0x2HMrV_^2Z$tHg7cLNt(nbuho!X{?_HwEo9!_b(A7tb z_mZ*HSN*H-;HEzt1MA0HrsU%mPDnbwMK=BSe!Yb>E6J%wDo-}l zcWl2t1>6di?SnC8&<+1fXtL8V>0${@dYRGSmec$76k)l-2QCSuy1^;u9I)q0eeb&1 zX*Dh3P#WpY9eaRlE%b*~-N^aL2kaChdx>Or>H&Gbb^T*}hlQ9v;efrzJg!7;nRI|# z?6vm>#Yar)I1=v~Ck$c4!5_Z_e|nYh#-=a+nAt{J(r zOqo-W=|*1h$T#-9Gbo9r%AQI(V$ko3(5^x5Z?QY74}n$Un&7dMA!RDR51)9SM5C@HxfvU+%xIG zLKLV}phhZCZgwDTOeJ*j;RAM9=p1=zrB4eq!5v+OFIW68jZ_x!hW|cbd!=uEs zT*CUy@ZE~v{wvhM^S>n1#QKSE)NA3r|1^B;MbS__LHOzsZFZWNpT&(i`kS!Rav>#; zmd3Z)tFPwKqKmAe>Ht4}cO3)3tTuin9(Xv#YOJO|sR8ER(54SBA6IaqH=V}V!h_(q z+syg%OXwNc0CWRu^4s+KehpCdyRPf$vu|zFW5}COnE`rop~voQvzN-aP;@D6@P8TI zfEj@{yGQzfqEtql<80_OKqC*d**RY5(@@m`Mua{=BE~`!$2rwkE~CA(7~Gz1(=+!I ze%3Z*)=??G;W@G;|M7U$wW#mt92v!U$=cM$=YHS( z$y75aUVho8PjWw>PBs^Eo)z7;@0#t<5C`#tl8j?(N%M4AGB<1n_Vdx@1CeT z;&f8CXJ;xWX2&g5Li`5C-4x3t-(WN_J@Ze@NqaCtl`l{+zWjy38t z2LG%Z=*oAs=>aHqB7wPBD@gu?THE-t@4CwaN%2VDP@5fb=tEr1_{lriW+zDt_>C7A5zF|bP5Ke}Q5R1wTD5;~(}RqS zU%95*4LsV@roS|qfLHZ~s|Q-x+h*^P@#yA>QjgUnCVe(D@sn-(ZsUb$t3kIA+Wb|U zK9cuLl-59NPE*WcqcKXGp&2$UL26Z-geRZNcSDn6+x3CzlSVf_NMb90)-K}_h7mxgjhT0$0)%YM6^p;ODn$n&?h%h;lx*CL;4Y3E3smL-in z|3&tg=aRU--6YP)lCGXmyWMGIKXToncKawl)F9ziA^SSo?JD!U33+X#otsHj{Yr=+ zxBRu;ZZJP2E0d4{1CxPj&&dy+8>N|0t{b^{6dh=k&4fknT5!>%d>Rpu zI(_C(qR@l(DU6W3#vj=I5^;~$`ATB!{g>VB%tn1~EAA=%_0Q}+zRQ{c_R@ND>oL0qy`3a1vHq}LcN zM4}EcTdL?-BB4He0Ir*JP=7zT5-2k&Ps;7I%)1XVBSm#8#p++esuY-i-$DIB;VVE? z6^yz6pdFU}X&${Ccj2cc6q5;C7U7>xWzK>NS5+Z5A)lRDlF~Z(x?y+|yk;04gfAV$ zCDXI!(2>Gb>w89eN&ddMm%%E}2qd`CaXoTSFZbS&n95jC19d)X=!qz8hB}rSnn`~r zy6$dh%rZk4O|sViF)-dUm-+GICghEDqx$VqE_l-lgWJS_eB=R~yVAhZXLM`9r=B!; zQU(KsrFAz{AJq3P&&!C~ji9^wX`{OeU3FpZ9rRm2qzt8C8_(!wfqPdQ-41k%Gk7Zt z+_dJPy+X!<*vZjc5Y=Z5Er`-)XwJ_Jecn)aH?;Z%L%SyHT)2}OyUqkP;qqu~bHSDC z4W4tk$pv7_%LcAIqgx9OZZP;wbX6_@t2P>V_>67@oc@NvHo7Vo=FxaJ8JL+FjYAf= zveDpsGR=||nDUl^PoL4P0tdGkycyl53&}BH#XAS}S1?^b^_C?Jt^KW0P2|!SUGDwh z?B5;KUun(AqQB=hSWhAInC(V);Tc^&xb|IxpF_9m=UO-Wj|Of(qg#(|WT(NOq8q~Q zC}7R|2A)5~TKO(ZWLVZ-!)8sP`;m%w7h`>^f#p-8kACSMV?8v&>M$>5u>(8c4vo4oC!qmW9v4CucokdzT2zgGN(E=sjn z{l9Gf@uBTKN|lxl=ov9_BUg-aO3F1#>~tU0KWq2i6;`5LRMZ5l`{ba0HPfo0CjvbB zw}bkNt`2Od^}FjHGU&5|cAr>2O`P?FDxr^zJNCsv_Rg)x9_M%!YNfqcl+!aOm74n4 zp$VS-fAnO+UtxDg?O=36`B+vj1q!C=pgi9B^dfPG?50c5T>=epAl?mJk$y-YYIx-; zU7b8t(4>q*dbZpKRW%P-nR!TGDH}H(_-Eelg`tI057`;gf-|R^Opli=D7=cmtn;4W zy+atW6EWXQ7+iN_W999mTi@PpTj#a|AUA0O%z?2Qop=X4~;xx=ueT@wALbEr7{6r#tqfR6KJ^3MZp6e_oI`Jh#ssSQ|ketM0rPVP!*`_@BtL_%AC zty=oIVU@cN>1!1_W->RC`^JIQ`wr=kKTiW)Te+YkK>cn%WUrNazcAO76lq=h!6CUx zlUm{_MrRYEx|CvBE}I)~Etu>i;#q$^#19>*_gfW+dk}Xh(bJ8W>i;HE(yU{zb6WKi z_+4LD39aOlL-t}>p-+WMvJ(36TGme$WpN@mCUQ%SBO{&29{rk1KBxz%#Y87OA`=Vi zdQv7A#s{Izj>9@Q_bd}!4|H+dVS8>Wx-+3FxUgiyWrw*F?5yA%#5a_6c);;p>2NAa zsUPru$=vBTP`+}@Uf{S|rnjfU1iy-$*n zQXNxo()(Ea-XY7C9~{=7Ha-KDN;;+=n!Wb0T`Zl))|;i8tMz&ILS~5;=@x!ZK6%C` zxfxz!UjOppA=@QYXg9-MWQ%j`Ewp=9&Tin^R}SkV45>g>e}Sd15)09s1(f|@cNqor z+F`xYm(YrEt2wg4zp|j&7W-jq(4XiaJ8bIb*t`~;~m7i>9-V*e)XG$ z*o&C0ucAeAY$g8sDq5rzq-=8)E#frwP~A-1gqV+5tgfQH0jUP5P~x!I{0gRtkC%UY zc)pG2G7*mciQ7Sn!tl}&)`3`ROBS;0cZcm36`zqv-M>3*o&H1MVkhp5-yh~BwZ0e^ zu^zG6T#So2ZTn$yJawX##Dh-DP&LHj>7{+b%|-V z;j%c1{t5TPeZ%ON87?}}KXF$XJ7@P9!t3BUI}TrE(`e58$%7^yWD&sGh9rxE@C9QxU=E4@Uz2`x>1jjYIv=*tk#>Y z(~UCH03+{H*`)WCrXu6}NGz;N;^$?X__!hcVKny9;AJFu1r61Qxyaw7E&_>FyJ`u! z$bBD@5VK`bf!z5qc3tX|l7xEXm|k*zg!NQO;L?O3axZc}-!6|~OQa9E2)6nA5WW1H!fa?hxkfHTq9;M>k%6e7AR1Xe zN`<$Cd5vWK>;DB(Mc;nYDrLfWlid!2j`o9gyHiUq_R>CO@hWEYQH?Y9IR zSM;H{IzWogsscXT#rRkOpD$s)Ntp6iX8riaz&PvUErHRV1{7A8hV^%In+q7o&-_+T zm`BY&4(nH8ZQ@s*PWN~pBR79Ws#Hz!Q&aZx*2xF;|D2+b_q^NvqOI=KtAV>VhV4Fi zzx2v&%$xY^VN4LZV;lJ?ecAEbMO%IL-VfjMe%Q_z+neVI*B$v1D&m2#o_!_Gr5BB7 z6QB&*e>iMsGdXuoh3eZxplP3z&tl{GJGAbYFf{TH@{XqM+2 zjLhZpgg?dGGAD`ep7jBfh}%*ElRQ;uRp)=8&k)SJi^T=+3EWN4V{<>yv5mW1H>3zK z=B^L)mU;QzW&+^&4%u_}2YMd(JhaKl56^6PmCGJ-dDK$$ft{^N^&ayIp%S|7fe-Y& z^*N~eVd^Gm#X}$Hn*7l{R^o4{vfaQQ&k;TFESyh*p(UPB1 zc2|-%q&f+45?0iy?n>yi%pY9QC^0soYWcxTmf7xaQS>|&Fa9# z@vu%$!R3OlTO^l*(d?l4 z?9*>ypFV3jlXE<)PEfK@-p{*%wO1cecNRGtfpU%ZNYc}EJ!L7sHCT+$^VgNUl{hcL z@hhZtH&8&<6uD3zsU4}zy6rDo@_t*MshL8AhkhmgAkouLRq8CBTyGcS(h8!!%G(^%Or)R%MCLpCrWpBJo zSN1|wcI2N)ZY84Q77^7)pWS!~-+Dw}>bU4G>G|YF6Hm%Y3i1xBmsEz`^mTH)*ooh? zyQp1yjg|6UbP#K-{q};ikw`sv9kGtT%PhDB@1gle^mpbf@3NBL3rrr@fJU%vV2_hd zMQMQ_g?H*NO1s7EgY-2jlmr(sOnQjQGQxWI!$9g~h>=CQ-s4yONw-yBMc=ach(15n zdY9_9;%iXOC_ln2bW&+O{phSlR0H8=5~bejWj)Do^XL(KsU)>cWkKL7UZI1JEj^-N zkscT2!z_&aBy7Vn@?Q_s=OOkW>JHGl_SAxlL~^vecIrUv8z5q5dS|k(0#Wt zJGu#+^CN?28k{7CyVo4i%iKj#WlukN-LpnnhB>vn$lAyEQv=^Sqw5FvK5y`Gbk*)6 zu;J$>5o4tnQ{O_=gZ(cW-Pv?`vb%U5@YH&vyTtn5yMbgkXv51!Z#{ZybMgCle$~L; zXKdzzPi-{#qzpH*5eaN~!@yMO#Uy-pEqLyK8qAQe{l5a2oY&uI!16PC5%e~_W$;GE zoSo5+H_@e;p!0#A|KF?ne=T3Q=*;~+P#olKX1PQt2eFLW67cKS*^vd=c zTqIZ>R`5yw99hYS&4phJJ#@rq=^pE+8I zPEKhDFMO@HiWXcNA4cvI*}Co1K-#GPpjqADVYf(ISa`41xCgUYBq_J7!;WY#afQge zWgXUO9=b#L*z{nBJ|8msUfqEcdr8LxDq=V?WmYz|n zL@66_k1Ugxp(ML1qnn_?>JGhQ5F5?TxElQC|DeOl+{dNR4G4ul=oqjll}^(23`y?7*axu2bKaJpThfDU;wsZ2t#g(52qWDZeu0 zejcyYBVr9=1y;>Ey8-bi;#xI%Nbs(v6+GQx*T-2eZw;hazn{Gz!R-S^eoR&qxO4Zt zR_0%rdsP5EUv}7x8tgmXt2c)V$%C9Vlw+**)TitKBhG!cgM%Xa1M>#tv==(;%5znT zCWMeHe$l~2EY?$n^o@v{Uh3c-lJ&*6S=3ehh%L1ZgeyTzC!gh$z)`^dSFs_Hp$(|W zv;cFWks*esySQ1tflT$h)?pRw4_uTGM3{fFgRd#AOI@-EMfSedA=_AzODf@|8$0-H zPUl)S$qP1g$l$`6c_&iV>m3Y+zbfL|qV~V@EqUn2j5lwPR;em+QfD`_Q7PWu>X4sT zl9Trl#JtTN97&$?7e0~muVFTF%H$dImz6)_G%C#be};|KQID6DH{frDD$@8`#L6vX zjGAdrZbHocHBZTcn9_lpF*3Cb@w|@boXD3@b887T8p38X*{uZjqSGzexSI)?yk;I< z4{dt8L!T<|kiKmH-#F9^t$l}L6x~mu`uM9GT-e;fX;|Ar)^;j@)u{DjG@!WO5`9N7QyrV;mAGY=7|7L?ZQA*oK)8G3S`qZS@SmikH%GRGb_3fOsw zo=)Hi-RmUyiFtas!`^U?b^9&UKFNrNBOP3RrfPmdH=e=~YAf4j(y#yFrUh{cEhrWK zrNf>UYsr11@rY%AB|+y{m(E^rp~t_Lq;z+1KNA7D@6+?2QB}|t|1{NWg7wP-fy_~$ zZP7H(yiczIdw^A+&@D*z%u{0otCBI^pVFC}rVo-G@B*-2#k>9Rh7p~*^{=^4)nqrU z`y9hI5&^Xb(*jL*7`i=5`=Dj#8hY5!FPSP6tI*VB4cr}PaBPt=Tn|l;H#FJM zQDJCVf}zu`eXW7Z6Iw`HLt>}&h+n+R3MKn_+K0>NOfWvjR6xV$b?RTcpIH=5s;2>- z?lIaoM?;T5%SIboqUmIJ9RZCoaJf-+`=QwQj zI|5g@(o>DR$Y{B%&?-wabXBp{cz{H~8pauBMKycG-grYd7hB1lfhmdU=?3iPW_3F2 zco%Wm@R1C$Q}zYMPL|Y_PV5}ApIm1#V!#Wfn!Z^~E0!Nsi${AMG=?3=&jS~_BWUGM z`zCTT2_Ykh()`PYn#^LhUItetR}pLVV@M8Sy%sv(dUUQ_AdS)BOzwJ_ z=wE5V`N*WC2A@@vI=MnohU2&f#F|N+RzW0iQG5`gnP)lbCzjkVvc5o4AxnO#Lp?4c z@5|^MuyrHDekIza@Ir~gaubCy_0Sd3C~PJ}%ywEBUO2ha4vO~J1?Cm6;}4+ zzRgfshK~ZC0;-Yx%>~w)57{g(22Q)G)254Kvky)6UL}_Vd$NY+VFTJJaFvpsXiJyt z4ngywY7c1p0zFjs0n?|O&^i{V-p8G_p6(sZ8j05lqQDFz!68Y@?v$@BnEzd@M%^)0 zXr_OwlcUgRP7g%W>u!dp<(S-AQevI|5l14sfyK9U+GS$4(faXU0v9K=U^V5MPHrt! z+ZCg->&fnGJM}A}XROQ7aTmk#@uzZRV~Mq92Y155deKw2K5s9Hb`S0leD1AA_nlJf z^aqUTFHw043~Mb_Y4qd*H_htQuZcb`)r%1~Fy;nRAk*(>)g!-@O0+$|2J1Gy%WyZL zQzxRNBJqAJ@vnSD5C(d_O`j$Ml6X|FCS5NRNnfX(C#vhA>Vrq1^Ttj)SK!wBX)|*A z%neO}&KG)E3~-`slH`UTO7hP9N#(0YI~Tqdx3lAZtF@hMf;GUl2y;I`!{O|)z$B7h zEpQf4nUzfHM>PW){S&jLQbS^B&N-R|i~;-EH`CmSa~Pi)(=< z`8%2KLsvq3j;iyDA(*P;7Oeg)>i7nxu)t|jZJv8TEkZ`;0+WiP30O$Rs7YH2Nocyg zlPj_IKfu%vsS~Np+JBtiKq*E{nbT?eqREg{@Lv#H`EYflBXuE}aRDa^fKCGFljv;( zs*{(m5|w$K_A!C)0aZ%;(E36X>n`!n550{7HUWD@^)SEMaEys}J+K&~dn74|Wn5$z zm}sSa5^%)TkQ=#oby}I9P(k`o3kC2i4LG$-HQ;fR(Qw|~Ip9sNyf4aqjrLdCX`d41 z*=16>|0PSV6cVrveZT%)np)IS9xx?SQl@+EN_3jgDYL$w!>ptZu@{l4E0s5{88QE! zPOIo|fs5`9BlP2c8bL9-eY~; z#sQN$)N9J9Ws-^sDivzsSczKIgA{|_-Rwba{zGK7sLeyo`g#xdM5Hv(zb>NR6};$- zZ;u~dwwOF1K<7#_vg+i5i$()i162>POexE}aZD3@&%?&{nlnb+5qSF}CMB5_E3 zPLEJ-jC7RgiC8W$38(CrK`GOxiWZE&P|Dl&1~uiePJRF5O!Z8aw`9#W_<6V%Pxe#-yVrK=3r@-hI`u^$$q!kr#{(DL;Uiz>f4_6UNfU{5F?{YYyb_*2h)ZN^;WcnQ$%t=4 ztVP_Qw*W$jt{*Ts=nwr8dXOE+8OZwsW1ZxLJf5bsAFldOIut~8U+ka^m9Xl0zT&5y zc7-H#&A^1p^A?^5d0r{cpBehRmf*^M*2!I&YQJ8}&rA7iQNOt8PWdIH2%?%<&3?#Q z`8hWo`haWeq9rdT)lJCpWNGiu8HM;_R;|*c$kx;K#HvO8tr5Icy=-b-!O)oW^SnO# z{N{nrrB;Tp*D24rzUqwymyPx}QUPD5tCf_UkG|fBhi-erG~1~Usrgb|A(>FIoolPU zpyGznXn&IoCgM)QF@tjxeZyw*L9A_tR?KBxnhjmLh1?hVj)d_c3omyu*zxO5`>5cp z1i};~9@Ye7v+clVyj#5ZlR#oTNveBW26yXW>_g14ej-bM*RLq)cTCYehZW{k zo^0S;;A%1bJn>LJ_FfF#0u4#^->6b`iM2x(CvJURT3b-b5Rs2O-F3Qy}| z^F)9RzomSnX--(A(;XKiH@sv``9FBy-Gfm12l^`O!vfZq#cxsf+D%?&E|P+ll8yI~ z)Ges>Sub73HhU#v<-2MeVo({~jjs)eDs6b z;l>X+N)d^W_%-U{P?=W=-GERebRCZM7m?9HXq~7C%{fJUFNS(K=8=bRTBtabg)*q9 z6#UERCMTARbIXyCX{Wl>wxna+{nkdFCI$gX)L=*4{nlZCt0^X;t3wa#MpYfsY^sBQ zM8wLpF&D-$PaJjUM68wKIE7gj)-+q94(FrHH88{H}b;ll8LU2 zktTp2m*@aqSX<(Z-7_-s!g{oPamp%1&583(agi5}1N(s#?zlL)+;P4WVFa`ZhpLzj z&{GI&g!;#?d8?9XN`d#LveUxFLkhb4n&A&rgZycOy59^2kqgN>ivoA&5db z3W@#k5%qfmj%5q1_2-malAN9xv8B<_-aNM$A3gZUNsL&B@ey0)B0}P*I4@#Nh{cgT zDqqRTP~;&n&^Zc#i3egB~(RMki{!%`yAI@_&Ts$YAM`A=-b=WnAmJ98KQjFu`!q9$%?Lzx-v_4caIWCKj z3{ujJ$3g@z!puuc#$S!wl{U0t*BL%Ir<&kS@%t00DF|73rWvU0JX2HP=_nl@MI5rn zk*_#b^^A)Q*tZkYg>)#s*#iqicm+HUo^31_m=;_EFCN4td+XsV;AJ#gYJT2J&X?nE zIPa2k?*7Y%X66!Oz2Yv3&usQZ)cn!$CO<>>jpFjCo~q~=tGtm|yU9;4m)7pl0xkb0 z1_FjqPd6&*H|aX!kkg=BP6fP);<*-mQ9I7~JEs}JYt*DcN>!5Ng|yOuj1%5%^i8tU zB-vuLAD%76_c}33znCH*gf%CrO1S%pU3msQm)x&Qx!NA4K@R(NYvJgUi4*$B^}z#B zu2>ik7sV5|TaBYjE=hEyN4RYT(0aRdcr;^-Cxh~mPVkM}t;8{uw~Z)bI0K$rs?i?kbbQ>-^ky zh5shPTPBWnKRuPG^r2EGM%oIj)(c9e#BSlqX;Epwk(gIX{kfFi6YxjWE}G*J4n1!< zuQbW3xUj?(dkh`oGcj?~^oTkX?HFHRHC{+uyx)qbDZXP=f%P#Ov9(uYZfwaE*IZ1g z(Z7T5ETW@7H<>VL_wh*00N%OPDj!SsmI4M>h+rBuo^UhAQ>Ab(#w~-Erw*YwYCLs- z@fIFQxXSqHTV#4cPis8J)s5rTzoZ1}DnxBs3>mVDbLrDAW*py<#2ATTt5tkqMhDl7 zFNv^HPCQH55m!8(`2c!qpsPX1NAK)(Nc*XWOLWhkzDV_HhD+2KNSK`CP#vgaf{r6i zm8qQxR+{OprrG&WSc*1Ho|S|4&lCzOnWb#BAc*Cn&*%@kwJ>CO>4!_GiIY%DCqhjG zCh?WPqGM1ld=pAcj#%GlC96Ot!9nOU9Ij5h<>Slo+)d7(pI_pgAT}bXo*KqpAG{Br zU1B2VHX7I8S<X`}~d8cF|vY zyBUnrFC*Cqw8!!8iDV<1s?f&r@sujzxt9>oVpNL0L!Cms47aLNK7{#E{f&HrrSz*q z%ziM+$8Bx1HA9)RH8tDYe9v z-Y|@M1?pl(sXu*|x-&IpGBsn67Ya8f8;&U}IgR9P!y%P$QVkSgKpskb#7Z+fNqVM^ z8>}_>O0J(XaJDFByCt|eG)*zP1&5lxX7gQ1148mRD&ji4sdhj4hHob3&g2&G;G(O? z-!}ZoI>Y1Bg6^w!<(=JERq&`OYWCGUtBY`A_e4YYWzy3l&_PXf5hoq`L@cOf!P4<1 z&gAegp*P{L-Gm+&Hp0vhH4=9)YCWC&kvJw!AWM2MlSDR1+mvOFWJwtcaH{}?*rQQz z%}@g6#!9?7=MMGOhXUN{LLo5?g$&92?_O^urei1R4xKA;l~Wj>w4kZ#%$`c?MM%C3tCjPHCb|*@xNi5jm*Q3nD<47?9#p*C zxe~8&Gx~s@y9Q3Sr3$&|O_Jb)t5Z7Mdzb1;>9bK7QdB6wt%6C!dIt`bmS*T4g!Mw( zaj?=Im+H8ZV#P)t0ZMV-Zn823?!8;J?Qy9-g!H?I#-tdYhLUO>HO2?il8G)S+J#tj z6kO}HdY!cTo*$PwJ>nsYM~mgrBpz+KuGDKC&7hyGz|L{J##Z7eUr5vnuOhRC3AF;g z0wuLKQHM~2uyQg*jzib4f@`csKy1}LCUV~ClmfzO=!AxQ2IiSmgfMo5tLoXBBh_dQrFL67vndqQ@HkaC(0&fxPzaS_dLIfc* zlex@_d#NJgbLR{;=&MW8;u?7Dx{tvolbDD@tq1#{PJ}L@={Q*SQ(E7mwC)=kUNJlk zrOc_aubIVYmxtC`31`>UR%2Gl#PhKilZ)EA=!2KkgDJ7S5=vIdl;mkeLk;I%O{o?U zdaDfE2y+n%rbwO@n*pa8D#Ci9b>fh{ImZl5Sxz&;6c1fR`B11uJM#)-Z02sf)j>Bw zS3(Q6;mu35qw@%Hhf!!AhWEg?zy~)N2O|#LI*!3)EDta!Mdd@GLEM!kF< z%exz%chx069zJZPPAeH5yLJI}RJI)|v9tl9Xc`f2!l9aI(9lMqTc9c#-fJ0l5SX5i zABkK1saZ-l>U9guKr@NkCcfE!szq-bkIv3{Nqqyn8UJgpBm{A=0mK3yx!96O_Fzr&QWn$_N)tQ+Pcl5Z{T3XCOP&=Q?#JzTXPVR6(Dp!* zm6coKjC18OU5tj8jgS%;8lE5Sg%1v|Y#1)#^%I`xtMJAS2(Jk*(*mX&4kP3sY@bf5 z^KdY>u%Nw;7$YQR%f20E&dykIm!YtD5SI+Ef|ucOAs#2x4~nnED;EXfa%RHOb%oW4 zV!?)zp$T(bPtgyjrrgg-R6QR?!^xSa7c$q$9~{Harctly-EZ zDP;Vr1xBA%vbqQ6b~c4;zv9cU*&CvM>>&4q* zyqz7mxcgA3M4?N()rh8a^uF1Y1VZMuB@<_^9TYc7OAQLOgSgb*6!>a*HEzeE$<`VS zOy~rh-7H113`OCpnrBXyYCdj`*GHf6&_HDgE$iQK-!NPfRjj#QF4Z7}2N@Nmdd-#6 zsvtsWkdlNPG5qY@7TyOB4x{h7aVVGMHW+bKaXX&j3Ns8$$XPTnCq=OmMd2#j z3nuAoPrr$7XYoK~2`%^E@WNquI{Fow>uj$>$R1==l$tcx*&as78l)s4_ZU7n+Z{L4 z{D#p_8HP)8o3SJMD%&$J8$R1}uP<>W=b?3WZc9|Fuu8tjx?x;u1H$}alv?10D6uEO z`U9Z?q4j!J*bNU4%+hR3iWT9W5fs#{iM$N2FUgouoKIkn3|&!F!fW7XHy(*tt>)Is zr=^J_oO*6ReZUM+Lcd16@wpqXT_N>??1@$D@ohD8yFb$ZTg1 zAPDV8`|PwzjujiOa_m>*t=1b@`Gp^2`Xk;uaj0AY zJF;YG973pfqSg9WS4p#foiKIOUrhuV*I+^OmDC{^q4LTD2zGm9u~+?#M0luG}G&^%1KTHsqyQXzFC zv?H|MLP#MTDx~arnkL_Bs0yhD+KEcJ&~C9HuZhFZ+9#-xLO0;h)2c#R6vCRDh!yTV zxYgE8WmG7jGwFU}V8%&hY(@cYtrvx9%ZJvbJ`}Q+Qxqt~=HZZPo9?@dS}=@uF&rf| zkXpry*#{~0Q`y$xuiTG;W-%Zo97b^u!ggqK5FcmPKZ%(4Zki|x6#K;KNh=1%+>1gX z3WK?LtkB#nSrNP|u<{n0*0?=&Mv@pP{B&q7(@Va5RB(KRBl{WzyVT3y3GtIPa2$o{DJTpsOP^L4GSU>oJ$Ni|loA&N*D%)W;SQA4 z!X=0hBXOBWT%bctIugFK35AG`sb%)1D>9fdTY)UW93x(0<#6gb8) zG5Odq7J?{rqd+G;(dAgFmwAp^Znl6D7%+S9Vj2_!K0D(jD7A21fD0#fi3D;Xabg!M_7_Y!80gel8%??RS&2&d0biAfnW=gFZlse)%e zX=2iVFb$=_F=>Hkprqczb!%ZjHIbSvmeTRO0k>mbg4Aqwh4H198ii#fQo<>MuEwF- zQ-h&vgsu}RDd>ZW$1b7bNxk0mJ*X{Y78_ma055op8QJR5p*Nip+m54Ao_C7l_fi56 z5uK-oCMgSkO1x2J;tCP^5N3{KCWgBw`k(>f7y_r8cs~}Ueb5L3@f$yK5z~L%YBu9T z5UtElXverw8jwv=gKOXtyYhfBsp>%Z-)Q$3ZS}IpyI7k)jo0MiY!{*+wr7^0;2_m$ z1bB8IQHO%-DN-#8DJYy>=_Phy6p~QbE(-o(6ub{p&rvvyLTnxmRW@Z%5tt-SoIco_ zgwdeA4GFIW?!%)#A7`wzVkI^wYCHQ8YOV#rE z#7c;I0bH(Cjti9p=;<$%L|8K)VCl9N%gtDGoIJ-We}I=Iu2n;W3gN@K%6RWX@FH~K zJvIl2I=|+tpi4nebp!YOVa(LP3&q1il8W+x@{^b~g04xv?@$8})Zy|TRATU2Eor#vYpZB6s&k{NK~(ca z5SoWWjhWv6$C44@v{3a}&JdSDMWx_jV?iak87eC4A1;})a47)|9@F|!7>;|F4bQU- zmpUe;5W1$4$-v^vB6U@8iLu%$+WAlG zIKEspPn&nMZ}8iS)z9(zdRhhJN?Hw_Km}G)a4Zx@*?-W;6!{_LRzc$W9w!_v@c0=+ zeNRvwR+Dj$;;Bg-=dhHjgSM>JN7^KtZycq!IGW%);7-YY^Ow!PLHHItH$GbOt=QT% z*yaqCrvbWQjX4R%g{GtER;BUBtRUz*bg z-GiSD3HYq}l4}Kd4~OyE{z#~vQV1g)54H_mtuIvFrF*n>3A+$DsN;^P-iu6 z{vT@%z!jvL%$FRS$uEvZ4=g(4`tj8B6S^eXv`zmW^92NTI2E@%P&;Fl2>l2g2jdlx zIOL605bAiAk`vk_4rr=(CFT6=z@slRQf0xzD5-6ZLWG#-$VZu7;O-aSa(=x5p%>pC zlkw4cVhjA3_-4-{wHu)arNO1sZ-q7oRHbawxqJO5}$`r2>A6_^S0p9YQ)L(@dhGtC=Qv7A9HEa2^{W z7p1|8>VfB=q^3~brxi zdr<7hnnMx&KdB{-YHH65F2~sHCFgGGsf}C7go`7eD$v- z+dm*jgZQfa>A)UG!id1jerj^m@qK0$!ziV|=c1%C$A^%Qkhy~KG8gS6%t${H-S?Uabh_w{ir`FnH`&bo;D-q7*c@wgY# zF+LR6k*rMC449gaTdiKg2!#mS@fX{G<6|7@dDhU7TF}ggA0xvYqmIW}bDu0pa!d9} zQB>6MKZ*70B%uz0$XY8`Vl)fK_6BG-v<{(FXdjM~;;4C%9IC=mhl5;aCiWj>%Zm|p z&7I>j!$2)X7pO3=Pap}}{LF(TukT3)#l&nXBI z@a*;___B#xLv`Lvr@V*uE-Ch6D7`{L%Dk=?fG`N5=JS+B`MnhG5y~_M8bj#<_4xZw zZ;ra4i9ZPknX zx+lIz`^{N5A^uPXK<#tnDuH9|p%?TCp|#&nm+_E!-&ZIz6i)A~D@NXf%t7F_by1Yg z`%jNqr=K+sf=4X46p}dV0Pm1wo=uhL-EZ6OzBCPb6g0aEh23r9>Vfk^DShb+w1MO| za*0ycfi5P>0(e^iTpCrx!1dNI(gwyYhC)a{0M`c~v?VMANm1*D1fJcx1g`)eDZuv@ zz$J_0BqV&l_`Lb~6653&PnAp8v}1DI;!0wR8n`^Vq_-ZRVWB;(&ZQ${j)iuEcS4d0d0QMM4k^2iB*WwX22Yu|aKve5Ik*fy zgj3bvJzu4(q1eB~Sb7leRgkr=XG@G{b&X$QFqP}gT(^mp>|Ae2U?pU0D3c~`O)?E0 z!*~KOn-?+6CW!34jd>9~yE3Ju{opA{Ue1|^4JF4|!gYYpV%(3cZJX8iewkPsV`hn` zxLS|GL$7tkJ#+wMwZ-K{kqhc2bmTgb<$dRfskGiq+w{kBqg8Fwv>bq76Bnv#owpl4 zmISQ@Rcp79i8geC;!HaF+A=R_2cBCb}0iA?T%`gQ4w}+bX`ss1Ir_ zY%h4}NN#(Rvh;&b!mmTlZcHI??E!|3TV&XMz&PS0gvPUtc`XLv2!t*OHtiu^P!=J4 zka|OCD0?{9r>eI*ShW?v{op|hE+rQNKlwN@d(zj^MhTRe|^GSdS=WgDrqCENBEYjM92L+U-Y$>IEkCwUXfMsaTWm41xN z_H=?93kSf}ztU}Y!LR!j?hrhw-{m$?X%gCfG%axHCfdqhnOi?cU$;Xm8RXLO-w~i} zza&w{QPdkj$fL-{MBL9Z1jVkCRMGD#X?64lG>uznjhQ)IAz!&h+C0?9( zIV6G?fx|ZR^xx;Y5)<$JloSLG6*EC0TqQyqLaPWtu~m`73kX`t{MC+9kFzEmX!rgy zdvm7h8|-9?5zE%HB)oQb=@sxA;PoyBEA$|bvK@7k<`eEKfiq9I9j*v)c5Wraaa?vx zlC-?Kkw)o9nYerVCQsc|?&vDZfe{FP@UX-Za7hiCGG^FF}34}z-?v!e(cPh5Lx1hn+o+=l2SjtUc3yQtg7IQX!A z)8<)-ZZ1j_$_#D`5a++?vXSysP`et_IWaTFQ{-;$B2MBQCbDXvr(2w&O!qB@t296(fsdW0^ZZXGD?x zi?R`}kZbilN^SK|n97f4Z9Rg(+L2DbU$J=ChX#+<5yx zhEk2o1TMArB=prW`gA>k-`xnilCZs@>`T83R^=={TbBrZAu5l{s8DQ zf;!_H1}%Sy+7Q%(aFYn52y8dWm#1((&v_c>BTR;K`2klMxW4*9@?Z6G{^m*>gu0jc zIuZn19AU2r2N4b^;SV$*5f%_sXY~$IG$_1>yKWW6$v>D&w_Beymu|s_SgB7!X?+Mo zt{W{SiQzcPFsO^mdELSJ9ZCSgk`T1{{5BAPP&7{!9mH=XLRTH1yXiQ{lL#O5>{Y%R zW1zRdQr$O&5<*e;eUH*nyjk^l-S`!Z=Yq$I$dy-t>QV%BC5sIvRmk9AY zPl|z22-fk+2jQ?KEhmO81#pQWO+v!=i}R@wbLXXfaJ!=+3G4>Wp0Gx6Gg$ynf~UYG zDdA`KITpZYiP!k3%J*35{1Ii4;%Y%K<^fQYJkxgYCP?c1cMK(r()BG)jvf3{ZdrOs zGXz0!H3yCj%anWBnu_l;Oumwv3n@h}c;_p$zHf62D}?OvNwN?&4Xt?hzrkY#a7k#y zz>Rfe3MEWpbzG1#%H01hgZF`3%g%Y2R!5W^TxA?XkUml-UV30l)wZ){!6~kD0r#> zJ_w$);Hs#>6ZjnX9?@3)mD_K}j`EOu+TM!W=nc%6NAz z1sXqND$^LQmWU5|6m-%&huDk6>Kks*EcoC6nUUklteoPE^F)(BogBVsFp_swl$eHdVMehTT zFrx6$S{{f)$WBoR5eVRVD+F5yf|@6ipnFh;1(gx$c?A1$?2lukoqAYbJu3Xw)Q$-4 z2t2lA$ve8ebaP^LZVn{Ck)QEz!6p49cpU3t+}MS%DDC`;hxK`Y&F$yqMl7CuKPRi; z)-q}V51&Vcyng%I4@FRVAX&?)4?G55fg>rW%r0>p{GcT(rKz$HR)EQ>o;G2mt3+2yWsVd8F+pSksI0WUwF`j8FE2uh_X*q5D_8>T{plhOUNA*nk&Kn$>fFkb7T82*si(IY)3JaS(L7XbavR*N=uo9 zF(H&*l-q!-$du=ol;1^Dy8XxWTsK0^kBO%mLCRuVjLUVHS&MxHytV+I1m6lS`Q4{VdwKGdioIa#c0lo)ZYDGFyW>WNm zce@Gq=XeQkpv)QASBaOSuy;!_{;glXo~s+n)=r&D3h>+h5~*bKc+{t}zhpUy;mBHo zlGg<^*oRT(#rF_`>$5}{0PXeUR=QMU8+g=$tHuD{;~}syyhQPGhX^TzVG%~xF^rDU zyu5JK#1i-oy%B{yb{2|wtd^ix-}kQvO{FeRfrLh|b7QC85KN(n$1$APsstrRYrN0U zbxe;^ikZ_Ne(+jIYUd%0;zLo>C2}3In$8lYGVlw03SEWk{4KW$C`*FkTz&RvO$fA! zl(Gjnsk?Rqm(K%j(06a()@u-i@-%iHlBP2JOPmR+D#F9`Lec8>r|ED*c$IRM_@$q! z76xGiLIZ@rEQB(XAV(Rca$*pUTfz~1qyR2q229+KtUa;cytkixnx#w{H)1O3XYSQ2 ze#i3+(pNX!J`@Knkr&H1tnc2CTLxZn2tjal!@YXHal<_V7#1 zOH7V6`_A7pAi-H8MO!a|diW9o?Z#srUL@GeO>;YV9Ne0TDEN?gk+(gO2jNIrXfNMw z-YWBIa;XbSPOVBX%ciNZg*{>Tm#mWR>AU7y@T2%wq!3CHPuUeEp4!33A*ltJ$52l7 zb3rS)+qf4_0@hxd8@^;^0emaC)uT2^`@EE7e@)?3As8>*nP|;1np7ob<+zYiI=#;d z0o+*ljG(wtR5wVO%9xnqFs~pzQ--NMDLq0`l+h#%Dn6PssJanOfJ$@&f=YVo4Fcyh z8#^dVpqo1_Nl0b`5F+4iGwRGbp$)tn!)tznJ8vaJtq5B$o6-*;*vB_b8PBp_x>G+U zS9;z=A_%V1>ZzPl;!+oZ8E*3+$Zg(RkkfC<QmJ1~5o24SF={vtACeNF5)03DY5S(vjG!;T)0YU;o9fSc0wlIR)(s4e^jEu4* zXflI_K<7{zj)RU|j#rjfWnR$qaS=ul?_#t@a5a}V|Z|kUp;jywF2OQ z+e`G?nV@@{FU8K^dvZ%&YPtn{cL6*M9<<<6Q{CW=?=f=q@i>a#LK3Ir;I#$t6nIqu zd>Om~+}hlnFDRTJFr$^1L0FbNeW6F+I7#77)>8o@%)OU#5uyG+7_48C6%K}p1}Z_& z#`n|3r|7HR7g?Ja3PuR6Q>=1>Q>=1#e?Vy)>?c1kb*kkoDazaQ{ZreoaJB5u9}2XW zm1|dkfePVqcA!`Up%C#b1E50A3Gi z;4CuaoMWMcvNTOe>XIa)vcCxaQ z`(@`JSoEVTVQ3R!{j-w5Ex1B(C2z^S{qo=_hRJaVT|!7fkS3Eo@212j1U{rvnBbW= z2=?bl3lHWaL(n;tW6N#=w&?=%1rO5sp5G)M6wJD#`@t=9n3Rbdk)_LGKAVWC3@6@WU9Y zyM-{yI11-fH*7}8+dPazNLg?x*m3Y>3{@7=C|Zyn@_ofe!QN7C&aAt*YfxFPHpssk%cSz(+$I zpb9`rE%RVRJ4u%Xcbj--o4o@3D7dv6yx`*m<$8rs%kCtHaywV;BTWaF8t3fBeg2FdB0eIz*==K>9VlIb_8=&3 z8Z?eFA!xeSjTy?uKTDImJ9mRljSLXV?#2fMn+WOwc+y0N#jFamaVirYEUn32H9)?|JvNLy|?chTeFH)q@0=QI7m5Hl*yQ|&2`&3^eo#fJZCOvJL z+!aW#0(`DOdfo!Kq&JRJ;j8riu{S%tc1*Odn@u=|a+1V(S8;=5A!G1)4Ai$?kDg#o zEc<$Xr8-`t-{VA;t=CjsX=agf*y@$Z6Q9!?09=Cw);BRM4zh6Rf?!J^s86<~L4AF> zRpTWy-6pQ?u7CPDeJM>-tGFkZC{^F`PbT4eXqfUHy9i1TO6y-30i&?pFrVPASRlE5Hb30=9-9)yP z%+FiK^4(UMcy`r^>;rFtpFKHC)lHJzZtyU&_R^=bPwjML61SL0gfZ}O;^=yffKmwR zOP6WTWt0if&1uZ65qL}Z<_SUR@L*c@m8-siyy?|ka>)l*$<$4d-vx`l#m@uyo1X*Hc!f~FdV!Lz6 z1l6&QkOArqD?sBJY8;g88M{7{CPl5GG`o?(`5b-#RQNS3@gjn8&=_C`$^DMfY#3H7!4KxHghr+kUxRJ$&wSmMSOhV{_U^|YW*0pKSBy4LvI?m>| zY$2&P;k_s%pEpnV!LOpHQRW4$ zKv0z!0Ifvf(?2s661+4>6OL1~+UDK(IE% z5Cp;9gp@r6w}ZD}XnX{~An9GDK|TTiI*dD87{R!YIG0IM5_uhoa5+B_2!dNHxgC5D zhI~V1?YzftE4!b_Pc;Ie(}IhaKJfl0SV~~%sv0#;I7wLl#q%2>OhV`w zr8ed1o_LYi)$fko_c8qhR{M?V8SDBAT+y01OB!9EM2 zS~7M^NZ;t7<;*@z!;%+0qtHaz3u+GxPMsP&1DY$O4>)LPN4~=ZAy;}IWo55%<(Zwj z{Vag^_ohz8Wb0;lr(OflQ2AJH>yntG=hF~=kdF_7&suPaIRQTT0~!JjZH^zBRV7|x zhbbx9b1vPf+s@|dQD_@QNFb;U7v}}EQk+UF)qecZ>8G0Dj z%p6b{#IOuJAq973Pj(MQa?PxS`7gC0F- zaV16IF>u|!nh4#D3u^Tf2KAscgKn;56mdh9jAicO;t;CAvrAFraqwCU`CK`7K`0@V z3B0&kU|WmFdoin92regyhY^eynm`Ai%+0kI-xVg##8aeIe3+k5q;E!kMDb(3dC!mX zZ-|_iFc^Yc)2#yU!%*5}SrWIskfZ>$Pq$>>w6teDxV028313<%mLf?8p%r2X3S?v}5DNS31Dhw-wv9N!}d>O0jb&?B&|b+ZhffTW(@de(6Rj$*%% z(r_fq70VM%dd-EwO|Afd+el0`Oi8Q{iX zfWKhkR=)Ona#Mg`@h_a@Xn2_|M6Yo{cU>Ihw|Fd;;yq1Df;%M(Yp&IILbP`r=YCay zl56!lE@mhh`Tdms6jvO5Q&XpAG1Gn>;7f)-2)fJSq~M=6(I-IrpEVz3w_M6}GLzea zq+-M1>1it961wdorrAwQ2yqCr5cWf`mCjIk{5b2X2&e~l$0e{6*XSq2eEivbbAKiC z_p^+x{|H{p&pQT7?W51J7Llm+YxJFKaO!=YcD06#4ZXe2g1rtxrvzmCfNo!l zX)mVDO|-+twZYQOhq-L6`tCQZD5`ojx8aN57WPf(_uHQFXNH%yPxkTc7y3h+TlYVh@;#85VR z$Ofi43neL(2!uFu&x@aQuOC^fIoMq?(bj#?s* zOUsdGnQ4?cQG{M}!dxZ!Si5^p;nsetKg~yTQw; z7zsFP+V6b>;gEoFjx7ax5J%P((Xz=_hb>~J%YI31XT5QbE#PJ8{@2_%CFVA82e{Q^ z1YG+o#lhyDtq4Iamy#yR@xTqPWdg}=PZGBC3OWPP@?GV1#mH%7wRj4dN<$Tv_{%G> zm}%Js!FJLtxstSLHjzQqZjbLRMsOQ9!Ik9HLMRGaO{9B4H-{`qNM4f=g5YjsX%LxX zYzyGKB(HMZ-MNK|Ls=5vBZ8{8D4-n1bXMk^omcDEypgNB{!U^D``Z4VTM{ZU{1n0$ zOgy{6h^%cThys2pOx()%f`<(LK9!r(udn^ajTS>w6MPW75nP6PV_?44Fi3Dgav-f-E@U=&Cc)dmt(!b)@O}$l+K}U|jM)^e+T`(~ zOrmf=oWpMRY4hPZ=vI_gQ2P)*CS@3@xk}$JK+DpU@iRs5xk?|a4qn`#E$1!{BpVfP zqjf^eUULZU1y5OUiOLV2Tw<8z*xa@-%25kRjJv@{3*a&EAqy@}N5K1Wdf?53-Aj}S z*}1stUHUNqTUF7tzLXKxUk)<2a$0W?q0y#Ff_Ek^XSv#hw*PVl&<>3bTP^UL|xw6QWR=JYOT>0IV`hL0MeBHD@%oSJ5>!$NY z0OvbcSV36&cZ7gRsJY_bc!-*Wy%209VSHC91-c7mOwcew>svUv=Dm^LmC{NNP)5d#56)jmfe>t}J3vFHwE0mNnO# z_~jG-TZ5$~E$~XEf2bFDQ0he4N_qi=fwu3LPOCYsgSOCs~J*vP0(ShfV00wDg!|kg?2TS zAqr?iJ64iRrWL3pA?yLqE(*b0z~h!sWc&?-AI4#GEqeeJXXiQ;!U%-&vq`Zwc-fi- zlyCu(_HLe_8l+9G@d5-tgd?VxZS5$YRnu7$gE^6a*A~DB!2{sdHAKR|^?|oj7*PvB zGOfLbTZ004MFCvei`T&A+lAb|tfJQ6F2At@I*u3dm?>&u_kkbDkP;}RW%;B@aIH*v z;@f-gU|99R;>jBu%2((oBq8@X3@%p&H+a0~|Uh9HRb@aCH zKPW0_%@^)4zNRq_aQOU;dz2&!H@fT27Uub83L7`;_IHs&dAS*0xPd1*D9wTf5!8LY z5462}`c%7Q>A>asA-Q_wLS?hTk-pH3sP%FqBHeuzQ(@Ufq<$5|dIZ(CqJDO}Q1%Mi zok3He{U~FCCJ-8YL4L;SKe>l?QLWd?Z0W;aJsOub*#;5z`XC=gpj#OS(8}7d@K#K# z#f=uP=BfV048na^GYD6_k8!s`CA_x8hq4=GlH6`7ZKxf)dhj-B zY`=J;yxz~R)B|)2Fz`m*^&T9~UNS8&|E(>FG%^pNv!i?r~FymLx#OQ3g(?}AX||%A<_a1B4T9GEC)^eU^-~ow(8l%CInO&J+qK}3PC4Y>>Ap&R z04vwl4X5W%_5QPryxNB-pA94?Zns`a9%b_>02)H6c^_sym*x(JVitwa4MA# zWw$qJhe_~u3ogbB;9-o_*#&14gF=B6s=)iq6xIY#q6Iv)flCBX1P6yFc(euIgIK`W|I1oa`PJ-GyEttf)FASl1iW-^Yl1iCL)m0OEa zK>-N;1@JcTKJe`P3qJxLEx_*s?W34}v#AQb$FSD2*tDu*tRuVP1rO1ocB5EgvCk1$>0T zdmuHx#>eiEJCP^e$`p}6=@sj13FRPyO2xUIibYwv7UxG0HhvIc5uy2m@a7Oy8H~d# zdm{tTC-@-LGRoFB=I7QKWbA^pB&JmeD&Y`lElR_OK>Y~nmn!0*5tRL)u4DmcX$VKf zhx|mz4i+dPOGbPs$5A#mVL4a8G6Eq5p%sE{GGmqmT|gNYbXhLT&jxuuO2}`bUj7R- zf}qea=m<))ppI%2O@R7P20-o6>giK`vi8|mp-%`K6E4y-0X{U`&VuJSAL8-VsPn)?+rRWb8ynbudgAe6q9 z42V#Hu(O5s)r4>dh<*3lSV0n!_QZwyQv!?t(8HLDF4Rv5Fjq5uDk5{!^%v^vKMYX& zj%j26=))K4*8tci-@)XI&`^72et{?dhb`v<_yTx^1(&kXKF%ucN^&3$ODzN`Y#)S^ zgpgOW;ByvS9EQP<6Jhg52sMD`8hHUO0osc)An5Kox&cpBN}Rjcl|+%Zu8Wa(A*)q# z2&EmRVLNmYR3*htbU&!QyKdU}^2%%H>tjOmzEc&;+HKxXFjBlTKVm<4qyQcQ4_k1_ zNjrE5r)rNah7z=pqLJF8@%|}7^fEve2K_e(#p!<5Rn$FutO+n}dw=PYW z!H2+Q=_K=1W*gPn#vBiB-A1hfpR@2K-#+kV@W!Gd{Y^WAYi%AMC3`EA-0q#+uh#pf zjqg)zU#;J?lNc8O=CIS=wL1Gq+l`qIR!G?|;B)Zm{EF7DV|FZnSAch0aEZ+e-VQD@ zc~nQ*F1;vt{`c>UEBeki!XaTG!fP zCKVC-5Y&Of1ibP0PM?a(Aavz9`sV+kb5%E(WBcZFWNg21Ti+)cKK%Jb9S3(5z{kOt zagsf1NYE+pg$7w#Fx<>p2$EaRZibHncrEx53oZ@=;D>Qo^Kmj&=Qle+3{;e^4605| zq(K`&)iabn6hD!x=k~X)((Sv*clv$Pr_yThU8UCm*bcv+SUKQvY3x%>Oz+RF9d$ba z4#_CK3s&*_gSe@<#+)lxtkNgMO=rODv%XK$G*LEw0yKRsaX&#_MM3L7$nXWax#NSm z#U`bags|I!OYRrIgBZ#XwZ(Zot1JsijH|%?7F>*d;I$ZU{9lQsXpBjmj9`_$9Vqpk#;xE9@wWd=ouB&Q z6JOVHvY_$9r$>;}4|hj!*YaUnoIE{F8A?vhr4*LIn=rPPi1S8vBr#qh7F!sBFPj@1 zTWwr%euSZ&@3fahO=a)@K`R42AVMX=mdl=(D ztv597;Jd-I^DhBL3*b^NRVMD2a`^(@`=9=3xvmZ}PI9T+;z}wbZQ%OECkeA?JC&a1bbfN5EUatzqu(32E09nWJcaSzOXxPpv&ibXzc`x2K&ne?J|p|s zq@&&BNey^W#DVL2!oa`?E&?h_E2xXhIW0!2Ghq@2AlN0Heo5y;nm!?Z{2!%CdH%D- z_x~uLkLH$-lvN9O6L@w*6t`jUMvT?{9dbRgS`;Nvd?*89+zV9TD{xdv@=(B_&$t7X-!WgiWj9u?pl$nk$H`uG4Znuu)ERtnQwJv7xJOc z;uAyy63vwo+l9wf_FeN-aA4$2q}AL|{>&@E#%N@O?NyZ@5gJ*YTkw?IN;BMs1pWsPwKe%-b zy#O8pmyRbRR%Q*YeTfW$vxepp3(w3qc`LZkXEBgWdBKN>*ws!xjw7fAbg-Rm`(^06 zplIuti}l8r+4b*k4>}y)Pn!Mk)Kc+X&+wR7Vwl9u;3t`3+k>0zvoMNeup3y?m&EVT zZp!B>Rwbb?Gbo@m{6EkX!u29VucvxMs1D;ngf@hE5rPOtqqv!|5vAtypp6Jdi}*Y( zq6e)@;7)`?BKSXpl?WjOqd9a^!J_Pw<QTv->EPMOZ^p zED!y?Sg$_yk#c=}AJ05@-$0spZ%Evbzu5BL!c)uwxF0-b!KGG0;87f^`^0XP9t%lA zj)8X+z(>G|CU2pf1P|hLxPy`zM^HC+p0BW2N3nmwM7f_{TM`D1-AJDnv>$=ZhqbGG zpz#~0jqdF<~F1M2vLH7K=Ojf?i+>OFM4-YCopFfvGAUHlxq7dx85CYQhr%vem z#bRV%ZdaGOO=EF*9|?)Y9E3)>JNWVm-Tq~O(l45QXYUEUMu6i03)0-KJE6CJIe4+F z@232!9l4Fk)_cC3n}&38 zCl*fd!z!3p^_#@955O-+dbYi)9|Eu)zJ;9K%pfq-MJJOhuX|Nr-5I>X*7H?5Z6}oS z+tp~v(VkAallyk_K+bJ{E;fGDd8Ct3rXJWYDSZ;S?Sk#@O6S)Y@<62wWym}I&d%*L zckmWrZ-ialv$I0IFW-ViABm~CJ%ZAUqJ9S!If|@S^+}W%%J3~z81$U6RuXgGL92(L zj{G4HikA|WzbPyeW<;88u~_}cr@naYc5O>HyiqPyn!#p%-XsQo6x=$@j2O6a$Rva! zegl%Dn_nr`7fTs@7rsKV%mLR6yc0OsWFFF~jnd)1#^l~b7OKCN-{#sOR6&rNhPs%c zzK^H)ch| z+(Ca8v=zSvlONz84%4AnxrNCrZbPL#d3VeGjRL8itOXaHqQ&?bZvA{^;uoa`Zr z(7pLt3g69uelMj7!EqRZ+6J!qL-Ac@+(h^HFgH5xBTHPi#rkQ$tC+(Uf!Ckx&mGC6 ze-Gj<+DrAz0QShs{G=RSJMT8V>Ms`?zo&dVUMKH1`_b2F1ITJ5PnyawcDBgZ&7$<| zXK{#P{~D-!|Fpgt!Ex|D}5A0Mx?&Ff`_@AEByWqMG16V6F1u;(6 z#>DGM1hu60_VFkQ#dQa$2>hPg+AR^#GV*Kfihba2aBEkL8#upAhZhgUrXJF2_i)dE zGB2nf!B~}m)}hoy$&?poD)QKi3G~rLX z@&$A3Z99K^X-VyUtkU2ZpXoqZKvAFRFfSON=|EZJ0;B7?Vw0rqVYGg>_qi~C7YX+t zpdpmX4hv}fK<5EzkwfHg)kBfKUpdrWb+(g4JErBbe_lb%q-O ztwL!PRE(M*=N#H3XiI^B(%=C|6T)spP|w(X2Uz?Uh^_^^9+G;bA3+I2a+5D9smz)0 zKJa!(@;QPn36yS&C&}|9c&7!I0!o8NBp$g1iy4lL2Zty)(l@>kTz3g_A>#(dJvA?!=mx{W2S-oUWUdww2k)yM}9<|-%IBH=@3eA!i8sRw&XQ zSrD!C}lrJxu0#2L0pQP%)lV> zIE2Fx4&5(Z`X~7W#{jz-)VdmSy{6*&2H^@S{jDhi>cq6n^qu+MSRc5!v^KnW0bFKM zzlp2K;Ooa(2gt^y`rgJr= zQWGzNtL?>~{I*!{?%Q6uW)gJwk^EsH4Zi0HzHw*kLulB@ zsqyLuX#YZ~d4Q?lIM?gUR5P2EQG68rJU`??12^6$N}_0xq@W1-^vAOoz}-J502ajj zc%D-728t^1t&r5JEr3#oQu81U%!kYDRw6|eg-{D&F9bV+v03?4QXc@Y4aybyGMaOU z#KstX1novppA%~X-8F8;6E&2)b}r`5u|J?wMSX^jOPxbQd51f3E249(@nqT9;GYmryl)S4T=kH zlS;xU36$n5lNhRLHjQ!=WdbiYLFEPVZN5V^9!#xWv*q95 z;R3iM)otL$Ckx^zrN5vg9ww<;5kAf*VYE0!`-}XfDoosso6Mi&$_pNXpFRBu?gwuN zmr|5ol-arqf%kx0AAh%l$A2-M|7%)NE*v4cy#s`~h@iIaMhBR-oWGntHG+HXiKq2r zT;A6YFekt_o-UStVE$M`&a>~@?{YiwbncD61RMZwEP%Ix*I95W%LsTixX5N&`g_jY ze%`i0E>u|zB!L8YMFD&g++o4RX&QX_mo$Yz*02!>F+hHIxH#wGxBq*r8@MPbNIA=m zpvWQcv;`Nh?cj?~bGqhRQk+MbPet(m8bKa@r@0(LnGm!c!S-#0!w4HiC_6^KT(jWf)DNB}vV*#|#@Lu#4v>o=L~k1#)>EM-t5`=E88>Hveopco^?*b#m2 zAsnQ+%Fnd%!{~>Cr47Mna?_IxFJsnN0C)ZX-xgdlTm@eJjM=mUC{-4cIBf&3D1b-6 z9Tr@i_JJ=G>P>OxXV0^_tyu_@5Zuqwn{^gEvvEerHrz0V@@(p-`U%Wzi@&9;zH16s zA=sCXGr9<6)lc~)K(6fmJ*6Q+8-g6;Sff3`O6&Le=~aLWNgc=Vp^Tzz{2p`QN!Z*| zoc@#SMj*^taFs3a=i~DLEYo0K(!e%DySPlwHfb|j7BJ~!xVMnOzzf-q#K41gwPDZ)`D=8 zFvBn<+RR|ADh1|l2x`Yd`w?qXlzB0WBB;m$po1tik5P10v$@Mp@fU^Q1-JSh1h1au zlq80>K5Bkggi!?bWed+!ENxNjkAp5EsKdNr&^Z)t*EhM`&*gg^fl%=rolB1Hr%;?I zV?l~DLBm8giU_3)#WjrcYJ}mxL63m;p|pZFq;PI+1qler0{A3&!h)*`29M)#LL3fR z2vQ#2AG6J00QZCUSa5L|0`I_K!w7L}&+~vzgt8ZC^dfi=)blj$CvD? zf1)xt8nYz^+V-dXAVv8@8H#CG*45yW00 z6oh^Kub5p0hWx3n0`nlabxk@5J_>GKlP18E;MO(iB=|`SUm{6^I~I*2nKPpt$@DH# zO7hcZzMoU$=gi2Ptn1E(RSm0G2G*yC_2wsOM7@7DN7|?O$>b+F`|UiDUwV^x(F)*c z@bs&>e2K>~#(n0iX1npC%vwlND1Pvx1@I8~s0A0N?chT=-T5PmJDjG+BiKEEHDCVI zAJ>P~mA^5z{Ee)8#tBZ8r=acnJ8wT0lkYb?uGc)pbF$@AY=xfzaMt7c^)PI6+Kj$m zsM;Ab#YSlFtiX5;ByW`#M$j3fCV#`H^)cG32cn zbo~VPVyQMw)1b8l%E58eV5@V^UKBqTuAiEwYBxUuN)hU_(6=Ndz8gcVvwXvwMQQ{x46_V zrTc$l@+3!L6rAbJ+n5B9#l~7!aTB*DI1b*At$ht^(liRG=QIE*KgTl$Nj{@fCZ4b` z_NnH-Q>?e2A9Sw?K`C?Qo3?|OI?etbL(x#Wei7WTveaqx$24FO-~^y;nNZYSm+!aC z)+if)nMI8P3U#l5%c~9h6krgP~U!sipwF^XoE&~}P&u$*R{5%?4^uS_0eE4tz$8ic?@6*IamiQvA3 zMlFxQrWo5U$&EqMih!5HX%+Gaf|_HJphGCbppF=3YHIz`!^YHl*KbH_kjwVpFs27!ea-?;f=NR-0%1Z32sy)w5WF)6flo-RD@GoLY9JEQy%7nkMgf(3~b6zY98Cow%{)%l{lxiNq=) zhEe)ant#V8-0`)!iF$GFg&??^mR@?mc)YV^0d#0x?yx55XwOqA;Mt)|c~=;?dBg^# zYCXmBd+w;K*XOnt@e+Yh51w69BKLs@Ff^uLly;N>yx77b$UNyxu|&eO4!Trk=4nk8 zcn`R>Fnr+M63Ybrp%a3dBi|k~=g8d?bO^b=m+Lkh81q{St6s=uW-9WeP6AvuQc=Ij zR~9pq?B{~kb)Z;Z_;1cF1zunr^3ZH2Ww#9<*+nJMMIi{D9jVBJ;OPQsCcqaY`~0v< zG4dR;I+Emk(YT<_jUlJFpn7Y_R2rtp(;}!^xW)~7PP&q(ad7czJOwdLC&W}xb>hPJ zk_t`VI1MVX7@vy+b(7P*pf!F^evXn5>cQQlk~24gH-hhxBZ1HN>k~Mz_r9KXB9p>z z`gQw^0GG}fKXv(oe!T`@v;VUE0X;g$v}eI3Q-k1Dml-+Vl0>Prkfg*Hz{@ST7;7&x z7GOM2s*t z&eOfXvzw`t zG77EZJ?41a+NZ|j3f-OJb2x1tAV8vyu@SC`L z!FhF`K8yqVk0B@wz;5V zr*HdA&e;>GyY4@8BL?n9&in};18)PDHINKInHTy-z$4(<+fI^$B>2JY6#pF2EPRs@ zKt2NFd6mT^iv6wI*X=_-`OW-h7y37NyNQpR5q!#AlSIJ>AI=>by>P0)-9%O%QARAqwB|BraBV;lV2TGC%DJ|A7co- zG=MT>AxZ8RNUt9}F6n(hXLBTYh0EEN?=67?t&KkU2a2ZZI!2!J7yuUkz_||Jb-8qD zWmRczm|(4*r!NOTHKSiOFLs}yu_L(ld?w!{fypii1DLFz{cJA5htF;ZN5Ol}A=a1g z)R*RiZ?~0qk;4TNNg=c@a1MO@)*1c40;y@YG3JWk@1fNqtoPoY>s3m8{4YFg09WN% zd8c0UN1V;wfwMni$`586k7tvArC*^8gWB7o+|fw+-x1~YBKVa${q#@pOMA)cpFob@ z&B!J~+1Ck2gp&xzgwxc=jDq0uJditQN)rs6qyaoYo?hY3wf+HfCkn6*unTZ~o5f0s zI|N}Dcqg(p`ZfI+MAxW=DDJEN&NzZ6PD3)IEi$?v-#>GzUbSX84v2vyHDx7@*f6Y~D&XBy{P(nI-)oOkaWQCBUVi1~9Y-#ZYo~ZI3=7K;Xd{ zrU zk(-N>ZsuU-GQ>E;l`2xtKgo@ZU4J3}i9vIjAOEUe^B1bI?^{$gS6m2r1(Cos4q-q{ zMqU4AhXuy6YrB{deikQmmir)*DXp3XJpnx#NVii@p^r`7WR_oUTcr6cr#%f-ip0 zoHw+UilonzhAoPzdMiHw+G{bD=CXikCpa@?k@kOGdh_4OUHxPEfy8mJ^)YfMgwn@z z398{iI0<3m?-XCzFva%|0`MXjds()XMY~X#komQu;h9qhW$eG^D|(mEnx34|4~fw6 zBRn9ik35yzHYABSKKj5LCD^BL(bq3wF_NJ9E|KQKI5!0duIguK^-yS@)hoH}mU5ib zRu)zLma&XqA}G<$SXoq$GLQW=)xXQXt@AID)PGXKj+dEc{)vz7m-Bt}m8>jkhj0@FTm36^EQHOGS8|zBiWVXA2)F~oa~Wn-0)+py3!~o zNp*r$YtjY0cwe`Y$6m&bfq3~OODkyt;>GtT*0oaOr@nM&&5jKYO2POh=(As9E&19< zoOgEYD77t6HuhCJ))nJv?vQ;iP` zMl5_O$v*gHOAMAQ{fe}!Z_@2H%F?rJmSxpVMp^2OHVX5|GD8a2Z3%>%MCf>p{EN_y za7=`LgeBXKD^_+E>0du@`z3m#wxiThwPMzIp}h2q%&VX0RkU_(hr`hWECr>#@CD;_ zmop{q@w4bbEA+RWNq0;m51B0K*O}sUoV~IrwL*WxDJsH?+_rL7cb!4{B3vcHP|2*` zim-CDME~DC+t-yOp*hZ&)rZfZ4fqh|xw@i7|H5k@S)*4MlfNdwnqsa-5n79PT(Le` zoLlr#WPw%GFt{d-@3DPybI4&Jv6m$0i%BwBqM~0DC|g-{v}9JjS18e6Yc_^9aA)bP zeoYC1mfL6by&}vZ5Zq-Y3tVC%A)bJ^W&-oFIzRMuYVok zIM1Ec8xU5`ovWXD>GpM%ajtG%J*!?GBscCxGdF(lUEmc`lQZq++gL|mN6Ia$XY~nj zHsmCeHwM>U;#dL2yY? zTDg2@TdGE!jDmY*L_M}wAH#t?aRF^l>gq>(^`$d+TzpaWg|j)6inKYuljJWn+FTg9 zq5!8G+;O4)hZ_hnZgAvO8)No`v&O`)owu^6+hVDD8SHlOP6^|CpVRG*9ei!?qWmyI zI7nPXxeKAnl}iv$F$fhdnuddBT2(>4!dw}wke+bKU1w3`bAa}Rj!%U zcOvYIy3N*%Bl(koWaNCNdGKlhD9X(Ja}qobE{O`BIbys3egs_BtI`NE9|zDbSjmT2 zbNOnX0WVrRtG=-H$f4~Qm-qlG*Us{DgG6-XP5G4@flvtVGjWMpBFY@bje{rf6EJc4 z7`sI62bYMBAZxBY*~@}=-l1K0?4A5*($i<}IL8(tnk6}ku#XdTx0pVD zqh14Gt6WDhuG+C_y_>|cgOJ30m{x$RyR#46s2>s+{p%=isq#18s6Q_*de-B-3?YWF zSp>I-o{O+zT)+LS?Q8V@vK@SOYyHR1^5Qw6sXI{@+%s~u{)V>@WrC|mub$NhocNr(+DO`Y2~!8)5}<9@yBY1y z+p%GNuzps3yjxnif0b z`fxd!-SdfAW9>D&+gLB$b>WWE6&3oEo3^hn@vmE1RQ|t==3`{6kqfq3G(LyU2Pj*q zZxMPBhWSAHii7(5-?V+rT^GTMf!QyjHO;n~lUnyDjY%!YNaiH&KO+3 zvgo+}t7`NiuDOx~-Xi6lHRmqCDZg%3KXwtNQL&r)N7%WrJ9o&EejV^o-=CUQA1)CO zO;nxWZQzaIZe(dDr%#%IH-X0u+}#Ras;Cb<{V8MK`*;Gy_v!q^CdC-M(sY`6%Rddi z3*2qunZz6$sCV$}DNz#h{C~dA2QKRJe&FaGNO>mZRp^~c3T1H`##t6eVPa97MM;~R zSbV>SWr@WWEy^=kQc==kNj)^N*ksEll}mn`O)4t3+@zvOMUxuB@yDd1#hOhTzxU^k z)4Su_zOR?^dEU?G`S*GLKi@wW;A*lRE4tL{7c(3bz_RY7USWyNcZLU&QA+{|_aU3J z*Hd>HEX^A1n#ERJ9Gsw^eJ*?8?iI3iwAWnF4o zg0{?*^HbVw0$#fiHYaH5CfEIR*aYo{==%G+M!QscjCQ7Sou#>Kj!k1mq0n-PwHwZ3 z_M$MPK29b;Cjm^>aysH1ZIP|LJg`*u2jjm?{*@=w@*bcI%^?@_9_muN z=Mcrdhq^|~)s&t3Y-OISSxwdoqL_<@{b9z_x!Oik+s_%6gw#DwF%z}BV)CA(QYNSc zMJyd(P1MdaxfG>L)RMBDYOJ%5B`hsIa{)7i0ndXw;N~%1`6Ja^438(mRY_V>3@@OL zc15Wh*Jx*`+9WM8x)D&T(w`>jkCU{yrns6eWjY%x)+113?7PmU-*@0zceZweY3)yJ69ovZe9BujXqfaxzgd{GR?Mz|5hx?n;n4j?BF&-PDUw~{`$T}YV4)tw1 zX`ePvyTauDB?-*a9N_ZB{bIF_+Ve7dxia~_^BD6e* zj(80rq@AbT5RI93T>`xUPvR&Xrr zz`gJ|16~b}3dGOPnvGpzzXm)8-yNT!7I+6dGT~16J_G$>c%uQgxEQ{};vs!WI1!I3 zg8(kLH!MIvKNntTzzgAd5nKkAa=06wC51il?%|RxYGbN4%_dQWR)TC!S_ra|>f4#B zrKdKaV3)9Cm*m-=&PoOzI*v%=cfzFs*qk(g5rk|f{XOeFq7u@AaL`E$kN+F3Wf4Ly zLiQq>O%Vb^A73R}L=!2*wH5#9!~_0u?;6i^_4y)gj;ZVb0WZ|H#dNlJjW#nv{*n># zoeLR^bKj@;T&OKeZGFEha6=>{zr`6;Vg#4YQ3>}EaOXwZd{uW5DVsm=yB66JKM1dL zv5R#HXAdYGyNLd<79njhvrc1#rWm3g&3Y6zFQ(W{2z${qIX-01u~=rA4#Hln%}>qm z2v0?fTYEV(7CZqtcu7Sz!dDV->&049bRG&7>f4L8*~G^IllcaGk6lbcu^-W| zFTwPQe<$hNJUokV3I1+zU4nl*!dI6t_~drdNz*9Aj?VCAAl7NmoETM&!d?`z_eCg3 zP7{~W)(yA|UKhb7!d!SI5vIAmBf|Rch_LB9B5WUva4!*>+KGAVi~3p0n$C=F{+Nj| zU0W92`Y}5IwXI9Hsj74>cGdvy&<3AL##*nK7}X9Ric+UIm}pwlnP|M9V9j)<&dM&L zdX1;6s;{I=c7+EQJ2b%8!b8UhX$39tl?2{-sWv~m3I+d30UmNmKugxds2%XdeiHc4 zZ&-L+L_)cEyWmYkIQKHL)!fa1e3`a9yUG{d6D5WbG|LUR^(rP}_`Hx5C94j2g^$ja zq0LWfM!~-nSb9p_wuw(q;BJ6l-O2x66!+lYrq+MviB}slI77?n#qt@n%A#JD{_2%9 zT4m>KEq0RSYRZRab{0K5ZiyC~+K7fU=HMlHb)(e`_m5Cx9->nKACk~Zh}zx9nL=RE zSGh#9o9gk|55aX*up2vq}A)8*Q-nBq^nc(7P~vQ(R;sxQ~9GY0_)V-d?Asq)Tj zb{OzNHUCdqf_mjeeX<(5T#GlwA7Rd3s;#!wd=}WM1p`V2)VeX>=Ur;kQYv8h3x>0$ z+M}k5A$n1!Hs4b{6y6A=bgj#&2?Oqf7sDgl#0b1Hf{Qh**D$1z(6LO0%VvbR%e2+e zabI(Kqt@S~Gr8WXnJ2ZP<@}me?lNZHYCLNK^ZtLAF-H3ENWKD7mH(RzU%|R0_bA=_ z3dX41Z?NJO^rBXTxmRjWm_}j_@v}>eA(MgmP~@M_H&Gk`mOf_i#8d2?m6+HO8o6tvDoB~%muBv zoCCuvWM#v;DqEWqZJkC$>XpTw^VDp&Hr?c#c1WeUF^kiBNUd{Y_(Fu8BJ4ppB3_lJ zW8LMnTI-pIMt4k9FMQy!tNWL07n%yDQvvvx8fP3*rfaBm5t6SV&_0A!*HBxvwnJ*m zHQMSJ*UUqsg%i~6>&eU1Yqf=@m9q}1rPrcjpM6MexRz*EX5ORTyq3^4kgu*~^e;b) zY~>*2&pD)ea(z%wi{w!KOjUWk<}^9852-h=rAUoD;$j%CSPd!5R zY|b@?RxmX+;yMP7$-4H?XxT({O^G%`73FFf(QB_eG}@xJl`^n@kjoOlcRiZ9L=crr zUT@GA&2r`*3LDXLsh*}ASr@`buxLM@e|hx=?GjVV_XtV|Q^ofWsnqXbitVOFK2$O$E3e^ay zKjiLO;{&wd3F>FFSlrzAL+$d^f(NM$X?bIpH1%N*$AEAtZSazj+)}_!<{^x{mfo5F znr@!tf+RrZuA-oLjb^Eji)h=0tEf8H33siyb8+uc%bo0u^H{A<8X<5efoXT=p5$1= zh>Svu+L%IJJMtKay$@rTJnEzH5z3s$X5wh$A-<}qZk(;tpH|b?hkj3XR7X~tbi7x`45p_*^fGHipd9SR&q zk0n;gU+1k@^)-5%qR!8$*r(=(4$shlCd>e<3C>+b@KqUbMnN@<9KQkz} zQApE>VGxCcpf7(VhI$l+QP`|e`R+FksofgmZq@tPQ>UbD2%B{JPTL3cCJ_ohq#isP zj{+5v%YcJ#Vs+3DJVeokut9_&gzX~4e#9UvLOjB%VlC;(rOXko^&F-E<`yuzw;d#v z0(PcFowVix#(>3L=&oVFi0USqHB`#HUKt=yD_AkI-+tR>|ckaI}uEUWTs$7x76sl7kTfZFf+o-AhxZBd*MFh;3eZj13b&tt+o(L zbeXN2KC;}Y*;H4dmJ(BB?;b7Uv}L6}Q>Csay^5LLYTbI4(IYdvN9)JV5Z1GnSUC%0 ztS2K42+6mzQB0iO9o8Ww6Sa49d;$+$kV2>wlD#vNMh%sSKuLewQ4FX}}JQpTBEbY}BA7~#rrA63tL837ya zV022DLsPkf+N?%ME~3UOlc?4r5~xPlUPK|=5Dpa47;EQs%OT(=$%LN&BPNQ%b1~45 zuvB$GSU73;UKZ&%4hoGuuUk#~G3SZp$=zylz0Qj}8(0tG*!yEzMoV&c*uauWp6y-^ zVo@;NsV(#P9OG-&i$c2ruaQ=i;@M>^l$$PXlGs|+R_K0lP-aj!a{{~u_ z+P0nfto9z7$1dD;DqW5o-nobMM%?$P;DtO|;M&C6635(oNoXy?ihIe`@b}5gy%;e6 z2UPF|Qq2D$hT1@>eF$3+Y?Z6J!?t*0v61qLQ4OoQRnG=#26^GNEDD(qP-}U#NH56^ zBCPVVcFkSQa2A+-YrUEyrsT$MIR}~bgg!?NdATbPdsBDVq$cB?<3S$IyNQOlkz6_Q zF%d#^ZGJcB?w@rrKW^KoC7YZY*4)U^WPSk}_iIb$G(JSF7IcSg*d)GIcqe?v*n+{y^Qkt z5Dt`4Z;S7yl7FhD&-C6MUJfxy!y^p*@CNn#Q3k00{8T%6b|-8Y7P=TelI~b zQING8y4B`Q+M1ZSjkF#X8A+^tEajXcti6u{m1Fl7ggeWbBP+`=RJr!(%!&sMiuf}| z2Y9_&|98$}U%pkFd{QUuD2zkY-vpWEF>WI~6mAL^YzHjT6uI!4hsef*Sh@{i-Ghv6 ziz{fI50bGOg#8av2=l|V;D>0h#Se!YKij1MK3Wew{6k65tc`}4PM4$0KB2~V+ zlnr;!Lo8tTZ0;VdF{#fB$nFId+ALGtV|14a(#S>FQb9#KpJWiPz=l<-TP=Nh?cHAx4qQ%D=>4u&#I|yyca{U2yv=WccS~xU7W?|C}O3 z{e@xUaq^juu=H_m@3gjt_a*5aBU>?HD}&kNR8q#;XK6VO!BhLN{0ln%9H+iJR1-G|KK?1)bGa5z`ZezdNGS)rP$-S-hgRS7UUU>S(}i$E z5vs!6qdYZ`l;|GyW(~DB58;Ri@d(qNLP$VJLr8^$^*bqR^{*IVBDjATgC8aGEl-i| zVu}1IZCSQ+Qcu_zB{8_RQ&$E&7jA)Df+pmzw9rC$)TAD@;uqxYXiSgVAc7Dw$tT2q zL9Y?K9~@&Qf?Q5<9%9dX%2sWLO;U;+JM!wek3#sRTght*!q%-sRJE0e3IZ;k!bEs; zD^=i%?NPQ`T21^ZJ!(@eAsP{O*D^bHP3=*0w`t3x+v9pTSn#hntF~z=ri9Z7ybW{5 z%_5gi6J{;Kx~Hky0fg;O)8t|kd&2s+^xC`~G}lBj_6#*-PD1k;?S@(Vl6u01ZZWsx zInIjUjbmerqfWENT}L`GiAb?P)hzK1xT3JqgMTrHDAHGJ?h{uwM8*4=MrS%*s}Up6sojshkq_5M?QTBQ* zGrDzg4`&zt9l5ujDaUe2kJ?$!IBrSn2|GCxYgk`kyO7qSj@1*T4$-g1zZ3v#;mz>}?%I~n@+YWMK9{Y- z3oN*X?xBibph5@l>0$chu#_d}3)Fqqz4V$FDC9hEkNWBbZKExvyeDkU?IzCpJskCx z_o&S;YRgj_Q3&n3GJ05EX4MWCIe5t^kqECN;N)G50u>MTjCRJVr%UxYYUM61gQ=SK zwu>!%!Zr%Y zUl;$}@S|`#QFkh2Hr`%UnYKa+*sG{5-X9%X7|(P8fE zksCOd-lfetO;XI|pZ68EL~uD+P4~=F<&Bzimi2JBF`Xz5q8Ja~!z9zi8R{2}+H_CN zr#)e7Un!L9Rg4PHLJnTSbK&i9sqNq;ybvCBBz$NWBb37jKc%7mpO(Jd8KEEnJ5fl0 zFAm1WU*W^>47jw#;3W}SUZZ2f2Lq4NSbnc1#w;G}8Ex?&rrOo@zt=8It^YiH(vS$7 z2v`%rCBk-z@N-)8?->r-QOF4<$6qJ^9L>x^U(lKUK)WwP$VRXY4}}+24AO{Z*AVUM z4;*x7e%UiRFhSjSEzSMgKWHmrn*NE|Oo1j?vWF&E^Dk1}L*K6ahS*=`h_~yT@JPKx z>V1Q;7{1mV2wL&7w$jx2ZI9}CSz8~oa)NI(YhvJOo!kE?2Nouu+WJR2RV%{5Ka!DZ zvv0IuqMFs=nV~ZFYFVbL7@yj_mo~L$l20Ak%Q~UrWS>fH;yk?7;v03VZ4Y~9A3tyE z{1b<87N2^viJY#T>XVgeQcTNK-{@jYE)6^X6^>LIPW6rMnkZ}GS*r0B4#&+_B7a3& zwy5Y#pZ_;QD2xA+$|!h?W(1dh8oZ=3yznmgj=+5j@2jkVvf_Pe`>S+*^K@TWCzps4 z_tEa)g~3?(E3yloJKd+|zNW2@E>6P&p*syccfcyux5JEzL)=k1+42`Qk1pS6(**Ux za($MvHfwfUS-LN5MwUu0K(RXAr?Q*bLp5B68A6hl_R@kv>t#N*vsqh|8nq<6kdkNX zUujVAypVvBX9qlIiBC;?ovC2xYMnPQ(JemJ^E!i6!#aY#!4r$S?jl4;+>&PDeomr(;`2Y|9`q7k4sW>I=YJ|Wl-I)T zCBD((kTFR{<3@PNJv6a5IM4Il@AE&@84M^jXm6#PZSpD8n_7CQtK1j1c#{;1QAmMD z4&#;Z1bBQfHvWo!{TPqbZ-U1e#M2Jvp77`%b5!`FFN1j0RrvhBa}`WO5-`8b9mzC_w=pEsup;LK?mozV@RM zwRI=E{IV7n6IGAVGh4Kz(sIwIa)(#&G zaL4f^#KVb4XG8$Wz8l_3j@SKJTR5p4M_iTP!P7Sg2mj2YFKvIu#Zy+Bb!$bX3pzspT;>mPli z`TjM6UA^?KHY?iMw z=RLB$uidBae2?v9(MQt%-d?E9Jax%r$zv}6Tn9O1`G~pyZ>(5We(X~l{zjOLPkd_c z->~0~Lq0Y60Q=UuPZ@0wU=9)9JfPiR+coGLx36}8%u&uD3AbaxeF&a*va;)Qg0vHV z+YmN=pG{QrPV3?R_ixrQ?-Rs+)W^q!SkP1+9Y3ym|H1vN2rd;_ z4KF0%h7ZU_2g1$|$i~`H%JL!WvEosdGyaYKc`E-yE#9^V5ZaezZf@uzJA~NsA;)ex zQN5!M_1QfY$F}CiIRrOjNhupifsXc4$jXd8S^q z`6AC8_1RFf|+~6GAjknh3A`lRodUlN*%(wzq9Oai_nz%Zb!2Pg}s00iJX1Wy*v!G zeiEDP1qZpWkr30XRvaXXM1)NUrSoEX$IX>KANwM>o9Kd_+d$vi%YC~DE@2&T z2fR*}O-oM6*>>{NC-GR>k}a{-la?v-6EROltMfaVTfLKdm8TOk6~*?dt(~-rij#WP zSDmzz){`mp#}N0FUbW?8?i_lj^p5MC!+mTT;fcZQ@>gU_Kie4se)Tb%^F330mF*Ln zdgbY)@(H94;muEE?SE#kn)?rk4+Q!oIS>x?8GQe19z^#W_E5IY?PX{~?9@_H6 zj+yWr1N}UBRzP3+OW=|K#dx^zh+GX;j`7BzGJnPJ_3(~aw8}2lrHu*U0VQh7r`%^s zz%E_dveJ<`VU zHIbI)qi3#-P>}2mqOdZ8OV2caPFpA75g)TfE(&H~@Dhbg6f#gq?xkD05m?I3S7p7j zF^~j%nZ=w*y=uP*9SD>A7(j*s!hBWKr^S}Wo;|*V4PS5&l{B8Wzy}O?C!FZVRr4@> zp8>ZFaa$z7!C1A2QP%vXOCaf21ekLaEVa%9*VzYFMKw$>;Ubz3I(tF>_Jc98P}6K@$7`vsgM864aVo5=N_r$ zpUg++Fea!eAF}L=J4}`5;+D(?FOl8oMqPgqBCHi$9+=>1$JpbHYb?|enSRN3#6ZHk}9PEft zm*~AmnIPd3GSuYdczmomuW#^Sf&4jLFV-@v@=V~&KuvhEZ;EV8Sq4SK0Gr2 zE_kj1&xL0h#8U`g9N>;%M*Tx@IUe&O0=Utrg~y-A)bG>JS1%3m@P$2@CCU(HsX&{=dJWJAyTi}by@y@TG z3`ZzP4)Rd&8Sr9wy8*9+w;1qxcw+>YR?q~mhx7Rl_3Xdc5>{f@ga4vG)?%k3wefsU zvP$_{i_LDwZ6-wUlH3)JQd|Rjmcw^NaB04^@H$E0YliL?9Qz`aB+^d!o(L|1hv7Q{ zfs?Y^A`~Q`GsT83KMf!vyj@UN1+CV&Htu$d<(~ye-MQ>18$yR zifV#eh$MJP4(;$=2HXj+H{fn~O@K@Az$GoN0FTOrWc?^7aGhw>sJGwJl2!9jmSV08 z#-}_&fE4(NXaWO`b)qTC0gs%;9dNq=&xBhHcpiL&d=QW1FK|g>#dr(`Jc8IiqE^Bs zq>3;jsqX1wWcPKAv3ofB`RrcLeweV@dlf z$75eA`=S4E($$6r&lmi69(Nvh{YT3&jW~Oi>6o@=dCG<3tzT<4MJ2+`$4wBhej_{% z9=Wn_g$sQG3!kWDADkukcK``_f+S_n)|g=fM*% z>kYf>DZCh70uQZP;g#^U0e<80n8c$VkCg@in&4RmydAz69y+5qiDwX=0xwY8?&g8m z;ct1oBkwZiiT~1nTMQy9oMeh>G~ng%dIMeyuQuR~@Nxs*3NH@u@C}L&j{<`LBk)`U zZjCiXWg2h?+-blw;fY~cvqG%_}lk4vey7smt)6 z+f3BYndCmn6xFh%_lZ<}QFPqpz4F-jG&Yk>6ZM2iE%;Sl-uuK({RUIRQo>Hq7f#AO z*%UR5BW(g9ESa=e^}I=6q<%X=pJj3^^K0=;mI$NVBg>sk95~V@>fAiOg6=hua3fcQ zrj!_6a%Jym@e|MMXY<`Z^s2K6K%}Nl5hT?X3#sDRX(BIiR|oSlg@%PA&8+iWST=D4 z--PfoQv^E!e zPSWR>R^SoZ*CeZ!Q~BNuJaURlgclod7n}&k#ghxqhliHVZy$ILJeT{xm%XN+t_ovy zYpTQ?YABH#(JX?8=0ptG3NN4t{_jh-#p;}2;W`+rFDl&?k)TAAc^az$1D*#bU|0r4 zzZfnC2+g?gO1NYvlGnq>3K~8ZG~tnB5TG5NVZaCBDF)m;&BR-n;}f>S*O}Is0ZaR7sn-mdz`Se-~$_*Mlb_y-CQs-ug2o)Z@rs!)@ z&1=FpGX89x$&w_3yChq1>l$|Wr|9V>_syhxioQD4c`Ktp#Kh-}r;2Z5#0i#`zfS(S z;m&pJo2N3=R2R~rrV@jFeQ(%9Gm?i9H1pvFAu&iEtkX?V4eJ>mrjm#F+bLI^zQ|U4 zJL7JMW+8Gtn)!ENw>T`&hHxy7fiABIE1gP^x*~s9I37r{S3QFz6bc(qFg5=OQ=h7@ zkLlPz%O}`@5T{gZ=G})-72wqK;?QlmKH?dCBpNQ^!K&FRpr|PM5rHl=B zru7GV!*23R8C&3W4>D9t)6-|=J=7cav|b(x_L&Uva30LM^rs%1I?JkG7Ss8#EGX1F zSFzu}-^$cb`3N;+r5)65=KhFPf7Dd@IMshT#J+_+_32o_yM@C^Vhmm~mbqq|qPkF+ zdj<{VXf>5|1`|l)6S55OKl$8zhMo|e^`xw(UYYKhty(YQ6CQDAG9J`E$tlvA1am5y z$(dNO5n=0@Od$g`Wa3OcJtpTVO3X`C3pfc{9D}O-}@#y9wY)6kb zOS=%VXE3~1Kg0b7)Pk3^!1lQ;#-E`UXXtC96Q9NMYDy;0I(MGuv8WuIl>Awadu_}- z_8s9vvh?kyL^{q63WtKJ7~y~juIE_b+6m%*Zu}5Xz=QAkC}i99r06OXTGYo&xSuW$ zwVl+2XX0;JC#qL|ET=nmeYPp*w;Z(D^+lx zGBv!wJ;a&%YTL-~!efv&nR^aH*zf3Wv#?dkOZ1UhG@q2+y`%Z~2CqB>ADSh*8D3`5 zwVU>gua~@e>?+}svEY@9Pz*<3t(vXh;Hh~z+>D~^L!rumkH9P7DZ$wIEBe-R=|}L; z1|Y+$15P~ZNERQ<%*9cTBQ1g9wFJSFpz}KMA1OcrJ!NDsE&43le@T;nPnf{_X6w(= z=bGAH!3O8^bBXQeu?u)5++vc-AiNVL-d*5SHQ5x^9-$;zbint)L$fF?CKJAgz{zv; z`O8Ua+%a?|3d9~3P$H~{w?^notu(}tx^xEd|ikCKIpKppPY^KpC z(uP`JXU&{QvukM~NTR+hHSf>ki|JgzA_ty8@Zcrcbi<4O%tVsJxG{pTE=gZDvG^@@ zbruh*wk6Rc%idybk|e$7Em<=AzX{OvqHa+sXY28^nt_&JjQo{Iz2~!ef#;g!J34&4 z;B0+{sqL=}U}w`3y56P5oUN}mH6NhEoWqdT^&wsQ97emSkMKH&oS6U4usKhr8H5${ zQ10?Ei_AmE-p>p)k9g__2!1Ye(%_dA{9H^?^-sLcCBlraX;a5Pd{CRplmgjw9uXED zC7$zS=$_E0OvwbdnETY7$u!y&gssWw%%hz}P;OJYULm64B4s=Pz1(QeT+)rIod#nE^K=2QRVUAlw1Z zS5x|^hp*=Ar{k=&$G;YCT< ziA|}g3Snz19cM?9)FeCqz=4S+ogoAiI#!916XE*^Guer$IuWv+(kT%(IraH#63z|} zBDwPsB+h`3z@rSf^-^Y^h@_=74tN)Q>>~gvi}aM}Hp17bnRDe6Ag}9jlN!-kd=5og zq$hb0!kWEgW*CJO18%tt(;DzZcmh10u)#|Pd{=<;1BX1BnQ( z@R9%z-%54jvDP5KFnlF^+$MGjTQ9g|B6x|M2zMKB7d#7oqG0KPxjPpRmqCC+xK!ea z07Om#97fBix>(1;B+>tr8Ud}NeJahNVOVn$Z=x5o62pn1u{#<6Ve3D#VLO&Tiw@)oiWAw0`M~4w%F~aUNeSUO)vec>n zE1>^P(=Ul0#LaUU$Dcg(xb&H(JO_i0i+Q3Q!QT&uTzagn%Mo4}C;4<-!HNv6Y3Zz) zUGw__-?f(#a7k&sDCEOKGb|0E8oqMAzdt9Last9xlYG!D9Q)HbT*`R)C_2n_mXb$nQpDuPHu-N%AsEkhPFG=Q36hsp*S;Nq^XonU>Y+$*XBEoZJy0)uRm*{7j zyaY;K!n&;3*{8NIp$c{&99+T#-i9#waQ=3hLh4}4VcRBVhSu{Rp zonu;Lh)oW z=Te=wMi-N}OjHUH(nP32;CcNdTf^e8Wx3}D41#_tYm8_lWa-2W0{mP>tcWY z&Ye_w4Q9gOAHf@Oti-W(86k6m)O;<~FZ$4!jEnn5YxpAD8{EoBxk68fskx+Yv~%qJ z{M)b4FEQC&Bz*;yTZ1t9N~$|Aog!XIJI}n7o*cNDUHF+kRqei#HB|g%v@CpQW?mLv z7Jo~=P7d$;MsotY!G&4WVh#bav#7i(gmsTowz@1mHoHC|xU}<5g4e+3AqOwv!|)yO zp&;b1REXtzj_ERJBp#iwir}cm;eT|b07peecm^dVFWd`{Y<|`7VghftiW((KUf~IR zVz2co-EML&!JPO+uU*nNx>9Y7<^igNQ+4x6g)7*;!SdAVrA+e0SL@c&M%FNd2nA4@;8@%PWUhZZEm(BEz8&fxYK`xWg5klJ@thFE>$LLvx5q=H~*VBEkq5qd4BwtIeS`gM< zOCKv+fkm!m^HZJcuQfshu44W;e}L_7AoU#mu9*5C_HiRay-?34M&7SKsT1EpV2;}O zku2t~qh}7~P zdOf2}O&+QU(Svz?yw~kd=Fs(YTiI=ITio#_8kt9KO}uIq~$3?g(kGnV4h*-d@0_ z$r5u{Ut2)^oq(3QlKP{k1b15Vm9AMfM-$;Thl%UgcH z{gbN4nRk9b%d}KuwI8C|`~-o2C{xmt)Gb2HuwseCCu~0BO@Y~~^o7waHGQMaDqYjg zRvT97r$=W#)hEvr%bx7kjoM_@v`V+y%7Gby#^C>7T9bJVN6k->?^PIZ7{QjuwmW_+ zmdt~=5ccNji;DeRw>RpkrY00p zZz8r~gmpI&#PT%L*-g|*<1>W43A0-2sN{TftN~%+q{dr$d;!N+Xmnzo^u^Wf+_oId z*Aq>-c7$L(+FIGaHj|z2s=gSLLlB*YJyJ79>8VO_2s3B+gXDI&B0$Q z|7zDU>B21$yb+!YPl@2I@IrXxEZ~FZMR0%PhP&ZqY=mbkEm2waXj9b;kA8}&d^@@H zV3-<&RUR6BEy5;ffN)AgJ2<;W~z_hrEI z;LQfS7``ilOMWZib?{oX{zr7^!|SNSx?5yiewHS83pq?g=(&XgI1nbUg>)h;6(Mg2 zWn0S(xpK$&<$vdoShT>UcLp!1v|)G^0S|IcXR1Lk-HPBtNWPVMtBW8`zQWMU2PrCU z)#t^uJjX=M8}&12_3gLnd8XW*^uOC!`^PnK_QZ`4`OMU>ZqsixS)M1hbqsHXyJ&ao z*k|VN3Z3Nx9iy?Bp~8T-!gJu`IsiNa9@&vb;7$W>y^EzmAfE8E00$oN1_3hRmOy}@ zq5M5K4?gnZ_zV@p2jP+HsYDkVg#z*b^2{%Rz zxEpSThgPPTaO!0 za_PV$ikwZmU7w##7RSX{jDo}%S>2WJ*a%)JMuZ>z9Y(yJW8gi+Y`X(%9z|FoLe_4) z5TZ*OWeLIS3U+nq4hHGAMrP$Z*wu96(K2>2erb_@d344eS*XZMn(9|Y`WdF2Jxqv2 zbcWo3z|X4POH;)$`A5(^gw!8#4x90EAD>@a|6@*nAN!Ghv8iz{1I3S+exhC>S3j1u z!K=(nKjt>fP&4Dqj~Nv6U#Dx_iI@2eGJGeo)V|TjcQDr{F$Xo=$>SNWH<`QcWc_6R z6Gl-}783on#d5&;CuXf;rbzo+j07UM_t9DJ;!tGmU&d5rcCcMCa=fPJR@M1W1KCbhX zR^pLi;872E8t^9gJOkbiw;S+5c$@(@|CFlT*H=0&M|M1pzBN9lPWYe!cf-33cmcfK zfP3Nlj`JmfN|P$6#-r)D#|hp5-vv(yApid|3%0=b(4Tge(6gHn_-NEwldSjqV^POS z=(41*lJ8+?iKn}H?&0v=$aGBvF*02{+{ko;a7-6Ac}RxLo0x1!@dyc-M3{Cjf`z2h zL?9~VxtG4*{ueSWLiv7nVE5|FQ>|~0w|8+lgJ=YIl1e3fq?J{}eLBCmvVnDm{cYmg zKyl|G9NfSNRrwC(_9Dc+hoYAesro?Q=)S-=;QPG#^(J3Cx!NeXdfzYbjL(B?7jSGA zx;99Mq18AJLQ9+9AD>OTNXe+q34(rV}kjt$UK$D#4&X-6T!fDgj02Hd=vS~uW! zI0=pGtxot*fQPS?+<5p50u;bI47e9gvBo7(4R1E!4e&bJK>c*Y^EdlF#KpQ^LkL3znT2ARB{y4M+do|p3>P*4OH zra|JPl;O+qHxpd&J@CktPcFQ{fEU8+;JN;@yz1=!umzfQ zDj%AKXZQ2bTE<4}IsIz#yL{TuUBx&!<~YfVBk`PmKH2r{xjZH1eTWA&GjK<)^;*zN ziQrO@PIv;5?f-?GwLhfCMw1S|c{AlkR!imzcI@@|CReauZH)--H}%iu7Fc+4a-XLb z-ax=j6+FgeIk$hbl|$|k4!OH3^pu#2^RUW9^|R@unffqg%XIXsbq}+At#VKogb!Yl zM(g7&1`N0lUKYW{z9aAwBJ3f;(hd|NZIQW!sm*}r!S@*OV)zaNUJ0*(hh|u8S`U|k zq%amf_K1F#2_?1r5o)^)fxX{+6}MSVZE)E(v;W;UzhAA|ECUw8rp+kUEg*!D9S8?S zs72tROn$8uAz6f0gcX(gvKd+D_lNZv$wTWCjE?84Pir)OAQ#zjKJiE>JHq~N`Jt?Y zM|EBnCunH)#ol>OvY&uQnynZ-ew(XWL240t`f!+Mkq)Wg(wii=wh{zJ0a?-d`_Fo9;0RjM%HW- z%C3k=r2Or0hXEgi+YRC|KgFzQpl^qp13bKDop=n-ADr!@p3$eB<->C*A_i#W3q#EaG1;~- z(nc-x3w%^Uuo>6pEflpHVK4p@YZt2Xexof=3DtPFK$EK(pypjbMye@d)&>2e)oRL< z@}o%Sd#0*3QLD%Ips2;C68RIX`K(U#pFrQ~?B_?6j^B`*H25@QGoF*5gP$?Z#Qw)@Xrzli20x?o3 zMRqI~Q7FZ9?7O6&4_p&VRvL;m2z3Y~vM72mjcQRF*D}e~)^NMPhsW+3hQ}xuWkDm` z?dl)5aLN1?M>+7&ij)462cH+gr9zA0@kF@lDPp!DY7;x*anb!@t z172dlGvRCDp`%(R@#n$wFYPyt*0Q9KUy{19mR{MIK`W@$Z-{PNB27@9g?Mrs_alcd zr-FF}_S)j#Ft{xZFOy`q5^gcz_3)9)!yAQIvk5*xq}ew!QuxLk`?pc!M30ZqiQ z0cvwE3m?1k$cPVx3>5Z1L)%ZtqU+Yt72C53Qb*@3cGJb{^!1*aYx~0Q8AE4<@I`t7f%+;u+BV(->)i^|MB9N_9;J+`m8jmrNujq&I@_7ZCTsdAwCYkj&YrI7Ir57WLM zv%LEa=dFv&`qh@-aE~+UA;LVXKVVx~6<*g;koH}yD5|K?XUS-OK;RJdcMOU+ChvfH z1HxI8ilOB=Rtc>{NIsySHKzqyOU$8zgXFstjuKCsss*=myP;G=~ ztmpJO7dAgWezYlmiCGOEPb9%hYP@ocTgE;OT>TuIin40*{v0z~Np(NBSeKV@GCc9O z`mC5ePxQ-EPEX&<@R$8tGQ6^;U)}jzDk!U#g6-7jKe>}?^9CG?OuG=4$~%zur|Bm< z36OyB=1zJ}0m8AJgxpg{;T!ZvLMj+|V~8CN5;RU9vpF`gQv7E*U9Wi1By&>gb}kWMRQ00sO$*@APC-;y$eR zJN<#^*w%iYcS+B@iO*ZSq&sZ!Z--~TfV?&BWjuSEjpWBR~_OY9hGA)()>E;NIO7+W8)(@8M0;%vYFM zaU?g=pVlI*YUCuQ;JxtSRN`$!GY38oId}~ zC6IX{Krlc4O+(&y=ogRan~!S;mYkJvOc1iD82dPIJs$HSN-S&9Cir4Zwf+CFSqTCi z=B$&guW{0ic6IP=+N-oUmH2zsFfFL0{hl7shT!=cw`s^XoqJS@IiQ1AfjM2{-?{# zuXBQRfHl(}812hY2yLR0dp8QjDDY_CS+k3ARG}1FEuvHj_o5`fdpx@lN1;Jdt?&|* zcJHAoRM!F2QkS)ThR@TWfFwsP6a^d9Sn3>Yud&xbz@?{k@?n)oIg z9~374k$zs#!D#eH4n*rdqLTke%=7+Eu|&v0u zpSW8OkL;%AKeL@N;CA>fcxbgq*_`m&2rko;8(sl-@y(QrUg4Ht`6tW|uh7^t{=u+$ zrJm$}V`I_?dWDdlS13X`g6&m$Mj1ldLe9`C-{S0O%yCjvz`-gp@G5}(8t5Rb1%<7m zZQmDgm|l}Ht&2Ebqi$RX>kv{iyT+Hdl^|$_y_71=%?B?d;QrURPwGXXf?wjkQlB%~ ziKpu?+>60;RWtjbVjLp@2ahHk8lyg_8^``;vQms-dL5w?Ax(s}-ApdCr6vEB7TZ0( zPqe}dQ3`yQ^>v=WEjG}y>}RPR)QWopts(<0H(CWjtsK!J=5f8S60Ll+Sd=g&jzzrn z4Qittdh88~YHj5}F5uvK?jAp#ukzpI7$c`Ad_^H`qZV}|-Z;i1+fpmsMLdz*2cKua zN8r`~mvK07Ny65*S=~kika}~#2g(1m79J3f^Nnu}UI_>f9ib#(HGG)zZXlqEfNFOO zk1I49#E|$72Nnk01+R|a(ob^X&rui*Z!oSoIdVZ3tW6V(n9On96&LKurh)T6Bt= z%v8R|xzMK^h%$P-&ciLPYgl5`?b8#oeb5s&4osB8Xdi_~4k4DmvC)d)nZ%w5@A#Ak z_7|SlG!KSbS!_{`!qFoX>n|Ah=x5;yQm>sT3>xrZcvl3MPHZ_qKmDv%TIx*uTVze`Qr#^-py7 zvqfzAXFo5W`Cm+|-_Kkh`xVuIM~v&MetCb-|8wJ(R#w(K@JVf@DmsVRNVHNF_J0v= zP~hWb{HpE;G<<0C+tghX!n(KhH8BNWbHu`{fETdL{QPaU(5+uHY`#NOiT|cD-=S^i z{Cj*^eIGKNM{qIH2t0*=J@3%f=OIjfS6`Oh^v!tlmv=A+81PzneFT@78{swI(Bj@@ z10fOS1s?pgFW}|!p?CFIenllbpZ-qz5i=9KaO}shoNd_A{2vV5#*_cU5h0{e))T@< zI-A?56E~WB+nBB6M;LV9gXAHkzJ~=9zxCG=A42&%PZi+U`5tDkMCf^sN*qQ={Tt7N z=8Uo&`y0d=HK4xw8#=8B?8cI8olyf}=NgjX@=jVA3hNHg0ESV>Q|qfacsp`CuLrgs z;Pt@x2?OdNzNUPHY3*cg55lT;J>6!XI1tt2&@6PvSVTo|yeSKq0yJ=vwf~Nb7o}hm6fqt8*)jXhj zK43!?6*HjHK4c%eYtn$){~=jQh$U|wdV1;La_ z!&mzwCp^eT;F1hkyNxsC_zs@=9XxN0&kIH##S?1MsEY9znM^Hx#NDYpOL#3w4w_JK z8}N3x3vM|cV_>)(gr^wjn|oNt8*n>3F2E(Zz$L?^6OSm%fU^BvPfu+)WqeANDAYx8 z30M!WK4m~{CZK5;VZR98sRL^AL0bFb(3(3yS1-iaya(Obs@Y_=G;{HP?u4iPgCl^1+2PeDM(9K#ZuWqB^B)wa3c=LHS#NwoxTds#^23}4CeRJL zD6b1)YZrYhUxfJ_OLcY8CzY3nuwr?K*1{$A@@_d?pfsJ5EEYQSquz8U;euJ z*N8$F3R@3hk+pM(3eD(|IRnAp|8;lki8j~V@VrU!>yNO>n~N>G$&v`WyD3gB!dKn; zqHBBviEMv)gG|5h6OAd*E{oyq@Z6BhiJ>ataft(?jj`%RAH&(>J$!(q+(B-A`o*&? zpE0)256_sBP>Jx0`Lrk>MrmF!KH6dwMi$W0d}O#I%^zJlXYJ#ovV1OQ?f$6dtAt+J zs$I%3+)Ja$Lh$rbbP+c9@?>@8r30h<0>JT0N@@9mVSdR#*joU?6X9iW^KtEfC0y`A zxYS+n68&6wje&k4yga}~EpSQgl;csfgqG7s7K;%!Yn+?y>Z1s)xc2rj+%{&?^!gdf zEmza-)${%Od8)KuKi5>doZi>3-%vW7GZ6NhO_GN5OU~}E8yFoKOHKaR`R9gLUO!gp z29G`#;$QMV{44P<2=_l@0zZe~Pexip0}44PbO!EjGz_qW8C=0MGeGAs=Ter#6smIN zfXY71O2oQ~LWtnXrvg7kNLYhCKIILN#kWx-YW=73YZjmCS*Ex<=pjd#l3Eb99MR`b z?7Blea)5hVLq{-J7xdT>YPk5v;Y~!$;r$ochKJs25MB+>gG(n1UcwvTRqzv|eW2!B z;C1lOGf~m+9OIZcd|DdDqn-efoy_tzO~rsG!YkpC3s4u_Yru2ih42#v<5%9KT^8aY zC3YWwpU^RD?VaHz%0sUey%IQ|5Av@$TR+n?O|iv{wVyNACKS`JqsGSN&-J-6)gfRT zz!ZBIL*(Z&rXZNUK zPD?uP8Bli)>FJ9)H-r`_V0qs+L2i^!%XR=2w$?9 z&-V_D+mRHbP#nRfKUTsk2x2yJP<)^AxQMR1A50goyjizOFFB963S8Bh^C!{oJ0h~%|- zn7r=6wIBb~q0;erP5dw0#z!{po;8{hCZ?Aow#~^);C;!L=3t)LlOf&zz((Oav_vTvD+_ znWH)+pnRy!iDLwZ?cb!5aQ}c>`fpNMiQxBc!P|>tC*G-b_m5A+Ji#2*7{MhGJA7X- zmP{OjIFgUDl!@Ckz?(1rcj9k9%4@~Bn~44>-DwZPK@keeDfKr9BM52Vupw-CaA4GF z4%}0H^&9;HQ`IA^1HNHM9jV0N|KTQ;tBNN0A4cdA1lutRQT%h};A7n9=v02PXtE5J zj%agKZVgE~dEd}6qB~8yaCt`971?WvVuZ=J7Gd(YbnND*sl{(ux)eRbVDT-n@2SJ< zzr^nPB?SUTZrBe=ve4EGZFpu|!aj3x6Vb5u)&wltGGct-^H=LJ5vec*{z9-b?# zXNEsnpZP?chxbG42cFpJneTDe8_W(To1-!ecp{u|<7N{Vd|m{X$v78oC(*PC9y%(* zh6$dHrd`i5Q%>-#G1c#+$|iblFztB(n@{wxUV4!RAwnlYvWZaM-!V#=Jlwo`iN&J{ zucF-;)Z|%js(%?1n>{>v`A5oS_N=khy%xS$a*~I{Q_NA7uTkC6o<-5^D72|-|ozdi}_;vcsA{qK(Fp{{^Vmymt5JuxC2EK6jc#P+Y(!@8zlae~H z#F?Yw40s}Z|BmV>l+wq5*D+*Nl_+I zrW}NWld#wxglVy!BwO2G1~@Ydh79Z<3s0pH|8+pEh$TquetLljPK4dDn7swzSS*pm zz0KHll4rTC^X-AKhjzutji;HTD&E0zCt>7y?+$RblV+WF|CK$xr}|h?|F+S z**5%XxQQeqmNU#zzE5dH7P4G(ghn)lgewvJkGj_4T^)3^;;0QeMsU;z9gZ{2Q4K*y z9*)L^#N85e<&vfP_Rg zwg_9NdXiF`(TuG0VKjF|@JuP`baPZ40l%6`EtP*pJB{=3iLNiOtO%B`sQftWSM_gy z*^^Y;rF?nXJA-up9iED`plWypnj22_q?b0M5V>F+M4{1un{DQ(9R}PEuQlLKI9VDO zzZ+g2;NdIS0z66#0(jwt2D}=cZ@?Sixdyxio)yN&9%%2x!xiQcSP2fpQ{X3-ya8^p zGYCd-nW_@u2~r8us20~T#;j>ni}$~DFd;(|4=a<^vpOav=CJ(Q`#ZbX!`^T8TpF`) z(&5pPu|u&wtLG9^SL|Um_jJ#rrh&YPnxEr*ru z3{Sc(bIRec<|PfW5(Vd!!|Kj6r2C(8SZzl$b>%6C!yb>3;l`T4S|EZ;5)Sy{sfYdB z?TZR=xZ@6w+p?C65(Hl0a-b)R-v?G>RiATagDdt%qLo;E(dytB+v zd*IE)5xgXm#qj)T<9Q`K)*7C^R8BqoDEiL8Hl^|^?zZlZ$C#ZcGddr?q@1~~d^i`}z)V)aaQ@`u{2Cub7d z|Fie~@oi22|F>(pWm`~Igmzn4X0c^kw`E&xon>^C1x06J8QBunSy9w`Wg(emQPvT} zZnkw(6lF!MW47DoN z`?v$*HJBFhPekKgmb511bLArr;3?EQKg5%IO(s~_IB04-yr3P4Z$zTj09hGaH>J8y z#@G#r9>qo|5lE)TG*tPa$yo824#?|Ia?PIA1_EIz@k69LLC~6n3(XAxZ$ZUxPI65h zXFfI29t%N`Hw9`0-j*VN@em%U>RE|Lc3(OfxA>jIv6EVf;>yWGi^rwv&4^JaBiiYw zLYfm?i_>bSBErb~=8N}}PjF?V4xnK71W*)DKOi5P09B@EACTu8VW^rJhz~}{Au;w4u@2y+0TdSLh6-NDRv^o)$Yvy6t6A{4D=O=P6hTStwBWaRwF)Gb;!~j(6 zo(Re6au3L7p5i($t@L!*pS)r``lvm{<;c`8Jdp5iUI%LCW@{whLImYWt`%u+>w&}d z@>6p$qAa|(Wkd@KyQ~M~=O(#kyBZfA7&2jG%|HwTKG^F8pBCV?D!2`JRT6Fiy&HIF z5$xUs(e#1nzPW<6nM26iQW0IWoM65GorzQ#Q=~;rhqtv z#Aj2m9?Cd-D8shdm{3%3H}HY8hSGb0_p0C_;GHUXE$}GeiR+;z6tt*RXb0Y?g7*Qh zSHX325ZhF6Bk;-uoYzCSCx@ld=8c&7^94!mvgf&3v2^`W3irGhR83QoesXpF$C7sGX?yCyEFOd=2icY~lp z1@{2=0M7$W{1BcL0$zg#*H4FYG$Zlcbi~O9j2ZvY@(cow2zw)Kr;(xO$=6(gmF%5* zOly8%146Lbs41PTB&N!(*_awN$bFWLwWkh=(KC=RA%SPAD6ux4z;jcC?4NEM4>8`_`MCB0K6tSt@Fw6jzy~jI#CY48 z-bzp6DL;kkoheou`Iw?+y6|+$IS1tBvoP;eor@?k3rNcnjKTsWY(tU7wRm{pc?ZO+ zv&KE>Qs&DH`AdsyWU6#N<{OJ^!HLBeBz7z`=Qte>aDjYc_sWyKexwVMXav)hz^y8H zJ@9N5yal*H1@8o&u7VE$mo7M;{TFjwlT-VaLN0SLKWQ#GAYPFx{-)-Nxvo=F9hYF0ih|S< zN=%h|=R(AO_dZb@fmOp72FRz3|t5}ekj5Q9s&-L{Bh(VRS(=JdOHo>wjlA%X&6ZqiOhLe z<1}7+0Pm{${0FQE{PQpu_g@Oqd9dT2%dj4thZ(JGIm9yGH8rzmd19{?v|gNt1q28# zo{vVeE{B}vW9BMxqMP}y6`74|6D>zDRJs_O1#4k>xnQWa7!z48mW`b^fT0CgEf(LD zSfvnEn$Ci;-30Sp;95G&UnYP03#=~hY%D>_5{ZQ%9Kb78@KWFvDtHBOj|yH5yjTTq z0PZL|;7zbP(Qz9JY$_Fcfad~Fz8Kf!n1@+fbnSqd9F8bih>fbw|o)Yx-_Y#aO)-zxIwUc5!_l(ez*wsZuBNPprCXw zLGFj@yCzfLGBDaQhjqtjsRt|HmFZ?qIe-hiGifnV8=k zz5{rW_o;q}^3(AvM~$dOVU-X5D}JKZhD-wp3}`)mh}L?5Hvvz+PpdhP@MK+N0j~#r zGHwB0t%BQthkOUJhg5K*z>f-pha_yn1KbC$U3spl!^0rZ;6-8Lw{1`7xz0_qY!DX> z=PeemIbG~BrIv4iNEf@#b45^)YzHmp!#-5-PT*C*lgB*3cy?SsIE#y?j0ULtK6C?8NP-Cl2EAydPg!HR5RWu1Kx|l>H!R62G9zl!NEGtZ9xrg_+)ZGjj7>;#Sd-h$%Dk0^U!Vxi6!T`7JI9<3~j3E64fdBXBq2!cOQAzLARpI|>HR8#dsDzzeoOBj+Q?c7ec3b(C)raT-97 zemC@dJ`5!fiT&q8U5>l4^(sG=;vO#>FK}geeaIUI)f8P8+c75KgMaHKa6j-G;KI1# zhrla=Hvu=rL7W9%54;Vy;3j?uyajj%wV!y!*ogw^o}nEK0M7!R+(E{rxIO|d8jT+! zZ3b>q!SjF{6L9n|DmYMJNGKq@6u9U(xq}MedKJ7Hc!mnz06bj zF2f|Rf@c92l1paP0(=0XPR4D(`+<9t3*0E^Q>owq-U~c=Gb8jT^tDW%+{sH0#~EYW%@*h(0?Hc+EqqYtXctH@F(<@e?njX zC-g0X-m5aQ&OfOz@FyK)IMfGV1}@wzam3gg9Yp_!{|O?;pHwIvR6)@Tz65>6pU_wT z34Oy*dYy6;pp7cXdoOm)_6oBcqSO^+#>sdtaAEezcp-4%Cdqg)aN$)3LhoSu zk@F@ znk`0wlu$r+?FZf$8Y-bm;9bB6kIaIR)dTMcVUyxgEZo4^pnn9*a=}G_;DLpSqjN!P zV_?>0xU*b{&W!-$he%h0z=;~0FT*}>5CnsJ6LRbXK{@c`i=F}CWh!`vTU~!<;A;BI z11|IjQ%%&90|j|h5NBAi`BLCHDtHBOvkG1f95P85m>DfL02lgmi`FUpJiXj?a;go| znDW@lsaqYm`Iu~>LS(sDDkGGq{0HyTvVtlV_9`!NU?JY1(tkb3>ws%SKYWP(TYy)h z;_}j!6OYIPFaV$lgw1qgsQ7mArhc_bcOOelC3O zU9(bqcS62SFlO2%?la@XA6fE@l`j12$}SknN?cEdkr=%SKQeB=8ct5=q7lZm2tf}j zB~w#F1s>aW6nWJy)xrH>-HV(gBB;Ls{eR@ER#mV}!KhTtCH z6)N;0;64?+7I>)&-UPge@I;4hM}b47LLcw~6R0cdbA{l|_s?g^G&rZP6zp&gw z6c`f<2rmW>Sq_neAGl5huLLfs;Pt@!9vs?Eix&l5Dg~Xu+g0!Z;H@fn#AwIVrpcTZ)b5#p)VHtyQ;mn=XIR1qI zdm$mTHhQ&ds<#%DSu}LzTa3TB1VJ2lvNQRCt2tREaCqSm`g-8WPNujuaG@tFULJYW zgZL@#KUTYr&I~5CAb8HW9(#wvzgLT$A|&P);a_I0+_Pq-c9i)h>>Hv=EC0~N zTwYOwr^2hvH=`o(X8HT;a5r{Z2^OLqFTw0eV4}XgFwqjY zdk+$ym0;^yYCx>I9=BWS8iux2c?)6^2sU2tS}@$W4+JUlZP#FJ^7-|y38}sN@FeRE zxW8b0<4sP z<$G>)E%N5Ro>*A~9L=qm7gX>p;6@eP0$i_x+kop-a5r#?@Uzh!9in3o3i@6f%1{V+ zR}wBpSqr=!xDh{Yco2Ua6Df7&46ka!Lwxa5ScrEa96}-uS0uKrX-&zw>Sv%u}bnBt>Z?25_}`b6YB~jUKfcjBo37!csbs}TIFUu zwC#Q?aU~|24c(6C{z0(*W?b+2L12@=UxdemT5fjPQj3}~E#4v?9DN(Bl3TD2DAkq;cX^@tr>`2vsY($xG`EVn!mRL1+* z67yh&*L{rOeya%XQ3Ur}ajjdN8v!0}!Y{Lj^K zvd-%=r)GT$Q}Ndi4PT>8B+~M~M#zz`ISLDh+KqTv%#M5&JudjwM(kxY zg7DBr_`K;GY?%3x$VCD-^6~e^-wcgb^;;lr5bW@yw;&Q9iYgH#Mjv#YI?8r8hKXwU zg8=3IGM8+^PiZQ@g+*1)rtb%)hm#g3* z;2ssc7I=vY-UQrDxNr$NM91wYu&Y$)18z&g#rjouAFjMH5uu-HE{#BJts!*chw)=>Xm+e%?ygBsupk7*{Xy_;LQ3t0s-CydPrvS^P3(-((k_ zk4JH;?`KHsE^M$?qCi7zD&K-vV+g_kt{a3~kj@3}LB$E1(Q_1u<(pyg>3!g3GrY0k z->~1!P({`+u-^)7r|JI#D;xB~OEHd$2QVr3W1q1Cy3x#SCTM zf`FAVfY!IT7BA@-7|LJUR?HH>vj*`e`0fGT3ViUCEbK%hE4bXf1MB=+9}2{<(ef94kY%AqRNp6<%7Y0%4iuF$9zaAb}RHyh{O(&XhLGYNTgqNP(CCQ#Yjw%A=XYLTr!Zn)#w+A zOvf7NH{LkTHhlW3Afu}f%Ad)Id8W0f8-`gGuRSQ<)coE-OmpJz4#w9$1b4kQQN*Hp z6L7<|P(~Qli;y@Jb}blNa$O>&&|mSx2tvR+<#(UJfAU_t4NoFVB^bswsL_tZXWPJZ zJ0Y{ZLMFwJVC>f)OxQINxF2{n@MQf}GQ9~j@k7wp1J46}P8`J9h))Y}H*jI2bZ=-^ z>KVAGynom^@>|O83z!|$uBdN*9O79IJKu$0XxY{e?brhXs|p?hZc)K& zft!+WA+09hS?Fl@E^Meqk_f~Ivubb!30zo6{K!MX0vz;m=7R`89uJ)BL0E1p5|04M zOuseJAjP1vp1}6Utq0}QD#)P_iTPEo1>>qfSrTsC5k~f zoaRXk%ZH#>1&1p^V*W#rXv>B~O2KafC>u9`yN57i8E!v#IGpsVtE}C)B=#Sq>l#!L zhY)}TxF-MuR}lIt#mNRd95^V?dKkg1C#(!(9RREjnc@$gjKZ=P407u7)iJTcp>n@ z2pWIVwPIXLL!vT-99uxp2waO_Yc9ldqVGS6wRLbG^!Ow?Pj5UZU%cBjah$F(u}`7L z+IsAXy&~LRzPr~oS#I3z(x*C5<1@T6B((yG(Y26sE2@f@Dy>7vcGqGxRr@N2U+Y>i zHn%CUQ6n1Fy?}TQJV!oa6xd0B3c3Rw-k|R~&s&9pWWTROg^&tf54=3710ksv;AOxy zNXHL>cLH~-v@-zQPI%%DQ^p>wMO8X50~aGp?jR4iNu>h^@GKR)6nJ_<`@F+cfdWaT zgKFSCuMd?_1Mm(NybX98@WEGTLJ~c|n}8<|K;w-d#Huuu1-x1Xw*U{TbYKHsuF`=U zc&SP|9^gg5y~(-{p}?WiK`n5bN(W8Ab5uHL2X0ou`+yt%*FNcAh)DM$bfeON5%|Ds zLsgIqyjKM;1l|ceSp~(w+khvk0R8(>(5TW-CGdI`ydHRsN(U{#!$UfN7XbIGv@-y_ z%&St6@e+QdqtbyHxI?9bJmC2%?Kptvs^F!-v$_30{7*CckJwC@HUQfbGt*9*5% zDF~s0N2P;W;KeE(Gy%7(w9^jUrh@kYw+j3Z`9u7Q7c^jnqf)^L+@yl%0?$&x3xTJr z;Kjf-gK)gemOA#MpkMy#npI=cDv|7=WId7{lx#t=jgp;6HdAr{$p(?k(CkAbBhZXw zH6`_IY5NqRLeBj{ib zOkUt-0nZk5qZkz*B5eU~2A&rOaTd4@xE;7P33mhc0T-*a_+duE1H2lOuJu7hh?wfy8Q)A=nY8h6$u0; zx%&lNd_>_+etGKKD<@sxXru_5JjhbuMwQ4~0bCD!Fumxy8aM*0ym=40Zo$0&`X21) zmb@`kOvYDX-N1E&c1&z&As4vw&4c1kBk=a!+Zzsw{Xv6#(Vi$0{VCwuv?7d8V(KRKtCVt&r_YSR>ZFk17JOv|(xZl55lOs(&6lT&3(q zXUPxmb#gzhf?J6f_Slw=6KbmON|^x|F1#> z*;02xeDpvB?eD-8q;C23S6#PeR;DBp2!k!%kDIzF-SYC+U}Rw=Hot~3<)(GZ^IylC z+!{xA%e!Ak<2@r2>$-(}--YjkAhpSL zb%}(IPy5+TRiC4}|>^@vL$WDdjY2L@3hf})c?zbR%y$P)~ zqqTymXssD_dyv@Q3_-+>eW#vbliwqedGN&+W%Z>a8eh!H+kkMTtT#1Y7=( z5Vb+Dwgr!8cYr_yxcDK`eIRHDE_^3`2we9u)ObdB!d1G!jllK5t#M+Ug@AH_TY*;z z{EQ>hcMjVn-UPgS)EA%Y#!HJv=Z*S8Uihx-=;3uB!s7_n4u^t^-^G4q-kFfvyBNB2 zaku>0ySVNOFHTf|=-2j7%o9ntkh>eW4;7cZhb!>#S=|XMJPQb#Ku~@bEc!hNZ2$?p zgAV_t7R5Rd8N7!Mnnz;3NJwWxQvZPP1)cKGR-K^J0NpQ&bx0f%i3}vBvM$!e~NJ=;bMFZz)Mi^k@sQn z{YZ4bkA3N!bGq@Q>{KV7H(m6BYrMAvc^#?A%ggY3K z+x;PewdrDLq77I06-yED+7KPemqFYgxvun9UpiDK^-LHiZJ&A>xQ^F!|6eU95&woh|-vWw*F}HthmDsFEH<7kR57`Y4oD>gtwV zQ9PAYc`YL4aQWpb{BhHMQ4%Ue{QU$`E9WM}u}{EG84`Oxfhsk(K-HhZmx_?M@l(V) zqX&WhQ~c_Cz$46k%L}dvTW?>fnOocm;oRCiHVs!<$4X7lGLj>geGp#8{vCQ$tbs0_@n&ifZG-Zl)i zYX|Ub6}%Lj_0G9X_?#1}ayAPKRS~G~g zLLlh4GjTcbV=H{55Q)2Z<@)V3M;3yAKPqiXWoe${vJl;IOSf4zXaa2VM{qQxbafA@SKa zaG2&0dh3LFbRe-d2kVNePIzHIa=SZSH>Fi>?Z#VQu6YM5*TgWtNcGwVPnbQ?cJbngRQy^M~(b*(tRIov(uqN(^tGz2_(7V-n{O2UOC zD}lEI$D0p+ScY4NyS{Us=&ji{RP8+=3;q4}u;L>^LBnFgswp2VhRsNZ`o~Tx}vT{~*Gydnags zc>Ozvs$(DqF{DZ2H+MIybZW10q39d^`IaN1ww@JLvX73H)3u=1=>Ey0&WC8cw`pPTY#ejIkN{3 zf#s+)=m&uq$>4R6=%^BSo(f(MJQsMfL|T9g#s)JW+UW$&BNtgZ1ZM*%5S)Dj&Qj5n zocTR$EQBTo2O=9N{lCDuK(O|En6G&kLaa!XBQg31L?q`!Fz6qIEg`Y@2ZTG_BZ#s; z;;|{mquqF6BRz#&`Xe5js(chy_9L!4a~{XCxEGd~|0HVnVyncnJMp^1fu420B4qEz zlDZcbn)?)%-9O=KvH0n3+;5amUx>#7TYqw8r}jUMOVgiSQ?JrLGgL6{LzvxEa1U@v z1rGu5Ll1)mTnJujfp-BH@4pt$veo|V%Ef=2VU9-6srg7`#&Atr{&$QghJm#ru|I}s z!TM}Behw#Jz8-rTWBXiFX4O8IC}W`)&u<8LNq8>s5ODuM-c*zUh z;)Q0v?_G6*yzt-HD#+M_RiOOaM~JCg{_UDDya;&@c4W>2@ZP^&Cl9X%(1gFGydHOb zj{e0peYQR_)aFW|`t&4RFi`%NKKQRDtIaILKVCMczzNtrkiTux%*(@zhb({2EpLwU5uT)fpy|V) z&q8APVYsus6-^&TxHG-q{XnK0Pu1YO#Er+8-^cce@=V)^mXWYzz|XnS(FffRbc4+N z0pdZ5d+Jyu5<*EHgyb0oApv*F@1E~6$eU8!6H;?fVK*wI79sIjiW^UxfnxARr!eut z(P@(YLj+31uJ|GFV&H~$peffcFK11jp=AM|UMdJQpf;l8!7l{xOv0?7n zBWl~BAgqO+)3`5Ml`a~|$47*~I$>@~EXG;+9Y#44qEEXhsm4c%lp+)1%z#)}`|u@L zs1_LmniMQ&9Z;=o-RdNiz>XE6ySvjnzFG`9; zNj@^7Tc^l4kjcW?BQj;kbi^0-_TfZUFa{;X$OyjcL?(<(9?lVw(RlIDnP{#|w2+RB z31{WVK}Jl?3SB;vDJ6x-h+dVF5@bYkg`zpZrZHZUi;M_y{i10nGNPXWkqIFqn)V-q zMNdjK7b(qka8bQzPCt_9YDA?1WJIr3B2&yIL6K?Tl5&xWa!HrSWRD_#B+*(0XQ~x4 z&UlrMa=@ApkWJ9pkjcT>Br-u{3USUBnLcDHAz`z~)Zo9S#PBR4(}D~NrCQN;KQdx? zrO2dckrE|J(@tbCK*=Y_%0)&j`V{R2k*h>TIm~$5mH{cdptB)k#n~Y;6uu>94> znS@0vMqh_S0kw*6SiWdVDbXQQA!i-so;;^gNcZ7YmR zvLhp!E)f|wm$*enh)FXJ36044krM{e4-ZkyMl{zc|1{El!aS|OD$toAh{7W!JQ1My zUaQF9`j^-enE_;sI2VeHLCzcHp60DgNxdgU)D^=Dix6VQM|5Bj88P~7e9BQ(^5G-+ zHH(rEK7y=Ih_D79D?XK?qzj(`e3YY8j0CA(kfn4XBMB05V1q-_2+`%Ip-3?5ly^;C zJxc0lo@xHV7sfIg^zpav5n#jFpdk{;Co3$Rph=n$v?#HNObus@BGbSbgUGlcQNd8D$W(YamnCv$Sg;Qw(u+(jLW=?CbdeE3M`Uy& z)5Dnzk+$511y6s~Z-L$vgH+g=o-u&p!%R-#bSx-MzYSkMFjkfl+e0qbOZ2*}S?)Hn@ul z1Q<@;(|XTpUyrQy6lH54e&w4`?AwK(?umGcdVh9JgSf;2CX_>&{|4nZiI6%d|7}wK z$E5tRh?(LrDBt)hk>$}PYsOAUFOd}}lM9OYjKHfLWguKqvS#YZ_NBy&@N#kJ&!@A9 zKjOIdM|pe6nrX-6RBco8LWbhdo-BV_vS!?b*4ZNHNRo&w;?OTA3N2-&$fv{Q%T zof)}|3JxDWe4Qv0rY(+M&cB&Q<^SdUHM#PJUoO7H+juc`EVUl1&{rILigK>n@T+oe z8bdN|<$Tt0lyAOY1XdhZ98ym9351uNL%8piYz5EyX@+vnX1a~Z-^L0lzi#DY09~1_6f?_E>n5SdrB0L`ZrR2`?Z7z53N_|EH1rr z?!0Y|axPm-43{kxbeO5bFN{?Rob6P>UP%pfTuLL#ew#RMK2P{R7FEquUb~ni)%X}S zT<)TV8=g`|CY7(GymTqiS6xi!^u=N_k)*~eQ7%>rrDY_dnpISxalM$$;L)GaNV_&n zR`L~ndgbiDn{ev|8pXIOOq9>~2Qh3LIbNYFXNlyWO&zzcq4xD#Dc^MSWTk(}+A&k9 z&{#wSeP>aFCCqt2fH+R)1`HPxUB^{)Zab1xWQvdt`L~>>wAbpSa%Ye_EL%nlTEZmB zM$J)T{0P!VPy_ZdA}p+-5wspj6+HE%g7golye%?Gsn@cP&XLPRm_cyuUGnWd#B?J`^$Dv zN9H{zD+NV&QN{Gx#E`j)8Vs@MLl=^xU;{m0ZI_fl0;PU-Q4ArsK zM|nUUn~ARIA!4xXN*Y)l#|^tXEXI!uvt2CmtLfbQ0G<0vsY2MaO`)sNlgNvzsJx_+ zbnkqJt()Dm!z(NFdR9ew0U2fFAH=ZdJ!&^+otH$czlj=b@l#A6xR5%sub-_n)OQAn zGYq)fvm#K{N$ojQTgTlCUH`z#K>T%@% zK>2HA8?9dwefk7qNZU@jEqk6MXkX`3IxGl~u{Et4Q1aSyNph|2lg0RP4fYSca_;n# zyENTJAvK@ftSD|1Y-F|H)5x4Gse*He;jTHvNbZfqU^s{H%4Z2LIG^%Wx07VEgI*eu z{&CW2$16k-<-n0Mf-3gTrE{1krz$Sb*0YYcQ9HdG$?bY?p$=M^@ob(2t2nPamZtlN zmyILLZWMWs8tOlVM47*m)_55cNY~lzB&mE3ApVocEBcDaZLRq{a<&28i{u4`HqyEC z45BkUNDj$fnLjCPApIhXWPM>(vT z7G6o|IRNDxrgjV7AiBPvgz8{_c3#nxwUWqlbBQ4R6B=ojjw&j>;LFalW7ckp3!3e8 z{m}6l)lVNmc*Q3MrAiHl+^#SU$n-d!wIW~%`_ErZfPEdG*~s!c$c>6vv{5#q&IiS{ zHx6E0>b@WwDB+I!|4EG0NM0p+8UN!1yqN#y@!PtdFueTMw9z(?-Y|1ed^ zznHG&Ol=0GUp-5}(KTJkXK}o!T0- z#MwO3=ATIg+EK)Ll&=MI*r=i=V#v}$3{-JFD;sY)N7N!8g<8!dx<1I~*|U+ouI_d( ziAo!vy?CKe<)w-hQ|a7yGl?wkIEwM5Uy{g!ya+8gmqr%h71Tfxbr`*lN8CY@h_ZLI zItXv~zDf;+uO}coU9X6ygE`FEMUrVT5CgU;X~mdYb{5Q8lfDDU}# zM4xr@NTuC=9%%JF)UVgDnJV;OL=0FPiPPo@)PdtVgHrMKr4)$t50h@2-lh)9*cLii zBSi z$5RFc?`PvHK8<2~BggQtofs-&N!a$21e8kniZTNdtF+?E+mxcxbPQbBe?J$r9;V5p zrIkc0af3bFfsX@J-==9w1I_I3dJbSE9Ql+&e6?0mWNp|+1FYFh5~+EO2GDz6nEXFp zp^-&zeUC=erlqs)JW`RC7aBe9(R^OO8xT3{el5F*apMtWl#y++(zNDSy>hlQ1HJio zDfx&rh5SEVN0UfS5ph^PjEt{U*`vV@UM8a8n(VX zUO5|h6&(BzmFHhT=jd%z&#}@=qG@d;oz$@IqkKVGZr&kLE-gGxH*2>3tLpGDmqA&c4%A2v80skyO9ZKtKC&ghk$VBE^TY$6ZQ!>!&2a z{ygd^Vkc`4?IIOq-$HSr{9L~N&u5)gt*4IqKBQUB%7MjL#++Y64LaG_y6R|zIUI<> zEP*=RT?!**JX@N0a5Ni=eK`7U1ncLb?nd;EHUHzIYTNY|ymkyn_wV?!+kr1IBE zVy(kT0uAC;4vuu*FVylTbqTAajE&Fv8Bf#R5o9!07I`^Ov;91K<-EnZdXs9}aBj!Ysh{6TFLNAj&YE^I>TqkTn_!z@fa<=j3FAK?QznriQ|XkYFg_#Pbb@G zEB7gk>u;2mb73nPsqI5jfgT}U^e+`RQiIKG-Fj9<%>{~%q%e=vx{(^vE}gA3m=z=j za=2XELVjLaOQGAqu|J#Rg#KSd-^JeG`07Zde`(+#8Hw*v>Y$QmryRZ}G`vfZu>2rlV<1Xyq*!r4qi(1zzH)<~rg$!Xv4iLLHSX zqXzB9X-b_gb{}awNleF=(eVZ=nkXLBze=hrexAIg?<*RhC!cJ@@*KsJa_{}bxsP=i zPB*UzljALj3WliK|9a|Je zy;9v&^2_3zNhBqYk$<+lOe*N&yINg8Py^Dp24%#WLl))i`I;E2VurI%r+oCSO-i|R z7BSe*0jlkmD%~CwC=dO$p4!zA5aLatEl6yzmteeZ0%WhQb-Q7k!svz z)g@e>&v7G|N+S(DO(G9oPF|%wPOr4zdIm9O`jpx)T6su}AIC$oa%x;mMp$8?08+k# z^5$Pjq-90C?k^|2{2;k!HE&L}T1gUqUS5~5^^7MS_w#zbgYOMRcyFhOJG3vQcJqF}MHyJbOp;8)`=pApJ81xoUKU|q zIq5p;A{7+zc6pc?Yh+_nTEkZd8)Z80inr#|2*bR^(o}0uNW*+1qn|e>df9gLeDUh7 z;T;br-*m3wJ>EzQS!;Rx0%IRF80CAo{U=c5tbALqbflj|jF+BE64aedIQl~|R~lzixIn#L_@kQn-x%zTeG8X%*vhp8j?-q}ip>e(LUY@14M z=Lk|vuhtWtfkSxhjnfsn0`?-q2r}MYmQXX>QpIvwZ`43iqJK%xE0c;RZc-YkI+Jz! zcY~4-Jwqc7PovPR`GGpB;f^CLa)lUQ+W6{sA=yOD*(7=^2dLte#CXm*y#5bz1NoPc z@z^;ZI)*A{`$?BodBl0u8`OZrBWlg0i_MnPsJxZ&Fs~hruhSeORr(YjqrALtUCh`2 zZQE$X=F7>db?MYW(W4Y_g1q&Te;=u+i#sThiLrb((#kyYd;1+km&02(&2P{^nmMlM zH&VIYOKu?b++3n?R>l{PSq)^A#jB`;=-;S9&*Nk~T^CV<2EMmb*g|HfNQods<#g7h!QP_Vr`)z+djlh^m6`agzkUPp=LMjMy z?C<%FrfuCjBx*xkx9rAwU+a~D6fR`Ryh84)XI1v^L3_gg^4Iwk!WJKisQwpPkT@?s zq~LXa8hIIux}O>DY9xl5S*LdHxQcJvNz8cZ5fn$N9Mn#PjkoEU@#Oz~U1YVM3&;kn zR|~fAbPIP__#Npw%zHrExW9X3g|3$+Vs{Zk1!u7LTul<_;mJqOm+v3HPfIgT{RHYL zvVn9SzK0snKTeD^^0s>M2E|yU_7%ivGrM8$TQsr)-e~CO*)$kGyNQ7?-`?+9M(z8U zaqSN89AyNhAJ9B4vDG*DNN4fq{7QJoLc5x#=^CCJ+W1CelvhAGJpWhmxw(l4!k6=Q zA2AT-TRolLH(9s5`IOHUd*-p0-p9JE zzJ_DJfsO9~ZOLTcMxrl@FR{*}cKT=2Ie64`(Y%z+l4-9ZmAUz*bk!PO{|~Gs(Pr=? zRRg@ziF`#JM%iu3d8DN;khN=>(Yj|0N=LmFWL!;`4JdizuVg!6zT&a+fRsXfg|F}) zQqr{>NoTePZ&dO*%yDQFHE8*PW=TCa)cQM1;%k}%(#O(TuUflZsUPIYtc9Z0N>GP?A^aC}l3=3aTH+jpz5~3@16T^`u zwDfX3L>)99;@RcUuO2;+);Gu5(G|Go5qUGO95;K25BDZ+1 zSIVm##NfbM8o7Bt8KtzA{olkl8gzI3s#Ivy(iM-Xg=VoF9+^^zFDtKr^5Y?U2X$D) z`2x0y=GVz)49Cn?s`@*~mco4dJ$M!Se;xaK=a(cRa~D~4^-0t~ltBkJWC-tjuACf-ro z9VB|geiE&dN8TZk)z|UlRKT-l-3!!iCx>7YUuSsJzomlKUr0Aa68US8=XpJE!C3bY zT@~*a*mFc< zR~5r@fwXu?MYct3#5>5?Tb)8BuzwRz zqXurMm!DKB8ciMA`GEsB-$-yg|S92 zNy1n|ai$eEqxgTXmI6)ott3+4#dj$c(oZ69@XaG*G_?{#P9H_M;tU#5<44mJ`h2#D zmPyo}KSCYXuo0SVB#C^MP=DP2-38Qe5wFj6MKoe9TYt^@bPcHVg0F^u8kA)4cG{Ti z=Lp%cjN*nTMhp~QsaNQ-&m>7WStU&;QDm&Kd5J)w!dD~D(?vY3I+=mieI(Kd`+qs( z#m!V-%S$#*DK)G+hE%GbHeG4j_!8k+_fkA)x{4MkrQYjl+6?oKgq@dQ)?=vwO+Sgy z^9@}ahH{CKUbY2^y`+w9CVD%K)EeOccI0ge1NxnmFXny0CJw>g!dodumro&`ZeVwF zvIO+~G%Hq`DHQj44StKqx7XUvCgZd7ZMe26)Ik}G+VPQI8Cm&r2IU;On?&s&Ggrw6=a9&Ac-Ac7 zORxy{r&lh)VE>N$DK_`AJGGrnZW2tV$-=;k#`FO)s>XN&9CCyF!=-{EVzBNaQfcTA zwOh{C-o=cUv+7!k;0?n6npsr#>q#{B_$rmJa*O#1$Vdw5KA&}N<}t zgKeRe@bo=!{;f)XH3l-;{0qFar1I-1g4G^J9hCDHYB2uTEQj2( z2dTjt-lDN{Wb4QxJa{FIG)i4siK?I7vg>tXDC0V^nJ~uzTWF5LcpcB8jl2=* zyp?9XuKy52o|oy|`90bd_TRy7qtwP%`P+Qu@?R2heg%!##2X5^tEmAC-`iNc7*%PyBae)-?>`nLpL_pUn*Uq*$7e-+N!2WqsO)T9*;6UN)J~@e==+8m z*1tw{*2%OID*2SXqm9aoScTcVNgd|fb~UUL-)i3fPiJc{Ve2g55mm9s4IY};gX47y z=auY!RV;d`m1fB{UMba;vfJ@=UBqj`FiW~;DXGMKgZE~o!SD?X=FW%xP!Y_D-AU@EK$x`Yd92NOuE0@jEvMP zX&14v71Ozd{j`2MU&*k}TGrCYrI#oU*dHTRbUjM-D()k%D0+y>OAgT_<>ZIW{Sh+K zDBF~2U>XJh|1u8{57=Y+s>J`64#1Z9rzJC{4ZO?b(6+Cwn>8ynxBCBB) z6|5(`hF3zfuF?zmd_UvyIgMKqIoUZPfA&42?{oHq84075uzGn2omH`xH$Y z{d@=0&c>!KC7ne#QAa&Lk_4>c1vNPOIfNQ`Wa;c`1$ zS-q47;%(n0+yM7%zhDvb&+7aSu2k@rb|UQOfRg5Y?>a{l7Z4 z{wQDT+4$88J`NlukIhyp4sgT0Z1r}2{@1_Fpp=(APNBT~dQw53X`O;Q9wJ6sS+#op zC1s7%OIBKZh&Zm}z|d?bTNrqn8g7oe8P5$({L`##_V@4xqR(f)u48)VR%VEe&rnJd zDquG(^0L*sePm?C)5sPiw(f?LiLofVU%^EdWkmX4X@of|==DCG)7gGQKSLR`ANj&MOz&6;#1Ak=!stPd1SMB^g~aGiKo@AA>BhmRl$QnfQ94 z_8c;{&In1+&Jt;wLJ>DiyKG*`&UYr8S%o~qI@p$n(S$BO7 zNi4$8beHgzl>Y~6N3)CuWE?}PP#VQoMMy9V`_KNEL=t8ZTOT$kG*MoyW?V`QM0t&v zaSyp!*CVn*XKSYjXWvT<8Tjd!vKM$x;YY3VdH$~+PI1DYhjxYkwQ|QbeDm4&JFQ%- z99k5$z1lO!EA5oHPaywq zXdvS$<_!a*k(XWt4_IinAK1;}Qok7JY=;ZDu$2Pb3Ms zk08l3uVVlAj3SXnxIx2As+fOxy3$ekURpkPaUgN?E!do|X|k!~IbvWm8EKG>t=UJa zlQ`f+c_3w$bxOO&xB2;>y74vzDEN-7(_$covc4cjdO2`JT_oaicH3rN$#igs4ZIYq z*-wo3FDClx7`b0#HK{J0CF1e^N+Gr5O**$%(bkKeCzW7)%Y+#SUqqs{O(LU>u)Fm# zL#3N(#0}}BWB)2T7cqmq=aOwTGQBtFDsnSBuV`wXAOhnHw4$-I7wB)Kk!XA*@-}{~ zR?lxh@Rd-%*%B>ccg!TY{$$GHfFRcs`5(Z{AiW#HG`r81M4cxi$$xEjirq` zsQ8SGvW=hRZ2N-n5I@@;y_y&`pF$E+8Wmqfg!jEbb4k8pOYpw}HlF4V(tQu#g3)uN z)0{ve*B&7P23}lRPsUi!_XD)7nmo201J4QhI?{RMK9&rtKxqVDI&psx{YxHRwFa3H z%W>>Jtu&AK$F25S3N%svyOBoPG z@>epT80lZgfYSe8C;{(ZYW-4&_pfz7>HqxyFEl>b-v9Z(n0@}b0Q7(U|JMef|C|5+ zO6wm3&hF-v6}<2TLQ85ftV){yEPEI zEfDhtV!l9ZLm+m0Aht0O^9N#^02>Okz#KVyEf9M>5NmoN_D1-Z zJ=wp#IdI9I`pe&{J6Fz{@m9f}t^;r8kGaGB#9R0@?{Pozwqe1Z?18tBoh@HDV)nSu0HYG6CIiV$UHsk$*eJBZywt|cEPwExS`*W zf6~^IzBy^y$v2<;>d7M~6ij$v!lx6)8lA?6j9(j1p15-2gA>~)o^Z<2Q-Y_wbBbot zf=Pdy^wgwpCuN$v7n<%cHJEx$##5J_de^D@PW|yz!{iGm-#+=-$zM-CdWv<*wNomm zyfdYL%0%;p=G)9qnm;m2Q>RS5WU6oK?x}54f1f&OTEVokX%9_%d)iOa^wSqkziRrH z>Gjh;oi1gclD#DR`s}UQd$YgH*32-?u+1o$5t^}Q#-}rWpJAAJ=FF>Rmd||BJF{ix z4>OONHDlIAvu>Ofn)Upwk7oTc>p06C%O#e-S+-i9w|r#jvy7QNbM}R^ubX}M?AqD; zXCIh7V$Q@lXUuWVxoyslIgvRZ&G~uGQFG06&zXDW+zoSg&3$R^$8&$4dt}b!oW(gS zb38fWoab`h%Q=vvIc@xD^G+)~?Yh(MJnfOwUOp{)+RvwXb@NV{XPtNHyc_3jnfKVd zSLS^(@8@}==NsoQn19Lq>*n7vziNJD{`>O}%paC}V(!e`b8}ba-jaJ??vuH%=6;gf zo2y+ge!<)Y=P$T&foH+}3!Yr?>VoKk9~TTieeCJ8PCxf_=jrQC-*WmRr@wT1>*?Q} zK5+Um3r!18Us$+s%|h?O2NpiLuyNr>-i6%@C97mT0vE!^NXJTgDN8co9oiZ(*vs+{^<>OWGuQ?;6jnlm*kH9k$1<`qqcCME6Uw7j&d((X*FO>0f- zOFLos>BHT_HxGYy_$R|tMw~k0q7j}EkBxYL#K4G2+Cr^Q`?R)QJ8I-DPx0#GK&UN2qj7-BBWADs8ncpudCm$|MML0 z_q@mP4af2Aj=OtXYwfk}b+79_uk$?Dz1Lorwyb9vC)XaXaIO}v#oRjFH0~zu#XLKC z!g<MRTudrQlV+GGj`<3-8my5WGbcn27MP1duYO83n=(Om*)mK+@iaCoBU1FQX zlf=J>n@il1kXRGGW^&D;wKvyFO2$ckleAuUf1Rq-B`Lo3I6X9(xdb$0xvy>K<<;Dt%GbJ$Utq_!1i=~&HX(71U}3uY z)QSPMVUQBcCbluW(|$m!g=Iz0!c>!7cG?mA7tR!w0*2 ztsEm(s~FT5I1Qy-I2 zdot>w>OE4bvSRqP@|__*WzRw7ty0eqZW-;jSIU3prD)$r_$w$q^^s?Ja(eS{?-99% zM>?_v4<$CG^~}pecXw@wc#tU_+jU}n=6x}#tM>*ZJ3Hgoe(c!3Mx^QHG_GZ0ZcJW8X{1n?8(n`1G!FfcZ8Tii-*|H_sBz=> zipH$3pBlMmHJU;{Cp0b0d}#8TKF~b%vANlKQsd6#MExC)_XaKB-;T6|j8j{A-$=Dx zc=fbReJtVblTnj)?-7xX6~iAp?hJKydJbN_C-pq@{%C(}SN=01;(>i%bhpyev>uix z1rLXN8y+=08tyH4$nqquN9k#Fw|!s4gZyW)U8DV(_obd+z2`aD*?DK^BkWG3!+XS} z{mE#;UG=f2a5$+p-Z#|Nkns^{hCz$R`+8`W#vSL$W@zStX0PcF(Ch?gzD5)G>?b&# z3OKDG0?uzgoTn_DuK=7kGn_vK`hgkxLjd|k7W!vDbW{*@SOs+4r^X;o4d}=O=+F;M zyu1gXgPWWA1vH?;>+i4$8NdY?X_;CZ{d8_9jAB59uFs#w|{&ok1 zW$U)d2~7yoYul$j3P9L;K=`(5hJNOPaNY-D9V!g*T@G>H3-SH|;(kHP^%wL2{F0IN z++iVx^z>n2Mq@?WlK=fb?diijj7G)7u;TyKe{3V-R(awhc~(FGR|zcoA6|@^rIrGl znEr>?lK*MC+nTJ)cz{apw3 ze~$K_l}t={xIeG|tX#5$-cA|7n-_f4vqnF|)97EM3OM z!?kQF2OA4B(_+g1gJs13mk5&9A8CFbsisD>!!Zd`)(5BVKFJA9bC*~We7 zuWD1$aD7VJt6H}4=-?mn4N zS0|Wn!=2;jf&--2*%02J>*l0M)yb1IJkEyvrA1AZJ*T#qaAoUt5QedRfQGoUpor1O z4|FnEhwg@iR#Dr5#lh;78ioTRBv)||Pa931d$ z0C%p}VHk@IQ^;(p9DN+-XTEK9f?~aLvNWmBf{n!E^d0|d`pKs2+UVn;2;6TM0WCI+ z)$3R(CKD9PnM2}16*9H=V(X>Jy18s>J6}IhH#hi$gG~Q=7?wzrdoR>qwk!Ey_0@Dk z{+jzgqJ6>#`tYn$Bc~q5shN7#oYCu;9TN@FDHlG6jT%e|ziB$nL5OV(ir8CogmEEM zat)sB7;W`?;)I)!mQ2w2i0SkQR5{S+6MlrTw+4HpIL@o>rQm94>Pebii9qgPO5jfHox{-NS3#VsvZ<<* z*m!Id_LM-bT}k*&NoVc73Ph$?TX7t=1iKB-q-xJ)hfWv8`k|o#6Q|j~ z5`#Zne=(5;3qr7jgFJaLt6;3K{g|%B-V4cHmeDMc4!zje^-=yk`?gwnF?+AMPknut z&RngVftRQzRq00YgcX%nE;W*I-7DQUBt;Z2mkdEqc{}GUrTZ#qcI@>`J9+Hsw{Ywx z-Yn*_!Mki{0(TCk=r<1~Xp-x{<8|Z>J2KdL=+%kK4tr}X`WM31o+T>qn%cy3wW{+z zrM?s#qcN^>=Qt&KX=AVYlgzVifw|%wgz5D9@0w)FTNyfDYSBF9V#f7YN1}0`@VUXe zbFp{n)Yo|3zl9%r+O^B@^a;0jjn=~&p;-kdFJiYkCB-$k{`y5ouDK9ORIEL_J}P1} z#=}P1-H!#{u8PtA1AWC4`82Lpn|O>3-3;bxi++}XIJM%q=eJl>{K*9lj1%7wmzOiv zjt4$i*_Al-vJjC&3Hr?#H2E==otM{61)OF-OpX<*o#)M3*pC4u1f8x*tm3*%q<_Wk z$6mr z5eA}0sP%BRrS0K&wmRi_x$xTJP@9V#yc@DoJ-C?r8>w6@n&*}7q>llLm+on>tI%rd z>i5jE{v`G)1}k?C<7ynyz;LbFbA*B2hFyt~yAWp4PcwR9C+Qr1^T;4?7+x!kV(h7Y z)@Fipm1qca8E@8H>^fD9=yvE64*!cAoPDPr;`PPu#_0A+XIyuA85K0F^dnm7Monry z%~Svb9WV85`vrrlqxF{w|DN?x*!39omeI*wnVS}TC7C!#yzXk}SDWJqU?N?Ay(emx z{32X`sr+6o(r4(q2@xDJ#`Lc7+S8J|)Pt$7uYRf|GoPu3 zjwS;V~LBfnT6g_s$q}|tr$_reS?R^t!V+N7@A-j7lfG*bhr{zmhE0`7pMn2pb({F`+d0XG{gbp5bXG z)_>>!!2{_7N91dMP-WF&*96!ZFYv}fj!br_N zJ6vw~;ET7Hwi7gwIcX88^7{`Kgyz2Za+t^Rg&k2L(pMACl)k+dals@``mU02d9XU~ zMp{>KMy_O91GR@CB&u31O2XtW>%@PeQv<@_oMzis2PV4$1P*vb-5 zqj`Qn@K6oUe3oOl+kVdZ`7M#5fzYyipDP&IT8SA=1oKNGMbtOsd|B$b*_b8D2r9#* z=!~}C;Kl`ChhB?!EcD^}o+JR6$no@<8p)BlzNr|Qub@nOKv(Cc2ApCU&0 zwjUcS-12ZJGCww{9f7Afdf>i|OuJvr5+QQa<-QB&^Q=q}gjgW%9}v8(?+Jqi903?e z2uOVwHeJpuI(}lcx!U=G`^C{1I|xoV8r)S*oU!t%?5uk=L&tbQpwdqryzzVT1~qdN zOXLgzLxU}JNDNVng>Laq!Bs*hD#+!f=*%#Qae)Yi(fy-ish5;4Yf46wRwBj%qS-*G z$WXMI@$uXC%+)wzFxU{;SmGO76Zi?LsX#vMS4mP%PIABw1UVc%M}o{(Kc(LNc>J3o zi9?e>#LLL-Dvqfea-tcnJ&Tcx!x7Q1CS0ViW%o}Rhb+EsvB+^3XCw zOBij$n8(Qs<5wq?i;Exajl}Vb(77+h>E7FQI|BMyHAx(L3EABy2%|hC{||4XWoZP# zJWHDwBQa1BQZY7$%Wdr(4{+!F=$MUhh2TVZZH$n7+@`hQn&ZLMiUEfKiAbB19De)w zw`!tLidYD1Pm-5 za*_$*m@QOtMDtj=`P50~GPvpyIJ^*=F_wB(T@PBt)lTLWozHu~urNTFR)nb0qOKBr z8l3VLhp-3%k&T$0kga$vqp8`=N#85ovZWy&qZ#oV$Mf<1&bEf9m2PA{HweSgf><7$ zFxRZakwJv4yi3Qi%@VJzj<{Y)Uj5YJ@36k#$G@j*+?b9Lj}VW;v+fmlu&bhFbWELO z8VkK}Il?`WL)U$?(vf>lwq;fUj(LoJ#D30b!w2`}*7_zdVj`CnOkeD~@Yn+L0FM88 z!gBF%LgjZB*SDo(uCPo~sgr-(LIm%S_l!!cy_Z%&7hj2q<0Rc_T;Q~X-pOFyH@u$<$=d$G zFpSjhERoWx7IzPCJ;^kaJ4Oj~GXD!Elv819&sQB#wE5|{z1D9aKg>AmdMPHCkMT?` zwaat~C1GPaacy7r)dZ{U7}#lK|L5KSR>^(D)lY}!2w9TrLlO;>&YL{bqN*yoeTH#D z)`xbV*o2U!FEIffiO_!1vqR1$#C@(gY-B2A)0NqLjBKXlsQNeaZwPxygE03>m&~yU zjZK)COlet@%3fEt?g$Vbc=ExMrrh2Yi%DuWgSYC}lXrfXG#cUuZ#yNclHRNh1Vns& zi2i8)2|-g&8^voOk8>ijlaw1Udx^*9cW8mK2?Dr{?fJ zAf~_j{a8ji&U*X-Bi0M7g@#wltgTGX=e6Bi7qcRK?%Dagydw8Vqeo}e?|Ym$lhmFv zrWA6htoIxyyUQuhZxXZ_S;9s}En>bpl`$Ktw-(Xs5smi#lN*obT%hF0rzs{{U(ezw z%z^`F6U&vmsNNDfJxR%py@^Xmj$fD&qe3-btU5eqX?{wqGN3O#{A&8n>xg#LxCd=Z zh28}(;?tw8C^5?=QvG*fraVB-e_a>+dL=>iBt9s9wI;h?T7_WR?9Hht3A@$eoMU(+ zV`W=^TscjD0#VI8Tic=SuR!y2y2L^t+gTd!woMcWsdICz!=Z@5{*-26Bl*2)}Hk&d*zfCff|b z|AXV#61X610h)M7(TlGN8n2`tFE?*KuiO<9of8rA7*q7(sJ@;P%A;p0y`1i?dOb+z zt(wh1Y$1r$$Qw^S#8XXW_eSo#el@*5q;@stZejY@x9KjDJFW*QjL~L#N$n>`A~28l zo;y_bp*`lzLtT%Q=_am3S@O^vg3fH{&B0<*krRpzh1GMsU;-x6=%3WhvD zP7}@Ws&NievY!s7dJl*i-k?A+VwxI1b?4ho(rNr89pQ8!mtLG$tL!APFZ(S0?z*^W z`lUC>0iK56dfK6P$!Wn=qmeRvD75vG$|d9jDoJAvS-*c1HWIF(n=7o&W<=%6Bm9ce zWTr%X4l5Y=i}dMFl+&16KE@+YV9zkG_8YJY=vOs~3%j+ANJ%55IgvD2g>=8Hu%Vea zSalV%_il(ZN-(*Dc5sw!%RdH7v;m-#G-#`Qtkb6jnGpvch4kE%54{oZIKB5yLgE0Q1T z`#NZ9B`P;$C$W)@i;xpm#U#h}QBq&|6%I#M~=7U~w4U-c^ zVCXSy_8`2gk}=;o3F@xp3&9re^1skY%@GySYv7`Q+pu zF1^-w%R~9M+v(45UQR)xvn~Do^^~y(LF<)@qlw|V$<#+QLJ)Dkfm8!h;h*^o^9+L8A90gWRRxgduT7}4#LM6AO$H2P|HIoL z>Bw2{2W|7Kq^)->0uc^5+`Sl!&d@bG0+l!%NlZXy=eYMHpA#Y9%r7T)b5|3`zm+cV zlbA7)+aW@Vlq#N7Is}a8o^K3hNu+rjBH4ROw^h2AdP?6#)Fm)ABInzd5_YTqvorBp zx+dJbnmr>wEOH(4KZIaDk6#+efw?barbKC&+mQ=eo!wkv)9v8Xro{{hpaQzUj)J`K zP$*@%cW1dHjh=^*r!Z-K~4-buAJdk@Y&3!lUMPh0vdFNYBaJsM- z_4RwqWSC-+JR0X1UX7~%{E2x5Uu9u|E6!Us@F^HrwlcZ85d&a!!(Q}G$a~w-^P=ElT1A1s{+xBF8SJKNJudY4iRG@ zNoeyrKiS}Pc0z^_Ba<(9U#1sJSw)+bU>=)Y2cO9;x+DC$lMiJ!@9g)qNotr7+x)n2L1Ht-Yc08+Ng1ul#mIhhX?fC)<5W|;5uB7poLivS#fV- za^tr}KZqeQw$Q}#fwLje_Y{#KBY^$#k=fktm-~eF{t*om7qaD4#ynAdb8u;(yGnj6 zqEjzPav^nA3P~B0v%R|i_=&tCqet$Mn8lDrBOtM@ANS{FRU}ypSuYsp)Eq!cy$qly zkzjCm6WhOFDn__QdhL?mc%{2S7aw`0Dy6K~hmhhdHuj$o2O3hqgJ@?p!FPL=Bcna{H(O=*}|kd9-TZR=g_$F@B< zA*!A!S%ef}MruA45;nql{IQwGNyk!5-I!yLru)QxXrC4J3_7%|k~A%PlSd^oj0};p zV;*;>e&R0=?i%m^oJJzPBY)qQOUXNMRYAKbdUy(x>DecZmir=e&6u%IVK{7yJD&D7|8&f^PKGJ>SURq-9$m@N< z)e4-^Ds`4=+vyL5ko#laZ*>&X=doN?VAGuug*gCq!0RYLfX!7t9q^O!$N`EjmK;V+ zu!uw!Ah+l@k@fol{N?m#$s*G7()mm8E=>X=s9bvb;89dqRAM)3g_0hzFcp8F>Z`!iDtntgix$+rNH)>1MQt5FkP((P>)yA8ga`k+JFTK(Ie1X&- zC<{YDF_rb@+U6D+j}AS{wBS2i6B5a#Ul4S>!`Pn}nk3sOJ0;c@4kU+_X6clo&R|J+ zdS}hDgG9RUNqWIGLN41bVQ?FYj!g3M=fZ#tNehDabNHMLdEr9<4dIkEU%p7aYJ>e7 z=DSL_C)fRcX?%=ltv61VCtt9j zdg%-i8r^mx+_b`mxK{BvF5+EMRXxJ>)>yBO5;5i=Y0fnA%@xD^n9RDpsA{ChiMdLu z5??QIXs+l7CrSBg2T>(U%3OGP`B}+6>tfS4d0+1F#Ow}te1@n=k6itT;8*AMj5+h6 zy=6=~q_fQX94eotl(L%>)2oOknIjQvYkV2^L#x-I3L2mpzrW&^s>vG^HnMj5CwcPW zy-0-Xxw8)CCHHrD`{^(x-)_8-$V#61iRvglblHnCi@irvPPtbW^@WEsG1_ZTDW%2b zxA`t-qT2D95;U!nt+}$P^E(mW&B*qz%)x#l@zf_DY`-2OZN@Z1P(ppqi78>eX%xlTa%WfBZbC(@LS;kIs|EwS$ zvwb1_ery9>P&F_5hZSjGY%DOjB6ob=ob`fjms|9sh}mA0Yl1{nVNc&y39mt~wtGge zAJSv0vNBM+olQMbv)kvcx=q+#cT`ui-5R@`jIrD&g@I*QS zHQlFko62n44bDjIyqvPC`D?;fvi>{jJEpMcK@C&#gp0#`wRAs6_}$EJ6)5!#qaaBI2Ch4m->OOB$W%ffLm-tWWr>WU*I^?f$JvwT@AGt@1`D;fVJ@yTp zExpSfS4ii5gY;@VJoc%f-ghTix8z3o;oYI~1zi_W8=555HZTJs+>wY1HLuV)YZb*W zk2+D3_Wk3i_bUY_|A0RKi7NyxvZXK{d7V^-T=m<2r2r*0YFyc^H7OBf@=_F#&LKH3 z57^9_6j`k(QSB9qOiSo$Mll&1Guo*l*&4vYet@hmv^?*g>8>*h7Rb%Oe!O z3NNf6_s{f0db1{l&a++#EHkp*f3PMwt&X@N!W#0TR3S?vu0$1y z>>X0*le)j)27O;3BGzw}=$5z4Q&9Cbl8yf>fE!i=+5!#nSmg21HOw>(PIWvpZkfxh{Cs>%dR7B*!!Ra3n46S&5~) z+q69WcM+*w&1nh8NZYTdurS!U12KcR+OXKE{rE4Tl~3sh^0cp z^rhEIv!fC}Xd=srAl<$g2Oe4@3;sy`_pPMy`vDrta9Unl(b}45hpYR0&)K$LkChH- z8AC}9vs0cJ@6>YsP$ zIPJA;%Q)db_e}dk6fM6kEe>^iRz^%!QD1=nS@kXPmbYt@%}7;tWIty^o{!$MYC2eE zZFqII_ff=+#M_Oi=SN~>IzLM|1u{51NRunQ`EzG8_Mx^H1?XWShPZDLcfO4-@Ih+J z{6kFh&U+OWTzh0g92&^ocF!h;NDeC;K+UfaIq*nk+r0arC;cvE%rxZ7wW%!B|K=%{ zw{$-rBX(_g8ctMCFucRQOCpo4qb;Af=N_`HB#<(EbV`V()LjyVz5w+sYsJ$Caz3Kk zDoNapt3ek$_>CTcb!hjC6GsY;Q9`Tbs>dDJ44V&@W_$8%35FMQe?oMk=iO6f11WRiKc>d zc*irLy_2U}oWpKS4338y=D)cD21ANeVoTF?H{v2n`iHS_~Ac=-|g zH$L-a?_K|nn|{1rG#RONXZp(PH6yEoK5g-hskmXAdX$#VhbF{0{r#(oQx1DWj%5}y zKb(%Vie1rxh6E#;t!r8)&F{bxev<9-`~}wh9#f>^%;dA5Pl*7QH^iIyGe22jP-}o# z6CtZFm|W&9Za(qYY&O4yxZe=X8X@}>U5k5>Cm()OS$#&?%c3*#)erjRiX~@}Xv(It z+)Vq}P1V>m7SUeA#E=Vh6Gu1WCoTG2uxqZiXVB7@6VtCrM(>vhbT+)tb(V#78hZ8Y z=uLKMGEZDV3NIi5y&t-FXwK~YF}i(KmE*JB;no?0RRlU7Q*o26k^&AuKa*(BN-AB{R+?_`H*<3(Q45zLQ`BKw6^@_+1=6Fib%ydXpO|wU7woG z@BDr}seIo-^J;EQKCR&2^0^8GTjQ8Ytr#(GY!HO@aVQ55v( zcw|8QXbVzzwU~^1eo}$~-mI$R#=_Uiq~IWPuOof7w4TL4N-zNkgY4 zA^+SJ^NL2hRR@Uf?CuVZSjbz$NTEw34nEe`E^~GFsA};atq3_<{391Fn9$_%+q2&q z2z{x+F!idwjPY=<4QR&%&@O!V7hgGnRWXlHB;Qumll{Yur|cfMBJuO?L0 zze^G%LzkdUvk-D<{}5krWttf1?ZmS!2ox2dDuLtG_?KYjCmCROFL zswZpwF#Xt#v#IF)jHjKdHF~`{m``y_v~`_Ungo5D5Nd!_y4M?b#}s{Y%R>c;-CG)vK5oPyS%5myxyeJk^P{Fq?Kk}*Yb8G`1NL^DAWoM=~XMy zP&!P{8b5XV!mfS6Bd>=)T_us_pt*#6U%j>3Lqcydb=@7i1SB@-Gg*W=K2JRG(7M&} z{dN5TqAU!l6Piwa@ta%raVZfGg|^czuDND^O?b5(4JZ^8KLdQ$>JocCt(lW2fwj=k zjB3dXERw4pus1L^&O$DaLPJw0@vSp(FDzA;8sa0OaJ+&Al66ky#j|_Swt`Xs}<&1JWQg9>>=z_(jFy9jT zq)9Nz2uD1uE@y~^^{qum4C%Ord+he%z~>;X1Yu5881@x}Bk@4n4C!^QP*-pcuPW_xv2X6f)Ni}cLfcPn`nEIJ zWTiWm>jSD9q-kiURpdM?VYw~fVq{3om~5SjLuy6^YYi2Sq+y=DoQwSJy+ijyk^7;` zW}fKM^mfTxVpcTakJzb+Ap*DJeV*6k#5AX$)27vaZN1U&e$tS?q5X!6C3(0v@XFSE zF)TM_Qx#~=ylBP!paVeL9X8@TzUd08Amnmr%QZxo-0$5m=O@A}LYiEzzMz>meF!Z& zR79=BW!6cebm7@gW)k%!+I9291-8rbMRUjP&4bS)kwj66-raO0^TW5wd1s=$xbD4w zHBLt%i9Q~ZN2ke4)Nh+MM6SHvnLZX`D2ARMH+}uPS1uQH@`AcwBI8B9i2h#Xxxg~7 zj(cYUb+@IoG{HAZKqI2nhwN9xtmZiJ-QK*q{Sh-7nFU6j*9BdfEfcQxWrrlU957C!NG_wEBu z9j;>yNMO+iK%a0mumVN6cf3gAP$+8!l{ot-N=5-qLu9k2K3(!M{(N+5a%!>8H9(VXC+Ss~ zcU~^r(gZz5K5}%yo;bppNI1@-EJFe7I7@htz4<0r9LibkY7Q9Z$aIdxplU_)5jC2w zmY&;v5Bt{Vqh~`Bn{0Wz{cAD7wthu8%C+!tGifv>qiEV6oIS17mImG&RQRYx zL#d4hB}%T@5t1aYg50#;gL)ne@=B~%uwr^k6 zA4GEXl5It_JYUAp9&|BL(@9aw1>XgKee3omf<(oOj%I20(rbcEer~t*uco7#LY0f| zW>?tT{y?9aBC*sxt2yq58oHjfWZ{@>RB z^6BeA-G@pT9Z<1!{#vP5Q$hC>L!zte*wQ}G1eT*4iW;!RA!g5*<*S0pZmTF%#psNR zM~gntmOJA6ZP5}E^`P4Ydkb_)7m>`rzY(7neuykxzp_mO-c0YxkIVJiEL6jS6)|f z7P%tYvqJG4<3-S zt|&qNhin(U-I|!N&gE-Y1a`AqldM;S&R3ob+mALca>4aP1=lrV{%i1pAW5KnLeJOo ze0^bJY0}B@gJ!wNVo)-n|0@)!+Ph`@X?MEkgSMQP&LOCh&ow;INy!~%o4nj>7gpWR69)Dh?BH<3M|ghQ|SYr?8#T~^{A z;krsGWK-EE7A~00(+S7%>kK zqVwDYNMoed=vup7$h`cyILb=f%q8FW{&+OfX>_nbCO>3R%k&&QliwlriZ28yG`iW} zQY>#aPJN?NH|9j3Vh##TmOy9w18wr1fZJKE9YOk|5z{jyGG#QmQT1lryXz&n!zo#? zDJl`!F@cVEd1%Sd6Z2KamfG`Hp_E4YjqZ1I-0n6bK^5voeotCV$>*Hdlm%UM!ckT? z2j#9Rp=M3Ce>Edfte`8tHCL;IfjphF%WUeu?y=cmIjm#F$>FVaI% z0ijzCB9>^3TRcYuicN($l+T@Qh&EM1>-;C6v$AiFT!EkV6O`VlV$eqSWvs2)JG3QG zP{k*<>}FHSYf_LKEp?RPF}5oEMNXI&t$sw0L_vf0I#0}(dyMsU{v|B3Bues%oDB!j zY3C%1eq<4gIGhQh|MSG06p7p&ZFdxn`jy_NXeRrzy*jqWB40-fJ}#o-v5}6DE1w5b z3kp%B=xE0qC$rYCnR`e?uFDU5SIM7g5RoK<);x+*?=w48&IYJGcbYs(Lydtp{r=31 z%7c$h{7SbOC7|AvAjooN^z6q%YDPSd+nFhz6e;C>aykM92m1FYG9y>-3!3IEB;|`( z^ZPRH8lsmk0~8{HdW=6O*l8TKJ#u~Y_2se)uC2Rs&fR_Yy|kxySQ3!lqs5Ohzron# z1$rZ*QM@+H0NpJ2*G)Zh~=~<>N$_XTn2Mu z&9Vc;p=CzkU+NRJ%XSd&mu-i+&nm<|E=7Xm+C-FdNfBdQ5`-YP2;B7*B>cI#iDGVc zaC#OK+&n+1Iy_&go;*|3i#+eBPkCMf>mQ`5^FE zNi`BwrV@g3)H1u2T%r5H zJwkT?xa)$Igv)~MgbU!NZ#EHpS2!hjPB;pj9x~W+g->wo3TK!mY7;!Q!aP`fr4g`x z-C+7kwcx6iaxi5`GI+Vjis0QMTyU3QN$?esxu5}&k3maUjRkF6^(@F`Raa2Xs-~ds zRW(5r(PFrznHyvyni`ZM8VNQ=aL}x%N08KNJD3A`I4EMZQBdt_LI*hQ)}WPQ8-fhP zL}5Y-%)TmmB3oq$1S9PoCXPJpnKBHXcC8{j7;5Kt(^ z9Pmu)t3TWNH~uQ?`~2z5=`<3}{gT=JWiN%a%k80xog;~Br; zjW&K)HyXo4S}nh&o8ntPn*xH&6Pg<@_9Zw z@^L=y@&SZTj=Vjv{zEmMz&{ zpSDDLiEZ`rGTM5=D{!lUSK-#JUQf4*do5As@KR7FX3v~Z9yt@M+zH?0sXjBVoO?!4 zB^r?1>x`Sq@iSQ}d*H6G(wT26qGu#kS8J~#3T(veq_7`w#g_*B2TB9&?pxsqp zyVUiJb~?C)L9U(JCtbg48^BCsc~@eu&T>~@ou4k}b;evC=ybTu>6F5>vox3eI|5w- zc38u$rrj<*J7itvcksKc)BWyjtoy<_Q1_1WCEY8|J-YGE3%Xv;>vkS?Hr}b}9I$gO znDT7S-8&~w&+U8!6Z)^8-nT33wBIfo7&LaLyLK6z{@W+;?wnp>w)fJAadww`r?-_B3-gC#HYEOZ~(4Hum!sP6** z&ciKxNyA+Gy@oU(Y_|5Ddo1wJ*M?(&KG>^6Rc7wxPeku_rnAGm|J~gt}>=e6^ z>L~@Im8T9H{jj4M4cT2WYJi!7d3JcqMSR~$JNbh%i2EP&tgsAdKBl)Fa26Ejp(rcGLk?CJAaJOM)`4TR#H!=a*omn_ z%`n?E?}WN3ae}ZiJ$53@blZs{)0HQBOurwWHSIgT(yaQpmRZViTQiU2(PsOPmzv2Q z?=@R`{JYt^W1{AFkL@tObj;qIek{h^>R6e%=CLQ{BFE;;=RnFnJ-Wl9@~FK<($N?T z*Q2EthDUoXq~YEdGu-oeX{mj<0lqhrWf^(cA8bD}%kINUgyrYM+?GN|KEMQljw8p9 zT!Jqa(&7K(@RtTG6*|HVTPVS%X7CYz_-GdFq5*dG(sI>dX4thf9KsL| zj=;eD;h+kGlzWdd4A=uOaNS@4$G|`?gaO^+xSY@*ff4@G@eYjkvoPx2Vf5<(3ar{4 z1&DAFkf9L}Vi2I>yOSZnhJ@Z`fDi+K5<7qt8bC`HK+JW3nnwURlc&1@el7tF1ppiw z11zoE=>-rK4^VXlAnOi5*9(BK@6PLV`2o^oU5FmQw@ZL?0f2Y=0rw<#lmZ5J02Yn` zCjNBs1$^8KKq;YP0HApiz%vLyG#$XS6hO5dz;zTrcEPn30QW2auPXqsE&#ERmM?&E zB7k!tfOHdpbw7YM&Z_1B5MKjet`4AnkN|W)4JaQ1Xnzh+zXH&|6SBZd$OiN7GTV3| zJ8bZH2&v){qzpeu9eW{#h-qX)I;n!Rau3qWOGqy{_|?}#`q6|mbO_SXX-G>n zNKYA%rmjJ{YJs%%9Mac}rwODoNmWruYlITyw>^;Ojzhllg1i?E`7ampU^V2!PRNTR zkRNByC_u7YqAU)Hb1NiJ14yJNAfb9eVvU3Zn+=J!0upW;B;MzcfTz7Uw=98#EDVVm zXFuvdqBezu?FflG7!r6AB=Sp;&}+T5;n6aX;YT3TfA+41tRDf{-vU^GjDij@faiOr$YG!&r-70L12sti zijoghr4lGhD^Qm{pfGQN%FO#_0<9sOfZwPC&sn-j3pkH4a334sKxcppg#sr^1#Wc7 zuMvn+5)dY9AWn)vpccz~_v-~hbpeQ#7Z9wSK(qum7y#)y0^|#)-1-90TTBW?zk`msS_Z8-K_32@**;KByLiC2nk1%9jp zMA--k^I;&)c0iy#fJg@ep^gM%oeBgy7l?K-5bhcv-c3NjyMTy4142Fq#QY-=^tqrb zK-T?$wC@J;zFb5Sh`bySdbMCW0qoucSibm5b71^7!2F#-0r-FtAVCpCfig$|g^&$W zp#UU98AyjZkPvr3O56uY@dTvBFi4EIAT?${a?A%8g8c9S8L|uH2>)_XkS6OuqR4?% zQ3lDP3DRXZNSOT~Wz0d+oS+h>pl>7v+(7I2g65%u_6Y|K6bD);4Kz^}XrqhNbP!6m zAefXuI4$C91QB%?#MA>2RZl=%4T8ve31aIVh^{FRUtd9l{h)I5ECx}=4&sa(M4BLo zH4zYP5+L5BK*VhVF{cQkPK5w$V5(+*rTN{cA6k90%P!geBfzkqH6bgP=0?JM( zj!+Vz)IoU#g?BN09*PH)i;Ll@cm42&hlxVj10@tn6O@1VL1BY8*g$P4!BCz-F^8Q{ z;4}ESx3H}eGdw(ng+fV#jcYk5l+DXvJ+xSXAAWQW9_4%w9%!u%XC(`*&)7hrL~Mrj z@EmgX?eN^|PH6WAy&h%ykshV~tsXoq4ZCv@ zrI=$G{J)rD&$5hCyqJ@+j-3nsW}=9)a=|h#%Dct5d>N&mog3D1Q=-_oVf_-y422W6 z;ilYX;fC$FDJ!77Tg*jCf?pafhFT2jes&(p33$H_>a9>mvGGuJp)8^>Q;1RcEz=pw zGKvW+5A2ACa&r+E?2Lz!1jQbT7L*lG-Yw;Y9dlF4nPDB2Gf;}*?`$Yy@O~)=FC2)M z@?;4fj2oWjwG0l(OVNV&TcMc4@+dZ5iX9YPC=yT>QCJAdC@U{zl!=FO3F;XN7v(wp zLZAt}SAil5r3wDN38fm!Z5Ce2WhhBdzH#zF19>Tzpw@!g9O@NNFN6BsQa;KUGd7rq z(gbxmlzb>jP?})b8K@7#{)!j#^H35v_~0yfD2A{AU%wbMUNe4%e4+gkMi#Fb=dxeF zfB(i6Q2nMbMt>jVXBf{NT(W2pL!!b|XgdVzpV!ZSH^a^U7W~NHk7JF&jWvGe&pHNg zg{g=HzWtwegZssG|8-QhWjKER?&ePmL>N5NhuH-G`)>d4YcW1@ho6zS$#eEJflHr(d#zH!;VFNR2kDX#+l@%P+uV|@Mh zhT-4%A*^xR|90XGwx@?UdH=TX|JnmfWN{hp6c6y<&*JX^vBnqHix|AqhlSSt_eTG1 z57z&ES4$W=z7Asetiv9r>phx|4vX;pTf6H$S)H7G;-FaEZ9T2+-CV`@?lm(K*EwJ$ zuIuLF?&xgiDXt`^a{c+W&elaKBa2uWd1ake>^}^#4bV~s?VP<3L%h6`hhKQ#Kg<5s z+N_Hhy5*g+d={qI5W}u zNVN9IKO6n6t#EhnS^|YBC5fM(Azpzku>5DUzjf^Z3q!X8TF|oYp9{t>ss9GBjr$ zR$_L-pX9*j7X8x}_*s*I=s(*+%?PaQ+{&;2?}EQ|iS8nX)~v${2Kfj^>j>`uyJ+m6 z&-|_5Hn1?Xj@}hzh*!bdk)h;2YyZ|gFwOeEc3=gYET#PWQ-c)ubcUGgT|q`-Ri`*F z&%aA~+|&Q;z=6?J)wy};-`^$l`@1nuHEf*t@5YJ$ZYQp{8@) F{{kq*gL?n~
%s

bwPopC}14K6DQWp5+it!~%k31MJ2 z%4$}7M`YpH2j64l@xdz?N_vRx3S+c1vR$Dpe77uuW$%nr=q+Os6Sni53UYghxO6up zsUOJeEvbQ&jKdQX+TrPs>Gm|9Js8Qe(h%9;Du?ewNpI&&3gAh&C%T_$q8s4DC>d9b zZHAI;ypp75$X8c0nmfiOCOGbqA&@=w9<%6ezOnMf)vjqNwFonSn!HIZc+eO%*tQ!M ztmSI25kk7I!dxjK83DQRRYeCXCukiBa=3q&DD5w1PM=uKG}ai$U=Y6M9^Un+g@cXN zFS0}B1MZ5LxMi(nA|o>~A#cs-G!?*e*YLDCvvDc%ku5|=A3t*CdAPM&BSl&ZpSQ-G z#*$kMC0Tbhx3`z9kq(U6s}PziZ5Q(sF)SvACGlcFt~_>Xs)hS8GWWI2$+xuNX^JF6 zlfq8}w8LBABL_$2VR$=S2TDzLWVzf2-w7`<`Jq!d4mX2XjJ`ICTzKle1(lRIBuXfrG6{XuWg4Y`xZXjIC`QhcFQY*RvXSAh_>-$@wvdkD4DIIM||_ z7Qeb*766X(JQCfiG{KEW(f}SC&0FD}^3_ru)NyX-5t$#;iU%LFszt-C`2(e*d#0iL z#QhVt%-SE5;-8?k2`ycRJ3ZrQj#$^`=(zR15qk_N?TA{@Gv=pWJR2U9E)Bc^s5jRp zdijt>vlUpI$Dx~R@Xb8JbB1fmq=4a$?xtF<4JJ2xTpONEkIBX*Sl?_#nc^6qn9zpj z!1Bx~xwuKos9sYB4;h7!Qi*e$sxzIY1o4FN+-T#v4fl53#&t&+4~5Y2Q`fY)`!ElC6XrhKIDA4%{O%ms0&}{zU2M4ZI+s*8E9UE+ze~7EB2P)niNm z!+6*d`5Cq4$)U*qBx%b~4k4c#;-h!wHqY6nq+0rw~ZA>0ON$BzqppnhiA)*&+2#V7>Tfnej7Xt|HKG;r>AoxOQW7 zKD~s?wK#J|f@4<$pQ)mU)jTd8gg(Ll_~;7>&qT&Dcx^d{ z+ZhE65pRsnbOC(Dlad|4M$uDpy8aKh$x{C9_0KV+{EoHSrT|OVw&!Gv(w)!KJO4ou zd8X15o|m*=P{7^KbB08xF8K}ni_B2DFEaV-47K?;vg{YGV{WNbTsx08 zhRD(-4EM*;@3VNUzGE7hh@+qTU+y*{h}^dJ8UmT|OZHUiV*;x2ej-w?-ynAE4$2L` zBumw=a0RO1wV*uuO9qb(ugP0j$f*C@z`-6uIqnW7O5u_2JZBsB=e%yw8=;$u-JX2S za^+D>6G%q3C#}l>yytau%%9kVr#p^P8@%&%+4w6essDA!{+)|&pTeBmxqqN3d-8U% zuW(Jx+1xQYhVto5Bpt+X5l3CCR&ZagbqA{mP4`8&%MApx<#o!s6)bF@5_lO(#`!Kko~pNH(XUBe_1kir{tvz_8~M-ng`;a<1NWof zxLfujPcKAXuSt3NR>@h(3>geFz&=IWt6Isi#}>q~mEJHTF(GSrbW2yWEpX3nS+|nt zSA^wN{ZHj-7X7c{bIv#NU&-g3^}qZbSj}#*?v2I*{8} z0Cg3RQc%eH70>!=&VHa!)n%=K9=*j{0aewq&#}a`*MPPkZR3LQF{Ubl4A(NIddjXmI_3XUTWF_C!* z){d@nr!Fo&Tq$#JWqfFSPnOz`*;`0X%LAk(FAOBKxME6KG}d z*kUMzvvRqUWre=UX)I>yQPZMy{CkD9;L&%&Ppnl+fAqMkcQ!lU) z<=9osuxZ4+d*5PNY}UvotuPKYCHcIpsO70UTG6 z5$+{|JZwgO8nzW)0@sUHbGW_OTz-ZSXb!Yht01xx>4qTG?l}*^_okI^8$FRRgj5zcQ~D9KWuStqraT_QtQw z`zeQ)FhWIy$J9vrZ(S2?o4=A7za>;_MDXEta=8k+zmkdtfaV3&L6rH(zo#nbQYrC*^)p>$v`BiLxe?=`r>ThLH?@ zOWC`GD{6?0pA=c(^^ulP$q!4TmK}U8=Et_t5 zF9CIbImvMvN|JdW_uX3I-RRHL6iu#X#Z=Fi1S;=yrKVJ()vs|eiX{c{6v~^8dg~i! zseE`pH4(+b;JKPf`=gVKep+PHq@MXZPV8juX4%49XJjGoy4~6p0e<{Z?G}Q(nGr`Ir_L z3iH0T;{E=o|BW{_r3uxlZ>wG5aULo#D6=W_CfqGRw9SwEq3;dQtjldesare*HwV+-d|x6n?d-}qTJ zu|!Td5FK1AtslkVA=$f@Q;-YgmEW;OthkP?r%reP{W?v@4SseJxDW^pGY75LH%y*G zl80s8?`Urs-?J3rKvHr)aQgSM7nq*=y%qGeYb0kKL92f-gF01f?GFRSOR^lRuVMB1 zJC`S2lhQPwvO;aya<{oD+6ibm7_p9L+dLYU}S^smZzLF_b3B zswO6mGTfC(Qv7?GUX8){o&ri4&5@v;R~-tPVQWp2EvVXeB@Ie?wJt8tXN*abw1A12A0lV#(>u37oHDT5;xT%01JwrUCGg;#3}yX#7Q&U$Kk z4WL26Pp*`i%~VXM-1-NKELg#Gl0tm!$vbfGk~hK0VVvO<>1d|#w#)U8xZFp1E?{Yd zm5~<}8eOY~ibQwI6*BV=MCVDhqPzSGxg5X=uCE@&ZW~7QVXHr2x0dgP=?&2fskBtS zB}FEyc>vbDo&{E?%KRT(`KREl!rXt?mDXTmgd3fnLU;}OM)vb7DoblIYMp>*1{u?2WBRgf-e ze*|V^n2kNz56sJuMG6;2U>mSHLpB0!OER=1`9jwvv`5^^7Fx^)E6Z$imfK8EpZb4tgbsn=c}^J$^}3l`B^U6Q>Kmf<#80G4`$ zEQKW&$%lW@^CBA=Or{?pTVVEiM_2|umy_coB<*poVb>fHU3*$FKI9E?cs0BpJ~H2` zAB5M%(Qks+#?fzs2TXmr^e?V4DV=~CQpapIL3$o{rCuE``i#o>(HFquMPCAsjb5wC z2M=iZ@XkS;)pGBXoXBg%*{Duy9_hy49w{-$6%_Xoe6)(9j}Q(FrJblrQ->vA^(vw#J{}(p`OM|s=Si)n??gTYmbzr ze<7ZLWIja_L!hAHOzFef7%}O&ib^_C(w@X*8|mQR-W?G(Aq*Sw%}8NlN*G4)_^Z4k zXBbbxxaca^GVxR~@QjnRP2?tP90|LRRQrL`$H^if-^n@cX&vA}HREI>C}&$7JN?Mp zHGCU~^R8xD5wTT< zZo#gc!BM*fmDezo$Ke6^<`}Mp*Z|*dB>XU97qHv*O8>r3wpx#`(q&a89ml0cJZUj;?UWwd8)H3?a8U z^JL1i{P$0m`TCzaMV3EHvnrb+kKj+Q%x4WpQXDs)BX2)T>1_beJ(xJo5&Lt1aKYfg zpw1-6o+BqHn10ltxf?V79JvNy+kTX+dX8$GE>FGS@;H9X?yS1pllpL`PLD2p&9~zx zteB2sUVI{R%DK4vu^79ZQwHyi!z{qq2KY5ExKihr$LMG?Ye%Of4iCc% zW4PMvgXhkWk6xhu+hN}LGzrOe<@>Gp)68352$xZQrZm2xWdOnlX0uIaks{? zjM6HUA=UN)jRNwSaQ;@HUrn%~o7@7dDU@}e{&+^d2*4KFptUhTPxI z0jphrJ%n@oz>da$pYH!v)t18G6lX1IC6?|6AtWp#Y1o_`*CI&KGT zx#(reeDm>x2OD*0IZ!HRyv#_F>$OJeFH3c#9)Et*bqp9MjxOLf_#n!$gG48MPYl=8 z_QH302W9tu2ACQeNQ{o=v;ZE8!%N_8F;4NO6zl~O2c%s$xTY!Zp%DMW`CFrACu4jrVj;<18IS)t4 zEV{Q(k*#VbwZxkBUOYuUQ!{~+tu9)&oW^*v6u(L>^qeB|v$&zs2=ksQt6(QopE|l6 z!^kURxaPSJUVf@M>&^Duzyc^nNei+NJ|~82;4=91Q~9KqCge0(%)h<8j7uqfu^lqU znXIh1dz{pZXHXLV#x`UF&b~5pRB$|B!d4tFyp+5UgEn8W`zu$yl>sxPacm}tXV_BL z!6Nd&Toc@LW^_?%lG@ThIyfxyfKT}rym0q?6WmRyb&*f2Az6~ln|H@?EaHe!2w%1wtO!oeg>HbWa@i%sz zHV|gyo|;y4KQ@(z)YhfNiPHCOX0ELH8*fc0IqT49ap)drJLcw{#WIO|s1tfkPt?_# zR?aY-2Nd66RqOc`1Nm8!_Bv^*BHU+RN6yJ1NI2WNd~Y;7vI;HR@LBS-{(H`rE)7+P zlHNLVwxKlrZ0lnB&vOzbx7?j~sec9gW6;=Zh+23hd}Mw#ZH;lbmP4V%%e5R%o+FQM z=lXR;i~%k1eiT=nEqk|VbZ9QZ$b$={LoL)2$k+=ixP`X2fUkI2&{*^Yfb|Px zDKNbqOLdyx+mGW3avp@^W!gKb<34m8<>pe}*@!2roUvUM#~sHc?RR^OC+SP-h_qae z-^pUV;9Oa}lYZECuB_re+i_lWGc*#3zT-UUP`%RgKB57gFJ1(WRd_X@i<5F1!yk+{O(PODL zwHD-FxVp9X=&c5Ix5JCzdCIMy@-Tc3Ja%yDgIB<{H>sV-4RgnD$R3>4>r53KTE6BY zsE-MtS@Oc0F6G-?H7fBV8KSYDjPV((5W54Umb%ZH~F&w@wjh`38|n+@R|SE{`h-}>kHh9Q!`74qsk zn45E@?B(BHai!T9Y-RQG#k;O4=JV^-^;Gti(TzY$I|vWJW9z-i0Np^Nj=^Cjm4mf8JF ztv+*7zAR7>S~h6DRrBb4x$y(ngq-^7=q9Bm+wWm+s5Y0)lX~$4;wTNn{U{j^78R_a z9;+q0heT{Zd95bmiYc<7$2B$Id0liAI=FZUkO1F|+i~<1xgW*!dO*3JI7y!(uK{c= z%Vlp5UB4+nr&7URCrkc^t`lvwzmi2CQml@Z#sJCDlMm@V87l|P4}>h3Y<(c4^FxLf zFW6X%%>>uhWab^^xsPEEs+rYcPLJJbs#@=*ZNn=yRsYG8nIAFF*As^^JqHODAq<_TbP|!(JeBD& z-U?sRNPk)>$M})vUwNvhgx=FK^lk+-4cQ2%|;Dhe8Q&+s-#Q_hK}3n>7N5*HOW@@rfp2 z&Fxl!6|83scRSyBBHw7%iddWt#G|f+!(2s8GXPW;O;9ps~ZFkVSwKvKEkyc=oO0vs2_FW3@R1 zCHDe(HA5FLqh+-VB~S}lvd#E3%k)ds+BdFm^Aakn8S zAG*WfXl4VPR~x8uLj#o$oa6&GH$<;5wUbuE+fX{77dMS~dhqD2(FyH%x(T6Lk)c|1 z8iwzYH^1RA@jjfr@>M@6@ce54$(y2<;90cU)TW^P0?2+aDetOVK!vDEG6^G>jNza1TWKfLs}d;$ss zC7M)nIjQVXS`o^zbyx}aqGa4}4&tdoDbFg3$Wh@Y_!5-#;qciZJS$=>snu?HAckw1 z_QPvP&Nn1SjTm>=%39Qj6!$Zz#S0WfPN0>@?L=mdgkckQDBPgQ;e26A!5?WqcycOO zd*cq_-u*J~3aQ1@7YW*erdBZW1}N7i!{rkt-irJn9~X?}CrKjL}Sa9;3DY zMbf^b4{b-zI-A$Wj*+?FF`wt%W3*g0(!bMlRrj!DN=1C*7`Y#@twLlA;cT@cAAQG- z%g`g1deH!5T=)?w9$;O^6NXC%D4pp~L~mJW>}`Ky41Yp4BG0HouBmgJo?&eU?!%0I z$rDx^E!@D01D%mMQyXRQg-=NFAca|nvhi)3x>QwSS53 z?rO0UdCOnq)ghKygK^{;kF$O7q&0+k4Ufz?Kw1@Q7rQhFOn5T7KWeEr!PVl(JScCA z!*xb1x41F3Uy>?24$!7N#G;S0Oe$!lBNIz(eU`wznv|f9qj)Nwltsflrxx549krJz z)QECpOYXK5^W8t)z{;ma_x^sk|0&svF?;<}T)^JJ#bnX2hnL+j{D@ME&SB6S3nKhipAa zt*^zNu?F>QBGR@8(%cM(oa{7ShExsnJxlXu6+NlZ^o(j2t?&wzjHP54&%9?J=)g)D z%zT^hQ_4oCuLNEi3FyZ&=UG{lNXR0fdD|CQ^sH=DSOU~^Om{rZ$^~;H2TZM~CX`96 z`6`}MZN_VF#=?!!rJO)()q<`80(dq(D@$$eX(wza#K>l$?l$D17;bc6_%@6flW0Gl z_Ge`;M(hgp@!#{yo}u9oGPWaD{tq6A!!@P`lZ)}Jc^jU7O2JM{)1RZ=Z{uAYjy4MQ zxzRD@T09Rck)P(t3$H+bWT`1HhcAI^32Og|?3VfAweZ+`y|wV>=LW|`1<)inBH%&X zRSr_wO)8DuvYifhYI?%+gXVWNZagR-JKR%mX#ngYh~rA$`Sm~U^Oiiz1;FO$i*8M? z4_*?7SHlZqxF#zI&xNboic1Er%{=0~Rs>lw0W^XTJT(sQh7Xc(=Gj9(HQEo~^Sta$ za!*UIAzTZLuY1aqmt~GWbgQ@gITi;9H3BW=$lj(O-V?*sXf3>Zvn)?`PqTHuz<0X% zpR?7x)!UD(Vyo;`wq&cgQuuG#D#iTUhquxXm+MKX=h^v@#B{eisTHT!bcS#i$Z^n= zZk(QWb6!buY-T}ds^sEKFr8kUJgRn>+nrpFvuCSpNq0|43gGt1aT#vo@sgvO@GfkR z&YCtR4ef((!tIzlET=Ba950=z?hISFUAj`;dRFDD4ANKd0u^C6Czjw$eQ|Ud`{0A^ zGXF3_^~?3?ZjS@fYvm7TSpEP^!WC+lEvVUxUbMy#&lbjz7bQ&xHigEMAAX=$CXZog z)b&MjgQ;Zf;dybFkq9H<=MGs3Pb1->7o`g`=VZMUokXqGf~_Py4ljWZ#>*0XkEVcA zayVK0Ygshn44Y-qiZc`^U=@_o^@cv`^GThEW|p)QG(;B0kI$M z=1V@?WX9pzm$u1;{HO1Eg^sEUJHF$aSt#)F-HizB3tywWI0-P(@iI%5*G5N{3+EfZ z#x4Ca+^w%k@mS`OUUWwe4Vuv)@^B0{G6WA1k*?`xhwyBRQPRNO@J%sX1NXz5`BX5G z+UERCTuxG5{kpk^Nvht){3DZH?)>CNoV~B}?JMLx$c>%8Uf{mhrAuMPcC#}idtagV z^9kKdH!o}79=)%iF$R#AZg3}!|>pjU}e<8F`RRhD#o!xv?H z9nhF~eZaNb`979=+VNR$L@(OZS|jp2c&z1Cc;@VqLIc2XhhD|b%E{O<+G0EM)E(BMr58`a4(U=0gW8bv+?qGUYQ95ec!0TR z?x@fuKCpg=tOU;AiP_j14BpcTsFZo;_x>3FxEzvil(X)-iJ|b@8|X7*%PCrS`qS`@=rzJ)7jLcbR(R~_+txa$>LDr4X3)%imzyFwXs-TDmSyuSQ?Sb#MQ`B?q1o;U3lh3V z7hE?M_U#_c`{6w?T+@=VgUhhpR%7wv>5Ng*0x5^L$Kif>YYbPTweY6hvOI@^u6j?_ z@t^MefWrZros0I$jvU&3RS%ZnL5Is%SP4Q_c_-dde7*NPh~fPZ129&<4(cGU#Ol^iCO|`=8Ydb!{5ouiNunjVRe5q3?%9fg}FfEV!7ZSG|GYK#-?Rh z0xwi^XK)O_Z+fCGbc}+wl#GkP7CZ$5vThRQHKg{Dq<-LZBj+g@J5|nAq8=Ra;+Zob zGx98DV>3Dk%o~uEz_~us6nkA2Latn+)~P6R6RZ+m1rLE8$9*EZ^JuR95#atr(kD}% z^@HR__pAMHGF%MGqRGVFV!@O)pn4vk@18ONck|%r>gQLU<~NWJ^A42Or96 zaO9f65$0lLNQRKxs|jQr9;?eYKai$R?MG1Opu1_TzM1x zs0_ymS_|(tv$N*8%%mi|`jF~0%Cw(owXY@h1N%%JW5+c29i~}?#y(1!;gRB_MubRi z1ojQfDut?PblF~D&#-hU>;)PxHS_M$2uBxlIlK=g!-Vq$*%?EQ2~+mrIk@lfFRts&dT|~yw2jN2v3H-%lP(#9v7LCREB$@TriW1qe`5- zrg^5@qY86=h@MllX*R&w@tWx_aNsI1gLUHc$SVY!fXfjl*f6~Rd*kXhxuA>vkRK#_ z1_iL>2dn%7CR_?k+@SWkY@FdvwI`(QH;3zL6l$^DPa+)0z9*l}V7w_kIC#*ZO?kq5 zk~5R(F*jj<)Y?efQRQwX*f=}@AI3oJTB-rwchDS5Z)wA`Cq_w)cEWeX;l1$fariL2 zH+6qhKT>^E;xhJj5y zU<*uNLm*ukIZo>`CqL&bcWUC=5vI%Er%T2$?T4>PkwvpG-GXUz&k@*?A{&9(O_phG zwvihP{m9!=WUtEGkdGWBG`-#r4Ec;>G1`hzy$hZcRH!M+Pie)u=}2hLXvEXcS0Rhsvoh9Dr6B@3Zh9v{ z4>;!~_aiMhO!gL$j)KGXTVIa(kp0=ir1&^sDbQF)Gy+QwlT|=p)nWUihB-}482Li@ z$YN367l-R85VW{4r=9<=1S#*%%$wx>h?x;98gk@xQVy?)q%VM{fk%OlcTXz_rA0^S zC7c>jZcHbS{xdcs!l5k{oaNqaM+B(c(;|a z#fq;Pf#dAA6J+=q+KBJpj66L5e4=~Wf?iCFEGSJ`BXZ>pG&cu$-tL-1W%4AZ!+ ziaU(kn2J50m;&Rt5$>G`jIQZ7JhEsuIqC-LdU8^msT~!q=BN{{Ce6)yGvr1ZoI?~mWF`L0l;4AbB;NhL}*-3hV zG?pf!Gr+w&C1;KT=YI41Zol3s3jim~agCl58uu`Z#c<70D?H0(W_xxRk0(Y+OS=#5 zh~XO8@hSa3Q-d-ONk5iBx%5Z0k&s*F{|LI-v)}y8)*7YGBV-*k+jr#X#?p(e z@*|}Sxy^T^*oyV4DobYYpSVQsE#{&ou$N&VTb3$nkvA2!ff{pUBPhE(H#*yz!hYl> zxw04e2`ggcnltZbbQ}1{cBkRWO|Ani?_`|Ia<2xhHG0(U;{THy=DLruZ=bZ^d|l`^ z#J2uP(lM7Lm*&gY`d?Kb*(Lltr^)I3XZKATow$ZRX1r-~8}jsd)At{o&b;h6x>KGh z!Tg*eTJgIq>l)FjF0uyKqdJYjHCKvGcBdYna9niCHAj`7(>7wb<|trrS$Z;UFc2fx zaBawAxwgS_iyM!M{$q#iIGHB5{e=DID&(adasZIsugC4EeN{f5M+0b$QB>=N z`xz;)%27Ecp>ya@q2PY=Q$-mE#+u$B4{r^4S8tAiQV4`R<#mwnLt$&bjk5Mu84~{N@ z5CNMXlr0)?1M+5KaeVNie0Cm1mL;RtBi@60`&wq4uZUtUCKRvH$|G_dH6VGm!nHSIwyuYW%YFW;1m&-43PtX@SUdTQ9rbJu9zK5-K zZ3s`_!_fnTwvTRjH%i9%@35(o3|&B4>zY}@>O;&vV6Ztlq_&AZLI&VWatV$ZTV>gW zl&ANRXhn^p4Fd&_$i@rFY=4a0Xk5s9ACbKm>Y(zdWM4$=c`eogI$*aY_*!&6<>MkP z`wwo=@q6qRS$`3|x@@DoiojO=xXz{1@@rb7t6#0RVW1vfp~+nRf}G$Z;0BKJ`G{`U zv$Bf+oZOdb(!Em zX(y?KXTeAAyBK-KxCcAC&~co`N%Jd4HADFLBSx-t@+3TaD;7zagv8%P#2{ zEe|6v7P&q4?)S`MJ9@(;pu0|1}rQj-kWswTiJHPm`sk<4L3#GY+>U>_o{ZMlYU)pUI3XiJt!p z^}lJKtmNO`x{pmZZXPFxQ5yVQIZ3$&x$o#7i)_ox>uX4}M z-}Ys6fonmj-gdY{8{99R)QdKbwOmE95Z};MnA}Euy7w{B=d>lX@7r%Y>!m5b*lGaP z@Pw~qaTSSl^vf#!5BF=jW~B5X%lOt@N2Yi(8R_w0ZNeBYk(U7SzGcppo33(a$+=g% zb8Pjz8}(}Utn|=#R-)RTFcY=yY7(`U`-fMPsP+LXQ3Wnr!sda|i7J8fp3UPIlbD19 zvWS2C&I9zAI-cxrLzp+r8jv)Qle`KmC*|-8crMtnzEvhI)w?%~iMMQ6_Ns}s-?PWF zlUtHyZU)rv4_$!eMGlr%!c%`>9@o2!K|I`ASa}VjK=TiydqD`fa*a=0wZ5iTD@BcL zfO~c1yytP*eGQGbHDSnnBgoBg~+l1V28#2%RFW)FR*D_nT+lQiNChdHF!nE3D(Y1`- z9!IoXliq^d;gEIL((XJ-(t)0RUeb^@>j~ogF-5sENwR;8G&M!$|Criwrpj{uZ>c?O zXw+qE`;iPM@R7?_W0-(9!8JxLxX3xuKKLfMt|PT#&!s?B-!YCcGDhE+Dd2nH6&yu) zIm0y}xeVY;;}c&bXj9hE=*a?kJl{Y26SN(-n40piz|(&;d8DlMerryhecZ`g96gyZqkA|EKU0U*YV6uhYuZ`;~>;2kI8F4rG?CKS#?HPN9MtdY+FL9OKeNo7g;hcIz3wE z<;eY5UGS`~bn&bhCrg)-_^g=n_M%*ZT)9)z$_LK2E_EN1u@BIU(DCSF)^2e@jxC{T zyksvU#nt17%r$oaxMI941*SKQA2Qe6*F7fdmvOKn49HNUXFMivFQWi9Wy_ET4`&lx zJFhR70XbXdS5q1rCdzXCZ^@H&{M)zZ4atrAy0(6liYD`AF1ka_zzTrpYx{KW74;@>toy4N$q#@&((v%iFo;gFZ{`cHB!0p7n`((Yhb{(BKG)MMg zE4#2bI%QhH-aIC+Vwq7xTp{H3x;bilL@uwPm~&5&+Ys0`ogy3czwA^^B(H3)!D`8A zGE_rJHJ>gsuIIn$Tv>Fzd-mMii%0jww#l{x<+07Z9KQB~p@W0kKwfB;9oN&`t1cWe zS5QsO=EUz@&Rsi)e6`#t-zS}h=pRY+|G7s=A)B%;(O>-2wxPdb*f!MsNP zaD(3JzX6>FpJd;_WVPKlWX_=T9yTYd8kII(EGuuIZns@*j?NRq`OKiCxstSLkB`it zeei@!{x1pi9-uMh|bk0){L25-a>d+Jff48a`*yp|1GfLly8+c$=x8w+wx) zp(c3uq9J1@`*8?Q;pL+v>(;>V>1NKHL?POOZG2l zE(MiCQJWho_aiT=ltsw%Hy|GwUdJyDue=wxBjq7^`FAX~+JE8B$gaF1Iu&ZI4{iSy z@)6c-o+?TECD#uAs?oXgu`E~tADKH1Uk$IXV$7{(zN-5r8+#kj8kr{5YDH^9l{|uV zTQjdb;6HuaHAChHJ6~PT86)@9{8oQ-KraCc?`A%LSETT9^!wLK`W^10U4CF_8F^tm zNvm8j2^Jen={Nd9x4?nC7m~|VI zoZOV3Ij+=?x8U~ZC4)AcT6iHm7kA{Rg{=DhcMKVCJV?EV9Cc64%yKqBYwlx;*W}y} zE!pQBKNeVdCnZSPqzbU%8)u%g7g~N7<)`#XRsGDFcUalIwuE`BhYq&N=Y7s`PA}fV zh9To4ZIn=gv=?UPIsMS;d#s=ok(3;jIX$Tp+9YqTbmz|r;jF!X=wKBIO`ZFYneK{= z3C`c!9&+5D+>{D2+9P^x=rya}sSj~mxX(HM@cW3fk-1d!aM43DvzAe~1X%LGka6jk z`jdy`#v9#}$5sP#o3sg_xthYi&7G~GvmUgfzQ+vhYzI~VoeZ|A_Y+V1WU9XpTJ$?B zqUWuMJonSF*I5zmFe3W@_O3rFjw(wRNfQff)77b(&`C%F$|x#hSjB|Z))2)=3>qBK zpkY_CLB$bQW@H^EX@w{%yMx*q^r7}7t?3wIh+tq$C&4UP*$L4$A*RP=#&%>^92rG} z%IqM8_I~%>*Ph)y`{$m+KfZIS?)$!X-+jOC`%wkmy-?KnOvkKRq|^k&MxS|}o8rw| zC*=p6^krMg8@@Es+yT&opxdcEONhR9x!dCa+bzEKnG1|zMEkZ)#v7G_h@I>9%yG8h z#2uWJUq_=~glw94;2QU$TtEf8&_2qu4S9Ot45^i1i`y{} zN#f8~#v*q)aNiz`JJr+Nh6;VQ!kuO`f)20zTz+|mzIq$RYbo5J8|)yIy?DK(Um4`y zO|hOq<-1U0v9QiuoZWH5sFMQAA@_{XXTd^H4i1Rm@^GQ=5!0?df$4b+PfE_x4 z?S`Dsd{Gm=BKJH}%{ZyZb3l?&cRGE42?`EVZ(jN$>htzybHT;=(aCrj_1Q(BD3pFT zLt6BJQ_hfTWUcxgmJ%BGgOv40%iU=yeW07($I+jfl4f)R4g%u+h^EI?u|^DR_ybk% z#oJY79M8_s{Qo{FzlKp?ybsTK^zfQ&nlEmc?n`tgU{RkhbbrVXoHo2Y8;TZZM{E#{L*|g+&FYbXmi}XLvD_S<5%eTCAK_X>8_n>I4Z%` zenXp*_=C?(O98C@R>BKb!+8KJbU~sdl`8{NW;0K+aY#*lwpCFD3R?u+1wmTPwj1 z&9>vkG_!vRHkReiHUeOqF0grvS=`26YV?7P$ysZ8Wg1$z)IEjUI_5W}_1j!#foe|cG2o#zIbbBP`I zlYw=+6FrvS2tIl#3{!2_&`yEyf9#Fz(DM}7@hIhgt6lX=6l~uLRjt2(mHjeBx>uoR zN%zq`vR^V?FW|NNN}D&MH<-+rQw}x;b^@j9$M@ha2Qs+_d`KMrC#=BTh-z0T?>mBw zw8|%2FQVyU-Y?DbQwtHb*4T8uA$K*rzIsC88N_`>+N`ieEn)D$+L-fJ6@OFY{vs+D9x1v*aVnG zmY(kr?>%D9*TFU3f=(BYVYa7)0LK9<#p?ywzFGkD*V*v_a-Vx()_J)*O9ZjGyCO&$ zs8FNwafjISDAs*&)@@KHf8Ege-_>(MShVi4;~H6duTz$t0cvUW7Mm0$1CY#T!t6`9q=hdf!b+4nig@1r$2J+Uu;=PB>%sF0=fd_5*C0zR2F7lYq?>EoUK^Hs%S}e?R zdkBSrdcZ3Lpo9`0^E;ZQ-gs~L<^q60L&B@e2LC>wxQ-vf9H}e2XMhN zs+-Q=%X>l|$Wf3!^8IzxYUw4-pvTZ^FL#2EObJ`Q?bA2x73Vi$H2_!Fioqj?ykW0e zcw%6Cwy8pFu-K$BUAr(B6KAAPL1Hz^aC^a42H}`g^oQs~cJxZn5zw-uK1N4LNACk0 z4%zX1arb5DTA%@-0kP+N_hKUkShvHDkCPw0k;vkG89U=Hte5gYkXjB{1elj3j;(Sp zN@)Zxec6sziEF`F&^80o|02mg$|kmto>u+@9)xQCX@4(c}A#eHB) zJ8bz`Q2i8lyBl18r{X@qfbn9L;%rB2_uBC>*_`A&K!;fWG!EEVi1u`0##4#^2HSMJ zb(ex2>$c^00qRF+;N@}M2Ri@P=zSQb>VaNOXH68EVD}}IXGcJny{42q#Kxy^DhD+J zs)7pJNe!VxO4c4YK-iXVFZB%=AYxsmU^~G|-G{ow!Dr0Olx~o{h2(jdHEBkO;C|%9 zHfrq1GXQmw6F#&Z#ZDR1LzF0yB#cbvn!_q z?(#deWqr6`yoW{905|k|?5)&CT?bHmIRyG3cuGt@i?0WdAwFW ze$Kooxfan{vHv+Ur=C85rqOd!Auc+YX#Ke8&54shI_h3b1c3$s`D#L{0XRWs5pbX* zDP;;3)p7tRB}AYKfJ{3`4VBhPA$6Gt!#7nAh6C+Vh?PPn>A0075>So`@j%;YGoQyA zhN>t^M(9OD?;PB^aZxpj2v9pHC5J!^S3a(O0`#_nQnKf0_-R(!yQsRIltlhbNo54+ zs81;+1Of_p2~c|}C6B;D$w!+0QzFb5aa?}u%MFslw>&A zf+ZRP=DdrY#0`SWqBH{3$vKeaWHkp}N&VJNwXOxAYBh^v$XZ`OwX04+gCQ+|q$UNj zC?yO~1}W7%I1*CVWl%~F0F^L~UzFF2z72Gf+OEn6!W-D#$}gIhbQr00yjjWC zB`^qpDsdQAY7t5qQEGhvC?EIl^qc@>uATG@+{j#rKsIg}kTMi0AV;MNfbs-Mty-nD z5NK8@^zVWi-Do?Kp$+Y&Je?~MNg7aSkU&0q78TSQAd`x4qlPyTsKkxx(@3CIrL++U zily7k3$v=pd^4_2%mW#`V5pojN-4mte_!)9b7`_!2~4dnBF!3HI6|(sta7o?vfN_j zN~=)(CS-c*pW57@&3r~XHwqcJ&`)xO(ee<1;=-5A>&1N`b8a?SFCY`tFzRi3aFDZ(Y8=C*RpJ^G z!4>GCT*4G6LbftUn-r)jG6Zp_lsrm_;>y4!!#M6#9BozF1TGp+sYXn%n0m>4ao?<+ z<~tqxhHkQkW^Nfu()ab=VhyZKx?4QC*IIH#Sp_XGnwBZ=+;tS4r*M@@=S2%0uK4*% zj#P*lUDgFjVewa8*5ahw#r0j*61V>-TTS$Dfp`+BnMGTvo|-0?bI7VD31ufyY)G6S zBlv0;2=}6gIQ8pz{2q$ci_C6oZT-YSwq1J`wH*KR`a_obMJzLZi;+d}-^tiG!1~p% zGvD_IrMHjy>^m6OSS%YBseJcxdi&{&wL2uP*NP%+XzDALrPr}S_Zy5otf-CbX9F?X z$`Qhsv247B^$K5Q9P40NNWV3WU|q|&Kg_bToB7DqB(cJjNf*PavYr*1f58exS2510 z;)0D8jH{-|E#Op@jK^28{&*GR{C5~vg*jjTmCS25vmAX;*{4@}w8CqD%L)GDEW`J3 z#<8`m*nNs+>@Jpl@?3$*Fpu?1RL@j?h9w%I?|#-BnN5=xYwewEuXlv`$O6t6+2G*v z!*4J#vWI2vC_7fmM$V8=kE{q4swX_O_Y&4wf3TDB=yJxb@3IWHG9Ud3%Ocf70VS(< z&6MrOBO+%oR7=L*XWZyvS+Pt06;?~Mut51l%{$yO=TEtSGTP-4+WwPqn{vwPKQeBq zWZ9m^dOdg4Gf{D#Drg1csckGn?aXJZiVZ)&eE2ByO|P&lR6RGUd?b4>>qSE>OO!A4 zs38lgp3JX5$qLmyY{(gAoO3nf>ZL3z%2_roVd?mkW&dK9!&98EX@lyKFBliAmgcWy zJ=s0Dd83?OpHs#Ot@$h?s^IavSz+j7<_oW9>Hih;tsgK>3`ysWjLT=UY(30+g@+gq z{)w^U48}txQr2tM@0sv-vP{&lNKMDy%Q$0`T3C8+V%$mZ{1NKj;(YmqEGtTw&%1$f zr|OZIS_ksz6p7F$hlu9?T2-)evcfYN4{c$^h8tOCIhb!=#xi3k^WN)Nj;IRO{g%_y zf5v?4-!XQ?SQe@2SbQ5W`G4_0u%fIMZaKHI;?Pd^`u^7#CpM4Zv&=U>#QEx?oUW@b zj~!qfoXaw?Ddm2|`Xx5YDAMKpbJ9wLQ1l8XG=Ism@)%41Do)S)8^&!{vFs~mKAOS{ zO~0C!8EX3Vs%b5aD>z;MhL`C4Z#jR%t1R=?vEl)W;5Dq5-NDkI!?Jie7tna6lBz<9b)vnC`GPj-#P!;US{jYVIAKDybXZkrL>-wj zKH&m-)ie#<#`?`a;axBHGsZzStOc%TT#H?ff}@>f^9JTy<`ahhP0Zp1Pb!aDa6e<8 zS_w zCs;A-UdD}TdSg3bDmwCV1^#Xs*IDa$SNmM*t&8F%L)%@>IVa1VZ zRt)cEnW0)Z_4ka6lvj7(&RCVN4SmG<`>L4FRzsRs$~avOWtFO!mB#vYezpHc2U)RN z4Z+k>R>*pu`No?VxBiG_ZUggm!zx{EPK}>4j$O=pfuoG8US!$x3CqZxEC*BFJmxLC zI75k%yyZmF59|H(J{Dn`Wc_p%tjdK~PE*UdT$&ZrSph14Ix8T{pT-K*PpkK9{`%>i ze%kl*e;S<+zW4q7pWX%N`}se;3sCX@=kyaNZm}-k_hi3y&&(vRNQzj?lPbiD2;M7( z>6I!%Lf$Sm6P1gd7qp-bUucOUZ;R5Sxkq-@AEG z90olv7hgO{At5K;V6Uwgmka /sys/module/dwc3_msm/parameters/otg_switch") + + bus = SMBus(7, force=True) + bus.write_byte_data(0x21, 0x10, 0xf) # mask all interrupts + bus.write_byte_data(0x21, 0x03, 0x1) # set drive current and global interrupt disable + bus.write_byte_data(0x21, 0x02, 0x2) # needed? + bus.write_byte_data(0x21, 0x04, 0x4) # manual override source + bus.close() + +last_eon_fan_val = None +def set_eon_fan(val): + global last_eon_fan_val + + if not EON: + return + + if last_eon_fan_val is None or last_eon_fan_val != val: + bus = SMBus(7, force=True) + bus.write_byte_data(0x21, 0x04, 0x2) + bus.write_byte_data(0x21, 0x03, (val*2)+1) + bus.write_byte_data(0x21, 0x04, 0x4) + bus.close() + last_eon_fan_val = val + + +# temp thresholds to control fan speed - high hysteresis +_TEMP_THRS_H = [50., 65., 80., 10000] +# temp thresholds to control fan speed - low hysteresis +_TEMP_THRS_L = [42.5, 57.5, 72.5, 10000] +# fan speed options +_FAN_SPEEDS = [0, 16384, 32768, 65535] + +def handle_fan(max_temp, fan_speed): + new_speed_h = next(speed for speed, temp_h in zip(_FAN_SPEEDS, _TEMP_THRS_H) if temp_h > max_temp) + new_speed_l = next(speed for speed, temp_l in zip(_FAN_SPEEDS, _TEMP_THRS_L) if temp_l > max_temp) + + if new_speed_h > fan_speed: + # update speed if using the high thresholds results in fan speed increment + fan_speed = new_speed_h + elif new_speed_l < fan_speed: + # update speed if using the low thresholds results in fan speed decrement + fan_speed = new_speed_l + + set_eon_fan(fan_speed/16384) + + return fan_speed + def manager_thread(): global baseui_running @@ -233,24 +310,18 @@ def manager_thread(): start_managed_process("ui") manage_baseui(True) - panda = False - if os.getenv("NOBOARD") is None: - # *** wait for the board *** - panda = wait_for_device() == 0x2300 - - # flash the device - if os.getenv("NOPROG") is None: - # flash the board - boarddir = os.path.join(BASEDIR, "panda/board/") - mkfile = "Makefile" if panda else "Makefile.legacy" - print "using", mkfile - system("cd %s && make -f %s" % (boarddir, mkfile)) + # do this before panda flashing + setup_eon_fan() - start_managed_process("boardd") + if os.getenv("NOBOARD") is None: + from panda import ensure_st_up_to_date + ensure_st_up_to_date() + start_managed_process("boardd") started = False logger_dead = False count = 0 + fan_speed = 0 # set 5 second timeout on health socket # 5x slower than expected @@ -274,12 +345,15 @@ def manager_thread(): msg.thermal.batteryPercent = int(f.read()) with open("/sys/class/power_supply/battery/status") as f: msg.thermal.batteryStatus = f.read().strip() - thermal_sock.send(msg.to_bytes()) - print msg # TODO: add car battery voltage check max_temp = max(msg.thermal.cpu0, msg.thermal.cpu1, msg.thermal.cpu2, msg.thermal.cpu3) / 10.0 + fan_speed = handle_fan(max_temp, fan_speed) + msg.thermal.fanSpeed = fan_speed + + thermal_sock.send(msg.to_bytes()) + print msg # uploader is gated based on the phone temperature if max_temp > 85.0: @@ -352,21 +426,7 @@ def manager_prepare(): # build all processes os.chdir(os.path.dirname(os.path.abspath(__file__))) for p in managed_processes: - proc = managed_processes[p] - if isinstance(proc, basestring): - # import this python - cloudlog.info("preimporting %s" % proc) - importlib.import_module(proc) - else: - # build this process - cloudlog.info("building %s" % (proc,)) - try: - subprocess.check_call(["make", "-j4"], cwd=proc[0]) - except subprocess.CalledProcessError: - # make clean if the build failed - cloudlog.info("building %s failed, make clean" % (proc, )) - subprocess.check_call(["make", "clean"], cwd=proc[0]) - subprocess.check_call(["make", "-j4"], cwd=proc[0]) + prepare_managed_process(p) # install apks installed = get_installed_apks() diff --git a/selfdrive/proclogd/Makefile b/selfdrive/proclogd/Makefile index cd970c97e7dc91..e7a6a57f1dc93e 100644 --- a/selfdrive/proclogd/Makefile +++ b/selfdrive/proclogd/Makefile @@ -2,6 +2,7 @@ CC = clang CXX = clang++ PHONELIBS = ../../phonelibs +BASEDIR = ../.. WARN_FLAGS = -Werror=implicit-function-declaration \ -Werror=incompatible-pointer-types \ diff --git a/selfdrive/radar/nidec/interface.py b/selfdrive/radar/nidec/interface.py index 554ce944c629f4..dc8b5d073eb5a8 100755 --- a/selfdrive/radar/nidec/interface.py +++ b/selfdrive/radar/nidec/interface.py @@ -2,8 +2,7 @@ import os import numpy as np -from selfdrive.car.honda.can_parser import CANParser -from selfdrive.can.parser import CANParser as CANParserC +from selfdrive.can.parser import CANParser from selfdrive.boardd.boardd import can_capnp_to_can_list @@ -14,29 +13,27 @@ from selfdrive.services import service_list import selfdrive.messaging as messaging -NEW_CAN = os.getenv("OLD_CAN") is None - -def _create_radard_can_parser(): +def _create_nidec_can_parser(): dbc_f = 'acura_ilx_2016_nidec.dbc' - radar_messages = range(0x430, 0x43A) + range(0x440, 0x446) - signals = zip(['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 + - ['REL_SPEED'] * 16, radar_messages * 4, - [255] * 16 + [1] * 16 + [0] * 16 + [0] * 16) - checks = zip(radar_messages, [20]*16) + radar_messages = [0x400] + range(0x430, 0x43A) + range(0x440, 0x446) + signals = zip(['RADAR_STATE'] + + ['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 + + ['REL_SPEED'] * 16, + [0x400] + radar_messages[1:] * 4, + [0] + [255] * 16 + [1] * 16 + [0] * 16 + [0] * 16) + checks = zip([0x445], [20]) - if NEW_CAN: - return CANParserC(os.path.splitext(dbc_f)[0], signals, checks, 1) - else: - return CANParser(dbc_f, signals, checks) + return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1) class RadarInterface(object): def __init__(self): # radar self.pts = {} self.track_id = 0 + self.radar_fault = False # Nidec - self.rcp = _create_radard_can_parser() + self.rcp = _create_nidec_can_parser() context = zmq.Context() self.logcan = messaging.sub_sock(context, service_list['can'].port) @@ -44,39 +41,19 @@ def __init__(self): def update(self): canMonoTimes = [] - if NEW_CAN: - updated_messages = set() - while 1: - tm = int(sec_since_boot() * 1e9) - updated_messages.update(self.rcp.update(tm, True)) - if 0x445 in updated_messages: - break - else: - can_pub_radar = [] - - # TODO: can hang if no packets show up - while 1: - for a in messaging.drain_sock(self.logcan, wait_for_one=True): - canMonoTimes.append(a.logMonoTime) - can_pub_radar.extend(can_capnp_to_can_list(a.can, [1, 3])) - - # only run on the 0x445 packets, used for timing - if any(x[0] == 0x445 for x in can_pub_radar): - break - - updated_messages = self.rcp.update_can(can_pub_radar) - - ret = car.RadarState.new_message() - errors = [] - if not self.rcp.can_valid: - errors.append("notValid") - ret.errors = errors - ret.canMonoTimes = canMonoTimes + updated_messages = set() + while 1: + tm = int(sec_since_boot() * 1e9) + updated_messages.update(self.rcp.update(tm, True)) + if 0x445 in updated_messages: + break for ii in updated_messages: cpt = self.rcp.vl[ii] - #print cpt - if cpt['LONG_DIST'] < 255: + if ii == 0x400: + # check for radar faults + self.radar_fault = cpt['RADAR_STATE'] != 0x79 + elif cpt['LONG_DIST'] < 255: if ii not in self.pts or cpt['NEW_TRACK']: self.pts[ii] = car.RadarState.RadarPoint.new_message() self.pts[ii].trackId = self.track_id @@ -90,6 +67,15 @@ def update(self): if ii in self.pts: del self.pts[ii] + ret = car.RadarState.new_message() + errors = [] + if not self.rcp.can_valid: + errors.append("commIssue") + if self.radar_fault: + errors.append("fault") + ret.errors = errors + ret.canMonoTimes = canMonoTimes + ret.points = self.pts.values() return ret diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord index 1e28cf22c92aacf8e162d7f0dd72a16a3ca9a00e..fc78d8ff800c89a25cf98583e6000cf7424fdd06 100755 GIT binary patch delta 285712 zcmaH!4V+tLmH%&MrfsIL=?iTrrIWq@p}fUXA%z0zOo7lAh(i}fKnN}RPX#qCRl|$k zFs(W&O2TxVD2Sn;rqx}uz)Gs9p+z?;>jq`nQBl)^Zm6sqpkM}z{h#MP=iEH`(b?g1 zNzV5?Z}++9{O)saZqoASSJuC^GUK1sIKyM9zligH%L-nZUG|ODQx8pZYQUo|SrVvSYShhqro8UX)>sudBA} zCRYvb^=z8<2Qq$1+mp0?YWUQS6VCWAdiQnO{*AVKY5N!2inKYyq}M!c^7riUmX4m0 zbno=8ckO33lU`4w?R#u*rPm+P_ItL!!LPp=e%3S3-a^*rX;XXupX`yBhv?1Sw0)4a zuh4cbZM$gu32i6Rb_Z?WqD}p6rY%Do@0;~7y`Mnaztc8K+m~s34{c}Db|r0lXrsU3 z>pB;${B%=|}sCx4I8n@z({O`6^PZF*Ox?T5pQCe5}#P46D3?Q^u9N81Io zslN(sFVL2v?dP<;i?&;7JBc>+SEcQv&O6I`lwLnX+YPk+jz&GJFJz)#Zl|r^ zu+`hUXzONnJiV@`?P|8w%O{NYJB{~WqxUz{b}en+r0qJ|cF-n&z531Y-zIfm{0P0j zkG2wRY1*dJrvARGU!4EnPygS`_6WTW@_Y621=^;oy}39`?-naWe;=W3t@F;Z-pjB5 zM6X|^?Wb(Z%RThwY1%$X+h?eyo`s#(WJ}aUN~zaQYqk|>3?KAf==u2YqV7vQTZZ2= zb)M(f^nRYFTm65y*gfi5H@tebfB2!v|K)i}`G+%8{GKZvZ+S|{GimtMne&FdQ~i^_ zKFzXbQj^J}!^@^#?RkCp?x|;a?sTezPV^7grp7&=99})`T{a>zUpl9J#LxdJ+m(yj?bAm#cw6Kf@jz> zt7q6hCp!6Z8k3ri`rn2>IOoCP1PwTFT*z~cYQwY3nU?f%f%%Qgbx&Q~-)&Ac9|`$m z-#hM1kLSxypIckAFnQj|!@=YI!=ZVhcYVq!tR|3qx6RULd-86UgW>jbD=Z8X@ADE-)VJ~vrCcVQ$#m=y^LK~=553OblUpiw@#}LS5CiSQis#HXZX}J>=V^n5B+!bWEHZO6`*a? zG6xmF5ZH%}%Es z+e(6CV2iGh0{$HHH1Gvmb@?ISJDF#IKd@KtSl;2J?y|?eF1=?3s1W~{?w|;~#JmLj z){pD*W#ETDsd>fZ>g;luD^yJf@$2u>6-I%-z#Z3s581kW1NZ>%SQB`BcNd@CUe!S$ zGm#^Q`tt&hKd!kCc$v8$c;H`k`2g@8%!98^*JoGhxXz9cR9OFA-B1|#x0y$P`<~F{ zqrkT@kGWj;Z#~D30oUP7fVHBe8;S$ZF;4(L!aNE5`n|fH6!5amjx;y|-_sQ`z=tO4 zAk6`fU80hjR@e^4_&5t6}W$`<~7Z2H~sRw zXLYFX3|D9X_pj3pHG!{UZoSqX)CuO^HcrPs%?@9igVw;z{lII?1Hjj;*8>Ux4@}aB zEDZemGpW3azX&*XDhK_=fQPuD0pQP_q07gCPvv%!z$4sFintU1l78#Cp)^$3!8`+e zfE&sIFI}Mrlm~v#m6{h@T<4#6ik_lU%i+vG<9E738F=vbnpcs}(Cv%@ul-qPQw{ji zS6DLZ;PAh9qBDRd@CbKcz1|*NPhYOfdx0Ne?gO5=N|z7V;7I%Q9t43GKBFsyfWN{# z47~9CF ztkEy%4l=+ud{Ofp@SXQ+o(CS!XkGwr{iEU(e~^ghkgz-!EhfO~Jyec z`JK9a+~g|$Z~dfpBuxkLDtDX$zU>ZOJ`KFgdA4AL9b>#27kJe7Cp`e4ws7XaLVKZ@S#sf6Hnf z(iN;X+kW-+=+itz#2O;P(hA;0l4oR-9Zs}g6#_M5SOpExXwSR zP-{7ysP#2<(A9yz@+mzN4d7DF;(D@UJGo;&@Yp%F-h%)*n%r<0cw|fuC<6R}`}KgL zz!P~sWWXDr)jV#4qsDducw|^tNCGeK)I0^e$$SX7#XFE;?ymm_zN{O{L51g-=Yhx0 z(znqH!1IeWF9Da1%kA8@a@;|s-C>>n6+NITaM`mu@Zw5+C>y{fc)h&m5)&DxJjI_M z95ueT97N6yN0D>KG2qg19C(uLgnCu+FC*HT@^20E67X$b*X7H=%gn35lRThN;MaevL+5`D9BaOeMj>K z@HF!#@MoBNc>prgVYYp5!TR5NNO$0e3SG=2z{?lvLo)!p#yk#OI!*}>@;cwTh>x*2 zm`jDsaQ5bTb`HGNC-rdiz@=OXcz}B;0~fig0&lQAs$W|t>(mc)$2F+H1+6CVJa=sU zO^2o&2%DUq~n}d>=?J)2fcN_sO9mjwt*&YBsbwBm1f;A2fDVPEt zi0}agE*9O(*qp<{s8kh@LONkVb{|{~Gfe@M|uftni58sv9aIU#58pcVl_13#pp2xu<7h(zEav_!) ze$SS9b{f3lknUy(_6@DpF+sMyz$G$#z%9PO4FHz_2mz0&0jbD|f+NWzjRBVd#erwo zP5_q~O#<)Yfu@P8{@vV>Da}EJ3=b#|TxPBayvBA3xXfI+#hv~wFOR6&a;R~+xl;#T zlw%28X2{D)Er+to<$b_2maUI@5FFNJI*3BRWzV9(LtH)v+&whFV_ZIIgF`w<1JAHM z1U$Jyr&$g;caR4zw+4#L-IZgRK?y26&K*>Mm$`!~aOt1{JbtB~(PlfhEqPYJ+X3mP zp98ae!0)+5pH%(8SKO+30C@T%ng@aFXOk%YLg0{xlfuB|;iL#~c{V8uT%Jve0hec! z1{7EEFHtHFC&i(HJe-sOF3%<j5hLxw}8pFEtD0bb^3lXAf2 z*`z%1Q9d*U;7dQ;rSrcCj(a|=k69UbkYl0({B-W13VeY1DDVZ`eyxM^UkGOWgv-iN8cK*mPk`lnk8UUhJjjpkRe*&!hHj_;6(sMAz$NcXz$Nd?z$Nc1CRgz zcs-yY;CY)J8E`C^uPfw$?_8jH9{ALSniqh}xu6JK&INV}9C9uw1DBYn0GF7k0+(|^ z4Y(Z2y5_C*f0&P111fA|ZgC7qtVly%;2|#W1AZ&>KpUsyFAW9T9P}kNt`Gu#GxG@W z65AQz)oXRM=YTuqRs0pe(c}t6;L<@Ec;GtSK^1tEc@4N^S%bI}|1zcW{HMi_Zwi;^ zOMSrQ0oEY!0q!^qJjFcP;yV9w?1;ASrbyO+IjB&atfRdM{K;qZ43&UO z@Rotg0;ghdC;udRtA<16U!6M`1uoHB11`Z^2QI_7B?^1$!X z+_nnfC~}1&@HsrCCEzLM72r)CP!;%6ZolSm`bMq>md=&3{;S_eh#?kW*)fcW&yb9X3^zZ zk1Y|-lIu`1+PWiD1}?f;0WP{(1unWd3j76|v$+Ni5zabr(ai>M(ak1s(M@Y=`_ z)AoWxgwqE+$-(6ZURdB$Lod?z(r`2z(r`&z$J}`fS;~rRK;Hg90{K4JaB2K0DLKz zF9MG6FB5m-UldBTy#f_P+ed-RfNH=OaL0Av1I!yOuJeyi23E7>aMDlC1r{rz z3{=hqUf^;r@By}(`RW$s=NxzY<2T zy}OC7u7_6el;)v=G*kfI;D(C8Pv>?@z+LGTF4se@^ooP8hg|6eE(59o zuk(QFz?brX8o+H=dcomJFDs!0sVlv}UFij07wH9_n&V`JZH2%wdb8H*FmU@e8A<{`+;xZ9SFEw>yMRYN6>XB{i9zb*`zxN0hcd#hk?tNyQ9Fp zAJ9QP0Nii$MP~vW^7Zr~;6vO{9(Zb&KFJh-pMJ02fg3UG<` zDsYMRQQ)#*scGI?|4X#jp@Kwv1Gq$c6SzdXHM9M+D+?BH8>izh(e7(=(E6WmviX5a zvELh^io%ok@k`+q=D#*oR z61Xf_Qov&zTxsCf|Dz7Np%&NqH}Dnh$g~_z`dMGrJO})h2Q<$Ezl+-`AeVb=z>`^9 zH&g=03La@0xLhk%fJbt=ohooyu#5ti1xwuqhvabs_*9Rjyo<~G znY-)%2s;8$K~^k5;Id!|0ha|!1h@<++Rkn32rE>q-C>1!Km)*K!4d~93zh_MS+FF5 z>jewNUm6^V|EINj2)NwI%me3@j8y>c`(GUsMc}I%9CM1R_?KhmN-tD!r5Cs>y}(`R z1@20(!JYhbrPpw%{BxxjxGTNDUFn@Yj`RX2<<;y=ifQ2TvBwZ_yZO3~#tb;R zUei1WT&@-Kz~x%809>vWi@^C>(Y8w9kc-7KaJpD@&IuLZa;;be?n*CkS9%>z@h9mg zdE9^sD>z@9z?00q`by>;x376rbP`gQUz z297unXaKk?y}(`R1@1~OaJg1Y&w=%SEWy$X6yPD1uj_DP&3#U)0^F5e;I8xnccmBjdYgZ^uMQ4ZdV#yr3*437$pc@}#lZ;tIp)Q7ZoAT3YInHOTLv!DTLCW8TLmuCI|^JcdMW;D;1KDp0~hIS z02k?P0+$;O*1UE}7U}gWuHs*!SESbm6-0Xdz(slkz(sn4z(smP26ysLq&I9hRQ`$d zMu3a-MuCg;#(<0T4ge?R)%hO>he&S%xJYjjxNm|Ex)kuyiJGT@TVBnF=E3@Z$0Y5@ zK!q2W=YSWP=YcQf4hq2I%!|Th{XfKxk~nz%FVb5EUgYu>;3B;I`y(9URYa zzBYh+d8#eWe+gb`#|!*vZpR1Q((Txm9~>gR0pKFNLEs|2Vc;^L2=FI)Kv9QN{K+0P z*%5;ZBE18^MSA1FMS2s!MS4>vSMgtB=}nss;v&5n;EDNKP;$T@nWBR?k9?};1>kDY z>*QY%9CE{<1YD%I3|yqQ0$ilG3S3Js{i7XzSpSRk)}Vq&ZymTuZv(hUZxgskuXVgg zveqB>Ua!}6DE+hC52t;=MSA_fMS26kMS6q4H`x5tUI-i_yo|Ta?u9IlPUcJz9rzU z^a8KmrOQ`<%V)|};I8yCch~=}^g;z!dV#yr3*41n;I8zZAkym`VcWXrZoLQIc1KHk zfxFTR+?8J7uJi)epD9!Pg}^azsy=36;Lm+j4>STi_HoUlz{7kfW56G{O_v`~T*ben z-!=}GI8@khvK~+Z_|4mOLn+`Aq-o$`Zhy$&PX67>j*Q_@M<)>19p`|{r{8(ti5+@C zMc^`^67bNHNjm?_;JBFwQ~@64sjdPK@l=lje}H)n_%nPc8z;c}zsC99gbKMidM2y| zZP9BzeVpcA;Br6F2V7QGe&MqIm;4ThgV+DEv3rBw*HCZrBw;ItgOl=SMe`PtBUDR`8QVwR~5J{tww=wI8m3c0S_{-13$8Gl0N@8 zz>(kzP2jlzX8~u4%v_NN>IFW^+y^{7Pq*Vg5!U|}I|5MQdgejkE9UEl!oVesBfy{J zbd9=P>yOoB$AIfl^G{1Nw&TDb=kf{Q4dzMUva(76f7<4+)1<*6OREfU8Bh-Rx4Gjy z@H+DXa9LT|MR3T{ssvn?R%PI_w5kFR-=bGmqrg)uwSv|)Z>|4hT%iFKWGUub*e<>G z9&P)954=~$L;(0J%!6&5j=yMisLf%yHz32nMXDpfMXIB~MXF=K9jR9FHvkUN>Ns$b z>I86+>LhTH>J)I1>NIgD{w0q^tB0V1+SD{`q@QSY z3Ajjg8MsJw1-M9c75Fp1~Da}>)VDDnLO zFYu}SuhRICU&m4kJjCS#z@OxS2AR9-fBCv$2r9@8$T0AixSLPF%Pzm^RJfO1T zD*olz`*_bPP(if13S6Xm6u3xr4Y){k!{AQ-g+8RUx@kC6{)zN@1MSi~%H@5)nJi+B-z(uMDfQwYe19tnK$z^i_D#)@r30$N) z1ze;$4P2ypNVu&3MXNL7;Pt;~bq;um_c#w+q`ClHq`C;)7OgIUL$taKTpq=)06)S5 z8U-%Lz6N}SE>HOnjyN~e0KPM+W19@(~^E0f$rkO9lDx)F%NvvP8#P(&Q@t3cu5PmNFfR|6cPna9OYn0hf!*3~zref-+-XO}-zYe8T%iX1 zIp%fXvS4Wdmjz1`xGY$_BuGyDivr4?`BL$B>_Bg5=$@e_ge zFK}0Sf$M8UioXCjT3 zZ*aPnfuGKMTm>%ej4s9XKQ~l^3QM`6I&fEdfxFTR+?8Gyq)u7?%ZPm9;Prov2jmC7 zfCm%+?n*CkS9*cluJnS#m0sX=kzU~P{hm1R@F_Zd6Tr)VaN=GES(e8%47>1_ZP>9tspblTJLml1i}9Q5oLckBb6V(ten(i;FS(i;TsD6fjY5I977 zBft|M)vMkpa9Q;Z01ut2(=-me__7Yt1aT++MFH0w(vBol5a~?;7wJs{7wH`WF4CK6 zah-o6y}6ddNk5U^JaCcT0&tPuB5;x367c7q;PY=893s6H;3B8^oD?^Ikv*> zoX-FJiASW}Vdeg;gE0#HR^~C_@`H>6z~u)SzKW-`2t38S3|!i&7~ILf68$}5 z>8%47>1`rEmCyecE0xT|>D;jwc!IePxJa)bxJYjRxGZ{ur^5PQq&Ex|>MXqx;3B;- z;6tbDbQ}QQe4W<^!e#xRILw+X4qpGq`NwCHz~wo?6mXH=G;n!Na0s|9pLk@zA<~-z zF4CI^F49{7F49{B&Wm39{x3L0ddtA&Il&5Wk=`nBk={|@BE2<-Q~XQNiS*W?f_&o9 z0A6b9L)HW?&k0(~+9g?@6ZD!~<)1t#=rbL}lX(odJSR8+Tt1qK1DEFnlgnWJFKLs43Ip768u&fThk(m-f*IiQoM6u7 z&i>O>^MitU*P--}z8lI93KoIqIloK5A9+O|f->;f|7czT{-n)6Ib8*ZEUiX?OMcgY z%hIY2Tvk>M;F8{U6C9G?)@kk0EBWmOF8S>P&iQTmflGP^G;gi{WoZ?J3X&;C?;{<%v7-FABKrRUM@TsF2_aMc}KLmw?Ot#4_-k|H4_&;yVBQ4ehA5 z98UVl(rOfVgv-}}%hIY2Tvk?1;Q7<}{BLnS%S=RhO1;2$F!uu&JqQ4gaQPtcyO@V; zaLCds3|y905#X}4iUF4a4FC^w$8qNF`hOcc5>P>wR!QKpv`PV&rBxcZtgJHaoPH1e zWBRH#*Y2?7LBRs>GM6s`m!((*c>YW+WL4mEJnCU}ioa2CJm5I!*-zkd6c9{`7FbsV@zbpp6t1t)=vRHuN8RHx5?^}lHK5LV!;;0$n)>Kt&9 z>OAm(Uw=cQAY9h}Q|I$nC&a<)|HECHmw=CQkd}d$xO@fpjt<>U6}Wx<7M+XCeT+$~**I+6gax>E>b-JT%6oaV3G4qkGqqzBD#%rE4Y*td*MW=lHh{}j zaMR_^{r|V4gi;{;5hJCX6Zwg04`U-N#Jr7oYK6t{+FxZG*pnQ;342qj+G4X^oR6- za=_&(xX{Mw_)C-)+Z^=l7k5ws9${VvE?2=7;BpmQ1@2r0tN5#dLk3g_-o+g^fQOkk zfy-4e{lu~pV zHGs>~stH_v1IFT$js$gjx(-G!@HGyn`166|2uG^mFQ|8f=VhYC@?NDTll^sw{-f9^ERL%_G4ta;ewT7N9L3XZrA zrGJ(sSHV%>aupl{E>b-JT&{xSz?<^>KM8P%R;PeV9;bo7!09>!+|M^0a=@h>I}eWM zxS;}YA2(D4E>c|rE>c|vE>d09ytV$95sgBHXLvw0;9ee39k@t!1Gq?avyId77p=DV zDpvGBwAu%}db_>~_5+t2kRjmSb97dOfd``$j4J*j;CNCw=r4+#KP!p>ccmA&E4{#F zm7E~%#J}vZE4@&`m0sYk^a6LK7q~0EEw1y=mEM-anE_XNfxFTR+?8J7uJi&g@0I6& zz~M?Sa94VPyV48Xm0sYoO0L`BaHSWxE4{#7>3#P&(hI!FvE^g#uK(r3B0p4Ezg7oh z0QgInX&yu_KWGMA9>WQ@bK8;+iz4j~OCH0C0^i9U$AG)i3;ang9|x{i$rOJHaJbS7 zT=F;#{BfSrA>a+>IpESxUU3!wl78Rj3I(W8XI=#EN-uC%dV#yrYj7w3WJIHeL*?Hi z+;I(fjd>loE4{#7=><;8tMlJtiIkaer5AYY4whcvBE3Q2R#<062>8wGbnu4Hf%SiS zy>>*Pf~OQZn*=V>n*uJCJ#c zq&Ej#q&E*-q_+TEq_+s17rpfS4>&}6%fLl?E5Jp1tH4EiM}dp<)*MdpCqXCDTgM9g z*-rzwNN*Fkta`0;+a>u)jxDdrRs4(e`b-D$yZ%83qaS$Jdo&LKAK>yq;N`1y`4I37 zm3Q(l435Z^oCUxW%%i|XdSk$2SLk*IfXfYv__?tD7wJtx1TE2wbGM1YD%I0^G7$p{n3WaL1#-A7NetF49{EF4Efo zE{k5f2@a87FAq$zBYLNnULSCg-T-j9aS;SQx|xGf^Va(RnOn3Y3>D)11Y`ubeD)Is zF47wVE}#7jv~fEA@&shO&C&Yj_Y%NGdXvCKdQ-qfdegui4ECkI@l zHxFE-w*Xx3Hx!9G@h`_%q_+eWA#4 zY;Z{0M1eoa9mjw-m=6G#&wk>-<+Gmzb9enOpZz4Ef_(Oq2HyCj)`JXi`4x>kaQPLD zVmqhb|DK{xlht;IRX$JiQQ*(qr;mLN_~@|ab>N~O4d7inRe6fPCOAYuEFORai>%$e zz(qfNz-8&?2QK;%P+Y~obRYr}gbE@cA>guf3j-JZhyY*Z>@nR}Fu0R{A|Nrtq4G}z zWB|AbNF2E6M*_I$M-upRJNf>93LL2~>tmS){?db*XMmU4&H=A-Oyq$dVO}^7*8fTF zxCj-ZU)3F#fRBDn^9u07-8wr)flGGOh0FS1(!+ax`=T+;b_{s%Q@VpVaA_wAT-q4| zZb!JGJUB9|^gs&0bG~jB8deeb&RLq5fJ^$7ftPi8+p2&=(yt0!(r*;Fq+boVq+cDl zq+i3~6#tlhO{gI0XYq_kc}YJna7jNO@FvfY-{dO)B>e)WgSez$5V)jY2)LwQ7`UWg z1o-2#yY=}$3XVEC)L#sE?KsWjz$I1^!0+KbP6976PpyLWe~mj%LxoZ9cnJAiJ)j)$ z=x20x6o5fR<9mW94g$*14;nz;weo6zl+PKfe(F_7c6aD9e+Od`8EgryP&KCW#GvR zbxe!`54}(CKn-|}c^$a-1}g8wA2%q+eu(V|@Zjh59>jp>*p362fu?{*xScd{r+@4? z0~Ln2LLPXYc@cQvB0WPD;4f{~GgNJHoqsz&s2!s%hm(I#GH(FS-J@s1;*Mko!fgA1 z%YcHwi}&#F|A)Zg9s=Oj7x)kWFR+~kUgPpZz%y*;Y;ZKWLLRtuPy`w_e4Ss$c;%laSa;HhD~2RYz%w)4Qt-_-3CfZJ0Ge9XWRVqQZ2ZC$<$ zT=uvET=uvMJoFu>9orfOM@~De8gQA32JqmQ_*eo@vF+<^Ka_E{{mv`JpB($4ALu;` zK!pnPAn;e1hk)mPsM`qxml=wfT*bdkQPgy(^y8R_0WXzx2Lr%mh7!Q5BYK9Cz|{;n z`8NcPQMNO{Z>{K#bHJZwo(EoMUI6~|Pjx%RUReLj6qTTY%upG4?&rFp3h)igtH5Q3 zYA)CMV|gFYQ&e{yO8@AqnH)q`9|RGX_X3x7gCBV4tGfLF@Sx2g1db?I2m_bX@zBNX z14_eO%tU#GE-g{)sa^&eVC^9F|q#nTYZpicaLu)#c;B zqboH}13z+}<{9A0^NFkY%Yj2G)PVc?I7op9-_|qd<(ZO!mOiY@`+%33`-wa8FBK~6 z2ttL_eY&9#@C5TP@B!u#;9=&`7T5U~WJj#!a1Kd?`2g?`^EmJ*^91l1^Ca-(ee&;r zfg{cp(!i5^+8qKu#N{)<)68?gbIkKLI5O-g0532v0?#uq0WUI-zo}!xL$UT>G^aji zUg_fYubSKF$g=}^c^vL*9=n6uI6N}eR=&gXjbtZzX4~fAVsEvTaR;3ohZo1;jd6I0 zHOSaU9f!$xI-L1xjKh6Ljy=%OI6TRjYIN+hUwr%gV>cA}`>}bAMb2qx~IzTGSyywA_yy3{IN9hB;Vdb9^iW`$WzDQPX5VlC9F_7Mg^6Z zayJOe%T*-uI4_Tp(*?uTs=ap{g623Ce7vm1hJwgPZc-fbZqrBGL zfpIF73^_9!3QRh72cdCzWE?&)$(Ym#+eTN zzp@cFCifd*vu5OisdSb%-9x6^Xs$92A03DLjFYO_zW<$EM_b^X4yXIfI6OBF&yT|k zo7r((9KaLf@Z>l=H4aY$*Yi)4o$PMqg*l+| zI6O1?*yVHM@cgkk{anwn9aexpEmL`64k$Pd4~@gaXY5%c<27j!E+;5yz%>f0* z;lXiu$mH()(;=vt4kP^%hN74qC&%HD)yFwpV6cD#;jK6#{!Wz`Oz)p z86y_Wb}IbH2bM2t-Ll`YAO6+H9`DdN+%neKX2+>Q|t zCGPCM>OeopryVh)g1&#Q`GCRoEm6(m2A`sl^Z$gwry4xj;G($t$1>MJkN+9`G=mQq{B(oI z4St5f69zxi;7P?*{Ha55mf=Vl6+#A28~j}cA2RrIgJ%qWw!w1-w^taByy1Aa!3zdI z*Wg8ihYemb_)3G94St^HI{zw$<9wq+)!?fPK5Fm_3|=$%g$A!1{33%lF6ApKbqFGc zqiIxFZE!2v%7R{ldkx-aaG$}~7~C&hJpggB;RuL>_$3Ap8vIg&hYTJyc-Y{V89ZX} zwZ!%O)0?Q_SZ7p-8GOCL2Mm6>!Q%$M!r%#mU)kdH4w87oeDEWsB zzQHJ;F}S` zp=$6O3_fb`8x3AFc--K1gWts5>Azt(HX0S02H#|G>#|lB+-z{K!QXFipTYm1!Tp!< z6_q*!3BwUEDr`1*(BL05c*x+l7(8t7TMZs@Iqm<43`f*;Sk^}j9y55--~$HVV(_@Z zw;DWQ@NJ6A@lP6#j~W$H2LHIh(*{o&e8}K;7(8R}I}L8<498uDBX96e7`$L`8N6~A z4W2g2mkfTl!ONQ4PWlZRj*3xXyTPjl-(m1kgMZ54HG_ZJ;B|w4#+`pE&@dcBMun!q zKWlJnZ7T~tXK=54?dky<^Q@k!)M0cq@THqrk_=-euT# zkiE~aKS}mM!yY8NV?k>GpC)^;VSkS7Uc>$(*&7$=^)@n8umYvz41i5RpC(rgGPbxlD*5Yzen~y!~P-J2Mv24 z*&Pd8?fr!8#fJSevU?5t7i4d=4e(0>gNFS)*}Dw;H)QWK?BA1p(6A4Z-O9cNz9uWbZTVzmt8?ushb!00ON6OeA};VNWKz*RZFr z8MA#G4KRxe3>x-avUeHwe6sf$_Cm4`8untcI~KJDa5CA84SN~cy@q|}8k>%R0hUvN zLBl?W>|KU^9@+a0`$Do08g?()9gAB7xPuMi*3PK1%kWVSktGU55QVviBMG56M1g*!#%tIJq@|pOC%S zuzyB&uh=%73V%UhqX4phN%o*&KTq~9!~PA~`waW{WFIu_gJgG{(i*^@$X;yNhsf?_ z+g9h|zYy4H6nKs7LBoEN>|KWa7TNm@`|o5QH0+LxX#m02049>X*sv#)-K%Ze(f;WK zHW~$Hkv(YGbIIOi*z?KWXV?qLK4{pB$?iC{HGq@JUToOQ$nJG)KL4LdV53oBIoX4T zeGb{X4EsE?_ZjwuWFIu_Ua~uuwFYnr*^3Q(E!n-wmh=A=1U4E4`pF(N?5oM%W!Tq} zz0a_3Ap4+UZzQ|pwAKJVK=xw8{vg@CWV`484-?pE6xd4kpkaTE>|KU^2if}!`;%lJ zH0(jLJ5Fy6;L~I;Htf%l-Fv!m{{JF@jYfg{$R0H8FOj{=u)jj~KEr;H?1P5Ai|mdw zS_Ak7*^3Q(581tE*sTKpOkkr?;8C&%4g0%f?=tM~k-g8be@OO0!`?@B$C<76e?sYh(`^_M2qyGVHg=-e=fPrc;59hCPey zLBpO)_AbMoPxii%$!B;@omQPlN;ZMEF4{&SXLyb~`$+HDj>ElUy;k4YH)dF4U!QG_ zJu=T4d*9!WjvVN;_Hb)v6I5pjWptEP0cTr^QMS6XSHY#gB|I_W(PMWdhuhXnOw8Pq| z8urp476m+6>(z;4_kK$IYqWP?HvJpO|Hj0z&yas&r?vC8E~~hWw%Z0T%I^GGXZB`# zzhh39Gpmays?KNcd9icOo}W#2X18c<=*k}Gw0pAK)zrS&H%1*77u`A`dvHllR!y;* zR<$?Eci_c^S?^uiRt^8L(^|G;n{IsLq*mjPQRB7$rt*`l^+tF`Xm57? zFyF8CvLo<78&~C3hge?og~)B)5RJxc=wgnEh5C3G7nQoQHOjDQbgWO9WEJmxy>~3p z8QJSyY`wcq8FG%5@4vmv%DmCnlYPEpXzR-D7iPN`Sy}H*Ry|ZUelaASuPez89c_MpnTy1Tk+n*cOF8SH~wVt_? z*IL#J|0HXscY>8Y^&wBT$FtziKmYsD4YeuO@&gZhvOlBLfBjdN?5@%K1D$i7nY{iz z*3LQ&O0fy_KHpKkAU`pE!6F)PeLrz~drx+?mEL;)94dIUZ|t($zS)21Z+&Bb?p!n0 z9r^Os&Hdf?cYCa{%RK4+?wQu@ho*Fm{dq>$*kaYd_CU7Q7sw7${R5r;Whc$04qp55 zs)y#5FE~2U+EROc$EpLf(-(Yejk)evl{)pWlx@E?L2hKnz5IctQo7Hwr1?c6Rq2C8N8vi&SUMpWgopxpjT>$ zeyL^et%Elg3@yV~4*+9qsQLd->nG#tNNX&(=Cmrh!mEQjmS~IBREN zd#t&+BeHi--+M}@TGkx;7uc7tQw^`9Mz5r8`(m1n#ZJRfHJevayVp^>*HF7>Q@iI< znfy&2z4$Mt3h+zPr%Z`D}iB=d)_0E2zQ3Rk!Wl z-MOJz{}wg&9o6AU)Zs~PW1pl!)}P?EK7QHWk^0%5rS^H$;7|6f;NtlqbT4k{JkMlV;x{0I;8zoR36Sm9Z}W+nx8 z_O@LV)SV0dJmnP%Y6{qOF)I16mHp^HkODv4ySwAnPyDJjTg&%PC^HYtqw|i(di=%C zzTHQUc8q*vooBvH^(QkYTr>{OYY z_`}f^W_h>V^%Jy$`_ugqDoa0ex0B8e#n(H%dlKq2Gfii+^L}PzY>K1U6y!%cPaTmOM-ID)n%Y$QyxuvD&T1WPb9DUFsWdtC#pIpc^g8m=Ii8ai)2t2Btf_O{&;NFGq=%ep zFTJn!j=fA`N(wM?%DGf7Mdzx+*YxhLZKu9iVNTPpOlgeA!{~dYuJkM;;Uq=3Tp68q!i{58@)nch=9qGv4L;>7+QwNt+ywR4c_gnjEbu1Md=B&cAGSo98{z3*)xkGCcVHq zhn8-|I;rAi)SVRwXAhihWnZL&uGSaz6Rg``o?`92j)vaz$c!zX1=fbSRK7g<;T(Rrnocr%uud z`(?@$DkmMNd3!g7wX#1=uL-K_{qekP_kl=L1<9|7=a;Ah-(xRRBmU9$1*IQ#E@-~| zqNiD#l)m6c+fQh&pwUmDueN=?O0wH$W%tpZzWA_}eW`QK@^4UOI_Ar4*+V+JsRlnn zc47PVrJl{!mPH-bhWcrdy`P<$@87)p?yWtZ?pyBm5PK}Lvgg#!Eu>}}>Mz>8rJf1a z7Wz1ALw!k~^Zq7!|Hn;zC6+bV>uK2?!RguB3|dm1aN_c7X|E?(=~?cA^t%(XJAXex zFG%xxb`H|)$b$3<8sz0XQ+I!Vu>ULcvC+;q=vX)_*t)K;>np7af9yPN*=nlr1}#X` zbgD{f#^|FEXL`?~=~dHN?>v6_Zdy0|Y+Abi7MiIV&6rw(JMqwAt$cZ+wQ|qHC!~({ zTFpN%w^klqV(mR@dv@EurI?gyeuzf5iyDz>{u4E#ruk%^W?BPoPz}!|yS^l{w`Zlb z7rFZJ&?567{W<7VN`>&-Ld552}X;W}w_Mwq*Ci0&*p5N=u9w7g6@*mwk;n^eC%%&Ziv-|Bk zkK6rr--N9FdZ%aEVG6)nUq^PAPX%7jvNx7k+2?86DqR#v^j>(quVdw7_jyzQLB9Np zmdamF-xEteI=X82WjdCMI%RcxN|YX!WMazD62Z8#O$lh)W zkc+--ZShb*dEe)~s%O#Jw>(6F^!4S@)Ww~atQazsDH$h-c6hTpa@|gB>>5h<-%hc? zF_a;pYA-iOm+PQ%AE9#UtoHVu|3EWgZ`gh0nyYrx)MV8$u00khy>;~HJY&tEkCkz( zYc$}a`)Mlgx5nPQW)3w%Q+emy-EUJHhdVo#sTox%ZO-VMGz)`jM{!1Nn$lmoT*k6U&T)m2gckeXIvXQ|F)R=@hrS^Y81>Zdxa z6*lE)`*f|ClHHM*suk|@>HekTO{*$bo8pw~rE>GB+}n3vO|$V2lr=P~_eaKPmYiAr zKW5YJ{{oHl$dx~&DfCc8T3JfLXOHf;o=tS8`!|!49h$U2-7i>1OPZB0pJJ^%G|##{ zPSKpWU{8Pj;mlU=UBUaOylwx=`}X^P^;x>{;Pp(Ia%cj*-rapd{$Vpn7t%RqVN;zQ zkG^O%5A|5L|7g2?V)Lu!^wM!UIHhO#i<|gFLk%beth2~C(@SiW?D`25v=iy%vU$)s zxv0P`Y`>wTR8a-)AD8r&)D*vChF_YR-I1B5XZWVUbU*!bP{)p3RWPIrZlrSisGK8E z`z;bE5~eHni7>SbixI5njE#Kp?;Sny{l`6fnBr31c=_6LYs==Xq~zN>NdWb=>$B@= z&A5LeT`+ZK@1Xa8?d-_bt|(tn>*wp&zDaZ@nB-i(&hXLcXw&<4zxjG(%())kKPkIx zxb32aA7@5A>6R>Aw2kFB4m3s&KZO_zOK6JdbVQNOdw}RG&XYSYU%PXx7r$3LeC@ohEiWgn4bGJxT?@Z_zh|ueHP6`H>RPyy=4AiW>;YO^ z{(6SB^YAxUk0pK?Nxkv#>ajP!wR-Hc_Vmcgp$_Zz#D(-a*;<+CjjW_)_1T}DuHSnn zc&_U9^t9~m4zd@v>}j23pV+czc9FfHWgj=U#-YjukHxIM9ab#rKx>-Oy{y!Y3l1Ar#6=NH4pu@SGVzKAGOidT9-=);wYipZ_>=B-tt?OD-^BTREY2LcN zeP&)GTV`hKmovS_F9kXXV@#)o``#gOUs6~}qr(J5j`)j+bEibRL zHr%Lctm~k=DIH_Z4XW+4DAHzS@1~sEHJ#@2nqImuWi5aCs@}0f*Y%E^dzojgeRjv# zp>sR*{iyvj>44A7c6icT12p&L*M7e0sWVA1UQ4e!u!N4+uE@&Dd32j;yD$6lb`PBx zd-lv-ZDr4;E%iLzsq3WrBr*qRN$|Z>slQWt$GZD&3?EuT{hmheJ=V(ZO*e+SCs?<4 z-$t)9t(9L|>&c!xrGxH?(YUGITAz>VTg!WCyp@fS=1=Kf_@UXoV`KArN1j;gS=4cP z=g4o?dTv;^&7&tkiOYd^)6^YWux0moYU(KB)kM5b)Am=7o{0Ul+}u7RyP9@vhMI_@ z6jbL#Rv!A>YMPMVkvsc5&)dJHsQ-gUPedn`-#4P#`>LZRuW0A@yKn@|?8vj1c;iM4M@W`((^_LZNP{8$5 z0|(Zn`xE2&w;h+gn+6yk&ws?1y_*I&(C)Wed+42$^<0zgkF^(Q`RStPDH>pOJpbc# zQMI0Kzm4a=epdD-@`uSEq(e&ISDSOPHOrcF61`bU+Y;Iq(>Bsr?>W8Wmt!LfFQ@4E z@z_ZJ<(_48=F^c=_i8pBK05LQt^3rHTYXY?qOBHvbUUd|huwPnk};LmEAO;+uBM~6 zXwKYhZIU$>yo)NU`|q@P|1vf3H(C^)Kc{(aoys1hB~h*Ogk{R7uIK7@=We=Vy8AR5 zr!|MJ>*(XUP8wFN&y#&Us%~+rTO}thS9N~)`q2@)r_0(hWd>cg(g4(*IQl?n@6dGX z-A;#8>3^u9zg~CoZuRlj0kU5vyLp?k7drMI$$smai+3xZy1F<(wrcD3t1jMseD@W5 z6PJCuKfm9(<>9RD3!QUmH9EiaBYWlU*Iqwrs|9}Mq3s>d9;60eq(+?E98{s!dHgbU zJ#_)?v9rLRLJNH2XOLa!ytdTyF48o0_u{I^-p$mBy3L{PV2t%$+*Efk)C{T|SVNn- zYccpKx-qNn_0;EPcWjuKT}(F+#?)o7ni^RSUPe>o+}$Jg+NJbKL+5j=@}2*<$`Jz^ zq`IlSn#5p;KD|_*VyI6q-n_Q^{@qJHwtElV;J${~JYwtUa%V2BbEYUUIjwcm`ypBr z-A;82+uz$%&uezCy=~t8Yp2?sC!Hl#I&@!3>Cm(1 z;n!$SI_NVnhh4GvAib*l9O@p23j6b^t_qN+=rW|H%FtcG-%uUJ7Io66Lgc5qq!lEo zx6yPs4NWx_$8=-Gcl-{11`8sSX3(lwIxX zvi9En`V)(<@T5FbXI{1L|5JA5fi)f9|IOT+mk1(=BqFj|6A_U_#1;{I?4kB0)+%bR zeR)Vxlw88GH%{v+(StUuIsg3`MYd(}6<0sarL{Al(kDNoZEacUsZWr0O!t58iT3B2{u`#FeY|3Fv;ZQP)}FyC$tK>% zr#r6VxrXni!+yrIY%r@~3yacW7x3%|=vv#ty6dp-HM&yim4tWZF&(D^j{~@-p=iUt zLE*4aisQsjn?W#lX!zFur`|mc`15z_<724Y+oz^2^OdD(Q9D+Z2meJ!+p&PKH!z>j z_BNsqk|^mnrBdm?Y93uG-COttd`Am!qTUmtlofxGdpz@RX6*qJJeAlCPh@yK6^5mm zJ0Qwe-xm16(n@bkqOSq|qSH5Ne}my}RLazNR+_hdM$6+_Sg}w4%Jq1T8T)eplL7oC zo(1=M;(w{MVhS+i7@?P7eGkFL5bUMQjx+4@1v}yE7qL2`)ks?})JVzn;&`6I3=!J1 zf%>x|LN&{?N%}L#zi2>v<`3Up>7_UT!GNWxMX26|m=fn%{kV=?4VDxz%}0uqQNFOn zd8p%51dawTUq*Qf9~1b#2E)^AkFUJ?+2YqNqbVw~8}}qKc3>}g?=qCzftBSyJ|Ulv zSVw;N361#(%Nt)mp=}?ra!y}YR|>J1T506p5lQ}sAF)DCtMWZ^?TFF&ch#v(M^y2g zCluF_MaE8gf>L=Kc9rro>?@AY@B%%a8_cD3IEBlGjRrh{8FpVW!y;e-3k=z&upv*> zqaB&M#4A3bt6f;lE>5A!&0>Zy>07ZBZU{?yEZoEpHVAxB@+^#vvd}MN8T=|Ju_+al zzE3JB4Vs$b?|um0p`y|o@as=#P*;@t;bS`5mBp6$1$;#^LR9B-BqXjpCiiZvBCr0K zqPwxyTzN|KyRm9@gqUWbO5fq3$~5GtKZh6upe(WMBGfV1saw{p?n_+BuN(8^|2(1+ z-C^cFI>TCa3_Jcm3?Dtx%YW*zNQijR58YV;|M>}p^k9LmS>2#Q4iZgWyVX!8jw-8u z+=HE9ybHj+SgWa4L$!@i`kEpXhJ;r#H2b#_1e*mKf%l%l1)q%SN`r-__~`|~e*oO6 zhVreqDSpCZdfkgP4$X4%_f-mwPup9WIn6a-r5%2s<-fAJk^+yYoDx&3Iqu`|7YGN8 zgL@52V10c2A~gT~20q;xurBx`qoKHGc!W}`S_C~#U$Y#L*&9n{w)a$bBBkI|g)$+`8npU7`XnSAQtVlkiNd4GkE<^c# zY&yUFh>ZQ=%V)r+Ka1rDAJN+WYzklbhyn(%K77U_nmGXQPao0s0j#NglWOr$SEB;d zL2)wBq%zQ?GPEY;rx%w^FvYL=5FEu_GszUc>`$8VF>As%KU6buWqj2`a`}WsI(`2D zZQfwmMcIQ`snT{W>{1aB?BRjNpX0*vrRs?NJniVK zfQ8uUz|q397E?;1dvQx&W2U=_*t6sTc@1J!>@}ESM(Od8dJbY0~CUUI0l4z~J(`Hen1&*9NiD_G&dW6PJZrgIW9P zb^&fSc)nL#A^@5LoJk||B{qabXtcX3>cO#@DgNVvXa!u*0^aK(4H&{AeOj3fd*wd5 zQ5ZT>7QxzG>$hLrr~N}%!!ANCr%E8Lq%>%5imy=+YXLt}N$CxERlw0Ev~_BszJ0(v z0a3!TUp>%OC~j6^MFA@8zfb9(npN=F$KK{+iGn4VcWF%xtM{Lv^*bDMe)M@BFT(* zyo%y3;FkNSV5NkBqqB|E7;OqxTm%9hX!lW7#b-t|fnqmDdnltlzgAVj%WZCW-A=#n z9+FqCFCNh9;jB-kBY$A)1RP+uhhf)#aJB+`g(^cYy6RLK-IhlZ)WX| z69E6aSlL(4+h7r9B2N?1AOYz#tQn-gok3GZv;BO^J+<~{YzOD#@6)5PESi_TPa)%2 zKv6#s4+OFkD>Zi@HBh-nYq&|0xoc0d_tfXV>pGvkCzd4HdGsAg&)dkFO#dz6=&!`` zh65IZMB31xG`mkn$FakFWp$b{o>i1;IOdS6o8+k;AI};x?C3I6;~)l?GO zIx4AHO3y4(NG&&!IdFdccQt4-qmU^G@RNV1ZBy7--kYhFrm_hV|F#CLo6ch7 zC-ZtU`h7a9?3tgXpR1CZ$LE>4wZFq3PZu++-VO6Hxyq|RV5R3(u)y9f>baZplS z3oDtGi%_vd=G`bivw208)H_9$%pXMN57GBaQ+x>gLD=EFvUrwIQfHS?GTWAyB|MqR4LNHt zqic`a8r6r9$82_H0j@v%QVB zR>41&vRGTm?#q+_%r}L$WrGdLqTv@vGtfOx*#%#+Qoc4wR+9U_@m#`4V+ufr1#Kw2X zDi3GN=LbT{Qa>d#!(X!l|3-pstFHh`ZR>A-0~U zr?!oPnQEzhm$U24dnH43U`pmLuFR=sNXGU%H{mr$&za(j5nIJddc^*0rB5_ODXHES zV6zG|YbC4by2YTRJ~5zabEP#}gG|LYFb}%4l9hE9oM$^InZu3rMxcrYaVY-uTpr38ud!V!BSl+3y{=-Dc^p~yH% zN%fP#R#xiLwC#|7a5dXi&O#>&v-T&e5X}NhBN0Ms(xR_0BkK@Mx4&XB5qXjX#jP_| zio{ESO6m_mN@j8u#lNy4S@fzc;75bu{?)!_rD=EyYg{6`hGG$!I;1KL5<(|a*kt3> z>$!CCwi>qvd0+m~4Vto!l`DauXkQyU*Rg|)Wzg_cR%)slo@i4!HDR(qQ90}M%5l}3 zat3Ua1;JUU?JNNkwI$+@;BQk~N=^7%X)}E+N(Z0IN1I238g(>RDHYzp{Ge0DR_5lH zhhVK&WdM|VZB~R5Hn37nERt<1y8>GLpC8b6Evi3{u}$?K*uWlGDYcEKoIq>v*F7aE&r`C~Sa@YC$ICVxb^p<-(c(XK(piRUhG^bmZ~ksH?aT2s z=}kH-U1iv>xs;CD%qxb3U9?&|FZEtKufG}Xyqt|IwMT{c*timot8f!;L@`@gX=j@j z-gj&M7VhD1NS5>#4wuN+!mj`|#-`F6!`<$h`Q|AJD~bvi={n6ltre~i@UK#D#2ae6 zjrH};^XWWfn|eRDjcstY)+|lk&hGN1k@Rr}i*eIhfvBuJN>tVXKxk1KD_$<|sZCuy zD3{l&Ep^q?+@SMS$X8!uw!HcV`Rrhk0d=nC(t;a^$r3yNybZ@VQA&G@aC-@}l0PtB zG)2;w9jr@mmVdCf5`fJAJq+;u@KQ~%xh+`CB3v&u1KrH?vh-#L^O+jiG{?yhgEe35 zF-Nudhx#hFiur_D=*>f#JQvpJ{m{c)^V0@Uu@CefM!52Y@*HqI>RV)wqillDv~_ zgONsJQ%O}+cFipbh0Z{z(#Bw^<}h4lFKemMiX!Df(Z&=@OPH~jHH#A5^JCalp(SVw zzj^^T6-}=S0z+QY^WMk83lM^4XAv@ZAB(b6(A-n1``9TK@_y-T+LYF3*3b>Vvyvfs zG&T5^xp@k+*>sT_7J61sT5|>=RY0xHO&hI=@GZ))87|pfzCX!aG&OA6V9jrETC)I@ z5v8yKH0k^bc1vS$N3LsFgt60=T-tn%?tjA+tpB*6*vak4i?6dh_QnOU`n4zWNd zKVXl(mP<>%V-@(CNP2vT?fQ4mI((R2aI`!#(r+jIAZVW!^2bY@1hjl4O|%6bSS z+eT)YuT?w28oUqG2m3VZ1lvdJ&$Ht8uGlM+mFjPnn`FyYoADjQFfps5rtsP)x*Y@I zjiaErjjq;uvu#b7ARINfrh5os1L)=rRRyZ+^^vN^@YdhD zrZb_bPkv4F8^JtiE^~@iD7aRyRm!W?UZ+@fTO=!|&Q%euG2AXvjkbS~QwIFQGMGNa z0t**{e~2VUpx*Gh(zNebC+cv~T=zC^`tmzAMwqf$RbIAj(M*2_QwGmMa2XflFfYlr;nUiIrL+5^ArRdHL=K8N5H3Qv9gZ%8Q zYTI~J%`>c)Z53FNtPVg6&R|w;<0ZC=E(UWDX+wUx~Bb*NYt^Om1D)rg>KS*%MN1eo`$ zA_KFr^)0+Elr<#A0Tfgc;bTnsg-#?}3XBWPP-fdMaAUTv}h_ z!wcnWd`S-QOC$cY2#|m|rw#5c;EGP{jE5n4k5y*=vVI`A)DJ)wV$yk5&CWCe-P{b1 zok!*oR?I!m#@S)n7;wP_cF8qMQ%_j$PJNifK%*|Q9%Tx&*|j$eF=N|B!7DOBlGjllEKYZs_mdM{4xfW^Dpaz%CPe^ z0r&LyH}lw|5xVsxIHjo$9R|SYem<85U8YBu**D%!HS>QqyjK(q=f&>#ub2JBjx1J|DTk?S6P2PFN;QA#q!sLEP8i}dD4ZeSaR!` zMM1x?Al~adb^Han=7w3c#xj@Upq%(zp@JD z^QzgB4H9lDT8wQrXyUIdgH6q6NXwYkf^M6RIOStV4i}{qO=?I;+Tz=;eI@%7O=invZVq*STlCp0w$M>}rquzYlnn%Phq3zobXeh?O zc{DbIi#^_kWRXfMs8o8|!o!?pu@09N$Fhdx+xj#%DVtTbBzkPd$8;{6oe#A2SIvYU z$XV2dPgrNq{L0!)z@?|GyB*Z(LNxX%E9;2a zwk3H|nsz;9b=<7QwwYy1f3YAfw%U;BIrHnB^q&9O z&Z*a7>A^gw{tU1GXXAcMBSZ4X`at1*S{v@g{$>&00wcd!Z2H<>f1^)(pNBPy(29aF ztRaK0{LLB_z{5JDrkXEU=YPl8{DOTH(Elv9G$8Rb&=`}0p)*$4OQt7@Ls_tWq0o1^ z)Z?sJxp1ebmuwTSdm1|{SqQnlVot`>r?9*N=qoHWz57l8B8~I#Ec*<(=deM>;rM<0 z49(18y$jHzGZOGPP$o0jfuz^0fw4ZY7oDLgzwiKZEh5S4@Yk#*KidUKOav_plIRHDcLtjU$ra!`!fP349>XT( zQxsB^-~F(l0u}&&$A)hqDE{9BnHK;DyYO00l^|#$+7=yI&)w*V3r{Gx^fp1helh;F z1xb{`T0=HTvSO~>)G{NVZ9b3&3&xu%SK(e}yX2>_3EIE7@w7!5%L`n-b$wE6w%12|hiRNRLlvXpm`#8W%Bjo&szq|O;+K$$F z)Y8{Ug@0HQT>bGjl}K<|1mz>LNk?oi#eBn+iKkM$+KoQ zw1QbuTX&(ONNp9!)y4%@fU7naOv=aACa-nFop;tT@@Zz1)N1chAP<`)2zl^|ERqg+ z@JV)PJrK|H&1{G^tKaVjUE%=lb#$C;P>j=W>rNh%>((> z6Z!;r$`Lv{i@Q@oX^!Qv_gu@`Wavg|eyRWrn=H;TFCHKUzrTC&Mtur)?E;cGdrKIS zZ|KeaeHv>LM|W*=;%BjwA^8H~XhOGtOX~>JnGKNz$JfWk)&alnQ|7czc?U!CezO+u zS>Xc>Yzh33{JeRU0?cCLh97(L*#%(On6_|PJJV)pZPX^k^SCVU-1dF*h-jhbcy#j= z)pJx&(eiKqn@P=SAMz2t@-M}ui$1*W2Qc(WuUf^ImuB4KFg5YxAJNU`#5cq>d}3WHxiA-~D)bjhU8r5?O9DiU(@I(2$y(r=3`44UxXw7-aOX1L?;2@o?i9zhR%6zJK#(NFd z#!X5F^3!7ab|aA2Z6+{9V98S@aZ4Q~wR>G9)4Lv4#|#RO*M}P891Y3Ub(7~;J)*Lb zxw10#4dN{e;AZW*HEwHL>)a-z0>yqzw5|Ny^zAz8%OL)cX~oE|+@*RJjieZqZTq<@b$aZJ2bWDgt%E80PF+nGlZo{d;D+gvGc?6_w2H zm1tN9_sqkv_LV=>S5kwq`{OMs`$GZWcUXsa0(|q~T>8iizjuJb!T|54!wco?%cWL;zod5c zc|$(u0Hue+lit#oF+9A`3P2yjjhE@r-~$v;1JJK@Xgxp`K&i&QviQ{AeUB~;nnxzKn%dwAJFMz0bc@m zj2V7WrJ1pSH__pR?(EK`D8O&gns%`6XDYpG2=KlA8hN3a0AED~CF)=gmBus%c#aud z8Q@6(SJc7#_Rymy00*1Fr*~o23-BpYI)Hh%Jv5*hz-RaAx(xyN2x@51E_Hcx-j#86 zH@%1hLJ-W|6P3F&m%IVb+(|(#dB>*T>I1nXR6vsGBvSuDD;^T41zCz0ITeY{~R z+Ua}v=2m|a%uv~?Z!2D$@s&F%tThkw71*dMQN?)@5^WmDjMhBRp#oGIPYq&G8g&=F zXf2f8t10WW1IogoGHFCtK)dXsp=|;ELDda82;f7g=Ycx-%}%=84&b2x_vYb(H~~;+ z9lB~K^=uEQtC@J)*LZ^y;4RcH0le$)q{|%u-m!ru_Eb?D6<)Vd>}9royw z|H{avCICO727N(1V+Un+LK}ENpMK0EoB+IsN?fP|E9{`?E}&hyTc?c#cn-i3I{4(* zw5Kb;wawt4w&zkXz?Z4|0I>e#YYOQO@U>k!^#p*=qK?Pu;KE;l$2Wijn0&Hp&MhX3#>CGU_j3vnF^tD=h zFn3|@kv0s&%?$T#rk+Fi4UKqqVI+O9M?A3zwfK~WXwN*6v3P|o)Z<)e)~Eb)r&gd_ zgG$#&1eJ&K$^lMz^c-cHJ-_9vW_S~!RF{~v!`%HrHr|R&nThlDHq*$VJl&x;@Xk>0 z*4$0w{KN%=pkhkqURP>3jDKmomYz$Y8FYCV4{(o5w-&uAo(of*Nhg=#d;rf)qcOv| zkJHJtTxy0*{j_p8PZ9HB5l6Mg=`XB#uQ+0832HxrS1mFeERMsOH1v5RcmySV!aeDy z5!}`NY?@Wn_h2bRwM(aWBX~5eAH<7mx(>v)>+&VB!L=lH8_5HW)xdDZcA7JiM_Q2* zv7H^Kzh#&2)M+;Jdf!a2)?d z8{wYq(rA7XZ^+Uqb_~Fs%;3K_}^Q|-}SPFAq z2&}vC(WFhfkaFqNWIVVm*{TbP0DLy!VVh{e1k9J#ZnVBP`OGo))#{CuK7o(n}Va7Wk)JO3f|hZ%{^S$xXNPVH;_{L`-brHqo4ke4{Z1XR98OsOBVo!DXJ8lDNrR zNnPoKWe8vLn9RFs&+x))YO^xv|H{zR$#63ZUfr@v=998?U@{-imu{iRDLmRa96HT{ z56|49PMN|Z8IRgRd#3XEB4;<`QUCz{_@j*R%xz<36JDpdzmbBbaW5GI-6U!@jsN2P zMXR~-KpaFYA8Pj_}XlM;D#a~ai>iM$EZlplyuvnNK)DdnlmOdhK}^Y&L#2l``(?@xng^8S28I$fB_ zBVGE!DU9fPaJYh7LOQw6;u}ibT%Sud@H_&4;rI(n7t_wy#%J(?ztZUJY(CP(1e{B_ zzlgsJY1H})w33JGtgidVI^A`Lt*7f~eCo6T4&_e);e*bMh8H&Mm; zJknSTzrWl>edhC!p!I8Y#l*WvmWUUHyr_tLtJdm@mIMCSO|*YLpAy*#JjMGx*~qnA zz?Khz_ZE2V@Lar)^P-c4Q`}@sWAt}$(2k!t<&>+1L0e%H@g!c0 zWl`NE-j;K7BZyf~7n0Bjc5c)gK|7$P!pYjK)f>sJbriP{@Q=*!XKQk)Dd11n=v0Bfiy8h*(ThK74UJjM zefaGZTCy1Pp_bUFv@%f1>`;|1E=Fd!E%>e9K*l9}l~+dUlj?Y5+B@uyBxy(Nix?FE zgfVnJg_oqPCA^y~kf<8*(!Bi!iX&d5V6q30UtcHNLfqA_3-q(-*3qonHC%Hgem|SsdRlA_o@~TybYk^$GU#q|~H!sR%cJL7fe7)BbC9HbAdbAP4fh75DqeY_r zCT`+w{gW)UW-PUDq%;A#p<<6p{2hJJO`!)ZK~xwHhL zs1K0>X}(6&+v)cen494_#rX2F^xbCe!JjXu%Uik6k}ceu|F&H9*@86)J8Lw<_MhW; z!zQ~Hb=t}Uy-vVUwfF+fe_Jj}P%?cmI1gGu*UL#>v}-H(<6||xwfVs1YKd*U!oTor zvmHE}+VK3?%=1rNA1>De1uT1cJBHDJ(fNaD-$?-7`6`#@FDK`(`RXCpmkFb~r|)@} zyE`EuCQTS!9EZIZc!#GL(!{HdDd=Pe9yQ>of5U?q45rS5MhlG-V-XG;;84qBn|@f9 z>+#m+UYuXF9&&nX9W+Zn4mkOFN^X?39x*9+2Y2GVmQmymzJxDcMrU{Mq5Q;hir&c= zdYxJdL%SPt2Ea6;!iQ_ca!WtDl!@VhCH#a$A$MO^5PQUNw zz5UEL<~X2#T|_uv6nM--TcOb1Jd~F1;r|#PKy3Zhv|Qyu0iD2Boc|!seh}uc_-;Gk z2=XgS^%@$qoPzeEjr_VwZzB@{KL=kQzm$6J<2!U+5DtVcKAJA(m>^CFv&4m95Sdod zlKp(Gk>htqG_V7_jPpF~Ub}>Mx+Zbzdw^GUcu1IHld_%rQqoxNL0xpHokC`vhhlu{HV5ABIVKC}xOS_R*dg4aD9$W;)pZ#ATfK7vsmjvb>6 z4F^^^2CE2WnpL2btyNZ|RL8hK%{|5oSxo~@wn$%UNH(TJ{uuB)(@nC67cu6854MMU z=ZAOI;NitX^FMBGe%vVk<0w2vMUdwSj5WG6pzsqsjQ40jAD`f5F&LqlCwR4f{fx>@ z$FgC!ae$|2a(-pgT1UejTP@bRnVT5siRXv8Vc&W@pUrVBD$WzXhjX!T&RMNZI9+)y z#_O>bKH9-(I-g+8z1`9WQ16r6!{;7uIZlkwdoK6%WQgdE!*<1egT>T36M2WP@#0Y? z4|Ccb^VZ;>;IoE4J%Ntoz!JKf$t(E_8B&?B+c=s==wv9nsr5ZD5x)`1(pfTvKu{?& zS~+o)xf$*1V(NO5`}i!e(;?PIhsVjZ_8`KdYZ?16?YOn z!_z<3$!X1tFJAsf9lXXY<~YGlwD~j-Gydd=gW;X%_G!LL&PvUyPb@SloDe~tCVkJ#lo9mGE!3!W2wF0I`J!BU zgtq?!|CnQUa?>+>xlr=<8NRs0lH^?4T`?x-ZzKe=abQQ>LYi}ykKz575vAI9#|Jr!j+Q%;^Q#TFg8tmO9vWj$5@N{UXQ<2{B00*AAu9dXCnvX ziX2dOAvz2WQ!hhG5Q-^II>Lak~`S+M?JKk^`6Y9aYtMk_74 zkfJa1id_$ysm+c{OJ)Y z_Y-fzKRH5!f8x`vpu6xID2 z?<4W1$u!{xAJB6WnD3Wr;Y^;=>ErQxpA?nG@QEHPBd(l%B^Y_6j{yAT45zeH5QgTR z5jd^75;=b0D=|D81eg>0g%|4_({`izi{R2fiK4R+P0ClZXz*J4}r9#CPo?USbhM^V*wy3r}A_LAUsI-ggl>-$tNi^RYO!h+^@Z z(*hcEo40GEvohdgFQNEQ9Qq>*t7R{832i*<9<~Su{t=t=4~&FUc+&>r@RtKHmN=I9 zHU1`6Dnf9F|yaXw`#;|pq8uh!+aZsWYExOMGi=9Au=VRvI($R4KZ1o8G{ywkh66mB1 zt`VVNn3LgD+=+7U^WTiYXf;(7y8i%P+-+nt4E*nOve%xXXT$O z<<6t!|M1!&C1(jfZt2T#{S&f8Fuv!2?yUhnCfTKTUSJl@IpPcAZ}|+4vBs>oe6evg z@K?>FfOkBsNRpt1&f@G*${NQj8$-Zx`aE&sT^t`di>|)oRg8Lzqr$no9&a+6;&M6G z+h)`9Tz;!IY=m=rO2JlMubj}1HqG#Qg;qfC*ssu;C$w;{Gp$po4%=1 zt+b}I7w?gR9L2!fe_pA@ze}xJ&zh+n(VM;kW0Gf5ne+som?+=ph7ksQ8sRw9dWphd z&K)rpUn9!~>@c1k$<3{i%MDLs3OAVWMq2K50H03~p~r1DO=nV2mGi*Kh8ln4&o~=P z43c4PX@ng^A%h}b>VJkWmJxJ#iGk4-Ciy!q#?9`?2sM{U4P?G}4#gU!NatB|a)D)V z`+N>f$GtJ&b7c4C&>^EV-K!te9)$?D)4ZYB`7gbWMGfyaG8Lkmkoz1q#l^{5Jb%jCP2 zhVPbsafbS$ur!AmPrz8mXVc80C~a>5ch9CJE>cChS5z9#7tE%RVgLjKVA23fcvthY zm(z2p#cXv@G0B}9Pr&@gXVJ{!u!A~__7|6G8`}e6<1BhzT&jTVuU`qt+vPX#(MNo4 z>9=O6aV4Z^xx@xju7{Q`!F3(})|zO!yVS{LDUKn|!eKm4IA^Ds2j#j;WqI#udbNHuuvX|&%%daTizJo4yNPbtu8sR{33>QyzrXl<)UEPP(9Tf=Yg{YLk>dUB;?dRr6q zDI-Aunn_aZ3gK%bZ#;qu~m z2a!K?G|?VEX!v$2UH6mxS;i87$&E`>$lYIxvq z{!(R}>+z329QE7D*P*#uJe zj+3n=ZZFuN#6M3KDVI1NH<^OUOCP!A=hYeOUEsB-yj0bg0*dF;DYLxP#NEM$6E}03 zJ(&V3z;EYHp^g>IewSQUN!@~VFjpTsP(iBbEcBD{3_KrHkm?zmfOh$GHKd{x&3NM} zG_;a*PP3jMtc*piBwuP#*-SVD=P`kBVr8j;^NVTv8PCtBQD$W+%(!q876+%%yUJ46 zO3wH#EHn^TvxPEXp$u3k!`4Dm1Ev1_&1AY8C}Cs5G;L!-Ai6j`6Iub_6T zB4HJ>@HBlDGHoJ8AMlQi6ZNcH?a6dM81!3Bdd{l_;9mjWd?NXTNOfFJRZ+lTv8LSf`J?uSZ4`J;){wK}{sdm=5Y zF7@Q6CemNkr3o&gG{OtQK{9J9O$d`}xM_B>NKHM6GXlB?)3GqAs*@YA1`5W*M;CIV zBH>a?et$f54VTIm&R{=bQrOaT;rKY39xgTRn}GvxbEG5qs4w(q301W#H-umuDy8== zX^LM6W(Ev71fBtSXU8Kp0@n}|qAZR>aKQI4ozVP5#1(i#fasq4nN`jlPpeBic+rzB zl1$ekq$1QILJH<7<7s+?6yQQ&XF&5vsbbidJf3z$z}6GT)1W@ckB8Qf5_tFV^e#d2 zptKs&$Gq-%nvx*-P-vvoj0cRT36atU{%RZr)Rd<4E8}QGO=${O$I+oEDTF#iNdvi} z-7Mro#?jC&VDm{WX%ufhj;_~|X7WnfwIa={4M7g$=uvGvyggO`E7Hn3QUYyhf)uuE zUGxnpW9eNTsiL~6uH?yh+p%=Cp46>63QDjgAqW9ieX<8w`8aXcrwXNXdpG=L&s2D18FtiKbGz{K=&LrhHA$`b_KKS?}eWA z|3f+J$K*7sgC0oG*_6{)$Oi29CWd6!G3wD+3A^FG{S14Khq1?NeF5GAB41z z$&q959W*;3n?IwOjihM4;4{i>1m&lj`BoNuo8l;b3`i}Nlz{Aqs3dXCtE8qeId{M} z27E2JqLLnx7w{^K8OiZ3F{dfT96VAt49G_Dlk zLk(kcj*g+zjin&xhGwNDEb1OY8~G#Q&p zL!EDr)~)x&7@E?w0CwGCa?0ai*ENu8Tc}@0)1jvD=wqYlMN=4SkC{z(q5Xd~7Wj^~ z- z@vV{Kb|PAhR^K&;17WS~(=L)9b!j0DV`sJB>K`qnD8~J&QMp!91@7}1#kIo7w8to# z-%1MM?MBg|R?_tnUyp>6XyR*8O`?f^Gm^HomfW3hi063LV>F$`J$D>McUwz7Ugz*! z9C#|GCIa39ii=oTXcYOhfyezZl6tn0I(pq6l}jbDp70Z1lTPs!2eSJ#%WYr zX)*6QQgv=8&14=?LiuNgeJRiIl>ymMT?qETv+dIhm8IkHk|+Od1YM7p0^$sKDx%j0 z@J<=~9~#D3G`NAL_(Pzx)#ddFifb<|=j%qOciT%9CI0hpa_NL2oHT+W#r4cE>e)$Z zAEK8l%hEkbb4>9oU<&ZcvUE>ZhHK@@66LzlNh<65sSt*)^Be%r+Bd*XiN#LdRJpU% zmaV04`$#2eUT4Xh`wXY_&eBjeL4Ow9MT+75hl@UAAVRXM6ob&5p6x|)YQqnNJ%gXMKK4$nZitQmaY#vihR8ST_ zqF?pMA*bJ2iq8x}Pul_|3^Nx9xRqki-@LoSg_lHu~UU2sTLupPggp8v@aR57tv}UL% z(iA>zs3`Xo-W&J5(F-&jN-ug#BYDN4qW|v5T{Zjwy3pEE?gI#6?dmNG1706oW%Vi)N&J~>da-)Kv7vG({nz?vi<;yJ}0@;xQVdtr=O^YCQ3`V^wj{Y zCM%Bq>bNOVlq|38FNT2;vNvT-m%1104XEfx4EH8p^y#0g4qM__l2PkKblHFOS05!x zdsxNW0;fI-Umt}x_zs4W9a0)@ZH*mr{pTM@wFDj<^?v-zsRZZRdzh*BB$Z zM!y=0xJn5)Bu0#1%EaXKb2G)C0G$O_6rS~0LuN^@Id|_%L35;Ayl6jinJZ1NqcJf> zYD}x=bn5!MVf)$iv@r5NwmSG_e)a={zAedw<*;l)mU z)IRg2K1@2-=e-(zxIprY`v%WNq56Wi7?fEQ6*a2qW6<@H5`-T5psb&#DSjekTX038 z)IQWPNeXPF4Hjezv86C6`3sW>27T-ptcD_5VX(dCSd!G}1Dx#4avYpu>^M!ba5B`S z77C{34|>xW1(EfWKI&>kw6KbO)bxc?5a)Ay)8%C8I&a^b_AJJvyl(=HSt8X7&0>C0 zqWD={E4GwAqp~UfYHzK`dC}J$_X5XoB#Le?LC<-s7xs=zz2B$q8)%B(Vn=;1!AiY? zq{e(pFYN!9y1Y-_FbLlsv!mW+Lp^w@^dldhK(WivkVFZVNp*NkZQ8j^O68Y(Q`hB^ zSEX}c@C=bJuSb@ca#Pl~0S1Gah=y+`p2R^sjy|++xuo*vy@XeKsq3LR>LUi5C26dPm! zUY>m5PXd14J@mns2a`pEkL*Q*R!iIX>z?HGl@uqxglrlDgiI*r4Y*zI6ci}xYi4M%%l(>6Yj-eGrK5u zGZ@g&(cAEzrVFCSx!IGj(_u`BD!{SoSX9~Ai#Du*FZJlDo?RoQGyYc(ny^l45;?F3 z6q$ju2G=oV4O;$a+^@mCDA0B&v9=sja29)-z*#JCfmgB@y;vvtlxQ#RkAe2KPTQ*o zRa}pZ<#_QN&tCSV0qdnPVO?;arwr(SgmU7HdTodW`gXQ((4FZ?E~yxj%>utv>D#Cb zrZ>n8Yy}YRouRjCIsG`kE>{@L(4zBtj;3HHa11fE$ajNOHLfZih){76h$-E)P>~n> z1tQZ!g_$Wr1xC?wBUAhX(AhGs)I(jeLAuN0)^yhyHWdsphp`};W6%2xF^B1g;d3uL zhAX;L<|cIAFMH67O;RhHVkYD-<{c16*bxth5?V16YSF|rDLyc!wl?Iz$+5|B=YrR{yTQ zMy0n%}Z&=?y37ly@6@jiA8yLMAgZ-!3g-Jfb_rel6V%du=WS_ba4` zu@1vk)aY}|^BD7UT*dQ8-KgshX^dBv1#T#;)8Q)Mr%{7Dq_xpoyVyh;c#Q${o9v%K z);jxVhC<5fE_8aQ)W`XAz(n*r)`geA$x@Ns0(GP(p}yI(7lqoS0}Sb4pmaHipFpi)@av-uJ47l!Yy!NEde)M zt7;c@=spSW%w0f{_d}b@opf#7I$N}HJs=g4zr$lnYKf0mL>-XaB;KX7+WL?bB70Qt zD0*egk1_9Mc(GNKBpAKPC7+9+m;!1+;ie{C zlpbJ_fQ*Pv>8~XEdl7G?z)ORB%jqrC|^-+ z`KvUJao;wSd0m>%-?Uac-jJ?4lrPg-=QyoZE)8jkDzAjJW6hYHg9bygQyYC$gT`(2 zBa=yTQcb@}{fvIYfGA4*V+%y!I1s`3Ye0DXWiE9GBg%N}=t-s=siivbq2!0!jZ^3R zDNSQ?hA=|0$HEAmK`fXY0)w>X)cOgG5C+DY5$MPh=@rjxuI_&-^giEa8|th#pso!nL7f81xlOFplR#YwoOS9a|48L!X(QmhT02yirr<}h z4o)NJAd|DXe`9qumt&dyQ)A#~t&{y#2U*4evy<}fKXZ_`bLn;?jlL{3a+2Nn{zht7 zC;2Xuw=@Kqcc>9|z2o3YF(I(O8OZb+WlSnXO^ zUM=%SvFht$@&G699i#T~lrxPyI!3e#Zwh(ig$ZMqjTx|dSHZhum;t8 zA8p~|7~Qd+`^w{(Pf;`GC}8%q!Q2YW*Y$PGP5yFSF7*XQnb!_A$h*AUQVszwC447& zQet^IQ8was$y&XLoP85Yi%N3p9MC!JyRg-!~gSl5t^=hHCFDUqeoUO`al~ixfT%IKWl%tE2UDYtcXwji&euptInL z5vfZJdfh}0;*K>a`Y0B)Vw%e3`K$;U&=krHh@d%5jUs4%d?61CY$liF zi^D0pnHG}kj6D>NK!eO;s@JF+86-~0LNgcs|-aqC@f`3`~4F^JDSOHd|3p& zYbFQ8jRUR$rSth8N>|?56d!3Pb7TY!YA$!>A4gDTbMS3q=KBzMV$5o>gcxUQ<*>J! z7{}wAssEV!aJqzJ0mLhi|5 zhHHG=T@KgnFzJ8ci*azW9p5bQ5n*yERc#>$Q-zjt6@FZo5x34Pqxt_L0|VmTb~09l z)1j8oT`}_=ZszO$zwmX%_po%R8sZg_!>#00kG^3jO;gu>DNWmI`TPd5 zp+f+q4eRd^80TRY`wiHn_&WXnRpHw#r#upPKZ4G-DvF1zk6O#f!v=?`BiqU^C2p## z4(=eMhi8y4+VaQMvCT77@8OSpBsY?N0pP}xLSA}%O-OQdQ)4>Hote}+)SSaS*h#*} z<*%wCQfWEN<6Y53^aIoqS^NRgI)cP*aunygtBEMkutlgr@#~zhx3|II>UYX-uEF4Y z8UBi_R6Rw!<)!_`mUr!2cH+6Iz9KfAYR|LlYu~cN2x#ABNTQV9lBW|g49Q;NF0>m) zfXO}OX8g~pbiJqCDUp&h{#tHLmEbCw%+5q$vlOPY5yg_}qhXc0Lgs9gOWFwQB;)#}u zmix%AQXSmQtzD>kTnK&`5C$$myt%n*D&#fS1g-};O;tS^TOQ5zA?R$?#rKOA_K~YM z(uhUgQk0LS=)~MlvSETH3otlu$DkWB~Tqar&#OmD8xca-$D$ zipj5&h!x3poU$yOVkCOgS5Ck-o$mc)PpJx?Z@=K+&jYH`p-<#8w7Z|26zPZ8k>D6S zMZZegu24B$M&(B6jJ1S@2tvbk##x3G2b$Pl?jdy*9A_APD5t;NOWqL-uMzVc=U>h9 zue4xw$^hA&dHn*As4w4O!-#C;1g}``UCF19929rjd_No#Q_5*!Qj=<~&n%XrRZW(z z9qO|jQVbaL4;}yY_ zIZ*DEXDtKHm4ekQ*6N1}t!qaz4x$B)!C<6rpUCy3TUE^V|GA0^`v)-Y87$_;K1&8; zq&dC{MGr<-I=l*9zlEVs)o6#B>fXT^*GZ3p%!I!M(fm*4!6AOSbbbU^G{oEJR0~0x zttA>mm@eIsDh-ue$>DfFZTlF#>B&NR^VRnG7D6@4VSBO{yGrHH^^)Gi7INyD7gkBwXa;P zhS}Xrj=BL;aK!@0dUsR&C*S~%NtX4^)Ig16hQZ`W8%N7$c>O>c^O=mm2mlQ~<5-&h z{7h~yJ5?4Xz zaRW=+LbMGqi^wiQZxp$-<4rK|k10xJ7RoI@z}By5KHHQJ#&@>B#+Ge)3tPXUwE4rF z>=Z0t)f9i+j+4Q{2@2L(WKl4wD0N#TxBYJlt`EUyn(f$L^tU)sQF^>czEBnpcSMXP zvR$;Rl#N1SKN-WGuLc2hJz4g64<*J$L-7YnL;#goERW>B`>8V*%TqN!(%7Y#*_r*h zQ7x1ZqG78nOJFhJUf>#1TyQLz94S0RqXmC)wX}uxpiQ%*{msuz8{c)1|(=606E^5tXGGpAuk7_TMU-0L?Vvmj&`PDKy zQD{5afx4`a>+l8sv}A=G&A<1h%PZuHe5((=TOm)(lL@b~E$yAA_|`RK*jj3xuer2- zMb+&qIOCGS1H9+3oiXi zpyI&NR>W}d(JI5_s!m)ZFLbP<6K8RqILktu2(OPVs}bk*_fxzz;w%Gj8~-U3YAH4` zZjpP&}AUiGtY`9c4b3uYC?ZaG-gG+HcF0E|1xaH##^??%gLo;~=Dwrd$L=iSz z-ca?;aHzMdZJ#FGrZ-MFrcsOD7v@pMO<`p*Zpjjz@R9R3ctT(INfV#DRf2Xtt(V>vZ&yWE%Y zAIs4E40%G>9$<)}l>y5`J1xJlMw4Oro$ah_wfr^|R?^E*?XTqlQ;&F=>9PyuZ6iBi zd6wXu_iPWIRkayZ8NjbJp5?8z3)zt8X8#QO6tjP3D5N;+&&YR&{E_ps(&+XuLaXjY zQ+CLo$XWgwCFsEp`BxrWMm@b#-XrnhrD?h9G7Q5AjsJj>sb={#z-Ue@qSt z+2UqqjG?yy)6t(wK>@t*C44}<4jChgW`>7FxjmkFqO|kLm3GbMM?`1hGXBL=ur! zXb{96Lt^P5h^_V@ma6?#Rke(zw6=)AqbCX;??9sZIP)>Mw*Q0ftSrwi50@RHRcMVW~B=GH()vYdt=e%1hGpifC_n zZ(ug(Jqee8a78+P5-Z^^RnUeMNGqJqNfpeEoKE-$8#!&L$4^qGcJ!3=pyjBfXq&#mMo!fJa%P$1TRIfxLs4wNGHvA} zxOM`xRX1=v=li)%m2RJtb{M-7pE>iRC0bZ0#YmB0(N_j&=}g5XRt}}(g%Up;=DHv) z5XXno@(X(K=mqH+sWlVxUalnY!qC*OrBrEkSrZ@x?@H@4DPLKhCbubGCGo>?6AB}J z{Kbz3=wBy(E1f4bhgEO-n}Cf9asqz`B-1)FYH33+V$UJTV9powbmn}Enb!bsgBZ+# zQM$RoobSl1r49U6swf1Q9Z@Vfz7s>6+-=Q_3vkWu-Kf@jCp*MF^MZPmyk< zaOHZ%g@<`nvnGU0`j#x*bBF3nq zP*Rc9tDOzw5X$cx@C0K-7i0LYoHo+@X=at2~?RGE$pGeyX8ooaioYvAzTYHbR z#%9_J_eiU6rY*lmS{>KjSY6>g)A{4@k!&;#rV^yUB3Q?3JOG04LqXdK%wjj(f^>E6A#KAIcbIL8n zG?}hB<@8QgdGpFF*B1e=r|WggQAhte^*ScyWMUO`3i4vn^Pj+x#SZwfO!K02=NtTZYVs0t=Qjy07K-?ukxR2NkreKhplCD6O z!(B&vN|jd$0p^U7%$Zd%$W`k4quGw8EwHTG7|W`_>2Je%!Ks}qBbO6fSvGXU z1@Yl{a&2$=F@_GZp<>Af?Z=;>`|eRzj-t-x?Gr2A?i#d_19w;`So>9=yS zkJ?IdXuy_HB{kUuz6=}RT8QIZI-=s}!}4-&NdR|AfYdl|dTkrPPz%5vryZ;ymk~-L zcpoTXjMREK-p4r%GDc|&!TSJ}t0b>13E(dYa2ONa|JndP6U;pLAE3*X^T=acwndsTS=_pG`q=74c18EYRll(`lP z28?Fa&8FOt42LR{{3R}9@)u7*&LC@FQ7TP*`O z4L7-?s`;pJk`zTVqvXZgfT|8k#9p7B`s`Yl(-ZJLlE7c_SRkvD$1QShTLd}pr};x3@EupfeJZaXrt1IJ6Pzy4W-MkM5{ z!FSd3u4?r015#;iZ3B6WDDJsMo3N&T7v!jT-*bOzqngSQLg}Tqigd@(^G6XKY${dLHYLg53ruq8mbR+7yh_CH zlvGHStC#uK^ysJl&Lubt=ZngYgBsIY$tq;fs@`6&{bOp$T(8+S1+Z)JP z4qU`8bp!)z;WnkR)~%!biRj#fwC)F-4{1FfmdnUupPy++nw;pY|8o(Q`&DX3pQg#Z z#iAdz`0jGDSSu9KT#QqHDx#r3qP%!khnc_{l*nI5JNSpxh9>QImeKNiqK%5nf28CY z$`l&ZOP(6u987_k0giF;uGP;sX*rHXY2|y%A4uiAjbI)0q7HAt#vhRRhF7GjtNP20 z%KD9jcagB{2mIQB+^Jli5fvkN3#MDNbn_Y9qtERxS4eZ2=?5FG43W!=;t#ZLxEx7Uhssf&pP-imL;H)6 z%!eB+={!v7TIMx1a;s|z1LG{xVeDDw23d%6eEkN^8!CHR={&fd!C%p9e4RQkEQO70 zpN;Qh$Y)xIH;L2?Ip|Eo-yto)m^00Ww6hpV`%i}4O^`D{;h-NMlkjuDeN>eShslqK zi8qYgmv4&l9yDC8A-?-P%@_`wR?}0aiC3R%kSyP2)U#9(sc^WL{s?q2Bl@nF`i8(zK8K~4#DCnHocCY@5GO< z>UA6E5V$WIZr}$-kageF{!BSh9C@8?WXf^kQ{PkgNI6M-_IpYji7{g2_cURo9Pb%m z%5xOU(=kkW`9j|R%9Cn%)2rI#_5Pl|9w{fpv<4pEY040cJ53IUx1tB50k`Z*F897L zQ=jU@$-+QxOO=t)s9xeKJaJ-maM2(LzVD zxOooou8q6sy2%aN_ugjb6?=q*-^*c?F>;D^5!%^odBc($4Ny&2zVTz`+x2mLUq7-z$O?K-U(Bew~%AZ{D6 zbu1gi*72tIv@tESY=GNF>Z5Yqa2F!{4WL~E+QjtC63B&!XkFi8}iA*uS&vVKBXIW4iU7S-W7_evip@ zLgykvziWcJH2XVR{Ft1Wa1~6j_C8o!KOQJ3j@}=Ej_X^kLB`3XqgFV>IGOaO86L*D zGJ2f9F9q~C3$VNPq)ov$zQeD;$UAE1M^9?~zbE$4%Jj9XmEM9!u2Io=3D?Zq%NGGhWFon~MY2Y$M00A1n0g{u@gQEo5hn~{?yBJ!Xa*v)}$ zX5f#Ba&`0VoSoi+m#$LeB)Nqd;rA9SHOah_0%YsG1y7l=hl^u3cnijwv98Gh+U?$g z{#Pksascwb-h$31SynL_c?+7Ev7Z*lzThp0Gh?ex!7QN3HAT~X=d7-+|6#t~$u2-($Z^Jb;G1)q&XrMOXzdL7Db#pNYDP(^3u<}O z4?;??)W0s9QbGIfUPww2eDe^;8;jZapKm-b=P>?n0*(2$GixdMlXW*qgs1;5F#XLi zTr}gM&gIx~0khCAF4MZFKl7|1aY& zvOW;Pth?s#0FP<rpuViiVrU<^9oJADaHl$f|>&Nha z;B+0Nj7B)HgIQbfjWBR>He99yGv(;0Tp=%6zY%z_vSX#ChQsOTt>?WkneNV%tJcjG z9Bp-~9YIuXJcy}NMHy*1NYjI^Uc;$3)*|&7uE4MFm>06i% zL$6~}j~3)_&X;25Vp2F%PmZH4bK!ocnSq;gx!0q7Svb-@|miv~D z%#+7@e)-0TUk&X|XGO2G=HQb9i0y!*U`X#fhSbbFVO%NKqF}wijde)Hk(l@ki0oFz4enUkIknPVwYi#=V zG_tK_JdKIBc;^y@E`q?5m*~JE`G~mw5-og2&JNke^drjpwtPd0&&p3rStx6I^I7=? z$%_pP`#zU85{4_}5r2_wdvK8`qi-xqwaxw=CVv+L2|} zjx3|+L+v=x?$%)s)-b_m(Xwk;3zk?eukw5k5sdddPx^bVNoNpHcF3$$*998bSw$&Km6Qn^g4|0#is-M#58 zZIY%zW3CKb0&RA|a4=Y#3pBxpai-!0idZ2Jty5@pmLu;c{XgD)Vf?q168_&zL2Hp%>Q^_*N1=OdudiAwNqXh$SJkS8ow??Cl z7mCQuD+QqCU)RJ#UKKfK!w~OB^&fhHj;xg9OErWwc%-aCjb4x|iFGeh=nH7vF&8Nw z--POBa-gpTL`y&f!hlLbSYNBUKvQ0jCy1Rda63(;uvPM;kbcn1@2u|Y^EEABCC^h? zC$v|s3dwJXo^FLkZTXqCI^^Wqr{{ocpH7LsiNAr`cPQmn<_J8A0eXv;YhR~A3STX! zd*V#Ij~MUZzrZ_~a%(}RH~kX$g7KmXY3FJz3e31b*H&YlM%M+SGJnOqwm~|<7Z~YH z*KGVhpEs?a*On%(kvoJxh6sO3b>lUZ5!HSC8p^cubZm_r5kj1XxXKsk#u~Y=XFI|U zG@(A63GH8GLW5C8dDF++l-PWpmaj!7oG9wG|B#7G;CI{jX9i`W%S&>9Pd`(!J0SFL z{}+mFPq}qzv^Tx74Y=ody77{nAZ{(B$aVjqSmqea5g<3XbmD>(+qh017T=2%+UW4X zYPTxk1h4;Mb>E6}h&yCj9AUQjOXnzIy&PX=Kc^wCIrxn6V&!^yW_WLocGfTosdf#W zW#~DI^UIMTb2trgcg|CqUtTCKIcN0vt_^Z6ye7t{8}Jm`BWEdbgWQw;S|OK8(JKw6 zJbI~!JD|Aj_{r7U)pZ^?Cv;+iTrDp0EM%W>-twPF!Qkp{aRdzf zgikvRRaV@4=O{E=P7dE;rbXYq8%WDNN5iw_RUv1-Dx!8cuQB}`i5uZ}e0P@mZiLtT z=vkV*5q+%L%T+8B)W^E?K330QURiHJ&R2A8qufo;V8?r9aKu!sHA08r^4bagtqeZ7 z4ISOa6k}*|R`)&e6)oI^N?PqK9oU4m_1{O+c@yofBA~Fi=*i;V_xb0 zidMXgAu*rFR$%5^W9y-5c&pNon``xfoejD9Y}j%(xn;kigje8+Z!^)eUXgnYb%6l} z-nR`ve$p$r4rX>o`8*i1&_H)Y=ssq7(~p1;84d^*5%weP*w#R4=EE1Ewy(-Hki(3& zG}QRd+m_}S|3$Uc*1w9~GS3tg66;Wvb$ISy=GJ&@T>biK$u4s^(%^dUG7+M7Q(?# zIX(L&&3;{O*)p5sHwwNeVDhCYeb#_kK~^c8ti)_#bucdI!a>KlpMFU{y)LH<+ez4q z)y_6^U$XDMIAl8;4-8vTTeixR8|U-1f>)Q<0NL^=z3@YJVaDTkioPpn zz;F>$FZ|E<-G4bl1zY8qkV>o};(T9G(N?)-;xVSHEnY7Hx0xTdI)sO<^ktW}MBC+I z;wxX!pWEdQbpB=dM*rJ_mf-zUs2N<5a{4USj=n5P)vH|qe7@k@6AT8$b_R!`;5LNW=-2Tzo?6SNyBCz2l&{HE zDSsF5h<|}!0F>v6FMpv;*v&J$5noW`TXK7C?;G-inCBTGiq&Mdc=>b6c?-r^s>xHu zyw7=l7f z(#a3xN?OBrDEhQ24~-k*EZ`*;r7#@!}} zyVDW5$^E%gkK!p&PzPrqrkGpXbwqwf46tM2%26`^`FL=_#y;g!v(Td)^q&vp!D81> zso(=SIb1kLLPP0rO%v~?fK?VZWx5uvZHI0fG~Ls0kd9X8ZBL&S?mpPw|B81TOg z+OK&H7|nvuosa*NB2UO;lcyCF(MBAr;Cdr?@$euX4&;?)uNlwvS-@b)t6s11;Reud zKpHMy|`E^niZw=B1N{sFkpUPOV)pklk1)IjJRliY-lNZ@}nh46;tiT?O&iliIn{ za+2&^asr18W=M6k)@S9ksq|`3`AvY1kQ%ALkKjm#WS9Vl8_Lsa`a;AU*CaH!Ox&}Gx zAkZLDY9Y>hk0JzRv2^}Dwj@8C^NyfAARX6(iBd!Ho%bkGRAz)OJOa&7;rOkbl=o=D zDz&e6TT~7URd0hB!`cCt@~$Y|JOn}dqiX)r%B&>3 zJP?H%FXkCvXB4jF^Mzsf`m+J=4eIRngOh0;_@Vkcb~8rr7{?S^$L-{inP#l^zHU z0&vSEjKN1UI@Qzv#iml$IbCq4;N-4N5P2Q!%ipnTY1c)4P?(@Lx@8!5< zS%fDTTq=S$SP)j*dg1&CjyZk~K8sf0h<%s7uBaq>{(8s2+rW6;{{>!mJU@p+7yE2@ zzrI65Dk+OSM@+nNjE8sgEt&V#uM^gaaUGm9Z_%=TdGAnS81#G9#Oua*DgOcwzbvo` zcq0wGe9JG{@D6PYQ)Y)eZsJuxMBAz;Rq7h%$}%b`%+(6ntBi|$Huj0{(6q`*VtQYb z{WjA5jdgW&5oY$XO!F7xHHJFC3$x+%0FEDNRaek~2t09CK3s8ydk|?&JVqQcjskXg zhZ4e-RpJwQbR=BqE8fb(FDWStLr&)zcx`{rXo1a4yj5@rpU;bb1&sG@j0J5BaS z{vY{>t?o^qWW(E%NAs#GbIf*`_f^sYym)pa zn0FI+V{N<{7B8ONc(a<)#?#)+#}yFr)`XSU`<4f`CKh1p&0zy>orhnNQj$GUCLUK~ zK1cD7csNIK785y}v8>^l@+UGa!NAEas3l{JC9+U%4W?M-L91Vg-i zu-HzWYTVyW3&6{E3FcjE@xo3Y)=+wSo9+Ql1qP^C$#Qq|oK^f!;Msj8aQf9SJ8}2HJqg0*X@Ue3UZT zH4_o~4+XfVIV)@9qm_+L=WB@5-5+-yrHSbL`7P7yS^I!eUJ}pl*S6JDz7@qzZyIh( zR+1}BjC@l&mY^&aoIk&5I0`hWp|T}18X{HOz-45cqgH6(Sg5QQ55>5 z60S{Zq-+wT`5-Z#*lXBW=_*t$3pUGbum<|0drjwn_BK(noU_3K&!8IJY=!;6*-e!j z;?})1AqhkAy1hIU<1vsVB|#MSQBji8G2{oZa~*hLKczL}uCJ8O!Antj#*3)gUChGtR=1PpXeJ^!vt|Si6Hl=swjN$hMED_vN8BegQ(-u7^hW!kiI%|Q0C;e|_J`3l2 z4QezdmVV427Vo7q&6Rj@4zkX($efYRa@3)P(q+ydQ?kgCjXqn?TtG5jC((1{=6A(0 z2B2Tg#E=D)iwwnSq>1iI z`@RB!e<)Nne}$y^UW#d{q=~6}X-Z3_y|`!}?P;kbhRgsHpEr>9(oZdw3DtYBz(Y=7 zI~@4Kds~Pm;b~w91%rRS)41>qZQAU`yNOCnxSKVY@9+t*ZL}Xb z#On2BjlONAG)u}eGAz2w24x)H9*)}0hD@tyxb*i!cQ%d#kC^mot<)7O@1xnRl?X9( zAFXb!B#VnRI@20e?jo*_v{9yoU)=+_wS;~CTJ4OVT|n79qEU7mB_$viT|%+J@jg&p zti0OfcDCf^;qjDYrDcHE5n6(m&x_pzZLrSuEnY_`ElE~di1YW-kz^%4WI7vk34VG= zqd$`s{Or0$32l|(Nn=>&iF#@2IzzeMT$;72IwteUgHMsp6HBjo@{-RHoY+H0+A7IZ zrnOSxe#&LyMFX!*xwn9&8x+cQaVw3)%6n_RzU@FkY@k727LGQZ_L4p3BgKUn3J=d&9VwvHlHur9C?S zS$pV4dnGRJ`8R-vsr$x_#<`NOG5ZeZID}Jy!)eEMQ_B>kZ^9PDuUGJ!(2n597TP#P0x|AURIr zf2S`=qp_(T$pAS(plMhh~r+eP+cEkt-0i( zRx_O&d?}pagN}VN_aumGg}91lod2M^wB95H3u>bQi6-i-Io- zalDhD^TFb4kygC2B>G-N7z;M_0?Ym@jR+$=0^0xxvtrBfWhFk^O%*%Cy=(FYP3f$( zk0dtxL3yA5Utyg>z>mBgf8YzPb!q8ssC)EP!mf4qy2KqR|m7ULH?cYTaU6sgC1@XJENW>L=(N5~v71gl)8#JS<(uu3>p{`0DWysDV zYWfD<=nBVu3arshiBD?Aa=_CRU#^;g>I0b#gL42H)`@dDb{DPghFVgvi~j7U#ED0D zQA`?YOFiW9ezhfc7tKpk66aiI8ZJqzwiFtrGYq9K^#}97+ryI-=>|97@ACjCGBwXOpb>D-!p&%G&%iyzEeQ9mVQ}1OdM~B5Sb7)j=>`AnlO1@KP>BvAgEOI%J=j~Rr|Z$d zAEwI}@iYME(wR|Nw}b@udpzU@TVnGL-4a<2&`z2Mj{#^7M>*f<9rQ|Xw55tW=uB_8 z;pz@bR!hZ@ccrV8)~JtCMG!0IlBcgSIw4P&k|pX=aE2Rqi@pRZqy&~Js#sDo!s&cp z#gk-cm?ajXqVW2HsUiQe$eT9a-*Zh33&Uw>Kcz#+X^z0WXVy;I)(`WZs477iaQ9)h z!@zmLhI2BPZuG;7QBPQacL{do(zHjEUZ%02elQF!Tj2(1FB`;jmMWm_JJ&SUYbpC` z=2B>XCB`$=)GPub`2K-q0&`}PCD>KPjAIjKCW$sV6LM)re`RdMLB#v-!jHXMJTKx& zB(hS}9}|u?xmwx)1-~J7b-OlXpn~5Ho4Ot6`JPjvLl)s5Hqt{o=*FOX7zuZwVtFwK z8e3ZO^kD9GN*E09|I{`bI~c`&ejBYCtR#nbG2!$dV1omhgO&D<+i^=y8ThbOmNo2Tm%O;`vEh z;PoyW6fVRW-cnW=CtWiTmaXtwVR9k-J;4gs5GH3Jd}o_som!iaj?v_n6>jLLGC2bg zzgiI)#?jdyw^8y?EMHzS;}^4%kNt}hehejy%SG8xAlMM+w$c8f@T@{}>C8~noOevz z(TqFdU*L{FCCBp092@SN+o)rPvPX>GhMzzL?sOA3l5z1vP?iq&t&sz9FA1wHNjBUm z+qAL6l%Yb!hWy)dc=!?i=tk6o#I3j)nd7Y7bqg5u$DM=D>v2g7-l|6H%&V%8Y5M&~ z^bm)kn57I?JO{$;3mlz|OR_h^N>wZ6f)fBKHMi1`5lVRbB`n}xZOSeH?Sp?rXroQQ z`K`2Pgpw`ohsM-nIyQJ(WIDsNXET+4_^HROl#}eLp%sl(A_VczEn38AC0r19Z_yIR zDC=bB^ex6Z(w+&*B+xro3-Url^KHA@ihvWrnGl{ zu-V*UihE64JPkc+trm!3cVhi(MYQ-;X^T*-@+jA=Z4Q9hBsfyo)qF4vM!% zoMh2}f3L~E$KcQTsiN~#pYR%fBM&*y!~8URZgE)aI#0wFTQZB7GUz;2Dx$vIaW`;42yu)kx^ai z_q0-35+C106Q0GKaNH(Z!QT;^XwS3CYO($%Eq$?4AcSZejlOvB%apJbBUN6o6b$DW zsrZWc zY?*RIbl1j%!O90>=terWT$v#Llua$4Q(g%36d!K1=E7 z*<`YNpekRgv}m}qWupl8tf3Gyfj8WSw=SFZ15f;AqbB;4L_vIYBPFd+=7q;VfL_l~ zuUc&~Hk4{+)A1F`aPg6B?ghfhJ-}ItA7xOrN1j)_sx!i`KYJ3X-CC`z7o0ik&EUSZ z%7=opff*#E*4B=$Q)UXzgX;_uBkmc$;#Q?|YtaYjFLqpcRoNoGzLr+Kreudkyks;0 zFOnZyLmf9Ok&+Yal;1#&p#vwJRkRJ8l^=xA1t8#-a&1i!eYTp`y{^OyW2w<@rIjXa zQ6w?+TO=?+SA3fp1ky(=H2;0Pc2)Sg606PJro=i!9VX$Z)kW0vzdDk{%sQcVa|fQR z3muCz2Fw31_Rn85XnI&Q2H3dW%3hbai1552e!gYU+e(ud=|zKUEEQ3oRa}JVmoX$| zV^3(wUw7#ykls<^=<~OgLDHKbpxnWws!`7a%Bx~U9cXOKbKqskzaqKtg_0P%f$@}y zvE`sLNa#ovjw)3sDo?p7E?s44()k@|Qp!Y`2$TUfl(5_QDKBD8=1F--qpY`-F|_nu zrM?)miuS*&jEz~(!l8tW@6DAZm2iW7iO!CDI){`&V&50EV}}$JLGP7R@IEFOsVk}C zQGA=M)Y6Zl7K-sJxrRk(yN@a3#L!F61JE3SHmsn8kCl$)P6Wj*U4ap-sq_%#eyofu z_i|9ma4Q98!CaJaTzRJ4l%V7Wfn-@OMGu`&dX?)Mlw2y13~uf438lO<>!iJvS26u(fO&LDfL~>x1NKJgYoM6fwS0xUH=?~UQi-w z?^ntoE$f`pP;fRWK~O~}815`u9?W)OIkOFS9xW03x*i)vAqSO8G(JSB-g-Y8sy^_b zn~cV0i`AVA9L5@r)t&2M%w4VSoWnHfYh|WKh6D$E`PZS9AD6hJf_$tz0X~*H(#Kz? zH`4I2*tu7{>4(5)(Xx+qcNryJR0c@bm%$tjA6IHN4ps>xKnazsu%(h2rb`!%RQQ)%}y8h#0tEOHs;T*8o3ZW(R+Md?GWzTpXdq|Yzl zdW9QrJmPC)&v+oRv4N9o9S4{QeVE4Ku0?acftOWSn|6JJgE57*wI{w+nhKuJmKqvA z1x|KUp|Q@*8Z##wu~-Vm9kl#Q@FSlGvPH{AJh7C1yNu19Jtp3uH{||LiaZV$}hBs%amUI#$p4%l#Rc`5{kT`v~7eY!lf+o)1O?Y@c1at zXD)!{43PaP@FIBE6UCPe3;CAP@*B#KiXQ+@_Zp*&wD*=$(G4ZC#xU>%ZlPklcyF=M z^*Rwxc|YO8X5QISuF~0n(<@nFG!6X$`|XYxdjAJyjC2#PBvRv>O1sE<;A9`B7Qfwy zuLF`Mm~rD4(~6r)Q&5Bd!<))D{0D?qKkEMh;q@Pto+3*VJ5&%~T5&zf~584eI73{GXi+rh! zH=oz46`gJn`26_)9KO2K47%;$(YGJw<43?5j1a*tI)pQS0kpi8RxEO$vb28X9o1?-pS8DD2%ZI}m-ub@|J2d&YDvaH@{ z7MldLj=b8`=~rc#*!Nj2=T{}fDQ$elRE$3T1Ec95iwqf87t!onECbI(>N1S4v#^dX zBNH;p0y9{~!$2}*)S)VWDs4jQA%eT)lh4wSKY7I`PRBAZ(4V1ZOYqpQf-D%P&NH;` zPbJMGo9wT%?%2<_Xw3dGU$En~MgIuALpHp-izw+YbiD5_;)6{!=*%NhI8B=Cl(dGo zm0z6F`wLAAG(*wg3Aq@fcn#C%M&o@(y?Cv#<3Xc%t#ILkG^aqVv+7su((+r5Y%S36 z*BSL-z*_wmmCWS}kg8kD@!$)W)w&`ciVgonZ7Kfxv|hL^EU1ikJ0fTyjWf=pGgkyv|0Am@S z2b}MprrAz4P5k(2I_^|G;{K;8LQ>m{o1dm3k~+b&%#_oZ<)GttU{L3ZXv)bI3^}=m zc_0Vf+F>j@c7Ys=mgOvZ8t+A_X(6Lcyt0cZ*{R}KiLPcbJCBPPi0atbhryDvI-_rr z$^I46{rC|*OT>NEL0`83KQ-|S^O>r%It>x#e(;YzcPaX5ZMLHRCWLHUVA%BGg*4j* z-SEO3N;TK%=9lJ>H8?&J+R88+)=LZMfJ+@9Ee5;p_)v>d>S)g+CR!1Tx|ikb@N7B2 zhuh%O7tpm*YDe*{`Gym-bv~sD>WCz-p`GZcAEYIYN1#%jWYIynEsHSc#Nnt4$kN@ZxNE!(orIYJ%vQ zPiM-iiNo8NxEDFI*zvav5U3h<-0paE2tL$b%ok*=W(f1n|J`2jtlunN8m}{-Ccq|% zKg`nyk$7Gf(5K6=+gQltf#pH)8dGS|_l-f9Q+qz`3031_HXs~q^Q{~PZ!gvtHor69 zu=!u}D7>6HK|DW?ZJrkLA?VoLlNa3A++4$-wPoYIc@$Y5=6>B|@5y5RrMWKw?@=4x z%kyYmd6;|IJUU(;=JuMnTrB_A+=p@0Hra+dgUtYQx3`&l%sj)~iAd*hJ=ok^fx+f} z3~83RA2jH4M$My~3TmX7Hjhts#nAN%YKG?_B(e=Z0V5ykvda6ub)zx5AuJ1h$9zF` zH=Tbyvb=8pGNM}9& zL_D9jhMxIBqeGTpw7IN67Ya9l-;=9o=&93kcbvv@krtlLyEcMPgHDyb6dJB3cp8~9 zPO}WS4*w_vuEQqC_<{LMeON}lx!OYD3F1I6ox7qYifLXtAiHXiQWd@HRxhPhMWo-0 zBg*PD&pfY@Gp<%<3H*J|Py!2ZBF=4-I@3$-tEodgkC=ExoKwuQEzQgl{a;IAut~*Z zbKy3;bT3`2hGyN|#5>1$SPlF~JWL-B1MfHH3$jY0m&Qh*Sx0zjb%c6OTs4 z<+%hALv13~%%LMJ!fl9n7b1T5(r*wEas{NkM00!~4XB~Ucpf!HmSd5v{za}@p;YU6 z(;u*j95IJpsi`g$d(PGpBGuKRGakVDQQ$wK)JcMrG+Td0w+3bO!NFbkS-hLNJ4RhA zN;7A{N5DhKVdPJgT-u~M>NqT7&(z;$6}!%)(B7_=lz$x;v)sL1rD%M-`l{%BN(-;2 zel0kU%`84L97RnYQkO>l@s!aM4#D@~8ORiT8tdKGZ)R%e9#U5bN!O8}cayNhRs26k zbbQCp(lGI7Pnw6Xkye2JbvneKpFyuQP=`p*fu0W!Mmdx5U)w*WZZy52+PlUrgsjCe z>(?N5gI`}HbDzToShqG(IV#^stuHp6Ny&}SB|kZXhBQ()q~&rKA)!fnd1a*VA^j_6 zBb_MDt< zRNW_7MZBm8geB*Cw1V60U<2lXvlmiFOvQktuYo}DJ%BaCNs#($58 zt{@d_ACqi&Tc+bj%hhe3sU}_o;~8DS-{YYx$i!fjXv3Q@oo2Lvetk^5zmRTr1%Ho+ zu7F=Etz^UNKAnDRp`P-THSu;ap5bHvJszq{Dt@5kL*@&br>fJn@K)*+MdC=_cbXwk z@}g3q-KAnsme|)2x|zRyM1H>i0B3DvwiVfWs!ouKvxSDv>KV8nNtL zL#E;CFTky>pTK9)a+OGUT$|BRttFVc=8EoMJ}e%>PhD^0`EshRYp%oHh)#4;m-XF@ z2v(*$D}#a862M(6EAc4+&Ibxylbvl~pEsoa#-Uqv-4`zOFdCNRs2Tn6n-H)8bNPQHOg5y8BPCesc7eE{Ih+&RFk4^;052-Pn4=m&vsJF zCuKA>Wg1^+RFW=}=To9hX7UtEW>ZQ@S0AJ$oz&0(0A4NDOUeX@1;Ax61S?(J0>G=q z+tbw^B?0_40L+)(wE+|%6MC-wNm@!T^%lkv>==|jFaCD1B17ZS`HVk@1xHG)WB#P&fsDk zdcTkQkofu(`mK)|C(fEek$o{NHUt6J$WvhCsVa=AXU43NSwdkmHaaq0{Fd@2+~l|c zK8uz!9zU5D_k}ajcM9$A3;eDo{@qCi{>%Rld|s@0+lGH@5~cN1lbnZu*Wi>I?Kx!v z&tzbuDgC|TXf8aLTxkQ&pF}_PQ#&Sc)$_N-$=tR$nTz`u8)QfCt)`4xv5v`6IJ~pj z3O9F5_Tx;$%adrrBj|=-G~;!QHR3-TaSaAROtkvibXhTpt~~-H&YnyW{nfb08c5%; z5eK?AI(!#-F&QhXB2F~%J@d1ZX-I!G@8n6w5wV`84!?uvUl$~Xs&Y0Rx=bQvfEq8Y z1)h0zV1U}b3%t}8dPNYu#@AWcA~0BA0Bvw(sEIIF8V6`ExiMH{m=JL6;axoIGi4H; z8K6c=T*Fu0k?U5#DTN&TUn^Jm@gi*c^F&G-hDxSk4h&JllLj)tMLs9uEqGsYtkfMu(4HM{9FgHETZbQ(qBZ3V@|9IghtK(hhy>_EP#Tg~a)gD;9UopGK+I_t9oalntSXf3tO zcly|(f#cM`cnvhg#uR;C@S5RrISk@AKyuDapkqVTv@q0_tmr&Gs|0Jn72+_}&rqv| zUS=~O#(^70sCnrbYE1l>h^uUgH`68ri{vK}*Xk7+c%sQm$<8Mhha8z|Uw=>jw zbhoEkW@wgxC%U+ficziguQQ{y-j-s~Cp3rD;I=dssCruhZL7A10mtJ^UwXUTXxy04~1o@X01 zz;&|*#&xqiK9hzf%q{BXc$zm7Yn=nf)2WeaT)QvEfp$LDNH-d5q~CBD|1V(-RAR^N z_WBqRjWL1gxPcr-8n9Z_dJXqoNXRW!g?f)tTgUwJ7`!5j4`uZl^2x{AzruM5=Dq$H z?Hr}Xwa;Px8jfBLha=s(k5CAF$+V0AO&l*{*(l@Fz?^MiBD@4Ne~zPw(dz8>Gwy@) zDe}Pf^=rjAuL3762xlO0j*X);qt#?F9(ZF=e;SXYj$_oA(Al6xJ=T9d=J)Y5ZH$_f z{(^# zF+FA9&&ZMPO0YOK%}p?xu0*aiMbL$z>haeQf~p5sViN?pY=Tn9QOsCupu9hxMvYY? zmEXq}(a!O-c&r*BX`nUsPCpu}mI?nFNzbylw#B9K!Z_{5SXB|EInamlhr6n3<;SVb z1@XXG@{Gqq)#s1V3jU6LjLwY55=8UIX!ry*ZH}(veGDSuX5r_^D4MUHC-&9C5Vj2R zWh=8wfkC($^K&(CK|a=X_hD_;sOGAp_g_$$ZNvwq3$cK}c{9V!^pnp&TM_&wFzW3O zRv0IxA*}azRv0Ix3(@v2kJS%8&pBhpds(P4Kl^**V@k|F;rya4Q=bCIkF>SOkOO`~ zR~|8ufp!>JV(=$1K3lu3k*UHe`Xx8|@?oj0M>CZe%tVGW`S(ijybM3%{J2et9b;+2 zBseWC#u`ppmWi9hxQ2KA_qZ4pC0xHuv*9itOCgihRni#X8B^V^Z(^SJ>11_W9Ct9> zcz82sE7JMYfb|ghtw%X6ET`F6ZPXMsUJ$2`CA?ZwgSP!go#Omx3^xF0UFtejjg@wT zRv*5!tf^|A;B1XBzvM&Hr>Q-h9YOnpD7Da}C)6ybG#|lL{D@HQ4D~(M~Jl{XN;zuv(&_pPA1;>W9Y^#>{8j;aqKP=?6Qr$-Dpaft-d0Zrs#!g zCAu2|RV-R=dOJtaSg(3VxJhH?s)IUN zNxUMa=QK~$zapO5(Q};P)a}T>EmhtI)fFl+jl=Dv((}}AQcFbW1t@L68VAjsrw)=< zj6@v2_7rj!hrroicy^>#G!LF;#A8Sbv}iQQ(N?&;@tYR|%&-G;xnbr7Eu27ZzL1CK z-FbIh*U?xwkua653N^WX+iYal!CeEtjxse9YYX(r=djQ2^>nYC$bUTyUFM?8A zM$x=Q>Jf3zNb)>`b;_hn8v6{qr?r{10^jy*Q?8Ph5@wYw&b*~CS4nsy={7mbGwIJ~ zFp6%^G}Nqie>Ei>c4}l}AD^ksepX%L6r*IV^fDFiXnirlXzgwBjUSF>S$;<=W4W3t z?aD+^=bpvml6g0s4JrQzHA*Y{;PIL%2T+ovFfGjU#C~qE2e}cl-odsee$ga z-W*}3b+}a;xLS=CHxH%RtKnX)97+YN)%Mcqp-=;7n4&1Jid3G~ZpZ23A!|@4wIQ@; zjXE#^XVGHf4Ed()p2p!kdM)dkiYN#FIBAR}_h7Dj(5Won(+D`my2&L61 z)r`*i)sCi{j=S~!2UEfZwc9;2Hi8dK*kFeR!D<^+Zw2GcU?7DJHdgspWvj6?E?a#} z$82OX_Xsq+h)-=IcPlZ|S>N;)eZ@)4Gi)%k_ilw~cC% zSQ_6=YNB{%2*tmwwlzy8OSH-sjpiXkm_9OckMStfMA>FJGF(J2t6N2F5OsV-9cWfU zT<&vm{m8N^VJ23f&w>XE2QaEx7=B-SF4?Ts6cYzg&Ste=0K;DrBQ^>nk`1Gsh2bwn z&2rRH0bV?*5^R7}@SX#0umK`0UPlOhlA{jkV6@;YewHPecL8|!*?4~)XyzNVZ`H@R zfo&28u1y^rNYh?d*9X+dvq9lvp4SHTmIalEX9l;Z(*nHi(k0Zm1l~S2UZ2J5E=|90 zQCqgMvfwCFf|uVPYGLDj+~NgoYh(eB?V`?SZB^?OYfut}FJM%)q4c&;+-2yytym?r zG{BYMU?Zl2_ZDb_3!tgRn^%TLZ&TZd{RYr0+y1u&90Kog8*hlkixyC6yV@?KJ0kcu zQ{EduL$<4L({njk7q^sg<0mG9n?oIM`cpPQZGc&#c%5ZvuG&J38KAAsWsmT5e>$>5 zty>b&TM{uA7xxq!VtWhGTb3H{R5Mcbre``bS%RgTt*P=Az_Z{CHdHkWsnA8IcdETh zs*+byl}zjcb7q18e(rB(4o|>L+@<Td&40+7eh0M3 zK!CS}#f#$Zw?}PMejXzHa8v(yq==@$pQr1&Y7N@GM}7HzDoG8z>Dz6v-+|jw={XHG zux7hHl`y}W_lP!juR2O{J_ril_ulii`ivrm^fflJFZ9t4 z98!}du~c6wdSCr1vVI@KVOi0;h-UQy2G%fmn|e6>(Q19Q&=1rVlK4w6o|Yuh=O3$? z;=XiBKCTvsQaV*Up^geqV=g#-`qji=X6siIOQrLrq{p@ME@iVoTTZH_o8(60tu$+8 z4<2wXUN#M!=+(m+r2{8=^)MRsiMx1z*;SxM;m%CEFVz@aY_m|{E0;jA!WN1drkMq5 zz0{jr4Y=~d-uZ%GuP*swR5?BDbn}x8#=iFF>Bx-fN$YcQgqgIpB;SB2K;GH6W9yjPt=d4Y(xZ3kw)TWFG;1r3*|B-f2O906MFKY z&j`x=OzrJS2Psbt{$NZ@TcL11XOO*LD4Q$bb_sutjG68_T&(hj4mvGou4_*cPvJyK zeG{*M(=omNM?6fg7ho!J4SW_YMDn-j2RY-}WG!{2ZbkJ*}=4#2>mF&!H7|r=l-$z!L8)aQ?(R_xl*tWNh%5#|Z7UFEn zB0w2RmH$GO8(0`dvnj@~!WM=Zrs)@ONZ^ZZbl?IugN}7G%cZKB6XWYFUkF~#Vf^2uJ59N$9uwzwqvT6!Lc*_LWQTSa z()AsW`J%7>Q+JDZ8h|klX-t#TO5Xo`Bps@k&AF(D+BTMO(m{%rPY_Qr1(Ksu2e;01$_Aco7B}fz?N`T z9at7W$<8O}vaxjcL>F3hRZS`DHlp}I)QB$h?NxP1NCSxAM*UegO1p+tk&J3=%Phl& zXv3{AgM}mgJ!=-^NZ0L3%dg?cR;bCoo6XitZ^OAkeFC=EYAJdKtk#XTeUG))iCuYQdO)jrLtUgKJ<%CbYB~1JxTG&~^Sy6g zmEx!#N+%=6XcxxJ27!4heg~4p=pe+2i6CJ;eYYCH0_A0F7P`x6SG>IK=D2_iO zPYrB%k9DGjcho16@(l4J?%C;<)YZTxbc{cWjio(AGmXO?NsWutrk*%cmyeim;J?si zAl7%W5^xE8!Fh}7L_3SrGve8fwEV7m&6C~HFi~g5y;rf@^N3>K6y{COu;H%l_`n zC(!XjawPeaa4%=6>Z;+C;*exim7^i9SxLAb2a)-r*Z4Xe(RvrokACk4r8meox|yPz zJKy1rqNhr`ItF;%(K?33n+o0+Y`iBeUUxM8UfR`PY?4ChWn3-AIw`cgjB7*y%U=>J z6HggEY{Pom!tzJc17%%pLPjHkTV>e}G@+~uFAD@?pb?@omat}3$A&X3g|?M-rFq(! z?3a9)Lu(0=ZX`=oc6{Q zsra$Ziqzu@PGc=C?>b1$O1nY>`NnNCE(gnom#|3Mz=r==d(-~7ZT4IRS0AY#B8=m1z*`bv69AUk06wq)ys=az%r&*x zJw{$~1*2}|iiJ8-u9dgLSXmuvAmwxC$+lZ#Amus=W3>}uuCjvoa65iPJyC4kjw*(` z26*a#f(!XWaB|y5Ms#kol;8yGrEW?=siSSD;5r@30Ne(T)^%h|0n&rqgGWH_fZ&n&3$_@vb4A4{-lu zep{j6$J&Z$!%KEk%LwGRj*0gn<2C*lc<@Lvam@cB_$=9a`MPOOgexw*8sc?-v9{n# z#F0IA`NG`vQ-o`_=TcjvtQP-2WbqDjwoTT#wzR*x%M)_Y#2eX;LTdy%pyH~C-H24I z0?o3q?`x~2)o?Y&8CJdX%@w2SaGMP@lucNjVY38hZx}=|jU%cKX*FGMcHA}t9E^nL%EZS0ZPx1o)JR#vvxM7w%=I+$vH2f}}=Cht=_ zZNP1lDJcfy(2H$pN{p+o6bW2o+omwaHC_BRnFiE$#f0x`Z640wXdF@DgGrw!(~8Qo11!et%vpgBvo)$7 zh{2p|b(rU%5Db##@YbP254e82A8%}1Z+br)@AE;tKRoEVDh_C^ovG`><%ttW(JxPI zs_(iaNC~ZAjEt+UXxf_KS})#dsiie=wUoqfn`?_3yYQeoeyv#l9T@#V^#@uI9#oIf zjwZQU3r@AAc|{_sxob;g(-y`IZB6qcTG$Ll2G5q4omOMnDW+x6tLjlLT;&DnEs*GM z6I0iguD8O+f-A7(Wd3?eon{o-%C*P&B}lE;)b~oSFr$9x`e4p8 zCz*np41z^6Y3oy53FtC)6XlBrbG~J&RLoS;!JHA~w=OrB^Bo!W$l1ZwGQgXs z3l8w|L@mk2JH_J7t4IIo;OZl$HKk)6T+1Wkk#GU$sxk!QT{1r7@&uNKW1G^Hj;>@+ z7&F3M*$+V8v9=WAZWQH~FW?#$e+|Xqu3(JdsYn6%ELtw-(5CcfM|8_qnizP?84umE zMRQ*~?v{b~iVg4UCY003)zNd<#2d?aI6?7`cxbGfaP?uH4evk`tz~Cd_n-m^&KK$~ zra`rBJVRMF^6to}uN{2Y^{ePSh#0-!xzyG5mgu~aXg<7mw7Uzx-|$-_V=?>VMjCEq zEyU08HPlx1ais~)?jQtTwN?FGTWZZ}Wb`o?8y3;=2FRA#$81F(GZuvBKX=yDuJm(_ z5u{&`Ox{LPEKTq4S{wc4@J@JPRa8Vp@``476_k0b%r-A+W=Um&WwxmmnJK9$<)yXAsLUu$(A53E&d$ub%vZnp zd!E0~gRj{+=kq?FbDKGH=FE)s_%gPu{PMPDa?%7YU0q!sd0AH-(!Px^7pa zZT7zW`lM!zaIcF{#q2xO+k3f_bbtLi9YMeKXKHpK8}4^)eh2;bCyDxF)LtQ5p5u}G zP1`aifY)1WD-sP`DBa% zr+vcJBe?ILW>H^Ys`Io@?K{4UHV^2Hi9?bT{P{Uc5zT zd>66oF7^3P($4BhZ)0+?3T1K@O1g)cw6mL-G(o*SvXPPWM%u-MizLk@hJ4xW*A|_+ zUBvkbDj!nmte5x;iDKBqivJNT zzR3pSFpa%DIW|d+v0cizj7yvu7UOlDjFi3IMb2dPo{+7pN413IH-K)i*v>a?T|GqX z6m`uoz4PVqrpD^FT<0{h*xqE?61VAD3Y>wrowece3lXv;Y`z|%*;Ee6-8+e1Q#od| z?!+2w^}$rTG^AUtM$o&*_V2Z{XJGJp$cJ5cshv#_*GyBFrGB2E>rIh*yDmd-*TB;& zxFP+xMemaYk(j04C|RPeaTdE*W%@?{`#6hfrRNgFnJh9qxs$l&UaO$9 zXSI@z<5qGji{L0z(Al$a&%Nq@Y^kR@>RDVuOk=DP?1PtV*o;-=CsNj<6kcQ%9mVt+ z>cHw*)DN_wLyWuzd%`=+fcSxn4U z`-jr?R=17l?@1qRv0ZH1dXvS0Z1wh9GBKMkSqzw^w$^|6Q4Rf2`iN&kKb(CE3umcq zf=3W(XLs?`S(vkB13l@xNFcnBYMTkV`iS}usj2cP5VUnyx1DG3{ZswcXWTJUEAekMCi1pjBWi0<|mxgTe&5 z&N1uJ*GG)xhn;tsqBhMcf{|dwK%F@Dwn&p^6&OTy5jym;vv*!HOYc3+ilm3!L zXkUA?dH2bGr82B!GIMvYY9~(RsHr09VYPwPsc~q@;s|$YovFpxILD)|OnrbI@)+Ne zVvz3@FeA$YRClSu0Qk1uF+;bMX^kp&#_t@Sj(q8e?gdao7-=Bd}(i{nI_`D%jwT$~s-U!4-Bru47wBhv_rENZ*sOdtD; z6Z6&9O$V_MS zOW0RE;W(~znpzT0Hxu?@{e=2Pn|IoBOd1zFCY9KH19-GeKPG+1e)-y+JKKrPPpav5 zUpvw8DK*jIV}IAD)g~h2DYdhGU0X5lDRqPWg*Kx90`=~s68XSKu%dz$AYOoHb(!X@NFh?^}EPn!}hM`5je^+ub$Q=7tD zo>OnOiFNa{^F)Z+;BY;E7mMh?@TH%+Dd`l zY%7f1w^^(e-MU1!m8%4!>@Bfklu+LZ`A}k4YRDoD`7pi%b3+!D&CXyclqgD#!aT8zD?QzX8mwvXH|ec|BQ$0_c3 ziG%ewsD^BLGr%L*HfEnZA#gI_Pk&RKlkbVtW51lGllz=J{TOM)i`~RiaC|?cruo~; zQ*b;+XE%Qr5zg=PvAS;THo|#o?o90Y*kD4j3-!n7PMHz%h=3!1#frW!bFKK3vHvNV zQC19?Rb!l?N^IWn;^Pd(ih(#rr^|7`j4Q9*zK`V*4E2TU%(^eJ`@;=c#K?_>=@z56 zNnAE}g}C=s-~hAI%C;dJ`^5$ygNuCLaIQ~lv3UvC!B$_GOjyyI9%7MwI#!%tqE2X9 zh`BuL$|F3lW_afa`5qf99(+Yjh`&yk4t{9QMuEvVHu;e~^5-(cX4>u*zWX_t9eG7< z*7O>Zd9AH2Umky-YK1i0b@6nm+Nys~88%1{n%q>kHRspiKk?_!cRLIEr)`+fv)+RD;@W*(ZnMUI$;Rh|oV;_7XbA@H`anitu=< z9xtzYJbk@X{qTrnQf8oktVmd)#Pt|$%jM})^S_j{xAhqV-uE14&IxTP4jQk~d~uV#?n0=rMAUZ%VYm`8G= zae?v-UMS0+DkWuH#ixqjR;n!>he=z0qA9f}A+p8}NT->)H?53g0bM&-V+ElaW9oh| zC-4*4nQ>(bU0aI#Ustb5ZD{BfNj?4867=GddUTEmCJsw1dUaX~`zm#qeP#=hzDoU| z-qSd&4}zldpKKvwRzWWXBJ59H`HtTo3;wy zEtY4FU;|}V8QX3a+o`54aeMxbTOC~DkH>jhaljkQo|rOy4*MO%bMm_ja1{PqS@ z%(a_~32W3b13kK}J?I1jCI%Jzh#Ows4NY5TWd66u^swN?T|Lk4A7ez#H`OttEHYb> zdD|lMYjdLhyayIae%`^lKXd)BH`ZMU3~d7=Yl5Lq7WWPbHAU9&ZR7-2UPW{mfYutsaj39B~V zd(4)gG{JVqRTPi-o8yu;e8YVFKZ zU2PlBynK&!c!rvrYM$DKyWW-Sm%g|{$~|6P$&#@M=KJo}l|pk$E3XJ>I)$yy)r{35z)t!UO>d~ zk~r4P$PAVF)Q4&VoBhRRg-bW7wJ(&Xr82g$LZi7wWu&R%uPwg+NWCWHfl{|xU6f&a zj=13-^f7Ifx?<#J^WgPjn(b}J?UF=7jioTz!PlYtx)ival zRAY-qnyKNA690Uvj*9U#$d92!_jtldeF)p0;nR>hZ&qlI1gD140pT-Go z&@f*0fL6GFRgDe*D7cS*(!JJ z)$8SnHC&)=nkRjfMPShdf&AOU{b=UdJu&D{X)9Q}a9}Mkf zp3TS6q-0`?srY+EHu4 z{>2yinm5u1*++PrUC7HU&+bDFMXN8FE4E~KTsl{T7Wway2sScjr1Y!F zuhdyN0VL$r`JI@`L4%nqImnRhO@@uSNZ6l7*zk*l{c3~_y-3)PM%cA_SWdMB4;q2} z36!Io3(hoK^Gz_U(VE^D36m{aI-GQou+NRKju#2@H8!Tu+FT@XqhZ**k=VCW9h>@B zL;W&fG5h7P-E1>**e)y7=BX8Sgwdx2#*gCcgti%19{!Fs6p!vw`_~?fj>4F*k*9(9 za+msI>MA3F8)X9ApEivynE>~v%Wh+7nI(bO8j80|)LyCc4ZSW>k0nh1swZy?j^Pfv0m!Zc>)fMQqx9E*+DAs(f#P=JL6LK~PUNOrT2I^(f zQ2hM0njxBf!kQ2B5YG3WWkH7y;dk&_S$s0{B?~u^-!hIu+`oTd{Lo^rnk0&Lt7-Q0 z4MgM~^@X5h=!kBSEOT=w#3H$`K}b^kxJP}(+&}MJZKr9_wqm?Mwr^ZFrCRko!zSB?~-p7QF-jWPOTG9<%08aFz ze?c@d8&a*&faf*U<}t3;7YdStl`-`|A8#Ut?^icpa5PeuU&zt%cYD$wu}FRt70fJ- zMvCi7IR(zIFYYg8#;+eas&)b4u;n}c)Vtk_QH6&~)sex`l}zBjN@Ox?Ll6%4y+6In=rtb^MdT(SPnQ!|Ihb z`+<65(f4Ys-PJ|#aQD6RFD0)LzIOGiccw0>r)T*Z9FmU!m{P_8r^Gm-8Rbbkyo!m9 z`xy^dl3i3!eCJn3>Ea%q+dZP56$5tbSNg$9Wy&VJQnzLE9T^fg6O=tSiQh5~(>vm! zAJoOw1)S9dA|B+GwibcYbqxV$LoxD4^%46$^~HBTsvRSk1#c*7m8l)OXA>p#KGJBW zo4M=Jo6Nj6u4d@7SqJJcPqwvY&|mow^0+d!OXOr}NaXwLh?mOLm|n~I9h__=;t#ga zYckh(5gJWcXwC|o@d(P3)1tcK*D`gu-CIKp_(^@PB?CS3%iL6>AoYi$ZEFVRa5+&| z9REojZd84N(Vq&;BTR(Hlm0iUP<#dE5#~yMOF51(;(?>;m8nhHA=~pNib>8|nURgk zEifwA5T$aNwVI3YUW;&4UGdjZwL@K{QGReblCkWhdZPW$>PS1!g5~_IZn&hIkFjRn zqPCvGFx{L~j+-yCL%KOYx~ZR4gL%57n@om{M|h+~`1v~GXt~; z@}4?>AW+c=hi~{r9TJ|G`)Z4&zo^gKv+BycG!@tXs@`N@R$IKiyG9%Pi?s_k|EfM{ zi@0A(CCPVzJKuLi*k{!icN|k+8Xi-dwn7!lL6ZC^a(jNuX0n4!$(guD%q<7krNVm) z^jjISDfA;;F7pdEA>#Y^E%(pCp07%`78N;s=OFuc)njisDpJ;;`3N*`h>aAH6>3c6 ze7S#|EuV*86D!oEF}L$O)a=;*Em~4jM2e#o>OB#&2^SR=ysRqgPql~R1V7hRMszGJ z`BRN|G>y^Diyqv-@jgaMTji%snyqQ4iF$vlLmFO1*sFHqv(tnXMv4i4v%2$fO)ULe z?b}}3{_SYGCOpmy$om~l*5qIp%hx_{)(X%6t=5MwUF&G^d12Y@-k2<}ThX~UDqqWY9uWRb%DW5nu zs4vE!W$kfpEz#zj+ShR-X2G{ny4jEotS0J41Iv@0#%N%9Hg}VJT4bKX+eB~RvVrj$ zu2yK%XM%C%@o7{ovHcvmj;p2Lgz0VQ9#Tc(dCu8Z8E(RC;}-VcL<^U>vX+>79+`h? z>N52Vne~^JiDUMEhebxMB^n0Q3HHwnnQti}nai9@%gkkZRaj*9)D%YpYOmgJ)Sz%! zMK0Ip1aAp(>u0?oDPK|PK2*5$J_3uI7U2Y{+6%)=0@E!=I_;n^ZQBjcc$%LFNx1He<$hAJZk=S6Rs$Z5p!ya zNSoFz^O8P#{W)h!}n~QNj1ehn|95R4=g2P};n`u!?GOcF(mbFq-{-{?| zY`1H7HQ;-;iTeF4hU7M`u9=U~vK)2r2c?z&5+=C7XGTvEGRW-n}t zW~HnSIllKd6RRS$YwiE3A&y6A363WT2-s`16v;KTfxUc9^JOeMAB>cAnEvzBZwHIw zI8)ITE!Nf05<<4#>b7&St#7ft!L;>8i~2RgY~?E?!qQ!VZ6$HTbJE?kbzUK+)zo@j zYx>NKAHr?7VSCVG8*SPW_xo=sk@}Q5FR|ViA%3l?wYSfW5DjZ-3HDhLg)DuEwA<4i zB308SCVF*kd$2qlYX)(bs<}mbWQ0+|t{CyXrrjG^N(6a=>l-0PMQRg6<>QN~=4Tmq zsJ_8AJdX`bEnkeNjMPro-R95_Q?Wa2yw$n&4UWcz4eDq~_K>J0^Kr2pL8VPt6S$J! zvVau#72<(<+7$b5HgU9`HmYmn&GrR_XoC|9-qNPq8ck)Ea) zxt3qezCt@~pT~P43i+O?vx(Lu+Y&<~VlloS4yCix;o9teB0AC(o!8NVSvreC4O4+8 z)}ezoFfvu{V6N47R!r}pod|iOw2>tmDg}ApeX>PsHHphO3SSj}IbQ4H*!fSGH{JC^ zNywYFoIS6#C_G{+xMK5DzM|2(+iHzPT1Tx;pmp zI47>@qzwo;%D14y9gSn@;7V-6i|q)01s!#_DJ<-yU1^WFg*_r|EMJ;d6B(iTbq%|_ zt*+&58$7Vi<;v>>F~haGhP2v>oJ6gqW8;}~qW-O{%!!gQIk9b!p6f^ZV8t0n`vRL1 z7pBfxiKD$-`z%W>JcY=AL}XWOh<)Z6k=~VY)7@vpoUYo)kdv-(8IG(BO!F)fJMbx( zVON}}ous9R`f+r8Gnby~0xJ-hVi9=56yRMfB1zj;UBFUIE4U==WD%HX3b@;fSFhB1 z1O=`#J@8fcAcB)aU5mi=rT}rHzNBen-N75_)8aYBm?{e2JC{w=sI53uPGA*YmR(I1 zrCni8H?4uq;X6%rHLlS*bq^b|x@M7Z@Y}IQKf7dgaf4$#$Nqdv5?`Gb=eujyIGm>N zDns~2DJ;KJ_;148j2+Jr{VrWN&pgPyc3QmML!00jV+v0B0TxDc(kYXm{E>-c2}?*4KqeMjKd==CN7euthuggC$8$HJ#0Ty zDL&|>wQbFtDP&SVI2;L^v5~K_ErOi;668G5`)9=YURvMCzpC`YUVKJO?V<4r?qCDB z;3-A0jk899%wgCx$FVB$Xm2f{TOZ8jL25qIM>ws@ZPs=_^%^d<=KU6}71u0QNX`nb z{3LAFX>qu>*2~`Zv}l^FJ!2PD;`L-Lp;esJ8Dz^}KF*f^8Uw!{7|^b&WFNo3IW3MS zYl;0E$T+yZ{4qK4)QGG#Ub9ff;rA9<41}fdJ62|Qmom${%QZ_bZv`mjN5|4(Aq!SvLb8h2o`OhOPN7pwK7MzD8v1iy9Va6fR zNW)&$?bi&c5(#~^JM68h#FKrQY>MM6g#hvh>2`#=zmcq=JdZv zG2Dh6(=111w6I!fSy{NbzZPS=?l=M7{pju2zjb0`S?#B!A*;%~ruxMEZOj3EWd1hh zfHv}bT1KraQ`Z^+vXRR7IGHJ4GP8rY=@Rcr4;FfucdwrkFS)d5QtvnPTKpdhZ(D*V zy@w^YS*OJGfy^E3tQ0Q|ZO(kL!bc;h>J(vQh#VeZAB63<1MvUd>Y?W{{Se`t#pW$xYEJK{FX1WKKLp3LKxu7 zLB7o?m(6ph(OXXhhG=~pb|QWJkfWu@xK2w>J$O>D!$)P(4BJe(OC~KZ(is@OWJ!A8 zN%7rvT4KZy^z^q4m5kI>`_(5!Vv07v&ZOM56s?{8<&$Dj3Wu>LPKv`RTJM%*NM_9L zPS7*x>_`S}YiwM2cm7*+yI$*NpLkOIdILwg(T1n?|3e{-M@JT}nJZaHx8UjZTCZFB z8G1j+LSw$&jC0AHQsMwGMV)8}V!^^G`KSisPwT zfBWAjMB)v!$e&M$2{&kiLfQ6os+R4646x>(6rbIowXuJ8BAD&S4^QY7bm!lq)ld$Y z)~3Mueg$T;EMC2TLfkQwyO*X)I2;Hs%MG@ z)I`MJsLiq~?ZmWk{3yCn>tm;Bow!lE-hS_2qW>^$K%&3BUaOuC)FxA#%+Qo07+z{| z{FXJZDDmRWVa(9{@|V~-Ok3ob_SZSFZg-8=5fj)D&b@pC=Czx&!!|z2o2GRI1!>wu z5Ph@O*-`oDIq~X%8m(=|Maw(12MYZ+YmIEz1v|IAOqU7RTpe|1d^#OY{Y6l7>v_^Y zC5dpSZ2S&7Mcm>og~!KeO>H7=gf`S(_e9~+5!zDQ#4AZr;aszys76;U2|JdQ*xX%Z zawQIL*HBlL@0|JrJCX{t*-2<6z(nLu^BOg{WW4F{q@fZ zJ$)h5*Zb@LPM`i7M}J*sN&mMBF>fUO^)~b_^jBNDu#MyMeib9NC+r0c#6uYjHT+TH z%?#~`{q_p+%&qiUawct|Mg0ld6^3;lV@4^xcC2ve1g)Dbbq9MCdd+kM<#IJs)Tp-to15=X2QOx2;+)_(^bF>L z_DS^3xUvX8JI0qA87Zta^wOoCe!>hoc}YEbnw*2Z$D;T8vBH-!H9i%x^>>l_gZ7ee z-=o#Ps=y|{rY+0D$rqwSZgJ0zrt}L*hr85{-@!5=?y*fG@kecrh@V6g%4;dBtflZw z(gxc{{uZpTh+)6c-J)vLY$Dzmr`0X2H<{y=Jt|JLox-FvoH#|hM_N*aSBPU%G>`qR zU(E{Qy$wO96#21V#~N8d2ayYRCYs+tXIy>7fvHqbBX$HUsL3=cX!oxoVHy?mz^_IH zP5o6?P(7Q-&eGyiUu3sJEe#+`7p)~ExndDkaT##{Pl}bFvQ*XfnG}|XJ{Gr zH-0G`HdBk_#lq!c)O~b>Je!+Oywc}_PX^0!=A7SJm&-Fd!tJ_Tp5o~*KEF@<-Tp_p z*l@r01|N!52I$rvoeueYu{M@QXX^)l>tILz{LIQ<%QoppxJHqPks@H zv$gKS6vfD)PKQ^nZ{ghuRQ*7U*u%P50goBy58lWGFI~vI_bW@u#>3!aW@-IG$!q0NFGYm-{&>Do4EV-Y{^Y{%cN;i@XnVO>5MXg7fzuNkTIixUL*+xRblF*)?#L>sJ=}jlFKm1nfYuqwj`IDGBSBuG6N?Nfz zn7+hFlS#sjOqFev(^Fo)^SX%rNA&5l-~;T>8S&%;>||=hGv;p|V0X)PFXnF^VE2>G zJo7gXu)Fy!Gb!^XpI`R}*S-8CA|KbfMc!)!H2Yc1c|wbh4`wk>?`ULE-g0FIrYl+T z8CRn6+&1Z_!g-H#!glN_GmqK13`@F{iK)3-n}|5}inOE}aiS;s1kD*g{c@Fu6yF8zgro3uvjc4I$-d-j)Kf(3M`#*{EPiS-6Zv2tr zW%6zLa(#wy8RL(B>{~u4*gf-XuA1W2C$)Bw-^++Zy8S1y^GU6J??$8_oVg=n+~%;= zZ;#pXcMvzU8V;KjoRG79HL-biH>X0^Q`+ML-8E%v%d`7+>Yg(l%h7is5yQPMK~Tn3 zh%45!{&W-*$-m6_3a&&6s7C7qE?-O1}JR z%m5k2mtdB&ZQ5-)A|Ax9>BL}~_WYl)8!p!Z3=5MTW$HtgooP9kGA~v*w-`TJM8&$!{g&? z=L_*;S@~D(2+}F(Y`!*Z;3Kpj`4uf^hP&uaMTv42JD*aN*nP61ZC*9s zTibQ|!Ke!rAz#1{4D;z>GsKbSxlnRHr`2g2-0#=-PrR6oqKRjp(>m5N#Kp(YX-zr? ze<)for5i71Wu!DDn9>ca$h|^|uY}6~{V~S=9CJTkeEj%%t%;r!k0uVFr03tOTi7m|q$WBn)H)^vlXUA5kJrCQ;d=D2 zpX-bB&uL9X-a@TGD?|8zCB9o;+xu{5p}a)Z#2*W_rZGxnusF9EaXa94Fdol$#lAqe zOAp^*gf}WkXE*x%SIQ@R=U`<|3ID$C`!FEh+5MS)LQH`SNjCcmU*MjVu) z73&?1Bfi5xUTwsSvX_{|i13SUFKc7%uO1PLUgmmZ_xIwvm$hLr^Uw_S6?9LW(O>cJ z`(7O1q_q~~mS_!PXUK#ZHT^)KY=`pbMA?jx`{D?b(=ZXu*%01*j_F@5VaDjO@5QMl z+A#aH@5PW;v>A2zc$_>Njb+{Xhko(dE82Cp`uK#QoB(vy57Ob556Uvahhuh zJ|IM`DlX6N{~Q)?FV(u==+~3B2a{&J&voK1k_u0{wwbgiDu4Gnl4RCRekm%LtkNJ~ z-uRQr-t8BOuWE_)Um@8th8n@FIeDt)RZi^g2I9c0+O4VY9oEm)w@Tkwzhx#Q$3#Iv zo-UEp%fdK$GuFJ<;?!G*#T>5|6IoB{;Lyy&VwqRFxpsx(Z;;=fL>@UT&U>|i^($=B zMJ}$Si%%R9!(P*_WTz}HW9O_x;+fa9cG9$A{;5Of#Lb7r=GU0w?{D~8M%tI_>k96m zp2g10mmJ(A9~SA$m^zO&^gfk(%`PMF)Lj{Rhb($m92Ps5X^+~DiFej%jTUXvI@=Bg zH-&4Hri!)8S;+Xsp~AzGjzgmTDl+xULA}tQm3reYLvI|JLT{Bt??-gJguQ8GYI=C4 z{CcL^(5?rDWh#nH9ayDZdB;bF6XRqccQeh>GP>G-*ZdeV#af?-EKU?kCkV@tPS7NI zBrkv2A#u-YEivaMBMp~Kboyros4g1!*`eX$&|hdacn~wQ+=Jj&$1UnG5Aj91{1h(fUU=GSc0M zA8X`wPVi89q37O2R-C-GnrNm=vS-viD9&S^`X|XK90`PUn>%-AoJ+Qc8*m%Fbr!wf z4v2Ygavs0#kl64hZf!Mm?>;2Xzj+b2uEQ-Z`5v*zd~`tcU&~FJ<%aq7hs2z<7cn1% z7nt8^F@NQN*t}M2URRMH)YM-(@y|hVbS=l(2MtB1%;xby|rxrUU0Pr2EQm2Y0(>UK*YSQtx}zh^WXc9A-(vdh{N|jR!Bvy(^_gu zll;Z(KJlHHTEO@(YoAs}WUSL#*AF{-{qwCHV~ zBSc-V)hCZiO#bbZSkbrggx+4Htk>cqSF%H9@CMqSSGKnpIp8R8_+x?%NzN9OF#sD! zIgp<`a{%`0w_?M3t(!K_Fz+m${#c9tFKdoZaxvOqi?!!l(d~Wh!N@BpC3*I_={wPX zgVy_ISMy-vcArk&2|j$v9h69m#1Imejw-~hyGB10+x(2#w<`IS#Fgx#%id_px>|(g zjc;f$kSa$eJYR99EOCE(LqB)cM=p5rie#Pd#Fh?qZl4#?hm|W-Uji zV7HOp$CmW|DV6rF(_3X)3}T;@GiS_?%dFXaEWD@oWgXut(_veQ=EA(KA|5Ja+V5NG z1hWHfyV6G%<2(BeN7>#@n0#NHG?I(AhDZVS@Ay`1Db(8Z+8S<4#$GmU+1_NaO_H|k z-|(%7DbiwkKPH_<>k-JsNJ1o|XtRK3voCZ3L7Z$o&YBJI)h}zb5+9wbsfxEg)N0lA zbII^xsaRUXL`7byNZh2w@ai3{vwib^IU46_=#5&v8~u8v*@F#|H;S=1I~o7X0+*d@ zCfdQa;AxqEl`Kd`z{ZsTbKR`t=SrXrU1;~W;>nE+$!n4yV@O_LceN6qZTq_MQ91_7BPar~Ae659Q?Bepw82>fI`hVySML^&@RdWDg?AiBGppY<_{~ zW@Gl%swc*8)^5}kXMQ2E8}1h$Y}SUQo@ZMY!wRx>@nUcqoyi$GP^_SIb%E%UfJK7K#HU!3|xyAmU3T>iK0?6FUD+Y(e^ z{q0tEwAv@0+=9wFX+eKk&gFhkh3fAn_wn1kUu@YDRPndVf1RDSed7EU?Jhk}6Sp#7 zc;FkcXsb5lwil%d&Il;GStGNX;Y>ryNzMb55EkruNY`awO*0P3KS5Zi!JzZFuCqqE z%4BO(@pOxb+9G3{7N6>6m#pm}NXWT)Z`iUZN;1!;S680HZ`3x2sxn@dcL#-O#+5zs zrEkRcZCdkszV^XJA6R%_AtQ>|S)r9-}K*RnT0wYOSrTMGULh;`Vk%Zq}7`%^#lI&cX`hN?L$82KUiwBy(X9z7j?B+ZT!$@ z@_Wmo{)d_-hQ>xj)s)AC&EJSKpKHCZ^>@?@g*8($<9hY*?ng$5vn&a}k7%%Ph&x** zPLGpPuYM!$FV+U+m{R`gQgS4iVUb#BN)h)qBOh(Zhb$MFgiYy`FY_o*Tz^Viwj0S4 zmyzU5_Jz({GOUG?pI`=FzvtYAYaRT%o5=D+CR@9lUpqwe_(Drh9T6-f*Tyq4fu}B` zLZ0F{%?k?~%J^aTT88ZvXTIP{KFQGAC&TAohTeSc-Jo|IyKudPz2eF3-0_Yw^fpMn z$1X$fF}f6bJ1u&Vdqw1zjO?AAf?aAXWt#bo==LR-Fl7{#LYsV2CXsU)N#x)%FSTA~ zN#gJx@xhn4yv@+NN9sLv8F~-lGJ20%^fvDieRtrpOLw^qF1PqbjNQQn>0%>^{xXRN zE+dHtaG5u0-(pGPIdr^)jaosolP5~9!XMr%&hOxY^gbhv<}wZDc+A?lWLIU5r;IeZ zThf@eN8JAv7o^>H8^>59o#DjOTcrMaiO=_n4PSBPH^@l$7yS52Yj(Z$m^qECbYSk$ zlFZdID}>buWuW4M>m_1_q zPO^3Q>+o#V%|B1P@N7+|;q9W89Vh#;mC0T&XM;?wOBUxu@)_?*Uu#LXe7AT`>g_P} zrb|6$gZ@=-9Qi=+NsHcRyG2Y17v635iqsNxmm0c*rS6!^&>e%H9hvsB=q}zZc9$?~ zHOJ74lX^_%{Hve0;U{|iEPC1K$jKbna+)gjS&R85hil} zH7zD`%1BE#5Hqek#U<<(Pwr+I^hb%&z(`N}6W+My?h#vdYyC$lMw+ine_4-h>RhsM z-9-MlzTRv}^9+sIOW2lWgFZpb^F6#i~iqet29ri{9keV+ONg& zZ?timyL0|7ekOb!nr!J(KkS6ljWB(lCF*%cL_L|1;_8xL!0y_H36m{d?0l1yd6xDK zl*Ih!3F8h+LvO5oJhz{VogO7(_kQMByuqjpKBcdLV9^Bq zm2E&KB?q6?@)lrLp%;TsStnsPg$j{j?o9`6r=>WBC^_)Rt8H=?Zx5$37OC%oD zp0Zc8(bpZ89%S92ZI`}Kv}$MgLea^GSSU(7bCqFdQF2HdVSiw!TxysoMjX}}T<_`@ zEHAsiTX5(tR~sJ3v1%FNcd%JFyXXJ;YS?R(=o610(Jxfn?GkSv*1E-(;efnQoymUd z?ZYPsleZ7;o}I>W#3Vn<5#MCDEQgzAMwxCglfKYIx*JVIx=58Wr81by$-6CXuG}e> z`k7^Y%Fw&AL@!r9_oufo!<=%Ri~02y^T&4P^S0BD|;VJN7JN4@-@;iJN z)bvG&#WK%fZ8d`5!SZtVDD3njOS}21iqcD(mDoKx9ll=Vg-=o7$RA$?%?r$K+=<^Z zuHxw>o;|9ShgmDVgDR%Aoa9<%vHo#~VXgEQ>weazG<{fl$LQv@NjyF1&u_rQ3_7U$pvR z(*EkwWvqkiX_3Cyl;-Ph5B#Ftp70(!f>TkPG;J*Sl5=PZi&t8H$z6G_dFARQ8zIyMlT3)qiP&Vhe`bmG>L}*jKKb&ud-LJ>Sz% z$xlJY(?-ef_N9nCp~Vg)ST>Xq_^W(4Y~!h7{j$?zQ{H#aQ}S)hP~7*ZZYEFkxcL4d z;x>_=ACXm8B^H*Qz*gMBNr{6UrYueNqceM`NkH)m=Vtu97b(j(qn0n{^W5!LJI^ph# zQlhi-KK@T0gVu!rs~RCr-2}IidSnOxD=e$jrr2^O-!;|Q|7z!qyC1x3+JyM)h7BKn z(_K@>PrqyUEosvx&q}{5Yufag_jl{4%p8~1w`ol~ZbziY~v`?6%Ho^xYQ~cP^7sF*zlfZ1m4Pb$BF0w+;`mG9Z!&*F@2U(WPpk}h_#4dMdj8z}mGGB!UuB@q z1OK+wLoT{j8P{(aZZt zWuU-Q{jZdLDUVeKa?e)=)}E{WSI)i+rI69!cRh0!eq9x4vHSA=WL#@}>+jr)=*c*F z7uip`IhURINxR>z`R_xmSl3i`*F=(G<887k*v% zQgY;|TXXt7rYIAl6s7dpQvo;IXBVFe6u_t#PX&r$(MzWSRdDi>Q-LH_sQF+IT8^!FX zfPR>Flmy{|pD~=LCVGW#ph22 z^59%sWxxmB_R2sxbU7*mQMrmTyGCWemCFLsZEU#N(Yan_U@@Eti(tQ4j)Ab;Ss93a zf|Gk|4o|Q%%!bLZ2+oF8uudD|JxLB>GE8bqSAoY8=t^*PCmev~i8#QTUVl&G<*+g0 zDja}C{fP*@1L==&^dJt%ummPAP?WgAgu}dRD+8-x|(7VdvqM0p%G*X)&TQ;DizXA?I*5%yF}kbPG9wjYn1n{IEqvWk7wF-<+0`VL5ce zBF+-IF!?qdl)qsqlm~J(k1CJ{a99O1VdjL&KpyPO0lWe(nS=v8^qn=WGLQyc*_Al~ z4;xVrA_x~egafei96WxGx|>@Wh=-l$VE{)zL5`qv0m87yGnIj)=c#MxeG#2!iAPnO zg?TV39|vK|bLdm_zUR@Uq>^8tYM}pR&V_jtQN}A2B`jIW>4y?X@lqmq?0b#ILqf^R zsbg5M0z(qqv<5raV=Z=Y?OO;hq>9#20&qzIj>5+8QdMxldt?koyiXf>fui4lqi|tP zA&rTRIvep&?)Z?pl)pcss1{KIn@JF!{g?#d%uh%V9@|2KT!oI`MuPC*rz8kRd`^OJ zM==S)!P`l2F%Ex8g0RO|R3TiulZ?TfxDs;4#*(ioN{X=Y9_kLR-b)0y1C~PPHzfEH zC9w~O;Aofy3*cg??x)0Hi&7GNnS^07TnIDZF_;Y}e@j(CFD!bQ{(tg243^NC4$^92 z1^1zz-Kh<2d%S zV+e;cTi_5p))IZ}TeM<7biu{2sukz(A~wom$sw%MnuK4cAGfIrB*B!nRRK4g9f#+z z7#2ZSdvXY~J5&Xnt8geDVVDh5U`5BOz-pM1P!%YK3t%~n>r@qpUQHwKOvyoCXU^ds zHln+bGkCBk1~8*93A_ROQ37jl>}rJJiAl7{ItRN&s$3uL?wwkRST7 z8#)}jwFr+OL3j|l;DY~uo%<;P`TGGJTgL$gCc!e82Gg>M4@;pJu6U5Pv5x+q z{ZLh)iXB5|<46IX&!MhJ@T8|IkiqZSkCAg2HJ1cn#N!n0I|#yfSPawPvm3Ghr572p7Zk&WC!I`ie=0fEQ9EI^vIZnyIWS9xZ!#tP^i{K{chkmGTC;lH~5N5(0 zHyhb(WWy!U3w^K{?uC9BUxDG5I0Bu}15@Ba=!UCdHY|o-sQigNjDr<08LB%-5GKJ~ zm;uZGr2l)^=30w?|pbzea<*))q?Wa3-q=aAw%!D&x9$W#7pbz@tL8z8eA_-IpOoADu^#9Rp zWU*r|%!R9A0W5~4upBDi(&##!4n)Hg=z^1BCR_mX;CfgDi(v`u(V3EhDKP3g9D~Vl zJ#@ngn47~!au*VWLt!y2f)&u2NP-7w<F)V;SxDA#<<;v569OV#o!$v$zfoU)sX2K;f4{n1+unhWP<8CAf2Sev!iXJAz zJm`iiU^YAmSHlYEgYn(T80-ht?@6co>6}0k8(wx~!1XW-?&v`dVFfIL&YmO;`$5%D zf-niLfElm|W{V`;iR56d2tX2Vp|qHr=SfO}ynj2KKW zD#uY64^yD4oc=$XjZAi|fO&AowbUIfhvjha5W3GVbW<1)=Uzub&nR!7IF-f;`$6xoIn*5+#q3xCE8q?o{Tn%hNihBf5`;xC52g$y zzWfcV;0_pdjGW&{2|~{>N)WDwxo|HmfK{**#@$3o{7y;0=o~iOY`CBoX2MdK2amzk zP)Q?aFdCM^WT+gcu32wkuUX2L3%2V2~XJxqc=I2e|~3|IkO>GXf+AM`^uQs7#c z1&iTgs0_yt#=&yvf>9Mz1x$vkp&M?3*{}?HVe|+}2=;&#a59YklhzJh@F2{D$41cq zJ#0k$hXi2@SO7DjAFhY$U-S;>ga=_VJPFgF>lWGo%z~?-7nZ;>SOr^*#O?$o0F&Wh zmio5MyC8;ftJh~XxvoZ>(Oqv1)I1f%bu5yGL+16zzC$1nqy zz_qXn`k}Lu9NtMzp&w?$_^~($hr%N0h9xj(2^&>x_@J|jgkdtQGmg52Suhu_h6Qj3 zEQS%|$svq~(WeoFtaeal!VH)Tv!Hqx2}36=f+Hr7Q8*bYXXyWP*@!;F5eX*2O)vxQ zg<0?!~xg>7Q-IU4~N1kxERL&Lk3_PEQ6V_3VL96CiXB77Q=0KWA_jJ{~#Mt zXGsXg!#ekn6WAGM!oko3$HUcdHuS*-uoSL<6>t+&&ynLvlpt&Y)1Vt>!LM4JxG>nI5VH)g_LlwXb=!G+3F`S#jhM$cBsMfG4+n^Kr zVG4A5$RX?jvtb7G!nv>*dSM0hL$xL)0i7`V5$xe$m<2OoE}RX$um~2zgE?$eu#xmA zy`Yv&Nr6ew4O8Gu=!TnMF7(3!Sm!b75+*@KwJGCaJj{h@a1+diB`^<0&!y49e$Wpy zp{m)GoCRzovEhRm@FeuWZI4sLP?<-Sz!9(tW?g&=0*(txubRPFM<4VD>X42p2=I42MNIG6EZZ*zZ|#8b!`wGMo+5;6j)Q z*Fq260awGb&L+T1f!xEST zPr?is@f-p$9xjF>pbw6Rr7#yNjcm$#7!Tv0$8p#XWVAK`la0zV#Hil_18D_&2m zUG1vDVp{9oZL-Pyzt7%H-@oepeDr&s-*e7$&iS2lo|#>}?!fIf6UP|6SOX?`j5+SG z%J>}y$O1c@XK2V?Vw@+LW|sv<7WKn1u5yyyA?JTyA^IQ~MpTOP&AlyQK6|4VYz`1x~Zfc{W(%23rir zbhKpc8D)wi%reb+9$}qJY_rACW!n9<0W;5ZQDOLRG+=^@oZ%`P?6U9OGIY5NFv)Rd zIKvW;vdTr)d6I30YC3$d3^K|jlbmIabr#DCqwmon4|9VH3=c~YM>+If9ddzXuCT@~ zTby{Gjvk_8Cb-2c4==0FX*RgR4#V%4`YXiW@BAkemIbm5|E)|g%{ud3Wtm;p8NE^} znPmC{jvMo=vdkt|*CD3Ar9ftnSjINS8MmftQk21qW z<{A2X9W%xzlkBj-$khhKIG31Y-v{->!Q-BPjaPqBA+E5?G-v+7=HtYN?FB{~GQdrC zS^tOujoAGk^*|nHjxCnhW|dnX*Ac^?FhL#0x#RjUW7irO(<~lWC@8FRk+DzekST63 z%N@=#@=$w%3HCLmk}=M6oORB#%>{OOg3*V`EJwM^6h}WLgAa55w?D08fr-x;F-zRx z0%N0Rh1Qtj4)Yv2VTRmglZnqtIj0$VxHV;*>r8Wp1%^LoGjfa#rr3ITQ7RO61dcQI z2s31geV^AM6RdKIP0p~*GDDBlj&ZIs$)QzC!f}>3%Npm|!r&qJcijS~9^5(`>N7#Fu206KpcgH}h8$*wDVBKjtJa#wxXNvIxyx|Eo@rTY=9pradB(q{9|OuVq@N>SbN=HB zOF`hV2J&?cdH5STWR4{sWsQAnGQo*|G6N4h!X|6%aFsjmcNn?OguZD4jJGWbCs^h> z8=U^QQ2Qcyz58xPgm|^U&O~(}L%(KNR zJFIh;tIYq@zr^*y#Tw#hWW{V2>pBXvJZ16ZYxWVw#e8_ZdO2(Pt6idvr$|{>| zu)}pmp6-qJANB^vnPrvp+-8Hb|LOd96^<&zQZm5==YOsNTP$$w7cvvvKV@bt@0eL| zpW$c7)PHHuH0QZ-mrSs^YY91Zk4^VXFP@$~z>UzIy)<`1cNTj&h4@)__DamL$`b30 z9JsUB<`IUT{1O^)B^&R&PB_r0?hnJ|$17VqrE z6-L5F#1wPPvczMoF?7zIy%rZ4HuEMEX12~O`_8?yx8wd8W6$=YVS-1QW{Ww7`wfgE zZ18YVp`|d*4(Awpj!c|qU|e9DEf%=TMJ5m3*;{3ST`n{FT$y2#p@^kxE|vk7 znPZn_jt$8GXD&4`cCJzXh0g!+F%4em0nD(&68jz{1B|i7!`xw=v0qo8DQ+;!Z5DX= z(FVw)TxE@2t}y%}pCONtaZWN*RLCooc$78P*kULl6B#3Cobl^4-~#7a=OTBw%GJji zAh#HKu}wT~Vw`1$D=hKo<7J$67FQKE6}n76!OUKwBGc@$z~&Qm#KEMFm|&L^3|}wR z9A)=OI%4?A_5`C(F(D?{ zPO`}y+pIJ6a?fF$iD#QB)6DT0%WQCm#kuFGc$0JcT&d&|OI&4*nY2`LjyqgtY}(o} z#o_0f2|KJZ`FsQ7advo;p;y>rFVGJolP1Jv=3e3auPT%Ux-XPE#($kgmSl@l+z>A? z{7N(6C{HlMO_tdAA_L|)TbyBsON`uX#*8zZkr7U?aC6bj6v_h2Y_P=*b{Wn&uP@di zN15RSOU$vx6Krvv9rnFMhqrjgGr=^oEOVYM*165qqC)t39dd{}oM!A+9Znf3Ct2VO z%iLg-eJ{1j7a024gIESsF? z7VC^nOC3|}vcT}Gyg50_HDOTgN!FO-Cd-_gH2{vkMmwHlpDpw1ahYk3 z{9hUPZRdYlp(fCJlLrSCk7^)=8OC{nB@b+~%J?746jN-o#_;PLw?8pst}xAQ78w0g zr-p~w;2bx&$Z+xXQl=1NU)knkoOvE*m1VASlU)w{nI)O?ie`$N%ro@o>T{A!&auPe zjJ&}FnBa-G$Pg!wIsava8HF0>*yP4vXvl%L%Ea$U6{9@NB&V2RnI+a)V}~tfE0%_d zstn5T6w^G(0@qpQR@M2hDGdFkh8%di4ohA@jB<>lEHJ|*=Go*t+g#-Ig7!Sh4i_2v zeeZlm+2$w{@9-S1v&6yMZMvGm$n9p%DR#KT$R9Z0OfYhXUCc4gb9vEPa+@2R{VQwv zM(y6IK3AD$hXqF8WuT0+!2&l}Eh_9Nv>895qa_WQVu4dEGtU~2vB|Z+wig)v8#DYv z^_XOy87{NLZPplmw{{$2n<<9=kMmzrh$}RiX0)bbj&qSGxXR3XbjZkib@)e)DU+Ok zpUuSaWdjYa+2Ara*k*WMCK+S+{W8Qfv-8gXafNw-4c58%w?@bvb~*e35BR^T{QM#{N!yCK-B@C18m|e{bfDebC@5by6o;FZhM8v3+9(tRnp|Ut@lP4) zF(YT3Q%rK?(>i44Gdkqpsty_cqIRq?@)tU0oNG*TojGo^#KA9_C`XG5Erp{e&G4;K z$|$#)B?7a|2tDa*i^yEmI8tLZ&!<;I3Z$ z9bRbByLyq^J&!q-Vt4hbtPbDRYu@hsuU~anuOl#hwTgF`F%vw&EC)vJ>XkY2Pz{)2 zhb2Z9#UG|VPcX|37C1P1m%k4vLu_!88_aQs#~3UAl^H3dxWznU4>v*{VUrzpIPnM_ zzSA*df@@53?2$U;ILlmQgEh7o8q*=i7<-p`Ofb)4R-vF!;7R(&vqEcZu>L3`W`jFC z@@NlOvRM;4W{U+5K2|$sxXJ}~xxwgPJ8swA)k`wR9G6*U_qw}+zyD`skJAxj<7W6b z&M6x<-{|ATImxumHp?8#EOVJnYu#j_d7K+O@#|)K+~(vc3okNLF0sTDtg_8IhcX5n#2NaKc8qfC#Rkg0mzXF=S?0-? z1m|BNd%X@>;tm%X`v>QHN<*%(z|cz#l*hQrnFny3k&ie9Oz;06&ZV_338O9 zTw<1MEU-9uvyK%exyo5~InVIN9XrOj!4xNR8uAFsJi!M0ZZTkvF#HLb;V9>sVwG90 zaGo93KjHlED69$$-Kt}z82zN<$RuZ(;UY^s&MJ4=Wb8IG<^&^69W%itX1U6Fc35X* z#**+bL!T--E(-BaIgd>91PknNk)hu(Lq^%+C_BtD@@c1nah926jTyFCV*EGlAx^N# z8FpA^r1%-=*`j&PMpZtxhxCuD*#ZZXABUVDyko>|seVw=kheb!Pk z&d_f;|7nF`g#r^SGsgx`aDzJxf6h!_ZH7F`3_C1w__xiFOWa_CJM5b^z|UJ+COFPC zr&!?eS?9l|uqM#rHg`DkI~uN9BPN((nhh4%W|`sN)iKA|WS(s#s_FCsZrLZ87%)UP}5sq+!6AXXF`JYpWDJ(I?6=u24c@F%!0dSOUrWyLG3^2-L9A%3cZn4Dh zTPzKy+2R~KT%`XIztHqC?OM+NQH6{^izV)`#-YE^kfZFdz{uC^iMN^|%gk|+B{o=P zi**iF%#>r?3F3@>-Ft&6#;Y>@b>}~&FfTB}MXqp_>+G`2@Haf@FO8VT-e$mDW}Yi= zH(<8eVsycPIl|DIj4{qRrdeZwt6VH9Y$!B1@D3wpj5|y-_K(gn6P#z3@!PE_6RdHH zt>8X)SYzy;e5NqP>>UQmc~-f?Cf8Z)D1;WJ_M19pf*Gb+XO8PEGxApk%3-!x;tp3B zYdhcXlo?Jj&kn21yi147vdtX3%)iU|5C5~23XF1rDK0U~Wfr*h*HXpM-&h(Ba);aR z*73J=^givl@O~Y$%PPk{pkvOk!!je^_M8vdL!9|=Q3nb~K5T}pv&L06xy?2Q8b-`v zhS$xIqnu@m^B?sb?ylH;-29}aG{C;5_Q5s7-|?%yPJ;AJ$lBv8m8iNPSHQ z8&bp+SGdU8uS+?%*=2Oix&NMH`Hxb_%s&|bLv8guXNXz#Mp@ty=G?Ec#4WZM{$~UI zp7TGf5c^keJf@gqmP?%HI_unJny3R!`{bschqi$MjpnEj4({Cz2AoOPzzW`Vn0Wb(T*z!JMW$>_hE07tpa6bJrA zf6TC4RG3kyvCdX-V?%0~XXFPS_&p6d^sn{`53|Z?)_H`hTw<5240p`@-*n6rGpw@2 zCTm=0v86DyDK#8r=!ceqah8~7l{ubZnO!y*`n~}(&K<5Y{v!`&l3UC$^6xt4IBT3@ zi?jdk{C5e4cDc;xmQ*vzc*j6_gk@G)V}ngbe`und zV&o?#_`{+O6|!3z@+iw(VvQ?ovc)z#>~fdkpV~7&v3WVd1e44$%M#11a)ov7aFxS9 z^?u-NQ6c;@Yr+y2x+-$!KXk}hb~(pz*UT7WjVacdWrGDaS?0!nS|To;GGm@(>;)t4a@2rgq1|347#MTzS6OD44Gx^O z+uPtY!#|g5jqHT*A|j!Dik z&ox#V8PJXs>@dsFod&`vTO8#Uiy4KnU)$}?^BC(v1-3bGo`!c>YeqTCQI?tF@S)va zfeDs*f=#yB=5)kT>{<%O*mu4q;Bj&(` zX38`dd5o*9v&+$o)ejvA9bt;A%(FA3K1Uv;K2z)l_b*ZZtOKE;;-wlWWSQp@tBhTy z0cY7|gV6&ALea~uIVYLpGRy3+!LbKB1zct1>;s|5@NO@`CFa;=nMWQX(=0X>x(d-N zbkOI)Omdkyc39>3l^XB}I}F8ja32F_f(y)Ylk+TGWk9U4#lfrXrGp1TiyY+!GY1b8 zL%Rwkf!H;U3&+{w3_F}-=)MNRQO=I&h{rk47VF$*n~`hP4>(JJ*1iV*3&5bDLGhA1QOp zvco1L{Rcw3OcWKS#>|LS&U1xzw%O(`Lj#uRQD($(rkP=Zb1ZZIF*@QB+gyFDcE4tm zU8f!MO!EkHTw<}Ta9p9r6Kpd2I3wi&&q^9-M!Lfya9QGi-70iBiiJV-cx*lGO6>lcko^ta6!6?ywWwe~Q$e?>UTf zhDpvb!!q++EO3DYjW-=>C?F zQHGyp0GwowIhHuj8aIjxZH2_sZN5PjIm#SUoM)a*R=L9_qbW0Hp3w(bYo^#?p2=sJ z7^`e?nH`>FEn(ELV~PXMF+k3+8g>3R6`BI2w2p#`&(qO`2ESc~2r&;3+o1A5vRfZm96Ea#)^7b~_WCVV1`@&y%ck=@m9JM_y^5ms$$OIL-tQvzS)MDHNDznFZEZVw0(yj=9Z9 z%&Ynq58wo|%yXW{SZ9lE?l5$j`nSp`GfeX+3vAx%{4XkO2s9YE%^Gr?9Tph6+)Nnd zHj_-wNHqt4Lx#A^Ci{L<#~ffcxX~Y_Y(|tahAb^dXk!cXhy_*H}UhbDkqyGjt1N}KBU)aMBn*k+kCC7EIP57g&jM&s(eQ6^bT9+66gMV47( zjdeD;#tzpRy2>VGlqdek1GxGo?YYHOnHYMrj+kIse3A|3xxqz-uQouAUhVwvC}afU zN2QG8oaa&2xyClP8M;O)|5%1N#Uzh0#}h2G!v_2QM2CzqJmQ#hl*gE2=1*m6r09l1 zSzw6`HrV1xb~sqJG}oFrlN|Un9deXq=GkDK8(d@fp*Gu}J0(mr%^Y(qvBZVQ z3KI$)&M@+DA398Mm1(Xs$IxGzF^Ab;nj4&B_z_;&9OVgSxXlv#-ljv2u*s9`2JyE$ z|ItVKG<&;-j5Ea)^PFLoRW{jRhZ~HHS(*g{WrA6*u*?=~?6SqdcQ|ECGWICPl_|E~ z;r!A$mA0{>pe<1)p>xbwfJkQG?|kOs{Eg9cn%$!%s>Th$SF zzhKE2`J#5rvCGCu9X*v_wq#uTip+7DWwyTJ{5KTZ0xibBYJ{9&>}g&QU)PWW%<%-P zjQo?1m}sld%(pGk(`DkjmWTrBS9NEy2 z6O25=QZd0gvuv}#F3TMFo(`F1hc!l?DU(ca;9pIMV=ORJR46OVvBu=T+4amZ^ei)A zoF|#)@TP{G;v$c5l{I#G`1_V>LI#=SQD(Tx61Q1n?B7k0#W97BLY9$dYrq7X%yNVC zjQzkGbBwDjvC9=kpJQ`%bjT8OJp4lw;{qF8G zLm+qB2ziv@=Q}1G&F;fzzlQ4SusyO-hE zfxG?uudpCc=Q3B>Vwc;DzSxY;){s-oaE^H%XO*k0bDgW)WtU@p+P}mxW0Et>aDgSR z^cBriVdy@0_gc(xhx3eGZ}&6J(80TV1;)6@1RI=Si*t-j*`#3|ahy3GjTj&|*koqN zz*uJVr6yE-$lbk^!uXYD#5s06u*!MY$64nl+qC$-&<#?^D5sfZjX7?x#PC%n#u2tS z!5z*pcB2e1!Qx4UtU{Ob9JpGC%(2Z9yIf#2YY%XgJIwIJHQKSmMNW@c0?u=Tb%tN& zP03O2GQ)vuP55Qb|FFWmz&IB<&lcCX!ww@aHn-ZxB>IX zBMkT^1Lr8$nBg|_9DJmuxvA(lDbxif*k+#ozlTE$jI+TscbH>jOo}%MIex1i)rpW+2-QhVHpVSbCtX7GW%2+_zlO6 zNv5A>z|643EUV11&ZBJe7`t3x_&0s;C@RDhl24aH&M?ms=Q)}(b1rj($GO85MqVYg zjI+ZuyUcNiC5E11AUwteuBYEdP@=P;V7-N=s&NKEb9dm&jT;dLw8Tl;(VVrHI zxxpMeEV0Wfk51^A$JyaJBd@k}&(`m&o&OPqtia%NtTk(Fu+A16?6AquZyPz|++vd3 z%y5@^u02<(IsZHaemSSxy<^k^WRoz3v98=+zYMk?>NUyvc(MB%yXAj z_WimCaDb~knbDr{muUaHHXW-5l4YHBCdIqVaqxN*E(R498Z2{zD-6HJuAVY-CYa(B z^ITw+b=JATHius-Lj|v3#yN02T&B3q5_ef;-%SR}0j_eCT_$dF{==^~GJzOVOmLf7#$Rcz zIL$h1Y;%>NIoCJqn9-b$8DpMt&U2KDoa8E}xWQ@ea3<&cN8aE?F{5MVU!`Ln=RCWt zb2G1F4*!;pf6ptMaSpy(iaE;y=UCvbUb#~Zb$ex>;)t;rILRw*wIks5hE~`xZ zjsb9*t31vwL%(Y?l?>!HX3X)|s?Wo$bAqd!is6htc2H@DF6-kEEKRKb9dLW}S^c)e%o}hvBmOZ?sfzbs7v{lQGvjOfX%M z={Gw6GYSoXd2Vot;UfmXQSLCq(W=Za#~RCQvCbWCF!F~w{!1M&#x#>GFwaFE<0@<1 z_(Q4OR0#hcGkTj2Im8SLEV0ZgkFy@c->xCY7j*bXmWBz|m}QIe+-9BOcj%C5b~$vr zOw5}IQ$>Y>LY8F~SYw&nY;xcZn=gnn^nYcBarQ0R0~}_CDdt&al?^s|l5Ix*O8Ym- z#5=X;Jc~(%>brEz<6Pu68w@W=F-N$=3}bJ$yP4t=^IYLPTU=!5ug#bdZZN^{QEyNt z*kPIjf8+cY6cT@InN9inPr1Hw%GSR8R7_IWv7TKt}xFHHo3N} zKepemzdsW%DvT<0m|~Y%4*snUImAT{v%wL@|J*D315(I(-O{nmMb7@c407~CI^ya- z=;$pz+?ZtO!}bctSv8PiMxo`wGwiU$kcKB&QnAAt`x@$Tj62LQc1$}aSYwtg&a=xp zV;?afrr2ec;lI!iNB_e4uPbB()>vYfH4c1Khs<$@B}U$APcY5~lMH>#p5RGVSzgg$ zaGzc7GFp+rkE_oVb3Dd!#ra=Ss0pmF$u+ha`-G8J&6qJ3m}2{r)|6e&GxRC#7-O3W zcDcsrU%LNk9dnc!PBPCWR*MQJ6q?*%hq2FCg170IQD&Ir5$0HDnHy}d%NC<2WQq;O z-)^8xv&$U&J}biyR@nv&0$~*$nP~Q9Gu-6ny``-LC$!k#dYVjBXjAUrQ1KgNoma{ByiDhoE#?fE9$3NLy3N@Z&i_K?f@P6;^ zXBrTj6EeclXX}8e=a>Oo&ou*<(+2VZo9lTV9Qb?>=E=!>dUa0xx`70~$n$0J2zOXx zF(!3Qg#_D7b18FAFUJ#%{H-|SjKA1@rdZ$t7g=Y6iI*4h>xypHN zvChbi`eXIRqEsj>3q(F>momZh%QR$;1#Z9G3^{m{6mpb1oPDJZk4x#zQqN_UxXvmE zat0X0+2snuAM%}(quebjq!dPOacr1nmB-lR;H^613S9u*{RhHnxQvGTjard_kkbSe-G0rNBqY8C}9NQfJ9Ss{Yz&JBZGW8k_gE;4d>wbZH;S~K%jBjij) zN365W=3g4%$9$~5O$ThV!0`ng@Gu+9af5m8aNu?WTd}#{X%lmqxfSO>|1QT$puieW zE?Hwn->svMyMCV(a&}n?ImbNne{XS&9j+-B^PQhi*9+-8B%4;d({AJ$J% zA@)%nHO-Kt?6U2FJM6OhF%SNPS1OZiF~be!xx;xzS3H<$u5y-L9%WcR>5psY`FZBK z$zoMu^b=;lNp`r%(5E!`q&>g_(=3151G)AYGyAl9CoBO^Fwfd&WrXW&GWt2sW8w?y zf5vlI2%f_->tAsGYYM9ZO>VKxzAt*P22~cg$wh|0WM-V?2K!E$*$JnIqdfdoOUPxm zxy8_Do%fcBaE=*Pzee|4Un@GV3flr@HwM4%0gQgb131ml=j>j_xyd9W-?VucZfnOp zo2;|LHAX&f3BF|_++cy5-}Zctu3LLf78Q0B>Wr*P-M=^mY;Sl0G5tMj%PJRnoU0uD zH%q}9qhHVgN7=V&W?W?{h_lMj_njh+{Xph|`yHA4qVwNUh$(C{#a(7O_CpQE>WQ;kcn7B``S74fD zW)JrKN=G4d-(GKrV~l-G1E#pdJcq-*UX7#Y^m=X1G4yrEkMY1?>-Ew+aYzS@M0)-r zqc~R?KELNLGP=+3H)QIfUN6CwOM1OxUSUU}%EYC;UXxSoFdXakB5U4YmutWorkQz& znX|}l9>|0*dj5GE;dx%M9 zxXnCgo-gC978U9WO|Ei-8{FXzw_acd-?pZcX39FVTxEgFFEkLIWRpu71L4q%4P-s| zs%9X}Gsy;XY_Y^*_j(UdNW9d{IeCN4^&KN*lvO6V#XOJPDAiocS_%e#hW7ri{~Gvp z>51ou&YHWVf8pa-_noicU zePI73uN=DYRBs??dicD^?fMVKwdOzh=&9bZAf6g{P~`Rl?>IBGGh^Bo?z%r01gG}z zzvbYu@L!z!)`7}-3lZU9>_a*{{Ge0*vPR`^AJBi%^+D{g*z_f*dJ_y~{zu!rmS@H= zxV%4Fx&4Cv z^UmE8oPFh~-pE;%OP<(&`Tc{6vxb$w`BZPnxWm^>RepRy|7GV+2u|H5(c!%(?p0h9 ztNr#Vf1^dki>E5jimJFQ*!Z1Oz0FYNlA-=f@8fdzcPnp;_FsNz(gR0dbE+4NB>XSe zSH2X~9}!%6?Wx}SUj0kX2`c4ZcdEBhc}KMW(nD)5Yb%!}l?;H=Od9Lsa_Q!UaOqyMfWotFzi2r2Tkujr+Zt<;ZIIg z-mKx}n<_7>ytjLUn*Icpcg3dZ{g)gZ*0@lq{747q9#&4@_jE6MR^_J` z^*`|7wClM_#4UDcD%7Tr^~p%qh3tb*i^>u=1Q} z|0U-xxn6wlsov~;f|a}E+>@@iK5(ixeRky&t`Bazj(@Q7QEd;+%68{NdJG=^f$J+j z9@1lQBIZ8q0l_e?+#kjX!N$GAFt*1%$S{@!%O9@X`XGr2Dzw9={q3P(XI*jbw(Db_ zGIJ&|=MH-1Y&4vf{X~tqKK#+jo!TCpR9^mQ<)TXrX)Sm)t=Ns)hu?T+oev%lDxavl zPK9&Um76C{^|mX|erSL6ymP%!&f8DV>upBc;=H4R^N03>Z>e1Op#H1Roe>-U?5SQM zRQc|M`Y%Yi+;-V9NqoE7{vwW9qu=b$bOI4 zRDN`E|J8@)#PX_adP4XqwsfrjLH#4Er+VQa+b_7ja&fHx!t+n6HSh(?7u34xdT)_8 zT+)AWr9RZ}FY39s=H6Ox@3!FH-G+Ytunk)J;;CLM2*3W`@SzFe_?J%gNHoBfsvd)HRVay|K<`yXyEIP(fQcSUgR z=cjt3XICD2QU3+!xZFHtQU@wOjrBk9(BvWW`7a-o!Q1T3Ci!5!9}(QScPHK<7`&iX z1QYk}iw{p#zWs>)tIreLz4Oe6Vfd?4mD`5E3{sMELWSA6;PsO^OX) zu)nG9`_eN{JSsRH-49;+(#rcD(tmCL(uMnh$L!bIRcrI2{or$7TDkZNwT6fG12>7VRp7o&pV6pP1tNO1wPiX0q{ZM89Y3qWUm+l8Y@Y20^(77vu!KC8o!@oaru7DJ6>A3{!0B$KKOKRK1kJvHNC?5Tvlu8A^WvHQ~BbR{SQ5`c}3-; zSM@*QyrKJhY<&OT&nwr(-J8Cua`n~yk2rMHy``)7?>+d2%KPHJcWho$dE3?f53O`B z(f@AH`r7>(FSwy{@m2bte&~MSwj0jmaK;Dl(!=(HZ@i)M=AhQ*=zies`?c298h*rn z@Pjv0?%I3SBliPeI#cVsi3fPr*naTeDz_R+|K_9iukYG_)QU>OkJ%62|HjI#023X1pw@vvJ+&UhvU$@1LN&AigC& zS$V^?-XO_~`}@wF5sN0aa%%i^Z!kD=-!R+YxGxEop0?k~_4|`JBDkw&yz zI2hFFdwk{A5ucMMl*b-_+W%zc-YaC>hxLrhy>5eKJ-q+ID+dHm2#(!5V+P}$6W<6b z2Lt%|y#o;3xpx3k8@zAsw=TH$gwws?>st&zH6QFX~Fu_Pxp=n&v;C>@@>H@#|6tz`qlI;i!X@p&EtvL%9qCa zFFH?bRqSZcnFs8B#P13&rS`jeL3ZzW9U8mH>sZYrLCxFr@5{iseS$mBIPC+Wa>*tA zmmE6cdg+;`d)vY3`apJXqK8%l7oWYKk{`dU^2mo7`Ig}N4X1n4!Q-xc`I*NBH5Z<9 zx|cqy^3V$$;j9mxL*p0A^mDz5f;pc3@-su67F^YQFB_M>{LE%u5X`4f`y0ndHjMt4c<-O!$>W!tN!Q*mJ~+L< z1cIU8+Rx!vb?1xV`3r(!iEX$S{=vQTIRAujRd_uJpZ@Rgmhi;O_mg}7SKPbR2QT%# zQ+PDkMg6bX`$^&a!-7@aota2b*Y}c3uNo2_nLgc{@Z|sPd(*i48TY3vKY3jL1y@eF zTyS|fsJ{OvIKn5zSH-vcbousIoLQ^Bm_^a$whG}(UwQ9ZjR;TOa(eHpTKIAQ9i9{( zx^;gtFS<8;-kk7=a5s3!b1N@NcuOsbt$VOv)!8nutX%vkUtW(0uH0IA=A%^DRi2pD zDAW-8Y`+E?D7LVl+5lAwHCd3C1pI^`FyDbE$Gg^uq1GpMj7 zeoQ>r9{2vS-$PTEJM7{$f~L{ z?!S$Xx*quB)4k2JwRz3Wd%r>0`ljm#aVdn;$}{cLpgw(HGz?!T0N9(4Tw{scR0 z#r?i_o!5Bd<4jsP2u3OTtn&D3x%yqt6&IwNc&FNk>2>xKNx2uZB1+!(J_d)RD z+%G*j*hWF4rP{A3HpP%j>S0{YiFSiS}(ZH2P<$g9;{5SsceMt$eX}|lH(+7Hm zz1PIUCe@!fcDmOLo>%m&Y5smKs6AXGvy!F4t zgNLmCk9aWHqvCy)d%tR&v+Q!f<>KCEx$30Lqb{RC7ysjTQ9&k_zk2_u`V}d8Y7<^$<_qn%J`k!RMRs;)Q+7G_wmNTokDL8!6Vg)Dn zj$8JUaPWlSu~y|xPwKz?VOz@EUqACE3#I@2_m_T0IVvb&+ux{M_vHSI?zg2JTT?k0*Q3>LS(UE@zp0vbo&KitZhr>f#5Y|h z+WVjXKM(fL-j}_BhuMn%9Q+Jp6o+m(^F47)a9uDF3~g_F1V5Xc(4i4T;{%Q-oW;-kGn+v*JrXJl&g9C;W|DD?ff( z|D!J25D3;d^rZ7*!LM?Hj>dxPA62eKQ=qsqc>JcsW-Er%IO6v0iLzULk`@;uvKdOAo6ArBXsB+OW`Y%5?Y&fwWSFTQZ z>fDb{S00!4E9zOn){iT%6Fh6T^4O>MKlr}E&yU;gf9XB_m)}Qu>&KOkYJZ>Lmq8Pi zvr_#JJ{bI#ySi1mHF#|BBS82kLHUXUg`ZU3G@i!ofb@8y0_B zIro`53spYy47VqRvOlZ5MCicEo|hk75{q^#?+s$J-OAgZrI&57xo+joAQt`4%H_}E z%+D*&3|#m{<<)_mUj%ipIMDq?<=W_E*AUVd=wK8~aEgcx5QnA;6Te8qv* zo|hk7QzvnEb1S8Q^ zF+n8>YKmA<*ES|-&}?gr+)8xyi4iU8S|gz?wzQ@RZBf^nM*23bd+*JS>6Ny$jY!+5 zSP9bR{XH|Yy1Q)ogE{j%&w0*szCY&7Y~D&jb2TlghxPqa8epd2=6Y7JUf|w;vVPa1 zd}_VCwvwk%RsUijr)n8n*UN_hmp5zFD(nsG?ZU3OoWhP~N#*6lP&-NP&})9S?9yvX zwsiJl?;twLJ|{!ULZ6ea2CP>h5Y(SG#1NiuJoxWnq>v zne3P%lUHGUaLTBxsU($t;J_4FtH&ZsqOx$u-6-2m0f9mKzCs%*#K8Js%GQl8BC`wg=H3g^tcuAI@6 z+6rhqIhWc2h6&J@BOegJVVov;S8^RWO)k=F?=)%9YlmAN(QE(dvQMvlpO-&e$-b6% z#^^~GHNbe3oi#tXJ+EN&q&ZXAc)jECtDSDC^EV;19)eX?6JVZg=W^`S-qypl4xVdsO|bHEo0~l{>AIME%?Ll&+5%a9mD-Qq zyNDwU>n)H@SVmvLsBB)2F(bg?0vS`m0rOgz6M;ozR&T6zNZs#9Ov~*~V^-r-CUkfu z$EVx9BL%YkYG?7{5&YE#&F4!{rLqzH(H{6&8TuPjxDGG!@CgS6~rXu15~S@=84uYl*=QZG}fBUrU%qkBrqi3zzy~8<0&- zX(K!UPflqN-sF+(sw0Gs$DM_6M{OBU2O6WdnE5E(&fdSi@pNXYEAjF zop#+pE|@FZpC^w4xECU$QLBvBZgsc9OOv?fTNplXu5{L73p&OgWONx(9kQy%Ia{i) zr3UA-y_+hm7f#q^*HNp8Q_j1D+84CocA%pUqsZ*6C@eVF%%QAt+|6@k=*P~INu})D zhGPN!+_cY?)z{M=LRgyIZbSGhk58GVpbOqcxZi2*z}IyqogYdy5t~Rx+@t2OCtfyTfU-4A-(~~Zo zGShMO|NYLMTcpX)Z*YFDq`Y#}oa-4yS32SZzaEn_t2WBUDhS zc9IJ;$*NQLntSKU!H=jY9=3nm2*bjm#?UgL+>ybwq<}NiaPzHm{PcYn^k8 zn#uCy;iO!3C|AK-R>_-ddB_<$YxHEf0k~w9e7KfpD?8^?SlY=Iu9CCYIp;c>7RVLr z$b@YRWfNCt#iG%Z2Q)-awd_H_dH9^slLOdmbXUvUfV^!>6YG>F#?9EXZK>p~N7L@5 za*fHb#Vzuf0?{Rj&F{*}hR9fx~>r=IFTgtRr2&@^5#w0 z(Y|cdoN*i5FO!U$iPl{%B{w@4xDKzf$M7pJ`*aNFK^k-DetgVv{0o=KLj=h?21u>| zkpe2!Dyh7~S(J(M_$qTC$_e2fjA?$dDo%4RJ{qT~`Ri3WLzwFrv4WY~qQ_Rrt_{q$ zjv}-$jU;@s!XecS49Ei;81e>J$q?R-!*)!%d#aY2q7TH08d)asjLx{!O zuk}NBMAgvv`G?l69{9+rQQ2SVD$K%t9Jkp+8bzF$SS6FUIE!ZD9I&I-dRA#SG9P@D zJZZqpv@5J(CIlm&cEK`K@8)H$IkR-yU{sUni`y*Ob^?FBl7;u z&Z3q=akIU^1)Sh;Phb>{<@EnK<&yERqKoolC#5L z+ivhmnfz6zO{4NkgN}Y*Mfs@w{wuh<>*(N`kvT4l8l2OzLO8Sivg?~nuW%ZEO1Fyf zZ_vDvAyqSOiF&9SZoib=2FjP;-$LkmP_ADZK%RO2L}RpqX%G**O!NQZFFB;?HjZlb z-{y3AN>hk8BCcvo@sqyK#IrN=*<)L1Me4;_>X&6r6j25CY7IIw2;?RqJJbRVR}RnB zKHy59>}jI?dag>Gy;0_Ax(T@ODj7m+dYL?PD+S?YKd#ht<{ZVhfKX=9K7a9N6XWc3 zpS*u7S<#Mg#Z~5dTUCl8-*AJRr-KGmz zp;~cnutN3Vti4M1X{fdop+@j;liM4qNlpGK#?*H1cO$3IQH+l&>QSjW}Y(ndGh zEH_J$tF6g%1lE4_#O~)PycuM$zxNfG^ z)=0x$oR{dSkzIFDOL}WY<;fLVtMQD~=%T1NeLz+PsPwvlHc%tWzDA12(U+W00sP11 znE)y7yNtHe&i$yIAm~&dPUBkJriac~o8~MX0q$I#IJ?z0>Y~ASz?0jn?x3}=)-Fy> zTKhF^RiJ^@(g4a>zQ#7a2UxvE_5mF=YjnL>ILlxMDzIksWCi-Q-(6{ET0XpejW)}| zSw7rd$Rx*G3*WuQS}g@FdFBDdt~O--s59OucSz2)G*{Q#uIwBY@4;(>dOe5Nq5pKb zAHSP^ab%55z8j;)*U0uCGMn-*MnX>gItgjSnO18p;6u1wwXzFQr>oYkF>jnFZ{AG{ zFl6mU%EG;byseeIP0r$?((4k-f{Mmhb7+uov$kDwp4PTGnLz@1xdad(? zE2Frpu20mVc`$7A`20|};bks?d_30*m=E_|FWZM0UVOOgub0Zr&IMU%H&F0ta{VUf z=f(9KXHHfa&(IChxtYA+YA!iPU~M$s$!g1&QgC&n^3V*X zZ}r?9u9Jp)s9Cw|?5@5Cn7dB)0Ui14EW?d+O~yL3I4^%);} z+C#vF>tq+OvVuVIrl>oLe|ZW%3@?KxH$8)KplqGaFpBdQCWSMNz`qnD@OM<%hKFFw zu>rQFjxZ{xxg6V$h~nRvq)TlZhHps0jW1H|h-r5xN{0D*apJ6?y6tvq3E>$6vXg4=}D-ByR@k;O5Co_dBO$ z8s}4@rgK)lI&Vx2uIjxeHy69JYH=5&kO`PvHhqIJBiB?ny9bnuXaOp;uwt7k{gw)A z%06NW$r#}ro*S(lFy93%8*Y@!Z^8y{Gx&xO*h;-k&ka9Dqjz8YmkNq=^w+$KDnRSM-OnI zLG}UjjweN~fkyBjZ_v%FVu$M%D>r->Ge5sYDz`g}&&$0f(J(bKh`&3DYc0%&=fGQV z8-F}o_H1Y4q7D$>YE`fvLFHz3ec^1au5(tpeRwn`3Tteo|AzZga1ZjeCbuec5O-~o zPL*jlxhb@YqwyZKd3-i2AAwh;kavA)BG<%*ZTTwP#sekVYcG5%>*-9h*EUwl zC-*x~&GHj?14oit$?}aT*NC)^#P%RV_y>}>DldgM!CP<}86~p6l`QW|vQ7m92r4(T z{Ef4$Ecbkwsp+i~v%LJ@aDNK!L3yLett=1W?oHCEGF>J&WiE^2?n#o-6c5`xIm?Yp z2%kbeU%C8dyK`Dj4?$JL%;gv6Ii&V2XThv`1P(ysvr~;}hDUDI33%bGFz$gAGQIGl zx9Yl^y=&Yfx607BSaX)%mY88)^r;TzIq4L`{xcoYHSC)LF>d%S*^Y<9_?phC*^x)M;A?V3S^3@i*kqOzgjkeR+$|*`R)9zEmeqRQ zyGgc(5aMb*f4Ph*x+&2rjeQs%-ef<2S;^prOmgx{;mDZtDL?M+O|tqibi>T~R2bH? zNjjC`XT~>ThM5?j>vB3kJ3cS&jui1#Su(0;X#jT{G8NdWeUh&D)V@~u-V|ZOaBL}g zl3@~OHzHaQjhhP`(tQW(Rz18d&rqEmk@84t&QaK~2J`hv= z+H70(z#NycwA~b&IMDXM52sMu508=|476DzxQ}6)kdcF%%!fxSeXAJPHYe6)&4Ai} z!vi)?F2q*2YqK2WVbi1@+@+hXEzV5b^EO+%iN+PmW%3im4>O-b`(fVAvRc`~&C<}V zy%ww-o08+`g_qfJ4C1aKj`wn1g_&1U#qBt}xNA1cvR&wdnQ;VRb(>|ovPQz|gUTq( z-7H6x&1<%&Kz{VdDq)6Hg|oWZ-gdFwPtr#;HYaA4*6|+v8=GYx{^@&V$Kx#2M?gKz zGN$N&ydPri;k%0RHGN&RI1iwxg}~Chm!{v+POT}pN4B?PPWe4naYYfUzQ^3=nKh2P z>Yl{fq;b2irjNQui?TSqL)PwePMhTibs(DD12>x7ngxY$x8EbX2B8C$IURDl(|=SbvaA2%2(4r^L`ZD7@76zmJ6R^Rnz>LGh{k< zJdJ%_masmxn-|5Mzs1`0*5v2|0xiQvxECJ4ZOG|tI31;Sb-nA%o|V6b!+}Xbv<7+M zZChm7vy}DjEwXQn1{j3(A)B1;cKF^c)+6r-?w&1HZ#;~9cM5rP+qTF-;+fu>Le#iUA3&O-r8rwi z=EFL@P`pJ}hY5Bl$vn-P5dQsg>eJ4mGkb9!ND|QuR}~R>2X5nsr&*0!Z zCg(fsU2n4lOK%{2i***jkGngC{zmxT7V|lNRtWcj7TNV3O8i)h)gcVR23usvX6B&= zZ=K1Oy@1?t!t%6hRuDF98>1CZw}I5KcKB$E)y+q6k7KxogXzxdO!r#)s{0bRqqR1a z!aZ`|Gt_#Y>0I<2U05y70;IPgp|RB2u>|04_sOQ+XzspGH>x;s0y}h{98|`YUbryR zy^iJ~i=IboDb8G3`vR@mkJEks#M;&fcinHbW)0~=rh|x$GfuI}GXiYBUk<)V;RNKB z?@;61>sg!JFL|BB8o1wzwI0@I#oCOs*Nk;`80X#;vG&5d@3)_}3|cn{4MeM#>gkG^ z^J|xyGdClDt374**OQ>FI(8Oi;>_7YJNIB)!B(q$M_~C|W$a~azfnWkdzC)( zMk>23SswcFAg+t<-?LS_s0EIit#T00j5R;BX&vkSUUEhBLf}w6YE<{fyqCh9I)P+&%vT( zAIzB>95rA3FmB6~hkoFkpBDlo7iK>J+JaW#5!~%T8B>LQLGzGMrmvA+NEW?F18&4Q zkU~WeeiZQ^lE6Xy3rJL~$TYeL{=+H49fcnY+H=!eRYoTFP;8?qWPSLL1f>#x$Ea;? z2xfdkcEOyv->^3-&d-oHdz|yr>*V(D(eb;!O1=Juoc1Ha@yUs0dfjb?DLlo%uQwKs z{-wuRGOHJ6d^0f(TIZv1*Ei(|;hnkoGvcKgpLdA!#~l6e0a_INBVEq>G3&b4Z%V_D zi7EI^^F&ov?``xW-?UCz4dM=)d_j7@%=sZbLU|K&6Oew#^2 zK=#4Xcgib2B3&b(jt8_uDbCpWfL$Scw^No6n9)ofMqt|mwq38Dl+AnTx(>%ABS;>4 zKo0IDmIJ8ad|8(J4wf(vXv-+d!g(krTh9$L4L?B^e?3r_)nf|CzMnW3tQ#ekTvD$^ z9@{$~$3GQ!-8$a_}nCbf()j)pJOF1^;^nOc^85b@M;r4yYdWx@Q z^`%o7h={Zcz8s#7JNDXc;V2&|d_^E6J(i5(DjZ6wR#$yLf@b2VAz zV~4-W;k7&TfG~{*cgGHC_&M>kTPA1qz}j}mKA0;QGw|Ngbn`6m<9*KTyxq`bt@(G8 z=R3@$!BU^;p19_(g?Fb28-RE1kWGE`6?^eFpYgx;vFz!isH>Dk0kF6lp`{Hkz*ttW1{gOAFlS4dn7R~@P&u+~R)NlnIv^xQA!Y&TP$ zp~NEz+J%+EYeUu(5kKy2A**)b42GTu*g67zH99wYp!kY-H$9M;E2ark5v2ja= z`7+0qo5}N#l)Q#nts$$24_IuI%`Ed_J2CqM&RpRPrHI-)Uv;*O-yGYs#u;+pNgmq8+hOeuVC$e!5vxgo&n z*D-Q1WOb2Y*iq8{I^lN0$FX(rS$0k|Fk|BE!2}IW%3)0DmC)bLHft) zH|VwePbTJ?_FAeV8y#Kggq!icY<`2$B=|TlJQTA;jG$@!@x&fPV>k*QmPHXt*SL?d zK7~j={II0|LU(9z9+LZBMY<7Z1nFFq#D*1B7*wtbXG=@J)5z-LzVC7Q!2#!jyr@hx zV8oP{u>;I1##8uv?^gq5*)Q>*w{v3n0RFimmcbaL(PzsY$A=>XcE7&TvoGH&`?x>Qu_`v?b}*%^aRaHipZ*-S&% zz!TQ0A&UFx6LRDr(UW(8|)>*lY11`HyIH+TvLAo#Y6-tkUn5bygZR6in`q~_&6DkP zKR}i~Cwc#m_zDQ8jX~{+y>{cr-}{`b#y_LuIl6;f4vvI@rD5p=dZN#Nx@%aVyW6Uu z9{;YeeJ&|uh;iUC&iT52%{kvgVafY7x^kbldy4vPtSq0G2B5?Lyj3rHVAapdJ{9z- zpq_9v9%Oib-aNm0CeCu=U1%E{JHHwsoFA?kWqkiwx^88d-)9;&71{@p9y%tQ4^gbk zzhj^3P;K9lgNGQ-n!aOCREmztCn{vTU~bZ8`nID|cKllB95~ZnFi&e$gmCA)kl2rD zF?7LQNnCSA)nvn4a2wbCC0)9cw-8#nG-a*Z2zsZc!obIocc%bhs&FJQwq1>u1b>8IE_||$JZ$3`EXwfd2b4? ziR?$e%2%n*j6bJqZH{}!`<67m<#gxOC23SELujnqt&hEUD`vMjde0t&9Y(eQ|M+$_ z4j&*z*68$~DkLRQ0uJxC#@qnx7y&EnfU&cAt?--|t%n&sxXWLhnEn0#h7a0Yvqg=G zP3gwrWiMKF-SaIP*o#u~UrgT?qPrAPW71%{^|+_$znCWDy$NpzL3DR^X@npu8ed&B zila79j&1~A`l5`XW64Is#rvz<`!F*eczj7}{#L;oU$nN6G6Q-eFa5?jZK@0B2IM=C zG2Z-xJo(?c^g>WGchVrfhqy7HoU~ECFIwA1UfhRXlx6=zqduU*+NguT124*UU|uxI zG_xXFfevaQRcaQWdxse)?=X21dC{7E)myAVS@cD1%!N5#SazqqmVIp?U0gqQ7UZa; z7uurMKL_paan8%ke}tur%%Q5CgRAY8#2TczR0XdmTm^0|%vc4fhqrc0!~bdzy2m=a zqW;yVSi@5o|LQ%`iNB+@OMa`@@$bqQ*UFvWPt<3Y#-oh+DR>q9SQ6JPs)x7qNy8Dc zD9~r;Ymcc!_5mI9exPq2&3gQ8s?xv@Wb)fEe~&EIYvYe(HP?09emt={g+h$0@P&4Q zwU<=`yWk!03Y*8CX-41&lJuy7M@?>x!Ny}$-IrzZQI7jHzdUhq5#V<}!)Qd-diU3jg;Uum`48sRsmJdjXqv|J;_d80zdw*gk zs+|9E)=>NPfF3(<_~+XRh%HV-_#aLYuFK@sL+dE+!ToXs9U1d_%{l2zDfmBUw#)db z{bIsxZ>L+Yn&`U*E31Uj2e0G~qTc2emJ#N7ttHwF_ag7Jjl0~gx*>SoPi5Etk;tZ> zn*HQCgRsUFy2ou^VC&Ecjp}yqq;ruAf5)CqsXBiui{C+AS)Z)dtFO;m=!NmC?vqYs z{yyu(-w3R!PsWr{!>zsBC#WEOQaJ$QYQ9Ahg0=O@E@gZB7nKXUhd(!>`IF zWv-tQzNT+Gvxdig{55I#qn2hQcGL`5ACY|u zJ7UmyipCR>$%8=m>$apHSpB-J2J#s3!aovG7!)y`llpOv+oG8x+?2@M+W`n58sjx|HO`9^Fb#0 zF2E~qNztE~Cmr~2sr)n3!NzwItDUw1+GKkeEhIOFtU3|6m<% zAHhBE4>Iazz->&5Q=L7l@i~@#f1Id32zUQc)wA33M^#-i z>nJRWY`l7PkH80zLDo5pf1^fo_OIpa_oyE825sQ{wX6X+>Idy+9;QhTO6PmTkozZV zuVw`1`;&~p(ktZlA$kh$^GvkN_@3y@pb5s{h=tWb~>y(s8-*Q(2dxI^#i`+h~4FEEPQ*o(XQU0L=wl7*;wemn?ke^<6E+X-WbYf=;z zes@&fzKQiRZe-1^DbH?`$KD72^yS!ccpo}=&OfW(bSIA5YF;z^@Vn-#yIEn}1Mf=b z--&b3);$6{MzSX4->) zK?>dv&rRZL_aHoHNQTgt=fb}Lrqw*QVD@xUXNRQZebPd_=711@&BF#*260)l#t1NX zNT0G6W#P=R`6Txq+7vf48eN4`@i2&lyht-1KERk-;ELO5K(d*rcui+%2zL<4dA2#R z-Q6yD2(C$u^-h|M2)vEhKOh;cDg2Ets>zT{{*YwsCM)&PvmbU~NLIu01_+aD>x{h; z7Q%mENOozM@gZv&GYH%8;Y8VSlUuJ2hjH&kUj%)|Yrl{sBQ)8n_iXUDU&wlZW8gj6 zK0^D*msdVyYvj-f)5qLloyHZXw^*#;BTfl4%c|pKY1Q}0kYVdwWdL`_ux$DW!@7p$ zS-md*tM1SgXKef{`#|SS;X&{B$(6rOw6xUZviKjQy60~bcO)9|KkzrX1Aj;P-({Cx z7yeydHLu5INUwZe#{8^=x0~EJF3Ucqlde5(&y_wGvFA!HACsi|_&WN4jDDJ&jk7ypcCe#`C z4>b1ij_&>+4v>=63>`;fLQh>+QTS?kHj7>v$<)%WWROZDjU+Hb7?28pbR4gGBQ* zI^#z~`GHIxcNSl{9RD1c7GUgs7$5!>@c5|Qh}5RwYQhNdsC*S}<=sam>{_S=`5CtF=v6){gWm&XbCpsIq-pX zayE>6`~&GkuxQ~(qVZnht;b)vIZR#hGaUubnw9@DUE4>AMrsau;W;0fn+Z48+A_(x z5%@Q}_22Mt3a)YWDwp&Tx{!f?IkOj!V`K$fGcC4q97o23otlBlWBVlTy;P`=B<~~@ zC;ua}-scP=n~SWLjPbi(d!K}3u|`%a;)wBT3=eQ|FZ@XM5j4+>xaJY6KONRa@UQ+z z#?-$W|M*3&nMFULkUn~BnTwUrN7m>Y1O*U{uTLu44sZO(I^W|n-S*bV*8TG2O?spn zc$9$g$y2v$AN4Bs;4+(c!2|yoJtHB2CL)5z zwtvXM42{bSNaK*<;u!Ynazy1vKYxN>cES7SFN-tNHP?}oD~mJnn3sFPnip@v zLpWY){ER#x?;8!I*Ssu`BJJ!rF>3yhg>m!C@|p%O{X~WczM}h+#3weIBc7i#w5H(Y z@U|qb8RCbxd}4lZ=rWwmNg`$@!y8lZE_iJcH}e=?^@$wJqSp0%!YRtyDRY*(`=|-y ziCv8A=9<^>xf2tN3?bj~IoXAOhR=CI)?DwLGkXwN?mQ8zdIhm3CFAgF zg!V6*!tTsuS2jz#6DNaOFV6mJJx z6moat>9T1GQjMo$z*VZ^7wj&aE(aC10O=4xw3m(?SN7tn>4~VI6T^h;ghJk>RK zx-lcsSXJaZh=9D38Z46o8ir_q3L2NPReiP+zjYJj4-Uuv(?@Ur`8gBCfTRv7gweXG^)Rim9 z^&mHgXUO)`$W(tm@OkQb6j-01m=&6L!xp#37E5mpmAW(94_rfD7cog0T*Nmcg3UpInBN>MG&z28}B;#lSO`h*`Wchy0W?F$% zejdx*a}pylTL}I+b7VXI8J;I4|9Z@kvTGkw4<(23Uj$0FO*8I8Qn!E zhnF0jTI>nk*lUV`mLhx4lx;vhG@XUPycGJ1gKguwgX%qnb! z8Zx#~Pz8@5q@Rn;3~S5pvs>!KciUx_r}f8_@Jb8P?EN;-^x9X#F^&A;9hTy6B*yb8B*-qYqv zdbaVu7@wkW^WhsY|C7yF>f{Xfk=Aq@H@4gBRNk@7o>2yl&oYgCTtk*xJ-}?w+h{~cQ-2`nW{;p zID1gO|6vNnue?-N7rBaObQ3N)O(Fc@@+6;&%)-4Jw>bwJG;d^xfayJE&SiOir?OJw z0d<*iWd%UHOJx%%ql=)MwP%h1iSwXB)%~7>Zq)sMY@(G)-dtDl^qlz<6XwU?C9f2? z_{0%T_k6hnQAh85*`?RM1@bCar+>)_>-o(3o$}#a2HV_oB(IpnwViV!;q(u6_@|$I3-1t&@rEij(?%y+Lo-29tfVJn^upZcSt~4n0 zmC@@n>&fu~o6Am^KdWQ>;4!LmkIVitA3nwxC#G`56> z==JagvP-YS7s#u6Eep#K*No+1YYlOx_m9kdD-uU0ZBhMyU@V50XA}ACkgO?j&CMHs zZem*xp}+|9OKa4tQCYNrhCEQh#HxHbYxWHM93lCTz%Kua6DJ4L0dqp>Qu~D|1(*8< z*}1wbu_UxuYvH3+6L|oBEQxDPX@wuIvJ!Mt4>!>yAywKBkEGy(@SYTW93F-z*Dd#- zluKSI^?4`$&@J|Zhhsn7K*4f>q9>&TYvf>M_xfu~Onw_IcH{shc2|K3jkmvAq z4Dhbs7fAA7rx@sS?cYbbdOMkp_O8#W6o4p7G zTIJP+%s%SB#nemJqV6Fk-rthEMX2O@kzR+tB@JBjY9CHq`)Iy}k*|ALI@P}sf2|`r zhQ+o<2UXw0GW75KJ@1+RC5thg@Rkt)VAI303FrtsEYIq-4tYEc8OXN!Q=dULbjia zwwx#IX?7Io;)J!rG@#BcbHcz8G%O^5;eODb0rQbsV^Y=os z94WU|T1R95Va8MPAHc(!_(sYu035-1g{s%uT?2A>{~&OB&aR0mHa=!wbCjeAnE{azLqF6tRZ} z#we{4USM;b_G@I&4lp0e9x7?}N(bOQMj z+@cCsQPv2k{3#hzx#p*BIo}wIpQokrLalC3C+=*SjUE4;PxAvyYO@A1*LW5@qJeq{ zlxt@|Y|q{O3ElJ4l6Mh-^1sdM^>=K_)dMTOow$t99BPJ_!Q+)E52fH*0;M)Li|4d0 zvi~CT${&lx7$-d`V#$X$rHI9wf@>`O#G>+MEML1<)?7?1t;Awh$uOZ>zAc>>(_sZ- zQe*d6ufoakiy6aqf|DzN>z^bG9cCta%^O+fqv!8H*nGL|wtM6jAN{WPnTesp1X%ct zbP~W(^^7i23(p*Z^&=afd0xzKwYj-Wz4#uP@g>*%8R2IW1+{!@|HX*;EESDs%~?Ti za-Wm!U!tYuC(Us+EfM@Zvct!I>rtEq&ygJrPnpI^U6}sH=PEk06lX6%lMT|K%1wi& zH(QU5n-LC$6NS~NkjZ7&m#MrQZ2S_HcM#-yUWOEHl>16B!IPGr*77{L$&cSms^VrN zH)}%9vnDljWAST0_)EU<%GB? zh(&P2#<(ZilgcwJxwo$&bLzQSxLX=3$s7%A?o{>wy}MtBa5i5X$ zKy$6<2afKR)e1c?T5)HEfdw3)2j&4MY$goipZ_Aiw?u2m$G<}};m)tgj4Ew+Xwe<8 zrS+NVX+eDBYnN8cW}D~W)?C+pBeNpGn_rY&RcLLFY5n6}@}_DXwzbx{v(h>JHBoD+ z&EuP~x_$5g7cLCQN5gQ$UFxW7|6FC(uSI~hAQ|3`qq zP8kC(X(mu|{N72_^%Tmg;B6?;K_f?%aAO&BdB8TNeI-xfqA9}m5_ULdz#uoq9vNDR zRr!1D2I0-7g!ag?%jq1-_DsyJ0RCn2n-%O%wc=bT_pPAa_TVhtBl`%YpO8`C5zsu- zcT)c6sCGnP?(+D!nYTwOt6jx%Xobt26$H5V$aX+pE-}XEgJxdD@;``wy4Q-%J(-yI zNZu+e_oA2w9MoqEHUQJhO}We-P?=m<#VS!>WuJ7^6tO3RhSO9s`HD~Fv;3g4J+c~< zLE_EYpBV=FRG;-bGAsMJuSk(Iga3w)r{J0{H$P%mK_af?3GVU~`uzB(;*BY|>I<4& zwxiF%3nDzpEzFC;Hlkbou<0+<;UT%U271##E_Drkbtq7Sm%_RfM%guj{@l|c`SB~E8BI9pe-cCc-CMpcVOS|}BB|7T5 zP~1aX^#cP4n<_4dsc@Z|p4OW}g$KU3i&xp{9**Ll+!@y6ue<<*v}j{F+YBEhN*yn= z!lsaP)-b0u@wQ1H18@lT{2KKqfBCb`y4H~;;_-38?VxGx27g?p2@ zS{sIY;C8Fkr(g2&8rSs7f+S&8K8SEm3O)``OX8}~eR_J@@$X4qEraC-{1R5ct(0!m3@=r=B5I@T0xBqZ;aob=*4R}a^}x64szprO@^)~9v@Jr zBD1`?jOcb?t;L@{jD!1M(@lWF*#Xm?*h1CtR*PFLt%sYc*JR%fX!pmWG^VGgRlg>a z>uBTHF`*6l@UKgeCAIKcl$iSwL2jCO83-jA^+0p!5(U=0CP#qhwW1-p_i*RY|H9SI z*ubDIwTo~&;St=%{&jNRTJp6tVowf&ger~5_O(Q{+=i2)K)ul|gjwU<_-L3~(5g4K zzv!MpAw(o^9U;hqCl4bO=Z zxBwx|FXM05$FB^UZ8@EyO$uAeWDg&VoQYe*#OJrBe9+`FbfeDnQ$*~Ut>L8PCj8Z~ z_#)Nt^_G7F{!Z23p*FpJojy^Vo7a{iK$HO64#*J#WCTf(Ihphnn6Tt#V2hp1tN^h2 zfNWBD3~267MS#Z+$U%i83iZU3dk!UbK=L-&lGf@2IDi3VSfq78e@IcYwHcoF%TG@` z6zC@sG$kQ;#V`4-E|mCw$;z`^ccp>V2q%}vIJ^oW^EsoZkfrS}rQ|E*K?va%v>E5| z`?EsfYrCJIkGI#GVu z=E?F#F^NbapZ^)3W=0U(VDp+Dvg}q)DR`0ss`3#cQm#L_Y&?05Y`v8vW&aGN;^q@Z)qvt{U7EN&%X_9NtWOx`%tW#Q+ z0eJJE-PgBsvoVEG4}8O*?E5Ok(1x)7R^QYhunXbCYT9jA%e32Eb7%PfGBJv(d5j=` zA&N@Qy*Ay(v%TfVm{q9Z)2^1S1atHrlg`^XF;>RwL$?u0_uuIb#%Oh(v(nQJ{5^3T zRkO?C0|=QXzv{Ue|GP9aQHQd5Jw>mfi&F!SAir=FgW6n$r)UJoY*TZ# z_~q=|86FGXr+?i|1#G&VqmUKvPpm1eCFyBBA179KRUL+Re=ME1V}kpA`K?~VyuqT^ z@%N?h4z8mg@S}oUk9{b2aGl{!p{MI?=71k#h5oQ_l$+fnas=TFgsu62r<4iq$NV%B z6=D1z_GD=N74~GP=}s0#MheBP1WQAQInn6h#{Drr4u)b6&^)bV%xAxVknz)hO$ zBmZNiJo$Bo%sv!oAnl-HlddR&yx)K1>r|h^qt;fkXAx;Qkr)EtEDgi5=xe%%vXS~79!u<=HPWLf?MmWi(}DMl>GQUtnTstE#cJcH54zxc z$7I>v_Ol{^dwJf#_h<=0|8-MV~0le zPNjKT>Ri8<8FrGHYH}kyltN<=-b%Fkv8ycH+i;t6pQz~}M>f+b1PK^lebjFEIn;WD zXLR$R4tFzdb1GDC-bh0;4GV1(GAwKclurCJS_ove#t|#f*r!l8hJ8!bHmSS^NsY>! z)r5e1KapL)CBsSTHK9@bkHHIY$4_pC;m1*8o{Dy#OQDTR-o0q{jRVbN^+;5VGm7aL z^3El4=e@Mfx#OKGHghpC*S7D@?Q9`CBNm<2re;T$6ei;5)w|kW}OO4>6DbNZYKUp~n zH%?C6b{T=sgU8Ej?QwmPF8QRj?J~*BO+7apGUivca>lHUvLLiCN4B>xvnoTyQSCZj z{*vrR$~l-eX8m@@YhRN0T3j<%w5E?G9D37Kv=x&)F^|7qBr}3|_)n2#K|GenJf68o zZowmCBkG*zGfDXmaxdn2)kU&jL$#kGM+h~25RdrEXZ955Gd+?Ex6;MutachR%ehY_ z=TDMr{x@==&*bWEVcWgelGB~kIa!0;94BqxAfLuhk?r5qZtVgp=TuqtO<2WLiv?lJ zO*h-w7R&L&YNn1^KRdmsf^Wa>ce>4OgmHXAQz?`Ebn;BHam~q$a1)gDZ|L(+oGoy32imw0o+FdDF^AfiGiE&_{QddN zp|&H#@jFK>I-6aWqE`KIkgEJPJEb*!Ut)_b_}I?#Hdo_DXxv zXqD7VuFFlor*s#or5V!y#^P%N`{l{kpxg2Gu%BBaYuT99Bleh>0 zgQu!7#fx_mCfN|$ z5pKNl(l+W=!GroWVeXgfebG#}kJfzJL=#HkHS+#8*R~y7Y&ZHU7-fFX>MA`wzONE%o6{o0gbr&6!$w zIXpgo?I{EBifOW`mD9Ch{Nr;`{d@86m?o3|(^WES825Mz8RN@5M>J&?QkrccOeiWWOCy1C_4*n<4obpdk^w%^PmoS@8!ShpatrcFA z%d&4#E8M&q_n$6)a{=Z@M|_^BY&*Q#mWkkQOCfU<&f9e8nf3U?bea9g@Cb{2+cKH< zF#YlF&&#rhIqTE=`NRmkL@+|&z3>*?#yjWoF~oIK=1nbKPWUs%PWCJP;knG6m@T&h z;_cHi8$odA88Y@T9r?%^Qqo2ro0E$=jep6x>@g63-EA#>{VH87r1D0c~@+of?08CHXUBOg4XI zinTS`52(nG>E@<3Uv(FqqJsIh`WMcTvmZfyhpgJcgV?|d9+1qGO^;9@$7X6G3a9#D z#;mcE&6<$e=g3l1b&4v8+Yl&F6LK3!&?f>9fG$og=$KNY>2Jwo_~#i^^$4 zym!u+`9#QAxP)ieU!_0oeaywrey^kpl_wshwfb<5%I!F_8gcUQ5<~d)2gF?Eg?8xH z#h-iAT1J zngleTT1SCR9ytO$ub!aEE!@3|0)odcG&Jrm!lA^9`+|jX-cI7~j>SD=q1*zKf(1@aysBWxR$<-L-EpUaP55qCFGe?RBUAh3%d@fo2B&WA^0y3bf3 zdv>8at=QK6;e2@;!0)546>5mbPwo`+yJsw3H^@th0-*Y0*#vUb&C>+)ZDN>zo*aZ_ z)Xk$tn;V8#Q6lpsuN}Bsp}whA5A2;M4GKqMum_lZmh1yMjI&IYna0&xO;dfG0IiJ!se#xgJk@-@q_NvA; zWJ`%mej3C2N-00x0`dcgd6Nb>BX@pcSEqqO_`By*HF(5zZZ9`3gyL(M_Ki`vk;FCd zFnpYt%;)>=8k&EK7)s$DJBHbQZt_!TYJ{s9=Hb&2H#sSUy5QLenbAeL@urAw7``wT zo%>qLruYP@;id3`m?l3rRVg$z!k5Q1g}A9mWfQy%A)Q8MMY*Y+FGo741ugTnf)!?Z zR?}+brEfFqIerzho+|ElOZqcf4{?SU$);y0u>M7~NPQ3y0Y(9yFokdzd;lTyEJc)?!)E*o9BE7V zxhxiV^OjJ1IS@Fr_IeVvB(aP%x&S;^o}u6;wd2fD`3JSYxhYt}uVv9eEmVJ&Uf*G$ zoVP^szQY8hdWlqWYYc zOg_p@z$-_P&jc8DM_0Kl)@$4OvRbd<^X2|7s?)&v z@&oRjqZcp@#1!MaeEDM+x#z1GJ4y3ljLDa2-vu;XICe6qgU;V)$i)gG7uy>-|2sqO z1UTw_vg^BiPA1};n9tFhsAehnFg%>ZHA{?}nUMJyWBC<~%W$_P$!IqF;4LY5Exaj- zn@tX0=aWs}BNLCJdyT#?6#*7}Ne(I;{Sqx&-&b~XlxO5ilJ|Y!aiBHQ1C1|BgF@rW zcER*ma39d={_>dhNsPOv%X{Bv&e1DReAiWUj`u5c0hdh7lPb6?1+RyX%lqHegH||) ziAx8<%rG~{_o|9;?ihwjZ)kJcL&iG2`vi<+&fS8yu({vp!Apv(w|xYkfWT1p&2f7@gh~ z6HCmvm60n2&xgB{xZ3808*p`#M)SPZB|V(iN=p*fNCOBT$GB`2w*Qp3!UvMLDh$I9 zRZ3?M8!k2I3&V_kZXVWFJ9E!h1sZxBseXLb9UH3E?fxqDCW))oQg~#AEdCLd=;&p# zTCZi7OXrVtZHr&E>E_+S%jLJ~mw%Itan11DM9-~<Znh`iPh94JGL#~%QxMtL>WgV#>$iuG#xA_oukekq28A8CdZLQTO7+;^t##{s6 zI$OA(p|5SNEZa|b4P&0V2?m(Z*s@xIW3S}3!@J?}6uYGt-*w=Vm-fu_|bUyVvOiklroCjc1+g>c!&HbyiC@-kf6o;)e|M>cniF z4B?xRPY^Sa-mfv5uajjz<#2|NAn{vmTFN7+R35=?oH0dz{)3Mt{gemohwTV7nX$*9 zy=WUm^+Q+l{==YklaOXj|2TYrz{z>x{yJUyI?4MP_KmB3@5T<-;nBXH9z39FG;d@V zQjVSL8P-MNmg8zy$T}m&WQgBWEMp}9O#1%y|d=%;Uw5xHU z6kPM9)aF&1C;yx*`+v@=){WwL1zI>G2)gTK?C03Ft)7zPSX!pdm7g-!HmZ|w z$)imW9)=g7L$fz_ey<(QXCQvY@Y#cNcfIWELv;kz=6O706P4t~L_55w&~VCgw3plQ zIXU|k*Zf7%nP_HskuWv>w!d8^_Cf%P}bc3@s3O5)d*T38Xw{~-QOjif^(c`Hjkd5vx?ik1~T z2sqbw4>^%!ui9P-@WwPWZmn)11d?Y zo>ULi__bzdwQ_UlW_jdww(LC{Cgxid|AGzt?id0Z6XR!vuhv)A^hbH$4c2G}QlOFpjU8;x=FOFK@wuugFDj zFk$ceirn!A4YayJc5%(?Xqc!rihM_d98tNWw}|5a*WHa$!Zl-WBN;QFO~=4}%uQ~U zO~Aairisb!!N0Xh_GzHj+o_$uCgY6z$vAHGX<`=c1Gvpj&(BTo?Xvop8U^r{FS_W| ze#yIQqulM`mu)kVIDWhQ770hs9Wthp{dbsq1#_}|TN!@tkjjI=V?guJRtT7OXJV7m zYSjhLzLWh}e#Uopl$(VJO~_h{%Pn80h}}WPkUJ&sP1JV~(tMqx9=Q8XX#j4Cpg~o~ zdS0!6Vf+ulC)BjayfgU9ZEOhk>m$HP$=oTHe>LO{hlDj7MmlQE@2qs<{D7By4)L`CI{ zEpn_OQIez2%-CmCr!F#PRMg1WVs%=499wSV`SeI4L^cS{%gqVmeE8K-9(6X|l9e~{e5WrccnbO~76Jw|_b z_IUiM_vmt-Cpq{t?in=CO1p4S4j-g6%kPmv0!R7G0JO3PSxDa_*@pnv--{NG$(Y~+ z+;gvN2OQTf;|}sfr5DKZI;&25z5n*+pY~3uRPVjA?JzpK(P=yo?*Qz%SGp8T*i1jG zPrW@qXS%(a%dh~e0QX%1SOU0^yW0Wn+~xkXx>=lz(m_{OxkUz5*!EMagU|Xe2Hh>X zPr}&;KOH^ZRKn*<>uvDkQYv|9t9ARj&*k@jXEu>_e|S^Yd=C&H^L{R@B0w?xT%E4l zKbLd=!Nj}zXIAU@;xk#NK*82Q^We@8Ka&Ul;hdi2d0=!=w)}#D;Q^Y2o}17M5kH1d z5Zs24@#&JMnsR(V=D&dvSqRst5z~qD4d9>y2p%;kT+F2X*3OwS+AMI z1?0f>bRpfHPN%aSG)JR3e$pmYx5cH*b3aUP2CCT?>Mhl%#)qid;Q1>3tCOSVI8NccRxaLp+f0aVDb z`GgGT$4zCIl&>JF5L*E!6^>dLI-s*2d<}SH=h0%~=E}7YLe=J}+NcvU={ouj=Mj3+ zV$cvKZ5zq2x!CCI72U4mc#d}$;{j{>rEmo+cZE6I5!W4 z;hLR!;BDZo_#Lx9wMno&E@gt_QC6~CpV>_|7SxcpI(^SG!LCTSLmy-Lg#QUX{2!kM;gS1}a8O;5dLIw(el?#f!P7YPpd z^#w3-1%V>7z%2$p@ofUZH>Z+?fH{xL1_jpu>NIV9q4+& zy0^LQB9+pA9@G>}QfzVME&sx)6Z!Hf`o|Ps41S|(Up2upm60im> zk&Ueuya7D2vH1<0yQfgnh!TAw8SVHbGX;padg>(p4*cef5@OG@+&@JsT0*v_d?+`( zMJnogjm=9nIJyPFZdIp^q1Pbfn1<>jRI6sL^hwhDoFQEPtMG=V)irMiZ_diW_fS-X zxAIr!>~OpfqDpT3Cl#`e2X)ac&ejfJ=!_?+ zzYT-tn{9;m0SQ;oJWv6!lmitMECDnRRH$Q1yFp@)0;WDsTV}N~GY>H1`O)*i zBJf;<;&|8??Sm+XFm{StAoyteeO{F6z*|Y+$fns3UV*$m8;f>7MQ@>jd15sq1EPiy zk*m2p@apGfZ69sJH-<)^$=?n?stIMrnyeSFk#ikFpz&&f_h|!M@*$GVA<0TWKQ}Z2 z+6hq>>*7u*u--9D34nKV(WENqRJ(Ps&3cB~GlpIH;Oz(*&xtD`f(WHh^x9d6K8~&h zckCoPIA3^iD};Mzc%Etgb%V!8;Mz9^z?~e}a13))iSZyWt6r5z_HnXntU#6U3A7D< z6p@*$)eaNvQZP%+(bDleOI?C64?2M;fG{3#mP2d}g{_CE*eN^vnUt1d<;doz*7w3! zd}K{fe-OL`eB`=CQ{{e+7O+neKcbQs!e^e%T}3^z@*_s}mKTg_%qIIsOdi@^VD7}E z*0Holo`G%ee_8et&Ys|x6Cd$7wBR*MJo96^v*Onz`(q|}PQJzanCxkNJ$x5KWB31x zu6wWSf*%)zuhu#2@5rhRaZ?}rgmtB3uT@{u8kl(?F*04MAqzb4x@3QX9m#xVR;@1u z5i%)#?_k(Bd@9_C@ESB4d%Yb7Azg%w%2SXLD%$fr!xn^YO3uiE$U;qIo)v=U@0AS$ zge*kZXaj!00+OPjsxv-4aqOh%&@i%;)R1HoH=5$iEQoT1B9oR6UW%p%kJ05-Le%V) zZJ)A#;oTSB!>PtL_?i3U(5K8(d}HvPFR)v%4_meW^csXLIf1PTYRmdwC15QfNA?J6 zQZ2Y@9GM2i{bS%d;^kPlG3=aqM2?)GCN&X@eg!k$(@6W3^FN^{&cNHQvFj%@g%JJw zWW!0`?o0Vwcx+y@YBt+?e~HfijSOP$dTdI~fJiIELG0B+kagJ_HL>}Q2~56i~P z0M(-KK)7zryZm1>-8jI+g$?8Jl@KNJ?n&LU!&?q+eCgDxIDsQesT;f)A)^vFe!~XZ z0i6NQo(R4kdCd~Xo=$mD$K~A5Xc!2r{fzZ*0o+WuYIx`bAs-61j$vY>iJM=abU;)g zr1?VN(+B$YgEwG`&P8XsUo?nOl{XE1H$uj2DGy=~=6p{3Y(wM7ve%sP!EZgltyr|r zR`_*bj!WN=eV;7H&co0Qyxpd7!6}40OuzAFLKVC=A~xE! z-ymeyDVDmOh5_>&FERbVfRPPZ%cT}kHLOIFHQXVSy5puz!f(^G=Mczyh}_iI)=MCA z4oTU+D7V5x;YraN;fG%kfg8;dJRc>-h!}uab4UhJ5~ZMiD!eM|W$FnbBb!(L|ACi` zfon`vCT@I-KEV%BeTX}^h^dvBe*Y>*csTrI<`^+0TX+guLO)HD7rY<&k-4UL4!GlR z_)JCdLhuCe$Y;9c;2DPpM_;ewgTV*8+lR2S^sv!EOqZS^hMHQ`w4lBLZjyt>E=z;N9T92was0z$-gsFi5L%{@r?}n|M%O%Z;0M`jKwV?-=M| zY6RLt=z`P8W$^L{T$PrCm;PP0e91sq`VX%5!tHp&e54zI*Z+nLD(2{vv%kX4?38TW zsG3eDpnUhR%J(YGu5)zuHG;Q~fwzM1j=Y#F^qnSxygpj5p8N7B3+zVb6 zfveIS@bXUCYv<`_3I2gjDI4a|TL9USIi#&xbqs(v;dcz}H+KiShuIx0ep8MSD!cW~ z(aH4uH-$R}o&jDTfvZJ%;J!B>UF({gT^+$zgM6?n#=slFiz9GV*9ug)Rb2;q=U2+T+oQ?k5 zujoiUzb8S4cX|e1Usrfu7-<8qly|?P2QJ53VFvW!Ej9x-;w=~>U@JJUmJjp3TR+~` zu24!^l#s+IQlg-yWPBkYmlb@ay8&%_KBggLwe#=nlP98FbE3+R(0i@pTkxJJSIoG+ zM<=_cj1MB%Y53fKK*giWTvMXc@HHcAtc>y?{DwdgzIww~iO;8^6Ke5Q9+9UVuDMB# zAB5K*O?@}~h7U0EXx#M2#=BzT0!Idi>8dz=`gNHy-o@QOZ^@GJF51~!auaS`<=Zr3 z6?pJ#!yj=eOgGA0~+hwUcjneIi_F(ps_LR{S%G8SC+)MI6S^LeCt5tEP>z06~6H8 zy}j}@Zc-4rkqy}>2;@$o)Oe8N_%j*I9lzforsVf6oALm??{nprYwjZd`{DCIqZPt$ z0gu$&2;Tg@yhJ#==csh4(iKN3s~1uO+LUjHlsEIz6W)&)roM@MUH zfnSfX@i?*Kk3=t?={5z`Mb7 zB5>|Br3xG4LGlga};q6@tg~$p$AGRn;dCt6OtScHu@f9O|)@@HAD9r;c^2ij%j^bF^rIJ;#L*_{?-)@oPFcRCHL!&w} z&)=9LIAy+@uC`^$XnrC5<|(oPepKI-A@dQ47qAp%yVVY^75$4FYa8JnU(fdJel`m5 z>-OvgR@GhKYDiZ?@6yP2j0@TO0d zK^0wt=;<@lat_g>02rr=lt3h$ITW^X*BV^~9uFRwj`}fhO-F`>=V&_CzAF2sQRC7g z6lmfdhj~PFro<*Afss^8o7+j_gm0z+1pm2&lOhdLgS4ycK+8ZmPc)yj_)6 zlUJ<}r_PkU#FRLIuqI2DgdV*)I#|_UNfMUCoJH-`qt)^NGZVto?Im14$`p^+4yWT4 zxjV^qo;`t2I0=1$bK20TotRz}dBG!N4T3M6W>)-3^$=+YX%0FTykc(h=0XJAMrkSulPJkBqMkJe9EL-l6pyg2=;4Tl3BN4^v3b9f?;>gfKU2 zZu8ru_Eu-g%tAzJ#t2#tUTvjkLOq0j*E*dnRnTZ@0l=+%*Q#Kpf_g7-)*Fnv(L5yI(Kuxw<2U5B~k*>GEK^6(i^rTT%ox< z^CfvSiB5i#UM-Pc;s7h%EQkPNksAg1;Jstu zCEy(qxaN8lc&jR<>sjT8*c~CHW!VPaGzQ)ajzwWcsL~*KHA?r{U9-k}y4Y%wSu^Mv za!z|El&CjJ%4V^s%aU=)a9e?D<+mQ!OfjyiDS}Q&8X690PJHsB49%ij>IQIV{eSC4 zIrnVW^l{B{V+!l3{38s?>UAgMt4SVhR2BGEc__u@ap0>ogSFu;k%I(Nu+RXf2k}6{57n8dALjHK(Q%NBJP&XAqBQ441b$rJg!Vm2__ z6=ScTDTB&Q=T1Zq+=kioiNE29!nf#qW{1b98CeNlH(R!;Y?j9y&?a;Mrt`fmU|gEV z8ra7D+8o$Y<`9k7BlG9b<1B=$hL7xV3g4#fdSnCqs7zFv`;CB^9@(XV(k+!5C^WPM z;OFw@gYt9Xk8JpAr}rI$zho{-SD;ikW}_<&kUY|3fAHs=P5=b4b*Z!$P#-g_^7JsR ziBPS!XIQvKqbBK~rFb5A$r$M?0xw3X@x;LgQOy;T^IQv@X_ROy0Ua0bv|dsOz}-DZ z2IpbNZVJ=b#Ls${J=!^voeJ0uXiN@#fSq$>J78WAJ@J+?p=NBALP-nUf0$t$#R=5^TnfEx& z27F|_Q|&n>uAM6fH7;UP&xusEzA-noPJX(`bzW3q22*N1NVFZcy*fj>7GZMtrDDH8 zP0y71>NYNyt8f#yUKSp?MpD(!z;>BD3_q?nYiKxCAC`Z(L;i9B>N~jPeqTG&Gaphh zS6Kb&(H%yAnk<=KSInYX;E|SVit;~VWRJj&{4#JU^HK-nuN)oD4?hyuI+$bO##f%d z*da%}RJp=jYi4lo4vD*vnSc7~(aFpDn67lSWM4?~J!9}I;k#GMHu!eWYI#ZBwA-W$ zH_CGx?TI7lC)FdAMc`Tod9(JHa=~I^Yr1B1Y(<|?N3W5Mi-~Q;b>VzXM*S@y zt_6#{YllJ)Lr))_7J#1{for}w2k0!;auXVxj_K>d^(sFHe(E}^g02cnRCt|~A#AV1 z&35q?E?7eT(6CQaF#LoZzKBJ8d4UY7(5V|`FxxdlGSjJI!JAlPYs-G*2|3Wi+m=P? zF6T{cg+pO4CTJm7eacb>JOzK~r+7Vh06cOCX#scMG8DESqsDiDFT6#%(zUmGk)h9xLG1#s+Ab%*<(iX}Q#869(oV7xE;2i^d3g}& z5kk5b)lYn>;C_v7|Kn^QxGqery>qm-Ruoj-DSMZYG5(E=A-B-bsJhMQ=+d$fEj@&jeE7x~%iH;41H&{qY24S4lr%)F&W zk}_Nu+v}=jZ3Yn(JtW&QT#M~_kI0`hh^WdZ$JFiMy1t8Db7!|a7Oqh9x$QG{*ujll ztQT2#F{{~PUfd)AZ%oohzrx(Q<8zu2FKzbh^NG3K0ngG(J!oQc3b=_ zQU;h<^~&j#r-V}OhwpnucEPu&{7&9exBgX$U4izN=Aq#%ZIsc!kfkdq`}SS5Qq9ZH z|4VLP;hLUQ+Y;XR)#%!Bc3V}8*)z^;h1fcVP&arfLdFQ-u&a>7eiy@&|G*?xzfaBs zO!-5&daV=vgp3Dgn6o*K{ao(;E}7f@$8bTl!;ga9f0SKlO{{(`oNrVv_!Y0o;CHoG z*)8+4iM?faXm2OVZX4LGBP#ch{Ap;oL3{86Rq{eM&AR7*WtCjEl7LyfmA8`UN)E|(+@$6sv}gpViVN-R8>-pe4!h0YO&7_zw4u<~6RuFL?FFywA=CKuefk74bPO2}cyW)+zk)35 zeOIo!!nGhV=Y!F@e8^>dAls2k>>PvN0e{a2(gi;*aCB%mN2}(J2PE!FvNryhEV`1c z^?fWiU5NtsC!-^%jkdGfBu~S)w+Cb|?gh@z!sRsg99)1K|7AF?iA~mvalf?I9hs|` zhL?UR*{fW0Z!Si9WaCvWl}IZ-ve7GE3%-5~dB26HATzRWYBTkiO(g(P@udtB>C*Bs zlz6{k=UI+9dsiiQSW7!q(sq(*sFw5HTV-9YHs`>QdGO%%TjjtNy#H61>xzjg`HXe; z4X(4tqpJ8bIh0GT?*2mTt6dAmCk!%6kn68?oh3P|UGAvTL2Is3vDy`rG!Q)9zntz_ zYh&%UQ$h0VyNtc95LsW!-qkcUvcO#Yy5sD&LQKvv)4gytCTnh|f!83kauow)9z@Dl zOna~5afNz*if8kw=-{YqZ$VP=6jR;lJ^c=FTg+(rehb$qHOE4Oql3fEoDuTcgldtm zu?2^-SjpKOf4X1Jy_&3S92YdRvf+L+D~qqDdgR)r>}o1oj$NKsHzrEyd8J9qsG>aTJg7W!+@oh<)izX8t zw4N?Oq+3$jql7ZjIniz_LP#@mf)^qXElaK;dfc1TO?SyQ+^7|AHrZ zZ;Ry$Gnl=x7Bg>>-PRK;Yp;cw94FhZbuFHq?+njy%_x;C1b1kayKsvx+@?SFJ#vNU zV!wyRe4^9sj~RLKcH0_P(D-ai4Zp^!0Y%`oF4>5%y)It1t6Mx-&6*$G53gZz(3nX^ zyC>7tL!fQC%S+rD04oBJFEZKk?Rh$r%bNR-1o*(A!grM=A7AZ-|wNjD; zJ^-Gq1-Ndr`4!B-b;R47AcLwRJuxUx{FSGRSyLDc6N8~OSc+coqIEMLya6Hei6%sS zqHN>!uBDktqbqeQe8n|Bt<-ujua=1_Spn|Vu5;DBa(pdyH)lHaO$+IgdnJi?nUb1k z1j9xSjXuXs^fRoQRsvB!hENr_4Erzod{tBrzdl8F=2JWUv!n~TsJ>Z7<)1Do*OTML zXUqKS;Wo^cwbxUKO&-~TyE%ETRfo}{Kkchq&SVq^k6hq(fMd$-n^iBXy)QFS$6}YZ__;4as#W&25&HIiK0wQmzqju zYgzByBvA!uNH|C47f>2$=g3v+vVU2I8 z{m$tbtuvASX@Q(^BReQD5%w508NLIp>l$@>43XfKvKukJ8R3zGxEJFy;42=lwia)a zeK)$!b5@g~b((QEZ?g84JxMgE#WMdUEOsuYk?OH6C4dQR83M+oEe@I!^>1#H7jELc ziV^^)DvjDC|GbF|$h}BnZzg!jMOGWnOJ@ANNY(<{S1gq+>SkRmJ5^}?#dOB{oHKw> z`^7Q{m>7Ra(0D6ZE8Y*Ra`sMVB6tb+dr{#Nz9Sn78Evvw(j53?aY8H1H7jLrAsUMT zjjqK#gVAE8B;G=F11n`Y?(DuR81G21)~r>Q<{*LHR|bdswJYJ0+y`%AWNyz5%8|XO z?m$b*YUxrf30I5#R@{=Sxp0fTaOYXs*Yac8obCGeEA8bonM~#djgLp8>mmFQFFeW) zI{qg7$G!Tr?N%Cb;WaXduEe%$!!6SS_NFicxK@_jMqGv8qvGi{>Yq#G_S?wjmbLOQ z414Z6*`;ppIyG{}W9w1ceZ9o4C!;cNkR|G7Y>*A>U5l5t+!`-*+I(piLU+*F4rRK>+Ya1lSo;yqOEsG+4qUO zr&xBXn{cOesno(dt?}10+ipv{Q|51AEL)ES#`qeu(HzSvHlQM7qiowikb;fYSk^(1 z{Eef>vVQQojdB8Ed;O0k@ph)NC3l5)Q<}g$58V{_di>f`tf3AlUIg9=o?_ys=USEE zJ>Y&5Pq`g=Ety*I@}HOk-L0(j9P*OJumiudAo{PhkwP|Z}Vt;pp}41%VB zYI6v!qx+F|l*tLS+5P2`_yg7!j(bL@E^jWK0{F<(sWnC5srS&=-pp=N^$*zjTY*$$ zni`Q>agV%&c6;V#>B5aGs9>Deo@C1pd4Y&dG3UO~0kh^Y4%{c%KO|u8eX{X~)U1;G zT-*kTP_nlygHwL7*{*rFbyf!l1U4*kzhJ!_K)9Q*KRGm$A*Nx=p zD`U!WC?_M@4AZX)@*teJekDpRP7}nqtq{6vHwy-d0Mdwhl@*T~l~2JPm+%dFvDh{1 z)r?}-jB%SEt*jt#wvuF(=uM^usQ;W3$Sh?oRI0*CbczzKR(8}VQEjEur^FgkqG8euf)pu{ ztVAt@A+G;oVojn-iTpTIELDjXi*Q41wmHd7MYrm|Jr+@^M8IWcb%qi)n!dWF`Y#1S z^D|3{OpB8VF-|ASD*%mO4MYmQ7!_-_2!|4#7Gc}0)G3P!>PJxt{7X?#iFAuFG_0`* zLqn-W7)I4tgrT6>B2MAjIxWITcma`Vd?oxFSIfT`t$B?~)yEr^Vsj%!YW&obif;{t zXR}e98ZcLhg%**g#0m(lj>$?CS)2rjape##fW|K!L>1_v8sqZ$r@2?8L?QoFf$6wuA}FlQSrEG%fH=MW1n?>zU0-WBd+Rkzw2@R>FQ+z-$uyKoYW&tOFkMRtClen;?EF*<9v&XPLj}km<2PW@x2Bo&zbyI}GV8*LYc^kI z#%T%Liigc4`?gSY{F>K=j5H+%PMCa?ve{~`G{dLom~OE}_YGNcRu=8P!sMq~bfy*0 zlz0nRzral8o)Z%vIXG_m=B8OD{WZCpZC_KwR=jjvU#kJc|Fs&R@qe8L81a9N25kOX zYrm~&^Vi$_Z2!Oge~p!oy7zUr|1-yK|B{$7@vh`j_fOmv?zi3Vy65RHza}W->ojc^cWfK>~mhLbI<mQwoRX59zv(%Wtc^t8i%Auv>Qs`H`oWPrS&! Uo5QXzpLmIV)|ImT@`-c*7f-1H-v9sr delta 282652 zcmaf+3!Gb3wg1n_^pQSEUosEBFhYLp_uKVm58jmq^O6fq)R(}EgGg+L2r6zqSUv)4M=`O&%m`Fu_@ z>$~>r?7jBytdpEf8{b_~{>qAscdF+&)3AO*_P_McS=q%8uiW~_NwzJohM`JX|BkUd zb>%nelkIZyI&_sXOM_EP@0632GknrvHVvONc&fQ*YArk7Hrua*H<^p(HyPvWoK339 zIfGA_>n6QS#{Z?`2|6|p9_u>dxEJWRZFD?K$GvoXkBb*X`1SXL&zm!oak9QlhjsG5VUN7rPrsz-xSo#xpyL!e z9-!kHI*z2{RyqoFSU=a%@l`qoEQ5aXbd09smvsD&jv+cOq2nYvE~eu6#J6;IJ`*RW?Ny?&8@_tWbNI?kly5js9j$G_8YCmq&LH8*ANq|ZFMb@Xa; z@YOLv^RpBH)6AO(PaJ!M`6>GSh{4#{iRNt<9ZZj%I3q!IdhD9&pWEqW+~5z!&P?8+ z(LwEZ>(}*kTu#SBbX-9P$2$FH7~S^2?SCGmU$b;PMn{s4iF8;$kE$2@->=iZKVti9 z^m>|dnv(~oO#PhsfZa%bs&}wDH8B3S zcHdqjdgkExX=j>yt%l6$RNU+3E=p$}Ci7;$F0|YFuGPx;PdQ}v^US%;BGPN7i+ zxr!yR*3ZA}E`!s<ngU8O8Ihdc}n_W3W^*Kt_ zH+t=A9@6SZUz%~eX@1G>{nGX%ES|Y&Fg7zV>(kDFItM+|KChjFyJwzYj0@pn1B z4^Ex^G4m1InVRi2&#`_Rf3Mx>6vI;={PFBXreROyQI^Y`J2>Tt6UMKx>(8`S_533i znSUPKaKs7bJ$8Y8_Dofe2$*l#zj^0ab4IH=7^UA%8_dr6s`*W;yp*lVKrbFVc?CoRD}reW#_7j zeZX7HW61a0?IevjI2xZ&4JClDzgF=S@JE=ZfiL`|DxU$qkk~8)kP-j+v z3eD?PLq*`>8x$`Af1i07_~x5c`HIdh-Q0Yma#VE(@qKZ{Yrt>h4(hlm_zyoI}UIFes zQ}HVB0`t1!NoV`z`OF$n;mWgALrvfX<}KjQF*o*f26cuNq20h3VW-26!JgGz2`nO0|;*K4-P!#Wq*_&;3s|MWwdGKBLrcRE09|67wo> z|3TGG4S2k+c3Bs94wK!pr<&;-7fJ7@tfmQ*{&tDQl*jJaFm z_WpbM1y#YTIjmrineYL>k_Y4mo@O2ZzWRHr{UGp{zwcK2KLn1xpQs99-~~Q|2=INs zQ{|(;gU73-i~$dytJ3NCtI5tOnjTh;1XL(rqIe2;yhrgg@FC_I;9D+M<@3T>e~bo? zv>*1HT#mm4KUZZ#gcybLps^FM-m8wt&o;X2GX#@Ck{i=Ku z_{4RJw}6lOq|Isl|I)bxf$LQT5AY0k>;)dYR+aYw-^|<(oI5rGHmCk&`$@+ks8HgL z!@x5)sE#ARtIYe5e@2y$>fDO|_is{;xb7fc<&G1;M{z?b;1T9&;8o@s;8wr({>y`- zwN$Nf0r?-)K#RbieM#{W@CNfT@Ec!NI1D4twio#HPpgJ}z-ymT+z;Fn zS3C&3Y}r=)g}@;*5eELq2Gvjm_&ql%9tCb3%WDtZ$2?8kj(<_W5IZtZLDs$iJkI5d zz+-GzfM>XTwawN3lM3~=!;WT8Lj_#}_#L;YGj0Nxat7Cv6Fa~idw~~^O{yvKfuqF@ z2Z4uPQv(VCUy@M+3IlI#;Uxo}x|5eI36473G2qoNstR%7kuNEp0G?)^25#^PWSBeo zf8*a&Lqkwu{k@9kf!B{xZ=)4}2WBc>0xlhwJ9*OZa|e}9hw&uyDsVZo25`@DYAKt* zC3xL@<`NUlC02QgKQB1y{BE%yIX4^z9^#H8z@_6T@HpEs>(z>X8PO;Xq6Ajp4pP8H z!-s%J_NpMw122C~EoDLD_Ws+NQ;wqMu=d{z%uB#WeO;9=1CKDT0*~{6YQXnB;8Od) z4vrV{s)Gjb^0yRk0{1+mcnkQI%-uWynduxA3Kgfg*e-Nz_&iG zI*tODatYum?l`4$EB@t-hja(=Cfj-7kNiY+TmUZRO29q))C`w_hn{k&>wg6tQm_U* zzzx-bFZ-z)Py@J>YXJ`|Q@h642l;=PJMi+WEKQUv_<&3KAn+8I4*{3*5r-@NG4fm? z>NqU@GmQUvSLO3D;DM9X8N`8~#ykN$%sdU;oBX?4n+!PIzf)5>1pJ;C6wd>%F)sjb zFfRgcF;AAkQD?gX-1w{NxC;D6<~87>e#0>VJg{8NTubqG{_p3R@bRmxeS|9nfKO*0 z0v=~O3|wY3(!pu{>wE@%9S(Y4UkOwa1O2CWUaT&PiO_jJE|1#D87*^3&#P0aBP{aDx`tO=O~^5zM9MDf%|ws1>hU!s&&U-2gJh0I&P?0JzLh5V()ahb?Z!zl>CFJR(qGGv8|U0Uu%>1unN{G2n7* zme9Dp|3Xc*A5)sc+JBXW>WtICUuK>GzVK*Oeh7GAk>Um5)i?S2Uj&E5L0X?IZ~HcJ!-<#S9PdIZ?GuyuhDj?gQ>wugd!!ZlAwl$P-Kf$Dw3Eo?r?BmnWD) zz~up^FmQQ*DFXcTBtNOt2M&3HDGFSkV2S~k2bki(i@=QyzG1ty+SD;_du@XTNe3p~9SXikE>)OjLkB$!lK)-e6wq;I#gaaL4ry zhha?TjvK&J%v->t9Haq$64*@STkG8qmf30)Xh!Smwz5l%LaAE>Hx<|!C z8u+u!Gr;A+#UbF4?R@>sgTwt7j#A*V?~A}?-PzApop2Nx?zaLB%|0+)SX11|f% z4t({i>I53V_wk7}nLGLabAMA6T3CUfTr_woBvxeKyMb?gMYZDr?s-jdUnfr*`3uzA z`#T**9}gr1yu!~3hJjD)QqPJ-fLEFK0ar0W@fQV$Tnl2rzfT(SrtX(Ss)NS9#`Izl zB_;yEE4=nWhb#Rt4zMHSI4u36+>kpC1E0CedRtIIqSqK! zXD&e`8IBuxo(JjyE(wmegVXxU)y&u7ptPLtZ2Z6_!wCR?b(dO#An+T1rg#YW0gGGl z7Y4_bKUWnZzU1z&t_Rj(?d_;~CXK3MwpPo(3Lfo&mm*`4I3r z^L(4D{WtMh)p4Qiu(w}`c@g+S%uB%CJk=H8Y3{fReCIPs)o~phvds+MZZbo{y}tOOuGzwg#GzMIhG!9&pG+}Wo{^g8CN>fllq%;j&q%;FulynHVC~02f_WlzoEocsF z|A~|qfs2%ufQyorfs2w>fRmD{{a*!#NNEkYNNF9oEu}Qz25?c*CU8;G);}Tt7b!K~ z@4VQEl)8b7lzM<0lT^@ofrk!P+$UV}fB#(N@QZ`<|1BQH1Hd;Qp?DB@aHirR;G(c$ z;K}M_RUrb77V|#fBC%26c|PM9aFO0P@SRGMlST?0vX9fipS1TYeOeB@#XJvO+9?3v z$>obSr}&fY*JMWtDu}k1fs3|RfQz=*fXjgDI=ABg5$?F5JFIAC-UKe!f);SO78tCA za$<5Va09ol1@`{)f@A2TN@9J$<>C|s?m5WP3*5b2#a0-2hI!-z$p0Pbg$j=J0(Ybr zxFfy59qDzr(jVs*Eaf<8{^`e&Uf_=O0(YbrxFfy5S10*>x&k;H=>_gcFK|bCfjiO* zT$0#i6&#NA0(YbrxFfy59q9$`NU!4U{NIt@e~lo$z#ZuY?*5AkIxq0&IOu#GoYvpB zLRIj0I1J-JQ1Jlp7xpS11irPQcnElXpWjJW_@WV;AlWV_VCDF#Ki%N-8G`MVGm;F2*{fyelaYrsXe>%eWJ@9aw zD-DQUrXsno?XWdKZZu=S<(uqj;0b z54a>L{!X5B-f9bUIt+>SAaF@iLck?S2?LiTB?4R}DHMNw;E*gO3S5$u7;w2ij02Y> zB>}w7v6Zs875_5T`@Y1I2^AXmDxLwJ`8UOffZvf-JP&;0R~0X4+}?k3gILrY_WrwD zRVV>}mIqn}F87BO;MIFnJ5}J6q^SL01BYZO4dAkmo4~j7l(vA^n7euZ%S=l<9#>Lr z195EO3SOvCW$ptmNs1r1Bq;&llB9%$%X z#hu`3R-R$+zW_KK z=>_gcFK|bCfjiO*T<#D1x(-wOUzWg;UaTPRXajeo7q}z6z~%lh<#5$M{b5w~)_B@+ z*!pLr`Mxd#d<)-p4FQ+?!#r@gKP&*RC;0}k2oC!Ok;YI0F87CJ;BtRh0WSB4Rp4@e zn5==rkzU}kkDI`sR$eRq;^1(k7kKdsmR{uiu}U6zVvG`+0`LR- zmBJQ@+wm`Jv*iFwFH~@(7q}z6z#ZuY?nrN&tNrIlZ`)z-KSz3jJJJi>kzU}A^p4h~ zmwH(L2w#8Q;BcfDxFfy59q9$`NH1`?#S0|C;YcrVM|y!f(hJ;?Uf_=OGI#QSM|!b> zNH1_ldVxFA3%ts)mFncQ{vy4d4rA1NDi|}sH@>6z5b*lDiszAY`2uji-9GhS1jl;r zxCHzj=4Iec)(d8)AZihtRDj`TtW*~d-b_wbaqfLEBidH+lM(vC;t_Ws+< z6}+0m+J9x{KH!e@0(YbrxFfy5X+U=WMi?A-aK{ngCFXs=9q9$`NH1_F=^X?4zaza+ zA$=uFFL23vhk(c3N@()HpKYliEeMzVfBmp>6ve^$zesNhxJYjqxJYjWxJYjmcv7Ud z1`d(lI&hKR25^zyCUBA77I02_Y5m7`YO+YL8@NcX2e?SD7r02T54cFL-{#c6Y!8v% z08|j^4FVVG4FMPF4FebHjp*Epf05ok-9cR5aEJmI>5Tyw>5T)=b8IDm$No7+UH?a9B8tym@Jk2};T%@-TxJYjlxJYkI@pk?%(wl$^-m8@Krhtp|W`M`WD?J$kzRcji z5!%6N{g;`_QRr|OhDdJ_xJYjaxJYjqxJYjWxUIZa{8hmr(pv*A(pv{E(%S$o(%S^i z(rdJc+wm_^D$;9=>y%`XUN>-&UJr1QUN3NwUSFH5{U_4vZ#(SmC(;`LF47wWF47wU zF47wY?)xu(1~38+k={PwBE3=IBE2!-agMDxa7lU-NpLjBs9;P1-{(?14ZO(ZGr*UO zR^^9)2gWL%XYSlCUf_=O0(YbrxFfy7CI5G%cS5K1&bdXM zfg89Zy}%vm1@1^M@T4QX;E)fM1HcvGlKK}#9l9;N{ z2Yi%QbsPo$>TJbhzz=**wUYoYL7K8T#h+}y3P))gD!k7;16=+J`VesW^g9o{l~4mJ z>fDNd8Bs}h5HEAbW#9*xSAf@es;j`uYO0MI@FldH?EO~<$CbR6P2hFj-!0(&acT*S ziJigQJ6>@&aLKGZ6CwYX)XEDLWPkgBOKRl@E;qFS;Ih4g4p;i)JnI*79G3pkQ_%9C zi2#@V9RV);yAQZ*?}Yg2=o_%p zRD~w+7ME`U_s`&6z`I0rB{YF|0q~f`t@!hRqrw%uz%$H!!1pot1Alh1>Np5owsDBK z9se@YH9VzZsE}sf2V5G80$RZ75LEA>ZZ1q1V`dnC7})AMXu09&Y%5wCU;72 z<1l4=kzc4z*vH(-|L?d+Is8yTv^oG>q&f&(q&fs#q&nQmlZI$@q|@O%mfZ(jQn4s- zk?I(5k?J^bCDjyv32=y3r+~{{a2mKsbq2Ud^$>88>b%9R_?PV`T3vt&qSZy{U=&o11?fs2QE_G0AAwQY62&zR{OsNj%ECrkik(bGZbd- z2EH|-g4cumV#U3{%Us@f807zJxPl)l$d?WSz~wGD2z(>A69O)G!C~Q&|H~VYed6Hv z|79OXfp6p~jR7w*PXL#8Qoxfpa)mTF3d}RWMXHB@i&W=MC%N>Kbs7>blJ-{v^0WtD8_E6IEK>0xoyKZvJnTq@CbeRo(+!z6I&mxfTCz z{$G#+x`TKvs-iat{JFJ?hk(mna~ODw%SV7)Qf=?QK5&RuM}f<2a}2no)p6h=)d}Dt z)hQ3;|Dx4ts32)|2DnJ|5b$unnxQ;!k?MlOmHs&211~xbOaI#611|v=sV)PTyXFe; zdw4)K;O-=^eH|Rn@|rb(H<>qqFZ_f$;}&qa88x^c2~v3!JLv(3f1Qe6A8>gTI{@6^ z4kN(p>s32_z=Qm!ePW8Y^Z(E^m9fOJ!f(`>C6NDC@f2`LSkk~HVaarGT7St{hB_Sd zH^BHmp3DQ6grxvnc0m!i?1B<-dly*oR|bddf(mfi1y$g(3u?e6VW|U`UC-F!mLTv0 z^8SAa92+^f!ocO`G6MYN->YEk1KxZ=@hI@ETt1crhxbKQAr5>_P4NWq3U`nK{xb74 za7kD)%$@vyAy*iJ3X-wpflI8A}kjBrIXz zl}{?^jR2Q~C8lwE|Al6-^lA=!|NVi34tSb*3b-S^z#ZuYPRgtH{}4DF=>_gcFK|bC zfjiO*ToRD-G|2xQ>4gf8^a6LJ7q}z6z#ZuoF8RMBz2e~f-;rM6j`U6+L3)8Z(hEH4 zNG~`X=>_gcFK|bCfjiO*obMHrMhG0wa&U!#%eP}9z~$R9eZb}0F;U?6yrhCUW^;-^ z*?v)W#G!(GJ0=0#;BUvIfXlaI(!d?*)wvb_^7WV@-9g-uUf_=O0+(%E0-oX-Edzg& zxV`_X;E;xDz!Th19r#Y>4d9OS0+)Nm)^y1K9qDC3lBJOWd4R{cV=wSWnEQY`((7=g zKZYZ{j>FbJ!;xO#j`RW#$5?uS%h!9Nz=O$|YX8Q-5&0wM0l;5no&YY=n*uJ1_d*tk*caQ<6n`-N0?-wc^hM4v}6jaFJdgaFJd=aFN~saF$*pNZgKp z*=D|%RnUc?f@Hm6;PN(I1h~9S*9ScCC)Iwm&DH)J#g16pVeh|Q=5gRVd7ug4@-|%x zxJYjr_{%Tz`~Mkmi1ZEt7wIhk5ArrH0)LseYYDiQPoRcB;M z8^A?+o6Md3U!>RIGm)5(0l9%c#{=>Jck_U}z(sm}ojmDCufNmbNN)hRNN)&ug{3zP zT(aIi;DK4zHl_HBf+O@loFD*yfq5LbNN)nTNN)J^0e?Z2Pa0`(i1cQFi}dD! zt9@)31>n!|b}a&T^FYfsr}&fYCk<7g!n52^6}Z6-)qsoi)`5%kHgs;qzesOOcMz8W z8Macj2l^xr$PK*3+yh*s*9+WAdhPw^1BYb2e&8a#LEz!*RMr~;F47wTo}Qz&W8W;u z|I-al5THVfc?`IG;t>Zf&j}`gi}a=(uJp%{2L;oP!_q(cY?$8z&Hxwb9Re=Wn+Gn^ zTL3;PNq>jg`YD1#q_+fIq_+%Qo)fG97wN46m!vmY1BXa&9k@tu1Gs$R(F7j;yIRT? zaCuJ9m~F>EJO7sl1>MTwY)gJn(C`44=LEgTUsE0XfbV-)Q9O50&~D5+HyxTID!;IhB#z$LS4 z08c#4&;K{UA^W=pT=utdL}x-F``Zm%GAj>o+1}nHIAnkOfJ2MxCNdTABDg|6pt2FRAdsNV6 zfUC@k;%^8Xg}& zl3E3UOKKGYE}2yXxD2Ro4&?t8KC>uP7{vpM0hiP&4qV<(OaPb6DkWU zeZ5MphJed+f(76{E?)#LsaOSgGCx--Srr@)y`zGz27Jl8ir0aQR5yT&R5yXMR40uV zI7F+BBReHl?t0H#6_$7fQwW|fs0hffQwYefm>2-@BaiiM5|N4C< z3&7JNy};cIm5`Nzx90QpzXFbBqg6~)fj`8&23+of>%iqMxB*8$ly&m8qz1}ug`%k3T*LK+3Po&omT%5p=l_ygHGoTM z)dVi7RSUTM4H$!WkHlQk)1?H#4UQLFihF?H!$Il=p5gL7;Oh^np!NgjzX6jp0^pFp z0TTo+e*-22TvDqr@KK}G2}FQPX4PkNia(hONv&c~LH2PRc$jA*0emy_G;nDrqjM|% zLtJ4p4m4anYq6>tQ(<0|lt%xl0UwWR%d`qDmDaMq&g2= zq`ClHq`IhhJO3B0EN0SV>I!g?>MC%N>RJb<^%t$KcR1+VZ~XtXHGqp$H-U>( zw}6XO8%K3sYiy~u;?E5ZxeN9Hm%Csu@EYHw`hW+gtKjtmU++^qK-`Xh*=D1TP>vu} zkh|azaJdT(1DCtt2yl_=zBX6;ZzJCYN81j2`-xV^fQwWofXg;c0l$&AYZ`cAVp5&) z5ICfvJn;4M1_kgu^CEDO>Jo5~>T(hsqSaO4GN2mpE4kx3@FC_6;3Cyc=1%@ETHS&Q zqSXf9#Y(J*RC|C2KBc7E3tZlS40Q6O;a;S+MX=LhlulPm69T^G48_C9`7bF%fIHF) zTxH1=e^GEa(hJ;?Uf_=O0(YbrxJYl>;#U02lseK26&&dW?np0iM|y!f(yMWM|2fjD zIjsHXNH1_ldVxFA3*3=j;H122|JT9cNH1_ldVxFA3*3?3qYojybb{`qA^%TvaCxAD zJci>1{_>eB7=6GuGWR3rr)>hlCI6SlaDw9C{9isS3IUhLaKgYBa>o(ij`RXguHgz% za5&Nn+>u`3vW-)~SM!Xffu|Ht8bjcahVsBq=Y|Tv6U>Xi9q9$`NUzN){$%?((hC)2 zKsDgYxZ^tTIP(T@M|yQ`#lIuHx`VhQy{wQjP)B-!7e#uJ^WTW@12_D9{SScSz*#D) zgTOs2S(1TE)*A*c(i;ITZ&36tg8W~kHwqO*dSk#vdgH)FdK17!dQ%Qp`s4f`P-(|O z^G`n_y&2#ly+go7dh@_VdJDk!CI6G3{{e?cZwa_aZyC5qZw0tWZxy&Cy~!FlM0)GM zMS2^+MS7dSMS5Gn?X1_D+GA`(32fZ!G9Rz__SE=$L;4S81;3B;d;Pq~5$BMr`aESCqfs6FUfm{37`bhwH z^Ngl|uV$VhZpXg}i!?L@6%4MB2Yx#90&tPuB5;x3Qk$#&C(>JKJM1%(0abywLTU+W zz?boW>cB;M8^AO2{of`yM0#7mMS9&li&!k+|3>}n21;8#W! z4+59ZenP^@ zxY8d(8cI73m4D>9p*--+5;c$laR2CWcEuv_g<};j0dFP?YNMCI5#b6I;IjRyz-9Z@ zfXnu)1DDHpvH=d+eof%A{aV0f`x!hVvNW>&+`wh~c@%Hw|7kvBFI152=L0U=&ktO- zUjVplzhDQa^_T4z>TuA1zvotK76zVR9swR7ugXV(ORU6z&#_L}ioZBG!aNfR;BoFa z1w6(br;$%k0~!KexJ~Vj0&zS3WzA&!m7s!bn;P)MacURTfwzuR9XEilKSA+ko2&h| z^(^IRwH@|03ZAOC!5zs!<*!${fiF2xmG=OD?qtQiz%yqjmBR;)eP=4}2mb!qiU)zq zOoV`6$!8n}o@O3Ng5y~pX&>;+a@BDZ_yHbJ4EPqF(Kzsl=csm4%$@wdaR+BCP(ju{ z4_p+p3_N~3Cnmtlm#B{Gojhs8dz7Qm=`e0hf+5z#CjX58Ozq0TqG!PEa#cvA7lga%LN^Rx?qB3Jb4Myas#?^Cs{XcWiJ+ z(teO_kH+o&CnNG}4r~8;QtAu>z-1;vz@uC~0=&R>3V7(Q@oN94!I5Em2zcLJYCw75 z(m@e;n#-4g_YJ6aDknhxU*&=|s1WB0b>Px*6L>wK*0=?{_cpbZ2K&1t|8L%|9By%N z{x9jd2l$*jRCzCO$q#(MB|q>3PfCIi0EZ+9LEw@fgn&za5C$&!K?FGG2T7w39FibJ zf%ozm$AC+I5C<;#K?1ns2PvCV{K@u^1R)I-BtOUiZ}5PIfY157TADoYNA6U-sBkLY|gLs2uq6~aGcU(cv9an)r#2wdwpH3G)d;c}SF|=82j}~yr58NlJ=$4t2YlI(o zg6#fcH1_*xS#~ zb^v&R%LkG32R5CK4-4 zPEqB3 zD;Q^V&P44Csv$S<3Ud$e5_2!`A?7}dTk$Vbnr4R|D&(05fM=KofftyEfESsEHE!>} zDmx;Y!wQBn^FH8JzPv_(H@JKZc%6A1cQbE{O5L%r{^5HouvFJ1gs!m zyG7pO?{Xmb@Kf)|<-z3-arInK@xV8SR5h{2%yX~kzN2$#@50uPM9gCp?J2)wC2EK^rceXw5b zDyehd2;4sc4~)R;9h}wETC13*1A52t5qOB-UBj6RkHBMx;&%Vq9aEMDB6?ESE=oH0 zYq6vAiYE0s?`yTgLg&__o%WkY)){06fAYc1r0#ZWnV!z&5jMM)He7i~2YFbF0KFY~ zsz58RRzp6D)*ROQ7(s32^oANEaQRdM+i`0b^)YtK>YwWA{8^e+L3h-&+Z3->p*{i+ zYu94Ed}IV36K>s0>lFg;v{z2&5$&3*bH8@Y?cmyNjm{(5HP_;o$jK$Ni>_WFGZJ^T zFVY?5bMq&fGiRm7AKKl@{lIb?lMn6o=5~`i8PWn#Z@f>tTfbAXGr7fc|CPkV1zY?dYfETh-h5BC8~Iz#wTbUM>RfC<1vj- z(s+D1D~WZ+Y6~lGLaU%+Uh$O1MgA>MTH{kxQTyMF#;0n0NVxT>{4~vx7YFg_8ZT&k zhQ^B;KV0J_jnCA0S>slSIoH*S=9r~bsA_z+#%mfsLgRIfAF1(%#^<(q(r9Xqd2NT$ z(zs9K#wlt+tRPox_^BE%JDkq{G|f?Q9ENea#;Y1X zL*q4#pQ-V>#?R7tL*pTf%lbDp$4ae2OXJ-dH-hb5uu9`@jjz_YN8@K}Jn7XO=V%U} z#?RHbU*lno2Q+@3#)BF^U*jRgllJzzKy!q(3TreT(fEZL@6-528jouHVvWZ%9&zTM z3dA)>k5(a}@k=$H(s-}N(;EMn#xolKxNvLzhcri@IOsL6@yj$`(D>yVFKYY>jh8fj zrN+y|?fA2{-&LBUqE)zB<5i7cqw$)?qZ+Ske67YCZJspxHAl1UFxF|jrSbI|H&(QF z!6!8C*7zqi?$LP6=Dh#Bn&UdHf=}buYuvB#8#Er!_>CG5YW&k04<$9nXEaAx<8h5g zG`>OOeHy=6<57)o)Od_}(pvjlG)G*k@HveqG=8hbQyRZb<7tiGuJMel*LV_%}2j)%aG8$4=Gq|NAvZT&wVa#uFOP zYdod#2Q{A7_%@Aagj@Olw>8I*IEX*2@w~>rqw#{q3mPwKe7nX=8s9-&%|HE8)*Ro} zDpWN7h{mfL|4)tAH2yt}*ERnAHcuK2%~5PSjHbqapz)T*f2eWewDvA|RO4=q@6@=* z=5+qn_Ipfoc(n?TYuu;tlE(cSe?sE{jsIBVL5=?(Xa1=`NOL@?RS0YRDUC-o{!@+j zX}qlQsK%dWZucM49J{m%ag9H#@r1^Irty@nbWlVzoI#YvebIIPL*$c>a&9d9J>n|dEfo&&W zw83Hm-CBX;$?n(erDP9i_HwefY4)jP@6zlu$=;*c-DJCFw+CR*WN*{#%gNrQ*;kXjN3;9Mb{)|kz_nyAAUjFZZO_2<1iG~XpC-Fs zvu`4MK(lWldz)t8M)oevzLV@dnms_aYfgIrcayzfPBv++w>^L_6X@0o+)H-9X5UBl zfM$P<>}{I;b+UJ9_Wfk<(d=zxyN+xR;9;^C9GPr`9R#|y0^cLMU$cKm_JC&pi0o~e z{bRCsY4%fO@6qgCWV`0J`};ZB3z8c6C4p|u{x#YCn*AHH2Q>RdvbSmWOJwiT?EfKq zk7n;7+cmE}fWMNRT%duy1iCf*4YK<+`)#rZH2Yn$w`ul2$lj&d{~~*jX1i9?0DSEM zj9ERL^eoW8cq-7X*^|lc*X*fe4`}w`WN*{#*<|n1?73v`(d-3eyXLnCuxNFX)<6S` zsX(`8A5V6_W-ldsK(m*Vy-l-EC3}};cWbh3svb zeH+=kH2Y4n_h|M2*{+4o0FqPgCa|ClrhJ*~Zq2@z?0(I@kL&@>{ulihF zq;={2D}eRGyEXe>vimjrKC%Zi`)g!x)9kO4y-Tz2 zCwq@(ZzJ1vT(aHa!vq!_*S2?%-L2W*BfDR-e@OO#X8(xnZJPaKvUh3rQ)KVa>|JEL zlE=3@{5gRIn*B?%yEXgQWcO?KZ^$0d>=()2rr9r%y-TzIhwMF?y@%|i>xA|I{z_nh zX744tTeIIFyI-^4CVN1$-z9sSX8(iiU7GzbviE4V>zv`G9#^0}fHCLL05p3%+1;8w zne6`D-s8+;Cl$w#QjMl#6dgI=@#c(^THV8&o880R?{^PBe3&u(?PmIEt$6jJqKe2;ZozM48%htP$rS2J_;emhK)MGVhwNXEd z*paHfWxL0N2XwAy5DcLRK56`Zr-#7OjZqMw3F;=J3 zcD&LxeaBHU!&?r|?tW%&GMl!h_m8WF?X!AhW_HgjbFUz6Ta|1*^zYb@PEXG#ANz*1QXi$7?jdMy4Vy(*rh4y+0^1C~QC zOw)7-HuuBK?(9$> zZr3z&Q*BrEKHdGj6X{uvttqvTpH+*Pncq4*Tc2PIucrl^J=VyCzj5Ic{-ceP8x;1p zj50Fsbj{1YxXY7uuQjs6W9KcU|GjnCo+|S1>6)|Dy;^nOqO}MfWh|@BZ=FKzE#1A& z%>JJC;{HFMy}eGq@9sL>I-BIupIu~ZX;7mU{51WZca_h`k4c>|-^lkgHW6PnFT2u6 z-85<{m3wd1@Od|Xr)Tf}Rl~3UbJg&;(0|-?-PPm1G0rrG&ofg!i;p{wI-Iw9c;1o5t&LUl9e#|(Pgp&C-N4l)>iCJqrUj1AXZb!(zFp)S zO}=N2a(uHaA7%X4xvnXV8)x|zX6s4rY^vpaz-siG7CDDwRLDKrxMbcL#)kBCqqlNf zq2x9X|B7MGd$G~A$Z2$xRqwx655M-z>fyb=qQTBGZhh^yqlWkXe$;T|87jAFQFiwx zW9eg4sN5f^+$*bx5Bz!caHDJV@M~j74<{R|{4_;=I%A413ZZ{l(|p+3G|JEudyhH) z3Hk_qdSexhln2^aLjJE(Ltmi|2UiatVRg8UI{YMcxQfoU>nOX!|FAl|fy&)X9e##7 zJZ;qQYiCiJE^D^tOMl6wd#n!6wWftS%!QwrMI9D4xt^B}pQ8@9A9c(29bF%9y-wjj zfjZp&k>K{iGv@R8F4yzc+1*K<6)wGX`}VHOTZLl+q*3m&Co3XBmdnTlM=3CcE_u+J% zoSFR#?X545F}7G@;ePqxGQGT0ZtF~2^|wt=^(3k6>!Xb=bVbSR?{e>mS(l_qN;vG_ zr-UXcm8Vf1Tyk^-ZIP>)Nwampw~s|VoVq3d*45pqYG%Jp9ksq@0glh zJ3rNP_elPssabPDs^`v;{I61d^4~)K6(-HrVWHvuU6YI*ce#w6uXJ^9KX}m0op6dd z%WX~35-O4FJ;gkFF3sC6nq=$B`1n5$=H`;aI?vZAcE|n4q}(^CjCob==~K*U$6r9@ z3acpAHyPOjYt-+CSw6!Ut@KY~+|s`t#+Gr^ z{_byuw)=LUGi)uWwU`%?py!I-uGzV#dQ8tKBYWe8xtD_G)#G}3aOdS#t}stp+N9Ha zZ(a9x+DEi`=Plkx_B&T}Z@0$8BE9q_YiwOz_Bc1K$vwQnoa^#>az9@|;~DSC{cD9e zJM?|3NAD14A76Lc_WUZ7_Q13qznwwzKkJx% zL06^elwwTV@yFa{r5lC}t0i4LyJG8Q1gs zKCdpeKfBY;s4`ZQ^UE`{#%p7SAEhr7(fsfDfQDY4XDp|*FVjUwgGAYgo|0V`TAJN` zl65-s7B`MCZoPoY&3ovu4QuBay_8R824A}HiTXNMcALjaeC92FXO)rtIhCo5N+o-? zCpY!f35c_?&b4CueeT3l);t|$E!MonR>MEtG^g~_^WDQgJ;yzK8u><3V*KrBFuR)@ zeudh2h&p(f>d?9@zMBWJa+cA1OINO8ol3M z8czJhWpt{;ftlHLsoB}hTaL)q51Y4i;8Urd@+f1=ej3aqP@efx)}zYqxiQuA7?*WX z+5IQ2EOjW4Rep{)yE$phvZG|r%~q65TTFkoaLazTampbJuTf>YH>P^-r*b&0H(6&k zDrL{;UW%GS&FYRHx=S%CCo`MGsr?Iu$Nz6?13a~NO*VS1hI~AwzZhdoQPVo^h6j08 zzi_Bo4IG)>yne1VtI4Ii;;Eh+=xoLxYD%qwFCS@7{{kvUv$7>d`@?=}RSG{z-+bsHJSxKC9QsE^NB8 zH19fN!+e*~+xSN4i7!pe_guIAuAAnW<8HW%&aiQF_lkMPc5RqXzZdp|OY=q>8|bsf z-ok?O?BCbY@89k}uY^}BJ6`H@Y5kW_8cD&`eSNBDF`eCLBQ^DqYhUL$p|$r>Il5mg znsgXZGdn-9JiEE225*iwdQ&tbbWfS-j?lKGICzEfrz`p7EI)1eEN%Jh2e+@?RL+}uG{L(uDmwY^ATF-5BVvI*TuZqr*BI29HseJ zjWU{sRp0Vk^(nxQAb*H>Hy!Lh(J64(XHz}XK3u@@?n<~T>zlghbnVoA>A%jWE6_7zD97x|e&_t$&sUpsXPiFS*z(T0tG2(pKQwHo z{m+ce{xdhc+C1g*W68Dmu$99%bcb56O;|bHn6`5Gu}!Y$FQDZ8hB2XA-|d=^-S^dj zo}@YP2Kq~iz5DJ}zlV-7dM7e}`Vyn}hNYnu^oLJ2Jb0)%R_wif)1Rh0nfm_Cr|+JYIwN*!Xhr2@V_D;waoN{4(bb-m{_vGX_7pl2 zS9fI_tH#sS*Sam5zW9rNW6SWxD~H{yE(^YP!OG#im#!T4cNr_(>n;oW$I|P~mzC)C z*4&zl%oC43$sFE$3JshZu5TJ=$Ko+G;7Wg}^$U92Vee@xhyQU_ZrerX0`rvI&n`0m zeEe$Dm~KttgcFRDAGqJx@QbB1FZYL5{I@&R^G4U_e|XQGp}`wgO!~$H=7iT@IVtz+ zi_O`t>crgMi_NQNUrOhex6bWyI=8p!+@{jGQQh={Tz|w|>e_ou?rRbA$L1}$OD-`_ zaDCCt4P0VAJn0wxD@(_Ie#)ieW*H|Pn>)J4Jn7u7w+{AZNsg?Me0LU&WE(};kw)(| z)=K<}PU!#gN^F{(t*@G#y^C_7qbAZy{GL{THr#8!rJ4ET%G`I)H_xB-C{4oSyb{k$ zqKTN4bqB|cN#+o<@#XQptvTmQH@BWdmKE%UPLru*pX zpXxd8y$|hf%`;7{7}VhzA5a9*ls5)^R! z&-t=zX#k@~@@E!ipQZtP@a_mFu$k@&XCArqolgJBO5dyj)Q-xU=cju9-dUjSU$P*( z@+`W*lRuZ~HJ7-)`On-_y%dv~f9BrqH5Vrr(d=5uM6?yk9sh)4C z5g(&VvQuE?=Tbf2paK+vJ63v(C;aa|e&=Oo!px1o!o1iua7ylqE6np;UwJq8@D*my zqVo?N%x&9rd27!EV`uFA&=d2_={L|5RK3)F)hJu{f-`p<{cdjVmFBEum6F;W^Ec9a z0A1c4f1x|B{@J17l~i#4X2s}ywxnGBbFZXVi`(V5DBmB5)v2+Qbze#OenYHG^)AwV zFDu`#?0PeH95aR@-f6U@oX?W;!Btk~IB)Uq>74UpZ~s)7I(9v_`h)qkwO1Q-%y;+C zHT-Mmo}xEC=a^jARpxQ7+JW5CtIP#UAE3(CXkW1sFiP)tcg@)Gr`xO%&)89+DY90% zi?oH#uxg}E$*y`QclTB1{BV^nidDKOR*m}6+3vui?7Ax#Wlg%7y@!_6n!^wIPd_HR zmfjoPO#XL2{*&$RP=k-rqP%&PIm`9-JGt>!n@bOy@y@}S2QGeU`vG!pA?F2Gn@g^# z&hI@Yn_6HDkD+l{O*be3F&;T4n?B!o;#V|A>#F)&x|6h5q)NB?H0GZW&zr_Fn>7?G z5eo@>U$I9I3bNtyKPyxdPJ^t*M z^fEW9GK;8;?SIIh{U)_%m7ixAZ`Ef$FnhgT{z+ASHkEI5YNuo6 z^GmbczLT=+;wNQSo=fj8jO2ger0iPq-@QNg(kJMwhu+RDz1HlW`bBE@gWFebw`Tsp z#k&fd-p<{9t+~kcr?+z7yVktOb@GASzpgb;IL+#&az=Jt^Nj3WlStR88`7Yvb#rPj z1Pu2VZ>iyai<-}6t~I@`!dtn4Ptr7xIdp^nqJsZhgJ0(cH(CwS=OEtP=`l0v`uzUf z{W0@cPxA^2+2OHsmR|lxSN8V(iy!}e%>0?@`rz%{{nwipCRJu>okP{kt}|R&^DC(y zYfAsOE^AG74nL%>dCIMJs)n=^I4isIK1$K49nIgg{cBv=b!k`j={c#M1#joBzrj2^ zP;@`IBs=cb?IpkIw%-_~$S=;Hb5=G_G2zdLR-8xn`E(phA$UFo*q?7O`{(9Owbdx9 z`^a}04IoFiRNk-7%dYsonY-pjGwX`IoqPL6^Mpmus2yj(M_;T{UQJW?oRMAo`Bcvp zYD&aUpZBnzro>9OFC{-sZIQ#HXh3+p`KFrMUo>;S{u z-pXBclX)&~s`uVd!+4&C^P$tt8}{j%x21Z{qe#&F>U1qXo$iBoq|!o1=K>=jAqh z&Rk~KUA9cgV>s1w*rDoLeyc9|$G(|+@pI<#xo=T9YhpLiP~N49UOvi_>%;9U_qM<1 z7AMSAms!I~TUD23S5l^Fohk=Odsvn~baHkr`F}_L|7}lf;IqEq4K;+vcnIenVhGp% zJvaMS9>UPcY6z5TK6t1hSbl2=E2ds;VuailVC3B8vHa?t3$tml6H;_eV1G?pf}+ z=bU@)z31L{C&gg-2UE7k_!9}d$6XDU9uWM&fEa})NtGnl?2fYTU1_ky`rjsxDN<7w zc8AiYNVTS@SzLHWwsRyra7**`#i&QXg6h2yOq2`K7~CpDT0jO-<$rkli|6Iwi)jzdFlmouScU3^E{(WJHt_%U6Tt z_HByKk`A)KmUJ&mis02;O2{0{{gnpqNv);8f>exAZSdC?f1&M-maHOgOWqJ4OW_B; z%7Ph^k+B&!m8G*JCb3SpXvO;o@U?DI&}?ZeyX>LRY-s{#tvGqjm6GM64=#I9kGWDE z{{pZq0LucEWo`{io@bDy@O%)_T*>TN3d!5xXDJ+1jcU)6lKrzmlMR||m1dHcB`@3G zQn;ZSO_?VJrk3ScvAQL1P<2aT$3V5g(>^q3#KI|{jBGThEbii9OP*_prLZW3E`igO zve4|%GMolrP9gleTuyI3FVu^Errb^l!PVHGzm^a%2KIQ?{eGkFuJ9< zrooazniwle!8j5T_zPutlu^2zFaDC_OWP7o*~9k zm>ol}t&qO0_zOsoYWF^d$u+fKDK)Mhj>PCQZh5t~rSNebLe8tkvk0R5RE)9|wy#TP zR!U7wFI~0L{$B}V)KnVgN+hvXzbGeHNwE_9`zk$MEsgJXx7=F%V=aYo^;A8uPc=OZ zi`4XRuD2m46p}qdCn`^lvlLFMPbb!(@*Y21>A(%eeXTS@YTX5rAhkH&HPO%jL+ahf zaL0Wf{&UWy87+6wYI{4yhV!%wVq?e`i{{{{t4KfQ6&ax>lX50cx+t{`tc(y**;3fR z(=xlBAtx9)La_t<**6&D!3aGtyA~>lz@I2j`QE`S%WSmdeH0G`#?yoKQiNx;hb3>M z2l{zsOFFuSOjEZ@ew4Zahpj|4u3nbHyIwSGgA~zJ^o~BwErmT>SSH07a;~E)p#f2q z2pgiR)u(k;bxgA4HE(GttYe@P8>I2ULN0qF?TyQ-C?Pg6OW}S-12;lW>5qMoB|2Z)S<_CZR&w4^iK-lb8PP>1z6oo#vrVY$CMmf=5yUEj28sm5m9HHX zS=}00@;WxQ6nZzYgd%$@M%@mOY#4gR%KcI`D&8cushY_xb_RL3n?gO!sL^KWT~po5 zR+@iJ*|!uhIf1XrwPqfbHWY_z4VE~SBeU2F!XiQA?mD!NeOjSc~yqzbPUUJpG~`@0?#7R@gKsLyU^*+otA0X zZmC*buVO3Z!d!2QyXBPLwluxfp_gK zD@E3sz2!b>ox8)Z^!q;P8uORwyHBKK?*hB6N-1Hhy8F?=3&67g9bCoGI=D>`o!xHL z)H--wD8$ym``Y@pN^9@il|RM8`jsm*_fsh`?D~&ZO22~X9hXl1)tO;R$u~YhP(F)k zAx?(mn*-?Dr_#&O1)-ZGEn(PSzJaws2+lc1Yu%z$GU0`JaTtt7*QH?xq@XDQ?Mhq? z$t6g!m7v2Ggcd|wu2c?+x6_M>k0`gdOr_7o0NE#2oo1!n(#9d-)u+Qn3e{lwwi^<| z&U`)VS*Gda68oBBTazYTmR!m6pyc9TrjD#YOeH?3X(`+sLG=zwk?iJWI(Zpu;)y>h zV-8AgJg`7?8;DgTBB~H8OJ}fUpGiM@3x=i8JX=Jbb42Q>(w436Y!i!J@%N5M?Hdd3 zWifOnw8wAZWB1{*q8sYWS&cq8DkYQ(s9IGO5M9t-$qz@R#!dp-#?#uLOUI-s&$dq2 zzeN3?HPjUUG4`BBV*(_M^o-29kyNF@XzXt@s7-qg;T+u(^S%07m=_J)1b^-Gzbl}X zUr5o<5nCIv)oJ9F#+uj{Aa;xAan*HmA@*v-MIp%&M7+3XX*A=jUEQb+?VXQF%}do^ z>H+$3ef=@1OXRaUc7y;`SoR(EgHR!vH%kpn{DPH+UZP%KN|tgQ=p*#2vnESn7Z-9l zE=9V2^}Ur6E+IKO@~jkCArjUROTWlanfe`fkj{E%!>_eUfhzp!yP8fT;nHtwy~{3lsaX1XmRPpfd+!Z|%)t(tvcl{MXkI$I z6+~C=X%!jKBVTq971-QCZGYB~#L^k=%F|M02b~s$G+Jk=)6$Z66n$lbL2bbRHdS4< z+Hi|(3e|A4FdNoz$?J?%i)I~@s-%c;+ZdBpZJMkyx$?Ir-3&+Fv-h)7r09Ctx~|uY z{x~c3D4(a!Xvb5CmR*oO zw<8J1E-LK=jZK!kt1gzpwXQVf2Psf4aF-wdy4$!lNHQs|E}Bd`E-)B2sA-UvP>{HeX5 zxKbJ1E5H?l;MabJoZYrM5xL9yno;_T*kRp&sY)W}T=-Orpz3X`5g_fRs-($%@b)iy&DM z;)$AX5|ijs8r?{+JJ66LQhks}Pork(%E_I$i`<#TrG_ErXLT{X=(ZGNPd4c%*e!2M zry@m6&}-+j=j2UVQk9F6H+A|=I&0^p&ypnE!KzzrgmZ>u<{c@uL78TXRd;DKbxXFc z2%ENLnwnO#-jR9**!&_3>oU8l?CZ0)f0y1d^)0f}=ikzu-=!ykdgT;}8nSMZ&$G1pZ>grp|9|nf^pj~D%6!jK{(b3B z(_8p{{tT^tAe}Td$M-d7Xv{=8(&+gGa`WaehlC1q5P4wO0B-s z?^ILi0vG>By6+D2+4BMXvDDMQ0Ol`1Ptk@pT`u75$5J0BsKcq~`eUhvO9eQ2X`(j# ziPX&7!AZB^fBT6PrPga(=C6MuRb>99zN?Cxh2O9c6`?E#M@*p# zk`sp3VI0{wYA3POaw>7GziGY1dj2~`b;e!_3qOTZ7)XE(F(sE^N{vGSUitWaOyr@w z^LL%FQs61E&*F<8z+f9#@mG{4vsf~7=4u)P=ubs7m$Q9rwF*cyHAdOWBAOwyp{785 zpI$`wW!9e>-IF}j8OV8T1)RlJz~-v-wvn|m-8ycij3T;ojfIifkIPE2k#)qn;W)** zu={M&35sxKliBp+w9b_^DW^SR5@g$2{l}F>Gr3^Pc20FGu(qOGyj_7|NZY4 zuE2(PmYUzbaay+`8{(f0nrt|9wrV@a9vW?`$O0GEW$sNy1k-PsVmfNyGR07k{fvX? zwoEHj(s-y-TK#4zc-S{f%jKcpECsH8v$R}X{bs4)YuhXx;cLiQr#W%9m{OK)sPIAC z{^N;CEXH)8iEnm=6 zFIa8tF}m-~3R#OU=ztGP>Z+5^p;P_#=o-ml-yZ!EN6f|cXt^}H?a|J@%qLifRBA^3 z_ULq97AlpGHOaA0dBl&k>0x6f)Zt(y?5^!hYRi`0T0m$E8O8Erdy*liTsq;DwhhaE z{;Y{9zR*fbPS6T}cJ28Um9sf{9cSD{MH&BAk!^GGhia^e>zU83)D-=W;tKG-W?TTv zEWh=-c)l%wZPz0?ETl`DO{vbz9m~4Pa}s0Gc*Xky{OdATmvm)mbn&@EAWL=XWddrO zKd%pDi=Chjk(C}b5F?_?vMwhfHVSU!0dv|CVjcane}Pcf@TYcaT_!9cn1y?mHryTv zkOB*(S;4Hf4rEJ!9Smk0rrf;>R?ozVauQqbLnk7!^*?k{X35zeZybxnmY@;!lo4GW zDw=59w!%N`iLF;FYl$s;MS`d_i0Kkr!J#a={asz}*T(JVWVLME3T#c)aCKR&1);1? z7dE{?W^ByHCdU}ufQvB_4^FHZT0IC&dRKQReG#`8--)w zf7af*y_~nhStMJ6fGhTLqK;6~0_ICa;S3vcI(upsaC8~!T#Fr3F@zNz0Zx~~Nr+%! zV#3=af~A(awgXdy!g4Y=d+^fxC0lp5bq5EHBZH&4wk_+k(AAK0T1TT-u$JL@_1P4U z(9kpez%l37T+Ei@2{#&Y_Wg$#G^I9cUXI#yPWWAIHme*Aonj}}d9Gq@*`0ootY;T{ ztZ*pDk>1giQ%Ort{egb}vrai>%%#itxI_t0dB)_r2-`a9f3!|n7R9Pb?BHSAU6;Mo zu?Ti3LUb%Do$?sGEroA*tKzNhuZf2{F>=Iv!7xV=%u$wRkFO;U*OwF?^P?WoEZn~= zR0yAqLvVF`X+boL42e8!rECn0*6H%8#}f@De|7f6wrmxgvXd=Cuq{hJMze8@AExdx z>^CP~x%DuO#G#y=`qVp?MY<}7@S;C>QPC=_gL7lqEhmDG*v7FPky%rZedS$7G&^K^ z99zh?9;Sf$n8Y;yoSt@I@$O$7v{EdF)z1%7dOS;ET@KUyc)%|n)!?rKUUbw-uN|bM z)|kcKNMKU}g>LSa@oSySOmD!Bi^*x{hOBw}XECF(EdCLBzmM=n;y~m$Gqg#^I2S`s zeVgX>mde}N&{7zfNM{eZ7J+i{bT+|8&bkZt3gEd8W!dqe9rI|?WxD&N&fEy0ra7~4ocHlRyQm_NBhGi{O45t-l3NUaX>Ag`t@yd37q$Rleyrmjud zE3ExN+R>EVm(Ed@c$VPS|5LoT|CyEgQKxv;n%z7=QOyAzr$ITOLjjdE=m!UAbqhcP zRH%F2ek)Z3bj^OvUt$kXKuh?`{==HTv;%xAT)&MCUi2x=PX@fN4gTvVR_X%y^-nbV zQJ<1~3g8ACd=B7$!rkBhMEDzC|M8$ksq7CnbiWeShBcK~_5I4=wrrimwtqq%?b++z z1u$>{I<`7+=jDXr>_HgKY0pBOAbo;y$}NNr0uopNZI_|TYL3H~XKTPMgXo|3>;;p{ zJ}Zr|^$E)-H1`FlAecg1umtz~y;iD%Zn0sn)`Wyl$kYMg!&D_1;En))e85U+Ht@Im zXmUq@2dZGVJA17362P}9v=@{=b|2mE1gKGiW&`>F2AHcstL>u^ouQrepQ_q*iwAfK zz;PP*lf87U3&1aEVE40%m6`#3TG1qXWiR#30P|b)qyr=y1Mp9<&uAOix`)nn1^7b^ z><{o1fPEFk{Uz2*V!ij!;O=1m>nECRNAI@M53tXu-L$j^>)sB%D;vtshVs=BId4*; zrSNv58c`XJ(A$%$Ev3@lSQg*bw;T0j-C<~DUQbp93;*4;`ehbRITKhFwKM5D!o8PS zr0LWyD>b&cPj7_=_YxxR(-brsupeN$QM9THwEJW?UF;3;92?jd;CBJ`*1#)wQ}hxG zwEx~NI?x|*FB^OX;6}hdvcYTbqQrrK@7klOHyQBtFmRF${^d^EItcI{8r<#54lBI? zcrjIZ1=0=MNfCnqE>Se;vH-pX6He2>m3GpK*8pB-14jV-A;94pc-zP1`#Qia6zbc9 zCAe-!ehkn;!dqIc*^3|3+@XM8+O6>(3h*gde~1RYw}VV?06cX!rT5i{-v-oOgD%`b zlZOLZ(?-0tz)C&B#6fOn%EbbkcEpYNii{vZZafmzZu==a-c#7ID2+ojd~=Qb<7 z4Dek#H3Y;Hx6`$^;IeKMGl(^C1MnXhW&Sn_c$-c3y}1>yN+R1MvOL$fic|02`NOx- z*0-7BakR1}D-h|K%}CF5LwaU3+vPh$hdqFos2` zWt)9)Gy$`Kt9~?W3>LrJK>V)k?(O+oOthpT@w#VBLJ})P4 zJji@+731C9+!@IaH*cXU<5@m)+e&jMFh7;;$UvM_MnG#EL?2IJADU)?$L~9+?L-#l zdw;V-%zK+PF~@JA$rIUNwrMk6o5+G(-$r>Iypl{6C$U_=!x-?7;_q|(g$h*;!71&t z!E|I2i>Vk0*3;o$D*EF|tbrUU2phc1!hI*`sv2vn>d9sr@h(dW)-x@%Grj@FYjO6z zXDFR`7rp%l5T)#(NAI%4@(E-dv5yPGPFPLqJefrr_kkc(bMn-!^x0%M)9LM64|@fm zqj2Tko3$Q#Z3{Iu13uaYw{Ei1V8EYj(%`eU(2l8q``X~E02e)FcDz{-PHH@9*5Vl(Z|0+*KxG%1Snt<(3A%pE*9E2FqwQhv}VPJ)h3az>4P2e0ns4tv40> zSh5Vhw0aGykm7R2u9NHv*3Joy!|-tH?l6( zeV>hIJ+{%h_gRwrrH!~@2)(P#Hs#LyEKy<)wo=3#mQiT}0GCBq!QVrw(p>UdzjzMb z^q8AZOFv)%a(iLV`w*tRvH<~Yt9VzT zm4q|Cb6Fho-$)sA*<6*4a&<2Am(;I|vRQpw8d_At_9~0pLMiiEqDL5f)PxzKIIJJMg=WlW>#BaZ9^DEqA-cey`1@nC zSZ_Wu?ZEf#_@2W?c|-$e0iNgM&$5{gX3UgzjO3)gAgr}}zIKf!#JiVIn^WIB%0 z`kR%cMQp5O^29A>alZ5ku|HK2b!zxzF^lw{34akUt%-M_vhaPn?U~{hvyL9(H8vyI zy@AqUo2dH|*3|S@9(;HcEn317O~2rK$4zv435$*DlBWqK-jcG%!Nxd*AmZT*z!UNC z8+;~iqNt^8a-uJIiZ_pnkz_fIV;%x;BjBDW7jFvP@4;~jQ^vYQdpk%N*Y$6@xRgx@ zxCyURX)%dkYomP^v{&_4@$N z_J%K6qcu2qEnUlHL2TX{GOfZa=qsFn3T$L4Jlm97uR;>|G4KX%q%o`5^6Eu-apL{$ z!1$}2t5>TEjhzHS!;KWXnhlo)0AT(5ya&QjFSLSPPRCyaulmGXP)3yaj1~CvL~U?JiT+ zY-2qo|FW!bI45r;4(Nm!$!j|z$s&le9sU=dr}^Kul^FQp@LN{W)*UQ>eYS#*i_f|% z>Dmq!tHZv|r4>8bhjM}8s+&@87t518DgaX$ zL?ks_*Q$cMEgOxw$9{R_{7`@qwr z8%~;%FO{glhJzEb{3z$v>X_on0mCeufsGFMjNBU<+Qvy^T}XYq z^&`4?kj-Yhm(kEeEX?ym;M!%&Uk2GmeuSekw-4j8&7woh?1DirTXoUZ?ZFlb zv>T*_|6N5T9Uuhd9%6Ci`Wbs{A{0H%CHEsNDvX1#n5BqYCxkxi?)zk^=DyRHX(sYm zPD_uVn|ze3b(7lQF&DkC)-pPIlJz}lGO=s_6e5hxkm^xG@-H5%dk9eI2^filez&on& z(weqA!~2wl=c;gDzxN^OZ2Yw}7)FWr{Owm-%=?;E3z`amC=9{;GxTwFyeq6V;|4dB z%v7bU8H!el)|R4;^eTfkMn$U?>?L^J;J9C<9A2-gND)DTQ7MiSqi%MsoP<^cGgT`P zO0Sg^wCWocO8=Z>ZVuIelOC!5Qi?5N3007&MscaeLTtq!lr64oEB>f#@zW(5lY+9v zzuAh9mM#8qiLjP0%__qDVQ(s}DPr;L(^UGdh}B@q61rc+>J7T;Wx4E9BmQSxel2=s zNR5r@*A`o;gtXD*GNx*x{2(*zZ4XzR#c(^C0r!vLzG+w7gR_Af8mxw1QtW)7Y&)N` z;3K{drceeWCDi>is~sxp;ML=Q#>F>+uc5|<^lV!l2v_-A7SRe+~_^7GUua;s1|c*T@@RsIqYB zug&mwG;|ia*@vp1WAUb*SWRv4p|0oHPWf)0XH}~39gFe!6Ol|r>$~{-eHpd=j`cE~ z$M^4+(Yo(o$>YoD!gnmubwA3)z(}{xvFgX=e`<+ojgc>@CGdG;E!1e0=} zEfqp`{hlqX+7v3-6_H%>x40Yxmx0{Rp-10iIT*f-MqOaN0xE%hMf{0@Knz?6#F)7I z&;0aOxhea~D?_ zJeh8=2!5_oyhSwM6?YE~!F%TjhefWfnpj+)Tyn*8qYykBlABoiEQB}W<|#oFDsV10 zu!I_b2f8}4VPhD|Qi@Yb3>dr&A>NjP1=iYRC$0ez)$itb%XeQ$IpQ5PBpr%w;+F^_ zB|3hQMK;IXT=AAK0L1SvK*E%b_izz4B({j*3-&Hri@!YltrH8>ov=CXo6gHdZYR@^ z>Rn=yQ>LMoU*VzR78QLn#7!#truhFqoASm2oAgk__xA4)c7d)Xkx~=QOAS@tUn=f_ z6H*IZ(d|pD6*I?Ey<+CW4lba!#jKxrUSG_bOff)|dzFJ8+Jm%SY+)6>*t^iY|BnUS z?4m;KG4}5eJI*0CFM{?5TxL=1(;S+68NGB@4sE^6BG{%JI(M0^V|nvw@)b6sT?s0W z!=E@!vC_lv)@5AJnl&H!6+Ba+|}n;Ab41YIT@?_?abPsu1X4|yo2Kpud(VqCbt#%1F!bbk?C z+!oN*TL>s@0Uf`^K4Yim)7;yL#nUac?l!9xT7Xs-4D`g6*>Pg76NuXlz4FEHlQejM zWWDOOx7lWvKA)EU#xAn3MKs|K0_~P;e38GVlstx#aM|g`A-GuP6D$P9rKgYZH*tM6n)o}*W1B4$c9-2`?=B>d zKaeVML2V-zQraJEf`0{zmUPPugO?!b*5;AbFAd&9BmZFCg6;xSK%(Jn`qW&~JgZ;K zLQ4OWCAOVeI1Ds0RcdqR_6y^_wi4HEzhyZ87&v?X(k@(}&=%ZWly6@S)Sq#H4 z%~9#Ra4zk83}X!X zPzig&PBQr@+=VvZWX;)5%dU7{=u-9c`(@Wd2j-ExD{mTm@O{C?JHO3rtka=35sYsb zF;Q*R$l~>K|I)xLy7T!tG|H7vXP9d|aODe4uK>T#Jeu#u<12O+v=I3+1}#d?Vs%Ux zz`4~tdg{j0Sio#bbLVwUT92cN?z{!NIh*#m^K^D@Hn~^eSDMZe)8iLwLRA3|UD1y= zOb>WyMw#J!nB~S1gXM?2m_7=eziV24Ri}y7^EcFPvhmhzim1q=T*UM`v|>%_QIU5_ zPeA4WK%8ZmmE7ai^D~2z8wdYoc*}rWN{67S56~Pets9JW!Gsd9fhapZ@$I1M=7pv{vaDJ znD6s}!3t-PyDz5MZXeJ^Up^w>$$M76+jATlqLTMCVW!Mb2K({Zk|_(o>2v75KU!M} z%tp^4Qvi>kp4IqBmOh781ORXzR4rA&B38{-wgzSHbCe4K+?ScMpz`Un>3$&eFlIJI z)!>51K<9$@1&H23ZXUtIc)!<2T)r{#@KQSTcg3r$QOP@~e zVZ4Wjf4C*9OSmO(7B28P7EW)5@fyr6i{=VgK)B^xM!4m{>~M?!iEz3X#v8IL(R;L6YN5F>u?_$9?mbZ;j<{c7Vm3%b(+<$+br5qi_d2@v#4zZ z?-x_HYV~wR3cOxyLNCM=IhXm)(Q+tW`46Yj=?EUd?oX#j5j=xko=)ktc{^w6*VN{b zZ0|HWS({&ShJ8|phq8C3(ZxFasp;}mIPXll63GuR|Cu5VG+S-7?P@`Xs?dcpGIPyp_OP zx$i=+5I4wuoJENZc)TeIjPkN*L<8Qd_U_4=hP+YsZyNf&0e_XPG*kD67~5j9wA9od z5C?<#?#W_9u_X&nP);Or>?IzbPU>FbOF-CDn}pQ2DICIY3hi#n^V#jm zG@u!;AD9iJX2Yo2Gt{#j;8K8Gdqr%M{MCrIHRFxT!8nVT^lcctId9_n0%Q@sOhvv( za`bA>N3i*m>3DPaYu039EqGt{2C8epCwO!cN<$a8Gzr^`)97Xk-q5>D^?A*k;N(*i zN=V`{u7`kCTQDx3;^s}0l6Xh9Xc8Sy;x#H{OXsmd>}Wncaw7ei#M=za#-g!=ACfH? z>9VEbrs^j%H^XF#=MVHUXEcSB2F!Q`o&k6hz+B)O4mGnZOhcUT!}`k6TVaZT>?MZZD zIP!_P$vl&}PNETSa6hWnioeEgOr$%*co5~b;_cbViFC6SU&q!?r1>d)8k;_md|UI$ zY~VzSP35t4v^5{XTBr~6ng2w(I0$UMPvvj3zb8<78$N@bQ9mQ-aT`>$eFF7ui^6%f z!iw!sID7()Xb0XM)z1jUzdiSt*yHgO{{rt_A8Hb+U?EBBCr@q;wMqF?>zgy?Prxmp z7^g8G%UOkSc{P5nsLez=@B*xRVm#e{0UO^3#%pcwGm*A-;C>A=n`>-T?X&#V&5}#9 z;>{W3z)Ej{Js`^k>})&y6xVo~oW{qnIbfN_C$Klh)2I$SzI#6#>nB1Cq-%;XqY@Tm zuwW);1rq8KpIlehT3mrr4fu9kVeOY~b-jbS(#F%H4yY>{b#&xyS-^PO*O9MaeJ4<_ zP8gOij-&ieXx6E5TC?7S&R*1-Ri>(z$t9`H%o%gQT3^)(kmUk)y{#c<|2QQ+oi~-F z;dD5ady%;_k4}5V#`hl~Q`i5{rmo2)a9ha>-Tjy#YFX1L}wd0G5gdR2xSJy6|=lp;@by&gu2GHG30a_OLw{=-n}!1(z{`lsxy|Rb;Cqs$~ZdLjiEqZRa4N4U}5LA(-u*`2>BO>h(_FZbY$C6?Qq7WCw` z*k@yDUr$U(-Nw+5*uQTTci+kRK zZ(YVd+xT}VsW(q?-!K~dXBtX!XHwtSjMeGM>)bOIaT;z_WRKHp`kOO?1b-t^AhtN& z7xfDq#A*7uH($t1?MUkS?C^8m3ZiqQ!FzVLJvTii(>&ut2&ZCv?{dfdt z@4Zcv2VlCk?QL2oKF5!ulLL5H=XUYg=8V>mLC{BWRuPq9Y@7(dy{@e` zQf{tmAT1uqyRh`P>E=M#@c1YS7=+<9;%%Be2yRv7Z7~?kXSYY;>T+J4K75rA6G)F< z1#s6WN*~N;v-zX6f#;9G7+nRO@J3k@K%EHfMY_s%$GN;#sv0aBC-H6cru>FJQ9yH0nrt9kKktNZR-Mvq~Ab z%$zaHiQTcc97<_66iVq1WeBAl0>G}68uZ>!-kL3Xi;fS4QmVd1kA^}iBi<59n8rH2 zC7Lvu#k?ijJ(*R)^BV~FzmKHB!}%!bG`;mI`q1s+JXP8+z6VmL5xj%6y7apX?H|E= zR49@NVKincgt;?J$)C!9;c@}Xm6QeV@%oZSvthz;Uio=L@jArowDkh_r5iI4 z#jCub#Lnc481L{p)~U-~LX{iu^Tx8=eu$XpwUh%Xc`ol$*$q%Jk{E7GJahatt8!_T zi9LVktq z9ZZuK@oCKjv1CwZCE3iZeez-%%;fxV4|7I)2%u*)Yp`nDY=c==ni2PrnCD<6V=?!T z*s(!0Uf$W)bBMuAFf&^}p+QO88i&jJH?CkAN{M9>&;XeQw!p86b4 zW{sm=El0uW1}OES)Uk6i%k;@dSclUfy7m!5tIw;7$8yobP7hK7R`4js8V#bhx%?ut z4y1@xSbpgU1#>ZpHM!@p&L18K)vbR^M&wY(Wl zUQx|Fp2sE(qT_iyp!VBfa1T+ibR6cALBj3u_^{3hSJWXB$Iw~H+Yfz=b zZf^86pYLYF`qS=BynEtLnW*#Uik4N=As6Hma@|1LDwK(+|2<;z zV>~t}8qZ?7SzHMUHlU+p=et(*~nUAUZ9e6optYqmhfPA;Wm)!a*Nn3cn z#8za|&8@s`qPGxaI<6F4BUx6V=Z6R(@GKO(4MME0DOqr>`$mD&O5g%d=}&{V@t~^K zet13t+MhMr3YoNM8`6`t1Rlzk^`~>&_?UPjo=b%R{dhD$Tz9WdtU&(+d`jVHv$PwvHfMYc=IBNR_L1Wrm8F@>@M}_9CmX|CqM2C5*lT|-L#$#3 zVfyUi#IRjIO5BNId|4(9-pM=Znps@7nO8ylBPz95Bm!5Uy_v-(y0w#ML}oToryt_i zapB0>yr79i;7ceMpUfPmMg;3CGFz+bGu zMI93A5Hhvzr?w#_Ow{4^AL_uUItX(2ilIuQe0uoJ(2Hl0k= z>14jfyWqz(%7F}#FPqvlgQEuR#enm zBTPQb`>;;0C@T&N^|kCniAVS~W(3=#+&91qCPFL*QF5_sCgD@4qog;bABDPpu)~GA z1l*>sZ+j~jk8-^4HU@1jgf!E7Y0@0RrzVZLkXMx7!Q-Ny_#KQ5h1{F7C%u#dU-DSl z@28$(RK}_pt6lsyt2P>=%w?x3l(N6z-b&+>+{{?g%LIY|x?90iQ7JCsam)pw8QC^Y zerK>3@?H-m{S3b*`*!GVV<@7)V@;N}-D&cBaxi^(U3Q_7=lMg8*5IPN`MsEDr-DY< zY3oaPL$I5eXZMl=dO-e=UyXIBXp5f8w5|?`vL9)5ZMrJySFsxM{V~G*j*xk%_>$|Ioz1BeBap_BibZ`!3stzdbF@MNLbyT9B@P3jYn)6f; zJ?W?sy@t<>4%(8Y*or01nNEZyP0+4XIhC_99n_f@CEw@KRK(>QAqP5Wban9QmFAH6 zCL~@DUaG_jB!-oirs=4YT|j*W6hhRF_-yoogL)FEPk^IFo#`rv%e*V#-@I(B&!g~V zNC6S59-MsQ@&}UK5=<#1TMki%B+4<8WT2p1 za#N+Kkz61JeE^`S{eBBfY@0i3KaSepX{oGeBHxsP+-*psfz(fjv=vDAlC+i|Z6=?W z*!UK-qJ`X)U1&xZTFBkyRA5tP8>E!FB*9k_N*{B?W0-gpno-Us$yrjRrGmFuexq@{ zsec2x2klRm`}hpil}msb4APuP0r#V#6VR(?3U)^_TgjVQCoH^EWE|dZMo+gOfc>2! zf5$#;Mkia#VQgGe`m?pXmBlqvR;S7n7;Dj-g4)S*+3=>cwVm9z>XxPmPNM!-&8I^q z8I}!iLP722q4Jexq7{db63%Tek7GDA3G@JJ@Pa&qEpJ9EUXUZ)*Ei7=`AZWz`2v_1 zHc`^jWF!pt17L5I1mg(dCpN}u#tSY{RHdUl&~HIG7#SKyB<<`dU-exlFc5AGA&%un zt0uIylN{i_4w%A%R~yp^4`X%Zw@&gu65HCCVqb@ht}n{zl+gvPpVL?w(?wpFG!99q?A8 zvt*gf851Cf9aqef_cfxS8FCc+xDjpr8e3Qe8FDyFXhi2SAWYRp^e96fz)BLSZ&y6u zO{Axm|7bWR<8KbZ>O5N3W*_+!R%%kfgw?7%AO8f z+la!t$!V-jBO1|74oeHSweBauGYky9zWK)*@^G%L|XllJcFG}q`5u8cbAQCSHTx^`Txlm;VTvM>^GhG zZcC&^-Q~V)jmG!IX*Rwg{~x}X6E}C_I|+P5$XrazyUWqEu!mfijkL+$*;dDIp!v_T zV{+`~RL2X66x$QBx3KXIwDH~d|KaOt&Nv4;yZ(fS`XqFZ!ma< z91EFaFa)0~X2_-`SFnf|xYX|I{N3rk7)v4A#R z1<~to$^GQM^|TdE#h%^faB zrH!#Yd!sqIHPz5q){-HbsG5kdWKE; zAWY&%W7VZ`4H`KHQ_Whjv~>(j6c|hCcQD^s{(`ZQQfDk?c5G>kMrnzmr{m;dvAJ69 zEE$(jp$q1+QZ#$LNO(RjI&d%mhIuK08DTKhhSA!C-U=jI{-n z=PdcCF=#B{0{3zqD}7ZPxV9z86yRn?X%%|Tm1W7jD=2+<}#W&0v| z7=8yaf`S&yC)uyH=+0ufLun0$fHLA`1(`EG0Y|-f|J1V8ULal`pbaYvG3<zFA)^W=%%PlBMb{og2jIw^BY`1J0x=CQwsMW_381lrQ02*RSD} zo-6x3gK|hi2?ffJ;WRB*9>o^aRPN`>Q&b;O*@f8HfxYn6)Fx;cs@Cgyb4{C`Ljq~j zYB{mgM&K`al-dZiFFMg$?6ilfliwQoPGh@$o$3v5Zq9IZqHS-d1@1uFvRZENyqdE> z{Ts0LQpeb-4^>yzuazZeM)MMt3LLMGjiac2(-&q!;bq zu_KcnMEU#W!Bd8Svr1R&R(g_bpuH^9y|k<^%3^dACj9{B9W*CFRJ$n%MFnZeDn zTPve^pUN+}uf&6xh5ZyrcRrP0mkUDULa6rv`6qU*hSKz)yqh!sK>G7DIX2$EI^>YHRgTG0>tqFagfL>|0uo-cw2!7oc)1H#t}JRid`iDtwDIiK^QK|@SKMF zb8AYLR|g@72Ap%%DC%>0DEl}-S@b#bz^temP5VNg%nGUzJBCpsx0;f2Ox}S_mTGkW zOF1lKel?vc)-a0+)eCXHLb-P0fLSD4*%$UQ)Hn#I9ZF9jpk^~*g6=>y8hTvr&9ZCJ z7sutp>~w%K`-D7-GmAexJt>F9_Vlwc#`M~72)`oW4*~E}m$0RH=kY2SiK(}Mz3Z=} ze}fGP7OfHo*N08+`ReHL9PC6t#ZC{Hzdv0mLPE2WKY5%&-DmZ*$!->d6K$rQ7O)aO z>U#>bcl?Ch!SxMpmR)*sJYPmr^rE-2lLL0aPq}bPPLtRaKPBRftRQ7nSGjafep&Lk z2sT1h?eUr5Lv7C^tGdHaYz_G;htA8MvK;P%{uXx_i@3W#Vp{L!LrFg&5A=e!a`Gp6 zKIehnw*8xXUh4i$3p(^f9;7tBBG+NO56Z;m4omP_IN6w@oWCkRme?6D3gX77Mc0vY znyYZaNT6l_;aSQt9PfU$7qb<2&u2HOga{Rcum;fGiF=q^fz#+Q1#u_2K zm}?YAE8pC~mO?3Ua*WEvPApP{WNM3SI3N2qb&9(Z191gPXe35vgRGjBp&B#hUAC#6>u+ROo8#8XHny=(2zvst-dT zDS>^2&ruC@S-N~TifVylFvL?kH)Ab!%9TdAfyWV7TIXi$+RBN?5g7ABCmvrz3L6j0 zjqf!6;#C`izxnhES8D2RoaxM_HS#09o!BhXvDxj!<_%Y36^t`l8f*(*k^MlG*^(w+ zw!MjB1EUuB+VRA~_*IQ>wrJuP6^t)T5kMiI=-9siSsY923?%h6Asy_Z4c5LK*mpKq zt8!pPHdxbgU|+gh!_^8C$^m|6Ba8-YiW&KzS3K~N)K3+SEgM|MPY;D64Ws5}(c{(U zTtACc5xH9XGgd;9x8qsqQpt!s%BQfXhcT!u3#2*9u&_VdS=gTGkcY7kb91Gj%EqSb zkqh;zY|NmM-o`44xY%4+0Jl}BpImh^IbR$@3V{523-oeT9V8o`~oi;aKneJ&Ul-S+s)S;?zXepCJWtoVG(Z`9&M=mx24#g|Csu~wbrNqT$ zi3j;%?F(eR1d(>);&?^zHX8B1p-DO5WBl2{#gI@&2jNIsggSBQZ?cJCNTBchj4|%* zP+&j;_7@lO@HhHJhG_cK^oV?F0`jTgBRTPDWm3}pjg?umQvEyCUDKQ~O0d?YhISb3 z`cJTYeFkCukiRj6_5>IQxlaX1ND=&eDdcc-Ml&al6OA;uy3s<`Fr$airCB6caud`~ zyCIAMKH-VZ38VkxYI8>HFYJ@rCgpf~{p{ZbJa412kSHoCQD$Bvp zu#5<)b#boGiGw2BL@+d@DM7}ZvJ67XGB}E*ZYw7SQ|$~w8d8s7;|pn-C=fb)3dGz5 zLy28pu{$XmE5WqlQ*YW-tT+Rl826Huo59BGs#^(sW=Pc0A?t@p`$AEdP9NWLdutLE zmoTHrK^#(+co1G|YwJWj!%iHMNUducm-7b9N?MR7dx;@L6-DjcJpV`% z(juVJix6Yyg7~^V+}J8&2dWVOf9m<+f6o@4_EN&zp$w7F$z*Mjz}6Ro$MHaCtcL>lju(iWGc6?;TN zNPWF0BwM}3aa1qL_&R3&=%qN-Q;lMlb65H_$~aS=Dat|~x`t8Tr7rGts4n)RMs{$i z=!!sI5Q?-eb(tiG(Cxa$3KCx5u4{~w(*=n(IVGHN=@_kodPWyc4_@;v~{*`b+k^v#>H59?yXXy?F4j#U|qj0J;O8@QIi zs%(ojE|KK6K&0Z2FiQ?xY4V_;bFv3z#Tj?{4heN`ukv3<+ zfW8F8&{k=p>U+?@N=0Hoe^B4pN&W%_&KoIND6?;*g#I68R~{eJ_4eo9nY##Li_jpF zh#&}pAc(QoAc%b*qNsf-}Rscg{J_^L?K4oaLV7Ip<0kCquyQL@837e9w0}5xQC>@y1CBi=-}vl61+iwyqOd){`n71b4#h>3%De@nUvS` z5@>k?m>ULP_`>J*zD3-3XfQk=!Kt^sZtTbLO6-<@3eb>*td4lnq)qB0)Uu(YxUWQW z=~Yo2ewPlnl$t5oHfNK}l)H4NrSzNl`9E|mMM?^JSK};~_3T|rXeGUc61>q$`cCpT z$!z$K@2pdb5Q;atTcC|6Z{8`OdaWIg_`=#qzX(h+>aI_2C*e3xEhO!k?ud3o;Sc$j z+8^!5F=x)kQD%Lz9~uu*6joq>`Pyx*u(ECLrnJ)~JtmgCO`)Bo z7>5H18YTg=xUXMlDMt|VZ}}p+N-=`C_7gdOKh!-w-%L*!F2!0$;=HZCDrS`PvwA5QUc23(vl1b04e9Lq6V;afjIN)f9b z{F6(*TvimG#s5G-@k9?ZgAJG&Y`%#Cb4V@8|F*q^&p8+kR80PZb}y2r&__e0Y2kim z;H@e+bFo7gZ&hvnoeJO*2pg`bEr4vQPN~F@>hx4k<+PT^uWQ6(k2JY&2|!1E1#|rYO{Xywp$3zoF;e z<3xFXG+wGKPPjo=$HS&?Ybn#kCD&>31Zia2vp00p)CLT{z+oCq7@I~@&M6s6NqXf& z4UL6weMcx_(z0om0EcVuwqumg8a{UYCQ7klr|UF#A{xfzU+LIHDaO^^5OxjB?44i& zJWv?C6S#K@u?TbBp!i8rqFClS4Vfgxi8XG};z^kOHoif}CgEjK<_6_YlHy&mA#eNt zL!P6uCoKnjrf!@$T&SNmSxShxe4TrITb5h!XeXU)Hcwd>-U{5#%c;&oIoEW3&R(Yv zCQGfG-Vpq{^+dNEWJT<*VT!QWBIF%_v&C(0nc7Z~nzk<;3sO4p`H z5v~CS{wW0o#6iyLp0wK#7F8I%=iP_ z4&FQMaA4A7!ABiUoBnT>Jq4!6EKDy!xK=k|*>|T))kEvDWwF}8IgYF^L9ww%^1wfE(y`D6*t~yBfSDI#q-MYWhC?hO!t{$@cS%}TIXp4fwuHh3e(%xz} zqHo|7jMak=eVVqiwZ@a@_=P6S#Csv8SwZ3!c0`e$q0zZcc!gJb4%O zNNQIYyVjGJXT&a@gXw_(XWBYPYFy~IgbI)=cvNnNxqMKH-{%X^JFoslYla!-j&$D7 zT4l+F>oJv^E4k+dZt&@f(&j0q4-`C-MjZ~MbuiMh?~~TbNZWOvw5CSd*88M2(9-6G zWo@`mV!Xk)=00iFjI?L(lUCVCTYR6i@!Y>s6G=^`*exYMeOUuLySIIRW@A5CN(v7Phk zfT3Sk>~k)V28c;N(Xs^?AdUiUy(RFez~)W~y1YQj7PGF>`h`;Kp1DF)alOWR^`~8{ zxmcE|0!Ie$aUC>kZdru6cH2N(_YhVz@LspM%Va*c!uW41llk#gN?3$d)niv_%p#0! zMqZ^Xe)hRasTJiIDzR9aJ+Dxzzo^uORXu5}ZLrjxR}HD4J@E!4wG}cG5Xak&Tk)Td zK__z<|Gxw;AA#1|A{>!Om=n^SDdx z;K?f>#Q*kCcZn3yXe6gCKpMtwK2F2`W-JU@zlSvQ0Qy_NW12gNquf@w*{=UpI<`cL zOp69JCOz@x%q`%yLgpG!@kD3<(#$D#1^f^A*Fj1-gaiAV)r8DaI!;zs71++_;kz)%n*xf$#GQqSq#PRTxQxh zaz86g5ils$e~A460vt-mdgT&ARz(ioT5h);p`JXXmurqRZ`KU=VAy>hl* zw=sXgSY-s39S1-gla|M^>o3#QmC|l;%w<}?N{SE%8p6-7lEM;Ve>BR9)kj6|4xwVu zwsC!=Ygt2Dr^^(Xf#s39muW%NVPBm8&mIMe#}DHoPAE#g1?p5oR^>s&7wcug4Z-G{(?xApDV zE}pcW7QE-aCwT)3z4!NQ*^brGP`M<|l`bsFoRYR)FjuZ-u9=>^$V(KuNs6Zt8>NOF zbGcjQEkhVL!zhRhvmh>Z^Q2vXqRee}-!TX?Ef++~{jeYGcI6`FZ^Y~7*hO0QqBOL+ zTUX+-2PrYtleg<4D>3-rsvb@@& zWhzR0J0Me9WzI0)O$!IWrO*Q2%>)PS7=Yu3udGDuZzS~C+%DpwHzBgRff@1897Byb+Ya4 z5$U)!10qdY?x}viK#O0J(p-54-Xz95{t$S_+umL{!jrbbg7?t{irIk`0#vX8JFtRN z#QM&n)^|MSNgHb6-wZvps^u(6-|mpwhgU#^w{0c;!j$w%nS5bN%mqr`DMf^|jTns?gM~luyF$gv zWl6*0{{n$`n=R7@tCsVIW_mAH%1i-~_oQKQgxTVqzN1Z9QhbS#oQAmb;M3n8j#s3o z!fhOFudEkRwaOYx@$YEeD^g@gZB9enmJ4+36=|{9FixRXuSt)@ zeef*=pRwQeo@vX|=VlYYz*qdV##_sb8~+{6eN9RU?{B0<-@6w`>-Qbyy(X;-Sqz-k z@au^Bj;8F!5QO~n&Tb5#%lqltZgjUsPgk}?P)Iin3SAtoAM4+=J@*_P3Of&Fl00jvbqg^JmrkxHt#n zcJH^WS{z-@#{BZ zeI4{L?x8g3?zUh!M{?R9B=!hw9? zpf>HtlLy@RRFr;LrER6m-H0pf(ko@g`04NgDYER=;P{J`GQ<6J74hZQ1;?Wmgh0m% zwD*`)u9zEt`2|v13yS^ylzI>^jx-}WAO$5pvj|G1%qI}$7svj5T6a+DP_`Dr!IwET z&Zlb!rR3yPj^8F^oIrLF|H?{hWk*}2j=roJf8eM zjMX~i^B{d$NKX(kXpe7c(;L#{hBtWrzyppAKsASs9t=44V`}4tyX2a0z;F?BEd1va z?%r>x%^@i!y7>riL6|i<&l)R^U7Wt1=|B_lEu907 z`2IIka7a2=FP`I(tF7B~{v;0L|7UE4wnFAEzSim_uC?NNiC#iEA`KJLNZ2ctqo4&3J`dsgPOiJl#AZtrYKlO^e@@ z_KA1Svv!z;9F;E5TYR2X5;7O^6ROO|ldD)Qvv4j7nR5_VSomV*uMqNxnU3r~5u6S) zTtRvnGacFe9$|9}m6hc#mQC0^zo4B~;R4_bgv{Z=U{GvGa2N^>K$w}I$CEE7`Db=6 zP5ec!Le7&?MRFeJ{qXbnyq`2*>~Y?gf1GD?rOwmJcj2yC^DU_+=5}9eAzE`na*EG= zO%d zbBwc0Y;(>Bh#i9H_=--vFP#Xf_Z6!cmUZAO-^vf9G(qhC6&;Jj6&vR#+tqa+Ne-bS z^*ABbpd0J#jv?Nlolz8BHZNQ7Q*@Wqp61YS#6hfk1KFhK;%%OGa-k2Efs^Ks$p3jd3oDa^@ozJEGq~T}5&=#vmcycojTz&_TfrtyVM9}or zX|mRy^@V;RwXvtX`MI%#Viz*`$}TUS!-ncUL%c$?@H1l_0sr@c_5v^Tq8+g7d6_S0 z{)Q|g49J2U--`n3tXx<`6b>FL(rO#C{D%7{&SE+$es#UJuOFWnj^eN%Sy=09LwKhQ}UfTjY`U~j#&tyW#p)e15KVFUyKNo z$L@u&+D^GOeO5;9V$Vf9IBQVq=ZG1#eam-qcER9eO2R4mAKWM7O3;hG`gf!idxXa?J_W5FH@H z<}OPYE6LNSc%2}CoT31i;Eizu46sH3puP!^QY8F9qbFQO;MnM~2+KJ|X_0cGYo~$Np7FXp z1YS4XJO@9EVHUhCr|5K~yv#Mlz$?vo_{6|}>emrV!Z`O`$AUKw`K=25dK!4YA{{q3 z|2H1KE3h4SB`tVePf=u)JU1lTz&rjnMOKq5)UukZIkHzCr};o;s?N2((kc2ON={4@ z4R$Z9)9@kGX$WZO(FV@Rd^oyq==G+rj&hg|~#siz_#3 zSC?D5uAR`$u!8e}9SBp<1DgYOAQobW?PUw_MOG+;eFKP zg`Jw$lzX_U8~Hj3!iTk!BgT{VE%;0ua671ag3i{IM~aV~q?B5+%YO4Mygon08{ba1~&?0aH1n5=> zqwDeVGve73G^@6pS$Htr#?w>0!1yV8!?dT_PdnhqV%HI~&3?Kq5SiBI4Wn*#jIYUKMz^`S>YJR{$P?TtaoDhyKg!6i*87DaOx%HckL z3wgWXs0R}Ll09#V+(oE(fLV;;gXw!Y?T9f(pqfrO!yXS3yyhPvcSmggU31FU#QsMp zzct>-t|R^5{9&5qKsHrxSLV2kD2ofYuP$NQo)`eVHI zdjl2)ADFtYJwgR-ZWTZv1WDNg#g+>%TdFKyd2OMGVMCYL`F_~$0$&>dk(+-8_(L`stLrV{H zKzBjnUGPhXX?1%!RlISSF0_~1h_&COxDIk+2v-w!F33Ji!#l_mD&1nfllIKkaPAXq zwwYTm+BHRO?kM`HgIp#2H%JKugLi>lKl==AzCVoH66KiiORT{HeDDCajgE@Y7OtN= zOno}aO_H1la#7~!PrH_J4Eo?!7YDZBOpk;POl!-DppzZtTH>K2bgiQtA?`auA&<%_ zV$xx9J&G!~{4gzkRGuEb7S`}q6%Ki;w$?wqfDAhhQ`t^(+kjkWr67ajI-puuUWJ@s zxqkpglk2QR%R9-*0bWm0UiJ-p-opE($?K^^e|M6bi8YQ;l1q*csmwN6?z}zbFpY7^ ziK29vHo4^CNnxz>M6I+mogugvmuA(9w#n>f;6Xa?(R&OpOLiKVeTb4e%PEvIR4!vE zmo4hbWt#>afy)hQLOFNPD0;N6T(%9$9qBAL5Dy)uYn|n|kUb#e>h;editHk@$GWo% z2L5YUH}-4G&^}&~Hs9{aTZK5?<^5=PNpZBsP?9!wk)5<+kX&Y%Ub-04S7s{*lyTs? zfYV?MRwmR`2DG)7pjz`f4IHio_-eACAuOEZf`s=!M5$e2yk3WCepflk(E)mEJ(t+p zK_5(XMA&=1VVuS2{04=mqW7s2+%{yATv&YKH283V&rFNULN``UMe=Da}(-Q@UrA)K}V_$LeT zpJjZ6_cK0t!q|b}qL6uyBN41pn=s=MK@iZgO0Q?uZms+b3J>VkQ$^Mn@S9fMf%lDLw7l0UN!LW;;xCqif~_D#l%9|1jfSihW6BzjW(41 z0&(0)`jyQQ=F&?JDmAaq{Cu#0eq@~EwnGwkB#8SFaR-e!?{Q~wtwrEI+Fr%ppn~pl zOr=}^a>)$C$~BkF)^tPps0eD_Lyi=4D$~Foa^r|MfwY{FW(YIAGg{ANEx7;7M-lfx z4cc{(@_XPF;XO!VntXQNaMm7{aO25~KsBI|HY(mGWPS=O@l5^&q-k+&h0H!WUDg^i z?xc|UzCpLjjJt?MeZ-YEv0(8>kyg0CBxbfl80$8*1FQZ{Jwgws3z;ntX2p{6WF?;T z(fpnmg`RSo$mS5>JuV&c9&fK%OEWL}UeuM_r+n0=mzO0>0bOl&ri@~ z`RGnBIU?zdRc4fq+k^2Svm2fPnNB^;rOTX`$}}enWtKH%B93JyYO=yJU)P?t%=xg5 z4c$h-=?eP1hP1$f81$NH*pI82R*1mbZlRf^)7Z1}5Bje5mXn0=Y{c-A-fn)P7x)fG zajqYvq`q=|{Fet1R}V{b+^RwIhCwSrTeGsW@72hIw5+cj8JdOk{a7mEir(-59qfy0 z_=AtG_LVzwwQbl>t}cfF^D7?>>4(vKB&^X-j!(MCa=`N)o?JBp)dw=qBQB6j(6CNi zOTrIQNPpClSqEuMe>qN^bdXl}M{PO77JEQ#>35KR>n|tH(>e!OEKpnAdg+t|HkVv+ zJOd@?(bHrj&fKOJ+BpyLc%}~W99(;HS$0(m+S^h;&5vr`8UqcwJVb6G?m0klLoqy? z_d4z%l%s>lFqY8Bo*ydL*7Rr}6{BSUw~y%=@yDR|!Eg|x@A4KsdYgKHcG7$d7=UKO z9jxVEr*Jpg(y{&Ia$^*}e?RRmTP%idY*vf;wz%aAf_Q8n9Udl+N^n-wrD;;&uZ=TB z3xFDIu9N$X-1@6gx8brYDaz2$9a}_0{yD)}!{zoN3pj$;OAb(EI;K6| zU<{1*VYXAiX=%Zkv!8~fW7+6W#Peps(Eap7y4*8hEPpTzj-%n!=iiVNoQ>wDDxmH2 zv|+55+a7vdy>Tuc@*f4&~!g~8}dvQ8W z9@xn&ON#+{A!MTk{yf8Qy94cC^I*Vj`p{G??a71ag2&~EdDCGG@3+YGxB3KY3p`4W z8shm*TBzIWP*B(pf87IS7+$Szg!h`^jlyI<#(S@s;mX2fH^RHj@OGr*ZSs;Cu5YU_ z*^P)TW`tXJlYMb7?H+?Q%nTzwft4Kl5G6boC5&@KE{h?S?WOp!7+LMxN3OA`IpYo7 z;*6WF;cBZKTyvn{4X!!-v}=tFl{_7l9BV8!bX<*=%Wu?PIyhE7D1Mxc?;!#=*1$ah zI{p$AjQ8)j191ciD=qopGiez&a+VlhfYtB!`swj z0eYJ%nggol{ZQD%E+d+hBRrWJV~^>Uo+N_)TiVeyEy+>ar>YbF z_86+!YEXq|V3Z6V{EMv|>+G3{~bUbi*1!>yA1&aF-=P+r&Kf>T2uJdPkckxMt$aTx*65_6x zDRjB~j^Oll4U=CH$n&gRyg^2^7k9Vuz3b2tulbDV93@kD8K22B!%p1Go?RIBz4@%{ z7R1b#wP8XKKT5I)zZo|9jWA7GC40orcG7RF@E&-3CnaQHC(vD!TXDAN*PnJ3cUrF7FVdcT)ZuObaXSBylaCrFK%>T6w+rC3?b3w0?u!!PVVhzlL-^LTS<%{dk6;XRQzqr8ok3Ar?H> zOBBBm3oXy@@J-n$CkkTc9kk;`d4Blm?MCH7Woo`%-&lHoJEd%rhl{qCxc!Gy_G9*9 ze0PH4dvBBMQN(w)((W2kRo~+~klFda-~mZq#Wev0Nu;2sE+2 zpAX5g_RyC>z=UP-{AYtsxD3o1q0fC37ubbz8q++rv4BPyG=Cs22<-fE`3+TUxE@y> z%1QLmdvc?gSJ&%Y;dlx!a0#MA#!G1{wuYAfeUH`v>0>#L9(`XPE1<5O(FN*OxFsd3Dl|PgRiN8JXoAsd#$FZgwcM`qv5!BcVR#v_e zp0WiZ>@Gh2wVu_O?-+-)b??ce>F&pJ9r5(@6n`2DbTqj4B6TAbRlo`EdKz~eoj(l) z#OHm%ifg(SRS@Q^`IS5(v};g8sF9HSmAo`GA}HbOH9E(}b8@fHKh_q)AHXWmIk|&9 ztZGoC|2d2|utY^I&d8U1ExwgKLW!r>=uB;qre7p~$uHMY?ITv>75X@CQct*o-PVq) zY3|Q*B-Oku4?1{Nt}ocnX9lMq&*b#s_8moHpD|)56^ZSs#YWMr59D(6O?kOei^FJ& zTw4V63DI7@xK!`4wQx?UK##43ouvakHiyaoi~N*pZ-(CSbc5Dj9LkOg8c2D01ejAh zlb?259ep6hBY4@9HWr$hv^-LKC4+WclLt7S2OfDna+QX`Dxs4vqLLXlRWicV>$=>? zHPTSY!75?sWs2d>?7k|YVqAhsQ5Kcl8I*S&b?Jju6mbJDl_RUxMk>AOl^Z;1$CZ%C zm6)SH_1x)KLw*hMrby0NC4`yQmQ#nW-@pJ0ms3^y6)rGQNxmO{l^YALr&sAVtO^Bq zFlur?P+_#~OBgFQw@8}3ibnp9{hQ$io-LE|Z{odVEdso6VlhpuY+)a?iZ1*v&vG>| z*w3)y52;Q&IAr_;K2vqhciTk}p1cwSfXl*a3t-+#3b`q75;v{X zE-DCl&cJPu@xXkx!{?j3T40`CNs)iaS*|_?`yWVu*nB$R(NNlg*L|h0>@B?PLjHPI z&*$1zlzRI>{3BPK=jCi^b7|;s zQD4k^7s7ZU4?5)vIr`mbk!Bodu{v;DfC4-#dlT_nw#nE>(HHVAvr-FqJzCc2R8}1S zm*J@mg+bRBG};!!0^G>OV670r18>--a5)uBbHEf>-~(eP(6Rk|D`;_n+^Io!G`=bl z)L~{v=ivHEV~C613ZEXr^_9jDm&5Ds$-Nv4fU3E@HPT2-2)zRLSw`oG zT57>-h0YOpV=Z{EETbK=azdQ2jNO+ilWT+{oct^74xd+1{;)fyK4Vy*2?_=`!^P-j zs~bKe+EYU>TQh8{sh6!8_SdBA-ze3oez;O53AZ-FOxT9ipLTEKfVl+DPSCWYHN-Nl z4I}%$C6roX_EK7$uOy3GmQsFsCB2!6>u|t3u)hWVg{5>YR7n+QE~S)G zic1{1l$MoJ+K9cE(&j)o%w=H(hwFXt)zyO zGw}94^FTE(;kEOzg}vlbiY%kd>T_XL zJ^FZw?^+qu^G(>SN@5ya|AXkw_;nDJxxk+82?`bBggk$LK7mCaB=Wr+Fe0O6CYhn zHzSm)6kSoN7t#pCT+{NFP-><7m}wx|J_a(^m@FtC35#icMI|XD%wXTQgiha&y)R~= zU_WhP4@LGLQ4++Pi^%nek~sXzB3+9mtTMLjO;LfGU^QWn9FY zChpH+@csq)9KU6;ZsMJbXmNxxL0rCwO`IAs19WWN@(;EySLgwb4f4HXCcvcf>+EQB_GuytDu~7~O1zPV9bi1K}+Qv+QSBUrYcvy)5esnx%^< zCQ3<-xC^>~zKEY>=$o{VmPIM+hS&@}HzD2&uj&8P6T<+$`|U9E1yzDOtRK?C(|FrO z$n-&{x8~E_XeGh*4bs>avsng)1}5JFZGoY|cE})$j4u}WZURpbl?9aghmt7XnNJC2 zaH3**HFT!^7tpb4i0ra}eygTTcO@87KVpkKWC<*UN84rQ3(8r|1+*_#8RBvncv~3{ zGia0Mfw`y#OW|U;V-~!E`81$9n)Rjmx>e>g9@g^y6AyEPQ^4C~!ONdd=c=PwzcZgg z;*@+bc_Cem!+>m-fnSmF;a~rs_&n`_cU&V2{&=%EZ>pdoW22CE3;0 z5b+aO9=7saf(XSTqT_r@stFM}x`-1Hv0(v?tf?f2tYB!o&Q1@c4{9heuJVS+{T$!? zA#&9mqlMa@v@^^XRH~)sQ+O?9vG|Y2x2cx0UbN>uZS28}uA@v692Y!z^W*B<%9QI? zqbU0_t~`xRP&SHi6h;azFb<>ADGt@=udj^58uUEvR#oxVT$(#nO(y3peC#57sEUQs z#>!4{&m7<4B;|r&pD<68@(BCWE*>rQI#iCs&_Cr&}mns6sa- z)ah=X>EYRiUw_)8TA+qtYa9MHS-^(50}~pS%(OPpN}bU~lyctQMc?JgVf67^aw(s` zrP4)m&6%w?iAt)6ZZu0eY~s8MA46TP4vo#K60Y zbfXLScRX~$?XaLx(Sp}+Ha;<~>~=*Nc*ht|?*jfE4_&|ryoAm%UywB-X4BPn&`&V% zHZz{y1^hc6x&XdS^oRxT?^!gmy>ixdXqIljzKo|2rT-ldwWJ-sH!{_Nw||yzaR+6J zEcktszgFf5w0m{2P`bfac`r>>+KDecNvBhl4jr*KeuJm1d>ahPC0p>|5@b9@TZ;Cy zJ5#h8aSAoUIg_ioPS2}Oo+q^$k!`c3_y%@Uo)8?dhzTrslpy~nc8PvjqA2TnC|;L; zhMu*#fML^{P)5~&=wOlh$bKQtUabeHNy}o-&G23Ap;Q%;OjUD&`LHsGacV~k&l1Sy zY}s;Bs8vtp**?7uWqt=Czj#dn4^##Vfw7oDm9hYL0}k(Tj%|;Rip}uF^itv^hddo- z&<@;$Ty==jU4v*}s6~_o0@I{17Kkhp0<>?p(fb{E>E5Or zWs6nueKSNEBD5?7bQT5V8}sh~AUIpeCLm~g15p3oU>&zo>cKddfOElu6BC5fl5w2< z@y56ToFE%n^jV0y`Mw3GSRoEI8K%_bdNOjD5+_DKK`V#hg?WCe-f(8YGCXHBGZUz* zZpkRi!t0T@CP|=Gww{I_~F36F-^yR#lY|M|G?)}i^nYZFHNOm!<8ia zMBr`yPKkESH-MuUSZ`!n<$9pvXh=NEY+(U@YAOv+S2`qd33yw<>9!S|ZgIKm7RlDD zzagV)tZi}>{BnAm;ik69Uic^Um`eHS=&0Kn@fyYk@xP6@0i7bIU2yfb^eS6<9+C&HEz&ea-vz` zMIyk5;RLSaiI_^RkxHZ^0(#OURjyU0xbt=@0#&nxUoXO_o2Sr@k;qua6uK}H#<)D0 z%8pWoB;NukFYq?OwA^$heG?Z!!zl4QwW-e;$5V7_eP6Z!R|P*7arRB7tWiqid1%La z#Ma5i(lo4!dB<&ht4Jfw-`>?D!R~)x9hNC z^PGI4((UR~a6!BhA%;#S*W*fZ*@mFql5WrRwzX@Hu&XB1y2q9H@El-kJXmLE3{D>l z{Ku7MFm{frQKU@Hd2#4N4{`$4k>@jSF_r&-OOIUG+EEvzPH zu0lHNGZ=Afy|U&i%mRC6E-(YG(!l5innGjZ!BQ}i)ufCYr_`R89W)%u5OB#BT1kfJ)t`1hd$-}{Z}bd)O>x~@j(dhE zgqhX`+UBkF7nRK!nwgK1(0r<(_SfcrsPv`z-&r#A5A6FhO+7b-k5|fyiziY1cqLw( zJ*m*CmYyE3oHlL+%k<=}n@9sDDE(V#`tl8hEL(7f==y4U+OzB!Y7VsMxdC!DJ#kmW z^$ALg!qb%+LX?qXcX18L%rOsIn_G}(n@H~BG;yNR-Zc;ryi9N#gghEX$Em4jbod#9 zHy9K{Jd{p5d^fAS1-SPlDwwFu4f$A$56fyY33ux&sgVm9w;oQK)zeR!<*)-9nmD(( z=O@u`ldvkPOrj2xmAKZ6CW3YWmio5otErhB#{YVZfl6+>+eUkdMB}BwbliYOBMn&1 zs=kb~E;RW_u?lo*veF{PJE4GjntUk6?p$;yZJFocEy29cPoS77N?e;%=C5q)X|vhV z%(Do7;AcZN+r@hX&SWeb#lHZUF(xL$4S~61A}yPu%xx3-0345r<157J37p?p9|PBp z|I;UuYpRkWo}EC;rlJ~sJAn>PRboQpL5sdv`&!I~N%X^1B`K}7iMe0LtOD2n7Kmdy z?|$c@D8pNh^Sj*0uLJ4a@JpF34|bgax!l>boJbRwswq85I!!}|k zX+M@8IB!O{iRSgZ*^J=3e^GBYm|=KHyAdWc3@>Rv+TL^HHK*r!i;ehL7OGF}{@wVP zRmUb`Mrp~E2RL4&ZA6A_7)NyBH!3pF8ZVw0{9XpVX6;sbru-GO18&s0x1*#h-B3bc zCG;AQ!F@S*K2ZJ!cRu{odo*-DJf*|OoU7ncv2cCV z_V2iOYdUc9@+SCDvjVtD<7w7Y$~s3F;`K@LoA1~wBiJt^ zk?--L%TFua?Z1t|yD!wy%r|Yml3{n$Mj}n>i#bcwVr6R68-g2GkitHqUw_)8LbZ1t zPyI)LHaIWa0mZa7e@Wkmiy7e_wSRV^Dv6w`B1U{3N ztzTjc#XO@VhW!4xj+Z%>hCGA)EGs)4?nZ$9H4FPMkJF}SlpUh)aq6&4SthP|obr|_ z$6O-}IFZ%En<>Xw$1v2xx|F6K)}=Vp`kRSg@{zzdX<5A?kJGv3%0D=&`{fE{P)9RK zyG)mtx8NoPyX1;F`qS<&t=X_0Z1@ILFzFfU)@aR!xwf3rH2YbltK$bmXoct4f>}8I z{H!v_k%BmOzAo_%T)ugP(3pwpk0=)DTe(t65+f=g9B9*MlI6^BY5n6CvJu`6>D)9; z4FVZ=meMrVHATkJ{2Z9==77(nWo>PvDJ>JPluM&%{Y0#(?#@IL`DV1{dM}QBoOZ8K zDl{~);LoNR5w&>)jJU*t_3kKcNzU6B8)Me&ZDp@0E;fL==s>mZ0~CvWtI-yqmq*dQ z)ljPYpZ{@6myy^!y$jt>yQAYC7Ns^_7MFkx{;DYn0`7(OcFx`*{TyX+1rXYkj$_ zpB^iqvm>yi%NJ?ozM!;o^aU?PUBNeV>fg23C+FWvl<%qaN{%RwAK^=RQ3-cAW~YP1 z-^x*$oGa~vLR)~Jt;vr5{|xu#Z&CIM_EVr?*GAv&ZOVFFbv2w^FDadqoMBwp*m+jy{o^#FBpG(8F>X~iJ38N2RQliD)!|B>f7+^VvQ=1)18^;0=a6cAB z^{Y8bQ;8#REIz#h^P}`(6t`0um;gs>O_(MGV^Mthu(n0WSW}3A=rI{e64x^Nl zN&~92O9{0iTttI^3mm~}3WW&Ncb9ToES>&ffCX4w7-a$2In2nXzdRk!QeF~29IgX= zm>tj{Lp1Vm5_{D#IzYB*sNp(5h7ACpzM`}iw+*9XHHtN%uCFQ`jPW`S)=O^M^s3U8 z?gyLB&J}<`#saV7ilD6+w`j*qcxklDT?)Yu9)=i;%P?(+FG;)tpAo_;V$ZRE1oI8xx zXDh9Yq6rAIqt$#4@ZcPjFBC?~Ugb40eJCB=s|+-1VTR}q=L!N>cfA&lz&iFK3&z{X zE7REA;l7Uhu+k~s971FE2dXk=W<^2x(^-`*AcIU0Z#ez5UpW_0z+aS?ziIU)XoE9R z(d6}q)8DTvRmA)u6mdZ58^DOFP$UzvQFtj?Fn$?gWFo2p?L4524DjMYm0$z31MgxB z?>i>1rvkM-s0?YZH{lGvlqHyVA$W&bc(<6mpnbCr-XGX(vEkIz*dg@8L1lA54Y zqfK7Wwm=qe-L4Y5?vPTwP=TT#eD)&80%9{kavq_9hp>=nDu8=4f)!{7Ubb1V^4|?M z%FY=tZSF`Xl&>E_H(yHlzfgxl%_?d>UW;t_2X(pZ?G z{V%})Bd~=$)B>>C1i<|--yT!EMFDWnN-%%}8^UoGfRQEu?pZl`T6Md8 z^^n&Q!85FcfxdGmm5~m6?f_%ceA0W$QdvCMPu~T9wx2KIjFRFIUZd9U;e#dG;l#mj z*cE#IQ{}zL&-&`)mlQl}^#LRnA9%-mI7X>Q`}yX6rmS{|8~gA)C5ayWN*N(O)|+;J zrR0g(y=eY9Wn}ox-rzDuE#}tsfnIz(=?Nj%*F8*rS)j__D8(D$Jew3)48*`V19zMT zoPV`2R;oM-@zT_O9O8@<6(kr(mW6k z6YPbUO02fv<@KbH3(BmJod#a}-n8<9QlYU`9n`6I7_bequx|ky*SDk5_h@xbf|uwJ zU(<`qMnT+=rr(9OB2Bk5ZduUE%o(NI*&U^ic46mN86>F8eoiyW%o#`RdkgDIU!27!8 zEmC_2q{jG^%gPIa<35l|LIj&CA|?TsLeiu4`di{Xl!t!XAVTXL=4(&7a{P)6i6`Cdxbj`z^I5crs>n&7ji?{Du~~7quswM$%!Mou@Lj@aah(Agts8f#2*1f zyMrI$HB6T-WQO#hh~Jd65rYs8Y=Iy?*ATF-8-@IirN$?^aaAi2kEZHAaoMT5Pu!+I zlz}C^ao97$F%&H6RZAuLPo-_i96gGCtV*R)pFfo$Az!EJO?_r}I`$`4OZ>q$M9XfD zc`ZiQYgw}(JAR%@1%JW|?6AS!kIlxXw1d{|wX(6|VGOe!c+)I+ucy-dn^?TrVBj@_ zIydj5PD7}J<2}7C>}#RUP34#*8tt}-1~-u_c9bYPb-{+BJd9a1Uz7M24x zcBA39l*8iDZWMVNYp~_I@e8Vk@7deR5;>__XGp1PJ2dN(w)oAbzj^Vycu8pS&+HQ~ z=h%my{b%;EUH{l^neTPgY2WF3z@@^SaY|>s=SlC(E*`aM{HN%Ve-YGj;(MKO@gpvM ztthH1#LY(FO;O$GngV&ea#NbI^zKv}d~tUg#e=V?TH4d@=A+aoM0BSk;15%$3+RJ} zaN|1DR=b)O(%Hbf(uE4_YK2->c66Bw(Ys3)_V%59aDu}XA)mM?RZ`D6PP@!5=uuhi zCDwB3S&Kk2Uocr9s|n&97w2k%xTO<&Y&w{PC zo`q4+0a=jP)InKj@1hh{o#3isupi;{p<00#HHj5(C>$!0r!T-4j90-$H&t~;lC!oZ zUc|9Hwy0fG12@&;rL^0^a;*~%*MP>BQ=7IGQyaVT5W!iQ#JUW82wetZ;S9?ID=fet zb)uLM^_=hw38Gqo!iuY(xl#@6pP3d#?+IFsgc7-ep3hueVZG?Lhv8;S(3`aUW`492 zC6-Y0T#AAB660Z!&!jP`(*NRN1jrkDZ-LLGWjvviFSVqaWfxa>)VrcZ9er@m-718v z>8S4rK<`YJsK6EHWStMzO4~z98T!B*H2ch zf5KjtJWJr>b+?jwoZhXYh8p?K<}+%rZMJFuOISYr0(wE0Tyy2B0>Vs#Gir3NvfA5W zM}&Szeq0rGlu#7VTNH31R(yI`05jVefZhgFp{iP^D1a@oh(_B1(AWa-gb83vq$O3= zX+;6tMFCD>sa3H6bTk3niN01*YDq!-vn^k&o+w^!OY@`E0j^Kl>V-2AoZPNWgBXQ_ zQL$FohT%}yXxHscsSc((mW8aFZw{>jkDmr+LpG) zsHa`y47?D=!uTWrgmiD`hrsKM`~pw0;B{p@R@mG`&Dd9zr~`@ztKi7kClwq{2}l#mN|vRmMjb2)i#t> z9r^vlz?;Z;4IcszgOL$9G_c%)_hB1~i&Nvm-v*vGRIDasCc@2+M|(MKXn34D*Og(& zO89@s;!S6lMb@%56kkJig^V@uinXJ;H3I!kVO7NTL^~`CRkyG|*2Z_NhT0Gwv0C4o zEqaSKlE!K*OKEx;eP zrnq=@r0XREuPx*0?K$n+cWIMy`^0s5!{4;2QY-gKYUKqm24V-imsd!zrhwE3Tp6yi-YpAIa8){}4 z*)~AY9Y9Uqx_-q1{F9S*)Wz$kMH{+MSMB5Y0J!=-PWJ@$NpV?g`XE7#34g4W;px9k z_gZ0Jrl(qySWk6{LTgH`r*L7@NEwc=oY0S2U)Ucs?^Fh3^tvqS>KpV{4Du{PzBlU_XxAM6f zt2mP}6)D=iSYb`oOM>HEOIRiM4>g*qB&(anT`hgblGS8~xVpLTPKt_4*6%hiykz~; z=7dYuV|-29s4WEhD=mz37a48US0le^u20fB;+dF?qQmHx7ogT-0qUI=L3gcZv{Oq9 zj?o~|ZY-uZ+pBMemjzc~@d?{z80LTYNi$m6K|N?+0#fsi^*0=8%&09NHGNcdi&@Qd zSMCkXcrctyr8}t&lH83mZM-yyv%vhctF8^kUrnh-7qzi?s3{HUf=Zm#R3Gaf>!K#o zHybqLM)M6$oXk!&D*}J={6{%NOb&UoUP!MMwSy59#9w08aKz-O$ zGZ(hVn^L`0^@XB2^jiQhvg>I9c+LdyH}#e3hM8JGx`nwNW+it(9GsElLS~xUT}=+~ zI-3>IoF`@Z7T!pc*V&9Nc2|3gcbZUg4|Qe4*(Ulx+AW~{8Xy0jfwke>CUl{Pn&Qeq zIuAXEASb+KZ7Rh55t~cEA+AERp+CYqfu|j_ED9WMLSxd<4X-iq5*ZKO@PFcQHw?T~ z3*O2m6wy=d;F@IMg)$x-DgF}=jdD8 zSvJoX{LOszdaHkm_H@K(-Ak{2>YJi{O=IKQy`}?Ie7a$4BYiP@W+NYtbS=i$_Zs@- zVQQ*i|GkmXnM@k4zFM_9Li}1^)v$nOB_dx&XYv|4lTbiv-;C;)u8tNQUL@0v7LHiD zJVMJyMMoXBdII92j8)9vy{1 z4=s=)4o;-qqtvzu&gNX$*?c~W9m-Flrj>$77)5)RvQfH0Bc`!ATTs=}YLy}1fPi;! zJ0gL7h?rO~zH@liNORsN?TnGu>^^Dl8EJ`$yek~;%O0&(6vQ7I@HJBrlzZ5r($9~p zgOmI%b$#6_+S9J-tslvm0oY)@eGLq~-6=G0jG7eS#W5hxkI8!pOTdFHycKpWr#Q|1oR9O-GQC=TR?+m zfiXf;9X$hwg))2I!`BMus)@}_em!Ra{#fvTW8tr2@`JW1_{sm2TGz;4h8WeVhyv{Z zaMA)`HvytrQMd8xGh$wSIyYXuIt1<(TIbLh_TU9EQ){Dhz+fd99GwFe#A4BqdRPQx z0*9;ZYXyvl1v7L&p86Cs5qdAz?rIW zm2AOk@*vC8ipEY-2fM-zyjfXOhu;CpXpT5t~4qX|<~d{V_=Z`Od0-H*KqW)ooV zZDC(qj|!$>cJh?L9>JEt?8G$N14|IIlkLDuvfxdxN3*7?I|G*R2j>C}4iikl!qVEb zguj)q?=-cnXfS7sQMk=Ns7)-y>}n#2P2IRi_ata$%(g}01ln{pLU<7KB}{KBS(pbF zGSl@L>X-m;PEo=9O`zXF8!Wh?$%~bzRZpr}sb&}BxA0<)bHu{?cU?ni(1zcI!7=C- z;VRA_i{LIsaEi2KCVJ;@>(Y*y=srHKOV?(qvs}BG5p|>sGUEMI`0rBsw6!)D8f{VF z<+`+Qmb%q7)xaymcxQ^@!H@O^w_ASdy%H+nnbxqOa{7wYT8fT1PjT6QYfAi$={Ao6-I!ix{`?$5IAakT=$$3v<=h zMYD*Gw1`HSf3>vm&4GL^i+G)knx}RT0BBjlsmCG!aQm%j0qDmW;4Jw?`g@-Gj!{W5 zcftwDK-u83r^ayb18uN59x-`scKXYseh}b|!il^f-VsebX)joKzp8D>jgsiEr`6p7 zUYzO+=3SWVNpo9xy(X_)qOa!%>5MJ&BD^gjAe+UjzakneGJwUfEY;ks4$6AQ@s#QGu6Qd(vh= zK(K**@rIFdWSX~Fbs4{44GRI$0M@vcp9@rjTBwAXxS1qIiv>YnEu7ubb5(e zuQdj6ToC2}Zb4goYQUmj7qBo525_09pdaU($7{B4J$Y4XQOZ(vDvtw$VeIYjwKlK? zo2Y6b41K#)jTV2dNmrl27^wa;YHKUNNdWAz09>yX(1SKVW0s>+p?47w_i1Potw8n; zp0p<{KnH?=mMk-Yyr><^)Crve11X&J3u+pUM?Gn6EI{)Cq%}#LV|?+iAj^zin%A=? zja;s}NPS){V^p^wL{m>#r` zAft5+_kYGThwjfp&)+eu59}nPHogu%BRmg>>4eOhAmW+KH6-xZKNw(+mKK)v<9*Vm z8)^Rgq)jx^zPeA^Xd^AJrY~Y8+O+sgO<&3?HCz;{)uKL`YJ=`K1Y3w+cRl*k?!^-e z5(_ck-w8<5ZfwgRYZ!I_t$35m1x>YITdk>bWf5$}>5ELY1r95is8PlBYGj~p2kJr# z>M0X7syKCCt+p4Z)u7d@)p&7N4LY`39Up||DT=lbOA09#w7Djlr#PiQr$&cgkAtF^ zF;*R9*Y9lfR?1AQLF=DW<3xWPop=uWrJu#|IlgLCevRsK;CLfg*QoCW33iq!l8snQ zdX7O*uyG0?hmBx^e^dHebyv(_L~KjfY8PIwC2`VC?~_KcLijJ${6E&t2P}$eef+b# zs57XD{|W!Cii(Dce^N5DRmq6VNX@9M_9i8j8Fjry=54pa;+EA?=HZsvW>iF0TUk(A z?oBc(%gs#5NLQt#vLrKE|L*T|c4u&zn>WAD^W%AVKC^Sq`=0lG&!3q&b7n>iTc%F8 z=B0}JmZ`&R^Vt7vsoGW4EK}30R}B=0mZ|SpCk_y=3H8SGM)~}Q)NhT1(pE8tJ4UTc zHk@zRpd^S3O4V26XUJ&K;LaE*PL!(2*_#J6x5x^)2I32T%k*{#nj7TP$hK(Fd-%XM zkB7?q%0O}5ztu-#BIM@53^`ut6)j)N@d!#|BlNi}Oh(9^AO=09Zi$h$^BhKubP5+2 z*(T|S3~77fOQW7vEtvs1YuDVJqYW+~pX@+Wz_3FugE)*Nc0}^aW_)&3Q-CKsD(_sb zUTm>$OR3!OjC!d>-1@xQj(0y8%A9(QT|EyYViLoHs;+x&6=Jvu%WRG=cZ-3naTKu}_xYhb%Kaspr{aboK zZ!&@ACc_E*Jd^Y)Lz*V@%1TbQ=l2tzu2kQMwV|a8d4rfPGHJQV(Bke?`PTF5^(?u- zh!@oC-Vc+r`I#_2O7J%xf|1v>?HNNG`iT#EYsuDK{ltnF)PeDLlUGiSeBV!e@d9J^ zKhfGO%L@hWMb_UhdR*X`z;mY2SI^n`!pM8<-zA@kWS^ahyLa?_eb(}99A6Z9)A;SR zL>{ht&G=nKIuF}b7{9AY=UKWJ`<>_$IRN!pN(OeUG%|R|fFUdTiHaAwWGvD550{Rz zSiq>7<^z?zb4&~1;-Lpuu$-h`gmXq-*(x9I$731llNZFazF0w4ka0^P*(7u&h07MI zI6Ig8qY(p`kXEXvyxY(>@^D=IdAf1m^%uj+xtccH!X!i4Sb7NAVr@CQpO{~+-q39h z`{lt`4)nay;f-DRozPGGRIUz5{k?CbA|jvOvk)Jd$09$whkyHwv;}-UBmF+cv`b%B zyLbBmbU2m(|`AzL9B@qiI8A8r!QRqiRd!E7uxi{i2=+C?Ee^ zn#R6Y>`V&w7u(Tc{j{(6;K5csE@b!Ph%!(ONu-$>w+A1I?yL9=M)pxevA%DEu@Bk% z^?m>8E3T|;9VRVF2m_7#U-rDc79 zYw{Fmwp8?cq-FW!n5VZapG7{Hp)eK4lO>TANWXIm#1y2om)eZvl`X5vE^dEKon`IU zSA6=KI>zN7J@Wm*=;N6)Phjq2XiM}Omkjjvb4ML%OU z2|e;GJvQG*vH8?!zKoXndPIy}6Ppnyr31VBil<&zlY2i*+H;dR0p&?Ou3xoDIGs5V&f@QN}m-+H*wV)YA@SElr2Bnl)Z}$Sz|6~G_(1J)G2F>+5Ak7 z<4>DP__mMu;SF_C_6NGY*-~G0Z28|UfX)%egkqsdUsWG*`rpeyq-I%+nm14r z88F>e+2z%{{S((QoZg%BU(HLB+ZR>XC`)-E*)Sh=X#?Y^15Tq zZR6fNrdQ?mN_DASbbe%Xd%W+OtRrE5Yd&Lua+VNh^CwzKZ=ZYnywK(Cs-%|4W z(WtK9dWjY9#6-tXrebZmA&HQb7?jn_&bnp;^IshJs*{xOT1jku}^?Ok2lt z&++fG9;<~p3ZI%*xbYBaE6mXH1k8gbZ6EiHIOI{3Gb+#fKrUYTM?~G?mYPhC$qB!X zCQX+bnsBVUU%jq5D9)BvqzvO@0_2VL=}be`c}C^yer}sJ3wv7%S2HoV$RxbBhwg&+ zjLMroR1cgK_O}#{HX$bS2))Up-5;Ce%Np2Cl6lAxVWV;)(O0o#Y%JPg? zY}_-El}5&vdn{QunrFOj{z!enR?Ut!o3vgceS`YsNh?eqob8^TYtmF|Xrcy>ZcsZ~ ztmh|JCe)~HPsYJi19B&Z(J!bYKh2Ju- zV(%e7+o%riB!9@~N90lUKF&A(o-A5_t`3RrcSiTiHS2lFVp8*dcXYp8xPDo(xTkr) z_hkMl$>P1wIarK1L;U)=x-3B&5g9Jqx;Gbh7ZWzqx5~d@t%LJxwWAz=BOXNh6yq=R zK9`s*e=JG2obk8fhp1N(g`IgvMt8Aev)WtaY|<4DGbvn;!T~0Q*Pm1(;P;B zuNGm`OZCcR zM*n1a#;1?|XXHoD_B`D=+uQl2dbRbLZZd3#>CQswF4kq1YhHiqj?)#R(`bRez zthxUcBGimCsabeZjrjXl>ZR6mA|`Ybbzi9$nk%h;4xgSgDVTIpLCMvzc64`d?i{hB zwkuJcUlAC6H!e49G3z5k^8C0)gJ?6PJ@)D01FS@IeE2&1+KX3e)w^8JW1hU`ZjY#(0W!RjClJf^wAO!;_N1N` zCL(6JNAd9!JQ+6vFHi0xg$|7gvmHLKu6)Wnv9_^y* zdsFHgbQ=2Pv$g1x!Hw0I&{ZUVr}pXX;I^+E8RZQhd&kIiuzYzSG4XWvr-;kHQ**^* zKdK4mM3004E?;Dzb^p0GyN0*VnsjgP5*Y&m3VHw7&9(ZHooc#B-J#}KE4qk#rw=x%yb()ej1_y5sNBOLa8xJp!ye}Gf@ExQabUBQ*nX2^ zN9T(3J6BGtS1*s8L`mWQs;GG^{6KMRM1q}+g8GPWzmJ|wMr1jejIHE6WEY!cKQd%F znY`c!bz!rE(PMmb14+4sZ?~9a|82-}jBolu9bx^cvly~hy(xYU39@@zx}35O>e1KB zr0?oZV#i)S3hNy!n)Y(@;=)d1LW4TvRBblpRzA2%NwJ|AV3tTK~)wV5}?{^s{>(-n7cJ`gQ7l2;B8lRAp*ed?7_<@DTF z_Nm8&_&s{DM`ik~?nuwo6>)V{$k$~k+$c~gsY{I5?o-@-#LvH|r7abBTPlcK$op+g z3SKZ2c>9Qte^u}0Ba$L}zdAV1rzm!DCtIUZ$kP07(j>>b@*Sh!qUO0dt(!lc^wjgT20yZCCqIy62>3X-{B2NB<>CXcy<-;pUqGVZoCzcQ11Dy>UY(wb+YkV!?M;D#g&cf3~R8vc)d}5yq6<#xL|goZ=@_+B4!8_fiFqsiSRA^Rthw)!<6UaW&P}ZA04=Vl?+i$ty@KGma|bFv~{g;A=Zb_eI9RH zIp3mP6KA!w<=bc4NLy|E3GrFyxW2+~ZKaB|*4j*41A162+(WErt=--`m0!~O$I19l zEgDVv1VQ?)6QW}~`2@l3wjycRxpDo(#fxnn#FjSNTI=X|@wlpuvmHhx^5V&M$jfd} zL0-Lmd1A&mkA)Ai({DUBd;e(rmhFr8ZEZk~_7%x1+gIy&F;2tlfEK;8vWEhs-h11M z6`IB)-6l0udNsGFpE0TVP7^z%nwNAn@9AoCPpu|}Dg6Z|HLEpoU%YmM^>$s&VqH!D zQ>!Ur=JY(18kZ(!wbjOqy-X!ItQME2Vv+ki+|P09D&^ZK?fjk{^V`dPpj>|Ud6Y?* zU|TK8m2ISsCU=}NbBghs_kMf1{Wi(?ooBg?u+E%d{Fd(l=l0t;<99jf{2pWc&bQp= zrSy@;@ARlO!;Iff(iO!vbBHDuw$nyt_tF#A;Hs=|MV}^-!yXwMWqnJ=*0+4#Z<~~h znNsPli9_wQNmFhxg~r0Y#y{96>t4RpTpIVA@f&AksD3eiW2_9-k80#4=X2}y{R{sO zw#jGTmYHnZiXM3%?7-F&;$x#Ms!5i$p5L-sTFW2rsbXA$c6~=aX*(=>mx@zz3zrqb zm!K8ceCWNTNb4)SXJ{QSbEHH9WA#UA3r1gDA)m+{Z8BhiG(gTbk@qo-kZ;jZe9<*q za=*nfAkvwdMu`=vtp2hF8rdR~Y_%av-ko1#LkFVlNGQ3l zjkvOtHqe^hM%>p)8)6;Mrjpew@mA}JR^q)b+T3CGK@r{7NQ7+_lexpR9$m5Vuo=4j zgTy6WwcFwsQMf#c{m@!`+Ets|93Mw&3p?w%yYx?!uJ>E(@o}Vzx!ttG?F-lu=^q;{ zyr;QjmaR+Wz1_8RYqL_5^C^88D5XqH|NE|$u9P)8d(Y5rv5Gh`D_NT}%H&*syL`ItimD7K_Q7I*5AAB}S*^sho?5o`h^_Lep4x{NYu`9=O>b>d@9{`BFIq4yc=&f* zbiu>padN>!ayJ|fMDNV-4R+*Y1uTn`iywN30e!Uo-G<3x<@<~EH|ok25VuiKAFbQP zH^=EK9?p!ec$mxY*imVY@w;JR=d% z2hV`T8yl(U6h|4i8C3F1UyNvFp+^o-d7H%vk2Xx?+qHA`md`4{SRGu&v&uLq%Z-t@ zOL=(}O5Srevn^YG{^WOGvqj(e+e)|dd1)sPS{SmYw3DN89IKMonaT;<#H_yBx-oV> z%`LB6y;0hN@_iW5Z@mTf8)txc)gv}R9uayHfz`BdA7CRv8GXghEZ6*C5F zx2S8C=yjKH57tt|zQNjEW)q(0VYb^%YTm?LS(Npyes8XMNvj&Cvj7C((h`Amm#KdRx4_j0z z7pB9+B||mm$!ChCq{YzWXsM})Z;d=<(zG2Dq>SPiCVn5P&1`8()W2p^;y49dU{bK! zP~aab9v-G0j3}65Sm17HK|Qy=2bvVzU??E(y_oe{X`I$zls0?xgWN@2Up-CESd+g!ZsEGdlSV`2gwPeo#r#Ryxa<|k%V3X}c}_DX)f`K5O?H$X6$d71Lq>jo zM25g|_)PTe;x3%rRus#_&tYR@}I%unF(W-}v(U{n5#--JAhCcS-Q;ebc1xz+v&wh1!_-p6K&7alzCiCR`Sm9KT7|f6Gzv>xF+3hO1D=49mYv z>OMJKIV@XCwp{Qy3Epk!+ZO$#iG_8tx9K{K>7QGS-}>~=jmB?%`saFn@0`4s`hAhKV6?+>LYkY z9vQqp)kpBEhq$NLA!p>3`g$G~yQeataQhJve=(OXd&S}NwNcsIL(#e^luDsY(5okg!hECS+IX`esRed@tEB;gsfHKoe*6-0dcPZ-&G})3ogDCv<%yq&{Bl z^_TiC=YBc*E;i|VBqVxYqK(P^yRNUJ)HmZa^v$60utIOBN#89Yu>yV8b%({)OSCE3 z6Lr0EoRY5$`%617;RFV~N0Bq~%4#|%ByPxI=;^2H^Gkgforb=PsCM+#ne_DxRqoEw z23qEBXo^;Jo>a)KBBRjeis6+xk#^~jug>9U&8;H&4Pv)Rp&vc+?bUT3aaV-P0C_23 zvCFmC+|du(#jVq|vu&@DY50S-UZQ5YmXTeo7d=oG&B@(g7A>#jIenaDD*C=Akv&5j z7I)wfC!m2XoYFYvXsY$cLt@1Y?L2F6h}bzp8(_VlNwl8Huy$6Hm^M=z+Y5)JW7go< zsDobVpryjX<@uH-v2vz1(%QL6TzNSopQ>B>A|;=0kn+&;A##RSvKFmadYLw6Rs)tQ zjC>DBeayWZc}^L0f+=ShSDN(gMvn~iiE6I54vDRoX@jiFSt5KHlT>dU64%VqCRm>% z46|sFPmn%Ko80WSa&`;1CvpZhyh)6?TJ$yAt0>LY?y@?@ zik*ZH-ER71-ykjwn%Zmi} z^jlDkQ32!X;8oPfJPLVhKCHavX04k=_^;KbTHpAiGQp{>u+07L_h_rR8&SO#M#S}2 z6R-sNfVV8her|JDmG71ksE#da8+v3{{rx{NUDd63RZkz;RSE8O__m&$k^Z{iI{ND~ zdim$b@}vFrf0s{xO`*SDZYp2=E)HEse{F-lll?XB!~q%X%lYnB{v7RIYh!=$^Bm4T z?EOWLJZ+a%`(2#Kqub(~bW*-8CgQAHI?Jtd=CI0t7t^oTezjH|h<4jo(WubPF2VqL zC1M2OlmX*PM9u@v#V{kUY%nh!5bxYTw|zv{cc#?G$+nT_l=`>;k#C{7z@+a%^vE@# z&-+h^!UJN`TI%*bL5WEbKJ#NRXEq)e*QUjF6^VDrDTeu4 zFDp6en-x}nJMr+X+I-2Qw`y0|*6fdVDchTDJUg^iH&IfcxvZJ{#g4nQb9r3R&G$!T zwc6!JuWc3ga}i&OdOYwMU8D)ohzET1+I5?DhV1}5HqCC+TfBRl*4g^Te(}X^TC!~x zdm|n4;{BBgw`(IU*@f&;Xb0U0fn2<1C_Pzkd}uY&ab)2f;~0H1x#%5fGT`?8e6x|0 zgJ@e4FQ5i++?y!VUtlnDGo>u^rMVvn4{F(n