From 3f97660a1a03f88a2ab9f9e4ce20d61934d3dfb9 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 11:39:58 -0700 Subject: [PATCH 001/656] release nissan (#1515) --- RELEASES.md | 5 ++++- release/files_common | 7 +++++++ 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 67beec7795..08e08a9f17 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,7 @@ +Version 0.7.6 (2020-xx-xx) +======================== +* 2019 Nissan X-Trail and 2018 Nissan Leaf support thanks to avolmensky! + Version 0.7.5 (2020-05-13) ======================== * Right-Hand Drive support for both driving and driver monitoring! @@ -5,7 +9,6 @@ Version 0.7.5 (2020-05-13) * New driver monitoring model: overall improvement on comma two * Driver camera preview in settings to improve mounting position * Added support for many Hyundai, Kia, Genesis models thanks to xx979xx! -* 2019 Nissan X-Trail and 2018 Nissan Leaf support thanks to avolmensky! * Improved lateral tuning for 2020 Toyota Rav 4 (hybrid) Version 0.7.4 (2020-03-20) diff --git a/release/files_common b/release/files_common index 1ca68db684..ca05fbf756 100644 --- a/release/files_common +++ b/release/files_common @@ -122,6 +122,13 @@ selfdrive/car/toyota/radar_interface.py selfdrive/car/toyota/values.py selfdrive/car/toyota/carcontroller.py selfdrive/car/toyota/toyotacan.py +selfdrive/car/nissan/__init__.py +selfdrive/car/nissan/carcontroller.py +selfdrive/car/nissan/carstate.py +selfdrive/car/nissan/interface.py +selfdrive/car/nissan/nissancan.py +selfdrive/car/nissan/radar_interface.py +selfdrive/car/nissan/values.py selfdrive/car/volkswagen/__init__.py selfdrive/car/volkswagen/carstate.py selfdrive/car/volkswagen/interface.py From b224af1386599aaa5af179b913c9fd35fbe684af Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 12:08:09 -0700 Subject: [PATCH 002/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 856c9812d5..d589d5e3d8 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 856c9812d552fe0ac640b75074b080f76c9a3cba +Subproject commit d589d5e3d85a11e8011397069f196cfd58ac113d From 631d0d94d3beb1bd5ac9000b70104847c8c71dac Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 12:24:12 -0700 Subject: [PATCH 003/656] Fix two event names --- selfdrive/controls/lib/events.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 081ef0db81..d2427866f3 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -324,7 +324,7 @@ EVENTS = { EventName.driverDistracted: { ET.WARNING: Alert( - "DISEventName.AGE IMMEDIATELY", + "DISENGAGE IMMEDIATELY", "Driver Was Distracted", AlertStatus.critical, AlertSize.full, Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, .1, .1, .1), @@ -348,7 +348,7 @@ EVENTS = { EventName.driverUnresponsive: { ET.WARNING: Alert( - "DISEventName.AGE IMMEDIATELY", + "DISENGAGE IMMEDIATELY", "Driver Was Unresponsive", AlertStatus.critical, AlertSize.full, Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, .1, .1, .1), From c85b174584b1281ce1f1d168b0b0610d5d540896 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 13:00:00 -0700 Subject: [PATCH 004/656] White panda is deprecated (#1516) * Start white panda deprecation * Unify alert text * Add noentry * Change to no longer supported * panda is lowercase * Capitalize * rerun ci --- selfdrive/car/car_helpers.py | 8 ++++++-- selfdrive/controls/controlsd.py | 4 +++- selfdrive/controls/lib/events.py | 17 +++++++++++++++++ 3 files changed, 26 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 9052ebb26b..434ed1ef1b 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -8,10 +8,12 @@ from selfdrive.swaglog import cloudlog import cereal.messaging as messaging from selfdrive.car import gen_empty_fingerprint -from cereal import car +from cereal import car, log EventName = car.CarEvent.EventName +HwType = log.HealthData.HwType -def get_startup_event(car_recognized, controller_available): + +def get_startup_event(car_recognized, controller_available, hw_type): event = EventName.startup if Params().get("GitRemote", encoding="utf8") in ['git@github.com:commaai/openpilot.git', 'https://github.com/commaai/openpilot.git']: if Params().get("GitBranch", encoding="utf8") not in ['devel', 'release2-staging', 'dashcam-staging', 'release2', 'dashcam']: @@ -20,6 +22,8 @@ def get_startup_event(car_recognized, controller_available): event = EventName.startupNoCar elif car_recognized and not controller_available: event = EventName.startupNoControl + elif hw_type == HwType.whitePanda: + event = EventName.startupWhitePanda return event diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index c85db56713..e529054013 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -130,7 +130,7 @@ class Controls: self.sm['dMonitoringState'].awarenessStatus = 1. self.sm['dMonitoringState'].faceDetected = False - self.startup_event = get_startup_event(car_recognized, controller_available) + self.startup_event = get_startup_event(car_recognized, controller_available, hw_type) if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) @@ -140,6 +140,8 @@ class Controls: self.events.add(EventName.communityFeatureDisallowed, static=True) if self.read_only and not passive: self.events.add(EventName.carUnrecognized, static=True) + # if hw_type == HwType.whitePanda: + # self.events.add(EventName.whitePandaUnsupported, static=True) # controlsd is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index d2427866f3..78ccd2575d 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -198,6 +198,14 @@ EVENTS = { Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., 15.), }, + EventName.startupWhitePanda: { + ET.PERMANENT: Alert( + "WARNING: White panda is deprecated", + "Upgrade to comma two or black panda", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., 15.), + }, + EventName.startupMaster: { ET.PERMANENT: Alert( "WARNING: This branch is not tested", @@ -230,6 +238,15 @@ EVENTS = { Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2), }, + EventName.whitePandaUnsupported: { + ET.PERMANENT: Alert( + "White Panda Is No Longer Supported", + "Upgrade to comma two or black panda", + AlertStatus.normal, AlertSize.mid, + Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + ET.NO_ENTRY: NoEntryAlert("White panda is no longer supported"), + }, + EventName.invalidLkasSetting: { ET.PERMANENT: Alert( "Stock LKAS is turned on", From 3d75b4d7c08478188bc7bd480a411b6ff2aa5776 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 13:00:59 -0700 Subject: [PATCH 005/656] Add white panda deprecation to release notes --- RELEASES.md | 1 + 1 file changed, 1 insertion(+) diff --git a/RELEASES.md b/RELEASES.md index 08e08a9f17..b8b821e6a4 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,5 +1,6 @@ Version 0.7.6 (2020-xx-xx) ======================== +* White panda is deprecated, upgrade to comma two or black panda * 2019 Nissan X-Trail and 2018 Nissan Leaf support thanks to avolmensky! Version 0.7.5 (2020-05-13) From 302d06ee709cb65dba39e836917f5693f0819efb Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Fri, 15 May 2020 13:53:01 -0700 Subject: [PATCH 006/656] thneed saves 45% of a core (#1512) * thneed runs the model * thneed is doing the hooking * set kernel args * thneeding the bufferS * print the images well * thneeds with better buffers * includes * disasm adreno * parse packets * disasm works * disasm better * more thneeding * much thneeding * much more thneeding * thneed works i think * thneed is patient * thneed works * 7.7% * gpuobj sync * yay, it mallocs now * cleaning it up, Thneed * sync objs and set power * thneed needs inputs and outputs * thneed in modeld * special modeld runs * can't thneed the DSP * test is weird * thneed modeld uses 6.4% CPU * add thneed to release * move to debug * delete some junk from the pr * always track the timestamp * timestamp hacks in thneed * create a new command queue * fix timestamp * pretty much back to what we had, you can't use SNPE with thneed * improve thneed test * disable save log Co-authored-by: Comma Device --- release/files_common | 3 + selfdrive/modeld/SConscript | 11 + selfdrive/modeld/runners/snpemodel.cc | 44 +- selfdrive/modeld/runners/snpemodel.h | 15 +- selfdrive/modeld/thneed/README | 8 + selfdrive/modeld/thneed/debug/.gitignore | 1 + .../modeld/thneed/debug/include/a5xx.xml.h | 5201 +++++++++++++++++ .../thneed/debug/include/adreno_pm4.xml.h | 1344 +++++ .../thneed/debug/include/adreno_pm4types.h | 473 ++ selfdrive/modeld/thneed/debug/main.cc | 733 +++ selfdrive/modeld/thneed/debug/test.cc | 95 + selfdrive/modeld/thneed/debug/thneed | 4 + selfdrive/modeld/thneed/include/msm_kgsl.h | 1449 +++++ selfdrive/modeld/thneed/thneed.cc | 363 ++ selfdrive/modeld/thneed/thneed.h | 50 + 15 files changed, 9788 insertions(+), 6 deletions(-) create mode 100644 selfdrive/modeld/thneed/README create mode 100644 selfdrive/modeld/thneed/debug/.gitignore create mode 100644 selfdrive/modeld/thneed/debug/include/a5xx.xml.h create mode 100644 selfdrive/modeld/thneed/debug/include/adreno_pm4.xml.h create mode 100644 selfdrive/modeld/thneed/debug/include/adreno_pm4types.h create mode 100644 selfdrive/modeld/thneed/debug/main.cc create mode 100644 selfdrive/modeld/thneed/debug/test.cc create mode 100755 selfdrive/modeld/thneed/debug/thneed create mode 100644 selfdrive/modeld/thneed/include/msm_kgsl.h create mode 100644 selfdrive/modeld/thneed/thneed.cc create mode 100644 selfdrive/modeld/thneed/thneed.h diff --git a/release/files_common b/release/files_common index ca05fbf756..eb849cce95 100644 --- a/release/files_common +++ b/release/files_common @@ -387,6 +387,9 @@ selfdrive/modeld/transforms/loadyuv.cl selfdrive/modeld/transforms/transform.[c,h] selfdrive/modeld/transforms/transform.cl +selfdrive/modeld/thneed/thneed.* +selfdrive/modeld/thneed/include/* + selfdrive/modeld/runners/snpemodel.cc selfdrive/modeld/runners/snpemodel.h selfdrive/modeld/runners/runmodel.h diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 0872b653a9..f70057d649 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -3,6 +3,8 @@ lenv = env.Clone() libs = [messaging, common, 'OpenCL', 'SNPE', 'capnp', 'zmq', 'kj', 'yuv', gpucommon, visionipc] +TEST_THNEED = False + common_src = [ "models/commonmodel.c", "runners/snpemodel.cc", @@ -11,6 +13,10 @@ common_src = [ if arch == "aarch64": libs += ['gsl', 'CB', 'gnustl_shared'] + if not TEST_THNEED: + common_src += ["thneed/thneed.cc"] + lenv['CFLAGS'].append("-DUSE_THNEED") + lenv['CXXFLAGS'].append("-DUSE_THNEED") elif arch == "larch64": libs += ['gsl', 'CB', 'symphony-cpu', 'pthread'] else: @@ -34,3 +40,8 @@ lenv.Program('_modeld', [ "models/driving.cc", ]+common, LIBS=libs) +if TEST_THNEED: + lenv.Program('thneed/debug/_thneed', [ + "thneed/thneed.cc", "thneed/debug/test.cc" + ]+common, LIBS=libs) + diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 4bb442d5e1..bab7432207 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -9,9 +9,9 @@ void PrintErrorStringAndExit() { std::exit(EXIT_FAILURE); } -SNPEModel::SNPEModel(const char *path, float *output, size_t output_size, int runtime) { +SNPEModel::SNPEModel(const char *path, float *loutput, size_t output_size, int runtime) { + output = loutput; #ifdef QCOM - zdl::DlSystem::Runtime_t Runtime; if (runtime==USE_GPU_RUNTIME) { Runtime = zdl::DlSystem::Runtime_t::GPU; } else if (runtime==USE_DSP_RUNTIME) { @@ -87,6 +87,13 @@ SNPEModel::SNPEModel(const char *path, float *output, size_t output_size, int ru // create output buffer { + const zdl::DlSystem::TensorShape& bufferShape = snpe->getInputOutputBufferAttributes(output_tensor_name)->getDims(); + if (output_size != 0) { + assert(output_size == bufferShape[1]); + } else { + output_size = bufferShape[1]; + } + std::vector outputStrides = {output_size * sizeof(float), sizeof(float)}; outputBuffer = ubFactory.createUserBuffer(output, output_size * sizeof(float), outputStrides, &userBufferEncodingFloat); outputMap.add(output_tensor_name, outputBuffer.get()); @@ -94,14 +101,17 @@ SNPEModel::SNPEModel(const char *path, float *output, size_t output_size, int ru } void SNPEModel::addRecurrent(float *state, int state_size) { + recurrent = state; recurrentBuffer = this->addExtra(state, state_size, 3); } void SNPEModel::addTrafficConvention(float *state, int state_size) { + trafficConvention = state; trafficConventionBuffer = this->addExtra(state, state_size, 2); } void SNPEModel::addDesire(float *state, int state_size) { + desire = state; desireBuffer = this->addExtra(state, state_size, 1); } @@ -122,9 +132,33 @@ std::unique_ptr SNPEModel::addExtra(float *state, in } void SNPEModel::execute(float *net_input_buf, int buf_size) { - assert(inputBuffer->setBufferAddress(net_input_buf)); - if (!snpe->execute(inputMap, outputMap)) { - PrintErrorStringAndExit(); +#ifdef USE_THNEED + if (Runtime == zdl::DlSystem::Runtime_t::GPU) { + if (thneed == NULL) { + assert(inputBuffer->setBufferAddress(net_input_buf)); + if (!snpe->execute(inputMap, outputMap)) { + PrintErrorStringAndExit(); + } + thneed = new Thneed(); + //thneed->record = 3; + if (!snpe->execute(inputMap, outputMap)) { + PrintErrorStringAndExit(); + } + thneed->stop(); + //thneed->record = 2; + printf("thneed cached\n"); + } else { + float *inputs[4] = {recurrent, trafficConvention, desire, net_input_buf}; + thneed->execute(inputs, output); + } + } else { +#endif + assert(inputBuffer->setBufferAddress(net_input_buf)); + if (!snpe->execute(inputMap, outputMap)) { + PrintErrorStringAndExit(); + } +#ifdef USE_THNEED } +#endif } diff --git a/selfdrive/modeld/runners/snpemodel.h b/selfdrive/modeld/runners/snpemodel.h index 9289444b09..496ad51db2 100644 --- a/selfdrive/modeld/runners/snpemodel.h +++ b/selfdrive/modeld/runners/snpemodel.h @@ -17,9 +17,13 @@ #define USE_GPU_RUNTIME 1 #define USE_DSP_RUNTIME 2 +#ifdef USE_THNEED +#include "thneed/thneed.h" +#endif + class SNPEModel : public RunModel { public: - SNPEModel(const char *path, float *output, size_t output_size, int runtime); + SNPEModel(const char *path, float *loutput, size_t output_size, int runtime); ~SNPEModel() { if (model_data) free(model_data); } @@ -30,6 +34,12 @@ public: private: uint8_t *model_data = NULL; +#ifdef USE_THNEED + Thneed *thneed = NULL; +#endif + + zdl::DlSystem::Runtime_t Runtime; + // snpe model stuff std::unique_ptr snpe; @@ -44,8 +54,11 @@ private: // recurrent and desire std::unique_ptr addExtra(float *state, int state_size, int idx); + float *recurrent; std::unique_ptr recurrentBuffer; + float *trafficConvention; std::unique_ptr trafficConventionBuffer; + float *desire; std::unique_ptr desireBuffer; }; diff --git a/selfdrive/modeld/thneed/README b/selfdrive/modeld/thneed/README new file mode 100644 index 0000000000..f3bc66d8fc --- /dev/null +++ b/selfdrive/modeld/thneed/README @@ -0,0 +1,8 @@ +thneed is an SNPE accelerator. I know SNPE is already an accelerator, but sometimes things need to go even faster.. + +It runs on the local device, and caches a single model run. Then it replays it, but fast. + +thneed slices through abstraction layers like a fish. + +You need a thneed. + diff --git a/selfdrive/modeld/thneed/debug/.gitignore b/selfdrive/modeld/thneed/debug/.gitignore new file mode 100644 index 0000000000..b7ed9fb0a7 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/.gitignore @@ -0,0 +1 @@ +_thneed diff --git a/selfdrive/modeld/thneed/debug/include/a5xx.xml.h b/selfdrive/modeld/thneed/debug/include/a5xx.xml.h new file mode 100644 index 0000000000..4a61d4e72c --- /dev/null +++ b/selfdrive/modeld/thneed/debug/include/a5xx.xml.h @@ -0,0 +1,5201 @@ +#ifndef A5XX_XML +#define A5XX_XML + +/* Autogenerated file, DO NOT EDIT manually! + +This file was generated by the rules-ng-ng headergen tool in this git repository: +http://github.com/freedreno/envytools/ +git clone https://github.com/freedreno/envytools.git + +The rules-ng-ng source files this header was generated from are: +- /home/ubuntu/envytools/envytools/rnndb/./adreno.xml ( 501 bytes, from 2019-05-29 01:28:15) +- /home/ubuntu/envytools/envytools/rnndb/freedreno_copyright.xml ( 1572 bytes, from 2019-05-29 01:28:15) +- /home/ubuntu/envytools/envytools/rnndb/adreno/a2xx.xml ( 79608 bytes, from 2019-05-29 01:28:15) +- /home/ubuntu/envytools/envytools/rnndb/adreno/adreno_common.xml ( 14239 bytes, from 2019-05-29 01:28:15) +- /home/ubuntu/envytools/envytools/rnndb/adreno/adreno_pm4.xml ( 43155 bytes, from 2019-05-29 01:28:15) +- /home/ubuntu/envytools/envytools/rnndb/adreno/a3xx.xml ( 83840 bytes, from 2019-05-29 01:28:15) +- /home/ubuntu/envytools/envytools/rnndb/adreno/a4xx.xml ( 112086 bytes, from 2019-05-29 01:28:15) +- /home/ubuntu/envytools/envytools/rnndb/adreno/a5xx.xml ( 147291 bytes, from 2019-05-29 14:51:41) +- /home/ubuntu/envytools/envytools/rnndb/adreno/a6xx.xml ( 148461 bytes, from 2019-05-29 01:28:15) +- /home/ubuntu/envytools/envytools/rnndb/adreno/a6xx_gmu.xml ( 10431 bytes, from 2019-05-29 01:28:15) +- /home/ubuntu/envytools/envytools/rnndb/adreno/ocmem.xml ( 1773 bytes, from 2019-05-29 01:28:15) + +Copyright (C) 2013-2019 by the following authors: +- Rob Clark (robclark) +- Ilia Mirkin (imirkin) + +Permission is hereby granted, free of charge, to any person obtaining +a copy of this software and associated documentation files (the +"Software"), to deal in the Software without restriction, including +without limitation the rights to use, copy, modify, merge, publish, +distribute, sublicense, and/or sell copies of the Software, and to +permit persons to whom the Software is furnished to do so, subject to +the following conditions: + +The above copyright notice and this permission notice (including the +next paragraph) shall be included in all copies or substantial +portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, +EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. +IN NO EVENT SHALL THE COPYRIGHT OWNER(S) AND/OR ITS SUPPLIERS BE +LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION +OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION +WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + + +enum a5xx_color_fmt { + RB5_A8_UNORM = 2, + RB5_R8_UNORM = 3, + RB5_R8_SNORM = 4, + RB5_R8_UINT = 5, + RB5_R8_SINT = 6, + RB5_R4G4B4A4_UNORM = 8, + RB5_R5G5B5A1_UNORM = 10, + RB5_R5G6B5_UNORM = 14, + RB5_R8G8_UNORM = 15, + RB5_R8G8_SNORM = 16, + RB5_R8G8_UINT = 17, + RB5_R8G8_SINT = 18, + RB5_R16_UNORM = 21, + RB5_R16_SNORM = 22, + RB5_R16_FLOAT = 23, + RB5_R16_UINT = 24, + RB5_R16_SINT = 25, + RB5_R8G8B8A8_UNORM = 48, + RB5_R8G8B8_UNORM = 49, + RB5_R8G8B8A8_SNORM = 50, + RB5_R8G8B8A8_UINT = 51, + RB5_R8G8B8A8_SINT = 52, + RB5_R10G10B10A2_UNORM = 55, + RB5_R10G10B10A2_UINT = 58, + RB5_R11G11B10_FLOAT = 66, + RB5_R16G16_UNORM = 67, + RB5_R16G16_SNORM = 68, + RB5_R16G16_FLOAT = 69, + RB5_R16G16_UINT = 70, + RB5_R16G16_SINT = 71, + RB5_R32_FLOAT = 74, + RB5_R32_UINT = 75, + RB5_R32_SINT = 76, + RB5_R16G16B16A16_UNORM = 96, + RB5_R16G16B16A16_SNORM = 97, + RB5_R16G16B16A16_FLOAT = 98, + RB5_R16G16B16A16_UINT = 99, + RB5_R16G16B16A16_SINT = 100, + RB5_R32G32_FLOAT = 103, + RB5_R32G32_UINT = 104, + RB5_R32G32_SINT = 105, + RB5_R32G32B32A32_FLOAT = 130, + RB5_R32G32B32A32_UINT = 131, + RB5_R32G32B32A32_SINT = 132, +}; + +enum a5xx_tile_mode { + TILE5_LINEAR = 0, + TILE5_2 = 2, + TILE5_3 = 3, +}; + +enum a5xx_vtx_fmt { + VFMT5_8_UNORM = 3, + VFMT5_8_SNORM = 4, + VFMT5_8_UINT = 5, + VFMT5_8_SINT = 6, + VFMT5_8_8_UNORM = 15, + VFMT5_8_8_SNORM = 16, + VFMT5_8_8_UINT = 17, + VFMT5_8_8_SINT = 18, + VFMT5_16_UNORM = 21, + VFMT5_16_SNORM = 22, + VFMT5_16_FLOAT = 23, + VFMT5_16_UINT = 24, + VFMT5_16_SINT = 25, + VFMT5_8_8_8_UNORM = 33, + VFMT5_8_8_8_SNORM = 34, + VFMT5_8_8_8_UINT = 35, + VFMT5_8_8_8_SINT = 36, + VFMT5_8_8_8_8_UNORM = 48, + VFMT5_8_8_8_8_SNORM = 50, + VFMT5_8_8_8_8_UINT = 51, + VFMT5_8_8_8_8_SINT = 52, + VFMT5_10_10_10_2_UNORM = 54, + VFMT5_10_10_10_2_SNORM = 57, + VFMT5_10_10_10_2_UINT = 58, + VFMT5_10_10_10_2_SINT = 59, + VFMT5_11_11_10_FLOAT = 66, + VFMT5_16_16_UNORM = 67, + VFMT5_16_16_SNORM = 68, + VFMT5_16_16_FLOAT = 69, + VFMT5_16_16_UINT = 70, + VFMT5_16_16_SINT = 71, + VFMT5_32_UNORM = 72, + VFMT5_32_SNORM = 73, + VFMT5_32_FLOAT = 74, + VFMT5_32_UINT = 75, + VFMT5_32_SINT = 76, + VFMT5_32_FIXED = 77, + VFMT5_16_16_16_UNORM = 88, + VFMT5_16_16_16_SNORM = 89, + VFMT5_16_16_16_FLOAT = 90, + VFMT5_16_16_16_UINT = 91, + VFMT5_16_16_16_SINT = 92, + VFMT5_16_16_16_16_UNORM = 96, + VFMT5_16_16_16_16_SNORM = 97, + VFMT5_16_16_16_16_FLOAT = 98, + VFMT5_16_16_16_16_UINT = 99, + VFMT5_16_16_16_16_SINT = 100, + VFMT5_32_32_UNORM = 101, + VFMT5_32_32_SNORM = 102, + VFMT5_32_32_FLOAT = 103, + VFMT5_32_32_UINT = 104, + VFMT5_32_32_SINT = 105, + VFMT5_32_32_FIXED = 106, + VFMT5_32_32_32_UNORM = 112, + VFMT5_32_32_32_SNORM = 113, + VFMT5_32_32_32_UINT = 114, + VFMT5_32_32_32_SINT = 115, + VFMT5_32_32_32_FLOAT = 116, + VFMT5_32_32_32_FIXED = 117, + VFMT5_32_32_32_32_UNORM = 128, + VFMT5_32_32_32_32_SNORM = 129, + VFMT5_32_32_32_32_FLOAT = 130, + VFMT5_32_32_32_32_UINT = 131, + VFMT5_32_32_32_32_SINT = 132, + VFMT5_32_32_32_32_FIXED = 133, +}; + +enum a5xx_tex_fmt { + TFMT5_A8_UNORM = 2, + TFMT5_8_UNORM = 3, + TFMT5_8_SNORM = 4, + TFMT5_8_UINT = 5, + TFMT5_8_SINT = 6, + TFMT5_4_4_4_4_UNORM = 8, + TFMT5_5_5_5_1_UNORM = 10, + TFMT5_5_6_5_UNORM = 14, + TFMT5_8_8_UNORM = 15, + TFMT5_8_8_SNORM = 16, + TFMT5_8_8_UINT = 17, + TFMT5_8_8_SINT = 18, + TFMT5_L8_A8_UNORM = 19, + TFMT5_16_UNORM = 21, + TFMT5_16_SNORM = 22, + TFMT5_16_FLOAT = 23, + TFMT5_16_UINT = 24, + TFMT5_16_SINT = 25, + TFMT5_8_8_8_8_UNORM = 48, + TFMT5_8_8_8_UNORM = 49, + TFMT5_8_8_8_8_SNORM = 50, + TFMT5_8_8_8_8_UINT = 51, + TFMT5_8_8_8_8_SINT = 52, + TFMT5_9_9_9_E5_FLOAT = 53, + TFMT5_10_10_10_2_UNORM = 54, + TFMT5_10_10_10_2_UINT = 58, + TFMT5_11_11_10_FLOAT = 66, + TFMT5_16_16_UNORM = 67, + TFMT5_16_16_SNORM = 68, + TFMT5_16_16_FLOAT = 69, + TFMT5_16_16_UINT = 70, + TFMT5_16_16_SINT = 71, + TFMT5_32_FLOAT = 74, + TFMT5_32_UINT = 75, + TFMT5_32_SINT = 76, + TFMT5_16_16_16_16_UNORM = 96, + TFMT5_16_16_16_16_SNORM = 97, + TFMT5_16_16_16_16_FLOAT = 98, + TFMT5_16_16_16_16_UINT = 99, + TFMT5_16_16_16_16_SINT = 100, + TFMT5_32_32_FLOAT = 103, + TFMT5_32_32_UINT = 104, + TFMT5_32_32_SINT = 105, + TFMT5_32_32_32_UINT = 114, + TFMT5_32_32_32_SINT = 115, + TFMT5_32_32_32_FLOAT = 116, + TFMT5_32_32_32_32_FLOAT = 130, + TFMT5_32_32_32_32_UINT = 131, + TFMT5_32_32_32_32_SINT = 132, + TFMT5_X8Z24_UNORM = 160, + TFMT5_ETC2_RG11_UNORM = 171, + TFMT5_ETC2_RG11_SNORM = 172, + TFMT5_ETC2_R11_UNORM = 173, + TFMT5_ETC2_R11_SNORM = 174, + TFMT5_ETC1 = 175, + TFMT5_ETC2_RGB8 = 176, + TFMT5_ETC2_RGBA8 = 177, + TFMT5_ETC2_RGB8A1 = 178, + TFMT5_DXT1 = 179, + TFMT5_DXT3 = 180, + TFMT5_DXT5 = 181, + TFMT5_RGTC1_UNORM = 183, + TFMT5_RGTC1_SNORM = 184, + TFMT5_RGTC2_UNORM = 187, + TFMT5_RGTC2_SNORM = 188, + TFMT5_BPTC_UFLOAT = 190, + TFMT5_BPTC_FLOAT = 191, + TFMT5_BPTC = 192, + TFMT5_ASTC_4x4 = 193, + TFMT5_ASTC_5x4 = 194, + TFMT5_ASTC_5x5 = 195, + TFMT5_ASTC_6x5 = 196, + TFMT5_ASTC_6x6 = 197, + TFMT5_ASTC_8x5 = 198, + TFMT5_ASTC_8x6 = 199, + TFMT5_ASTC_8x8 = 200, + TFMT5_ASTC_10x5 = 201, + TFMT5_ASTC_10x6 = 202, + TFMT5_ASTC_10x8 = 203, + TFMT5_ASTC_10x10 = 204, + TFMT5_ASTC_12x10 = 205, + TFMT5_ASTC_12x12 = 206, +}; + +enum a5xx_tex_fetchsize { + TFETCH5_1_BYTE = 0, + TFETCH5_2_BYTE = 1, + TFETCH5_4_BYTE = 2, + TFETCH5_8_BYTE = 3, + TFETCH5_16_BYTE = 4, +}; + +enum a5xx_depth_format { + DEPTH5_NONE = 0, + DEPTH5_16 = 1, + DEPTH5_24_8 = 2, + DEPTH5_32 = 4, +}; + +enum a5xx_blit_buf { + BLIT_MRT0 = 0, + BLIT_MRT1 = 1, + BLIT_MRT2 = 2, + BLIT_MRT3 = 3, + BLIT_MRT4 = 4, + BLIT_MRT5 = 5, + BLIT_MRT6 = 6, + BLIT_MRT7 = 7, + BLIT_ZS = 8, + BLIT_S = 9, +}; + +enum a5xx_cp_perfcounter_select { + PERF_CP_ALWAYS_COUNT = 0, + PERF_CP_BUSY_GFX_CORE_IDLE = 1, + PERF_CP_BUSY_CYCLES = 2, + PERF_CP_PFP_IDLE = 3, + PERF_CP_PFP_BUSY_WORKING = 4, + PERF_CP_PFP_STALL_CYCLES_ANY = 5, + PERF_CP_PFP_STARVE_CYCLES_ANY = 6, + PERF_CP_PFP_ICACHE_MISS = 7, + PERF_CP_PFP_ICACHE_HIT = 8, + PERF_CP_PFP_MATCH_PM4_PKT_PROFILE = 9, + PERF_CP_ME_BUSY_WORKING = 10, + PERF_CP_ME_IDLE = 11, + PERF_CP_ME_STARVE_CYCLES_ANY = 12, + PERF_CP_ME_FIFO_EMPTY_PFP_IDLE = 13, + PERF_CP_ME_FIFO_EMPTY_PFP_BUSY = 14, + PERF_CP_ME_FIFO_FULL_ME_BUSY = 15, + PERF_CP_ME_FIFO_FULL_ME_NON_WORKING = 16, + PERF_CP_ME_STALL_CYCLES_ANY = 17, + PERF_CP_ME_ICACHE_MISS = 18, + PERF_CP_ME_ICACHE_HIT = 19, + PERF_CP_NUM_PREEMPTIONS = 20, + PERF_CP_PREEMPTION_REACTION_DELAY = 21, + PERF_CP_PREEMPTION_SWITCH_OUT_TIME = 22, + PERF_CP_PREEMPTION_SWITCH_IN_TIME = 23, + PERF_CP_DEAD_DRAWS_IN_BIN_RENDER = 24, + PERF_CP_PREDICATED_DRAWS_KILLED = 25, + PERF_CP_MODE_SWITCH = 26, + PERF_CP_ZPASS_DONE = 27, + PERF_CP_CONTEXT_DONE = 28, + PERF_CP_CACHE_FLUSH = 29, + PERF_CP_LONG_PREEMPTIONS = 30, +}; + +enum a5xx_rbbm_perfcounter_select { + PERF_RBBM_ALWAYS_COUNT = 0, + PERF_RBBM_ALWAYS_ON = 1, + PERF_RBBM_TSE_BUSY = 2, + PERF_RBBM_RAS_BUSY = 3, + PERF_RBBM_PC_DCALL_BUSY = 4, + PERF_RBBM_PC_VSD_BUSY = 5, + PERF_RBBM_STATUS_MASKED = 6, + PERF_RBBM_COM_BUSY = 7, + PERF_RBBM_DCOM_BUSY = 8, + PERF_RBBM_VBIF_BUSY = 9, + PERF_RBBM_VSC_BUSY = 10, + PERF_RBBM_TESS_BUSY = 11, + PERF_RBBM_UCHE_BUSY = 12, + PERF_RBBM_HLSQ_BUSY = 13, +}; + +enum a5xx_pc_perfcounter_select { + PERF_PC_BUSY_CYCLES = 0, + PERF_PC_WORKING_CYCLES = 1, + PERF_PC_STALL_CYCLES_VFD = 2, + PERF_PC_STALL_CYCLES_TSE = 3, + PERF_PC_STALL_CYCLES_VPC = 4, + PERF_PC_STALL_CYCLES_UCHE = 5, + PERF_PC_STALL_CYCLES_TESS = 6, + PERF_PC_STALL_CYCLES_TSE_ONLY = 7, + PERF_PC_STALL_CYCLES_VPC_ONLY = 8, + PERF_PC_PASS1_TF_STALL_CYCLES = 9, + PERF_PC_STARVE_CYCLES_FOR_INDEX = 10, + PERF_PC_STARVE_CYCLES_FOR_TESS_FACTOR = 11, + PERF_PC_STARVE_CYCLES_FOR_VIZ_STREAM = 12, + PERF_PC_STARVE_CYCLES_FOR_POSITION = 13, + PERF_PC_STARVE_CYCLES_DI = 14, + PERF_PC_VIS_STREAMS_LOADED = 15, + PERF_PC_INSTANCES = 16, + PERF_PC_VPC_PRIMITIVES = 17, + PERF_PC_DEAD_PRIM = 18, + PERF_PC_LIVE_PRIM = 19, + PERF_PC_VERTEX_HITS = 20, + PERF_PC_IA_VERTICES = 21, + PERF_PC_IA_PRIMITIVES = 22, + PERF_PC_GS_PRIMITIVES = 23, + PERF_PC_HS_INVOCATIONS = 24, + PERF_PC_DS_INVOCATIONS = 25, + PERF_PC_VS_INVOCATIONS = 26, + PERF_PC_GS_INVOCATIONS = 27, + PERF_PC_DS_PRIMITIVES = 28, + PERF_PC_VPC_POS_DATA_TRANSACTION = 29, + PERF_PC_3D_DRAWCALLS = 30, + PERF_PC_2D_DRAWCALLS = 31, + PERF_PC_NON_DRAWCALL_GLOBAL_EVENTS = 32, + PERF_TESS_BUSY_CYCLES = 33, + PERF_TESS_WORKING_CYCLES = 34, + PERF_TESS_STALL_CYCLES_PC = 35, + PERF_TESS_STARVE_CYCLES_PC = 36, +}; + +enum a5xx_vfd_perfcounter_select { + PERF_VFD_BUSY_CYCLES = 0, + PERF_VFD_STALL_CYCLES_UCHE = 1, + PERF_VFD_STALL_CYCLES_VPC_ALLOC = 2, + PERF_VFD_STALL_CYCLES_MISS_VB = 3, + PERF_VFD_STALL_CYCLES_MISS_Q = 4, + PERF_VFD_STALL_CYCLES_SP_INFO = 5, + PERF_VFD_STALL_CYCLES_SP_ATTR = 6, + PERF_VFD_STALL_CYCLES_VFDP_VB = 7, + PERF_VFD_STALL_CYCLES_VFDP_Q = 8, + PERF_VFD_DECODER_PACKER_STALL = 9, + PERF_VFD_STARVE_CYCLES_UCHE = 10, + PERF_VFD_RBUFFER_FULL = 11, + PERF_VFD_ATTR_INFO_FIFO_FULL = 12, + PERF_VFD_DECODED_ATTRIBUTE_BYTES = 13, + PERF_VFD_NUM_ATTRIBUTES = 14, + PERF_VFD_INSTRUCTIONS = 15, + PERF_VFD_UPPER_SHADER_FIBERS = 16, + PERF_VFD_LOWER_SHADER_FIBERS = 17, + PERF_VFD_MODE_0_FIBERS = 18, + PERF_VFD_MODE_1_FIBERS = 19, + PERF_VFD_MODE_2_FIBERS = 20, + PERF_VFD_MODE_3_FIBERS = 21, + PERF_VFD_MODE_4_FIBERS = 22, + PERF_VFD_TOTAL_VERTICES = 23, + PERF_VFD_NUM_ATTR_MISS = 24, + PERF_VFD_1_BURST_REQ = 25, + PERF_VFDP_STALL_CYCLES_VFD = 26, + PERF_VFDP_STALL_CYCLES_VFD_INDEX = 27, + PERF_VFDP_STALL_CYCLES_VFD_PROG = 28, + PERF_VFDP_STARVE_CYCLES_PC = 29, + PERF_VFDP_VS_STAGE_32_WAVES = 30, +}; + +enum a5xx_hlsq_perfcounter_select { + PERF_HLSQ_BUSY_CYCLES = 0, + PERF_HLSQ_STALL_CYCLES_UCHE = 1, + PERF_HLSQ_STALL_CYCLES_SP_STATE = 2, + PERF_HLSQ_STALL_CYCLES_SP_FS_STAGE = 3, + PERF_HLSQ_UCHE_LATENCY_CYCLES = 4, + PERF_HLSQ_UCHE_LATENCY_COUNT = 5, + PERF_HLSQ_FS_STAGE_32_WAVES = 6, + PERF_HLSQ_FS_STAGE_64_WAVES = 7, + PERF_HLSQ_QUADS = 8, + PERF_HLSQ_SP_STATE_COPY_TRANS_FS_STAGE = 9, + PERF_HLSQ_SP_STATE_COPY_TRANS_VS_STAGE = 10, + PERF_HLSQ_TP_STATE_COPY_TRANS_FS_STAGE = 11, + PERF_HLSQ_TP_STATE_COPY_TRANS_VS_STAGE = 12, + PERF_HLSQ_CS_INVOCATIONS = 13, + PERF_HLSQ_COMPUTE_DRAWCALLS = 14, +}; + +enum a5xx_vpc_perfcounter_select { + PERF_VPC_BUSY_CYCLES = 0, + PERF_VPC_WORKING_CYCLES = 1, + PERF_VPC_STALL_CYCLES_UCHE = 2, + PERF_VPC_STALL_CYCLES_VFD_WACK = 3, + PERF_VPC_STALL_CYCLES_HLSQ_PRIM_ALLOC = 4, + PERF_VPC_STALL_CYCLES_PC = 5, + PERF_VPC_STALL_CYCLES_SP_LM = 6, + PERF_VPC_POS_EXPORT_STALL_CYCLES = 7, + PERF_VPC_STARVE_CYCLES_SP = 8, + PERF_VPC_STARVE_CYCLES_LRZ = 9, + PERF_VPC_PC_PRIMITIVES = 10, + PERF_VPC_SP_COMPONENTS = 11, + PERF_VPC_SP_LM_PRIMITIVES = 12, + PERF_VPC_SP_LM_COMPONENTS = 13, + PERF_VPC_SP_LM_DWORDS = 14, + PERF_VPC_STREAMOUT_COMPONENTS = 15, + PERF_VPC_GRANT_PHASES = 16, +}; + +enum a5xx_tse_perfcounter_select { + PERF_TSE_BUSY_CYCLES = 0, + PERF_TSE_CLIPPING_CYCLES = 1, + PERF_TSE_STALL_CYCLES_RAS = 2, + PERF_TSE_STALL_CYCLES_LRZ_BARYPLANE = 3, + PERF_TSE_STALL_CYCLES_LRZ_ZPLANE = 4, + PERF_TSE_STARVE_CYCLES_PC = 5, + PERF_TSE_INPUT_PRIM = 6, + PERF_TSE_INPUT_NULL_PRIM = 7, + PERF_TSE_TRIVAL_REJ_PRIM = 8, + PERF_TSE_CLIPPED_PRIM = 9, + PERF_TSE_ZERO_AREA_PRIM = 10, + PERF_TSE_FACENESS_CULLED_PRIM = 11, + PERF_TSE_ZERO_PIXEL_PRIM = 12, + PERF_TSE_OUTPUT_NULL_PRIM = 13, + PERF_TSE_OUTPUT_VISIBLE_PRIM = 14, + PERF_TSE_CINVOCATION = 15, + PERF_TSE_CPRIMITIVES = 16, + PERF_TSE_2D_INPUT_PRIM = 17, + PERF_TSE_2D_ALIVE_CLCLES = 18, +}; + +enum a5xx_ras_perfcounter_select { + PERF_RAS_BUSY_CYCLES = 0, + PERF_RAS_SUPERTILE_ACTIVE_CYCLES = 1, + PERF_RAS_STALL_CYCLES_LRZ = 2, + PERF_RAS_STARVE_CYCLES_TSE = 3, + PERF_RAS_SUPER_TILES = 4, + PERF_RAS_8X4_TILES = 5, + PERF_RAS_MASKGEN_ACTIVE = 6, + PERF_RAS_FULLY_COVERED_SUPER_TILES = 7, + PERF_RAS_FULLY_COVERED_8X4_TILES = 8, + PERF_RAS_PRIM_KILLED_INVISILBE = 9, +}; + +enum a5xx_lrz_perfcounter_select { + PERF_LRZ_BUSY_CYCLES = 0, + PERF_LRZ_STARVE_CYCLES_RAS = 1, + PERF_LRZ_STALL_CYCLES_RB = 2, + PERF_LRZ_STALL_CYCLES_VSC = 3, + PERF_LRZ_STALL_CYCLES_VPC = 4, + PERF_LRZ_STALL_CYCLES_FLAG_PREFETCH = 5, + PERF_LRZ_STALL_CYCLES_UCHE = 6, + PERF_LRZ_LRZ_READ = 7, + PERF_LRZ_LRZ_WRITE = 8, + PERF_LRZ_READ_LATENCY = 9, + PERF_LRZ_MERGE_CACHE_UPDATING = 10, + PERF_LRZ_PRIM_KILLED_BY_MASKGEN = 11, + PERF_LRZ_PRIM_KILLED_BY_LRZ = 12, + PERF_LRZ_VISIBLE_PRIM_AFTER_LRZ = 13, + PERF_LRZ_FULL_8X8_TILES = 14, + PERF_LRZ_PARTIAL_8X8_TILES = 15, + PERF_LRZ_TILE_KILLED = 16, + PERF_LRZ_TOTAL_PIXEL = 17, + PERF_LRZ_VISIBLE_PIXEL_AFTER_LRZ = 18, +}; + +enum a5xx_uche_perfcounter_select { + PERF_UCHE_BUSY_CYCLES = 0, + PERF_UCHE_STALL_CYCLES_VBIF = 1, + PERF_UCHE_VBIF_LATENCY_CYCLES = 2, + PERF_UCHE_VBIF_LATENCY_SAMPLES = 3, + PERF_UCHE_VBIF_READ_BEATS_TP = 4, + PERF_UCHE_VBIF_READ_BEATS_VFD = 5, + PERF_UCHE_VBIF_READ_BEATS_HLSQ = 6, + PERF_UCHE_VBIF_READ_BEATS_LRZ = 7, + PERF_UCHE_VBIF_READ_BEATS_SP = 8, + PERF_UCHE_READ_REQUESTS_TP = 9, + PERF_UCHE_READ_REQUESTS_VFD = 10, + PERF_UCHE_READ_REQUESTS_HLSQ = 11, + PERF_UCHE_READ_REQUESTS_LRZ = 12, + PERF_UCHE_READ_REQUESTS_SP = 13, + PERF_UCHE_WRITE_REQUESTS_LRZ = 14, + PERF_UCHE_WRITE_REQUESTS_SP = 15, + PERF_UCHE_WRITE_REQUESTS_VPC = 16, + PERF_UCHE_WRITE_REQUESTS_VSC = 17, + PERF_UCHE_EVICTS = 18, + PERF_UCHE_BANK_REQ0 = 19, + PERF_UCHE_BANK_REQ1 = 20, + PERF_UCHE_BANK_REQ2 = 21, + PERF_UCHE_BANK_REQ3 = 22, + PERF_UCHE_BANK_REQ4 = 23, + PERF_UCHE_BANK_REQ5 = 24, + PERF_UCHE_BANK_REQ6 = 25, + PERF_UCHE_BANK_REQ7 = 26, + PERF_UCHE_VBIF_READ_BEATS_CH0 = 27, + PERF_UCHE_VBIF_READ_BEATS_CH1 = 28, + PERF_UCHE_GMEM_READ_BEATS = 29, + PERF_UCHE_FLAG_COUNT = 30, +}; + +enum a5xx_tp_perfcounter_select { + PERF_TP_BUSY_CYCLES = 0, + PERF_TP_STALL_CYCLES_UCHE = 1, + PERF_TP_LATENCY_CYCLES = 2, + PERF_TP_LATENCY_TRANS = 3, + PERF_TP_FLAG_CACHE_REQUEST_SAMPLES = 4, + PERF_TP_FLAG_CACHE_REQUEST_LATENCY = 5, + PERF_TP_L1_CACHELINE_REQUESTS = 6, + PERF_TP_L1_CACHELINE_MISSES = 7, + PERF_TP_SP_TP_TRANS = 8, + PERF_TP_TP_SP_TRANS = 9, + PERF_TP_OUTPUT_PIXELS = 10, + PERF_TP_FILTER_WORKLOAD_16BIT = 11, + PERF_TP_FILTER_WORKLOAD_32BIT = 12, + PERF_TP_QUADS_RECEIVED = 13, + PERF_TP_QUADS_OFFSET = 14, + PERF_TP_QUADS_SHADOW = 15, + PERF_TP_QUADS_ARRAY = 16, + PERF_TP_QUADS_GRADIENT = 17, + PERF_TP_QUADS_1D = 18, + PERF_TP_QUADS_2D = 19, + PERF_TP_QUADS_BUFFER = 20, + PERF_TP_QUADS_3D = 21, + PERF_TP_QUADS_CUBE = 22, + PERF_TP_STATE_CACHE_REQUESTS = 23, + PERF_TP_STATE_CACHE_MISSES = 24, + PERF_TP_DIVERGENT_QUADS_RECEIVED = 25, + PERF_TP_BINDLESS_STATE_CACHE_REQUESTS = 26, + PERF_TP_BINDLESS_STATE_CACHE_MISSES = 27, + PERF_TP_PRT_NON_RESIDENT_EVENTS = 28, + PERF_TP_OUTPUT_PIXELS_POINT = 29, + PERF_TP_OUTPUT_PIXELS_BILINEAR = 30, + PERF_TP_OUTPUT_PIXELS_MIP = 31, + PERF_TP_OUTPUT_PIXELS_ANISO = 32, + PERF_TP_OUTPUT_PIXELS_ZERO_LOD = 33, + PERF_TP_FLAG_CACHE_REQUESTS = 34, + PERF_TP_FLAG_CACHE_MISSES = 35, + PERF_TP_L1_5_L2_REQUESTS = 36, + PERF_TP_2D_OUTPUT_PIXELS = 37, + PERF_TP_2D_OUTPUT_PIXELS_POINT = 38, + PERF_TP_2D_OUTPUT_PIXELS_BILINEAR = 39, + PERF_TP_2D_FILTER_WORKLOAD_16BIT = 40, + PERF_TP_2D_FILTER_WORKLOAD_32BIT = 41, +}; + +enum a5xx_sp_perfcounter_select { + PERF_SP_BUSY_CYCLES = 0, + PERF_SP_ALU_WORKING_CYCLES = 1, + PERF_SP_EFU_WORKING_CYCLES = 2, + PERF_SP_STALL_CYCLES_VPC = 3, + PERF_SP_STALL_CYCLES_TP = 4, + PERF_SP_STALL_CYCLES_UCHE = 5, + PERF_SP_STALL_CYCLES_RB = 6, + PERF_SP_SCHEDULER_NON_WORKING = 7, + PERF_SP_WAVE_CONTEXTS = 8, + PERF_SP_WAVE_CONTEXT_CYCLES = 9, + PERF_SP_FS_STAGE_WAVE_CYCLES = 10, + PERF_SP_FS_STAGE_WAVE_SAMPLES = 11, + PERF_SP_VS_STAGE_WAVE_CYCLES = 12, + PERF_SP_VS_STAGE_WAVE_SAMPLES = 13, + PERF_SP_FS_STAGE_DURATION_CYCLES = 14, + PERF_SP_VS_STAGE_DURATION_CYCLES = 15, + PERF_SP_WAVE_CTRL_CYCLES = 16, + PERF_SP_WAVE_LOAD_CYCLES = 17, + PERF_SP_WAVE_EMIT_CYCLES = 18, + PERF_SP_WAVE_NOP_CYCLES = 19, + PERF_SP_WAVE_WAIT_CYCLES = 20, + PERF_SP_WAVE_FETCH_CYCLES = 21, + PERF_SP_WAVE_IDLE_CYCLES = 22, + PERF_SP_WAVE_END_CYCLES = 23, + PERF_SP_WAVE_LONG_SYNC_CYCLES = 24, + PERF_SP_WAVE_SHORT_SYNC_CYCLES = 25, + PERF_SP_WAVE_JOIN_CYCLES = 26, + PERF_SP_LM_LOAD_INSTRUCTIONS = 27, + PERF_SP_LM_STORE_INSTRUCTIONS = 28, + PERF_SP_LM_ATOMICS = 29, + PERF_SP_GM_LOAD_INSTRUCTIONS = 30, + PERF_SP_GM_STORE_INSTRUCTIONS = 31, + PERF_SP_GM_ATOMICS = 32, + PERF_SP_VS_STAGE_TEX_INSTRUCTIONS = 33, + PERF_SP_VS_STAGE_CFLOW_INSTRUCTIONS = 34, + PERF_SP_VS_STAGE_EFU_INSTRUCTIONS = 35, + PERF_SP_VS_STAGE_FULL_ALU_INSTRUCTIONS = 36, + PERF_SP_VS_STAGE_HALF_ALU_INSTRUCTIONS = 37, + PERF_SP_FS_STAGE_TEX_INSTRUCTIONS = 38, + PERF_SP_FS_STAGE_CFLOW_INSTRUCTIONS = 39, + PERF_SP_FS_STAGE_EFU_INSTRUCTIONS = 40, + PERF_SP_FS_STAGE_FULL_ALU_INSTRUCTIONS = 41, + PERF_SP_FS_STAGE_HALF_ALU_INSTRUCTIONS = 42, + PERF_SP_FS_STAGE_BARY_INSTRUCTIONS = 43, + PERF_SP_VS_INSTRUCTIONS = 44, + PERF_SP_FS_INSTRUCTIONS = 45, + PERF_SP_ADDR_LOCK_COUNT = 46, + PERF_SP_UCHE_READ_TRANS = 47, + PERF_SP_UCHE_WRITE_TRANS = 48, + PERF_SP_EXPORT_VPC_TRANS = 49, + PERF_SP_EXPORT_RB_TRANS = 50, + PERF_SP_PIXELS_KILLED = 51, + PERF_SP_ICL1_REQUESTS = 52, + PERF_SP_ICL1_MISSES = 53, + PERF_SP_ICL0_REQUESTS = 54, + PERF_SP_ICL0_MISSES = 55, + PERF_SP_HS_INSTRUCTIONS = 56, + PERF_SP_DS_INSTRUCTIONS = 57, + PERF_SP_GS_INSTRUCTIONS = 58, + PERF_SP_CS_INSTRUCTIONS = 59, + PERF_SP_GPR_READ = 60, + PERF_SP_GPR_WRITE = 61, + PERF_SP_LM_CH0_REQUESTS = 62, + PERF_SP_LM_CH1_REQUESTS = 63, + PERF_SP_LM_BANK_CONFLICTS = 64, +}; + +enum a5xx_rb_perfcounter_select { + PERF_RB_BUSY_CYCLES = 0, + PERF_RB_STALL_CYCLES_CCU = 1, + PERF_RB_STALL_CYCLES_HLSQ = 2, + PERF_RB_STALL_CYCLES_FIFO0_FULL = 3, + PERF_RB_STALL_CYCLES_FIFO1_FULL = 4, + PERF_RB_STALL_CYCLES_FIFO2_FULL = 5, + PERF_RB_STARVE_CYCLES_SP = 6, + PERF_RB_STARVE_CYCLES_LRZ_TILE = 7, + PERF_RB_STARVE_CYCLES_CCU = 8, + PERF_RB_STARVE_CYCLES_Z_PLANE = 9, + PERF_RB_STARVE_CYCLES_BARY_PLANE = 10, + PERF_RB_Z_WORKLOAD = 11, + PERF_RB_HLSQ_ACTIVE = 12, + PERF_RB_Z_READ = 13, + PERF_RB_Z_WRITE = 14, + PERF_RB_C_READ = 15, + PERF_RB_C_WRITE = 16, + PERF_RB_TOTAL_PASS = 17, + PERF_RB_Z_PASS = 18, + PERF_RB_Z_FAIL = 19, + PERF_RB_S_FAIL = 20, + PERF_RB_BLENDED_FXP_COMPONENTS = 21, + PERF_RB_BLENDED_FP16_COMPONENTS = 22, + RB_RESERVED = 23, + PERF_RB_2D_ALIVE_CYCLES = 24, + PERF_RB_2D_STALL_CYCLES_A2D = 25, + PERF_RB_2D_STARVE_CYCLES_SRC = 26, + PERF_RB_2D_STARVE_CYCLES_SP = 27, + PERF_RB_2D_STARVE_CYCLES_DST = 28, + PERF_RB_2D_VALID_PIXELS = 29, +}; + +enum a5xx_rb_samples_perfcounter_select { + TOTAL_SAMPLES = 0, + ZPASS_SAMPLES = 1, + ZFAIL_SAMPLES = 2, + SFAIL_SAMPLES = 3, +}; + +enum a5xx_vsc_perfcounter_select { + PERF_VSC_BUSY_CYCLES = 0, + PERF_VSC_WORKING_CYCLES = 1, + PERF_VSC_STALL_CYCLES_UCHE = 2, + PERF_VSC_EOT_NUM = 3, +}; + +enum a5xx_ccu_perfcounter_select { + PERF_CCU_BUSY_CYCLES = 0, + PERF_CCU_STALL_CYCLES_RB_DEPTH_RETURN = 1, + PERF_CCU_STALL_CYCLES_RB_COLOR_RETURN = 2, + PERF_CCU_STARVE_CYCLES_FLAG_RETURN = 3, + PERF_CCU_DEPTH_BLOCKS = 4, + PERF_CCU_COLOR_BLOCKS = 5, + PERF_CCU_DEPTH_BLOCK_HIT = 6, + PERF_CCU_COLOR_BLOCK_HIT = 7, + PERF_CCU_PARTIAL_BLOCK_READ = 8, + PERF_CCU_GMEM_READ = 9, + PERF_CCU_GMEM_WRITE = 10, + PERF_CCU_DEPTH_READ_FLAG0_COUNT = 11, + PERF_CCU_DEPTH_READ_FLAG1_COUNT = 12, + PERF_CCU_DEPTH_READ_FLAG2_COUNT = 13, + PERF_CCU_DEPTH_READ_FLAG3_COUNT = 14, + PERF_CCU_DEPTH_READ_FLAG4_COUNT = 15, + PERF_CCU_COLOR_READ_FLAG0_COUNT = 16, + PERF_CCU_COLOR_READ_FLAG1_COUNT = 17, + PERF_CCU_COLOR_READ_FLAG2_COUNT = 18, + PERF_CCU_COLOR_READ_FLAG3_COUNT = 19, + PERF_CCU_COLOR_READ_FLAG4_COUNT = 20, + PERF_CCU_2D_BUSY_CYCLES = 21, + PERF_CCU_2D_RD_REQ = 22, + PERF_CCU_2D_WR_REQ = 23, + PERF_CCU_2D_REORDER_STARVE_CYCLES = 24, + PERF_CCU_2D_PIXELS = 25, +}; + +enum a5xx_cmp_perfcounter_select { + PERF_CMPDECMP_STALL_CYCLES_VBIF = 0, + PERF_CMPDECMP_VBIF_LATENCY_CYCLES = 1, + PERF_CMPDECMP_VBIF_LATENCY_SAMPLES = 2, + PERF_CMPDECMP_VBIF_READ_DATA_CCU = 3, + PERF_CMPDECMP_VBIF_WRITE_DATA_CCU = 4, + PERF_CMPDECMP_VBIF_READ_REQUEST = 5, + PERF_CMPDECMP_VBIF_WRITE_REQUEST = 6, + PERF_CMPDECMP_VBIF_READ_DATA = 7, + PERF_CMPDECMP_VBIF_WRITE_DATA = 8, + PERF_CMPDECMP_FLAG_FETCH_CYCLES = 9, + PERF_CMPDECMP_FLAG_FETCH_SAMPLES = 10, + PERF_CMPDECMP_DEPTH_WRITE_FLAG1_COUNT = 11, + PERF_CMPDECMP_DEPTH_WRITE_FLAG2_COUNT = 12, + PERF_CMPDECMP_DEPTH_WRITE_FLAG3_COUNT = 13, + PERF_CMPDECMP_DEPTH_WRITE_FLAG4_COUNT = 14, + PERF_CMPDECMP_COLOR_WRITE_FLAG1_COUNT = 15, + PERF_CMPDECMP_COLOR_WRITE_FLAG2_COUNT = 16, + PERF_CMPDECMP_COLOR_WRITE_FLAG3_COUNT = 17, + PERF_CMPDECMP_COLOR_WRITE_FLAG4_COUNT = 18, + PERF_CMPDECMP_2D_STALL_CYCLES_VBIF_REQ = 19, + PERF_CMPDECMP_2D_STALL_CYCLES_VBIF_WR = 20, + PERF_CMPDECMP_2D_STALL_CYCLES_VBIF_RETURN = 21, + PERF_CMPDECMP_2D_RD_DATA = 22, + PERF_CMPDECMP_2D_WR_DATA = 23, +}; + +enum a5xx_vbif_perfcounter_select { + AXI_READ_REQUESTS_ID_0 = 0, + AXI_READ_REQUESTS_ID_1 = 1, + AXI_READ_REQUESTS_ID_2 = 2, + AXI_READ_REQUESTS_ID_3 = 3, + AXI_READ_REQUESTS_ID_4 = 4, + AXI_READ_REQUESTS_ID_5 = 5, + AXI_READ_REQUESTS_ID_6 = 6, + AXI_READ_REQUESTS_ID_7 = 7, + AXI_READ_REQUESTS_ID_8 = 8, + AXI_READ_REQUESTS_ID_9 = 9, + AXI_READ_REQUESTS_ID_10 = 10, + AXI_READ_REQUESTS_ID_11 = 11, + AXI_READ_REQUESTS_ID_12 = 12, + AXI_READ_REQUESTS_ID_13 = 13, + AXI_READ_REQUESTS_ID_14 = 14, + AXI_READ_REQUESTS_ID_15 = 15, + AXI0_READ_REQUESTS_TOTAL = 16, + AXI1_READ_REQUESTS_TOTAL = 17, + AXI2_READ_REQUESTS_TOTAL = 18, + AXI3_READ_REQUESTS_TOTAL = 19, + AXI_READ_REQUESTS_TOTAL = 20, + AXI_WRITE_REQUESTS_ID_0 = 21, + AXI_WRITE_REQUESTS_ID_1 = 22, + AXI_WRITE_REQUESTS_ID_2 = 23, + AXI_WRITE_REQUESTS_ID_3 = 24, + AXI_WRITE_REQUESTS_ID_4 = 25, + AXI_WRITE_REQUESTS_ID_5 = 26, + AXI_WRITE_REQUESTS_ID_6 = 27, + AXI_WRITE_REQUESTS_ID_7 = 28, + AXI_WRITE_REQUESTS_ID_8 = 29, + AXI_WRITE_REQUESTS_ID_9 = 30, + AXI_WRITE_REQUESTS_ID_10 = 31, + AXI_WRITE_REQUESTS_ID_11 = 32, + AXI_WRITE_REQUESTS_ID_12 = 33, + AXI_WRITE_REQUESTS_ID_13 = 34, + AXI_WRITE_REQUESTS_ID_14 = 35, + AXI_WRITE_REQUESTS_ID_15 = 36, + AXI0_WRITE_REQUESTS_TOTAL = 37, + AXI1_WRITE_REQUESTS_TOTAL = 38, + AXI2_WRITE_REQUESTS_TOTAL = 39, + AXI3_WRITE_REQUESTS_TOTAL = 40, + AXI_WRITE_REQUESTS_TOTAL = 41, + AXI_TOTAL_REQUESTS = 42, + AXI_READ_DATA_BEATS_ID_0 = 43, + AXI_READ_DATA_BEATS_ID_1 = 44, + AXI_READ_DATA_BEATS_ID_2 = 45, + AXI_READ_DATA_BEATS_ID_3 = 46, + AXI_READ_DATA_BEATS_ID_4 = 47, + AXI_READ_DATA_BEATS_ID_5 = 48, + AXI_READ_DATA_BEATS_ID_6 = 49, + AXI_READ_DATA_BEATS_ID_7 = 50, + AXI_READ_DATA_BEATS_ID_8 = 51, + AXI_READ_DATA_BEATS_ID_9 = 52, + AXI_READ_DATA_BEATS_ID_10 = 53, + AXI_READ_DATA_BEATS_ID_11 = 54, + AXI_READ_DATA_BEATS_ID_12 = 55, + AXI_READ_DATA_BEATS_ID_13 = 56, + AXI_READ_DATA_BEATS_ID_14 = 57, + AXI_READ_DATA_BEATS_ID_15 = 58, + AXI0_READ_DATA_BEATS_TOTAL = 59, + AXI1_READ_DATA_BEATS_TOTAL = 60, + AXI2_READ_DATA_BEATS_TOTAL = 61, + AXI3_READ_DATA_BEATS_TOTAL = 62, + AXI_READ_DATA_BEATS_TOTAL = 63, + AXI_WRITE_DATA_BEATS_ID_0 = 64, + AXI_WRITE_DATA_BEATS_ID_1 = 65, + AXI_WRITE_DATA_BEATS_ID_2 = 66, + AXI_WRITE_DATA_BEATS_ID_3 = 67, + AXI_WRITE_DATA_BEATS_ID_4 = 68, + AXI_WRITE_DATA_BEATS_ID_5 = 69, + AXI_WRITE_DATA_BEATS_ID_6 = 70, + AXI_WRITE_DATA_BEATS_ID_7 = 71, + AXI_WRITE_DATA_BEATS_ID_8 = 72, + AXI_WRITE_DATA_BEATS_ID_9 = 73, + AXI_WRITE_DATA_BEATS_ID_10 = 74, + AXI_WRITE_DATA_BEATS_ID_11 = 75, + AXI_WRITE_DATA_BEATS_ID_12 = 76, + AXI_WRITE_DATA_BEATS_ID_13 = 77, + AXI_WRITE_DATA_BEATS_ID_14 = 78, + AXI_WRITE_DATA_BEATS_ID_15 = 79, + AXI0_WRITE_DATA_BEATS_TOTAL = 80, + AXI1_WRITE_DATA_BEATS_TOTAL = 81, + AXI2_WRITE_DATA_BEATS_TOTAL = 82, + AXI3_WRITE_DATA_BEATS_TOTAL = 83, + AXI_WRITE_DATA_BEATS_TOTAL = 84, + AXI_DATA_BEATS_TOTAL = 85, +}; + +enum a5xx_tex_filter { + A5XX_TEX_NEAREST = 0, + A5XX_TEX_LINEAR = 1, + A5XX_TEX_ANISO = 2, +}; + +enum a5xx_tex_clamp { + A5XX_TEX_REPEAT = 0, + A5XX_TEX_CLAMP_TO_EDGE = 1, + A5XX_TEX_MIRROR_REPEAT = 2, + A5XX_TEX_CLAMP_TO_BORDER = 3, + A5XX_TEX_MIRROR_CLAMP = 4, +}; + +enum a5xx_tex_aniso { + A5XX_TEX_ANISO_1 = 0, + A5XX_TEX_ANISO_2 = 1, + A5XX_TEX_ANISO_4 = 2, + A5XX_TEX_ANISO_8 = 3, + A5XX_TEX_ANISO_16 = 4, +}; + +enum a5xx_tex_swiz { + A5XX_TEX_X = 0, + A5XX_TEX_Y = 1, + A5XX_TEX_Z = 2, + A5XX_TEX_W = 3, + A5XX_TEX_ZERO = 4, + A5XX_TEX_ONE = 5, +}; + +enum a5xx_tex_type { + A5XX_TEX_1D = 0, + A5XX_TEX_2D = 1, + A5XX_TEX_CUBE = 2, + A5XX_TEX_3D = 3, +}; + +#define A5XX_INT0_RBBM_GPU_IDLE 0x00000001 +#define A5XX_INT0_RBBM_AHB_ERROR 0x00000002 +#define A5XX_INT0_RBBM_TRANSFER_TIMEOUT 0x00000004 +#define A5XX_INT0_RBBM_ME_MS_TIMEOUT 0x00000008 +#define A5XX_INT0_RBBM_PFP_MS_TIMEOUT 0x00000010 +#define A5XX_INT0_RBBM_ETS_MS_TIMEOUT 0x00000020 +#define A5XX_INT0_RBBM_ATB_ASYNC_OVERFLOW 0x00000040 +#define A5XX_INT0_RBBM_GPC_ERROR 0x00000080 +#define A5XX_INT0_CP_SW 0x00000100 +#define A5XX_INT0_CP_HW_ERROR 0x00000200 +#define A5XX_INT0_CP_CCU_FLUSH_DEPTH_TS 0x00000400 +#define A5XX_INT0_CP_CCU_FLUSH_COLOR_TS 0x00000800 +#define A5XX_INT0_CP_CCU_RESOLVE_TS 0x00001000 +#define A5XX_INT0_CP_IB2 0x00002000 +#define A5XX_INT0_CP_IB1 0x00004000 +#define A5XX_INT0_CP_RB 0x00008000 +#define A5XX_INT0_CP_UNUSED_1 0x00010000 +#define A5XX_INT0_CP_RB_DONE_TS 0x00020000 +#define A5XX_INT0_CP_WT_DONE_TS 0x00040000 +#define A5XX_INT0_UNKNOWN_1 0x00080000 +#define A5XX_INT0_CP_CACHE_FLUSH_TS 0x00100000 +#define A5XX_INT0_UNUSED_2 0x00200000 +#define A5XX_INT0_RBBM_ATB_BUS_OVERFLOW 0x00400000 +#define A5XX_INT0_MISC_HANG_DETECT 0x00800000 +#define A5XX_INT0_UCHE_OOB_ACCESS 0x01000000 +#define A5XX_INT0_UCHE_TRAP_INTR 0x02000000 +#define A5XX_INT0_DEBBUS_INTR_0 0x04000000 +#define A5XX_INT0_DEBBUS_INTR_1 0x08000000 +#define A5XX_INT0_GPMU_VOLTAGE_DROOP 0x10000000 +#define A5XX_INT0_GPMU_FIRMWARE 0x20000000 +#define A5XX_INT0_ISDB_CPU_IRQ 0x40000000 +#define A5XX_INT0_ISDB_UNDER_DEBUG 0x80000000 +#define A5XX_CP_INT_CP_OPCODE_ERROR 0x00000001 +#define A5XX_CP_INT_CP_RESERVED_BIT_ERROR 0x00000002 +#define A5XX_CP_INT_CP_HW_FAULT_ERROR 0x00000004 +#define A5XX_CP_INT_CP_DMA_ERROR 0x00000008 +#define A5XX_CP_INT_CP_REGISTER_PROTECTION_ERROR 0x00000010 +#define A5XX_CP_INT_CP_AHB_ERROR 0x00000020 +#define REG_A5XX_CP_RB_BASE 0x00000800 + +#define REG_A5XX_CP_RB_BASE_HI 0x00000801 + +#define REG_A5XX_CP_RB_CNTL 0x00000802 + +#define REG_A5XX_CP_RB_RPTR_ADDR 0x00000804 + +#define REG_A5XX_CP_RB_RPTR_ADDR_HI 0x00000805 + +#define REG_A5XX_CP_RB_RPTR 0x00000806 + +#define REG_A5XX_CP_RB_WPTR 0x00000807 + +#define REG_A5XX_CP_PFP_STAT_ADDR 0x00000808 + +#define REG_A5XX_CP_PFP_STAT_DATA 0x00000809 + +#define REG_A5XX_CP_DRAW_STATE_ADDR 0x0000080b + +#define REG_A5XX_CP_DRAW_STATE_DATA 0x0000080c + +#define REG_A5XX_CP_ME_NRT_ADDR_LO 0x0000080d + +#define REG_A5XX_CP_ME_NRT_ADDR_HI 0x0000080e + +#define REG_A5XX_CP_ME_NRT_DATA 0x00000810 + +#define REG_A5XX_CP_CRASH_SCRIPT_BASE_LO 0x00000817 + +#define REG_A5XX_CP_CRASH_SCRIPT_BASE_HI 0x00000818 + +#define REG_A5XX_CP_CRASH_DUMP_CNTL 0x00000819 + +#define REG_A5XX_CP_ME_STAT_ADDR 0x0000081a + +#define REG_A5XX_CP_ROQ_THRESHOLDS_1 0x0000081f + +#define REG_A5XX_CP_ROQ_THRESHOLDS_2 0x00000820 + +#define REG_A5XX_CP_ROQ_DBG_ADDR 0x00000821 + +#define REG_A5XX_CP_ROQ_DBG_DATA 0x00000822 + +#define REG_A5XX_CP_MEQ_DBG_ADDR 0x00000823 + +#define REG_A5XX_CP_MEQ_DBG_DATA 0x00000824 + +#define REG_A5XX_CP_MEQ_THRESHOLDS 0x00000825 + +#define REG_A5XX_CP_MERCIU_SIZE 0x00000826 + +#define REG_A5XX_CP_MERCIU_DBG_ADDR 0x00000827 + +#define REG_A5XX_CP_MERCIU_DBG_DATA_1 0x00000828 + +#define REG_A5XX_CP_MERCIU_DBG_DATA_2 0x00000829 + +#define REG_A5XX_CP_PFP_UCODE_DBG_ADDR 0x0000082a + +#define REG_A5XX_CP_PFP_UCODE_DBG_DATA 0x0000082b + +#define REG_A5XX_CP_ME_UCODE_DBG_ADDR 0x0000082f + +#define REG_A5XX_CP_ME_UCODE_DBG_DATA 0x00000830 + +#define REG_A5XX_CP_CNTL 0x00000831 + +#define REG_A5XX_CP_PFP_ME_CNTL 0x00000832 + +#define REG_A5XX_CP_CHICKEN_DBG 0x00000833 + +#define REG_A5XX_CP_PFP_INSTR_BASE_LO 0x00000835 + +#define REG_A5XX_CP_PFP_INSTR_BASE_HI 0x00000836 + +#define REG_A5XX_CP_ME_INSTR_BASE_LO 0x00000838 + +#define REG_A5XX_CP_ME_INSTR_BASE_HI 0x00000839 + +#define REG_A5XX_CP_CONTEXT_SWITCH_CNTL 0x0000083b + +#define REG_A5XX_CP_CONTEXT_SWITCH_RESTORE_ADDR_LO 0x0000083c + +#define REG_A5XX_CP_CONTEXT_SWITCH_RESTORE_ADDR_HI 0x0000083d + +#define REG_A5XX_CP_CONTEXT_SWITCH_SAVE_ADDR_LO 0x0000083e + +#define REG_A5XX_CP_CONTEXT_SWITCH_SAVE_ADDR_HI 0x0000083f + +#define REG_A5XX_CP_CONTEXT_SWITCH_SMMU_INFO_LO 0x00000840 + +#define REG_A5XX_CP_CONTEXT_SWITCH_SMMU_INFO_HI 0x00000841 + +#define REG_A5XX_CP_ADDR_MODE_CNTL 0x00000860 + +#define REG_A5XX_CP_ME_STAT_DATA 0x00000b14 + +#define REG_A5XX_CP_WFI_PEND_CTR 0x00000b15 + +#define REG_A5XX_CP_INTERRUPT_STATUS 0x00000b18 + +#define REG_A5XX_CP_HW_FAULT 0x00000b1a + +#define REG_A5XX_CP_PROTECT_STATUS 0x00000b1c + +#define REG_A5XX_CP_IB1_BASE 0x00000b1f + +#define REG_A5XX_CP_IB1_BASE_HI 0x00000b20 + +#define REG_A5XX_CP_IB1_BUFSZ 0x00000b21 + +#define REG_A5XX_CP_IB2_BASE 0x00000b22 + +#define REG_A5XX_CP_IB2_BASE_HI 0x00000b23 + +#define REG_A5XX_CP_IB2_BUFSZ 0x00000b24 + +static inline uint32_t REG_A5XX_CP_SCRATCH(uint32_t i0) { return 0x00000b78 + 0x1*i0; } + +static inline uint32_t REG_A5XX_CP_SCRATCH_REG(uint32_t i0) { return 0x00000b78 + 0x1*i0; } + +static inline uint32_t REG_A5XX_CP_PROTECT(uint32_t i0) { return 0x00000880 + 0x1*i0; } + +static inline uint32_t REG_A5XX_CP_PROTECT_REG(uint32_t i0) { return 0x00000880 + 0x1*i0; } +#define A5XX_CP_PROTECT_REG_BASE_ADDR__MASK 0x0001ffff +#define A5XX_CP_PROTECT_REG_BASE_ADDR__SHIFT 0 +static inline uint32_t A5XX_CP_PROTECT_REG_BASE_ADDR(uint32_t val) +{ + return ((val) << A5XX_CP_PROTECT_REG_BASE_ADDR__SHIFT) & A5XX_CP_PROTECT_REG_BASE_ADDR__MASK; +} +#define A5XX_CP_PROTECT_REG_MASK_LEN__MASK 0x1f000000 +#define A5XX_CP_PROTECT_REG_MASK_LEN__SHIFT 24 +static inline uint32_t A5XX_CP_PROTECT_REG_MASK_LEN(uint32_t val) +{ + return ((val) << A5XX_CP_PROTECT_REG_MASK_LEN__SHIFT) & A5XX_CP_PROTECT_REG_MASK_LEN__MASK; +} +#define A5XX_CP_PROTECT_REG_TRAP_WRITE 0x20000000 +#define A5XX_CP_PROTECT_REG_TRAP_READ 0x40000000 + +#define REG_A5XX_CP_PROTECT_CNTL 0x000008a0 + +#define REG_A5XX_CP_AHB_FAULT 0x00000b1b + +#define REG_A5XX_CP_PERFCTR_CP_SEL_0 0x00000bb0 + +#define REG_A5XX_CP_PERFCTR_CP_SEL_1 0x00000bb1 + +#define REG_A5XX_CP_PERFCTR_CP_SEL_2 0x00000bb2 + +#define REG_A5XX_CP_PERFCTR_CP_SEL_3 0x00000bb3 + +#define REG_A5XX_CP_PERFCTR_CP_SEL_4 0x00000bb4 + +#define REG_A5XX_CP_PERFCTR_CP_SEL_5 0x00000bb5 + +#define REG_A5XX_CP_PERFCTR_CP_SEL_6 0x00000bb6 + +#define REG_A5XX_CP_PERFCTR_CP_SEL_7 0x00000bb7 + +#define REG_A5XX_VSC_ADDR_MODE_CNTL 0x00000bc1 + +#define REG_A5XX_CP_POWERCTR_CP_SEL_0 0x00000bba + +#define REG_A5XX_CP_POWERCTR_CP_SEL_1 0x00000bbb + +#define REG_A5XX_CP_POWERCTR_CP_SEL_2 0x00000bbc + +#define REG_A5XX_CP_POWERCTR_CP_SEL_3 0x00000bbd + +#define REG_A5XX_RBBM_CFG_DBGBUS_SEL_A 0x00000004 + +#define REG_A5XX_RBBM_CFG_DBGBUS_SEL_B 0x00000005 + +#define REG_A5XX_RBBM_CFG_DBGBUS_SEL_C 0x00000006 + +#define REG_A5XX_RBBM_CFG_DBGBUS_SEL_D 0x00000007 + +#define REG_A5XX_RBBM_CFG_DBGBUS_CNTLT 0x00000008 + +#define REG_A5XX_RBBM_CFG_DBGBUS_CNTLM 0x00000009 + +#define REG_A5XX_RBBM_CFG_DEBBUS_CTLTM_ENABLE_SHIFT 0x00000018 + +#define REG_A5XX_RBBM_CFG_DBGBUS_OPL 0x0000000a + +#define REG_A5XX_RBBM_CFG_DBGBUS_OPE 0x0000000b + +#define REG_A5XX_RBBM_CFG_DBGBUS_IVTL_0 0x0000000c + +#define REG_A5XX_RBBM_CFG_DBGBUS_IVTL_1 0x0000000d + +#define REG_A5XX_RBBM_CFG_DBGBUS_IVTL_2 0x0000000e + +#define REG_A5XX_RBBM_CFG_DBGBUS_IVTL_3 0x0000000f + +#define REG_A5XX_RBBM_CFG_DBGBUS_MASKL_0 0x00000010 + +#define REG_A5XX_RBBM_CFG_DBGBUS_MASKL_1 0x00000011 + +#define REG_A5XX_RBBM_CFG_DBGBUS_MASKL_2 0x00000012 + +#define REG_A5XX_RBBM_CFG_DBGBUS_MASKL_3 0x00000013 + +#define REG_A5XX_RBBM_CFG_DBGBUS_BYTEL_0 0x00000014 + +#define REG_A5XX_RBBM_CFG_DBGBUS_BYTEL_1 0x00000015 + +#define REG_A5XX_RBBM_CFG_DBGBUS_IVTE_0 0x00000016 + +#define REG_A5XX_RBBM_CFG_DBGBUS_IVTE_1 0x00000017 + +#define REG_A5XX_RBBM_CFG_DBGBUS_IVTE_2 0x00000018 + +#define REG_A5XX_RBBM_CFG_DBGBUS_IVTE_3 0x00000019 + +#define REG_A5XX_RBBM_CFG_DBGBUS_MASKE_0 0x0000001a + +#define REG_A5XX_RBBM_CFG_DBGBUS_MASKE_1 0x0000001b + +#define REG_A5XX_RBBM_CFG_DBGBUS_MASKE_2 0x0000001c + +#define REG_A5XX_RBBM_CFG_DBGBUS_MASKE_3 0x0000001d + +#define REG_A5XX_RBBM_CFG_DBGBUS_NIBBLEE 0x0000001e + +#define REG_A5XX_RBBM_CFG_DBGBUS_PTRC0 0x0000001f + +#define REG_A5XX_RBBM_CFG_DBGBUS_PTRC1 0x00000020 + +#define REG_A5XX_RBBM_CFG_DBGBUS_LOADREG 0x00000021 + +#define REG_A5XX_RBBM_CFG_DBGBUS_IDX 0x00000022 + +#define REG_A5XX_RBBM_CFG_DBGBUS_CLRC 0x00000023 + +#define REG_A5XX_RBBM_CFG_DBGBUS_LOADIVT 0x00000024 + +#define REG_A5XX_RBBM_INTERFACE_HANG_INT_CNTL 0x0000002f + +#define REG_A5XX_RBBM_INT_CLEAR_CMD 0x00000037 + +#define REG_A5XX_RBBM_INT_0_MASK 0x00000038 +#define A5XX_RBBM_INT_0_MASK_RBBM_GPU_IDLE 0x00000001 +#define A5XX_RBBM_INT_0_MASK_RBBM_AHB_ERROR 0x00000002 +#define A5XX_RBBM_INT_0_MASK_RBBM_TRANSFER_TIMEOUT 0x00000004 +#define A5XX_RBBM_INT_0_MASK_RBBM_ME_MS_TIMEOUT 0x00000008 +#define A5XX_RBBM_INT_0_MASK_RBBM_PFP_MS_TIMEOUT 0x00000010 +#define A5XX_RBBM_INT_0_MASK_RBBM_ETS_MS_TIMEOUT 0x00000020 +#define A5XX_RBBM_INT_0_MASK_RBBM_ATB_ASYNC_OVERFLOW 0x00000040 +#define A5XX_RBBM_INT_0_MASK_RBBM_GPC_ERROR 0x00000080 +#define A5XX_RBBM_INT_0_MASK_CP_SW 0x00000100 +#define A5XX_RBBM_INT_0_MASK_CP_HW_ERROR 0x00000200 +#define A5XX_RBBM_INT_0_MASK_CP_CCU_FLUSH_DEPTH_TS 0x00000400 +#define A5XX_RBBM_INT_0_MASK_CP_CCU_FLUSH_COLOR_TS 0x00000800 +#define A5XX_RBBM_INT_0_MASK_CP_CCU_RESOLVE_TS 0x00001000 +#define A5XX_RBBM_INT_0_MASK_CP_IB2 0x00002000 +#define A5XX_RBBM_INT_0_MASK_CP_IB1 0x00004000 +#define A5XX_RBBM_INT_0_MASK_CP_RB 0x00008000 +#define A5XX_RBBM_INT_0_MASK_CP_RB_DONE_TS 0x00020000 +#define A5XX_RBBM_INT_0_MASK_CP_WT_DONE_TS 0x00040000 +#define A5XX_RBBM_INT_0_MASK_CP_CACHE_FLUSH_TS 0x00100000 +#define A5XX_RBBM_INT_0_MASK_RBBM_ATB_BUS_OVERFLOW 0x00400000 +#define A5XX_RBBM_INT_0_MASK_MISC_HANG_DETECT 0x00800000 +#define A5XX_RBBM_INT_0_MASK_UCHE_OOB_ACCESS 0x01000000 +#define A5XX_RBBM_INT_0_MASK_UCHE_TRAP_INTR 0x02000000 +#define A5XX_RBBM_INT_0_MASK_DEBBUS_INTR_0 0x04000000 +#define A5XX_RBBM_INT_0_MASK_DEBBUS_INTR_1 0x08000000 +#define A5XX_RBBM_INT_0_MASK_GPMU_VOLTAGE_DROOP 0x10000000 +#define A5XX_RBBM_INT_0_MASK_GPMU_FIRMWARE 0x20000000 +#define A5XX_RBBM_INT_0_MASK_ISDB_CPU_IRQ 0x40000000 +#define A5XX_RBBM_INT_0_MASK_ISDB_UNDER_DEBUG 0x80000000 + +#define REG_A5XX_RBBM_AHB_DBG_CNTL 0x0000003f + +#define REG_A5XX_RBBM_EXT_VBIF_DBG_CNTL 0x00000041 + +#define REG_A5XX_RBBM_SW_RESET_CMD 0x00000043 + +#define REG_A5XX_RBBM_BLOCK_SW_RESET_CMD 0x00000045 + +#define REG_A5XX_RBBM_BLOCK_SW_RESET_CMD2 0x00000046 + +#define REG_A5XX_RBBM_DBG_LO_HI_GPIO 0x00000048 + +#define REG_A5XX_RBBM_EXT_TRACE_BUS_CNTL 0x00000049 + +#define REG_A5XX_RBBM_CLOCK_CNTL_TP0 0x0000004a + +#define REG_A5XX_RBBM_CLOCK_CNTL_TP1 0x0000004b + +#define REG_A5XX_RBBM_CLOCK_CNTL_TP2 0x0000004c + +#define REG_A5XX_RBBM_CLOCK_CNTL_TP3 0x0000004d + +#define REG_A5XX_RBBM_CLOCK_CNTL2_TP0 0x0000004e + +#define REG_A5XX_RBBM_CLOCK_CNTL2_TP1 0x0000004f + +#define REG_A5XX_RBBM_CLOCK_CNTL2_TP2 0x00000050 + +#define REG_A5XX_RBBM_CLOCK_CNTL2_TP3 0x00000051 + +#define REG_A5XX_RBBM_CLOCK_CNTL3_TP0 0x00000052 + +#define REG_A5XX_RBBM_CLOCK_CNTL3_TP1 0x00000053 + +#define REG_A5XX_RBBM_CLOCK_CNTL3_TP2 0x00000054 + +#define REG_A5XX_RBBM_CLOCK_CNTL3_TP3 0x00000055 + +#define REG_A5XX_RBBM_READ_AHB_THROUGH_DBG 0x00000059 + +#define REG_A5XX_RBBM_CLOCK_CNTL_UCHE 0x0000005a + +#define REG_A5XX_RBBM_CLOCK_CNTL2_UCHE 0x0000005b + +#define REG_A5XX_RBBM_CLOCK_CNTL3_UCHE 0x0000005c + +#define REG_A5XX_RBBM_CLOCK_CNTL4_UCHE 0x0000005d + +#define REG_A5XX_RBBM_CLOCK_HYST_UCHE 0x0000005e + +#define REG_A5XX_RBBM_CLOCK_DELAY_UCHE 0x0000005f + +#define REG_A5XX_RBBM_CLOCK_MODE_GPC 0x00000060 + +#define REG_A5XX_RBBM_CLOCK_DELAY_GPC 0x00000061 + +#define REG_A5XX_RBBM_CLOCK_HYST_GPC 0x00000062 + +#define REG_A5XX_RBBM_CLOCK_CNTL_TSE_RAS_RBBM 0x00000063 + +#define REG_A5XX_RBBM_CLOCK_HYST_TSE_RAS_RBBM 0x00000064 + +#define REG_A5XX_RBBM_CLOCK_DELAY_TSE_RAS_RBBM 0x00000065 + +#define REG_A5XX_RBBM_CLOCK_DELAY_HLSQ 0x00000066 + +#define REG_A5XX_RBBM_CLOCK_CNTL 0x00000067 + +#define REG_A5XX_RBBM_CLOCK_CNTL_SP0 0x00000068 + +#define REG_A5XX_RBBM_CLOCK_CNTL_SP1 0x00000069 + +#define REG_A5XX_RBBM_CLOCK_CNTL_SP2 0x0000006a + +#define REG_A5XX_RBBM_CLOCK_CNTL_SP3 0x0000006b + +#define REG_A5XX_RBBM_CLOCK_CNTL2_SP0 0x0000006c + +#define REG_A5XX_RBBM_CLOCK_CNTL2_SP1 0x0000006d + +#define REG_A5XX_RBBM_CLOCK_CNTL2_SP2 0x0000006e + +#define REG_A5XX_RBBM_CLOCK_CNTL2_SP3 0x0000006f + +#define REG_A5XX_RBBM_CLOCK_HYST_SP0 0x00000070 + +#define REG_A5XX_RBBM_CLOCK_HYST_SP1 0x00000071 + +#define REG_A5XX_RBBM_CLOCK_HYST_SP2 0x00000072 + +#define REG_A5XX_RBBM_CLOCK_HYST_SP3 0x00000073 + +#define REG_A5XX_RBBM_CLOCK_DELAY_SP0 0x00000074 + +#define REG_A5XX_RBBM_CLOCK_DELAY_SP1 0x00000075 + +#define REG_A5XX_RBBM_CLOCK_DELAY_SP2 0x00000076 + +#define REG_A5XX_RBBM_CLOCK_DELAY_SP3 0x00000077 + +#define REG_A5XX_RBBM_CLOCK_CNTL_RB0 0x00000078 + +#define REG_A5XX_RBBM_CLOCK_CNTL_RB1 0x00000079 + +#define REG_A5XX_RBBM_CLOCK_CNTL_RB2 0x0000007a + +#define REG_A5XX_RBBM_CLOCK_CNTL_RB3 0x0000007b + +#define REG_A5XX_RBBM_CLOCK_CNTL2_RB0 0x0000007c + +#define REG_A5XX_RBBM_CLOCK_CNTL2_RB1 0x0000007d + +#define REG_A5XX_RBBM_CLOCK_CNTL2_RB2 0x0000007e + +#define REG_A5XX_RBBM_CLOCK_CNTL2_RB3 0x0000007f + +#define REG_A5XX_RBBM_CLOCK_HYST_RAC 0x00000080 + +#define REG_A5XX_RBBM_CLOCK_DELAY_RAC 0x00000081 + +#define REG_A5XX_RBBM_CLOCK_CNTL_CCU0 0x00000082 + +#define REG_A5XX_RBBM_CLOCK_CNTL_CCU1 0x00000083 + +#define REG_A5XX_RBBM_CLOCK_CNTL_CCU2 0x00000084 + +#define REG_A5XX_RBBM_CLOCK_CNTL_CCU3 0x00000085 + +#define REG_A5XX_RBBM_CLOCK_HYST_RB_CCU0 0x00000086 + +#define REG_A5XX_RBBM_CLOCK_HYST_RB_CCU1 0x00000087 + +#define REG_A5XX_RBBM_CLOCK_HYST_RB_CCU2 0x00000088 + +#define REG_A5XX_RBBM_CLOCK_HYST_RB_CCU3 0x00000089 + +#define REG_A5XX_RBBM_CLOCK_CNTL_RAC 0x0000008a + +#define REG_A5XX_RBBM_CLOCK_CNTL2_RAC 0x0000008b + +#define REG_A5XX_RBBM_CLOCK_DELAY_RB_CCU_L1_0 0x0000008c + +#define REG_A5XX_RBBM_CLOCK_DELAY_RB_CCU_L1_1 0x0000008d + +#define REG_A5XX_RBBM_CLOCK_DELAY_RB_CCU_L1_2 0x0000008e + +#define REG_A5XX_RBBM_CLOCK_DELAY_RB_CCU_L1_3 0x0000008f + +#define REG_A5XX_RBBM_CLOCK_HYST_VFD 0x00000090 + +#define REG_A5XX_RBBM_CLOCK_MODE_VFD 0x00000091 + +#define REG_A5XX_RBBM_CLOCK_DELAY_VFD 0x00000092 + +#define REG_A5XX_RBBM_AHB_CNTL0 0x00000093 + +#define REG_A5XX_RBBM_AHB_CNTL1 0x00000094 + +#define REG_A5XX_RBBM_AHB_CNTL2 0x00000095 + +#define REG_A5XX_RBBM_AHB_CMD 0x00000096 + +#define REG_A5XX_RBBM_INTERFACE_HANG_MASK_CNTL11 0x0000009c + +#define REG_A5XX_RBBM_INTERFACE_HANG_MASK_CNTL12 0x0000009d + +#define REG_A5XX_RBBM_INTERFACE_HANG_MASK_CNTL13 0x0000009e + +#define REG_A5XX_RBBM_INTERFACE_HANG_MASK_CNTL14 0x0000009f + +#define REG_A5XX_RBBM_INTERFACE_HANG_MASK_CNTL15 0x000000a0 + +#define REG_A5XX_RBBM_INTERFACE_HANG_MASK_CNTL16 0x000000a1 + +#define REG_A5XX_RBBM_INTERFACE_HANG_MASK_CNTL17 0x000000a2 + +#define REG_A5XX_RBBM_INTERFACE_HANG_MASK_CNTL18 0x000000a3 + +#define REG_A5XX_RBBM_CLOCK_DELAY_TP0 0x000000a4 + +#define REG_A5XX_RBBM_CLOCK_DELAY_TP1 0x000000a5 + +#define REG_A5XX_RBBM_CLOCK_DELAY_TP2 0x000000a6 + +#define REG_A5XX_RBBM_CLOCK_DELAY_TP3 0x000000a7 + +#define REG_A5XX_RBBM_CLOCK_DELAY2_TP0 0x000000a8 + +#define REG_A5XX_RBBM_CLOCK_DELAY2_TP1 0x000000a9 + +#define REG_A5XX_RBBM_CLOCK_DELAY2_TP2 0x000000aa + +#define REG_A5XX_RBBM_CLOCK_DELAY2_TP3 0x000000ab + +#define REG_A5XX_RBBM_CLOCK_DELAY3_TP0 0x000000ac + +#define REG_A5XX_RBBM_CLOCK_DELAY3_TP1 0x000000ad + +#define REG_A5XX_RBBM_CLOCK_DELAY3_TP2 0x000000ae + +#define REG_A5XX_RBBM_CLOCK_DELAY3_TP3 0x000000af + +#define REG_A5XX_RBBM_CLOCK_HYST_TP0 0x000000b0 + +#define REG_A5XX_RBBM_CLOCK_HYST_TP1 0x000000b1 + +#define REG_A5XX_RBBM_CLOCK_HYST_TP2 0x000000b2 + +#define REG_A5XX_RBBM_CLOCK_HYST_TP3 0x000000b3 + +#define REG_A5XX_RBBM_CLOCK_HYST2_TP0 0x000000b4 + +#define REG_A5XX_RBBM_CLOCK_HYST2_TP1 0x000000b5 + +#define REG_A5XX_RBBM_CLOCK_HYST2_TP2 0x000000b6 + +#define REG_A5XX_RBBM_CLOCK_HYST2_TP3 0x000000b7 + +#define REG_A5XX_RBBM_CLOCK_HYST3_TP0 0x000000b8 + +#define REG_A5XX_RBBM_CLOCK_HYST3_TP1 0x000000b9 + +#define REG_A5XX_RBBM_CLOCK_HYST3_TP2 0x000000ba + +#define REG_A5XX_RBBM_CLOCK_HYST3_TP3 0x000000bb + +#define REG_A5XX_RBBM_CLOCK_CNTL_GPMU 0x000000c8 + +#define REG_A5XX_RBBM_CLOCK_DELAY_GPMU 0x000000c9 + +#define REG_A5XX_RBBM_CLOCK_HYST_GPMU 0x000000ca + +#define REG_A5XX_RBBM_PERFCTR_CP_0_LO 0x000003a0 + +#define REG_A5XX_RBBM_PERFCTR_CP_0_HI 0x000003a1 + +#define REG_A5XX_RBBM_PERFCTR_CP_1_LO 0x000003a2 + +#define REG_A5XX_RBBM_PERFCTR_CP_1_HI 0x000003a3 + +#define REG_A5XX_RBBM_PERFCTR_CP_2_LO 0x000003a4 + +#define REG_A5XX_RBBM_PERFCTR_CP_2_HI 0x000003a5 + +#define REG_A5XX_RBBM_PERFCTR_CP_3_LO 0x000003a6 + +#define REG_A5XX_RBBM_PERFCTR_CP_3_HI 0x000003a7 + +#define REG_A5XX_RBBM_PERFCTR_CP_4_LO 0x000003a8 + +#define REG_A5XX_RBBM_PERFCTR_CP_4_HI 0x000003a9 + +#define REG_A5XX_RBBM_PERFCTR_CP_5_LO 0x000003aa + +#define REG_A5XX_RBBM_PERFCTR_CP_5_HI 0x000003ab + +#define REG_A5XX_RBBM_PERFCTR_CP_6_LO 0x000003ac + +#define REG_A5XX_RBBM_PERFCTR_CP_6_HI 0x000003ad + +#define REG_A5XX_RBBM_PERFCTR_CP_7_LO 0x000003ae + +#define REG_A5XX_RBBM_PERFCTR_CP_7_HI 0x000003af + +#define REG_A5XX_RBBM_PERFCTR_RBBM_0_LO 0x000003b0 + +#define REG_A5XX_RBBM_PERFCTR_RBBM_0_HI 0x000003b1 + +#define REG_A5XX_RBBM_PERFCTR_RBBM_1_LO 0x000003b2 + +#define REG_A5XX_RBBM_PERFCTR_RBBM_1_HI 0x000003b3 + +#define REG_A5XX_RBBM_PERFCTR_RBBM_2_LO 0x000003b4 + +#define REG_A5XX_RBBM_PERFCTR_RBBM_2_HI 0x000003b5 + +#define REG_A5XX_RBBM_PERFCTR_RBBM_3_LO 0x000003b6 + +#define REG_A5XX_RBBM_PERFCTR_RBBM_3_HI 0x000003b7 + +#define REG_A5XX_RBBM_PERFCTR_PC_0_LO 0x000003b8 + +#define REG_A5XX_RBBM_PERFCTR_PC_0_HI 0x000003b9 + +#define REG_A5XX_RBBM_PERFCTR_PC_1_LO 0x000003ba + +#define REG_A5XX_RBBM_PERFCTR_PC_1_HI 0x000003bb + +#define REG_A5XX_RBBM_PERFCTR_PC_2_LO 0x000003bc + +#define REG_A5XX_RBBM_PERFCTR_PC_2_HI 0x000003bd + +#define REG_A5XX_RBBM_PERFCTR_PC_3_LO 0x000003be + +#define REG_A5XX_RBBM_PERFCTR_PC_3_HI 0x000003bf + +#define REG_A5XX_RBBM_PERFCTR_PC_4_LO 0x000003c0 + +#define REG_A5XX_RBBM_PERFCTR_PC_4_HI 0x000003c1 + +#define REG_A5XX_RBBM_PERFCTR_PC_5_LO 0x000003c2 + +#define REG_A5XX_RBBM_PERFCTR_PC_5_HI 0x000003c3 + +#define REG_A5XX_RBBM_PERFCTR_PC_6_LO 0x000003c4 + +#define REG_A5XX_RBBM_PERFCTR_PC_6_HI 0x000003c5 + +#define REG_A5XX_RBBM_PERFCTR_PC_7_LO 0x000003c6 + +#define REG_A5XX_RBBM_PERFCTR_PC_7_HI 0x000003c7 + +#define REG_A5XX_RBBM_PERFCTR_VFD_0_LO 0x000003c8 + +#define REG_A5XX_RBBM_PERFCTR_VFD_0_HI 0x000003c9 + +#define REG_A5XX_RBBM_PERFCTR_VFD_1_LO 0x000003ca + +#define REG_A5XX_RBBM_PERFCTR_VFD_1_HI 0x000003cb + +#define REG_A5XX_RBBM_PERFCTR_VFD_2_LO 0x000003cc + +#define REG_A5XX_RBBM_PERFCTR_VFD_2_HI 0x000003cd + +#define REG_A5XX_RBBM_PERFCTR_VFD_3_LO 0x000003ce + +#define REG_A5XX_RBBM_PERFCTR_VFD_3_HI 0x000003cf + +#define REG_A5XX_RBBM_PERFCTR_VFD_4_LO 0x000003d0 + +#define REG_A5XX_RBBM_PERFCTR_VFD_4_HI 0x000003d1 + +#define REG_A5XX_RBBM_PERFCTR_VFD_5_LO 0x000003d2 + +#define REG_A5XX_RBBM_PERFCTR_VFD_5_HI 0x000003d3 + +#define REG_A5XX_RBBM_PERFCTR_VFD_6_LO 0x000003d4 + +#define REG_A5XX_RBBM_PERFCTR_VFD_6_HI 0x000003d5 + +#define REG_A5XX_RBBM_PERFCTR_VFD_7_LO 0x000003d6 + +#define REG_A5XX_RBBM_PERFCTR_VFD_7_HI 0x000003d7 + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_0_LO 0x000003d8 + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_0_HI 0x000003d9 + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_1_LO 0x000003da + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_1_HI 0x000003db + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_2_LO 0x000003dc + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_2_HI 0x000003dd + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_3_LO 0x000003de + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_3_HI 0x000003df + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_4_LO 0x000003e0 + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_4_HI 0x000003e1 + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_5_LO 0x000003e2 + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_5_HI 0x000003e3 + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_6_LO 0x000003e4 + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_6_HI 0x000003e5 + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_7_LO 0x000003e6 + +#define REG_A5XX_RBBM_PERFCTR_HLSQ_7_HI 0x000003e7 + +#define REG_A5XX_RBBM_PERFCTR_VPC_0_LO 0x000003e8 + +#define REG_A5XX_RBBM_PERFCTR_VPC_0_HI 0x000003e9 + +#define REG_A5XX_RBBM_PERFCTR_VPC_1_LO 0x000003ea + +#define REG_A5XX_RBBM_PERFCTR_VPC_1_HI 0x000003eb + +#define REG_A5XX_RBBM_PERFCTR_VPC_2_LO 0x000003ec + +#define REG_A5XX_RBBM_PERFCTR_VPC_2_HI 0x000003ed + +#define REG_A5XX_RBBM_PERFCTR_VPC_3_LO 0x000003ee + +#define REG_A5XX_RBBM_PERFCTR_VPC_3_HI 0x000003ef + +#define REG_A5XX_RBBM_PERFCTR_CCU_0_LO 0x000003f0 + +#define REG_A5XX_RBBM_PERFCTR_CCU_0_HI 0x000003f1 + +#define REG_A5XX_RBBM_PERFCTR_CCU_1_LO 0x000003f2 + +#define REG_A5XX_RBBM_PERFCTR_CCU_1_HI 0x000003f3 + +#define REG_A5XX_RBBM_PERFCTR_CCU_2_LO 0x000003f4 + +#define REG_A5XX_RBBM_PERFCTR_CCU_2_HI 0x000003f5 + +#define REG_A5XX_RBBM_PERFCTR_CCU_3_LO 0x000003f6 + +#define REG_A5XX_RBBM_PERFCTR_CCU_3_HI 0x000003f7 + +#define REG_A5XX_RBBM_PERFCTR_TSE_0_LO 0x000003f8 + +#define REG_A5XX_RBBM_PERFCTR_TSE_0_HI 0x000003f9 + +#define REG_A5XX_RBBM_PERFCTR_TSE_1_LO 0x000003fa + +#define REG_A5XX_RBBM_PERFCTR_TSE_1_HI 0x000003fb + +#define REG_A5XX_RBBM_PERFCTR_TSE_2_LO 0x000003fc + +#define REG_A5XX_RBBM_PERFCTR_TSE_2_HI 0x000003fd + +#define REG_A5XX_RBBM_PERFCTR_TSE_3_LO 0x000003fe + +#define REG_A5XX_RBBM_PERFCTR_TSE_3_HI 0x000003ff + +#define REG_A5XX_RBBM_PERFCTR_RAS_0_LO 0x00000400 + +#define REG_A5XX_RBBM_PERFCTR_RAS_0_HI 0x00000401 + +#define REG_A5XX_RBBM_PERFCTR_RAS_1_LO 0x00000402 + +#define REG_A5XX_RBBM_PERFCTR_RAS_1_HI 0x00000403 + +#define REG_A5XX_RBBM_PERFCTR_RAS_2_LO 0x00000404 + +#define REG_A5XX_RBBM_PERFCTR_RAS_2_HI 0x00000405 + +#define REG_A5XX_RBBM_PERFCTR_RAS_3_LO 0x00000406 + +#define REG_A5XX_RBBM_PERFCTR_RAS_3_HI 0x00000407 + +#define REG_A5XX_RBBM_PERFCTR_UCHE_0_LO 0x00000408 + +#define REG_A5XX_RBBM_PERFCTR_UCHE_0_HI 0x00000409 + +#define REG_A5XX_RBBM_PERFCTR_UCHE_1_LO 0x0000040a + +#define REG_A5XX_RBBM_PERFCTR_UCHE_1_HI 0x0000040b + +#define REG_A5XX_RBBM_PERFCTR_UCHE_2_LO 0x0000040c + +#define REG_A5XX_RBBM_PERFCTR_UCHE_2_HI 0x0000040d + +#define REG_A5XX_RBBM_PERFCTR_UCHE_3_LO 0x0000040e + +#define REG_A5XX_RBBM_PERFCTR_UCHE_3_HI 0x0000040f + +#define REG_A5XX_RBBM_PERFCTR_UCHE_4_LO 0x00000410 + +#define REG_A5XX_RBBM_PERFCTR_UCHE_4_HI 0x00000411 + +#define REG_A5XX_RBBM_PERFCTR_UCHE_5_LO 0x00000412 + +#define REG_A5XX_RBBM_PERFCTR_UCHE_5_HI 0x00000413 + +#define REG_A5XX_RBBM_PERFCTR_UCHE_6_LO 0x00000414 + +#define REG_A5XX_RBBM_PERFCTR_UCHE_6_HI 0x00000415 + +#define REG_A5XX_RBBM_PERFCTR_UCHE_7_LO 0x00000416 + +#define REG_A5XX_RBBM_PERFCTR_UCHE_7_HI 0x00000417 + +#define REG_A5XX_RBBM_PERFCTR_TP_0_LO 0x00000418 + +#define REG_A5XX_RBBM_PERFCTR_TP_0_HI 0x00000419 + +#define REG_A5XX_RBBM_PERFCTR_TP_1_LO 0x0000041a + +#define REG_A5XX_RBBM_PERFCTR_TP_1_HI 0x0000041b + +#define REG_A5XX_RBBM_PERFCTR_TP_2_LO 0x0000041c + +#define REG_A5XX_RBBM_PERFCTR_TP_2_HI 0x0000041d + +#define REG_A5XX_RBBM_PERFCTR_TP_3_LO 0x0000041e + +#define REG_A5XX_RBBM_PERFCTR_TP_3_HI 0x0000041f + +#define REG_A5XX_RBBM_PERFCTR_TP_4_LO 0x00000420 + +#define REG_A5XX_RBBM_PERFCTR_TP_4_HI 0x00000421 + +#define REG_A5XX_RBBM_PERFCTR_TP_5_LO 0x00000422 + +#define REG_A5XX_RBBM_PERFCTR_TP_5_HI 0x00000423 + +#define REG_A5XX_RBBM_PERFCTR_TP_6_LO 0x00000424 + +#define REG_A5XX_RBBM_PERFCTR_TP_6_HI 0x00000425 + +#define REG_A5XX_RBBM_PERFCTR_TP_7_LO 0x00000426 + +#define REG_A5XX_RBBM_PERFCTR_TP_7_HI 0x00000427 + +#define REG_A5XX_RBBM_PERFCTR_SP_0_LO 0x00000428 + +#define REG_A5XX_RBBM_PERFCTR_SP_0_HI 0x00000429 + +#define REG_A5XX_RBBM_PERFCTR_SP_1_LO 0x0000042a + +#define REG_A5XX_RBBM_PERFCTR_SP_1_HI 0x0000042b + +#define REG_A5XX_RBBM_PERFCTR_SP_2_LO 0x0000042c + +#define REG_A5XX_RBBM_PERFCTR_SP_2_HI 0x0000042d + +#define REG_A5XX_RBBM_PERFCTR_SP_3_LO 0x0000042e + +#define REG_A5XX_RBBM_PERFCTR_SP_3_HI 0x0000042f + +#define REG_A5XX_RBBM_PERFCTR_SP_4_LO 0x00000430 + +#define REG_A5XX_RBBM_PERFCTR_SP_4_HI 0x00000431 + +#define REG_A5XX_RBBM_PERFCTR_SP_5_LO 0x00000432 + +#define REG_A5XX_RBBM_PERFCTR_SP_5_HI 0x00000433 + +#define REG_A5XX_RBBM_PERFCTR_SP_6_LO 0x00000434 + +#define REG_A5XX_RBBM_PERFCTR_SP_6_HI 0x00000435 + +#define REG_A5XX_RBBM_PERFCTR_SP_7_LO 0x00000436 + +#define REG_A5XX_RBBM_PERFCTR_SP_7_HI 0x00000437 + +#define REG_A5XX_RBBM_PERFCTR_SP_8_LO 0x00000438 + +#define REG_A5XX_RBBM_PERFCTR_SP_8_HI 0x00000439 + +#define REG_A5XX_RBBM_PERFCTR_SP_9_LO 0x0000043a + +#define REG_A5XX_RBBM_PERFCTR_SP_9_HI 0x0000043b + +#define REG_A5XX_RBBM_PERFCTR_SP_10_LO 0x0000043c + +#define REG_A5XX_RBBM_PERFCTR_SP_10_HI 0x0000043d + +#define REG_A5XX_RBBM_PERFCTR_SP_11_LO 0x0000043e + +#define REG_A5XX_RBBM_PERFCTR_SP_11_HI 0x0000043f + +#define REG_A5XX_RBBM_PERFCTR_RB_0_LO 0x00000440 + +#define REG_A5XX_RBBM_PERFCTR_RB_0_HI 0x00000441 + +#define REG_A5XX_RBBM_PERFCTR_RB_1_LO 0x00000442 + +#define REG_A5XX_RBBM_PERFCTR_RB_1_HI 0x00000443 + +#define REG_A5XX_RBBM_PERFCTR_RB_2_LO 0x00000444 + +#define REG_A5XX_RBBM_PERFCTR_RB_2_HI 0x00000445 + +#define REG_A5XX_RBBM_PERFCTR_RB_3_LO 0x00000446 + +#define REG_A5XX_RBBM_PERFCTR_RB_3_HI 0x00000447 + +#define REG_A5XX_RBBM_PERFCTR_RB_4_LO 0x00000448 + +#define REG_A5XX_RBBM_PERFCTR_RB_4_HI 0x00000449 + +#define REG_A5XX_RBBM_PERFCTR_RB_5_LO 0x0000044a + +#define REG_A5XX_RBBM_PERFCTR_RB_5_HI 0x0000044b + +#define REG_A5XX_RBBM_PERFCTR_RB_6_LO 0x0000044c + +#define REG_A5XX_RBBM_PERFCTR_RB_6_HI 0x0000044d + +#define REG_A5XX_RBBM_PERFCTR_RB_7_LO 0x0000044e + +#define REG_A5XX_RBBM_PERFCTR_RB_7_HI 0x0000044f + +#define REG_A5XX_RBBM_PERFCTR_VSC_0_LO 0x00000450 + +#define REG_A5XX_RBBM_PERFCTR_VSC_0_HI 0x00000451 + +#define REG_A5XX_RBBM_PERFCTR_VSC_1_LO 0x00000452 + +#define REG_A5XX_RBBM_PERFCTR_VSC_1_HI 0x00000453 + +#define REG_A5XX_RBBM_PERFCTR_LRZ_0_LO 0x00000454 + +#define REG_A5XX_RBBM_PERFCTR_LRZ_0_HI 0x00000455 + +#define REG_A5XX_RBBM_PERFCTR_LRZ_1_LO 0x00000456 + +#define REG_A5XX_RBBM_PERFCTR_LRZ_1_HI 0x00000457 + +#define REG_A5XX_RBBM_PERFCTR_LRZ_2_LO 0x00000458 + +#define REG_A5XX_RBBM_PERFCTR_LRZ_2_HI 0x00000459 + +#define REG_A5XX_RBBM_PERFCTR_LRZ_3_LO 0x0000045a + +#define REG_A5XX_RBBM_PERFCTR_LRZ_3_HI 0x0000045b + +#define REG_A5XX_RBBM_PERFCTR_CMP_0_LO 0x0000045c + +#define REG_A5XX_RBBM_PERFCTR_CMP_0_HI 0x0000045d + +#define REG_A5XX_RBBM_PERFCTR_CMP_1_LO 0x0000045e + +#define REG_A5XX_RBBM_PERFCTR_CMP_1_HI 0x0000045f + +#define REG_A5XX_RBBM_PERFCTR_CMP_2_LO 0x00000460 + +#define REG_A5XX_RBBM_PERFCTR_CMP_2_HI 0x00000461 + +#define REG_A5XX_RBBM_PERFCTR_CMP_3_LO 0x00000462 + +#define REG_A5XX_RBBM_PERFCTR_CMP_3_HI 0x00000463 + +#define REG_A5XX_RBBM_PERFCTR_RBBM_SEL_0 0x0000046b + +#define REG_A5XX_RBBM_PERFCTR_RBBM_SEL_1 0x0000046c + +#define REG_A5XX_RBBM_PERFCTR_RBBM_SEL_2 0x0000046d + +#define REG_A5XX_RBBM_PERFCTR_RBBM_SEL_3 0x0000046e + +#define REG_A5XX_RBBM_ALWAYSON_COUNTER_LO 0x000004d2 + +#define REG_A5XX_RBBM_ALWAYSON_COUNTER_HI 0x000004d3 + +#define REG_A5XX_RBBM_STATUS 0x000004f5 +#define A5XX_RBBM_STATUS_GPU_BUSY_IGN_AHB 0x80000000 +#define A5XX_RBBM_STATUS_GPU_BUSY_IGN_AHB_CP 0x40000000 +#define A5XX_RBBM_STATUS_HLSQ_BUSY 0x20000000 +#define A5XX_RBBM_STATUS_VSC_BUSY 0x10000000 +#define A5XX_RBBM_STATUS_TPL1_BUSY 0x08000000 +#define A5XX_RBBM_STATUS_SP_BUSY 0x04000000 +#define A5XX_RBBM_STATUS_UCHE_BUSY 0x02000000 +#define A5XX_RBBM_STATUS_VPC_BUSY 0x01000000 +#define A5XX_RBBM_STATUS_VFDP_BUSY 0x00800000 +#define A5XX_RBBM_STATUS_VFD_BUSY 0x00400000 +#define A5XX_RBBM_STATUS_TESS_BUSY 0x00200000 +#define A5XX_RBBM_STATUS_PC_VSD_BUSY 0x00100000 +#define A5XX_RBBM_STATUS_PC_DCALL_BUSY 0x00080000 +#define A5XX_RBBM_STATUS_GPMU_SLAVE_BUSY 0x00040000 +#define A5XX_RBBM_STATUS_DCOM_BUSY 0x00020000 +#define A5XX_RBBM_STATUS_COM_BUSY 0x00010000 +#define A5XX_RBBM_STATUS_LRZ_BUZY 0x00008000 +#define A5XX_RBBM_STATUS_A2D_DSP_BUSY 0x00004000 +#define A5XX_RBBM_STATUS_CCUFCHE_BUSY 0x00002000 +#define A5XX_RBBM_STATUS_RB_BUSY 0x00001000 +#define A5XX_RBBM_STATUS_RAS_BUSY 0x00000800 +#define A5XX_RBBM_STATUS_TSE_BUSY 0x00000400 +#define A5XX_RBBM_STATUS_VBIF_BUSY 0x00000200 +#define A5XX_RBBM_STATUS_GPU_BUSY_IGN_AHB_HYST 0x00000100 +#define A5XX_RBBM_STATUS_CP_BUSY_IGN_HYST 0x00000080 +#define A5XX_RBBM_STATUS_CP_BUSY 0x00000040 +#define A5XX_RBBM_STATUS_GPMU_MASTER_BUSY 0x00000020 +#define A5XX_RBBM_STATUS_CP_CRASH_BUSY 0x00000010 +#define A5XX_RBBM_STATUS_CP_ETS_BUSY 0x00000008 +#define A5XX_RBBM_STATUS_CP_PFP_BUSY 0x00000004 +#define A5XX_RBBM_STATUS_CP_ME_BUSY 0x00000002 +#define A5XX_RBBM_STATUS_HI_BUSY 0x00000001 + +#define REG_A5XX_RBBM_STATUS3 0x00000530 + +#define REG_A5XX_RBBM_INT_0_STATUS 0x000004e1 + +#define REG_A5XX_RBBM_AHB_ME_SPLIT_STATUS 0x000004f0 + +#define REG_A5XX_RBBM_AHB_PFP_SPLIT_STATUS 0x000004f1 + +#define REG_A5XX_RBBM_AHB_ETS_SPLIT_STATUS 0x000004f3 + +#define REG_A5XX_RBBM_AHB_ERROR_STATUS 0x000004f4 + +#define REG_A5XX_RBBM_PERFCTR_CNTL 0x00000464 + +#define REG_A5XX_RBBM_PERFCTR_LOAD_CMD0 0x00000465 + +#define REG_A5XX_RBBM_PERFCTR_LOAD_CMD1 0x00000466 + +#define REG_A5XX_RBBM_PERFCTR_LOAD_CMD2 0x00000467 + +#define REG_A5XX_RBBM_PERFCTR_LOAD_CMD3 0x00000468 + +#define REG_A5XX_RBBM_PERFCTR_LOAD_VALUE_LO 0x00000469 + +#define REG_A5XX_RBBM_PERFCTR_LOAD_VALUE_HI 0x0000046a + +#define REG_A5XX_RBBM_PERFCTR_RBBM_SEL_0 0x0000046b + +#define REG_A5XX_RBBM_PERFCTR_RBBM_SEL_1 0x0000046c + +#define REG_A5XX_RBBM_PERFCTR_RBBM_SEL_2 0x0000046d + +#define REG_A5XX_RBBM_PERFCTR_RBBM_SEL_3 0x0000046e + +#define REG_A5XX_RBBM_PERFCTR_GPU_BUSY_MASKED 0x0000046f + +#define REG_A5XX_RBBM_AHB_ERROR 0x000004ed + +#define REG_A5XX_RBBM_CFG_DBGBUS_EVENT_LOGIC 0x00000504 + +#define REG_A5XX_RBBM_CFG_DBGBUS_OVER 0x00000505 + +#define REG_A5XX_RBBM_CFG_DBGBUS_COUNT0 0x00000506 + +#define REG_A5XX_RBBM_CFG_DBGBUS_COUNT1 0x00000507 + +#define REG_A5XX_RBBM_CFG_DBGBUS_COUNT2 0x00000508 + +#define REG_A5XX_RBBM_CFG_DBGBUS_COUNT3 0x00000509 + +#define REG_A5XX_RBBM_CFG_DBGBUS_COUNT4 0x0000050a + +#define REG_A5XX_RBBM_CFG_DBGBUS_COUNT5 0x0000050b + +#define REG_A5XX_RBBM_CFG_DBGBUS_TRACE_ADDR 0x0000050c + +#define REG_A5XX_RBBM_CFG_DBGBUS_TRACE_BUF0 0x0000050d + +#define REG_A5XX_RBBM_CFG_DBGBUS_TRACE_BUF1 0x0000050e + +#define REG_A5XX_RBBM_CFG_DBGBUS_TRACE_BUF2 0x0000050f + +#define REG_A5XX_RBBM_CFG_DBGBUS_TRACE_BUF3 0x00000510 + +#define REG_A5XX_RBBM_CFG_DBGBUS_TRACE_BUF4 0x00000511 + +#define REG_A5XX_RBBM_CFG_DBGBUS_MISR0 0x00000512 + +#define REG_A5XX_RBBM_CFG_DBGBUS_MISR1 0x00000513 + +#define REG_A5XX_RBBM_ISDB_CNT 0x00000533 + +#define REG_A5XX_RBBM_SECVID_TRUST_CONFIG 0x0000f000 + +#define REG_A5XX_RBBM_SECVID_TRUST_CNTL 0x0000f400 + +#define REG_A5XX_RBBM_SECVID_TSB_TRUSTED_BASE_LO 0x0000f800 + +#define REG_A5XX_RBBM_SECVID_TSB_TRUSTED_BASE_HI 0x0000f801 + +#define REG_A5XX_RBBM_SECVID_TSB_TRUSTED_SIZE 0x0000f802 + +#define REG_A5XX_RBBM_SECVID_TSB_CNTL 0x0000f803 + +#define REG_A5XX_RBBM_SECVID_TSB_COMP_STATUS_LO 0x0000f804 + +#define REG_A5XX_RBBM_SECVID_TSB_COMP_STATUS_HI 0x0000f805 + +#define REG_A5XX_RBBM_SECVID_TSB_UCHE_STATUS_LO 0x0000f806 + +#define REG_A5XX_RBBM_SECVID_TSB_UCHE_STATUS_HI 0x0000f807 + +#define REG_A5XX_RBBM_SECVID_TSB_ADDR_MODE_CNTL 0x0000f810 + +#define REG_A5XX_VSC_BIN_SIZE 0x00000bc2 +#define A5XX_VSC_BIN_SIZE_WIDTH__MASK 0x000000ff +#define A5XX_VSC_BIN_SIZE_WIDTH__SHIFT 0 +static inline uint32_t A5XX_VSC_BIN_SIZE_WIDTH(uint32_t val) +{ + return ((val >> 5) << A5XX_VSC_BIN_SIZE_WIDTH__SHIFT) & A5XX_VSC_BIN_SIZE_WIDTH__MASK; +} +#define A5XX_VSC_BIN_SIZE_HEIGHT__MASK 0x0001fe00 +#define A5XX_VSC_BIN_SIZE_HEIGHT__SHIFT 9 +static inline uint32_t A5XX_VSC_BIN_SIZE_HEIGHT(uint32_t val) +{ + return ((val >> 5) << A5XX_VSC_BIN_SIZE_HEIGHT__SHIFT) & A5XX_VSC_BIN_SIZE_HEIGHT__MASK; +} + +#define REG_A5XX_VSC_SIZE_ADDRESS_LO 0x00000bc3 + +#define REG_A5XX_VSC_SIZE_ADDRESS_HI 0x00000bc4 + +#define REG_A5XX_UNKNOWN_0BC5 0x00000bc5 + +#define REG_A5XX_UNKNOWN_0BC6 0x00000bc6 + +static inline uint32_t REG_A5XX_VSC_PIPE_CONFIG(uint32_t i0) { return 0x00000bd0 + 0x1*i0; } + +static inline uint32_t REG_A5XX_VSC_PIPE_CONFIG_REG(uint32_t i0) { return 0x00000bd0 + 0x1*i0; } +#define A5XX_VSC_PIPE_CONFIG_REG_X__MASK 0x000003ff +#define A5XX_VSC_PIPE_CONFIG_REG_X__SHIFT 0 +static inline uint32_t A5XX_VSC_PIPE_CONFIG_REG_X(uint32_t val) +{ + return ((val) << A5XX_VSC_PIPE_CONFIG_REG_X__SHIFT) & A5XX_VSC_PIPE_CONFIG_REG_X__MASK; +} +#define A5XX_VSC_PIPE_CONFIG_REG_Y__MASK 0x000ffc00 +#define A5XX_VSC_PIPE_CONFIG_REG_Y__SHIFT 10 +static inline uint32_t A5XX_VSC_PIPE_CONFIG_REG_Y(uint32_t val) +{ + return ((val) << A5XX_VSC_PIPE_CONFIG_REG_Y__SHIFT) & A5XX_VSC_PIPE_CONFIG_REG_Y__MASK; +} +#define A5XX_VSC_PIPE_CONFIG_REG_W__MASK 0x00f00000 +#define A5XX_VSC_PIPE_CONFIG_REG_W__SHIFT 20 +static inline uint32_t A5XX_VSC_PIPE_CONFIG_REG_W(uint32_t val) +{ + return ((val) << A5XX_VSC_PIPE_CONFIG_REG_W__SHIFT) & A5XX_VSC_PIPE_CONFIG_REG_W__MASK; +} +#define A5XX_VSC_PIPE_CONFIG_REG_H__MASK 0x0f000000 +#define A5XX_VSC_PIPE_CONFIG_REG_H__SHIFT 24 +static inline uint32_t A5XX_VSC_PIPE_CONFIG_REG_H(uint32_t val) +{ + return ((val) << A5XX_VSC_PIPE_CONFIG_REG_H__SHIFT) & A5XX_VSC_PIPE_CONFIG_REG_H__MASK; +} + +static inline uint32_t REG_A5XX_VSC_PIPE_DATA_ADDRESS(uint32_t i0) { return 0x00000be0 + 0x2*i0; } + +static inline uint32_t REG_A5XX_VSC_PIPE_DATA_ADDRESS_LO(uint32_t i0) { return 0x00000be0 + 0x2*i0; } + +static inline uint32_t REG_A5XX_VSC_PIPE_DATA_ADDRESS_HI(uint32_t i0) { return 0x00000be1 + 0x2*i0; } + +static inline uint32_t REG_A5XX_VSC_PIPE_DATA_LENGTH(uint32_t i0) { return 0x00000c00 + 0x1*i0; } + +static inline uint32_t REG_A5XX_VSC_PIPE_DATA_LENGTH_REG(uint32_t i0) { return 0x00000c00 + 0x1*i0; } + +#define REG_A5XX_VSC_PERFCTR_VSC_SEL_0 0x00000c60 + +#define REG_A5XX_VSC_PERFCTR_VSC_SEL_1 0x00000c61 + +#define REG_A5XX_VSC_RESOLVE_CNTL 0x00000cdd +#define A5XX_VSC_RESOLVE_CNTL_WINDOW_OFFSET_DISABLE 0x80000000 +#define A5XX_VSC_RESOLVE_CNTL_X__MASK 0x00007fff +#define A5XX_VSC_RESOLVE_CNTL_X__SHIFT 0 +static inline uint32_t A5XX_VSC_RESOLVE_CNTL_X(uint32_t val) +{ + return ((val) << A5XX_VSC_RESOLVE_CNTL_X__SHIFT) & A5XX_VSC_RESOLVE_CNTL_X__MASK; +} +#define A5XX_VSC_RESOLVE_CNTL_Y__MASK 0x7fff0000 +#define A5XX_VSC_RESOLVE_CNTL_Y__SHIFT 16 +static inline uint32_t A5XX_VSC_RESOLVE_CNTL_Y(uint32_t val) +{ + return ((val) << A5XX_VSC_RESOLVE_CNTL_Y__SHIFT) & A5XX_VSC_RESOLVE_CNTL_Y__MASK; +} + +#define REG_A5XX_GRAS_ADDR_MODE_CNTL 0x00000c81 + +#define REG_A5XX_GRAS_PERFCTR_TSE_SEL_0 0x00000c90 + +#define REG_A5XX_GRAS_PERFCTR_TSE_SEL_1 0x00000c91 + +#define REG_A5XX_GRAS_PERFCTR_TSE_SEL_2 0x00000c92 + +#define REG_A5XX_GRAS_PERFCTR_TSE_SEL_3 0x00000c93 + +#define REG_A5XX_GRAS_PERFCTR_RAS_SEL_0 0x00000c94 + +#define REG_A5XX_GRAS_PERFCTR_RAS_SEL_1 0x00000c95 + +#define REG_A5XX_GRAS_PERFCTR_RAS_SEL_2 0x00000c96 + +#define REG_A5XX_GRAS_PERFCTR_RAS_SEL_3 0x00000c97 + +#define REG_A5XX_GRAS_PERFCTR_LRZ_SEL_0 0x00000c98 + +#define REG_A5XX_GRAS_PERFCTR_LRZ_SEL_1 0x00000c99 + +#define REG_A5XX_GRAS_PERFCTR_LRZ_SEL_2 0x00000c9a + +#define REG_A5XX_GRAS_PERFCTR_LRZ_SEL_3 0x00000c9b + +#define REG_A5XX_RB_DBG_ECO_CNTL 0x00000cc4 + +#define REG_A5XX_RB_ADDR_MODE_CNTL 0x00000cc5 + +#define REG_A5XX_RB_MODE_CNTL 0x00000cc6 + +#define REG_A5XX_RB_CCU_CNTL 0x00000cc7 + +#define REG_A5XX_RB_PERFCTR_RB_SEL_0 0x00000cd0 + +#define REG_A5XX_RB_PERFCTR_RB_SEL_1 0x00000cd1 + +#define REG_A5XX_RB_PERFCTR_RB_SEL_2 0x00000cd2 + +#define REG_A5XX_RB_PERFCTR_RB_SEL_3 0x00000cd3 + +#define REG_A5XX_RB_PERFCTR_RB_SEL_4 0x00000cd4 + +#define REG_A5XX_RB_PERFCTR_RB_SEL_5 0x00000cd5 + +#define REG_A5XX_RB_PERFCTR_RB_SEL_6 0x00000cd6 + +#define REG_A5XX_RB_PERFCTR_RB_SEL_7 0x00000cd7 + +#define REG_A5XX_RB_PERFCTR_CCU_SEL_0 0x00000cd8 + +#define REG_A5XX_RB_PERFCTR_CCU_SEL_1 0x00000cd9 + +#define REG_A5XX_RB_PERFCTR_CCU_SEL_2 0x00000cda + +#define REG_A5XX_RB_PERFCTR_CCU_SEL_3 0x00000cdb + +#define REG_A5XX_RB_POWERCTR_RB_SEL_0 0x00000ce0 + +#define REG_A5XX_RB_POWERCTR_RB_SEL_1 0x00000ce1 + +#define REG_A5XX_RB_POWERCTR_RB_SEL_2 0x00000ce2 + +#define REG_A5XX_RB_POWERCTR_RB_SEL_3 0x00000ce3 + +#define REG_A5XX_RB_POWERCTR_CCU_SEL_0 0x00000ce4 + +#define REG_A5XX_RB_POWERCTR_CCU_SEL_1 0x00000ce5 + +#define REG_A5XX_RB_PERFCTR_CMP_SEL_0 0x00000cec + +#define REG_A5XX_RB_PERFCTR_CMP_SEL_1 0x00000ced + +#define REG_A5XX_RB_PERFCTR_CMP_SEL_2 0x00000cee + +#define REG_A5XX_RB_PERFCTR_CMP_SEL_3 0x00000cef + +#define REG_A5XX_PC_DBG_ECO_CNTL 0x00000d00 +#define A5XX_PC_DBG_ECO_CNTL_TWOPASSUSEWFI 0x00000100 + +#define REG_A5XX_PC_ADDR_MODE_CNTL 0x00000d01 + +#define REG_A5XX_PC_MODE_CNTL 0x00000d02 + +#define REG_A5XX_PC_INDEX_BUF_LO 0x00000d04 + +#define REG_A5XX_PC_INDEX_BUF_HI 0x00000d05 + +#define REG_A5XX_PC_START_INDEX 0x00000d06 + +#define REG_A5XX_PC_MAX_INDEX 0x00000d07 + +#define REG_A5XX_PC_TESSFACTOR_ADDR_LO 0x00000d08 + +#define REG_A5XX_PC_TESSFACTOR_ADDR_HI 0x00000d09 + +#define REG_A5XX_PC_PERFCTR_PC_SEL_0 0x00000d10 + +#define REG_A5XX_PC_PERFCTR_PC_SEL_1 0x00000d11 + +#define REG_A5XX_PC_PERFCTR_PC_SEL_2 0x00000d12 + +#define REG_A5XX_PC_PERFCTR_PC_SEL_3 0x00000d13 + +#define REG_A5XX_PC_PERFCTR_PC_SEL_4 0x00000d14 + +#define REG_A5XX_PC_PERFCTR_PC_SEL_5 0x00000d15 + +#define REG_A5XX_PC_PERFCTR_PC_SEL_6 0x00000d16 + +#define REG_A5XX_PC_PERFCTR_PC_SEL_7 0x00000d17 + +#define REG_A5XX_HLSQ_TIMEOUT_THRESHOLD_0 0x00000e00 + +#define REG_A5XX_HLSQ_TIMEOUT_THRESHOLD_1 0x00000e01 + +#define REG_A5XX_HLSQ_DBG_ECO_CNTL 0x00000e04 + +#define REG_A5XX_HLSQ_ADDR_MODE_CNTL 0x00000e05 + +#define REG_A5XX_HLSQ_MODE_CNTL 0x00000e06 + +#define REG_A5XX_HLSQ_PERFCTR_HLSQ_SEL_0 0x00000e10 + +#define REG_A5XX_HLSQ_PERFCTR_HLSQ_SEL_1 0x00000e11 + +#define REG_A5XX_HLSQ_PERFCTR_HLSQ_SEL_2 0x00000e12 + +#define REG_A5XX_HLSQ_PERFCTR_HLSQ_SEL_3 0x00000e13 + +#define REG_A5XX_HLSQ_PERFCTR_HLSQ_SEL_4 0x00000e14 + +#define REG_A5XX_HLSQ_PERFCTR_HLSQ_SEL_5 0x00000e15 + +#define REG_A5XX_HLSQ_PERFCTR_HLSQ_SEL_6 0x00000e16 + +#define REG_A5XX_HLSQ_PERFCTR_HLSQ_SEL_7 0x00000e17 + +#define REG_A5XX_HLSQ_SPTP_RDSEL 0x00000f08 + +#define REG_A5XX_HLSQ_DBG_READ_SEL 0x0000bc00 + +#define REG_A5XX_HLSQ_DBG_AHB_READ_APERTURE 0x0000a000 + +#define REG_A5XX_VFD_ADDR_MODE_CNTL 0x00000e41 + +#define REG_A5XX_VFD_MODE_CNTL 0x00000e42 + +#define REG_A5XX_VFD_PERFCTR_VFD_SEL_0 0x00000e50 + +#define REG_A5XX_VFD_PERFCTR_VFD_SEL_1 0x00000e51 + +#define REG_A5XX_VFD_PERFCTR_VFD_SEL_2 0x00000e52 + +#define REG_A5XX_VFD_PERFCTR_VFD_SEL_3 0x00000e53 + +#define REG_A5XX_VFD_PERFCTR_VFD_SEL_4 0x00000e54 + +#define REG_A5XX_VFD_PERFCTR_VFD_SEL_5 0x00000e55 + +#define REG_A5XX_VFD_PERFCTR_VFD_SEL_6 0x00000e56 + +#define REG_A5XX_VFD_PERFCTR_VFD_SEL_7 0x00000e57 + +#define REG_A5XX_VPC_DBG_ECO_CNTL 0x00000e60 + +#define REG_A5XX_VPC_ADDR_MODE_CNTL 0x00000e61 + +#define REG_A5XX_VPC_MODE_CNTL 0x00000e62 +#define A5XX_VPC_MODE_CNTL_BINNING_PASS 0x00000001 + +#define REG_A5XX_VPC_PERFCTR_VPC_SEL_0 0x00000e64 + +#define REG_A5XX_VPC_PERFCTR_VPC_SEL_1 0x00000e65 + +#define REG_A5XX_VPC_PERFCTR_VPC_SEL_2 0x00000e66 + +#define REG_A5XX_VPC_PERFCTR_VPC_SEL_3 0x00000e67 + +#define REG_A5XX_UCHE_ADDR_MODE_CNTL 0x00000e80 + +#define REG_A5XX_UCHE_SVM_CNTL 0x00000e82 + +#define REG_A5XX_UCHE_WRITE_THRU_BASE_LO 0x00000e87 + +#define REG_A5XX_UCHE_WRITE_THRU_BASE_HI 0x00000e88 + +#define REG_A5XX_UCHE_TRAP_BASE_LO 0x00000e89 + +#define REG_A5XX_UCHE_TRAP_BASE_HI 0x00000e8a + +#define REG_A5XX_UCHE_GMEM_RANGE_MIN_LO 0x00000e8b + +#define REG_A5XX_UCHE_GMEM_RANGE_MIN_HI 0x00000e8c + +#define REG_A5XX_UCHE_GMEM_RANGE_MAX_LO 0x00000e8d + +#define REG_A5XX_UCHE_GMEM_RANGE_MAX_HI 0x00000e8e + +#define REG_A5XX_UCHE_DBG_ECO_CNTL_2 0x00000e8f + +#define REG_A5XX_UCHE_DBG_ECO_CNTL 0x00000e90 + +#define REG_A5XX_UCHE_CACHE_INVALIDATE_MIN_LO 0x00000e91 + +#define REG_A5XX_UCHE_CACHE_INVALIDATE_MIN_HI 0x00000e92 + +#define REG_A5XX_UCHE_CACHE_INVALIDATE_MAX_LO 0x00000e93 + +#define REG_A5XX_UCHE_CACHE_INVALIDATE_MAX_HI 0x00000e94 + +#define REG_A5XX_UCHE_CACHE_INVALIDATE 0x00000e95 + +#define REG_A5XX_UCHE_CACHE_WAYS 0x00000e96 + +#define REG_A5XX_UCHE_PERFCTR_UCHE_SEL_0 0x00000ea0 + +#define REG_A5XX_UCHE_PERFCTR_UCHE_SEL_1 0x00000ea1 + +#define REG_A5XX_UCHE_PERFCTR_UCHE_SEL_2 0x00000ea2 + +#define REG_A5XX_UCHE_PERFCTR_UCHE_SEL_3 0x00000ea3 + +#define REG_A5XX_UCHE_PERFCTR_UCHE_SEL_4 0x00000ea4 + +#define REG_A5XX_UCHE_PERFCTR_UCHE_SEL_5 0x00000ea5 + +#define REG_A5XX_UCHE_PERFCTR_UCHE_SEL_6 0x00000ea6 + +#define REG_A5XX_UCHE_PERFCTR_UCHE_SEL_7 0x00000ea7 + +#define REG_A5XX_UCHE_POWERCTR_UCHE_SEL_0 0x00000ea8 + +#define REG_A5XX_UCHE_POWERCTR_UCHE_SEL_1 0x00000ea9 + +#define REG_A5XX_UCHE_POWERCTR_UCHE_SEL_2 0x00000eaa + +#define REG_A5XX_UCHE_POWERCTR_UCHE_SEL_3 0x00000eab + +#define REG_A5XX_UCHE_TRAP_LOG_LO 0x00000eb1 + +#define REG_A5XX_UCHE_TRAP_LOG_HI 0x00000eb2 + +#define REG_A5XX_SP_DBG_ECO_CNTL 0x00000ec0 + +#define REG_A5XX_SP_ADDR_MODE_CNTL 0x00000ec1 + +#define REG_A5XX_SP_MODE_CNTL 0x00000ec2 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_0 0x00000ed0 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_1 0x00000ed1 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_2 0x00000ed2 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_3 0x00000ed3 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_4 0x00000ed4 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_5 0x00000ed5 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_6 0x00000ed6 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_7 0x00000ed7 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_8 0x00000ed8 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_9 0x00000ed9 + +#define REG_A5XX_SP_PERFCTR_SP_SEL_10 0x00000eda + +#define REG_A5XX_SP_PERFCTR_SP_SEL_11 0x00000edb + +#define REG_A5XX_SP_POWERCTR_SP_SEL_0 0x00000edc + +#define REG_A5XX_SP_POWERCTR_SP_SEL_1 0x00000edd + +#define REG_A5XX_SP_POWERCTR_SP_SEL_2 0x00000ede + +#define REG_A5XX_SP_POWERCTR_SP_SEL_3 0x00000edf + +#define REG_A5XX_TPL1_ADDR_MODE_CNTL 0x00000f01 + +#define REG_A5XX_TPL1_MODE_CNTL 0x00000f02 + +#define REG_A5XX_TPL1_PERFCTR_TP_SEL_0 0x00000f10 + +#define REG_A5XX_TPL1_PERFCTR_TP_SEL_1 0x00000f11 + +#define REG_A5XX_TPL1_PERFCTR_TP_SEL_2 0x00000f12 + +#define REG_A5XX_TPL1_PERFCTR_TP_SEL_3 0x00000f13 + +#define REG_A5XX_TPL1_PERFCTR_TP_SEL_4 0x00000f14 + +#define REG_A5XX_TPL1_PERFCTR_TP_SEL_5 0x00000f15 + +#define REG_A5XX_TPL1_PERFCTR_TP_SEL_6 0x00000f16 + +#define REG_A5XX_TPL1_PERFCTR_TP_SEL_7 0x00000f17 + +#define REG_A5XX_TPL1_POWERCTR_TP_SEL_0 0x00000f18 + +#define REG_A5XX_TPL1_POWERCTR_TP_SEL_1 0x00000f19 + +#define REG_A5XX_TPL1_POWERCTR_TP_SEL_2 0x00000f1a + +#define REG_A5XX_TPL1_POWERCTR_TP_SEL_3 0x00000f1b + +#define REG_A5XX_VBIF_VERSION 0x00003000 + +#define REG_A5XX_VBIF_CLKON 0x00003001 + +#define REG_A5XX_VBIF_ABIT_SORT 0x00003028 + +#define REG_A5XX_VBIF_ABIT_SORT_CONF 0x00003029 + +#define REG_A5XX_VBIF_ROUND_ROBIN_QOS_ARB 0x00003049 + +#define REG_A5XX_VBIF_GATE_OFF_WRREQ_EN 0x0000302a + +#define REG_A5XX_VBIF_IN_RD_LIM_CONF0 0x0000302c + +#define REG_A5XX_VBIF_IN_RD_LIM_CONF1 0x0000302d + +#define REG_A5XX_VBIF_XIN_HALT_CTRL0 0x00003080 + +#define REG_A5XX_VBIF_XIN_HALT_CTRL1 0x00003081 + +#define REG_A5XX_VBIF_TEST_BUS_OUT_CTRL 0x00003084 + +#define REG_A5XX_VBIF_TEST_BUS1_CTRL0 0x00003085 + +#define REG_A5XX_VBIF_TEST_BUS1_CTRL1 0x00003086 + +#define REG_A5XX_VBIF_TEST_BUS2_CTRL0 0x00003087 + +#define REG_A5XX_VBIF_TEST_BUS2_CTRL1 0x00003088 + +#define REG_A5XX_VBIF_TEST_BUS_OUT 0x0000308c + +#define REG_A5XX_VBIF_PERF_CNT_EN0 0x000030c0 + +#define REG_A5XX_VBIF_PERF_CNT_EN1 0x000030c1 + +#define REG_A5XX_VBIF_PERF_CNT_EN2 0x000030c2 + +#define REG_A5XX_VBIF_PERF_CNT_EN3 0x000030c3 + +#define REG_A5XX_VBIF_PERF_CNT_CLR0 0x000030c8 + +#define REG_A5XX_VBIF_PERF_CNT_CLR1 0x000030c9 + +#define REG_A5XX_VBIF_PERF_CNT_CLR2 0x000030ca + +#define REG_A5XX_VBIF_PERF_CNT_CLR3 0x000030cb + +#define REG_A5XX_VBIF_PERF_CNT_SEL0 0x000030d0 + +#define REG_A5XX_VBIF_PERF_CNT_SEL1 0x000030d1 + +#define REG_A5XX_VBIF_PERF_CNT_SEL2 0x000030d2 + +#define REG_A5XX_VBIF_PERF_CNT_SEL3 0x000030d3 + +#define REG_A5XX_VBIF_PERF_CNT_LOW0 0x000030d8 + +#define REG_A5XX_VBIF_PERF_CNT_LOW1 0x000030d9 + +#define REG_A5XX_VBIF_PERF_CNT_LOW2 0x000030da + +#define REG_A5XX_VBIF_PERF_CNT_LOW3 0x000030db + +#define REG_A5XX_VBIF_PERF_CNT_HIGH0 0x000030e0 + +#define REG_A5XX_VBIF_PERF_CNT_HIGH1 0x000030e1 + +#define REG_A5XX_VBIF_PERF_CNT_HIGH2 0x000030e2 + +#define REG_A5XX_VBIF_PERF_CNT_HIGH3 0x000030e3 + +#define REG_A5XX_VBIF_PERF_PWR_CNT_EN0 0x00003100 + +#define REG_A5XX_VBIF_PERF_PWR_CNT_EN1 0x00003101 + +#define REG_A5XX_VBIF_PERF_PWR_CNT_EN2 0x00003102 + +#define REG_A5XX_VBIF_PERF_PWR_CNT_LOW0 0x00003110 + +#define REG_A5XX_VBIF_PERF_PWR_CNT_LOW1 0x00003111 + +#define REG_A5XX_VBIF_PERF_PWR_CNT_LOW2 0x00003112 + +#define REG_A5XX_VBIF_PERF_PWR_CNT_HIGH0 0x00003118 + +#define REG_A5XX_VBIF_PERF_PWR_CNT_HIGH1 0x00003119 + +#define REG_A5XX_VBIF_PERF_PWR_CNT_HIGH2 0x0000311a + +#define REG_A5XX_GPMU_INST_RAM_BASE 0x00008800 + +#define REG_A5XX_GPMU_DATA_RAM_BASE 0x00009800 + +#define REG_A5XX_GPMU_SP_POWER_CNTL 0x0000a881 + +#define REG_A5XX_GPMU_RBCCU_CLOCK_CNTL 0x0000a886 + +#define REG_A5XX_GPMU_RBCCU_POWER_CNTL 0x0000a887 + +#define REG_A5XX_GPMU_SP_PWR_CLK_STATUS 0x0000a88b +#define A5XX_GPMU_SP_PWR_CLK_STATUS_PWR_ON 0x00100000 + +#define REG_A5XX_GPMU_RBCCU_PWR_CLK_STATUS 0x0000a88d +#define A5XX_GPMU_RBCCU_PWR_CLK_STATUS_PWR_ON 0x00100000 + +#define REG_A5XX_GPMU_PWR_COL_STAGGER_DELAY 0x0000a891 + +#define REG_A5XX_GPMU_PWR_COL_INTER_FRAME_CTRL 0x0000a892 + +#define REG_A5XX_GPMU_PWR_COL_INTER_FRAME_HYST 0x0000a893 + +#define REG_A5XX_GPMU_PWR_COL_BINNING_CTRL 0x0000a894 + +#define REG_A5XX_GPMU_CLOCK_THROTTLE_CTRL 0x0000a8a3 + +#define REG_A5XX_GPMU_WFI_CONFIG 0x0000a8c1 + +#define REG_A5XX_GPMU_RBBM_INTR_INFO 0x0000a8d6 + +#define REG_A5XX_GPMU_CM3_SYSRESET 0x0000a8d8 + +#define REG_A5XX_GPMU_GENERAL_0 0x0000a8e0 + +#define REG_A5XX_GPMU_GENERAL_1 0x0000a8e1 + +#define REG_A5XX_SP_POWER_COUNTER_0_LO 0x0000a840 + +#define REG_A5XX_SP_POWER_COUNTER_0_HI 0x0000a841 + +#define REG_A5XX_SP_POWER_COUNTER_1_LO 0x0000a842 + +#define REG_A5XX_SP_POWER_COUNTER_1_HI 0x0000a843 + +#define REG_A5XX_SP_POWER_COUNTER_2_LO 0x0000a844 + +#define REG_A5XX_SP_POWER_COUNTER_2_HI 0x0000a845 + +#define REG_A5XX_SP_POWER_COUNTER_3_LO 0x0000a846 + +#define REG_A5XX_SP_POWER_COUNTER_3_HI 0x0000a847 + +#define REG_A5XX_TP_POWER_COUNTER_0_LO 0x0000a848 + +#define REG_A5XX_TP_POWER_COUNTER_0_HI 0x0000a849 + +#define REG_A5XX_TP_POWER_COUNTER_1_LO 0x0000a84a + +#define REG_A5XX_TP_POWER_COUNTER_1_HI 0x0000a84b + +#define REG_A5XX_TP_POWER_COUNTER_2_LO 0x0000a84c + +#define REG_A5XX_TP_POWER_COUNTER_2_HI 0x0000a84d + +#define REG_A5XX_TP_POWER_COUNTER_3_LO 0x0000a84e + +#define REG_A5XX_TP_POWER_COUNTER_3_HI 0x0000a84f + +#define REG_A5XX_RB_POWER_COUNTER_0_LO 0x0000a850 + +#define REG_A5XX_RB_POWER_COUNTER_0_HI 0x0000a851 + +#define REG_A5XX_RB_POWER_COUNTER_1_LO 0x0000a852 + +#define REG_A5XX_RB_POWER_COUNTER_1_HI 0x0000a853 + +#define REG_A5XX_RB_POWER_COUNTER_2_LO 0x0000a854 + +#define REG_A5XX_RB_POWER_COUNTER_2_HI 0x0000a855 + +#define REG_A5XX_RB_POWER_COUNTER_3_LO 0x0000a856 + +#define REG_A5XX_RB_POWER_COUNTER_3_HI 0x0000a857 + +#define REG_A5XX_CCU_POWER_COUNTER_0_LO 0x0000a858 + +#define REG_A5XX_CCU_POWER_COUNTER_0_HI 0x0000a859 + +#define REG_A5XX_CCU_POWER_COUNTER_1_LO 0x0000a85a + +#define REG_A5XX_CCU_POWER_COUNTER_1_HI 0x0000a85b + +#define REG_A5XX_UCHE_POWER_COUNTER_0_LO 0x0000a85c + +#define REG_A5XX_UCHE_POWER_COUNTER_0_HI 0x0000a85d + +#define REG_A5XX_UCHE_POWER_COUNTER_1_LO 0x0000a85e + +#define REG_A5XX_UCHE_POWER_COUNTER_1_HI 0x0000a85f + +#define REG_A5XX_UCHE_POWER_COUNTER_2_LO 0x0000a860 + +#define REG_A5XX_UCHE_POWER_COUNTER_2_HI 0x0000a861 + +#define REG_A5XX_UCHE_POWER_COUNTER_3_LO 0x0000a862 + +#define REG_A5XX_UCHE_POWER_COUNTER_3_HI 0x0000a863 + +#define REG_A5XX_CP_POWER_COUNTER_0_LO 0x0000a864 + +#define REG_A5XX_CP_POWER_COUNTER_0_HI 0x0000a865 + +#define REG_A5XX_CP_POWER_COUNTER_1_LO 0x0000a866 + +#define REG_A5XX_CP_POWER_COUNTER_1_HI 0x0000a867 + +#define REG_A5XX_CP_POWER_COUNTER_2_LO 0x0000a868 + +#define REG_A5XX_CP_POWER_COUNTER_2_HI 0x0000a869 + +#define REG_A5XX_CP_POWER_COUNTER_3_LO 0x0000a86a + +#define REG_A5XX_CP_POWER_COUNTER_3_HI 0x0000a86b + +#define REG_A5XX_GPMU_POWER_COUNTER_0_LO 0x0000a86c + +#define REG_A5XX_GPMU_POWER_COUNTER_0_HI 0x0000a86d + +#define REG_A5XX_GPMU_POWER_COUNTER_1_LO 0x0000a86e + +#define REG_A5XX_GPMU_POWER_COUNTER_1_HI 0x0000a86f + +#define REG_A5XX_GPMU_POWER_COUNTER_2_LO 0x0000a870 + +#define REG_A5XX_GPMU_POWER_COUNTER_2_HI 0x0000a871 + +#define REG_A5XX_GPMU_POWER_COUNTER_3_LO 0x0000a872 + +#define REG_A5XX_GPMU_POWER_COUNTER_3_HI 0x0000a873 + +#define REG_A5XX_GPMU_POWER_COUNTER_4_LO 0x0000a874 + +#define REG_A5XX_GPMU_POWER_COUNTER_4_HI 0x0000a875 + +#define REG_A5XX_GPMU_POWER_COUNTER_5_LO 0x0000a876 + +#define REG_A5XX_GPMU_POWER_COUNTER_5_HI 0x0000a877 + +#define REG_A5XX_GPMU_POWER_COUNTER_ENABLE 0x0000a878 + +#define REG_A5XX_GPMU_ALWAYS_ON_COUNTER_LO 0x0000a879 + +#define REG_A5XX_GPMU_ALWAYS_ON_COUNTER_HI 0x0000a87a + +#define REG_A5XX_GPMU_ALWAYS_ON_COUNTER_RESET 0x0000a87b + +#define REG_A5XX_GPMU_POWER_COUNTER_SELECT_0 0x0000a87c + +#define REG_A5XX_GPMU_POWER_COUNTER_SELECT_1 0x0000a87d + +#define REG_A5XX_GPMU_CLOCK_THROTTLE_CTRL 0x0000a8a3 + +#define REG_A5XX_GPMU_THROTTLE_UNMASK_FORCE_CTRL 0x0000a8a8 + +#define REG_A5XX_GPMU_TEMP_SENSOR_ID 0x0000ac00 + +#define REG_A5XX_GPMU_TEMP_SENSOR_CONFIG 0x0000ac01 + +#define REG_A5XX_GPMU_TEMP_VAL 0x0000ac02 + +#define REG_A5XX_GPMU_DELTA_TEMP_THRESHOLD 0x0000ac03 + +#define REG_A5XX_GPMU_TEMP_THRESHOLD_INTR_STATUS 0x0000ac05 + +#define REG_A5XX_GPMU_TEMP_THRESHOLD_INTR_EN_MASK 0x0000ac06 + +#define REG_A5XX_GPMU_LEAKAGE_TEMP_COEFF_0_1 0x0000ac40 + +#define REG_A5XX_GPMU_LEAKAGE_TEMP_COEFF_2_3 0x0000ac41 + +#define REG_A5XX_GPMU_LEAKAGE_VTG_COEFF_0_1 0x0000ac42 + +#define REG_A5XX_GPMU_LEAKAGE_VTG_COEFF_2_3 0x0000ac43 + +#define REG_A5XX_GPMU_BASE_LEAKAGE 0x0000ac46 + +#define REG_A5XX_GPMU_GPMU_VOLTAGE 0x0000ac60 + +#define REG_A5XX_GPMU_GPMU_VOLTAGE_INTR_STATUS 0x0000ac61 + +#define REG_A5XX_GPMU_GPMU_VOLTAGE_INTR_EN_MASK 0x0000ac62 + +#define REG_A5XX_GPMU_GPMU_PWR_THRESHOLD 0x0000ac80 + +#define REG_A5XX_GPMU_GPMU_LLM_GLM_SLEEP_CTRL 0x0000acc4 + +#define REG_A5XX_GPMU_GPMU_LLM_GLM_SLEEP_STATUS 0x0000acc5 + +#define REG_A5XX_GDPM_CONFIG1 0x0000b80c + +#define REG_A5XX_GDPM_CONFIG2 0x0000b80d + +#define REG_A5XX_GDPM_INT_EN 0x0000b80f + +#define REG_A5XX_GDPM_INT_MASK 0x0000b811 + +#define REG_A5XX_GPMU_BEC_ENABLE 0x0000b9a0 + +#define REG_A5XX_GPU_CS_SENSOR_GENERAL_STATUS 0x0000c41a + +#define REG_A5XX_GPU_CS_AMP_CALIBRATION_STATUS1_0 0x0000c41d + +#define REG_A5XX_GPU_CS_AMP_CALIBRATION_STATUS1_2 0x0000c41f + +#define REG_A5XX_GPU_CS_AMP_CALIBRATION_STATUS1_4 0x0000c421 + +#define REG_A5XX_GPU_CS_ENABLE_REG 0x0000c520 + +#define REG_A5XX_GPU_CS_AMP_CALIBRATION_CONTROL1 0x0000c557 + +#define REG_A5XX_GRAS_CL_CNTL 0x0000e000 +#define A5XX_GRAS_CL_CNTL_ZERO_GB_SCALE_Z 0x00000040 + +#define REG_A5XX_UNKNOWN_E001 0x0000e001 + +#define REG_A5XX_UNKNOWN_E004 0x0000e004 + +#define REG_A5XX_GRAS_CNTL 0x0000e005 +#define A5XX_GRAS_CNTL_VARYING 0x00000001 +#define A5XX_GRAS_CNTL_UNK3 0x00000008 +#define A5XX_GRAS_CNTL_XCOORD 0x00000040 +#define A5XX_GRAS_CNTL_YCOORD 0x00000080 +#define A5XX_GRAS_CNTL_ZCOORD 0x00000100 +#define A5XX_GRAS_CNTL_WCOORD 0x00000200 + +#define REG_A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ 0x0000e006 +#define A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ_HORZ__MASK 0x000003ff +#define A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ_HORZ__SHIFT 0 +static inline uint32_t A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ_HORZ(uint32_t val) +{ + return ((val) << A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ_HORZ__SHIFT) & A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ_HORZ__MASK; +} +#define A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ_VERT__MASK 0x000ffc00 +#define A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ_VERT__SHIFT 10 +static inline uint32_t A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ_VERT(uint32_t val) +{ + return ((val) << A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ_VERT__SHIFT) & A5XX_GRAS_CL_GUARDBAND_CLIP_ADJ_VERT__MASK; +} + +#define REG_A5XX_GRAS_CL_VPORT_XOFFSET_0 0x0000e010 +#define A5XX_GRAS_CL_VPORT_XOFFSET_0__MASK 0xffffffff +#define A5XX_GRAS_CL_VPORT_XOFFSET_0__SHIFT 0 +static inline uint32_t A5XX_GRAS_CL_VPORT_XOFFSET_0(float val) +{ + return ((fui(val)) << A5XX_GRAS_CL_VPORT_XOFFSET_0__SHIFT) & A5XX_GRAS_CL_VPORT_XOFFSET_0__MASK; +} + +#define REG_A5XX_GRAS_CL_VPORT_XSCALE_0 0x0000e011 +#define A5XX_GRAS_CL_VPORT_XSCALE_0__MASK 0xffffffff +#define A5XX_GRAS_CL_VPORT_XSCALE_0__SHIFT 0 +static inline uint32_t A5XX_GRAS_CL_VPORT_XSCALE_0(float val) +{ + return ((fui(val)) << A5XX_GRAS_CL_VPORT_XSCALE_0__SHIFT) & A5XX_GRAS_CL_VPORT_XSCALE_0__MASK; +} + +#define REG_A5XX_GRAS_CL_VPORT_YOFFSET_0 0x0000e012 +#define A5XX_GRAS_CL_VPORT_YOFFSET_0__MASK 0xffffffff +#define A5XX_GRAS_CL_VPORT_YOFFSET_0__SHIFT 0 +static inline uint32_t A5XX_GRAS_CL_VPORT_YOFFSET_0(float val) +{ + return ((fui(val)) << A5XX_GRAS_CL_VPORT_YOFFSET_0__SHIFT) & A5XX_GRAS_CL_VPORT_YOFFSET_0__MASK; +} + +#define REG_A5XX_GRAS_CL_VPORT_YSCALE_0 0x0000e013 +#define A5XX_GRAS_CL_VPORT_YSCALE_0__MASK 0xffffffff +#define A5XX_GRAS_CL_VPORT_YSCALE_0__SHIFT 0 +static inline uint32_t A5XX_GRAS_CL_VPORT_YSCALE_0(float val) +{ + return ((fui(val)) << A5XX_GRAS_CL_VPORT_YSCALE_0__SHIFT) & A5XX_GRAS_CL_VPORT_YSCALE_0__MASK; +} + +#define REG_A5XX_GRAS_CL_VPORT_ZOFFSET_0 0x0000e014 +#define A5XX_GRAS_CL_VPORT_ZOFFSET_0__MASK 0xffffffff +#define A5XX_GRAS_CL_VPORT_ZOFFSET_0__SHIFT 0 +static inline uint32_t A5XX_GRAS_CL_VPORT_ZOFFSET_0(float val) +{ + return ((fui(val)) << A5XX_GRAS_CL_VPORT_ZOFFSET_0__SHIFT) & A5XX_GRAS_CL_VPORT_ZOFFSET_0__MASK; +} + +#define REG_A5XX_GRAS_CL_VPORT_ZSCALE_0 0x0000e015 +#define A5XX_GRAS_CL_VPORT_ZSCALE_0__MASK 0xffffffff +#define A5XX_GRAS_CL_VPORT_ZSCALE_0__SHIFT 0 +static inline uint32_t A5XX_GRAS_CL_VPORT_ZSCALE_0(float val) +{ + return ((fui(val)) << A5XX_GRAS_CL_VPORT_ZSCALE_0__SHIFT) & A5XX_GRAS_CL_VPORT_ZSCALE_0__MASK; +} + +#define REG_A5XX_GRAS_SU_CNTL 0x0000e090 +#define A5XX_GRAS_SU_CNTL_CULL_FRONT 0x00000001 +#define A5XX_GRAS_SU_CNTL_CULL_BACK 0x00000002 +#define A5XX_GRAS_SU_CNTL_FRONT_CW 0x00000004 +#define A5XX_GRAS_SU_CNTL_LINEHALFWIDTH__MASK 0x000007f8 +#define A5XX_GRAS_SU_CNTL_LINEHALFWIDTH__SHIFT 3 +static inline uint32_t A5XX_GRAS_SU_CNTL_LINEHALFWIDTH(float val) +{ + return ((((int32_t)(val * 4.0))) << A5XX_GRAS_SU_CNTL_LINEHALFWIDTH__SHIFT) & A5XX_GRAS_SU_CNTL_LINEHALFWIDTH__MASK; +} +#define A5XX_GRAS_SU_CNTL_POLY_OFFSET 0x00000800 +#define A5XX_GRAS_SU_CNTL_MSAA_ENABLE 0x00002000 + +#define REG_A5XX_GRAS_SU_POINT_MINMAX 0x0000e091 +#define A5XX_GRAS_SU_POINT_MINMAX_MIN__MASK 0x0000ffff +#define A5XX_GRAS_SU_POINT_MINMAX_MIN__SHIFT 0 +static inline uint32_t A5XX_GRAS_SU_POINT_MINMAX_MIN(float val) +{ + return ((((uint32_t)(val * 16.0))) << A5XX_GRAS_SU_POINT_MINMAX_MIN__SHIFT) & A5XX_GRAS_SU_POINT_MINMAX_MIN__MASK; +} +#define A5XX_GRAS_SU_POINT_MINMAX_MAX__MASK 0xffff0000 +#define A5XX_GRAS_SU_POINT_MINMAX_MAX__SHIFT 16 +static inline uint32_t A5XX_GRAS_SU_POINT_MINMAX_MAX(float val) +{ + return ((((uint32_t)(val * 16.0))) << A5XX_GRAS_SU_POINT_MINMAX_MAX__SHIFT) & A5XX_GRAS_SU_POINT_MINMAX_MAX__MASK; +} + +#define REG_A5XX_GRAS_SU_POINT_SIZE 0x0000e092 +#define A5XX_GRAS_SU_POINT_SIZE__MASK 0xffffffff +#define A5XX_GRAS_SU_POINT_SIZE__SHIFT 0 +static inline uint32_t A5XX_GRAS_SU_POINT_SIZE(float val) +{ + return ((((int32_t)(val * 16.0))) << A5XX_GRAS_SU_POINT_SIZE__SHIFT) & A5XX_GRAS_SU_POINT_SIZE__MASK; +} + +#define REG_A5XX_GRAS_SU_LAYERED 0x0000e093 + +#define REG_A5XX_GRAS_SU_DEPTH_PLANE_CNTL 0x0000e094 +#define A5XX_GRAS_SU_DEPTH_PLANE_CNTL_FRAG_WRITES_Z 0x00000001 +#define A5XX_GRAS_SU_DEPTH_PLANE_CNTL_UNK1 0x00000002 + +#define REG_A5XX_GRAS_SU_POLY_OFFSET_SCALE 0x0000e095 +#define A5XX_GRAS_SU_POLY_OFFSET_SCALE__MASK 0xffffffff +#define A5XX_GRAS_SU_POLY_OFFSET_SCALE__SHIFT 0 +static inline uint32_t A5XX_GRAS_SU_POLY_OFFSET_SCALE(float val) +{ + return ((fui(val)) << A5XX_GRAS_SU_POLY_OFFSET_SCALE__SHIFT) & A5XX_GRAS_SU_POLY_OFFSET_SCALE__MASK; +} + +#define REG_A5XX_GRAS_SU_POLY_OFFSET_OFFSET 0x0000e096 +#define A5XX_GRAS_SU_POLY_OFFSET_OFFSET__MASK 0xffffffff +#define A5XX_GRAS_SU_POLY_OFFSET_OFFSET__SHIFT 0 +static inline uint32_t A5XX_GRAS_SU_POLY_OFFSET_OFFSET(float val) +{ + return ((fui(val)) << A5XX_GRAS_SU_POLY_OFFSET_OFFSET__SHIFT) & A5XX_GRAS_SU_POLY_OFFSET_OFFSET__MASK; +} + +#define REG_A5XX_GRAS_SU_POLY_OFFSET_OFFSET_CLAMP 0x0000e097 +#define A5XX_GRAS_SU_POLY_OFFSET_OFFSET_CLAMP__MASK 0xffffffff +#define A5XX_GRAS_SU_POLY_OFFSET_OFFSET_CLAMP__SHIFT 0 +static inline uint32_t A5XX_GRAS_SU_POLY_OFFSET_OFFSET_CLAMP(float val) +{ + return ((fui(val)) << A5XX_GRAS_SU_POLY_OFFSET_OFFSET_CLAMP__SHIFT) & A5XX_GRAS_SU_POLY_OFFSET_OFFSET_CLAMP__MASK; +} + +#define REG_A5XX_GRAS_SU_DEPTH_BUFFER_INFO 0x0000e098 +#define A5XX_GRAS_SU_DEPTH_BUFFER_INFO_DEPTH_FORMAT__MASK 0x00000007 +#define A5XX_GRAS_SU_DEPTH_BUFFER_INFO_DEPTH_FORMAT__SHIFT 0 +static inline uint32_t A5XX_GRAS_SU_DEPTH_BUFFER_INFO_DEPTH_FORMAT(enum a5xx_depth_format val) +{ + return ((val) << A5XX_GRAS_SU_DEPTH_BUFFER_INFO_DEPTH_FORMAT__SHIFT) & A5XX_GRAS_SU_DEPTH_BUFFER_INFO_DEPTH_FORMAT__MASK; +} + +#define REG_A5XX_GRAS_SU_CONSERVATIVE_RAS_CNTL 0x0000e099 + +#define REG_A5XX_GRAS_SC_CNTL 0x0000e0a0 +#define A5XX_GRAS_SC_CNTL_BINNING_PASS 0x00000001 +#define A5XX_GRAS_SC_CNTL_SAMPLES_PASSED 0x00008000 + +#define REG_A5XX_GRAS_SC_BIN_CNTL 0x0000e0a1 + +#define REG_A5XX_GRAS_SC_RAS_MSAA_CNTL 0x0000e0a2 +#define A5XX_GRAS_SC_RAS_MSAA_CNTL_SAMPLES__MASK 0x00000003 +#define A5XX_GRAS_SC_RAS_MSAA_CNTL_SAMPLES__SHIFT 0 +static inline uint32_t A5XX_GRAS_SC_RAS_MSAA_CNTL_SAMPLES(enum a3xx_msaa_samples val) +{ + return ((val) << A5XX_GRAS_SC_RAS_MSAA_CNTL_SAMPLES__SHIFT) & A5XX_GRAS_SC_RAS_MSAA_CNTL_SAMPLES__MASK; +} + +#define REG_A5XX_GRAS_SC_DEST_MSAA_CNTL 0x0000e0a3 +#define A5XX_GRAS_SC_DEST_MSAA_CNTL_SAMPLES__MASK 0x00000003 +#define A5XX_GRAS_SC_DEST_MSAA_CNTL_SAMPLES__SHIFT 0 +static inline uint32_t A5XX_GRAS_SC_DEST_MSAA_CNTL_SAMPLES(enum a3xx_msaa_samples val) +{ + return ((val) << A5XX_GRAS_SC_DEST_MSAA_CNTL_SAMPLES__SHIFT) & A5XX_GRAS_SC_DEST_MSAA_CNTL_SAMPLES__MASK; +} +#define A5XX_GRAS_SC_DEST_MSAA_CNTL_MSAA_DISABLE 0x00000004 + +#define REG_A5XX_GRAS_SC_SCREEN_SCISSOR_CNTL 0x0000e0a4 + +#define REG_A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0 0x0000e0aa +#define A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_WINDOW_OFFSET_DISABLE 0x80000000 +#define A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_X__MASK 0x00007fff +#define A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_X__SHIFT 0 +static inline uint32_t A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_X(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_X__SHIFT) & A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_X__MASK; +} +#define A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_Y__MASK 0x7fff0000 +#define A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_Y__SHIFT 16 +static inline uint32_t A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_Y(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_Y__SHIFT) & A5XX_GRAS_SC_SCREEN_SCISSOR_TL_0_Y__MASK; +} + +#define REG_A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0 0x0000e0ab +#define A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_WINDOW_OFFSET_DISABLE 0x80000000 +#define A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_X__MASK 0x00007fff +#define A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_X__SHIFT 0 +static inline uint32_t A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_X(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_X__SHIFT) & A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_X__MASK; +} +#define A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_Y__MASK 0x7fff0000 +#define A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_Y__SHIFT 16 +static inline uint32_t A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_Y(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_Y__SHIFT) & A5XX_GRAS_SC_SCREEN_SCISSOR_BR_0_Y__MASK; +} + +#define REG_A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0 0x0000e0ca +#define A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_WINDOW_OFFSET_DISABLE 0x80000000 +#define A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_X__MASK 0x00007fff +#define A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_X__SHIFT 0 +static inline uint32_t A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_X(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_X__SHIFT) & A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_X__MASK; +} +#define A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_Y__MASK 0x7fff0000 +#define A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_Y__SHIFT 16 +static inline uint32_t A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_Y(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_Y__SHIFT) & A5XX_GRAS_SC_VIEWPORT_SCISSOR_TL_0_Y__MASK; +} + +#define REG_A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0 0x0000e0cb +#define A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_WINDOW_OFFSET_DISABLE 0x80000000 +#define A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_X__MASK 0x00007fff +#define A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_X__SHIFT 0 +static inline uint32_t A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_X(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_X__SHIFT) & A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_X__MASK; +} +#define A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_Y__MASK 0x7fff0000 +#define A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_Y__SHIFT 16 +static inline uint32_t A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_Y(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_Y__SHIFT) & A5XX_GRAS_SC_VIEWPORT_SCISSOR_BR_0_Y__MASK; +} + +#define REG_A5XX_GRAS_SC_WINDOW_SCISSOR_TL 0x0000e0ea +#define A5XX_GRAS_SC_WINDOW_SCISSOR_TL_WINDOW_OFFSET_DISABLE 0x80000000 +#define A5XX_GRAS_SC_WINDOW_SCISSOR_TL_X__MASK 0x00007fff +#define A5XX_GRAS_SC_WINDOW_SCISSOR_TL_X__SHIFT 0 +static inline uint32_t A5XX_GRAS_SC_WINDOW_SCISSOR_TL_X(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_WINDOW_SCISSOR_TL_X__SHIFT) & A5XX_GRAS_SC_WINDOW_SCISSOR_TL_X__MASK; +} +#define A5XX_GRAS_SC_WINDOW_SCISSOR_TL_Y__MASK 0x7fff0000 +#define A5XX_GRAS_SC_WINDOW_SCISSOR_TL_Y__SHIFT 16 +static inline uint32_t A5XX_GRAS_SC_WINDOW_SCISSOR_TL_Y(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_WINDOW_SCISSOR_TL_Y__SHIFT) & A5XX_GRAS_SC_WINDOW_SCISSOR_TL_Y__MASK; +} + +#define REG_A5XX_GRAS_SC_WINDOW_SCISSOR_BR 0x0000e0eb +#define A5XX_GRAS_SC_WINDOW_SCISSOR_BR_WINDOW_OFFSET_DISABLE 0x80000000 +#define A5XX_GRAS_SC_WINDOW_SCISSOR_BR_X__MASK 0x00007fff +#define A5XX_GRAS_SC_WINDOW_SCISSOR_BR_X__SHIFT 0 +static inline uint32_t A5XX_GRAS_SC_WINDOW_SCISSOR_BR_X(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_WINDOW_SCISSOR_BR_X__SHIFT) & A5XX_GRAS_SC_WINDOW_SCISSOR_BR_X__MASK; +} +#define A5XX_GRAS_SC_WINDOW_SCISSOR_BR_Y__MASK 0x7fff0000 +#define A5XX_GRAS_SC_WINDOW_SCISSOR_BR_Y__SHIFT 16 +static inline uint32_t A5XX_GRAS_SC_WINDOW_SCISSOR_BR_Y(uint32_t val) +{ + return ((val) << A5XX_GRAS_SC_WINDOW_SCISSOR_BR_Y__SHIFT) & A5XX_GRAS_SC_WINDOW_SCISSOR_BR_Y__MASK; +} + +#define REG_A5XX_GRAS_LRZ_CNTL 0x0000e100 +#define A5XX_GRAS_LRZ_CNTL_ENABLE 0x00000001 +#define A5XX_GRAS_LRZ_CNTL_LRZ_WRITE 0x00000002 +#define A5XX_GRAS_LRZ_CNTL_GREATER 0x00000004 + +#define REG_A5XX_GRAS_LRZ_BUFFER_BASE_LO 0x0000e101 + +#define REG_A5XX_GRAS_LRZ_BUFFER_BASE_HI 0x0000e102 + +#define REG_A5XX_GRAS_LRZ_BUFFER_PITCH 0x0000e103 +#define A5XX_GRAS_LRZ_BUFFER_PITCH__MASK 0xffffffff +#define A5XX_GRAS_LRZ_BUFFER_PITCH__SHIFT 0 +static inline uint32_t A5XX_GRAS_LRZ_BUFFER_PITCH(uint32_t val) +{ + return ((val >> 5) << A5XX_GRAS_LRZ_BUFFER_PITCH__SHIFT) & A5XX_GRAS_LRZ_BUFFER_PITCH__MASK; +} + +#define REG_A5XX_GRAS_LRZ_FAST_CLEAR_BUFFER_BASE_LO 0x0000e104 + +#define REG_A5XX_GRAS_LRZ_FAST_CLEAR_BUFFER_BASE_HI 0x0000e105 + +#define REG_A5XX_RB_CNTL 0x0000e140 +#define A5XX_RB_CNTL_WIDTH__MASK 0x000000ff +#define A5XX_RB_CNTL_WIDTH__SHIFT 0 +static inline uint32_t A5XX_RB_CNTL_WIDTH(uint32_t val) +{ + return ((val >> 5) << A5XX_RB_CNTL_WIDTH__SHIFT) & A5XX_RB_CNTL_WIDTH__MASK; +} +#define A5XX_RB_CNTL_HEIGHT__MASK 0x0001fe00 +#define A5XX_RB_CNTL_HEIGHT__SHIFT 9 +static inline uint32_t A5XX_RB_CNTL_HEIGHT(uint32_t val) +{ + return ((val >> 5) << A5XX_RB_CNTL_HEIGHT__SHIFT) & A5XX_RB_CNTL_HEIGHT__MASK; +} +#define A5XX_RB_CNTL_BYPASS 0x00020000 + +#define REG_A5XX_RB_RENDER_CNTL 0x0000e141 +#define A5XX_RB_RENDER_CNTL_BINNING_PASS 0x00000001 +#define A5XX_RB_RENDER_CNTL_SAMPLES_PASSED 0x00000040 +#define A5XX_RB_RENDER_CNTL_DISABLE_COLOR_PIPE 0x00000080 +#define A5XX_RB_RENDER_CNTL_FLAG_DEPTH 0x00004000 +#define A5XX_RB_RENDER_CNTL_FLAG_DEPTH2 0x00008000 +#define A5XX_RB_RENDER_CNTL_FLAG_MRTS__MASK 0x00ff0000 +#define A5XX_RB_RENDER_CNTL_FLAG_MRTS__SHIFT 16 +static inline uint32_t A5XX_RB_RENDER_CNTL_FLAG_MRTS(uint32_t val) +{ + return ((val) << A5XX_RB_RENDER_CNTL_FLAG_MRTS__SHIFT) & A5XX_RB_RENDER_CNTL_FLAG_MRTS__MASK; +} +#define A5XX_RB_RENDER_CNTL_FLAG_MRTS2__MASK 0xff000000 +#define A5XX_RB_RENDER_CNTL_FLAG_MRTS2__SHIFT 24 +static inline uint32_t A5XX_RB_RENDER_CNTL_FLAG_MRTS2(uint32_t val) +{ + return ((val) << A5XX_RB_RENDER_CNTL_FLAG_MRTS2__SHIFT) & A5XX_RB_RENDER_CNTL_FLAG_MRTS2__MASK; +} + +#define REG_A5XX_RB_RAS_MSAA_CNTL 0x0000e142 +#define A5XX_RB_RAS_MSAA_CNTL_SAMPLES__MASK 0x00000003 +#define A5XX_RB_RAS_MSAA_CNTL_SAMPLES__SHIFT 0 +static inline uint32_t A5XX_RB_RAS_MSAA_CNTL_SAMPLES(enum a3xx_msaa_samples val) +{ + return ((val) << A5XX_RB_RAS_MSAA_CNTL_SAMPLES__SHIFT) & A5XX_RB_RAS_MSAA_CNTL_SAMPLES__MASK; +} + +#define REG_A5XX_RB_DEST_MSAA_CNTL 0x0000e143 +#define A5XX_RB_DEST_MSAA_CNTL_SAMPLES__MASK 0x00000003 +#define A5XX_RB_DEST_MSAA_CNTL_SAMPLES__SHIFT 0 +static inline uint32_t A5XX_RB_DEST_MSAA_CNTL_SAMPLES(enum a3xx_msaa_samples val) +{ + return ((val) << A5XX_RB_DEST_MSAA_CNTL_SAMPLES__SHIFT) & A5XX_RB_DEST_MSAA_CNTL_SAMPLES__MASK; +} +#define A5XX_RB_DEST_MSAA_CNTL_MSAA_DISABLE 0x00000004 + +#define REG_A5XX_RB_RENDER_CONTROL0 0x0000e144 +#define A5XX_RB_RENDER_CONTROL0_VARYING 0x00000001 +#define A5XX_RB_RENDER_CONTROL0_UNK3 0x00000008 +#define A5XX_RB_RENDER_CONTROL0_XCOORD 0x00000040 +#define A5XX_RB_RENDER_CONTROL0_YCOORD 0x00000080 +#define A5XX_RB_RENDER_CONTROL0_ZCOORD 0x00000100 +#define A5XX_RB_RENDER_CONTROL0_WCOORD 0x00000200 + +#define REG_A5XX_RB_RENDER_CONTROL1 0x0000e145 +#define A5XX_RB_RENDER_CONTROL1_SAMPLEMASK 0x00000001 +#define A5XX_RB_RENDER_CONTROL1_FACENESS 0x00000002 +#define A5XX_RB_RENDER_CONTROL1_SAMPLEID 0x00000004 + +#define REG_A5XX_RB_FS_OUTPUT_CNTL 0x0000e146 +#define A5XX_RB_FS_OUTPUT_CNTL_MRT__MASK 0x0000000f +#define A5XX_RB_FS_OUTPUT_CNTL_MRT__SHIFT 0 +static inline uint32_t A5XX_RB_FS_OUTPUT_CNTL_MRT(uint32_t val) +{ + return ((val) << A5XX_RB_FS_OUTPUT_CNTL_MRT__SHIFT) & A5XX_RB_FS_OUTPUT_CNTL_MRT__MASK; +} +#define A5XX_RB_FS_OUTPUT_CNTL_FRAG_WRITES_Z 0x00000020 + +#define REG_A5XX_RB_RENDER_COMPONENTS 0x0000e147 +#define A5XX_RB_RENDER_COMPONENTS_RT0__MASK 0x0000000f +#define A5XX_RB_RENDER_COMPONENTS_RT0__SHIFT 0 +static inline uint32_t A5XX_RB_RENDER_COMPONENTS_RT0(uint32_t val) +{ + return ((val) << A5XX_RB_RENDER_COMPONENTS_RT0__SHIFT) & A5XX_RB_RENDER_COMPONENTS_RT0__MASK; +} +#define A5XX_RB_RENDER_COMPONENTS_RT1__MASK 0x000000f0 +#define A5XX_RB_RENDER_COMPONENTS_RT1__SHIFT 4 +static inline uint32_t A5XX_RB_RENDER_COMPONENTS_RT1(uint32_t val) +{ + return ((val) << A5XX_RB_RENDER_COMPONENTS_RT1__SHIFT) & A5XX_RB_RENDER_COMPONENTS_RT1__MASK; +} +#define A5XX_RB_RENDER_COMPONENTS_RT2__MASK 0x00000f00 +#define A5XX_RB_RENDER_COMPONENTS_RT2__SHIFT 8 +static inline uint32_t A5XX_RB_RENDER_COMPONENTS_RT2(uint32_t val) +{ + return ((val) << A5XX_RB_RENDER_COMPONENTS_RT2__SHIFT) & A5XX_RB_RENDER_COMPONENTS_RT2__MASK; +} +#define A5XX_RB_RENDER_COMPONENTS_RT3__MASK 0x0000f000 +#define A5XX_RB_RENDER_COMPONENTS_RT3__SHIFT 12 +static inline uint32_t A5XX_RB_RENDER_COMPONENTS_RT3(uint32_t val) +{ + return ((val) << A5XX_RB_RENDER_COMPONENTS_RT3__SHIFT) & A5XX_RB_RENDER_COMPONENTS_RT3__MASK; +} +#define A5XX_RB_RENDER_COMPONENTS_RT4__MASK 0x000f0000 +#define A5XX_RB_RENDER_COMPONENTS_RT4__SHIFT 16 +static inline uint32_t A5XX_RB_RENDER_COMPONENTS_RT4(uint32_t val) +{ + return ((val) << A5XX_RB_RENDER_COMPONENTS_RT4__SHIFT) & A5XX_RB_RENDER_COMPONENTS_RT4__MASK; +} +#define A5XX_RB_RENDER_COMPONENTS_RT5__MASK 0x00f00000 +#define A5XX_RB_RENDER_COMPONENTS_RT5__SHIFT 20 +static inline uint32_t A5XX_RB_RENDER_COMPONENTS_RT5(uint32_t val) +{ + return ((val) << A5XX_RB_RENDER_COMPONENTS_RT5__SHIFT) & A5XX_RB_RENDER_COMPONENTS_RT5__MASK; +} +#define A5XX_RB_RENDER_COMPONENTS_RT6__MASK 0x0f000000 +#define A5XX_RB_RENDER_COMPONENTS_RT6__SHIFT 24 +static inline uint32_t A5XX_RB_RENDER_COMPONENTS_RT6(uint32_t val) +{ + return ((val) << A5XX_RB_RENDER_COMPONENTS_RT6__SHIFT) & A5XX_RB_RENDER_COMPONENTS_RT6__MASK; +} +#define A5XX_RB_RENDER_COMPONENTS_RT7__MASK 0xf0000000 +#define A5XX_RB_RENDER_COMPONENTS_RT7__SHIFT 28 +static inline uint32_t A5XX_RB_RENDER_COMPONENTS_RT7(uint32_t val) +{ + return ((val) << A5XX_RB_RENDER_COMPONENTS_RT7__SHIFT) & A5XX_RB_RENDER_COMPONENTS_RT7__MASK; +} + +static inline uint32_t REG_A5XX_RB_MRT(uint32_t i0) { return 0x0000e150 + 0x7*i0; } + +static inline uint32_t REG_A5XX_RB_MRT_CONTROL(uint32_t i0) { return 0x0000e150 + 0x7*i0; } +#define A5XX_RB_MRT_CONTROL_BLEND 0x00000001 +#define A5XX_RB_MRT_CONTROL_BLEND2 0x00000002 +#define A5XX_RB_MRT_CONTROL_ROP_ENABLE 0x00000004 +#define A5XX_RB_MRT_CONTROL_ROP_CODE__MASK 0x00000078 +#define A5XX_RB_MRT_CONTROL_ROP_CODE__SHIFT 3 +static inline uint32_t A5XX_RB_MRT_CONTROL_ROP_CODE(enum a3xx_rop_code val) +{ + return ((val) << A5XX_RB_MRT_CONTROL_ROP_CODE__SHIFT) & A5XX_RB_MRT_CONTROL_ROP_CODE__MASK; +} +#define A5XX_RB_MRT_CONTROL_COMPONENT_ENABLE__MASK 0x00000780 +#define A5XX_RB_MRT_CONTROL_COMPONENT_ENABLE__SHIFT 7 +static inline uint32_t A5XX_RB_MRT_CONTROL_COMPONENT_ENABLE(uint32_t val) +{ + return ((val) << A5XX_RB_MRT_CONTROL_COMPONENT_ENABLE__SHIFT) & A5XX_RB_MRT_CONTROL_COMPONENT_ENABLE__MASK; +} + +static inline uint32_t REG_A5XX_RB_MRT_BLEND_CONTROL(uint32_t i0) { return 0x0000e151 + 0x7*i0; } +#define A5XX_RB_MRT_BLEND_CONTROL_RGB_SRC_FACTOR__MASK 0x0000001f +#define A5XX_RB_MRT_BLEND_CONTROL_RGB_SRC_FACTOR__SHIFT 0 +static inline uint32_t A5XX_RB_MRT_BLEND_CONTROL_RGB_SRC_FACTOR(enum adreno_rb_blend_factor val) +{ + return ((val) << A5XX_RB_MRT_BLEND_CONTROL_RGB_SRC_FACTOR__SHIFT) & A5XX_RB_MRT_BLEND_CONTROL_RGB_SRC_FACTOR__MASK; +} +#define A5XX_RB_MRT_BLEND_CONTROL_RGB_BLEND_OPCODE__MASK 0x000000e0 +#define A5XX_RB_MRT_BLEND_CONTROL_RGB_BLEND_OPCODE__SHIFT 5 +static inline uint32_t A5XX_RB_MRT_BLEND_CONTROL_RGB_BLEND_OPCODE(enum a3xx_rb_blend_opcode val) +{ + return ((val) << A5XX_RB_MRT_BLEND_CONTROL_RGB_BLEND_OPCODE__SHIFT) & A5XX_RB_MRT_BLEND_CONTROL_RGB_BLEND_OPCODE__MASK; +} +#define A5XX_RB_MRT_BLEND_CONTROL_RGB_DEST_FACTOR__MASK 0x00001f00 +#define A5XX_RB_MRT_BLEND_CONTROL_RGB_DEST_FACTOR__SHIFT 8 +static inline uint32_t A5XX_RB_MRT_BLEND_CONTROL_RGB_DEST_FACTOR(enum adreno_rb_blend_factor val) +{ + return ((val) << A5XX_RB_MRT_BLEND_CONTROL_RGB_DEST_FACTOR__SHIFT) & A5XX_RB_MRT_BLEND_CONTROL_RGB_DEST_FACTOR__MASK; +} +#define A5XX_RB_MRT_BLEND_CONTROL_ALPHA_SRC_FACTOR__MASK 0x001f0000 +#define A5XX_RB_MRT_BLEND_CONTROL_ALPHA_SRC_FACTOR__SHIFT 16 +static inline uint32_t A5XX_RB_MRT_BLEND_CONTROL_ALPHA_SRC_FACTOR(enum adreno_rb_blend_factor val) +{ + return ((val) << A5XX_RB_MRT_BLEND_CONTROL_ALPHA_SRC_FACTOR__SHIFT) & A5XX_RB_MRT_BLEND_CONTROL_ALPHA_SRC_FACTOR__MASK; +} +#define A5XX_RB_MRT_BLEND_CONTROL_ALPHA_BLEND_OPCODE__MASK 0x00e00000 +#define A5XX_RB_MRT_BLEND_CONTROL_ALPHA_BLEND_OPCODE__SHIFT 21 +static inline uint32_t A5XX_RB_MRT_BLEND_CONTROL_ALPHA_BLEND_OPCODE(enum a3xx_rb_blend_opcode val) +{ + return ((val) << A5XX_RB_MRT_BLEND_CONTROL_ALPHA_BLEND_OPCODE__SHIFT) & A5XX_RB_MRT_BLEND_CONTROL_ALPHA_BLEND_OPCODE__MASK; +} +#define A5XX_RB_MRT_BLEND_CONTROL_ALPHA_DEST_FACTOR__MASK 0x1f000000 +#define A5XX_RB_MRT_BLEND_CONTROL_ALPHA_DEST_FACTOR__SHIFT 24 +static inline uint32_t A5XX_RB_MRT_BLEND_CONTROL_ALPHA_DEST_FACTOR(enum adreno_rb_blend_factor val) +{ + return ((val) << A5XX_RB_MRT_BLEND_CONTROL_ALPHA_DEST_FACTOR__SHIFT) & A5XX_RB_MRT_BLEND_CONTROL_ALPHA_DEST_FACTOR__MASK; +} + +static inline uint32_t REG_A5XX_RB_MRT_BUF_INFO(uint32_t i0) { return 0x0000e152 + 0x7*i0; } +#define A5XX_RB_MRT_BUF_INFO_COLOR_FORMAT__MASK 0x000000ff +#define A5XX_RB_MRT_BUF_INFO_COLOR_FORMAT__SHIFT 0 +static inline uint32_t A5XX_RB_MRT_BUF_INFO_COLOR_FORMAT(enum a5xx_color_fmt val) +{ + return ((val) << A5XX_RB_MRT_BUF_INFO_COLOR_FORMAT__SHIFT) & A5XX_RB_MRT_BUF_INFO_COLOR_FORMAT__MASK; +} +#define A5XX_RB_MRT_BUF_INFO_COLOR_TILE_MODE__MASK 0x00000300 +#define A5XX_RB_MRT_BUF_INFO_COLOR_TILE_MODE__SHIFT 8 +static inline uint32_t A5XX_RB_MRT_BUF_INFO_COLOR_TILE_MODE(enum a5xx_tile_mode val) +{ + return ((val) << A5XX_RB_MRT_BUF_INFO_COLOR_TILE_MODE__SHIFT) & A5XX_RB_MRT_BUF_INFO_COLOR_TILE_MODE__MASK; +} +#define A5XX_RB_MRT_BUF_INFO_DITHER_MODE__MASK 0x00001800 +#define A5XX_RB_MRT_BUF_INFO_DITHER_MODE__SHIFT 11 +static inline uint32_t A5XX_RB_MRT_BUF_INFO_DITHER_MODE(enum adreno_rb_dither_mode val) +{ + return ((val) << A5XX_RB_MRT_BUF_INFO_DITHER_MODE__SHIFT) & A5XX_RB_MRT_BUF_INFO_DITHER_MODE__MASK; +} +#define A5XX_RB_MRT_BUF_INFO_COLOR_SWAP__MASK 0x00006000 +#define A5XX_RB_MRT_BUF_INFO_COLOR_SWAP__SHIFT 13 +static inline uint32_t A5XX_RB_MRT_BUF_INFO_COLOR_SWAP(enum a3xx_color_swap val) +{ + return ((val) << A5XX_RB_MRT_BUF_INFO_COLOR_SWAP__SHIFT) & A5XX_RB_MRT_BUF_INFO_COLOR_SWAP__MASK; +} +#define A5XX_RB_MRT_BUF_INFO_COLOR_SRGB 0x00008000 + +static inline uint32_t REG_A5XX_RB_MRT_PITCH(uint32_t i0) { return 0x0000e153 + 0x7*i0; } +#define A5XX_RB_MRT_PITCH__MASK 0xffffffff +#define A5XX_RB_MRT_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_MRT_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_MRT_PITCH__SHIFT) & A5XX_RB_MRT_PITCH__MASK; +} + +static inline uint32_t REG_A5XX_RB_MRT_ARRAY_PITCH(uint32_t i0) { return 0x0000e154 + 0x7*i0; } +#define A5XX_RB_MRT_ARRAY_PITCH__MASK 0xffffffff +#define A5XX_RB_MRT_ARRAY_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_MRT_ARRAY_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_MRT_ARRAY_PITCH__SHIFT) & A5XX_RB_MRT_ARRAY_PITCH__MASK; +} + +static inline uint32_t REG_A5XX_RB_MRT_BASE_LO(uint32_t i0) { return 0x0000e155 + 0x7*i0; } + +static inline uint32_t REG_A5XX_RB_MRT_BASE_HI(uint32_t i0) { return 0x0000e156 + 0x7*i0; } + +#define REG_A5XX_RB_BLEND_RED 0x0000e1a0 +#define A5XX_RB_BLEND_RED_UINT__MASK 0x000000ff +#define A5XX_RB_BLEND_RED_UINT__SHIFT 0 +static inline uint32_t A5XX_RB_BLEND_RED_UINT(uint32_t val) +{ + return ((val) << A5XX_RB_BLEND_RED_UINT__SHIFT) & A5XX_RB_BLEND_RED_UINT__MASK; +} +#define A5XX_RB_BLEND_RED_SINT__MASK 0x0000ff00 +#define A5XX_RB_BLEND_RED_SINT__SHIFT 8 +static inline uint32_t A5XX_RB_BLEND_RED_SINT(uint32_t val) +{ + return ((val) << A5XX_RB_BLEND_RED_SINT__SHIFT) & A5XX_RB_BLEND_RED_SINT__MASK; +} +#define A5XX_RB_BLEND_RED_FLOAT__MASK 0xffff0000 +#define A5XX_RB_BLEND_RED_FLOAT__SHIFT 16 +static inline uint32_t A5XX_RB_BLEND_RED_FLOAT(float val) +{ + return ((util_float_to_half(val)) << A5XX_RB_BLEND_RED_FLOAT__SHIFT) & A5XX_RB_BLEND_RED_FLOAT__MASK; +} + +#define REG_A5XX_RB_BLEND_RED_F32 0x0000e1a1 +#define A5XX_RB_BLEND_RED_F32__MASK 0xffffffff +#define A5XX_RB_BLEND_RED_F32__SHIFT 0 +static inline uint32_t A5XX_RB_BLEND_RED_F32(float val) +{ + return ((fui(val)) << A5XX_RB_BLEND_RED_F32__SHIFT) & A5XX_RB_BLEND_RED_F32__MASK; +} + +#define REG_A5XX_RB_BLEND_GREEN 0x0000e1a2 +#define A5XX_RB_BLEND_GREEN_UINT__MASK 0x000000ff +#define A5XX_RB_BLEND_GREEN_UINT__SHIFT 0 +static inline uint32_t A5XX_RB_BLEND_GREEN_UINT(uint32_t val) +{ + return ((val) << A5XX_RB_BLEND_GREEN_UINT__SHIFT) & A5XX_RB_BLEND_GREEN_UINT__MASK; +} +#define A5XX_RB_BLEND_GREEN_SINT__MASK 0x0000ff00 +#define A5XX_RB_BLEND_GREEN_SINT__SHIFT 8 +static inline uint32_t A5XX_RB_BLEND_GREEN_SINT(uint32_t val) +{ + return ((val) << A5XX_RB_BLEND_GREEN_SINT__SHIFT) & A5XX_RB_BLEND_GREEN_SINT__MASK; +} +#define A5XX_RB_BLEND_GREEN_FLOAT__MASK 0xffff0000 +#define A5XX_RB_BLEND_GREEN_FLOAT__SHIFT 16 +static inline uint32_t A5XX_RB_BLEND_GREEN_FLOAT(float val) +{ + return ((util_float_to_half(val)) << A5XX_RB_BLEND_GREEN_FLOAT__SHIFT) & A5XX_RB_BLEND_GREEN_FLOAT__MASK; +} + +#define REG_A5XX_RB_BLEND_GREEN_F32 0x0000e1a3 +#define A5XX_RB_BLEND_GREEN_F32__MASK 0xffffffff +#define A5XX_RB_BLEND_GREEN_F32__SHIFT 0 +static inline uint32_t A5XX_RB_BLEND_GREEN_F32(float val) +{ + return ((fui(val)) << A5XX_RB_BLEND_GREEN_F32__SHIFT) & A5XX_RB_BLEND_GREEN_F32__MASK; +} + +#define REG_A5XX_RB_BLEND_BLUE 0x0000e1a4 +#define A5XX_RB_BLEND_BLUE_UINT__MASK 0x000000ff +#define A5XX_RB_BLEND_BLUE_UINT__SHIFT 0 +static inline uint32_t A5XX_RB_BLEND_BLUE_UINT(uint32_t val) +{ + return ((val) << A5XX_RB_BLEND_BLUE_UINT__SHIFT) & A5XX_RB_BLEND_BLUE_UINT__MASK; +} +#define A5XX_RB_BLEND_BLUE_SINT__MASK 0x0000ff00 +#define A5XX_RB_BLEND_BLUE_SINT__SHIFT 8 +static inline uint32_t A5XX_RB_BLEND_BLUE_SINT(uint32_t val) +{ + return ((val) << A5XX_RB_BLEND_BLUE_SINT__SHIFT) & A5XX_RB_BLEND_BLUE_SINT__MASK; +} +#define A5XX_RB_BLEND_BLUE_FLOAT__MASK 0xffff0000 +#define A5XX_RB_BLEND_BLUE_FLOAT__SHIFT 16 +static inline uint32_t A5XX_RB_BLEND_BLUE_FLOAT(float val) +{ + return ((util_float_to_half(val)) << A5XX_RB_BLEND_BLUE_FLOAT__SHIFT) & A5XX_RB_BLEND_BLUE_FLOAT__MASK; +} + +#define REG_A5XX_RB_BLEND_BLUE_F32 0x0000e1a5 +#define A5XX_RB_BLEND_BLUE_F32__MASK 0xffffffff +#define A5XX_RB_BLEND_BLUE_F32__SHIFT 0 +static inline uint32_t A5XX_RB_BLEND_BLUE_F32(float val) +{ + return ((fui(val)) << A5XX_RB_BLEND_BLUE_F32__SHIFT) & A5XX_RB_BLEND_BLUE_F32__MASK; +} + +#define REG_A5XX_RB_BLEND_ALPHA 0x0000e1a6 +#define A5XX_RB_BLEND_ALPHA_UINT__MASK 0x000000ff +#define A5XX_RB_BLEND_ALPHA_UINT__SHIFT 0 +static inline uint32_t A5XX_RB_BLEND_ALPHA_UINT(uint32_t val) +{ + return ((val) << A5XX_RB_BLEND_ALPHA_UINT__SHIFT) & A5XX_RB_BLEND_ALPHA_UINT__MASK; +} +#define A5XX_RB_BLEND_ALPHA_SINT__MASK 0x0000ff00 +#define A5XX_RB_BLEND_ALPHA_SINT__SHIFT 8 +static inline uint32_t A5XX_RB_BLEND_ALPHA_SINT(uint32_t val) +{ + return ((val) << A5XX_RB_BLEND_ALPHA_SINT__SHIFT) & A5XX_RB_BLEND_ALPHA_SINT__MASK; +} +#define A5XX_RB_BLEND_ALPHA_FLOAT__MASK 0xffff0000 +#define A5XX_RB_BLEND_ALPHA_FLOAT__SHIFT 16 +static inline uint32_t A5XX_RB_BLEND_ALPHA_FLOAT(float val) +{ + return ((util_float_to_half(val)) << A5XX_RB_BLEND_ALPHA_FLOAT__SHIFT) & A5XX_RB_BLEND_ALPHA_FLOAT__MASK; +} + +#define REG_A5XX_RB_BLEND_ALPHA_F32 0x0000e1a7 +#define A5XX_RB_BLEND_ALPHA_F32__MASK 0xffffffff +#define A5XX_RB_BLEND_ALPHA_F32__SHIFT 0 +static inline uint32_t A5XX_RB_BLEND_ALPHA_F32(float val) +{ + return ((fui(val)) << A5XX_RB_BLEND_ALPHA_F32__SHIFT) & A5XX_RB_BLEND_ALPHA_F32__MASK; +} + +#define REG_A5XX_RB_ALPHA_CONTROL 0x0000e1a8 +#define A5XX_RB_ALPHA_CONTROL_ALPHA_REF__MASK 0x000000ff +#define A5XX_RB_ALPHA_CONTROL_ALPHA_REF__SHIFT 0 +static inline uint32_t A5XX_RB_ALPHA_CONTROL_ALPHA_REF(uint32_t val) +{ + return ((val) << A5XX_RB_ALPHA_CONTROL_ALPHA_REF__SHIFT) & A5XX_RB_ALPHA_CONTROL_ALPHA_REF__MASK; +} +#define A5XX_RB_ALPHA_CONTROL_ALPHA_TEST 0x00000100 +#define A5XX_RB_ALPHA_CONTROL_ALPHA_TEST_FUNC__MASK 0x00000e00 +#define A5XX_RB_ALPHA_CONTROL_ALPHA_TEST_FUNC__SHIFT 9 +static inline uint32_t A5XX_RB_ALPHA_CONTROL_ALPHA_TEST_FUNC(enum adreno_compare_func val) +{ + return ((val) << A5XX_RB_ALPHA_CONTROL_ALPHA_TEST_FUNC__SHIFT) & A5XX_RB_ALPHA_CONTROL_ALPHA_TEST_FUNC__MASK; +} + +#define REG_A5XX_RB_BLEND_CNTL 0x0000e1a9 +#define A5XX_RB_BLEND_CNTL_ENABLE_BLEND__MASK 0x000000ff +#define A5XX_RB_BLEND_CNTL_ENABLE_BLEND__SHIFT 0 +static inline uint32_t A5XX_RB_BLEND_CNTL_ENABLE_BLEND(uint32_t val) +{ + return ((val) << A5XX_RB_BLEND_CNTL_ENABLE_BLEND__SHIFT) & A5XX_RB_BLEND_CNTL_ENABLE_BLEND__MASK; +} +#define A5XX_RB_BLEND_CNTL_INDEPENDENT_BLEND 0x00000100 +#define A5XX_RB_BLEND_CNTL_ALPHA_TO_COVERAGE 0x00000400 +#define A5XX_RB_BLEND_CNTL_SAMPLE_MASK__MASK 0xffff0000 +#define A5XX_RB_BLEND_CNTL_SAMPLE_MASK__SHIFT 16 +static inline uint32_t A5XX_RB_BLEND_CNTL_SAMPLE_MASK(uint32_t val) +{ + return ((val) << A5XX_RB_BLEND_CNTL_SAMPLE_MASK__SHIFT) & A5XX_RB_BLEND_CNTL_SAMPLE_MASK__MASK; +} + +#define REG_A5XX_RB_DEPTH_PLANE_CNTL 0x0000e1b0 +#define A5XX_RB_DEPTH_PLANE_CNTL_FRAG_WRITES_Z 0x00000001 +#define A5XX_RB_DEPTH_PLANE_CNTL_UNK1 0x00000002 + +#define REG_A5XX_RB_DEPTH_CNTL 0x0000e1b1 +#define A5XX_RB_DEPTH_CNTL_Z_ENABLE 0x00000001 +#define A5XX_RB_DEPTH_CNTL_Z_WRITE_ENABLE 0x00000002 +#define A5XX_RB_DEPTH_CNTL_ZFUNC__MASK 0x0000001c +#define A5XX_RB_DEPTH_CNTL_ZFUNC__SHIFT 2 +static inline uint32_t A5XX_RB_DEPTH_CNTL_ZFUNC(enum adreno_compare_func val) +{ + return ((val) << A5XX_RB_DEPTH_CNTL_ZFUNC__SHIFT) & A5XX_RB_DEPTH_CNTL_ZFUNC__MASK; +} +#define A5XX_RB_DEPTH_CNTL_Z_TEST_ENABLE 0x00000040 + +#define REG_A5XX_RB_DEPTH_BUFFER_INFO 0x0000e1b2 +#define A5XX_RB_DEPTH_BUFFER_INFO_DEPTH_FORMAT__MASK 0x00000007 +#define A5XX_RB_DEPTH_BUFFER_INFO_DEPTH_FORMAT__SHIFT 0 +static inline uint32_t A5XX_RB_DEPTH_BUFFER_INFO_DEPTH_FORMAT(enum a5xx_depth_format val) +{ + return ((val) << A5XX_RB_DEPTH_BUFFER_INFO_DEPTH_FORMAT__SHIFT) & A5XX_RB_DEPTH_BUFFER_INFO_DEPTH_FORMAT__MASK; +} + +#define REG_A5XX_RB_DEPTH_BUFFER_BASE_LO 0x0000e1b3 + +#define REG_A5XX_RB_DEPTH_BUFFER_BASE_HI 0x0000e1b4 + +#define REG_A5XX_RB_DEPTH_BUFFER_PITCH 0x0000e1b5 +#define A5XX_RB_DEPTH_BUFFER_PITCH__MASK 0xffffffff +#define A5XX_RB_DEPTH_BUFFER_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_DEPTH_BUFFER_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_DEPTH_BUFFER_PITCH__SHIFT) & A5XX_RB_DEPTH_BUFFER_PITCH__MASK; +} + +#define REG_A5XX_RB_DEPTH_BUFFER_ARRAY_PITCH 0x0000e1b6 +#define A5XX_RB_DEPTH_BUFFER_ARRAY_PITCH__MASK 0xffffffff +#define A5XX_RB_DEPTH_BUFFER_ARRAY_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_DEPTH_BUFFER_ARRAY_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_DEPTH_BUFFER_ARRAY_PITCH__SHIFT) & A5XX_RB_DEPTH_BUFFER_ARRAY_PITCH__MASK; +} + +#define REG_A5XX_RB_STENCIL_CONTROL 0x0000e1c0 +#define A5XX_RB_STENCIL_CONTROL_STENCIL_ENABLE 0x00000001 +#define A5XX_RB_STENCIL_CONTROL_STENCIL_ENABLE_BF 0x00000002 +#define A5XX_RB_STENCIL_CONTROL_STENCIL_READ 0x00000004 +#define A5XX_RB_STENCIL_CONTROL_FUNC__MASK 0x00000700 +#define A5XX_RB_STENCIL_CONTROL_FUNC__SHIFT 8 +static inline uint32_t A5XX_RB_STENCIL_CONTROL_FUNC(enum adreno_compare_func val) +{ + return ((val) << A5XX_RB_STENCIL_CONTROL_FUNC__SHIFT) & A5XX_RB_STENCIL_CONTROL_FUNC__MASK; +} +#define A5XX_RB_STENCIL_CONTROL_FAIL__MASK 0x00003800 +#define A5XX_RB_STENCIL_CONTROL_FAIL__SHIFT 11 +static inline uint32_t A5XX_RB_STENCIL_CONTROL_FAIL(enum adreno_stencil_op val) +{ + return ((val) << A5XX_RB_STENCIL_CONTROL_FAIL__SHIFT) & A5XX_RB_STENCIL_CONTROL_FAIL__MASK; +} +#define A5XX_RB_STENCIL_CONTROL_ZPASS__MASK 0x0001c000 +#define A5XX_RB_STENCIL_CONTROL_ZPASS__SHIFT 14 +static inline uint32_t A5XX_RB_STENCIL_CONTROL_ZPASS(enum adreno_stencil_op val) +{ + return ((val) << A5XX_RB_STENCIL_CONTROL_ZPASS__SHIFT) & A5XX_RB_STENCIL_CONTROL_ZPASS__MASK; +} +#define A5XX_RB_STENCIL_CONTROL_ZFAIL__MASK 0x000e0000 +#define A5XX_RB_STENCIL_CONTROL_ZFAIL__SHIFT 17 +static inline uint32_t A5XX_RB_STENCIL_CONTROL_ZFAIL(enum adreno_stencil_op val) +{ + return ((val) << A5XX_RB_STENCIL_CONTROL_ZFAIL__SHIFT) & A5XX_RB_STENCIL_CONTROL_ZFAIL__MASK; +} +#define A5XX_RB_STENCIL_CONTROL_FUNC_BF__MASK 0x00700000 +#define A5XX_RB_STENCIL_CONTROL_FUNC_BF__SHIFT 20 +static inline uint32_t A5XX_RB_STENCIL_CONTROL_FUNC_BF(enum adreno_compare_func val) +{ + return ((val) << A5XX_RB_STENCIL_CONTROL_FUNC_BF__SHIFT) & A5XX_RB_STENCIL_CONTROL_FUNC_BF__MASK; +} +#define A5XX_RB_STENCIL_CONTROL_FAIL_BF__MASK 0x03800000 +#define A5XX_RB_STENCIL_CONTROL_FAIL_BF__SHIFT 23 +static inline uint32_t A5XX_RB_STENCIL_CONTROL_FAIL_BF(enum adreno_stencil_op val) +{ + return ((val) << A5XX_RB_STENCIL_CONTROL_FAIL_BF__SHIFT) & A5XX_RB_STENCIL_CONTROL_FAIL_BF__MASK; +} +#define A5XX_RB_STENCIL_CONTROL_ZPASS_BF__MASK 0x1c000000 +#define A5XX_RB_STENCIL_CONTROL_ZPASS_BF__SHIFT 26 +static inline uint32_t A5XX_RB_STENCIL_CONTROL_ZPASS_BF(enum adreno_stencil_op val) +{ + return ((val) << A5XX_RB_STENCIL_CONTROL_ZPASS_BF__SHIFT) & A5XX_RB_STENCIL_CONTROL_ZPASS_BF__MASK; +} +#define A5XX_RB_STENCIL_CONTROL_ZFAIL_BF__MASK 0xe0000000 +#define A5XX_RB_STENCIL_CONTROL_ZFAIL_BF__SHIFT 29 +static inline uint32_t A5XX_RB_STENCIL_CONTROL_ZFAIL_BF(enum adreno_stencil_op val) +{ + return ((val) << A5XX_RB_STENCIL_CONTROL_ZFAIL_BF__SHIFT) & A5XX_RB_STENCIL_CONTROL_ZFAIL_BF__MASK; +} + +#define REG_A5XX_RB_STENCIL_INFO 0x0000e1c1 +#define A5XX_RB_STENCIL_INFO_SEPARATE_STENCIL 0x00000001 + +#define REG_A5XX_RB_STENCIL_BASE_LO 0x0000e1c2 + +#define REG_A5XX_RB_STENCIL_BASE_HI 0x0000e1c3 + +#define REG_A5XX_RB_STENCIL_PITCH 0x0000e1c4 +#define A5XX_RB_STENCIL_PITCH__MASK 0xffffffff +#define A5XX_RB_STENCIL_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_STENCIL_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_STENCIL_PITCH__SHIFT) & A5XX_RB_STENCIL_PITCH__MASK; +} + +#define REG_A5XX_RB_STENCIL_ARRAY_PITCH 0x0000e1c5 +#define A5XX_RB_STENCIL_ARRAY_PITCH__MASK 0xffffffff +#define A5XX_RB_STENCIL_ARRAY_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_STENCIL_ARRAY_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_STENCIL_ARRAY_PITCH__SHIFT) & A5XX_RB_STENCIL_ARRAY_PITCH__MASK; +} + +#define REG_A5XX_RB_STENCILREFMASK 0x0000e1c6 +#define A5XX_RB_STENCILREFMASK_STENCILREF__MASK 0x000000ff +#define A5XX_RB_STENCILREFMASK_STENCILREF__SHIFT 0 +static inline uint32_t A5XX_RB_STENCILREFMASK_STENCILREF(uint32_t val) +{ + return ((val) << A5XX_RB_STENCILREFMASK_STENCILREF__SHIFT) & A5XX_RB_STENCILREFMASK_STENCILREF__MASK; +} +#define A5XX_RB_STENCILREFMASK_STENCILMASK__MASK 0x0000ff00 +#define A5XX_RB_STENCILREFMASK_STENCILMASK__SHIFT 8 +static inline uint32_t A5XX_RB_STENCILREFMASK_STENCILMASK(uint32_t val) +{ + return ((val) << A5XX_RB_STENCILREFMASK_STENCILMASK__SHIFT) & A5XX_RB_STENCILREFMASK_STENCILMASK__MASK; +} +#define A5XX_RB_STENCILREFMASK_STENCILWRITEMASK__MASK 0x00ff0000 +#define A5XX_RB_STENCILREFMASK_STENCILWRITEMASK__SHIFT 16 +static inline uint32_t A5XX_RB_STENCILREFMASK_STENCILWRITEMASK(uint32_t val) +{ + return ((val) << A5XX_RB_STENCILREFMASK_STENCILWRITEMASK__SHIFT) & A5XX_RB_STENCILREFMASK_STENCILWRITEMASK__MASK; +} + +#define REG_A5XX_RB_STENCILREFMASK_BF 0x0000e1c7 +#define A5XX_RB_STENCILREFMASK_BF_STENCILREF__MASK 0x000000ff +#define A5XX_RB_STENCILREFMASK_BF_STENCILREF__SHIFT 0 +static inline uint32_t A5XX_RB_STENCILREFMASK_BF_STENCILREF(uint32_t val) +{ + return ((val) << A5XX_RB_STENCILREFMASK_BF_STENCILREF__SHIFT) & A5XX_RB_STENCILREFMASK_BF_STENCILREF__MASK; +} +#define A5XX_RB_STENCILREFMASK_BF_STENCILMASK__MASK 0x0000ff00 +#define A5XX_RB_STENCILREFMASK_BF_STENCILMASK__SHIFT 8 +static inline uint32_t A5XX_RB_STENCILREFMASK_BF_STENCILMASK(uint32_t val) +{ + return ((val) << A5XX_RB_STENCILREFMASK_BF_STENCILMASK__SHIFT) & A5XX_RB_STENCILREFMASK_BF_STENCILMASK__MASK; +} +#define A5XX_RB_STENCILREFMASK_BF_STENCILWRITEMASK__MASK 0x00ff0000 +#define A5XX_RB_STENCILREFMASK_BF_STENCILWRITEMASK__SHIFT 16 +static inline uint32_t A5XX_RB_STENCILREFMASK_BF_STENCILWRITEMASK(uint32_t val) +{ + return ((val) << A5XX_RB_STENCILREFMASK_BF_STENCILWRITEMASK__SHIFT) & A5XX_RB_STENCILREFMASK_BF_STENCILWRITEMASK__MASK; +} + +#define REG_A5XX_RB_WINDOW_OFFSET 0x0000e1d0 +#define A5XX_RB_WINDOW_OFFSET_WINDOW_OFFSET_DISABLE 0x80000000 +#define A5XX_RB_WINDOW_OFFSET_X__MASK 0x00007fff +#define A5XX_RB_WINDOW_OFFSET_X__SHIFT 0 +static inline uint32_t A5XX_RB_WINDOW_OFFSET_X(uint32_t val) +{ + return ((val) << A5XX_RB_WINDOW_OFFSET_X__SHIFT) & A5XX_RB_WINDOW_OFFSET_X__MASK; +} +#define A5XX_RB_WINDOW_OFFSET_Y__MASK 0x7fff0000 +#define A5XX_RB_WINDOW_OFFSET_Y__SHIFT 16 +static inline uint32_t A5XX_RB_WINDOW_OFFSET_Y(uint32_t val) +{ + return ((val) << A5XX_RB_WINDOW_OFFSET_Y__SHIFT) & A5XX_RB_WINDOW_OFFSET_Y__MASK; +} + +#define REG_A5XX_RB_SAMPLE_COUNT_CONTROL 0x0000e1d1 +#define A5XX_RB_SAMPLE_COUNT_CONTROL_COPY 0x00000002 + +#define REG_A5XX_RB_BLIT_CNTL 0x0000e210 +#define A5XX_RB_BLIT_CNTL_BUF__MASK 0x0000000f +#define A5XX_RB_BLIT_CNTL_BUF__SHIFT 0 +static inline uint32_t A5XX_RB_BLIT_CNTL_BUF(enum a5xx_blit_buf val) +{ + return ((val) << A5XX_RB_BLIT_CNTL_BUF__SHIFT) & A5XX_RB_BLIT_CNTL_BUF__MASK; +} + +#define REG_A5XX_RB_RESOLVE_CNTL_1 0x0000e211 +#define A5XX_RB_RESOLVE_CNTL_1_WINDOW_OFFSET_DISABLE 0x80000000 +#define A5XX_RB_RESOLVE_CNTL_1_X__MASK 0x00007fff +#define A5XX_RB_RESOLVE_CNTL_1_X__SHIFT 0 +static inline uint32_t A5XX_RB_RESOLVE_CNTL_1_X(uint32_t val) +{ + return ((val) << A5XX_RB_RESOLVE_CNTL_1_X__SHIFT) & A5XX_RB_RESOLVE_CNTL_1_X__MASK; +} +#define A5XX_RB_RESOLVE_CNTL_1_Y__MASK 0x7fff0000 +#define A5XX_RB_RESOLVE_CNTL_1_Y__SHIFT 16 +static inline uint32_t A5XX_RB_RESOLVE_CNTL_1_Y(uint32_t val) +{ + return ((val) << A5XX_RB_RESOLVE_CNTL_1_Y__SHIFT) & A5XX_RB_RESOLVE_CNTL_1_Y__MASK; +} + +#define REG_A5XX_RB_RESOLVE_CNTL_2 0x0000e212 +#define A5XX_RB_RESOLVE_CNTL_2_WINDOW_OFFSET_DISABLE 0x80000000 +#define A5XX_RB_RESOLVE_CNTL_2_X__MASK 0x00007fff +#define A5XX_RB_RESOLVE_CNTL_2_X__SHIFT 0 +static inline uint32_t A5XX_RB_RESOLVE_CNTL_2_X(uint32_t val) +{ + return ((val) << A5XX_RB_RESOLVE_CNTL_2_X__SHIFT) & A5XX_RB_RESOLVE_CNTL_2_X__MASK; +} +#define A5XX_RB_RESOLVE_CNTL_2_Y__MASK 0x7fff0000 +#define A5XX_RB_RESOLVE_CNTL_2_Y__SHIFT 16 +static inline uint32_t A5XX_RB_RESOLVE_CNTL_2_Y(uint32_t val) +{ + return ((val) << A5XX_RB_RESOLVE_CNTL_2_Y__SHIFT) & A5XX_RB_RESOLVE_CNTL_2_Y__MASK; +} + +#define REG_A5XX_RB_RESOLVE_CNTL_3 0x0000e213 +#define A5XX_RB_RESOLVE_CNTL_3_TILED 0x00000001 + +#define REG_A5XX_RB_BLIT_DST_LO 0x0000e214 + +#define REG_A5XX_RB_BLIT_DST_HI 0x0000e215 + +#define REG_A5XX_RB_BLIT_DST_PITCH 0x0000e216 +#define A5XX_RB_BLIT_DST_PITCH__MASK 0xffffffff +#define A5XX_RB_BLIT_DST_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_BLIT_DST_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_BLIT_DST_PITCH__SHIFT) & A5XX_RB_BLIT_DST_PITCH__MASK; +} + +#define REG_A5XX_RB_BLIT_DST_ARRAY_PITCH 0x0000e217 +#define A5XX_RB_BLIT_DST_ARRAY_PITCH__MASK 0xffffffff +#define A5XX_RB_BLIT_DST_ARRAY_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_BLIT_DST_ARRAY_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_BLIT_DST_ARRAY_PITCH__SHIFT) & A5XX_RB_BLIT_DST_ARRAY_PITCH__MASK; +} + +#define REG_A5XX_RB_CLEAR_COLOR_DW0 0x0000e218 + +#define REG_A5XX_RB_CLEAR_COLOR_DW1 0x0000e219 + +#define REG_A5XX_RB_CLEAR_COLOR_DW2 0x0000e21a + +#define REG_A5XX_RB_CLEAR_COLOR_DW3 0x0000e21b + +#define REG_A5XX_RB_CLEAR_CNTL 0x0000e21c +#define A5XX_RB_CLEAR_CNTL_FAST_CLEAR 0x00000002 +#define A5XX_RB_CLEAR_CNTL_MSAA_RESOLVE 0x00000004 +#define A5XX_RB_CLEAR_CNTL_MASK__MASK 0x000000f0 +#define A5XX_RB_CLEAR_CNTL_MASK__SHIFT 4 +static inline uint32_t A5XX_RB_CLEAR_CNTL_MASK(uint32_t val) +{ + return ((val) << A5XX_RB_CLEAR_CNTL_MASK__SHIFT) & A5XX_RB_CLEAR_CNTL_MASK__MASK; +} + +#define REG_A5XX_RB_DEPTH_FLAG_BUFFER_BASE_LO 0x0000e240 + +#define REG_A5XX_RB_DEPTH_FLAG_BUFFER_BASE_HI 0x0000e241 + +#define REG_A5XX_RB_DEPTH_FLAG_BUFFER_PITCH 0x0000e242 + +static inline uint32_t REG_A5XX_RB_MRT_FLAG_BUFFER(uint32_t i0) { return 0x0000e243 + 0x4*i0; } + +static inline uint32_t REG_A5XX_RB_MRT_FLAG_BUFFER_ADDR_LO(uint32_t i0) { return 0x0000e243 + 0x4*i0; } + +static inline uint32_t REG_A5XX_RB_MRT_FLAG_BUFFER_ADDR_HI(uint32_t i0) { return 0x0000e244 + 0x4*i0; } + +static inline uint32_t REG_A5XX_RB_MRT_FLAG_BUFFER_PITCH(uint32_t i0) { return 0x0000e245 + 0x4*i0; } +#define A5XX_RB_MRT_FLAG_BUFFER_PITCH__MASK 0xffffffff +#define A5XX_RB_MRT_FLAG_BUFFER_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_MRT_FLAG_BUFFER_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_MRT_FLAG_BUFFER_PITCH__SHIFT) & A5XX_RB_MRT_FLAG_BUFFER_PITCH__MASK; +} + +static inline uint32_t REG_A5XX_RB_MRT_FLAG_BUFFER_ARRAY_PITCH(uint32_t i0) { return 0x0000e246 + 0x4*i0; } +#define A5XX_RB_MRT_FLAG_BUFFER_ARRAY_PITCH__MASK 0xffffffff +#define A5XX_RB_MRT_FLAG_BUFFER_ARRAY_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_MRT_FLAG_BUFFER_ARRAY_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_MRT_FLAG_BUFFER_ARRAY_PITCH__SHIFT) & A5XX_RB_MRT_FLAG_BUFFER_ARRAY_PITCH__MASK; +} + +#define REG_A5XX_RB_BLIT_FLAG_DST_LO 0x0000e263 + +#define REG_A5XX_RB_BLIT_FLAG_DST_HI 0x0000e264 + +#define REG_A5XX_RB_BLIT_FLAG_DST_PITCH 0x0000e265 +#define A5XX_RB_BLIT_FLAG_DST_PITCH__MASK 0xffffffff +#define A5XX_RB_BLIT_FLAG_DST_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_BLIT_FLAG_DST_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_BLIT_FLAG_DST_PITCH__SHIFT) & A5XX_RB_BLIT_FLAG_DST_PITCH__MASK; +} + +#define REG_A5XX_RB_BLIT_FLAG_DST_ARRAY_PITCH 0x0000e266 +#define A5XX_RB_BLIT_FLAG_DST_ARRAY_PITCH__MASK 0xffffffff +#define A5XX_RB_BLIT_FLAG_DST_ARRAY_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_BLIT_FLAG_DST_ARRAY_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_BLIT_FLAG_DST_ARRAY_PITCH__SHIFT) & A5XX_RB_BLIT_FLAG_DST_ARRAY_PITCH__MASK; +} + +#define REG_A5XX_RB_SAMPLE_COUNT_ADDR_LO 0x0000e267 + +#define REG_A5XX_RB_SAMPLE_COUNT_ADDR_HI 0x0000e268 + +#define REG_A5XX_VPC_CNTL_0 0x0000e280 +#define A5XX_VPC_CNTL_0_STRIDE_IN_VPC__MASK 0x0000007f +#define A5XX_VPC_CNTL_0_STRIDE_IN_VPC__SHIFT 0 +static inline uint32_t A5XX_VPC_CNTL_0_STRIDE_IN_VPC(uint32_t val) +{ + return ((val) << A5XX_VPC_CNTL_0_STRIDE_IN_VPC__SHIFT) & A5XX_VPC_CNTL_0_STRIDE_IN_VPC__MASK; +} +#define A5XX_VPC_CNTL_0_VARYING 0x00000800 + +static inline uint32_t REG_A5XX_VPC_VARYING_INTERP(uint32_t i0) { return 0x0000e282 + 0x1*i0; } + +static inline uint32_t REG_A5XX_VPC_VARYING_INTERP_MODE(uint32_t i0) { return 0x0000e282 + 0x1*i0; } + +static inline uint32_t REG_A5XX_VPC_VARYING_PS_REPL(uint32_t i0) { return 0x0000e28a + 0x1*i0; } + +static inline uint32_t REG_A5XX_VPC_VARYING_PS_REPL_MODE(uint32_t i0) { return 0x0000e28a + 0x1*i0; } + +#define REG_A5XX_UNKNOWN_E292 0x0000e292 + +#define REG_A5XX_UNKNOWN_E293 0x0000e293 + +static inline uint32_t REG_A5XX_VPC_VAR(uint32_t i0) { return 0x0000e294 + 0x1*i0; } + +static inline uint32_t REG_A5XX_VPC_VAR_DISABLE(uint32_t i0) { return 0x0000e294 + 0x1*i0; } + +#define REG_A5XX_VPC_GS_SIV_CNTL 0x0000e298 + +#define REG_A5XX_UNKNOWN_E29A 0x0000e29a + +#define REG_A5XX_VPC_PACK 0x0000e29d +#define A5XX_VPC_PACK_NUMNONPOSVAR__MASK 0x000000ff +#define A5XX_VPC_PACK_NUMNONPOSVAR__SHIFT 0 +static inline uint32_t A5XX_VPC_PACK_NUMNONPOSVAR(uint32_t val) +{ + return ((val) << A5XX_VPC_PACK_NUMNONPOSVAR__SHIFT) & A5XX_VPC_PACK_NUMNONPOSVAR__MASK; +} +#define A5XX_VPC_PACK_PSIZELOC__MASK 0x0000ff00 +#define A5XX_VPC_PACK_PSIZELOC__SHIFT 8 +static inline uint32_t A5XX_VPC_PACK_PSIZELOC(uint32_t val) +{ + return ((val) << A5XX_VPC_PACK_PSIZELOC__SHIFT) & A5XX_VPC_PACK_PSIZELOC__MASK; +} + +#define REG_A5XX_VPC_FS_PRIMITIVEID_CNTL 0x0000e2a0 + +#define REG_A5XX_VPC_SO_BUF_CNTL 0x0000e2a1 +#define A5XX_VPC_SO_BUF_CNTL_BUF0 0x00000001 +#define A5XX_VPC_SO_BUF_CNTL_BUF1 0x00000008 +#define A5XX_VPC_SO_BUF_CNTL_BUF2 0x00000040 +#define A5XX_VPC_SO_BUF_CNTL_BUF3 0x00000200 +#define A5XX_VPC_SO_BUF_CNTL_ENABLE 0x00008000 + +#define REG_A5XX_VPC_SO_OVERRIDE 0x0000e2a2 +#define A5XX_VPC_SO_OVERRIDE_SO_DISABLE 0x00000001 + +#define REG_A5XX_VPC_SO_CNTL 0x0000e2a3 +#define A5XX_VPC_SO_CNTL_ENABLE 0x00010000 + +#define REG_A5XX_VPC_SO_PROG 0x0000e2a4 +#define A5XX_VPC_SO_PROG_A_BUF__MASK 0x00000003 +#define A5XX_VPC_SO_PROG_A_BUF__SHIFT 0 +static inline uint32_t A5XX_VPC_SO_PROG_A_BUF(uint32_t val) +{ + return ((val) << A5XX_VPC_SO_PROG_A_BUF__SHIFT) & A5XX_VPC_SO_PROG_A_BUF__MASK; +} +#define A5XX_VPC_SO_PROG_A_OFF__MASK 0x000007fc +#define A5XX_VPC_SO_PROG_A_OFF__SHIFT 2 +static inline uint32_t A5XX_VPC_SO_PROG_A_OFF(uint32_t val) +{ + return ((val >> 2) << A5XX_VPC_SO_PROG_A_OFF__SHIFT) & A5XX_VPC_SO_PROG_A_OFF__MASK; +} +#define A5XX_VPC_SO_PROG_A_EN 0x00000800 +#define A5XX_VPC_SO_PROG_B_BUF__MASK 0x00003000 +#define A5XX_VPC_SO_PROG_B_BUF__SHIFT 12 +static inline uint32_t A5XX_VPC_SO_PROG_B_BUF(uint32_t val) +{ + return ((val) << A5XX_VPC_SO_PROG_B_BUF__SHIFT) & A5XX_VPC_SO_PROG_B_BUF__MASK; +} +#define A5XX_VPC_SO_PROG_B_OFF__MASK 0x007fc000 +#define A5XX_VPC_SO_PROG_B_OFF__SHIFT 14 +static inline uint32_t A5XX_VPC_SO_PROG_B_OFF(uint32_t val) +{ + return ((val >> 2) << A5XX_VPC_SO_PROG_B_OFF__SHIFT) & A5XX_VPC_SO_PROG_B_OFF__MASK; +} +#define A5XX_VPC_SO_PROG_B_EN 0x00800000 + +static inline uint32_t REG_A5XX_VPC_SO(uint32_t i0) { return 0x0000e2a7 + 0x7*i0; } + +static inline uint32_t REG_A5XX_VPC_SO_BUFFER_BASE_LO(uint32_t i0) { return 0x0000e2a7 + 0x7*i0; } + +static inline uint32_t REG_A5XX_VPC_SO_BUFFER_BASE_HI(uint32_t i0) { return 0x0000e2a8 + 0x7*i0; } + +static inline uint32_t REG_A5XX_VPC_SO_BUFFER_SIZE(uint32_t i0) { return 0x0000e2a9 + 0x7*i0; } + +static inline uint32_t REG_A5XX_VPC_SO_NCOMP(uint32_t i0) { return 0x0000e2aa + 0x7*i0; } + +static inline uint32_t REG_A5XX_VPC_SO_BUFFER_OFFSET(uint32_t i0) { return 0x0000e2ab + 0x7*i0; } + +static inline uint32_t REG_A5XX_VPC_SO_FLUSH_BASE_LO(uint32_t i0) { return 0x0000e2ac + 0x7*i0; } + +static inline uint32_t REG_A5XX_VPC_SO_FLUSH_BASE_HI(uint32_t i0) { return 0x0000e2ad + 0x7*i0; } + +#define REG_A5XX_PC_PRIMITIVE_CNTL 0x0000e384 +#define A5XX_PC_PRIMITIVE_CNTL_STRIDE_IN_VPC__MASK 0x0000007f +#define A5XX_PC_PRIMITIVE_CNTL_STRIDE_IN_VPC__SHIFT 0 +static inline uint32_t A5XX_PC_PRIMITIVE_CNTL_STRIDE_IN_VPC(uint32_t val) +{ + return ((val) << A5XX_PC_PRIMITIVE_CNTL_STRIDE_IN_VPC__SHIFT) & A5XX_PC_PRIMITIVE_CNTL_STRIDE_IN_VPC__MASK; +} +#define A5XX_PC_PRIMITIVE_CNTL_PRIMITIVE_RESTART 0x00000100 +#define A5XX_PC_PRIMITIVE_CNTL_COUNT_PRIMITIVES 0x00000200 +#define A5XX_PC_PRIMITIVE_CNTL_PROVOKING_VTX_LAST 0x00000400 + +#define REG_A5XX_PC_PRIM_VTX_CNTL 0x0000e385 +#define A5XX_PC_PRIM_VTX_CNTL_PSIZE 0x00000800 + +#define REG_A5XX_PC_RASTER_CNTL 0x0000e388 +#define A5XX_PC_RASTER_CNTL_POLYMODE_FRONT_PTYPE__MASK 0x00000007 +#define A5XX_PC_RASTER_CNTL_POLYMODE_FRONT_PTYPE__SHIFT 0 +static inline uint32_t A5XX_PC_RASTER_CNTL_POLYMODE_FRONT_PTYPE(enum adreno_pa_su_sc_draw val) +{ + return ((val) << A5XX_PC_RASTER_CNTL_POLYMODE_FRONT_PTYPE__SHIFT) & A5XX_PC_RASTER_CNTL_POLYMODE_FRONT_PTYPE__MASK; +} +#define A5XX_PC_RASTER_CNTL_POLYMODE_BACK_PTYPE__MASK 0x00000038 +#define A5XX_PC_RASTER_CNTL_POLYMODE_BACK_PTYPE__SHIFT 3 +static inline uint32_t A5XX_PC_RASTER_CNTL_POLYMODE_BACK_PTYPE(enum adreno_pa_su_sc_draw val) +{ + return ((val) << A5XX_PC_RASTER_CNTL_POLYMODE_BACK_PTYPE__SHIFT) & A5XX_PC_RASTER_CNTL_POLYMODE_BACK_PTYPE__MASK; +} +#define A5XX_PC_RASTER_CNTL_POLYMODE_ENABLE 0x00000040 + +#define REG_A5XX_UNKNOWN_E389 0x0000e389 + +#define REG_A5XX_PC_RESTART_INDEX 0x0000e38c + +#define REG_A5XX_PC_GS_LAYERED 0x0000e38d + +#define REG_A5XX_PC_GS_PARAM 0x0000e38e +#define A5XX_PC_GS_PARAM_MAX_VERTICES__MASK 0x000003ff +#define A5XX_PC_GS_PARAM_MAX_VERTICES__SHIFT 0 +static inline uint32_t A5XX_PC_GS_PARAM_MAX_VERTICES(uint32_t val) +{ + return ((val) << A5XX_PC_GS_PARAM_MAX_VERTICES__SHIFT) & A5XX_PC_GS_PARAM_MAX_VERTICES__MASK; +} +#define A5XX_PC_GS_PARAM_INVOCATIONS__MASK 0x0000f800 +#define A5XX_PC_GS_PARAM_INVOCATIONS__SHIFT 11 +static inline uint32_t A5XX_PC_GS_PARAM_INVOCATIONS(uint32_t val) +{ + return ((val) << A5XX_PC_GS_PARAM_INVOCATIONS__SHIFT) & A5XX_PC_GS_PARAM_INVOCATIONS__MASK; +} +#define A5XX_PC_GS_PARAM_PRIMTYPE__MASK 0x01800000 +#define A5XX_PC_GS_PARAM_PRIMTYPE__SHIFT 23 +static inline uint32_t A5XX_PC_GS_PARAM_PRIMTYPE(enum adreno_pa_su_sc_draw val) +{ + return ((val) << A5XX_PC_GS_PARAM_PRIMTYPE__SHIFT) & A5XX_PC_GS_PARAM_PRIMTYPE__MASK; +} + +#define REG_A5XX_PC_HS_PARAM 0x0000e38f +#define A5XX_PC_HS_PARAM_VERTICES_OUT__MASK 0x0000003f +#define A5XX_PC_HS_PARAM_VERTICES_OUT__SHIFT 0 +static inline uint32_t A5XX_PC_HS_PARAM_VERTICES_OUT(uint32_t val) +{ + return ((val) << A5XX_PC_HS_PARAM_VERTICES_OUT__SHIFT) & A5XX_PC_HS_PARAM_VERTICES_OUT__MASK; +} +#define A5XX_PC_HS_PARAM_SPACING__MASK 0x00600000 +#define A5XX_PC_HS_PARAM_SPACING__SHIFT 21 +static inline uint32_t A5XX_PC_HS_PARAM_SPACING(enum a4xx_tess_spacing val) +{ + return ((val) << A5XX_PC_HS_PARAM_SPACING__SHIFT) & A5XX_PC_HS_PARAM_SPACING__MASK; +} +#define A5XX_PC_HS_PARAM_CW 0x00800000 +#define A5XX_PC_HS_PARAM_CONNECTED 0x01000000 + +#define REG_A5XX_PC_POWER_CNTL 0x0000e3b0 + +#define REG_A5XX_VFD_CONTROL_0 0x0000e400 +#define A5XX_VFD_CONTROL_0_VTXCNT__MASK 0x0000003f +#define A5XX_VFD_CONTROL_0_VTXCNT__SHIFT 0 +static inline uint32_t A5XX_VFD_CONTROL_0_VTXCNT(uint32_t val) +{ + return ((val) << A5XX_VFD_CONTROL_0_VTXCNT__SHIFT) & A5XX_VFD_CONTROL_0_VTXCNT__MASK; +} + +#define REG_A5XX_VFD_CONTROL_1 0x0000e401 +#define A5XX_VFD_CONTROL_1_REGID4VTX__MASK 0x000000ff +#define A5XX_VFD_CONTROL_1_REGID4VTX__SHIFT 0 +static inline uint32_t A5XX_VFD_CONTROL_1_REGID4VTX(uint32_t val) +{ + return ((val) << A5XX_VFD_CONTROL_1_REGID4VTX__SHIFT) & A5XX_VFD_CONTROL_1_REGID4VTX__MASK; +} +#define A5XX_VFD_CONTROL_1_REGID4INST__MASK 0x0000ff00 +#define A5XX_VFD_CONTROL_1_REGID4INST__SHIFT 8 +static inline uint32_t A5XX_VFD_CONTROL_1_REGID4INST(uint32_t val) +{ + return ((val) << A5XX_VFD_CONTROL_1_REGID4INST__SHIFT) & A5XX_VFD_CONTROL_1_REGID4INST__MASK; +} +#define A5XX_VFD_CONTROL_1_REGID4PRIMID__MASK 0x00ff0000 +#define A5XX_VFD_CONTROL_1_REGID4PRIMID__SHIFT 16 +static inline uint32_t A5XX_VFD_CONTROL_1_REGID4PRIMID(uint32_t val) +{ + return ((val) << A5XX_VFD_CONTROL_1_REGID4PRIMID__SHIFT) & A5XX_VFD_CONTROL_1_REGID4PRIMID__MASK; +} + +#define REG_A5XX_VFD_CONTROL_2 0x0000e402 +#define A5XX_VFD_CONTROL_2_REGID_PATCHID__MASK 0x000000ff +#define A5XX_VFD_CONTROL_2_REGID_PATCHID__SHIFT 0 +static inline uint32_t A5XX_VFD_CONTROL_2_REGID_PATCHID(uint32_t val) +{ + return ((val) << A5XX_VFD_CONTROL_2_REGID_PATCHID__SHIFT) & A5XX_VFD_CONTROL_2_REGID_PATCHID__MASK; +} + +#define REG_A5XX_VFD_CONTROL_3 0x0000e403 +#define A5XX_VFD_CONTROL_3_REGID_PATCHID__MASK 0x0000ff00 +#define A5XX_VFD_CONTROL_3_REGID_PATCHID__SHIFT 8 +static inline uint32_t A5XX_VFD_CONTROL_3_REGID_PATCHID(uint32_t val) +{ + return ((val) << A5XX_VFD_CONTROL_3_REGID_PATCHID__SHIFT) & A5XX_VFD_CONTROL_3_REGID_PATCHID__MASK; +} +#define A5XX_VFD_CONTROL_3_REGID_TESSX__MASK 0x00ff0000 +#define A5XX_VFD_CONTROL_3_REGID_TESSX__SHIFT 16 +static inline uint32_t A5XX_VFD_CONTROL_3_REGID_TESSX(uint32_t val) +{ + return ((val) << A5XX_VFD_CONTROL_3_REGID_TESSX__SHIFT) & A5XX_VFD_CONTROL_3_REGID_TESSX__MASK; +} +#define A5XX_VFD_CONTROL_3_REGID_TESSY__MASK 0xff000000 +#define A5XX_VFD_CONTROL_3_REGID_TESSY__SHIFT 24 +static inline uint32_t A5XX_VFD_CONTROL_3_REGID_TESSY(uint32_t val) +{ + return ((val) << A5XX_VFD_CONTROL_3_REGID_TESSY__SHIFT) & A5XX_VFD_CONTROL_3_REGID_TESSY__MASK; +} + +#define REG_A5XX_VFD_CONTROL_4 0x0000e404 + +#define REG_A5XX_VFD_CONTROL_5 0x0000e405 + +#define REG_A5XX_VFD_INDEX_OFFSET 0x0000e408 + +#define REG_A5XX_VFD_INSTANCE_START_OFFSET 0x0000e409 + +static inline uint32_t REG_A5XX_VFD_FETCH(uint32_t i0) { return 0x0000e40a + 0x4*i0; } + +static inline uint32_t REG_A5XX_VFD_FETCH_BASE_LO(uint32_t i0) { return 0x0000e40a + 0x4*i0; } + +static inline uint32_t REG_A5XX_VFD_FETCH_BASE_HI(uint32_t i0) { return 0x0000e40b + 0x4*i0; } + +static inline uint32_t REG_A5XX_VFD_FETCH_SIZE(uint32_t i0) { return 0x0000e40c + 0x4*i0; } + +static inline uint32_t REG_A5XX_VFD_FETCH_STRIDE(uint32_t i0) { return 0x0000e40d + 0x4*i0; } + +static inline uint32_t REG_A5XX_VFD_DECODE(uint32_t i0) { return 0x0000e48a + 0x2*i0; } + +static inline uint32_t REG_A5XX_VFD_DECODE_INSTR(uint32_t i0) { return 0x0000e48a + 0x2*i0; } +#define A5XX_VFD_DECODE_INSTR_IDX__MASK 0x0000001f +#define A5XX_VFD_DECODE_INSTR_IDX__SHIFT 0 +static inline uint32_t A5XX_VFD_DECODE_INSTR_IDX(uint32_t val) +{ + return ((val) << A5XX_VFD_DECODE_INSTR_IDX__SHIFT) & A5XX_VFD_DECODE_INSTR_IDX__MASK; +} +#define A5XX_VFD_DECODE_INSTR_INSTANCED 0x00020000 +#define A5XX_VFD_DECODE_INSTR_FORMAT__MASK 0x0ff00000 +#define A5XX_VFD_DECODE_INSTR_FORMAT__SHIFT 20 +static inline uint32_t A5XX_VFD_DECODE_INSTR_FORMAT(enum a5xx_vtx_fmt val) +{ + return ((val) << A5XX_VFD_DECODE_INSTR_FORMAT__SHIFT) & A5XX_VFD_DECODE_INSTR_FORMAT__MASK; +} +#define A5XX_VFD_DECODE_INSTR_SWAP__MASK 0x30000000 +#define A5XX_VFD_DECODE_INSTR_SWAP__SHIFT 28 +static inline uint32_t A5XX_VFD_DECODE_INSTR_SWAP(enum a3xx_color_swap val) +{ + return ((val) << A5XX_VFD_DECODE_INSTR_SWAP__SHIFT) & A5XX_VFD_DECODE_INSTR_SWAP__MASK; +} +#define A5XX_VFD_DECODE_INSTR_UNK30 0x40000000 +#define A5XX_VFD_DECODE_INSTR_FLOAT 0x80000000 + +static inline uint32_t REG_A5XX_VFD_DECODE_STEP_RATE(uint32_t i0) { return 0x0000e48b + 0x2*i0; } + +static inline uint32_t REG_A5XX_VFD_DEST_CNTL(uint32_t i0) { return 0x0000e4ca + 0x1*i0; } + +static inline uint32_t REG_A5XX_VFD_DEST_CNTL_INSTR(uint32_t i0) { return 0x0000e4ca + 0x1*i0; } +#define A5XX_VFD_DEST_CNTL_INSTR_WRITEMASK__MASK 0x0000000f +#define A5XX_VFD_DEST_CNTL_INSTR_WRITEMASK__SHIFT 0 +static inline uint32_t A5XX_VFD_DEST_CNTL_INSTR_WRITEMASK(uint32_t val) +{ + return ((val) << A5XX_VFD_DEST_CNTL_INSTR_WRITEMASK__SHIFT) & A5XX_VFD_DEST_CNTL_INSTR_WRITEMASK__MASK; +} +#define A5XX_VFD_DEST_CNTL_INSTR_REGID__MASK 0x00000ff0 +#define A5XX_VFD_DEST_CNTL_INSTR_REGID__SHIFT 4 +static inline uint32_t A5XX_VFD_DEST_CNTL_INSTR_REGID(uint32_t val) +{ + return ((val) << A5XX_VFD_DEST_CNTL_INSTR_REGID__SHIFT) & A5XX_VFD_DEST_CNTL_INSTR_REGID__MASK; +} + +#define REG_A5XX_VFD_POWER_CNTL 0x0000e4f0 + +#define REG_A5XX_SP_SP_CNTL 0x0000e580 + +#define REG_A5XX_SP_VS_CONFIG 0x0000e584 +#define A5XX_SP_VS_CONFIG_ENABLED 0x00000001 +#define A5XX_SP_VS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_SP_VS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_SP_VS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_VS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_SP_VS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_SP_VS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_SP_VS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_SP_VS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_VS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_SP_VS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_SP_FS_CONFIG 0x0000e585 +#define A5XX_SP_FS_CONFIG_ENABLED 0x00000001 +#define A5XX_SP_FS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_SP_FS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_SP_FS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_FS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_SP_FS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_SP_FS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_SP_FS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_SP_FS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_FS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_SP_FS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_SP_HS_CONFIG 0x0000e586 +#define A5XX_SP_HS_CONFIG_ENABLED 0x00000001 +#define A5XX_SP_HS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_SP_HS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_SP_HS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_HS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_SP_HS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_SP_HS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_SP_HS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_SP_HS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_HS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_SP_HS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_SP_DS_CONFIG 0x0000e587 +#define A5XX_SP_DS_CONFIG_ENABLED 0x00000001 +#define A5XX_SP_DS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_SP_DS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_SP_DS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_DS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_SP_DS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_SP_DS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_SP_DS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_SP_DS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_DS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_SP_DS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_SP_GS_CONFIG 0x0000e588 +#define A5XX_SP_GS_CONFIG_ENABLED 0x00000001 +#define A5XX_SP_GS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_SP_GS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_SP_GS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_GS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_SP_GS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_SP_GS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_SP_GS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_SP_GS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_GS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_SP_GS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_SP_CS_CONFIG 0x0000e589 +#define A5XX_SP_CS_CONFIG_ENABLED 0x00000001 +#define A5XX_SP_CS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_SP_CS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_SP_CS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_CS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_SP_CS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_SP_CS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_SP_CS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_SP_CS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_SP_CS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_SP_CS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_SP_VS_CONFIG_MAX_CONST 0x0000e58a + +#define REG_A5XX_SP_FS_CONFIG_MAX_CONST 0x0000e58b + +#define REG_A5XX_SP_VS_CTRL_REG0 0x0000e590 +#define A5XX_SP_VS_CTRL_REG0_THREADSIZE__MASK 0x00000008 +#define A5XX_SP_VS_CTRL_REG0_THREADSIZE__SHIFT 3 +static inline uint32_t A5XX_SP_VS_CTRL_REG0_THREADSIZE(enum a3xx_threadsize val) +{ + return ((val) << A5XX_SP_VS_CTRL_REG0_THREADSIZE__SHIFT) & A5XX_SP_VS_CTRL_REG0_THREADSIZE__MASK; +} +#define A5XX_SP_VS_CTRL_REG0_HALFREGFOOTPRINT__MASK 0x000003f0 +#define A5XX_SP_VS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT 4 +static inline uint32_t A5XX_SP_VS_CTRL_REG0_HALFREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_VS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT) & A5XX_SP_VS_CTRL_REG0_HALFREGFOOTPRINT__MASK; +} +#define A5XX_SP_VS_CTRL_REG0_FULLREGFOOTPRINT__MASK 0x0000fc00 +#define A5XX_SP_VS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT 10 +static inline uint32_t A5XX_SP_VS_CTRL_REG0_FULLREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_VS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT) & A5XX_SP_VS_CTRL_REG0_FULLREGFOOTPRINT__MASK; +} +#define A5XX_SP_VS_CTRL_REG0_VARYING 0x00010000 +#define A5XX_SP_VS_CTRL_REG0_PIXLODENABLE 0x00100000 +#define A5XX_SP_VS_CTRL_REG0_BRANCHSTACK__MASK 0xfe000000 +#define A5XX_SP_VS_CTRL_REG0_BRANCHSTACK__SHIFT 25 +static inline uint32_t A5XX_SP_VS_CTRL_REG0_BRANCHSTACK(uint32_t val) +{ + return ((val) << A5XX_SP_VS_CTRL_REG0_BRANCHSTACK__SHIFT) & A5XX_SP_VS_CTRL_REG0_BRANCHSTACK__MASK; +} + +#define REG_A5XX_SP_PRIMITIVE_CNTL 0x0000e592 +#define A5XX_SP_PRIMITIVE_CNTL_VSOUT__MASK 0x0000001f +#define A5XX_SP_PRIMITIVE_CNTL_VSOUT__SHIFT 0 +static inline uint32_t A5XX_SP_PRIMITIVE_CNTL_VSOUT(uint32_t val) +{ + return ((val) << A5XX_SP_PRIMITIVE_CNTL_VSOUT__SHIFT) & A5XX_SP_PRIMITIVE_CNTL_VSOUT__MASK; +} + +static inline uint32_t REG_A5XX_SP_VS_OUT(uint32_t i0) { return 0x0000e593 + 0x1*i0; } + +static inline uint32_t REG_A5XX_SP_VS_OUT_REG(uint32_t i0) { return 0x0000e593 + 0x1*i0; } +#define A5XX_SP_VS_OUT_REG_A_REGID__MASK 0x000000ff +#define A5XX_SP_VS_OUT_REG_A_REGID__SHIFT 0 +static inline uint32_t A5XX_SP_VS_OUT_REG_A_REGID(uint32_t val) +{ + return ((val) << A5XX_SP_VS_OUT_REG_A_REGID__SHIFT) & A5XX_SP_VS_OUT_REG_A_REGID__MASK; +} +#define A5XX_SP_VS_OUT_REG_A_COMPMASK__MASK 0x00000f00 +#define A5XX_SP_VS_OUT_REG_A_COMPMASK__SHIFT 8 +static inline uint32_t A5XX_SP_VS_OUT_REG_A_COMPMASK(uint32_t val) +{ + return ((val) << A5XX_SP_VS_OUT_REG_A_COMPMASK__SHIFT) & A5XX_SP_VS_OUT_REG_A_COMPMASK__MASK; +} +#define A5XX_SP_VS_OUT_REG_B_REGID__MASK 0x00ff0000 +#define A5XX_SP_VS_OUT_REG_B_REGID__SHIFT 16 +static inline uint32_t A5XX_SP_VS_OUT_REG_B_REGID(uint32_t val) +{ + return ((val) << A5XX_SP_VS_OUT_REG_B_REGID__SHIFT) & A5XX_SP_VS_OUT_REG_B_REGID__MASK; +} +#define A5XX_SP_VS_OUT_REG_B_COMPMASK__MASK 0x0f000000 +#define A5XX_SP_VS_OUT_REG_B_COMPMASK__SHIFT 24 +static inline uint32_t A5XX_SP_VS_OUT_REG_B_COMPMASK(uint32_t val) +{ + return ((val) << A5XX_SP_VS_OUT_REG_B_COMPMASK__SHIFT) & A5XX_SP_VS_OUT_REG_B_COMPMASK__MASK; +} + +static inline uint32_t REG_A5XX_SP_VS_VPC_DST(uint32_t i0) { return 0x0000e5a3 + 0x1*i0; } + +static inline uint32_t REG_A5XX_SP_VS_VPC_DST_REG(uint32_t i0) { return 0x0000e5a3 + 0x1*i0; } +#define A5XX_SP_VS_VPC_DST_REG_OUTLOC0__MASK 0x000000ff +#define A5XX_SP_VS_VPC_DST_REG_OUTLOC0__SHIFT 0 +static inline uint32_t A5XX_SP_VS_VPC_DST_REG_OUTLOC0(uint32_t val) +{ + return ((val) << A5XX_SP_VS_VPC_DST_REG_OUTLOC0__SHIFT) & A5XX_SP_VS_VPC_DST_REG_OUTLOC0__MASK; +} +#define A5XX_SP_VS_VPC_DST_REG_OUTLOC1__MASK 0x0000ff00 +#define A5XX_SP_VS_VPC_DST_REG_OUTLOC1__SHIFT 8 +static inline uint32_t A5XX_SP_VS_VPC_DST_REG_OUTLOC1(uint32_t val) +{ + return ((val) << A5XX_SP_VS_VPC_DST_REG_OUTLOC1__SHIFT) & A5XX_SP_VS_VPC_DST_REG_OUTLOC1__MASK; +} +#define A5XX_SP_VS_VPC_DST_REG_OUTLOC2__MASK 0x00ff0000 +#define A5XX_SP_VS_VPC_DST_REG_OUTLOC2__SHIFT 16 +static inline uint32_t A5XX_SP_VS_VPC_DST_REG_OUTLOC2(uint32_t val) +{ + return ((val) << A5XX_SP_VS_VPC_DST_REG_OUTLOC2__SHIFT) & A5XX_SP_VS_VPC_DST_REG_OUTLOC2__MASK; +} +#define A5XX_SP_VS_VPC_DST_REG_OUTLOC3__MASK 0xff000000 +#define A5XX_SP_VS_VPC_DST_REG_OUTLOC3__SHIFT 24 +static inline uint32_t A5XX_SP_VS_VPC_DST_REG_OUTLOC3(uint32_t val) +{ + return ((val) << A5XX_SP_VS_VPC_DST_REG_OUTLOC3__SHIFT) & A5XX_SP_VS_VPC_DST_REG_OUTLOC3__MASK; +} + +#define REG_A5XX_UNKNOWN_E5AB 0x0000e5ab + +#define REG_A5XX_SP_VS_OBJ_START_LO 0x0000e5ac + +#define REG_A5XX_SP_VS_OBJ_START_HI 0x0000e5ad + +#define REG_A5XX_SP_FS_CTRL_REG0 0x0000e5c0 +#define A5XX_SP_FS_CTRL_REG0_THREADSIZE__MASK 0x00000008 +#define A5XX_SP_FS_CTRL_REG0_THREADSIZE__SHIFT 3 +static inline uint32_t A5XX_SP_FS_CTRL_REG0_THREADSIZE(enum a3xx_threadsize val) +{ + return ((val) << A5XX_SP_FS_CTRL_REG0_THREADSIZE__SHIFT) & A5XX_SP_FS_CTRL_REG0_THREADSIZE__MASK; +} +#define A5XX_SP_FS_CTRL_REG0_HALFREGFOOTPRINT__MASK 0x000003f0 +#define A5XX_SP_FS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT 4 +static inline uint32_t A5XX_SP_FS_CTRL_REG0_HALFREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_FS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT) & A5XX_SP_FS_CTRL_REG0_HALFREGFOOTPRINT__MASK; +} +#define A5XX_SP_FS_CTRL_REG0_FULLREGFOOTPRINT__MASK 0x0000fc00 +#define A5XX_SP_FS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT 10 +static inline uint32_t A5XX_SP_FS_CTRL_REG0_FULLREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_FS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT) & A5XX_SP_FS_CTRL_REG0_FULLREGFOOTPRINT__MASK; +} +#define A5XX_SP_FS_CTRL_REG0_VARYING 0x00010000 +#define A5XX_SP_FS_CTRL_REG0_PIXLODENABLE 0x00100000 +#define A5XX_SP_FS_CTRL_REG0_BRANCHSTACK__MASK 0xfe000000 +#define A5XX_SP_FS_CTRL_REG0_BRANCHSTACK__SHIFT 25 +static inline uint32_t A5XX_SP_FS_CTRL_REG0_BRANCHSTACK(uint32_t val) +{ + return ((val) << A5XX_SP_FS_CTRL_REG0_BRANCHSTACK__SHIFT) & A5XX_SP_FS_CTRL_REG0_BRANCHSTACK__MASK; +} + +#define REG_A5XX_UNKNOWN_E5C2 0x0000e5c2 + +#define REG_A5XX_SP_FS_OBJ_START_LO 0x0000e5c3 + +#define REG_A5XX_SP_FS_OBJ_START_HI 0x0000e5c4 + +#define REG_A5XX_SP_BLEND_CNTL 0x0000e5c9 +#define A5XX_SP_BLEND_CNTL_ENABLED 0x00000001 +#define A5XX_SP_BLEND_CNTL_UNK8 0x00000100 +#define A5XX_SP_BLEND_CNTL_ALPHA_TO_COVERAGE 0x00000400 + +#define REG_A5XX_SP_FS_OUTPUT_CNTL 0x0000e5ca +#define A5XX_SP_FS_OUTPUT_CNTL_MRT__MASK 0x0000000f +#define A5XX_SP_FS_OUTPUT_CNTL_MRT__SHIFT 0 +static inline uint32_t A5XX_SP_FS_OUTPUT_CNTL_MRT(uint32_t val) +{ + return ((val) << A5XX_SP_FS_OUTPUT_CNTL_MRT__SHIFT) & A5XX_SP_FS_OUTPUT_CNTL_MRT__MASK; +} +#define A5XX_SP_FS_OUTPUT_CNTL_DEPTH_REGID__MASK 0x00001fe0 +#define A5XX_SP_FS_OUTPUT_CNTL_DEPTH_REGID__SHIFT 5 +static inline uint32_t A5XX_SP_FS_OUTPUT_CNTL_DEPTH_REGID(uint32_t val) +{ + return ((val) << A5XX_SP_FS_OUTPUT_CNTL_DEPTH_REGID__SHIFT) & A5XX_SP_FS_OUTPUT_CNTL_DEPTH_REGID__MASK; +} +#define A5XX_SP_FS_OUTPUT_CNTL_SAMPLEMASK_REGID__MASK 0x001fe000 +#define A5XX_SP_FS_OUTPUT_CNTL_SAMPLEMASK_REGID__SHIFT 13 +static inline uint32_t A5XX_SP_FS_OUTPUT_CNTL_SAMPLEMASK_REGID(uint32_t val) +{ + return ((val) << A5XX_SP_FS_OUTPUT_CNTL_SAMPLEMASK_REGID__SHIFT) & A5XX_SP_FS_OUTPUT_CNTL_SAMPLEMASK_REGID__MASK; +} + +static inline uint32_t REG_A5XX_SP_FS_OUTPUT(uint32_t i0) { return 0x0000e5cb + 0x1*i0; } + +static inline uint32_t REG_A5XX_SP_FS_OUTPUT_REG(uint32_t i0) { return 0x0000e5cb + 0x1*i0; } +#define A5XX_SP_FS_OUTPUT_REG_REGID__MASK 0x000000ff +#define A5XX_SP_FS_OUTPUT_REG_REGID__SHIFT 0 +static inline uint32_t A5XX_SP_FS_OUTPUT_REG_REGID(uint32_t val) +{ + return ((val) << A5XX_SP_FS_OUTPUT_REG_REGID__SHIFT) & A5XX_SP_FS_OUTPUT_REG_REGID__MASK; +} +#define A5XX_SP_FS_OUTPUT_REG_HALF_PRECISION 0x00000100 + +static inline uint32_t REG_A5XX_SP_FS_MRT(uint32_t i0) { return 0x0000e5d3 + 0x1*i0; } + +static inline uint32_t REG_A5XX_SP_FS_MRT_REG(uint32_t i0) { return 0x0000e5d3 + 0x1*i0; } +#define A5XX_SP_FS_MRT_REG_COLOR_FORMAT__MASK 0x000000ff +#define A5XX_SP_FS_MRT_REG_COLOR_FORMAT__SHIFT 0 +static inline uint32_t A5XX_SP_FS_MRT_REG_COLOR_FORMAT(enum a5xx_color_fmt val) +{ + return ((val) << A5XX_SP_FS_MRT_REG_COLOR_FORMAT__SHIFT) & A5XX_SP_FS_MRT_REG_COLOR_FORMAT__MASK; +} +#define A5XX_SP_FS_MRT_REG_COLOR_SINT 0x00000100 +#define A5XX_SP_FS_MRT_REG_COLOR_UINT 0x00000200 +#define A5XX_SP_FS_MRT_REG_COLOR_SRGB 0x00000400 + +#define REG_A5XX_UNKNOWN_E5DB 0x0000e5db + +#define REG_A5XX_SP_CS_CTRL_REG0 0x0000e5f0 +#define A5XX_SP_CS_CTRL_REG0_THREADSIZE__MASK 0x00000008 +#define A5XX_SP_CS_CTRL_REG0_THREADSIZE__SHIFT 3 +static inline uint32_t A5XX_SP_CS_CTRL_REG0_THREADSIZE(enum a3xx_threadsize val) +{ + return ((val) << A5XX_SP_CS_CTRL_REG0_THREADSIZE__SHIFT) & A5XX_SP_CS_CTRL_REG0_THREADSIZE__MASK; +} +#define A5XX_SP_CS_CTRL_REG0_HALFREGFOOTPRINT__MASK 0x000003f0 +#define A5XX_SP_CS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT 4 +static inline uint32_t A5XX_SP_CS_CTRL_REG0_HALFREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_CS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT) & A5XX_SP_CS_CTRL_REG0_HALFREGFOOTPRINT__MASK; +} +#define A5XX_SP_CS_CTRL_REG0_FULLREGFOOTPRINT__MASK 0x0000fc00 +#define A5XX_SP_CS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT 10 +static inline uint32_t A5XX_SP_CS_CTRL_REG0_FULLREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_CS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT) & A5XX_SP_CS_CTRL_REG0_FULLREGFOOTPRINT__MASK; +} +#define A5XX_SP_CS_CTRL_REG0_VARYING 0x00010000 +#define A5XX_SP_CS_CTRL_REG0_PIXLODENABLE 0x00100000 +#define A5XX_SP_CS_CTRL_REG0_BRANCHSTACK__MASK 0xfe000000 +#define A5XX_SP_CS_CTRL_REG0_BRANCHSTACK__SHIFT 25 +static inline uint32_t A5XX_SP_CS_CTRL_REG0_BRANCHSTACK(uint32_t val) +{ + return ((val) << A5XX_SP_CS_CTRL_REG0_BRANCHSTACK__SHIFT) & A5XX_SP_CS_CTRL_REG0_BRANCHSTACK__MASK; +} + +#define REG_A5XX_UNKNOWN_E5F2 0x0000e5f2 + +#define REG_A5XX_SP_CS_OBJ_START_LO 0x0000e5f3 + +#define REG_A5XX_SP_CS_OBJ_START_HI 0x0000e5f4 + +#define REG_A5XX_SP_HS_CTRL_REG0 0x0000e600 +#define A5XX_SP_HS_CTRL_REG0_THREADSIZE__MASK 0x00000008 +#define A5XX_SP_HS_CTRL_REG0_THREADSIZE__SHIFT 3 +static inline uint32_t A5XX_SP_HS_CTRL_REG0_THREADSIZE(enum a3xx_threadsize val) +{ + return ((val) << A5XX_SP_HS_CTRL_REG0_THREADSIZE__SHIFT) & A5XX_SP_HS_CTRL_REG0_THREADSIZE__MASK; +} +#define A5XX_SP_HS_CTRL_REG0_HALFREGFOOTPRINT__MASK 0x000003f0 +#define A5XX_SP_HS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT 4 +static inline uint32_t A5XX_SP_HS_CTRL_REG0_HALFREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_HS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT) & A5XX_SP_HS_CTRL_REG0_HALFREGFOOTPRINT__MASK; +} +#define A5XX_SP_HS_CTRL_REG0_FULLREGFOOTPRINT__MASK 0x0000fc00 +#define A5XX_SP_HS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT 10 +static inline uint32_t A5XX_SP_HS_CTRL_REG0_FULLREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_HS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT) & A5XX_SP_HS_CTRL_REG0_FULLREGFOOTPRINT__MASK; +} +#define A5XX_SP_HS_CTRL_REG0_VARYING 0x00010000 +#define A5XX_SP_HS_CTRL_REG0_PIXLODENABLE 0x00100000 +#define A5XX_SP_HS_CTRL_REG0_BRANCHSTACK__MASK 0xfe000000 +#define A5XX_SP_HS_CTRL_REG0_BRANCHSTACK__SHIFT 25 +static inline uint32_t A5XX_SP_HS_CTRL_REG0_BRANCHSTACK(uint32_t val) +{ + return ((val) << A5XX_SP_HS_CTRL_REG0_BRANCHSTACK__SHIFT) & A5XX_SP_HS_CTRL_REG0_BRANCHSTACK__MASK; +} + +#define REG_A5XX_UNKNOWN_E602 0x0000e602 + +#define REG_A5XX_SP_HS_OBJ_START_LO 0x0000e603 + +#define REG_A5XX_SP_HS_OBJ_START_HI 0x0000e604 + +#define REG_A5XX_SP_DS_CTRL_REG0 0x0000e610 +#define A5XX_SP_DS_CTRL_REG0_THREADSIZE__MASK 0x00000008 +#define A5XX_SP_DS_CTRL_REG0_THREADSIZE__SHIFT 3 +static inline uint32_t A5XX_SP_DS_CTRL_REG0_THREADSIZE(enum a3xx_threadsize val) +{ + return ((val) << A5XX_SP_DS_CTRL_REG0_THREADSIZE__SHIFT) & A5XX_SP_DS_CTRL_REG0_THREADSIZE__MASK; +} +#define A5XX_SP_DS_CTRL_REG0_HALFREGFOOTPRINT__MASK 0x000003f0 +#define A5XX_SP_DS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT 4 +static inline uint32_t A5XX_SP_DS_CTRL_REG0_HALFREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_DS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT) & A5XX_SP_DS_CTRL_REG0_HALFREGFOOTPRINT__MASK; +} +#define A5XX_SP_DS_CTRL_REG0_FULLREGFOOTPRINT__MASK 0x0000fc00 +#define A5XX_SP_DS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT 10 +static inline uint32_t A5XX_SP_DS_CTRL_REG0_FULLREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_DS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT) & A5XX_SP_DS_CTRL_REG0_FULLREGFOOTPRINT__MASK; +} +#define A5XX_SP_DS_CTRL_REG0_VARYING 0x00010000 +#define A5XX_SP_DS_CTRL_REG0_PIXLODENABLE 0x00100000 +#define A5XX_SP_DS_CTRL_REG0_BRANCHSTACK__MASK 0xfe000000 +#define A5XX_SP_DS_CTRL_REG0_BRANCHSTACK__SHIFT 25 +static inline uint32_t A5XX_SP_DS_CTRL_REG0_BRANCHSTACK(uint32_t val) +{ + return ((val) << A5XX_SP_DS_CTRL_REG0_BRANCHSTACK__SHIFT) & A5XX_SP_DS_CTRL_REG0_BRANCHSTACK__MASK; +} + +#define REG_A5XX_UNKNOWN_E62B 0x0000e62b + +#define REG_A5XX_SP_DS_OBJ_START_LO 0x0000e62c + +#define REG_A5XX_SP_DS_OBJ_START_HI 0x0000e62d + +#define REG_A5XX_SP_GS_CTRL_REG0 0x0000e640 +#define A5XX_SP_GS_CTRL_REG0_THREADSIZE__MASK 0x00000008 +#define A5XX_SP_GS_CTRL_REG0_THREADSIZE__SHIFT 3 +static inline uint32_t A5XX_SP_GS_CTRL_REG0_THREADSIZE(enum a3xx_threadsize val) +{ + return ((val) << A5XX_SP_GS_CTRL_REG0_THREADSIZE__SHIFT) & A5XX_SP_GS_CTRL_REG0_THREADSIZE__MASK; +} +#define A5XX_SP_GS_CTRL_REG0_HALFREGFOOTPRINT__MASK 0x000003f0 +#define A5XX_SP_GS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT 4 +static inline uint32_t A5XX_SP_GS_CTRL_REG0_HALFREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_GS_CTRL_REG0_HALFREGFOOTPRINT__SHIFT) & A5XX_SP_GS_CTRL_REG0_HALFREGFOOTPRINT__MASK; +} +#define A5XX_SP_GS_CTRL_REG0_FULLREGFOOTPRINT__MASK 0x0000fc00 +#define A5XX_SP_GS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT 10 +static inline uint32_t A5XX_SP_GS_CTRL_REG0_FULLREGFOOTPRINT(uint32_t val) +{ + return ((val) << A5XX_SP_GS_CTRL_REG0_FULLREGFOOTPRINT__SHIFT) & A5XX_SP_GS_CTRL_REG0_FULLREGFOOTPRINT__MASK; +} +#define A5XX_SP_GS_CTRL_REG0_VARYING 0x00010000 +#define A5XX_SP_GS_CTRL_REG0_PIXLODENABLE 0x00100000 +#define A5XX_SP_GS_CTRL_REG0_BRANCHSTACK__MASK 0xfe000000 +#define A5XX_SP_GS_CTRL_REG0_BRANCHSTACK__SHIFT 25 +static inline uint32_t A5XX_SP_GS_CTRL_REG0_BRANCHSTACK(uint32_t val) +{ + return ((val) << A5XX_SP_GS_CTRL_REG0_BRANCHSTACK__SHIFT) & A5XX_SP_GS_CTRL_REG0_BRANCHSTACK__MASK; +} + +#define REG_A5XX_UNKNOWN_E65B 0x0000e65b + +#define REG_A5XX_SP_GS_OBJ_START_LO 0x0000e65c + +#define REG_A5XX_SP_GS_OBJ_START_HI 0x0000e65d + +#define REG_A5XX_TPL1_TP_RAS_MSAA_CNTL 0x0000e704 +#define A5XX_TPL1_TP_RAS_MSAA_CNTL_SAMPLES__MASK 0x00000003 +#define A5XX_TPL1_TP_RAS_MSAA_CNTL_SAMPLES__SHIFT 0 +static inline uint32_t A5XX_TPL1_TP_RAS_MSAA_CNTL_SAMPLES(enum a3xx_msaa_samples val) +{ + return ((val) << A5XX_TPL1_TP_RAS_MSAA_CNTL_SAMPLES__SHIFT) & A5XX_TPL1_TP_RAS_MSAA_CNTL_SAMPLES__MASK; +} + +#define REG_A5XX_TPL1_TP_DEST_MSAA_CNTL 0x0000e705 +#define A5XX_TPL1_TP_DEST_MSAA_CNTL_SAMPLES__MASK 0x00000003 +#define A5XX_TPL1_TP_DEST_MSAA_CNTL_SAMPLES__SHIFT 0 +static inline uint32_t A5XX_TPL1_TP_DEST_MSAA_CNTL_SAMPLES(enum a3xx_msaa_samples val) +{ + return ((val) << A5XX_TPL1_TP_DEST_MSAA_CNTL_SAMPLES__SHIFT) & A5XX_TPL1_TP_DEST_MSAA_CNTL_SAMPLES__MASK; +} +#define A5XX_TPL1_TP_DEST_MSAA_CNTL_MSAA_DISABLE 0x00000004 + +#define REG_A5XX_TPL1_TP_BORDER_COLOR_BASE_ADDR_LO 0x0000e706 + +#define REG_A5XX_TPL1_TP_BORDER_COLOR_BASE_ADDR_HI 0x0000e707 + +#define REG_A5XX_TPL1_VS_TEX_COUNT 0x0000e700 + +#define REG_A5XX_TPL1_HS_TEX_COUNT 0x0000e701 + +#define REG_A5XX_TPL1_DS_TEX_COUNT 0x0000e702 + +#define REG_A5XX_TPL1_GS_TEX_COUNT 0x0000e703 + +#define REG_A5XX_TPL1_VS_TEX_SAMP_LO 0x0000e722 + +#define REG_A5XX_TPL1_VS_TEX_SAMP_HI 0x0000e723 + +#define REG_A5XX_TPL1_HS_TEX_SAMP_LO 0x0000e724 + +#define REG_A5XX_TPL1_HS_TEX_SAMP_HI 0x0000e725 + +#define REG_A5XX_TPL1_DS_TEX_SAMP_LO 0x0000e726 + +#define REG_A5XX_TPL1_DS_TEX_SAMP_HI 0x0000e727 + +#define REG_A5XX_TPL1_GS_TEX_SAMP_LO 0x0000e728 + +#define REG_A5XX_TPL1_GS_TEX_SAMP_HI 0x0000e729 + +#define REG_A5XX_TPL1_VS_TEX_CONST_LO 0x0000e72a + +#define REG_A5XX_TPL1_VS_TEX_CONST_HI 0x0000e72b + +#define REG_A5XX_TPL1_HS_TEX_CONST_LO 0x0000e72c + +#define REG_A5XX_TPL1_HS_TEX_CONST_HI 0x0000e72d + +#define REG_A5XX_TPL1_DS_TEX_CONST_LO 0x0000e72e + +#define REG_A5XX_TPL1_DS_TEX_CONST_HI 0x0000e72f + +#define REG_A5XX_TPL1_GS_TEX_CONST_LO 0x0000e730 + +#define REG_A5XX_TPL1_GS_TEX_CONST_HI 0x0000e731 + +#define REG_A5XX_TPL1_FS_TEX_COUNT 0x0000e750 + +#define REG_A5XX_TPL1_CS_TEX_COUNT 0x0000e751 + +#define REG_A5XX_TPL1_FS_TEX_SAMP_LO 0x0000e75a + +#define REG_A5XX_TPL1_FS_TEX_SAMP_HI 0x0000e75b + +#define REG_A5XX_TPL1_CS_TEX_SAMP_LO 0x0000e75c + +#define REG_A5XX_TPL1_CS_TEX_SAMP_HI 0x0000e75d + +#define REG_A5XX_TPL1_FS_TEX_CONST_LO 0x0000e75e + +#define REG_A5XX_TPL1_FS_TEX_CONST_HI 0x0000e75f + +#define REG_A5XX_TPL1_CS_TEX_CONST_LO 0x0000e760 + +#define REG_A5XX_TPL1_CS_TEX_CONST_HI 0x0000e761 + +#define REG_A5XX_TPL1_TP_FS_ROTATION_CNTL 0x0000e764 + +#define REG_A5XX_HLSQ_CONTROL_0_REG 0x0000e784 +#define A5XX_HLSQ_CONTROL_0_REG_FSTHREADSIZE__MASK 0x00000001 +#define A5XX_HLSQ_CONTROL_0_REG_FSTHREADSIZE__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CONTROL_0_REG_FSTHREADSIZE(enum a3xx_threadsize val) +{ + return ((val) << A5XX_HLSQ_CONTROL_0_REG_FSTHREADSIZE__SHIFT) & A5XX_HLSQ_CONTROL_0_REG_FSTHREADSIZE__MASK; +} +#define A5XX_HLSQ_CONTROL_0_REG_CSTHREADSIZE__MASK 0x00000004 +#define A5XX_HLSQ_CONTROL_0_REG_CSTHREADSIZE__SHIFT 2 +static inline uint32_t A5XX_HLSQ_CONTROL_0_REG_CSTHREADSIZE(enum a3xx_threadsize val) +{ + return ((val) << A5XX_HLSQ_CONTROL_0_REG_CSTHREADSIZE__SHIFT) & A5XX_HLSQ_CONTROL_0_REG_CSTHREADSIZE__MASK; +} + +#define REG_A5XX_HLSQ_CONTROL_1_REG 0x0000e785 +#define A5XX_HLSQ_CONTROL_1_REG_PRIMALLOCTHRESHOLD__MASK 0x0000003f +#define A5XX_HLSQ_CONTROL_1_REG_PRIMALLOCTHRESHOLD__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CONTROL_1_REG_PRIMALLOCTHRESHOLD(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CONTROL_1_REG_PRIMALLOCTHRESHOLD__SHIFT) & A5XX_HLSQ_CONTROL_1_REG_PRIMALLOCTHRESHOLD__MASK; +} + +#define REG_A5XX_HLSQ_CONTROL_2_REG 0x0000e786 +#define A5XX_HLSQ_CONTROL_2_REG_FACEREGID__MASK 0x000000ff +#define A5XX_HLSQ_CONTROL_2_REG_FACEREGID__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CONTROL_2_REG_FACEREGID(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CONTROL_2_REG_FACEREGID__SHIFT) & A5XX_HLSQ_CONTROL_2_REG_FACEREGID__MASK; +} +#define A5XX_HLSQ_CONTROL_2_REG_SAMPLEID__MASK 0x0000ff00 +#define A5XX_HLSQ_CONTROL_2_REG_SAMPLEID__SHIFT 8 +static inline uint32_t A5XX_HLSQ_CONTROL_2_REG_SAMPLEID(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CONTROL_2_REG_SAMPLEID__SHIFT) & A5XX_HLSQ_CONTROL_2_REG_SAMPLEID__MASK; +} +#define A5XX_HLSQ_CONTROL_2_REG_SAMPLEMASK__MASK 0x00ff0000 +#define A5XX_HLSQ_CONTROL_2_REG_SAMPLEMASK__SHIFT 16 +static inline uint32_t A5XX_HLSQ_CONTROL_2_REG_SAMPLEMASK(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CONTROL_2_REG_SAMPLEMASK__SHIFT) & A5XX_HLSQ_CONTROL_2_REG_SAMPLEMASK__MASK; +} + +#define REG_A5XX_HLSQ_CONTROL_3_REG 0x0000e787 +#define A5XX_HLSQ_CONTROL_3_REG_FRAGCOORDXYREGID__MASK 0x000000ff +#define A5XX_HLSQ_CONTROL_3_REG_FRAGCOORDXYREGID__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CONTROL_3_REG_FRAGCOORDXYREGID(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CONTROL_3_REG_FRAGCOORDXYREGID__SHIFT) & A5XX_HLSQ_CONTROL_3_REG_FRAGCOORDXYREGID__MASK; +} + +#define REG_A5XX_HLSQ_CONTROL_4_REG 0x0000e788 +#define A5XX_HLSQ_CONTROL_4_REG_XYCOORDREGID__MASK 0x00ff0000 +#define A5XX_HLSQ_CONTROL_4_REG_XYCOORDREGID__SHIFT 16 +static inline uint32_t A5XX_HLSQ_CONTROL_4_REG_XYCOORDREGID(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CONTROL_4_REG_XYCOORDREGID__SHIFT) & A5XX_HLSQ_CONTROL_4_REG_XYCOORDREGID__MASK; +} +#define A5XX_HLSQ_CONTROL_4_REG_ZWCOORDREGID__MASK 0xff000000 +#define A5XX_HLSQ_CONTROL_4_REG_ZWCOORDREGID__SHIFT 24 +static inline uint32_t A5XX_HLSQ_CONTROL_4_REG_ZWCOORDREGID(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CONTROL_4_REG_ZWCOORDREGID__SHIFT) & A5XX_HLSQ_CONTROL_4_REG_ZWCOORDREGID__MASK; +} + +#define REG_A5XX_HLSQ_UPDATE_CNTL 0x0000e78a + +#define REG_A5XX_HLSQ_VS_CONFIG 0x0000e78b +#define A5XX_HLSQ_VS_CONFIG_ENABLED 0x00000001 +#define A5XX_HLSQ_VS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_HLSQ_VS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_HLSQ_VS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_VS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_HLSQ_VS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_HLSQ_VS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_HLSQ_VS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_HLSQ_VS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_VS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_HLSQ_VS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_HLSQ_FS_CONFIG 0x0000e78c +#define A5XX_HLSQ_FS_CONFIG_ENABLED 0x00000001 +#define A5XX_HLSQ_FS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_HLSQ_FS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_HLSQ_FS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_FS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_HLSQ_FS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_HLSQ_FS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_HLSQ_FS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_HLSQ_FS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_FS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_HLSQ_FS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_HLSQ_HS_CONFIG 0x0000e78d +#define A5XX_HLSQ_HS_CONFIG_ENABLED 0x00000001 +#define A5XX_HLSQ_HS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_HLSQ_HS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_HLSQ_HS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_HS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_HLSQ_HS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_HLSQ_HS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_HLSQ_HS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_HLSQ_HS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_HS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_HLSQ_HS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_HLSQ_DS_CONFIG 0x0000e78e +#define A5XX_HLSQ_DS_CONFIG_ENABLED 0x00000001 +#define A5XX_HLSQ_DS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_HLSQ_DS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_HLSQ_DS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_DS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_HLSQ_DS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_HLSQ_DS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_HLSQ_DS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_HLSQ_DS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_DS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_HLSQ_DS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_HLSQ_GS_CONFIG 0x0000e78f +#define A5XX_HLSQ_GS_CONFIG_ENABLED 0x00000001 +#define A5XX_HLSQ_GS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_HLSQ_GS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_HLSQ_GS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_GS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_HLSQ_GS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_HLSQ_GS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_HLSQ_GS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_HLSQ_GS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_GS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_HLSQ_GS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_HLSQ_CS_CONFIG 0x0000e790 +#define A5XX_HLSQ_CS_CONFIG_ENABLED 0x00000001 +#define A5XX_HLSQ_CS_CONFIG_CONSTOBJECTOFFSET__MASK 0x000000fe +#define A5XX_HLSQ_CS_CONFIG_CONSTOBJECTOFFSET__SHIFT 1 +static inline uint32_t A5XX_HLSQ_CS_CONFIG_CONSTOBJECTOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_CONFIG_CONSTOBJECTOFFSET__SHIFT) & A5XX_HLSQ_CS_CONFIG_CONSTOBJECTOFFSET__MASK; +} +#define A5XX_HLSQ_CS_CONFIG_SHADEROBJOFFSET__MASK 0x00007f00 +#define A5XX_HLSQ_CS_CONFIG_SHADEROBJOFFSET__SHIFT 8 +static inline uint32_t A5XX_HLSQ_CS_CONFIG_SHADEROBJOFFSET(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_CONFIG_SHADEROBJOFFSET__SHIFT) & A5XX_HLSQ_CS_CONFIG_SHADEROBJOFFSET__MASK; +} + +#define REG_A5XX_HLSQ_VS_CNTL 0x0000e791 +#define A5XX_HLSQ_VS_CNTL_SSBO_ENABLE 0x00000001 +#define A5XX_HLSQ_VS_CNTL_INSTRLEN__MASK 0xfffffffe +#define A5XX_HLSQ_VS_CNTL_INSTRLEN__SHIFT 1 +static inline uint32_t A5XX_HLSQ_VS_CNTL_INSTRLEN(uint32_t val) +{ + return ((val) << A5XX_HLSQ_VS_CNTL_INSTRLEN__SHIFT) & A5XX_HLSQ_VS_CNTL_INSTRLEN__MASK; +} + +#define REG_A5XX_HLSQ_FS_CNTL 0x0000e792 +#define A5XX_HLSQ_FS_CNTL_SSBO_ENABLE 0x00000001 +#define A5XX_HLSQ_FS_CNTL_INSTRLEN__MASK 0xfffffffe +#define A5XX_HLSQ_FS_CNTL_INSTRLEN__SHIFT 1 +static inline uint32_t A5XX_HLSQ_FS_CNTL_INSTRLEN(uint32_t val) +{ + return ((val) << A5XX_HLSQ_FS_CNTL_INSTRLEN__SHIFT) & A5XX_HLSQ_FS_CNTL_INSTRLEN__MASK; +} + +#define REG_A5XX_HLSQ_HS_CNTL 0x0000e793 +#define A5XX_HLSQ_HS_CNTL_SSBO_ENABLE 0x00000001 +#define A5XX_HLSQ_HS_CNTL_INSTRLEN__MASK 0xfffffffe +#define A5XX_HLSQ_HS_CNTL_INSTRLEN__SHIFT 1 +static inline uint32_t A5XX_HLSQ_HS_CNTL_INSTRLEN(uint32_t val) +{ + return ((val) << A5XX_HLSQ_HS_CNTL_INSTRLEN__SHIFT) & A5XX_HLSQ_HS_CNTL_INSTRLEN__MASK; +} + +#define REG_A5XX_HLSQ_DS_CNTL 0x0000e794 +#define A5XX_HLSQ_DS_CNTL_SSBO_ENABLE 0x00000001 +#define A5XX_HLSQ_DS_CNTL_INSTRLEN__MASK 0xfffffffe +#define A5XX_HLSQ_DS_CNTL_INSTRLEN__SHIFT 1 +static inline uint32_t A5XX_HLSQ_DS_CNTL_INSTRLEN(uint32_t val) +{ + return ((val) << A5XX_HLSQ_DS_CNTL_INSTRLEN__SHIFT) & A5XX_HLSQ_DS_CNTL_INSTRLEN__MASK; +} + +#define REG_A5XX_HLSQ_GS_CNTL 0x0000e795 +#define A5XX_HLSQ_GS_CNTL_SSBO_ENABLE 0x00000001 +#define A5XX_HLSQ_GS_CNTL_INSTRLEN__MASK 0xfffffffe +#define A5XX_HLSQ_GS_CNTL_INSTRLEN__SHIFT 1 +static inline uint32_t A5XX_HLSQ_GS_CNTL_INSTRLEN(uint32_t val) +{ + return ((val) << A5XX_HLSQ_GS_CNTL_INSTRLEN__SHIFT) & A5XX_HLSQ_GS_CNTL_INSTRLEN__MASK; +} + +#define REG_A5XX_HLSQ_CS_CNTL 0x0000e796 +#define A5XX_HLSQ_CS_CNTL_SSBO_ENABLE 0x00000001 +#define A5XX_HLSQ_CS_CNTL_INSTRLEN__MASK 0xfffffffe +#define A5XX_HLSQ_CS_CNTL_INSTRLEN__SHIFT 1 +static inline uint32_t A5XX_HLSQ_CS_CNTL_INSTRLEN(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_CNTL_INSTRLEN__SHIFT) & A5XX_HLSQ_CS_CNTL_INSTRLEN__MASK; +} + +#define REG_A5XX_HLSQ_CS_KERNEL_GROUP_X 0x0000e7b9 + +#define REG_A5XX_HLSQ_CS_KERNEL_GROUP_Y 0x0000e7ba + +#define REG_A5XX_HLSQ_CS_KERNEL_GROUP_Z 0x0000e7bb + +#define REG_A5XX_HLSQ_CS_NDRANGE_0 0x0000e7b0 +#define A5XX_HLSQ_CS_NDRANGE_0_KERNELDIM__MASK 0x00000003 +#define A5XX_HLSQ_CS_NDRANGE_0_KERNELDIM__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CS_NDRANGE_0_KERNELDIM(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_NDRANGE_0_KERNELDIM__SHIFT) & A5XX_HLSQ_CS_NDRANGE_0_KERNELDIM__MASK; +} +#define A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEX__MASK 0x00000ffc +#define A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEX__SHIFT 2 +static inline uint32_t A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEX(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEX__SHIFT) & A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEX__MASK; +} +#define A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEY__MASK 0x003ff000 +#define A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEY__SHIFT 12 +static inline uint32_t A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEY(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEY__SHIFT) & A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEY__MASK; +} +#define A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEZ__MASK 0xffc00000 +#define A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEZ__SHIFT 22 +static inline uint32_t A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEZ(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEZ__SHIFT) & A5XX_HLSQ_CS_NDRANGE_0_LOCALSIZEZ__MASK; +} + +#define REG_A5XX_HLSQ_CS_NDRANGE_1 0x0000e7b1 +#define A5XX_HLSQ_CS_NDRANGE_1_GLOBALSIZE_X__MASK 0xffffffff +#define A5XX_HLSQ_CS_NDRANGE_1_GLOBALSIZE_X__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CS_NDRANGE_1_GLOBALSIZE_X(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_NDRANGE_1_GLOBALSIZE_X__SHIFT) & A5XX_HLSQ_CS_NDRANGE_1_GLOBALSIZE_X__MASK; +} + +#define REG_A5XX_HLSQ_CS_NDRANGE_2 0x0000e7b2 +#define A5XX_HLSQ_CS_NDRANGE_2_GLOBALOFF_X__MASK 0xffffffff +#define A5XX_HLSQ_CS_NDRANGE_2_GLOBALOFF_X__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CS_NDRANGE_2_GLOBALOFF_X(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_NDRANGE_2_GLOBALOFF_X__SHIFT) & A5XX_HLSQ_CS_NDRANGE_2_GLOBALOFF_X__MASK; +} + +#define REG_A5XX_HLSQ_CS_NDRANGE_3 0x0000e7b3 +#define A5XX_HLSQ_CS_NDRANGE_3_GLOBALSIZE_Y__MASK 0xffffffff +#define A5XX_HLSQ_CS_NDRANGE_3_GLOBALSIZE_Y__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CS_NDRANGE_3_GLOBALSIZE_Y(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_NDRANGE_3_GLOBALSIZE_Y__SHIFT) & A5XX_HLSQ_CS_NDRANGE_3_GLOBALSIZE_Y__MASK; +} + +#define REG_A5XX_HLSQ_CS_NDRANGE_4 0x0000e7b4 +#define A5XX_HLSQ_CS_NDRANGE_4_GLOBALOFF_Y__MASK 0xffffffff +#define A5XX_HLSQ_CS_NDRANGE_4_GLOBALOFF_Y__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CS_NDRANGE_4_GLOBALOFF_Y(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_NDRANGE_4_GLOBALOFF_Y__SHIFT) & A5XX_HLSQ_CS_NDRANGE_4_GLOBALOFF_Y__MASK; +} + +#define REG_A5XX_HLSQ_CS_NDRANGE_5 0x0000e7b5 +#define A5XX_HLSQ_CS_NDRANGE_5_GLOBALSIZE_Z__MASK 0xffffffff +#define A5XX_HLSQ_CS_NDRANGE_5_GLOBALSIZE_Z__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CS_NDRANGE_5_GLOBALSIZE_Z(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_NDRANGE_5_GLOBALSIZE_Z__SHIFT) & A5XX_HLSQ_CS_NDRANGE_5_GLOBALSIZE_Z__MASK; +} + +#define REG_A5XX_HLSQ_CS_NDRANGE_6 0x0000e7b6 +#define A5XX_HLSQ_CS_NDRANGE_6_GLOBALOFF_Z__MASK 0xffffffff +#define A5XX_HLSQ_CS_NDRANGE_6_GLOBALOFF_Z__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CS_NDRANGE_6_GLOBALOFF_Z(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_NDRANGE_6_GLOBALOFF_Z__SHIFT) & A5XX_HLSQ_CS_NDRANGE_6_GLOBALOFF_Z__MASK; +} + +#define REG_A5XX_HLSQ_CS_CNTL_0 0x0000e7b7 +#define A5XX_HLSQ_CS_CNTL_0_WGIDCONSTID__MASK 0x000000ff +#define A5XX_HLSQ_CS_CNTL_0_WGIDCONSTID__SHIFT 0 +static inline uint32_t A5XX_HLSQ_CS_CNTL_0_WGIDCONSTID(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_CNTL_0_WGIDCONSTID__SHIFT) & A5XX_HLSQ_CS_CNTL_0_WGIDCONSTID__MASK; +} +#define A5XX_HLSQ_CS_CNTL_0_UNK0__MASK 0x0000ff00 +#define A5XX_HLSQ_CS_CNTL_0_UNK0__SHIFT 8 +static inline uint32_t A5XX_HLSQ_CS_CNTL_0_UNK0(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_CNTL_0_UNK0__SHIFT) & A5XX_HLSQ_CS_CNTL_0_UNK0__MASK; +} +#define A5XX_HLSQ_CS_CNTL_0_UNK1__MASK 0x00ff0000 +#define A5XX_HLSQ_CS_CNTL_0_UNK1__SHIFT 16 +static inline uint32_t A5XX_HLSQ_CS_CNTL_0_UNK1(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_CNTL_0_UNK1__SHIFT) & A5XX_HLSQ_CS_CNTL_0_UNK1__MASK; +} +#define A5XX_HLSQ_CS_CNTL_0_LOCALIDREGID__MASK 0xff000000 +#define A5XX_HLSQ_CS_CNTL_0_LOCALIDREGID__SHIFT 24 +static inline uint32_t A5XX_HLSQ_CS_CNTL_0_LOCALIDREGID(uint32_t val) +{ + return ((val) << A5XX_HLSQ_CS_CNTL_0_LOCALIDREGID__SHIFT) & A5XX_HLSQ_CS_CNTL_0_LOCALIDREGID__MASK; +} + +#define REG_A5XX_HLSQ_CS_CNTL_1 0x0000e7b8 + +#define REG_A5XX_UNKNOWN_E7C0 0x0000e7c0 + +#define REG_A5XX_HLSQ_VS_CONSTLEN 0x0000e7c3 + +#define REG_A5XX_HLSQ_VS_INSTRLEN 0x0000e7c4 + +#define REG_A5XX_UNKNOWN_E7C5 0x0000e7c5 + +#define REG_A5XX_HLSQ_HS_CONSTLEN 0x0000e7c8 + +#define REG_A5XX_HLSQ_HS_INSTRLEN 0x0000e7c9 + +#define REG_A5XX_UNKNOWN_E7CA 0x0000e7ca + +#define REG_A5XX_HLSQ_DS_CONSTLEN 0x0000e7cd + +#define REG_A5XX_HLSQ_DS_INSTRLEN 0x0000e7ce + +#define REG_A5XX_UNKNOWN_E7CF 0x0000e7cf + +#define REG_A5XX_HLSQ_GS_CONSTLEN 0x0000e7d2 + +#define REG_A5XX_HLSQ_GS_INSTRLEN 0x0000e7d3 + +#define REG_A5XX_UNKNOWN_E7D4 0x0000e7d4 + +#define REG_A5XX_HLSQ_FS_CONSTLEN 0x0000e7d7 + +#define REG_A5XX_HLSQ_FS_INSTRLEN 0x0000e7d8 + +#define REG_A5XX_UNKNOWN_E7D9 0x0000e7d9 + +#define REG_A5XX_HLSQ_CS_CONSTLEN 0x0000e7dc + +#define REG_A5XX_HLSQ_CS_INSTRLEN 0x0000e7dd + +#define REG_A5XX_RB_2D_BLIT_CNTL 0x00002100 + +#define REG_A5XX_RB_2D_SRC_SOLID_DW0 0x00002101 + +#define REG_A5XX_RB_2D_SRC_SOLID_DW1 0x00002102 + +#define REG_A5XX_RB_2D_SRC_SOLID_DW2 0x00002103 + +#define REG_A5XX_RB_2D_SRC_SOLID_DW3 0x00002104 + +#define REG_A5XX_RB_2D_SRC_INFO 0x00002107 +#define A5XX_RB_2D_SRC_INFO_COLOR_FORMAT__MASK 0x000000ff +#define A5XX_RB_2D_SRC_INFO_COLOR_FORMAT__SHIFT 0 +static inline uint32_t A5XX_RB_2D_SRC_INFO_COLOR_FORMAT(enum a5xx_color_fmt val) +{ + return ((val) << A5XX_RB_2D_SRC_INFO_COLOR_FORMAT__SHIFT) & A5XX_RB_2D_SRC_INFO_COLOR_FORMAT__MASK; +} +#define A5XX_RB_2D_SRC_INFO_TILE_MODE__MASK 0x00000300 +#define A5XX_RB_2D_SRC_INFO_TILE_MODE__SHIFT 8 +static inline uint32_t A5XX_RB_2D_SRC_INFO_TILE_MODE(enum a5xx_tile_mode val) +{ + return ((val) << A5XX_RB_2D_SRC_INFO_TILE_MODE__SHIFT) & A5XX_RB_2D_SRC_INFO_TILE_MODE__MASK; +} +#define A5XX_RB_2D_SRC_INFO_COLOR_SWAP__MASK 0x00000c00 +#define A5XX_RB_2D_SRC_INFO_COLOR_SWAP__SHIFT 10 +static inline uint32_t A5XX_RB_2D_SRC_INFO_COLOR_SWAP(enum a3xx_color_swap val) +{ + return ((val) << A5XX_RB_2D_SRC_INFO_COLOR_SWAP__SHIFT) & A5XX_RB_2D_SRC_INFO_COLOR_SWAP__MASK; +} +#define A5XX_RB_2D_SRC_INFO_FLAGS 0x00001000 + +#define REG_A5XX_RB_2D_SRC_LO 0x00002108 + +#define REG_A5XX_RB_2D_SRC_HI 0x00002109 + +#define REG_A5XX_RB_2D_SRC_SIZE 0x0000210a +#define A5XX_RB_2D_SRC_SIZE_PITCH__MASK 0x0000ffff +#define A5XX_RB_2D_SRC_SIZE_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_2D_SRC_SIZE_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_2D_SRC_SIZE_PITCH__SHIFT) & A5XX_RB_2D_SRC_SIZE_PITCH__MASK; +} +#define A5XX_RB_2D_SRC_SIZE_ARRAY_PITCH__MASK 0xffff0000 +#define A5XX_RB_2D_SRC_SIZE_ARRAY_PITCH__SHIFT 16 +static inline uint32_t A5XX_RB_2D_SRC_SIZE_ARRAY_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_2D_SRC_SIZE_ARRAY_PITCH__SHIFT) & A5XX_RB_2D_SRC_SIZE_ARRAY_PITCH__MASK; +} + +#define REG_A5XX_RB_2D_DST_INFO 0x00002110 +#define A5XX_RB_2D_DST_INFO_COLOR_FORMAT__MASK 0x000000ff +#define A5XX_RB_2D_DST_INFO_COLOR_FORMAT__SHIFT 0 +static inline uint32_t A5XX_RB_2D_DST_INFO_COLOR_FORMAT(enum a5xx_color_fmt val) +{ + return ((val) << A5XX_RB_2D_DST_INFO_COLOR_FORMAT__SHIFT) & A5XX_RB_2D_DST_INFO_COLOR_FORMAT__MASK; +} +#define A5XX_RB_2D_DST_INFO_TILE_MODE__MASK 0x00000300 +#define A5XX_RB_2D_DST_INFO_TILE_MODE__SHIFT 8 +static inline uint32_t A5XX_RB_2D_DST_INFO_TILE_MODE(enum a5xx_tile_mode val) +{ + return ((val) << A5XX_RB_2D_DST_INFO_TILE_MODE__SHIFT) & A5XX_RB_2D_DST_INFO_TILE_MODE__MASK; +} +#define A5XX_RB_2D_DST_INFO_COLOR_SWAP__MASK 0x00000c00 +#define A5XX_RB_2D_DST_INFO_COLOR_SWAP__SHIFT 10 +static inline uint32_t A5XX_RB_2D_DST_INFO_COLOR_SWAP(enum a3xx_color_swap val) +{ + return ((val) << A5XX_RB_2D_DST_INFO_COLOR_SWAP__SHIFT) & A5XX_RB_2D_DST_INFO_COLOR_SWAP__MASK; +} +#define A5XX_RB_2D_DST_INFO_FLAGS 0x00001000 + +#define REG_A5XX_RB_2D_DST_LO 0x00002111 + +#define REG_A5XX_RB_2D_DST_HI 0x00002112 + +#define REG_A5XX_RB_2D_DST_SIZE 0x00002113 +#define A5XX_RB_2D_DST_SIZE_PITCH__MASK 0x0000ffff +#define A5XX_RB_2D_DST_SIZE_PITCH__SHIFT 0 +static inline uint32_t A5XX_RB_2D_DST_SIZE_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_2D_DST_SIZE_PITCH__SHIFT) & A5XX_RB_2D_DST_SIZE_PITCH__MASK; +} +#define A5XX_RB_2D_DST_SIZE_ARRAY_PITCH__MASK 0xffff0000 +#define A5XX_RB_2D_DST_SIZE_ARRAY_PITCH__SHIFT 16 +static inline uint32_t A5XX_RB_2D_DST_SIZE_ARRAY_PITCH(uint32_t val) +{ + return ((val >> 6) << A5XX_RB_2D_DST_SIZE_ARRAY_PITCH__SHIFT) & A5XX_RB_2D_DST_SIZE_ARRAY_PITCH__MASK; +} + +#define REG_A5XX_RB_2D_SRC_FLAGS_LO 0x00002140 + +#define REG_A5XX_RB_2D_SRC_FLAGS_HI 0x00002141 + +#define REG_A5XX_RB_2D_DST_FLAGS_LO 0x00002143 + +#define REG_A5XX_RB_2D_DST_FLAGS_HI 0x00002144 + +#define REG_A5XX_GRAS_2D_BLIT_CNTL 0x00002180 + +#define REG_A5XX_GRAS_2D_SRC_INFO 0x00002181 +#define A5XX_GRAS_2D_SRC_INFO_COLOR_FORMAT__MASK 0x000000ff +#define A5XX_GRAS_2D_SRC_INFO_COLOR_FORMAT__SHIFT 0 +static inline uint32_t A5XX_GRAS_2D_SRC_INFO_COLOR_FORMAT(enum a5xx_color_fmt val) +{ + return ((val) << A5XX_GRAS_2D_SRC_INFO_COLOR_FORMAT__SHIFT) & A5XX_GRAS_2D_SRC_INFO_COLOR_FORMAT__MASK; +} +#define A5XX_GRAS_2D_SRC_INFO_TILE_MODE__MASK 0x00000300 +#define A5XX_GRAS_2D_SRC_INFO_TILE_MODE__SHIFT 8 +static inline uint32_t A5XX_GRAS_2D_SRC_INFO_TILE_MODE(enum a5xx_tile_mode val) +{ + return ((val) << A5XX_GRAS_2D_SRC_INFO_TILE_MODE__SHIFT) & A5XX_GRAS_2D_SRC_INFO_TILE_MODE__MASK; +} +#define A5XX_GRAS_2D_SRC_INFO_COLOR_SWAP__MASK 0x00000c00 +#define A5XX_GRAS_2D_SRC_INFO_COLOR_SWAP__SHIFT 10 +static inline uint32_t A5XX_GRAS_2D_SRC_INFO_COLOR_SWAP(enum a3xx_color_swap val) +{ + return ((val) << A5XX_GRAS_2D_SRC_INFO_COLOR_SWAP__SHIFT) & A5XX_GRAS_2D_SRC_INFO_COLOR_SWAP__MASK; +} +#define A5XX_GRAS_2D_SRC_INFO_FLAGS 0x00001000 + +#define REG_A5XX_GRAS_2D_DST_INFO 0x00002182 +#define A5XX_GRAS_2D_DST_INFO_COLOR_FORMAT__MASK 0x000000ff +#define A5XX_GRAS_2D_DST_INFO_COLOR_FORMAT__SHIFT 0 +static inline uint32_t A5XX_GRAS_2D_DST_INFO_COLOR_FORMAT(enum a5xx_color_fmt val) +{ + return ((val) << A5XX_GRAS_2D_DST_INFO_COLOR_FORMAT__SHIFT) & A5XX_GRAS_2D_DST_INFO_COLOR_FORMAT__MASK; +} +#define A5XX_GRAS_2D_DST_INFO_TILE_MODE__MASK 0x00000300 +#define A5XX_GRAS_2D_DST_INFO_TILE_MODE__SHIFT 8 +static inline uint32_t A5XX_GRAS_2D_DST_INFO_TILE_MODE(enum a5xx_tile_mode val) +{ + return ((val) << A5XX_GRAS_2D_DST_INFO_TILE_MODE__SHIFT) & A5XX_GRAS_2D_DST_INFO_TILE_MODE__MASK; +} +#define A5XX_GRAS_2D_DST_INFO_COLOR_SWAP__MASK 0x00000c00 +#define A5XX_GRAS_2D_DST_INFO_COLOR_SWAP__SHIFT 10 +static inline uint32_t A5XX_GRAS_2D_DST_INFO_COLOR_SWAP(enum a3xx_color_swap val) +{ + return ((val) << A5XX_GRAS_2D_DST_INFO_COLOR_SWAP__SHIFT) & A5XX_GRAS_2D_DST_INFO_COLOR_SWAP__MASK; +} +#define A5XX_GRAS_2D_DST_INFO_FLAGS 0x00001000 + +#define REG_A5XX_UNKNOWN_2100 0x00002100 + +#define REG_A5XX_UNKNOWN_2180 0x00002180 + +#define REG_A5XX_UNKNOWN_2184 0x00002184 + +#define REG_A5XX_TEX_SAMP_0 0x00000000 +#define A5XX_TEX_SAMP_0_MIPFILTER_LINEAR_NEAR 0x00000001 +#define A5XX_TEX_SAMP_0_XY_MAG__MASK 0x00000006 +#define A5XX_TEX_SAMP_0_XY_MAG__SHIFT 1 +static inline uint32_t A5XX_TEX_SAMP_0_XY_MAG(enum a5xx_tex_filter val) +{ + return ((val) << A5XX_TEX_SAMP_0_XY_MAG__SHIFT) & A5XX_TEX_SAMP_0_XY_MAG__MASK; +} +#define A5XX_TEX_SAMP_0_XY_MIN__MASK 0x00000018 +#define A5XX_TEX_SAMP_0_XY_MIN__SHIFT 3 +static inline uint32_t A5XX_TEX_SAMP_0_XY_MIN(enum a5xx_tex_filter val) +{ + return ((val) << A5XX_TEX_SAMP_0_XY_MIN__SHIFT) & A5XX_TEX_SAMP_0_XY_MIN__MASK; +} +#define A5XX_TEX_SAMP_0_WRAP_S__MASK 0x000000e0 +#define A5XX_TEX_SAMP_0_WRAP_S__SHIFT 5 +static inline uint32_t A5XX_TEX_SAMP_0_WRAP_S(enum a5xx_tex_clamp val) +{ + return ((val) << A5XX_TEX_SAMP_0_WRAP_S__SHIFT) & A5XX_TEX_SAMP_0_WRAP_S__MASK; +} +#define A5XX_TEX_SAMP_0_WRAP_T__MASK 0x00000700 +#define A5XX_TEX_SAMP_0_WRAP_T__SHIFT 8 +static inline uint32_t A5XX_TEX_SAMP_0_WRAP_T(enum a5xx_tex_clamp val) +{ + return ((val) << A5XX_TEX_SAMP_0_WRAP_T__SHIFT) & A5XX_TEX_SAMP_0_WRAP_T__MASK; +} +#define A5XX_TEX_SAMP_0_WRAP_R__MASK 0x00003800 +#define A5XX_TEX_SAMP_0_WRAP_R__SHIFT 11 +static inline uint32_t A5XX_TEX_SAMP_0_WRAP_R(enum a5xx_tex_clamp val) +{ + return ((val) << A5XX_TEX_SAMP_0_WRAP_R__SHIFT) & A5XX_TEX_SAMP_0_WRAP_R__MASK; +} +#define A5XX_TEX_SAMP_0_ANISO__MASK 0x0001c000 +#define A5XX_TEX_SAMP_0_ANISO__SHIFT 14 +static inline uint32_t A5XX_TEX_SAMP_0_ANISO(enum a5xx_tex_aniso val) +{ + return ((val) << A5XX_TEX_SAMP_0_ANISO__SHIFT) & A5XX_TEX_SAMP_0_ANISO__MASK; +} +#define A5XX_TEX_SAMP_0_LOD_BIAS__MASK 0xfff80000 +#define A5XX_TEX_SAMP_0_LOD_BIAS__SHIFT 19 +static inline uint32_t A5XX_TEX_SAMP_0_LOD_BIAS(float val) +{ + return ((((int32_t)(val * 256.0))) << A5XX_TEX_SAMP_0_LOD_BIAS__SHIFT) & A5XX_TEX_SAMP_0_LOD_BIAS__MASK; +} + +#define REG_A5XX_TEX_SAMP_1 0x00000001 +#define A5XX_TEX_SAMP_1_COMPARE_FUNC__MASK 0x0000000e +#define A5XX_TEX_SAMP_1_COMPARE_FUNC__SHIFT 1 +static inline uint32_t A5XX_TEX_SAMP_1_COMPARE_FUNC(enum adreno_compare_func val) +{ + return ((val) << A5XX_TEX_SAMP_1_COMPARE_FUNC__SHIFT) & A5XX_TEX_SAMP_1_COMPARE_FUNC__MASK; +} +#define A5XX_TEX_SAMP_1_CUBEMAPSEAMLESSFILTOFF 0x00000010 +#define A5XX_TEX_SAMP_1_UNNORM_COORDS 0x00000020 +#define A5XX_TEX_SAMP_1_MIPFILTER_LINEAR_FAR 0x00000040 +#define A5XX_TEX_SAMP_1_MAX_LOD__MASK 0x000fff00 +#define A5XX_TEX_SAMP_1_MAX_LOD__SHIFT 8 +static inline uint32_t A5XX_TEX_SAMP_1_MAX_LOD(float val) +{ + return ((((uint32_t)(val * 256.0))) << A5XX_TEX_SAMP_1_MAX_LOD__SHIFT) & A5XX_TEX_SAMP_1_MAX_LOD__MASK; +} +#define A5XX_TEX_SAMP_1_MIN_LOD__MASK 0xfff00000 +#define A5XX_TEX_SAMP_1_MIN_LOD__SHIFT 20 +static inline uint32_t A5XX_TEX_SAMP_1_MIN_LOD(float val) +{ + return ((((uint32_t)(val * 256.0))) << A5XX_TEX_SAMP_1_MIN_LOD__SHIFT) & A5XX_TEX_SAMP_1_MIN_LOD__MASK; +} + +#define REG_A5XX_TEX_SAMP_2 0x00000002 +#define A5XX_TEX_SAMP_2_BCOLOR_OFFSET__MASK 0xfffffff0 +#define A5XX_TEX_SAMP_2_BCOLOR_OFFSET__SHIFT 4 +static inline uint32_t A5XX_TEX_SAMP_2_BCOLOR_OFFSET(uint32_t val) +{ + return ((val) << A5XX_TEX_SAMP_2_BCOLOR_OFFSET__SHIFT) & A5XX_TEX_SAMP_2_BCOLOR_OFFSET__MASK; +} + +#define REG_A5XX_TEX_SAMP_3 0x00000003 + +#define REG_A5XX_TEX_CONST_0 0x00000000 +#define A5XX_TEX_CONST_0_TILE_MODE__MASK 0x00000003 +#define A5XX_TEX_CONST_0_TILE_MODE__SHIFT 0 +static inline uint32_t A5XX_TEX_CONST_0_TILE_MODE(enum a5xx_tile_mode val) +{ + return ((val) << A5XX_TEX_CONST_0_TILE_MODE__SHIFT) & A5XX_TEX_CONST_0_TILE_MODE__MASK; +} +#define A5XX_TEX_CONST_0_SRGB 0x00000004 +#define A5XX_TEX_CONST_0_SWIZ_X__MASK 0x00000070 +#define A5XX_TEX_CONST_0_SWIZ_X__SHIFT 4 +static inline uint32_t A5XX_TEX_CONST_0_SWIZ_X(enum a5xx_tex_swiz val) +{ + return ((val) << A5XX_TEX_CONST_0_SWIZ_X__SHIFT) & A5XX_TEX_CONST_0_SWIZ_X__MASK; +} +#define A5XX_TEX_CONST_0_SWIZ_Y__MASK 0x00000380 +#define A5XX_TEX_CONST_0_SWIZ_Y__SHIFT 7 +static inline uint32_t A5XX_TEX_CONST_0_SWIZ_Y(enum a5xx_tex_swiz val) +{ + return ((val) << A5XX_TEX_CONST_0_SWIZ_Y__SHIFT) & A5XX_TEX_CONST_0_SWIZ_Y__MASK; +} +#define A5XX_TEX_CONST_0_SWIZ_Z__MASK 0x00001c00 +#define A5XX_TEX_CONST_0_SWIZ_Z__SHIFT 10 +static inline uint32_t A5XX_TEX_CONST_0_SWIZ_Z(enum a5xx_tex_swiz val) +{ + return ((val) << A5XX_TEX_CONST_0_SWIZ_Z__SHIFT) & A5XX_TEX_CONST_0_SWIZ_Z__MASK; +} +#define A5XX_TEX_CONST_0_SWIZ_W__MASK 0x0000e000 +#define A5XX_TEX_CONST_0_SWIZ_W__SHIFT 13 +static inline uint32_t A5XX_TEX_CONST_0_SWIZ_W(enum a5xx_tex_swiz val) +{ + return ((val) << A5XX_TEX_CONST_0_SWIZ_W__SHIFT) & A5XX_TEX_CONST_0_SWIZ_W__MASK; +} +#define A5XX_TEX_CONST_0_MIPLVLS__MASK 0x000f0000 +#define A5XX_TEX_CONST_0_MIPLVLS__SHIFT 16 +static inline uint32_t A5XX_TEX_CONST_0_MIPLVLS(uint32_t val) +{ + return ((val) << A5XX_TEX_CONST_0_MIPLVLS__SHIFT) & A5XX_TEX_CONST_0_MIPLVLS__MASK; +} +#define A5XX_TEX_CONST_0_SAMPLES__MASK 0x00300000 +#define A5XX_TEX_CONST_0_SAMPLES__SHIFT 20 +static inline uint32_t A5XX_TEX_CONST_0_SAMPLES(enum a3xx_msaa_samples val) +{ + return ((val) << A5XX_TEX_CONST_0_SAMPLES__SHIFT) & A5XX_TEX_CONST_0_SAMPLES__MASK; +} +#define A5XX_TEX_CONST_0_FMT__MASK 0x3fc00000 +#define A5XX_TEX_CONST_0_FMT__SHIFT 22 +static inline uint32_t A5XX_TEX_CONST_0_FMT(enum a5xx_tex_fmt val) +{ + return ((val) << A5XX_TEX_CONST_0_FMT__SHIFT) & A5XX_TEX_CONST_0_FMT__MASK; +} +#define A5XX_TEX_CONST_0_SWAP__MASK 0xc0000000 +#define A5XX_TEX_CONST_0_SWAP__SHIFT 30 +static inline uint32_t A5XX_TEX_CONST_0_SWAP(enum a3xx_color_swap val) +{ + return ((val) << A5XX_TEX_CONST_0_SWAP__SHIFT) & A5XX_TEX_CONST_0_SWAP__MASK; +} + +#define REG_A5XX_TEX_CONST_1 0x00000001 +#define A5XX_TEX_CONST_1_WIDTH__MASK 0x00007fff +#define A5XX_TEX_CONST_1_WIDTH__SHIFT 0 +static inline uint32_t A5XX_TEX_CONST_1_WIDTH(uint32_t val) +{ + return ((val) << A5XX_TEX_CONST_1_WIDTH__SHIFT) & A5XX_TEX_CONST_1_WIDTH__MASK; +} +#define A5XX_TEX_CONST_1_HEIGHT__MASK 0x3fff8000 +#define A5XX_TEX_CONST_1_HEIGHT__SHIFT 15 +static inline uint32_t A5XX_TEX_CONST_1_HEIGHT(uint32_t val) +{ + return ((val) << A5XX_TEX_CONST_1_HEIGHT__SHIFT) & A5XX_TEX_CONST_1_HEIGHT__MASK; +} + +#define REG_A5XX_TEX_CONST_2 0x00000002 +#define A5XX_TEX_CONST_2_FETCHSIZE__MASK 0x0000000f +#define A5XX_TEX_CONST_2_FETCHSIZE__SHIFT 0 +static inline uint32_t A5XX_TEX_CONST_2_FETCHSIZE(enum a5xx_tex_fetchsize val) +{ + return ((val) << A5XX_TEX_CONST_2_FETCHSIZE__SHIFT) & A5XX_TEX_CONST_2_FETCHSIZE__MASK; +} +#define A5XX_TEX_CONST_2_PITCH__MASK 0x1fffff80 +#define A5XX_TEX_CONST_2_PITCH__SHIFT 7 +static inline uint32_t A5XX_TEX_CONST_2_PITCH(uint32_t val) +{ + return ((val) << A5XX_TEX_CONST_2_PITCH__SHIFT) & A5XX_TEX_CONST_2_PITCH__MASK; +} +#define A5XX_TEX_CONST_2_TYPE__MASK 0x60000000 +#define A5XX_TEX_CONST_2_TYPE__SHIFT 29 +static inline uint32_t A5XX_TEX_CONST_2_TYPE(enum a5xx_tex_type val) +{ + return ((val) << A5XX_TEX_CONST_2_TYPE__SHIFT) & A5XX_TEX_CONST_2_TYPE__MASK; +} + +#define REG_A5XX_TEX_CONST_3 0x00000003 +#define A5XX_TEX_CONST_3_ARRAY_PITCH__MASK 0x00003fff +#define A5XX_TEX_CONST_3_ARRAY_PITCH__SHIFT 0 +static inline uint32_t A5XX_TEX_CONST_3_ARRAY_PITCH(uint32_t val) +{ + return ((val >> 12) << A5XX_TEX_CONST_3_ARRAY_PITCH__SHIFT) & A5XX_TEX_CONST_3_ARRAY_PITCH__MASK; +} +#define A5XX_TEX_CONST_3_FLAG 0x10000000 + +#define REG_A5XX_TEX_CONST_4 0x00000004 +#define A5XX_TEX_CONST_4_BASE_LO__MASK 0xffffffe0 +#define A5XX_TEX_CONST_4_BASE_LO__SHIFT 5 +static inline uint32_t A5XX_TEX_CONST_4_BASE_LO(uint32_t val) +{ + return ((val >> 5) << A5XX_TEX_CONST_4_BASE_LO__SHIFT) & A5XX_TEX_CONST_4_BASE_LO__MASK; +} + +#define REG_A5XX_TEX_CONST_5 0x00000005 +#define A5XX_TEX_CONST_5_BASE_HI__MASK 0x0001ffff +#define A5XX_TEX_CONST_5_BASE_HI__SHIFT 0 +static inline uint32_t A5XX_TEX_CONST_5_BASE_HI(uint32_t val) +{ + return ((val) << A5XX_TEX_CONST_5_BASE_HI__SHIFT) & A5XX_TEX_CONST_5_BASE_HI__MASK; +} +#define A5XX_TEX_CONST_5_DEPTH__MASK 0x3ffe0000 +#define A5XX_TEX_CONST_5_DEPTH__SHIFT 17 +static inline uint32_t A5XX_TEX_CONST_5_DEPTH(uint32_t val) +{ + return ((val) << A5XX_TEX_CONST_5_DEPTH__SHIFT) & A5XX_TEX_CONST_5_DEPTH__MASK; +} + +#define REG_A5XX_TEX_CONST_6 0x00000006 + +#define REG_A5XX_TEX_CONST_7 0x00000007 + +#define REG_A5XX_TEX_CONST_8 0x00000008 + +#define REG_A5XX_TEX_CONST_9 0x00000009 + +#define REG_A5XX_TEX_CONST_10 0x0000000a + +#define REG_A5XX_TEX_CONST_11 0x0000000b + +#define REG_A5XX_SSBO_0_0 0x00000000 +#define A5XX_SSBO_0_0_BASE_LO__MASK 0xffffffe0 +#define A5XX_SSBO_0_0_BASE_LO__SHIFT 5 +static inline uint32_t A5XX_SSBO_0_0_BASE_LO(uint32_t val) +{ + return ((val >> 5) << A5XX_SSBO_0_0_BASE_LO__SHIFT) & A5XX_SSBO_0_0_BASE_LO__MASK; +} + +#define REG_A5XX_SSBO_0_1 0x00000001 +#define A5XX_SSBO_0_1_PITCH__MASK 0x003fffff +#define A5XX_SSBO_0_1_PITCH__SHIFT 0 +static inline uint32_t A5XX_SSBO_0_1_PITCH(uint32_t val) +{ + return ((val) << A5XX_SSBO_0_1_PITCH__SHIFT) & A5XX_SSBO_0_1_PITCH__MASK; +} + +#define REG_A5XX_SSBO_0_2 0x00000002 +#define A5XX_SSBO_0_2_ARRAY_PITCH__MASK 0x03fff000 +#define A5XX_SSBO_0_2_ARRAY_PITCH__SHIFT 12 +static inline uint32_t A5XX_SSBO_0_2_ARRAY_PITCH(uint32_t val) +{ + return ((val >> 12) << A5XX_SSBO_0_2_ARRAY_PITCH__SHIFT) & A5XX_SSBO_0_2_ARRAY_PITCH__MASK; +} + +#define REG_A5XX_SSBO_0_3 0x00000003 +#define A5XX_SSBO_0_3_CPP__MASK 0x0000003f +#define A5XX_SSBO_0_3_CPP__SHIFT 0 +static inline uint32_t A5XX_SSBO_0_3_CPP(uint32_t val) +{ + return ((val) << A5XX_SSBO_0_3_CPP__SHIFT) & A5XX_SSBO_0_3_CPP__MASK; +} + +#define REG_A5XX_SSBO_1_0 0x00000000 +#define A5XX_SSBO_1_0_FMT__MASK 0x0000ff00 +#define A5XX_SSBO_1_0_FMT__SHIFT 8 +static inline uint32_t A5XX_SSBO_1_0_FMT(enum a5xx_tex_fmt val) +{ + return ((val) << A5XX_SSBO_1_0_FMT__SHIFT) & A5XX_SSBO_1_0_FMT__MASK; +} +#define A5XX_SSBO_1_0_WIDTH__MASK 0xffff0000 +#define A5XX_SSBO_1_0_WIDTH__SHIFT 16 +static inline uint32_t A5XX_SSBO_1_0_WIDTH(uint32_t val) +{ + return ((val) << A5XX_SSBO_1_0_WIDTH__SHIFT) & A5XX_SSBO_1_0_WIDTH__MASK; +} + +#define REG_A5XX_SSBO_1_1 0x00000001 +#define A5XX_SSBO_1_1_HEIGHT__MASK 0x0000ffff +#define A5XX_SSBO_1_1_HEIGHT__SHIFT 0 +static inline uint32_t A5XX_SSBO_1_1_HEIGHT(uint32_t val) +{ + return ((val) << A5XX_SSBO_1_1_HEIGHT__SHIFT) & A5XX_SSBO_1_1_HEIGHT__MASK; +} +#define A5XX_SSBO_1_1_DEPTH__MASK 0xffff0000 +#define A5XX_SSBO_1_1_DEPTH__SHIFT 16 +static inline uint32_t A5XX_SSBO_1_1_DEPTH(uint32_t val) +{ + return ((val) << A5XX_SSBO_1_1_DEPTH__SHIFT) & A5XX_SSBO_1_1_DEPTH__MASK; +} + +#define REG_A5XX_SSBO_2_0 0x00000000 +#define A5XX_SSBO_2_0_BASE_LO__MASK 0xffffffff +#define A5XX_SSBO_2_0_BASE_LO__SHIFT 0 +static inline uint32_t A5XX_SSBO_2_0_BASE_LO(uint32_t val) +{ + return ((val) << A5XX_SSBO_2_0_BASE_LO__SHIFT) & A5XX_SSBO_2_0_BASE_LO__MASK; +} + +#define REG_A5XX_SSBO_2_1 0x00000001 +#define A5XX_SSBO_2_1_BASE_HI__MASK 0xffffffff +#define A5XX_SSBO_2_1_BASE_HI__SHIFT 0 +static inline uint32_t A5XX_SSBO_2_1_BASE_HI(uint32_t val) +{ + return ((val) << A5XX_SSBO_2_1_BASE_HI__SHIFT) & A5XX_SSBO_2_1_BASE_HI__MASK; +} + + +#endif /* A5XX_XML */ diff --git a/selfdrive/modeld/thneed/debug/include/adreno_pm4.xml.h b/selfdrive/modeld/thneed/debug/include/adreno_pm4.xml.h new file mode 100644 index 0000000000..08f8ff2682 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/include/adreno_pm4.xml.h @@ -0,0 +1,1344 @@ +#ifndef ADRENO_PM4_XML +#define ADRENO_PM4_XML + +/* Autogenerated file, DO NOT EDIT manually! + +This file was generated by the rules-ng-ng headergen tool in this git repository: +http://github.com/freedreno/envytools/ +git clone https://github.com/freedreno/envytools.git + +The rules-ng-ng source files this header was generated from are: +- /home/robclark/src/freedreno/envytools/rnndb/adreno.xml ( 501 bytes, from 2018-01-31 18:26:32) +- /home/robclark/src/freedreno/envytools/rnndb/freedreno_copyright.xml ( 1572 bytes, from 2018-01-08 14:56:24) +- /home/robclark/src/freedreno/envytools/rnndb/adreno/a2xx.xml ( 36805 bytes, from 2018-05-20 19:03:35) +- /home/robclark/src/freedreno/envytools/rnndb/adreno/adreno_common.xml ( 13634 bytes, from 2018-06-10 17:35:36) +- /home/robclark/src/freedreno/envytools/rnndb/adreno/adreno_pm4.xml ( 41584 bytes, from 2018-06-18 14:25:44) +- /home/robclark/src/freedreno/envytools/rnndb/adreno/a3xx.xml ( 83840 bytes, from 2018-01-10 16:21:40) +- /home/robclark/src/freedreno/envytools/rnndb/adreno/a4xx.xml ( 112086 bytes, from 2018-01-08 14:56:24) +- /home/robclark/src/freedreno/envytools/rnndb/adreno/a5xx.xml ( 147158 bytes, from 2018-06-18 14:25:44) +- /home/robclark/src/freedreno/envytools/rnndb/adreno/a6xx.xml ( 88437 bytes, from 2018-06-18 14:25:44) +- /home/robclark/src/freedreno/envytools/rnndb/adreno/a6xx_gmu.xml ( 10431 bytes, from 2018-06-10 17:37:04) +- /home/robclark/src/freedreno/envytools/rnndb/adreno/ocmem.xml ( 1773 bytes, from 2018-01-08 14:56:24) + +Copyright (C) 2013-2018 by the following authors: +- Rob Clark (robclark) +- Ilia Mirkin (imirkin) + +Permission is hereby granted, free of charge, to any person obtaining +a copy of this software and associated documentation files (the +"Software"), to deal in the Software without restriction, including +without limitation the rights to use, copy, modify, merge, publish, +distribute, sublicense, and/or sell copies of the Software, and to +permit persons to whom the Software is furnished to do so, subject to +the following conditions: + +The above copyright notice and this permission notice (including the +next paragraph) shall be included in all copies or substantial +portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, +EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. +IN NO EVENT SHALL THE COPYRIGHT OWNER(S) AND/OR ITS SUPPLIERS BE +LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION +OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION +WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + + +enum vgt_event_type { + VS_DEALLOC = 0, + PS_DEALLOC = 1, + VS_DONE_TS = 2, + PS_DONE_TS = 3, + CACHE_FLUSH_TS = 4, + CONTEXT_DONE = 5, + CACHE_FLUSH = 6, + HLSQ_FLUSH = 7, + VIZQUERY_START = 7, + VIZQUERY_END = 8, + SC_WAIT_WC = 9, + RST_PIX_CNT = 13, + RST_VTX_CNT = 14, + TILE_FLUSH = 15, + STAT_EVENT = 16, + CACHE_FLUSH_AND_INV_TS_EVENT = 20, + ZPASS_DONE = 21, + CACHE_FLUSH_AND_INV_EVENT = 22, + PERFCOUNTER_START = 23, + PERFCOUNTER_STOP = 24, + VS_FETCH_DONE = 27, + FACENESS_FLUSH = 28, + FLUSH_SO_0 = 17, + FLUSH_SO_1 = 18, + FLUSH_SO_2 = 19, + FLUSH_SO_3 = 20, + PC_CCU_INVALIDATE_DEPTH = 24, + PC_CCU_INVALIDATE_COLOR = 25, + UNK_1C = 28, + UNK_1D = 29, + BLIT = 30, + UNK_25 = 37, + LRZ_FLUSH = 38, + UNK_2C = 44, + UNK_2D = 45, +}; + +enum pc_di_primtype { + DI_PT_NONE = 0, + DI_PT_POINTLIST_PSIZE = 1, + DI_PT_LINELIST = 2, + DI_PT_LINESTRIP = 3, + DI_PT_TRILIST = 4, + DI_PT_TRIFAN = 5, + DI_PT_TRISTRIP = 6, + DI_PT_LINELOOP = 7, + DI_PT_RECTLIST = 8, + DI_PT_POINTLIST = 9, + DI_PT_LINE_ADJ = 10, + DI_PT_LINESTRIP_ADJ = 11, + DI_PT_TRI_ADJ = 12, + DI_PT_TRISTRIP_ADJ = 13, +}; + +enum pc_di_src_sel { + DI_SRC_SEL_DMA = 0, + DI_SRC_SEL_IMMEDIATE = 1, + DI_SRC_SEL_AUTO_INDEX = 2, + DI_SRC_SEL_RESERVED = 3, +}; + +enum pc_di_index_size { + INDEX_SIZE_IGN = 0, + INDEX_SIZE_16_BIT = 0, + INDEX_SIZE_32_BIT = 1, + INDEX_SIZE_8_BIT = 2, + INDEX_SIZE_INVALID = 0, +}; + +enum pc_di_vis_cull_mode { + IGNORE_VISIBILITY = 0, + USE_VISIBILITY = 1, +}; + +enum adreno_pm4_packet_type { + CP_TYPE0_PKT = 0, + CP_TYPE1_PKT = 0x40000000, + CP_TYPE2_PKT = 0x80000000, + CP_TYPE3_PKT = 0xc0000000, + CP_TYPE4_PKT = 0x40000000, + CP_TYPE7_PKT = 0x70000000, +}; + +enum adreno_pm4_type3_packets { + CP_ME_INIT = 72, + CP_NOP = 16, + CP_PREEMPT_ENABLE = 28, + CP_PREEMPT_TOKEN = 30, + CP_INDIRECT_BUFFER = 63, + CP_INDIRECT_BUFFER_PFD = 55, + CP_WAIT_FOR_IDLE = 38, + CP_WAIT_REG_MEM = 60, + CP_WAIT_REG_EQ = 82, + CP_WAIT_REG_GTE = 83, + CP_WAIT_UNTIL_READ = 92, + CP_WAIT_IB_PFD_COMPLETE = 93, + CP_REG_RMW = 33, + CP_SET_BIN_DATA = 47, + CP_SET_BIN_DATA5 = 47, + CP_REG_TO_MEM = 62, + CP_MEM_WRITE = 61, + CP_MEM_WRITE_CNTR = 79, + CP_COND_EXEC = 68, + CP_COND_WRITE = 69, + CP_COND_WRITE5 = 69, + CP_EVENT_WRITE = 70, + CP_EVENT_WRITE_SHD = 88, + CP_EVENT_WRITE_CFL = 89, + CP_EVENT_WRITE_ZPD = 91, + CP_RUN_OPENCL = 49, + CP_DRAW_INDX = 34, + CP_DRAW_INDX_2 = 54, + CP_DRAW_INDX_BIN = 52, + CP_DRAW_INDX_2_BIN = 53, + CP_VIZ_QUERY = 35, + CP_SET_STATE = 37, + CP_SET_CONSTANT = 45, + CP_IM_LOAD = 39, + CP_IM_LOAD_IMMEDIATE = 43, + CP_LOAD_CONSTANT_CONTEXT = 46, + CP_INVALIDATE_STATE = 59, + CP_SET_SHADER_BASES = 74, + CP_SET_BIN_MASK = 80, + CP_SET_BIN_SELECT = 81, + CP_CONTEXT_UPDATE = 94, + CP_INTERRUPT = 64, + CP_IM_STORE = 44, + CP_SET_DRAW_INIT_FLAGS = 75, + CP_SET_PROTECTED_MODE = 95, + CP_BOOTSTRAP_UCODE = 111, + CP_LOAD_STATE = 48, + CP_LOAD_STATE4 = 48, + CP_COND_INDIRECT_BUFFER_PFE = 58, + CP_COND_INDIRECT_BUFFER_PFD = 50, + CP_INDIRECT_BUFFER_PFE = 63, + CP_SET_BIN = 76, + CP_TEST_TWO_MEMS = 113, + CP_REG_WR_NO_CTXT = 120, + CP_RECORD_PFP_TIMESTAMP = 17, + CP_SET_SECURE_MODE = 102, + CP_WAIT_FOR_ME = 19, + CP_SET_DRAW_STATE = 67, + CP_DRAW_INDX_OFFSET = 56, + CP_DRAW_INDIRECT = 40, + CP_DRAW_INDX_INDIRECT = 41, + CP_DRAW_AUTO = 36, + CP_UNKNOWN_19 = 25, + CP_UNKNOWN_1A = 26, + CP_UNKNOWN_4E = 78, + CP_WIDE_REG_WRITE = 116, + CP_SCRATCH_TO_REG = 77, + CP_REG_TO_SCRATCH = 74, + CP_WAIT_MEM_WRITES = 18, + CP_COND_REG_EXEC = 71, + CP_MEM_TO_REG = 66, + CP_EXEC_CS_INDIRECT = 65, + CP_EXEC_CS = 51, + CP_PERFCOUNTER_ACTION = 80, + CP_SMMU_TABLE_UPDATE = 83, + CP_SET_MARKER = 101, + CP_SET_PSEUDO_REG = 86, + CP_CONTEXT_REG_BUNCH = 92, + CP_YIELD_ENABLE = 28, + CP_SKIP_IB2_ENABLE_GLOBAL = 29, + CP_SKIP_IB2_ENABLE_LOCAL = 35, + CP_SET_SUBDRAW_SIZE = 53, + CP_SET_VISIBILITY_OVERRIDE = 100, + CP_PREEMPT_ENABLE_GLOBAL = 105, + CP_PREEMPT_ENABLE_LOCAL = 106, + CP_CONTEXT_SWITCH_YIELD = 107, + CP_SET_RENDER_MODE = 108, + CP_COMPUTE_CHECKPOINT = 110, + CP_MEM_TO_MEM = 115, + CP_BLIT = 44, + CP_REG_TEST = 57, + IN_IB_PREFETCH_END = 23, + IN_SUBBLK_PREFETCH = 31, + IN_INSTR_PREFETCH = 32, + IN_INSTR_MATCH = 71, + IN_CONST_PREFETCH = 73, + IN_INCR_UPDT_STATE = 85, + IN_INCR_UPDT_CONST = 86, + IN_INCR_UPDT_INSTR = 87, + PKT4 = 4, +}; + +enum adreno_state_block { + SB_VERT_TEX = 0, + SB_VERT_MIPADDR = 1, + SB_FRAG_TEX = 2, + SB_FRAG_MIPADDR = 3, + SB_VERT_SHADER = 4, + SB_GEOM_SHADER = 5, + SB_FRAG_SHADER = 6, + SB_COMPUTE_SHADER = 7, +}; + +enum adreno_state_type { + ST_SHADER = 0, + ST_CONSTANTS = 1, +}; + +enum adreno_state_src { + SS_DIRECT = 0, + SS_INVALID_ALL_IC = 2, + SS_INVALID_PART_IC = 3, + SS_INDIRECT = 4, + SS_INDIRECT_TCM = 5, + SS_INDIRECT_STM = 6, +}; + +enum a4xx_state_block { + SB4_VS_TEX = 0, + SB4_HS_TEX = 1, + SB4_DS_TEX = 2, + SB4_GS_TEX = 3, + SB4_FS_TEX = 4, + SB4_CS_TEX = 5, + SB4_VS_SHADER = 8, + SB4_HS_SHADER = 9, + SB4_DS_SHADER = 10, + SB4_GS_SHADER = 11, + SB4_FS_SHADER = 12, + SB4_CS_SHADER = 13, + SB4_SSBO = 14, + SB4_CS_SSBO = 15, +}; + +enum a4xx_state_type { + ST4_SHADER = 0, + ST4_CONSTANTS = 1, +}; + +enum a4xx_state_src { + SS4_DIRECT = 0, + SS4_INDIRECT = 2, +}; + +enum a4xx_index_size { + INDEX4_SIZE_8_BIT = 0, + INDEX4_SIZE_16_BIT = 1, + INDEX4_SIZE_32_BIT = 2, +}; + +enum cp_cond_function { + WRITE_ALWAYS = 0, + WRITE_LT = 1, + WRITE_LE = 2, + WRITE_EQ = 3, + WRITE_NE = 4, + WRITE_GE = 5, + WRITE_GT = 6, +}; + +enum render_mode_cmd { + BYPASS = 1, + BINNING = 2, + GMEM = 3, + BLIT2D = 5, + BLIT2DSCALE = 7, + END2D = 8, +}; + +enum cp_blit_cmd { + BLIT_OP_FILL = 0, + BLIT_OP_COPY = 1, + BLIT_OP_SCALE = 3, +}; + +#define REG_CP_LOAD_STATE_0 0x00000000 +#define CP_LOAD_STATE_0_DST_OFF__MASK 0x0000ffff +#define CP_LOAD_STATE_0_DST_OFF__SHIFT 0 +static inline uint32_t CP_LOAD_STATE_0_DST_OFF(uint32_t val) +{ + return ((val) << CP_LOAD_STATE_0_DST_OFF__SHIFT) & CP_LOAD_STATE_0_DST_OFF__MASK; +} +#define CP_LOAD_STATE_0_STATE_SRC__MASK 0x00070000 +#define CP_LOAD_STATE_0_STATE_SRC__SHIFT 16 +static inline uint32_t CP_LOAD_STATE_0_STATE_SRC(enum adreno_state_src val) +{ + return ((val) << CP_LOAD_STATE_0_STATE_SRC__SHIFT) & CP_LOAD_STATE_0_STATE_SRC__MASK; +} +#define CP_LOAD_STATE_0_STATE_BLOCK__MASK 0x00380000 +#define CP_LOAD_STATE_0_STATE_BLOCK__SHIFT 19 +static inline uint32_t CP_LOAD_STATE_0_STATE_BLOCK(enum adreno_state_block val) +{ + return ((val) << CP_LOAD_STATE_0_STATE_BLOCK__SHIFT) & CP_LOAD_STATE_0_STATE_BLOCK__MASK; +} +#define CP_LOAD_STATE_0_NUM_UNIT__MASK 0xffc00000 +#define CP_LOAD_STATE_0_NUM_UNIT__SHIFT 22 +static inline uint32_t CP_LOAD_STATE_0_NUM_UNIT(uint32_t val) +{ + return ((val) << CP_LOAD_STATE_0_NUM_UNIT__SHIFT) & CP_LOAD_STATE_0_NUM_UNIT__MASK; +} + +#define REG_CP_LOAD_STATE_1 0x00000001 +#define CP_LOAD_STATE_1_STATE_TYPE__MASK 0x00000003 +#define CP_LOAD_STATE_1_STATE_TYPE__SHIFT 0 +static inline uint32_t CP_LOAD_STATE_1_STATE_TYPE(enum adreno_state_type val) +{ + return ((val) << CP_LOAD_STATE_1_STATE_TYPE__SHIFT) & CP_LOAD_STATE_1_STATE_TYPE__MASK; +} +#define CP_LOAD_STATE_1_EXT_SRC_ADDR__MASK 0xfffffffc +#define CP_LOAD_STATE_1_EXT_SRC_ADDR__SHIFT 2 +static inline uint32_t CP_LOAD_STATE_1_EXT_SRC_ADDR(uint32_t val) +{ + assert(!(val & 0x3)); + return ((val >> 2) << CP_LOAD_STATE_1_EXT_SRC_ADDR__SHIFT) & CP_LOAD_STATE_1_EXT_SRC_ADDR__MASK; +} + +#define REG_CP_LOAD_STATE4_0 0x00000000 +#define CP_LOAD_STATE4_0_DST_OFF__MASK 0x00003fff +#define CP_LOAD_STATE4_0_DST_OFF__SHIFT 0 +static inline uint32_t CP_LOAD_STATE4_0_DST_OFF(uint32_t val) +{ + return ((val) << CP_LOAD_STATE4_0_DST_OFF__SHIFT) & CP_LOAD_STATE4_0_DST_OFF__MASK; +} +#define CP_LOAD_STATE4_0_STATE_SRC__MASK 0x00030000 +#define CP_LOAD_STATE4_0_STATE_SRC__SHIFT 16 +static inline uint32_t CP_LOAD_STATE4_0_STATE_SRC(enum a4xx_state_src val) +{ + return ((val) << CP_LOAD_STATE4_0_STATE_SRC__SHIFT) & CP_LOAD_STATE4_0_STATE_SRC__MASK; +} +#define CP_LOAD_STATE4_0_STATE_BLOCK__MASK 0x003c0000 +#define CP_LOAD_STATE4_0_STATE_BLOCK__SHIFT 18 +static inline uint32_t CP_LOAD_STATE4_0_STATE_BLOCK(enum a4xx_state_block val) +{ + return ((val) << CP_LOAD_STATE4_0_STATE_BLOCK__SHIFT) & CP_LOAD_STATE4_0_STATE_BLOCK__MASK; +} +#define CP_LOAD_STATE4_0_NUM_UNIT__MASK 0xffc00000 +#define CP_LOAD_STATE4_0_NUM_UNIT__SHIFT 22 +static inline uint32_t CP_LOAD_STATE4_0_NUM_UNIT(uint32_t val) +{ + return ((val) << CP_LOAD_STATE4_0_NUM_UNIT__SHIFT) & CP_LOAD_STATE4_0_NUM_UNIT__MASK; +} + +#define REG_CP_LOAD_STATE4_1 0x00000001 +#define CP_LOAD_STATE4_1_STATE_TYPE__MASK 0x00000003 +#define CP_LOAD_STATE4_1_STATE_TYPE__SHIFT 0 +static inline uint32_t CP_LOAD_STATE4_1_STATE_TYPE(enum a4xx_state_type val) +{ + return ((val) << CP_LOAD_STATE4_1_STATE_TYPE__SHIFT) & CP_LOAD_STATE4_1_STATE_TYPE__MASK; +} +#define CP_LOAD_STATE4_1_EXT_SRC_ADDR__MASK 0xfffffffc +#define CP_LOAD_STATE4_1_EXT_SRC_ADDR__SHIFT 2 +static inline uint32_t CP_LOAD_STATE4_1_EXT_SRC_ADDR(uint32_t val) +{ + assert(!(val & 0x3)); + return ((val >> 2) << CP_LOAD_STATE4_1_EXT_SRC_ADDR__SHIFT) & CP_LOAD_STATE4_1_EXT_SRC_ADDR__MASK; +} + +#define REG_CP_LOAD_STATE4_2 0x00000002 +#define CP_LOAD_STATE4_2_EXT_SRC_ADDR_HI__MASK 0xffffffff +#define CP_LOAD_STATE4_2_EXT_SRC_ADDR_HI__SHIFT 0 +static inline uint32_t CP_LOAD_STATE4_2_EXT_SRC_ADDR_HI(uint32_t val) +{ + return ((val) << CP_LOAD_STATE4_2_EXT_SRC_ADDR_HI__SHIFT) & CP_LOAD_STATE4_2_EXT_SRC_ADDR_HI__MASK; +} + +#define REG_CP_DRAW_INDX_0 0x00000000 +#define CP_DRAW_INDX_0_VIZ_QUERY__MASK 0xffffffff +#define CP_DRAW_INDX_0_VIZ_QUERY__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_0_VIZ_QUERY(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_0_VIZ_QUERY__SHIFT) & CP_DRAW_INDX_0_VIZ_QUERY__MASK; +} + +#define REG_CP_DRAW_INDX_1 0x00000001 +#define CP_DRAW_INDX_1_PRIM_TYPE__MASK 0x0000003f +#define CP_DRAW_INDX_1_PRIM_TYPE__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_1_PRIM_TYPE(enum pc_di_primtype val) +{ + return ((val) << CP_DRAW_INDX_1_PRIM_TYPE__SHIFT) & CP_DRAW_INDX_1_PRIM_TYPE__MASK; +} +#define CP_DRAW_INDX_1_SOURCE_SELECT__MASK 0x000000c0 +#define CP_DRAW_INDX_1_SOURCE_SELECT__SHIFT 6 +static inline uint32_t CP_DRAW_INDX_1_SOURCE_SELECT(enum pc_di_src_sel val) +{ + return ((val) << CP_DRAW_INDX_1_SOURCE_SELECT__SHIFT) & CP_DRAW_INDX_1_SOURCE_SELECT__MASK; +} +#define CP_DRAW_INDX_1_VIS_CULL__MASK 0x00000600 +#define CP_DRAW_INDX_1_VIS_CULL__SHIFT 9 +static inline uint32_t CP_DRAW_INDX_1_VIS_CULL(enum pc_di_vis_cull_mode val) +{ + return ((val) << CP_DRAW_INDX_1_VIS_CULL__SHIFT) & CP_DRAW_INDX_1_VIS_CULL__MASK; +} +#define CP_DRAW_INDX_1_INDEX_SIZE__MASK 0x00000800 +#define CP_DRAW_INDX_1_INDEX_SIZE__SHIFT 11 +static inline uint32_t CP_DRAW_INDX_1_INDEX_SIZE(enum pc_di_index_size val) +{ + return ((val) << CP_DRAW_INDX_1_INDEX_SIZE__SHIFT) & CP_DRAW_INDX_1_INDEX_SIZE__MASK; +} +#define CP_DRAW_INDX_1_NOT_EOP 0x00001000 +#define CP_DRAW_INDX_1_SMALL_INDEX 0x00002000 +#define CP_DRAW_INDX_1_PRE_DRAW_INITIATOR_ENABLE 0x00004000 +#define CP_DRAW_INDX_1_NUM_INSTANCES__MASK 0xff000000 +#define CP_DRAW_INDX_1_NUM_INSTANCES__SHIFT 24 +static inline uint32_t CP_DRAW_INDX_1_NUM_INSTANCES(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_1_NUM_INSTANCES__SHIFT) & CP_DRAW_INDX_1_NUM_INSTANCES__MASK; +} + +#define REG_CP_DRAW_INDX_2 0x00000002 +#define CP_DRAW_INDX_2_NUM_INDICES__MASK 0xffffffff +#define CP_DRAW_INDX_2_NUM_INDICES__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_2_NUM_INDICES(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_2_NUM_INDICES__SHIFT) & CP_DRAW_INDX_2_NUM_INDICES__MASK; +} + +#define REG_CP_DRAW_INDX_3 0x00000003 +#define CP_DRAW_INDX_3_INDX_BASE__MASK 0xffffffff +#define CP_DRAW_INDX_3_INDX_BASE__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_3_INDX_BASE(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_3_INDX_BASE__SHIFT) & CP_DRAW_INDX_3_INDX_BASE__MASK; +} + +#define REG_CP_DRAW_INDX_4 0x00000004 +#define CP_DRAW_INDX_4_INDX_SIZE__MASK 0xffffffff +#define CP_DRAW_INDX_4_INDX_SIZE__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_4_INDX_SIZE(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_4_INDX_SIZE__SHIFT) & CP_DRAW_INDX_4_INDX_SIZE__MASK; +} + +#define REG_CP_DRAW_INDX_2_0 0x00000000 +#define CP_DRAW_INDX_2_0_VIZ_QUERY__MASK 0xffffffff +#define CP_DRAW_INDX_2_0_VIZ_QUERY__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_2_0_VIZ_QUERY(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_2_0_VIZ_QUERY__SHIFT) & CP_DRAW_INDX_2_0_VIZ_QUERY__MASK; +} + +#define REG_CP_DRAW_INDX_2_1 0x00000001 +#define CP_DRAW_INDX_2_1_PRIM_TYPE__MASK 0x0000003f +#define CP_DRAW_INDX_2_1_PRIM_TYPE__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_2_1_PRIM_TYPE(enum pc_di_primtype val) +{ + return ((val) << CP_DRAW_INDX_2_1_PRIM_TYPE__SHIFT) & CP_DRAW_INDX_2_1_PRIM_TYPE__MASK; +} +#define CP_DRAW_INDX_2_1_SOURCE_SELECT__MASK 0x000000c0 +#define CP_DRAW_INDX_2_1_SOURCE_SELECT__SHIFT 6 +static inline uint32_t CP_DRAW_INDX_2_1_SOURCE_SELECT(enum pc_di_src_sel val) +{ + return ((val) << CP_DRAW_INDX_2_1_SOURCE_SELECT__SHIFT) & CP_DRAW_INDX_2_1_SOURCE_SELECT__MASK; +} +#define CP_DRAW_INDX_2_1_VIS_CULL__MASK 0x00000600 +#define CP_DRAW_INDX_2_1_VIS_CULL__SHIFT 9 +static inline uint32_t CP_DRAW_INDX_2_1_VIS_CULL(enum pc_di_vis_cull_mode val) +{ + return ((val) << CP_DRAW_INDX_2_1_VIS_CULL__SHIFT) & CP_DRAW_INDX_2_1_VIS_CULL__MASK; +} +#define CP_DRAW_INDX_2_1_INDEX_SIZE__MASK 0x00000800 +#define CP_DRAW_INDX_2_1_INDEX_SIZE__SHIFT 11 +static inline uint32_t CP_DRAW_INDX_2_1_INDEX_SIZE(enum pc_di_index_size val) +{ + return ((val) << CP_DRAW_INDX_2_1_INDEX_SIZE__SHIFT) & CP_DRAW_INDX_2_1_INDEX_SIZE__MASK; +} +#define CP_DRAW_INDX_2_1_NOT_EOP 0x00001000 +#define CP_DRAW_INDX_2_1_SMALL_INDEX 0x00002000 +#define CP_DRAW_INDX_2_1_PRE_DRAW_INITIATOR_ENABLE 0x00004000 +#define CP_DRAW_INDX_2_1_NUM_INSTANCES__MASK 0xff000000 +#define CP_DRAW_INDX_2_1_NUM_INSTANCES__SHIFT 24 +static inline uint32_t CP_DRAW_INDX_2_1_NUM_INSTANCES(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_2_1_NUM_INSTANCES__SHIFT) & CP_DRAW_INDX_2_1_NUM_INSTANCES__MASK; +} + +#define REG_CP_DRAW_INDX_2_2 0x00000002 +#define CP_DRAW_INDX_2_2_NUM_INDICES__MASK 0xffffffff +#define CP_DRAW_INDX_2_2_NUM_INDICES__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_2_2_NUM_INDICES(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_2_2_NUM_INDICES__SHIFT) & CP_DRAW_INDX_2_2_NUM_INDICES__MASK; +} + +#define REG_CP_DRAW_INDX_OFFSET_0 0x00000000 +#define CP_DRAW_INDX_OFFSET_0_PRIM_TYPE__MASK 0x0000003f +#define CP_DRAW_INDX_OFFSET_0_PRIM_TYPE__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_OFFSET_0_PRIM_TYPE(enum pc_di_primtype val) +{ + return ((val) << CP_DRAW_INDX_OFFSET_0_PRIM_TYPE__SHIFT) & CP_DRAW_INDX_OFFSET_0_PRIM_TYPE__MASK; +} +#define CP_DRAW_INDX_OFFSET_0_SOURCE_SELECT__MASK 0x000000c0 +#define CP_DRAW_INDX_OFFSET_0_SOURCE_SELECT__SHIFT 6 +static inline uint32_t CP_DRAW_INDX_OFFSET_0_SOURCE_SELECT(enum pc_di_src_sel val) +{ + return ((val) << CP_DRAW_INDX_OFFSET_0_SOURCE_SELECT__SHIFT) & CP_DRAW_INDX_OFFSET_0_SOURCE_SELECT__MASK; +} +#define CP_DRAW_INDX_OFFSET_0_VIS_CULL__MASK 0x00000300 +#define CP_DRAW_INDX_OFFSET_0_VIS_CULL__SHIFT 8 +static inline uint32_t CP_DRAW_INDX_OFFSET_0_VIS_CULL(enum pc_di_vis_cull_mode val) +{ + return ((val) << CP_DRAW_INDX_OFFSET_0_VIS_CULL__SHIFT) & CP_DRAW_INDX_OFFSET_0_VIS_CULL__MASK; +} +#define CP_DRAW_INDX_OFFSET_0_INDEX_SIZE__MASK 0x00000c00 +#define CP_DRAW_INDX_OFFSET_0_INDEX_SIZE__SHIFT 10 +static inline uint32_t CP_DRAW_INDX_OFFSET_0_INDEX_SIZE(enum a4xx_index_size val) +{ + return ((val) << CP_DRAW_INDX_OFFSET_0_INDEX_SIZE__SHIFT) & CP_DRAW_INDX_OFFSET_0_INDEX_SIZE__MASK; +} +#define CP_DRAW_INDX_OFFSET_0_TESS_MODE__MASK 0x01f00000 +#define CP_DRAW_INDX_OFFSET_0_TESS_MODE__SHIFT 20 +static inline uint32_t CP_DRAW_INDX_OFFSET_0_TESS_MODE(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_OFFSET_0_TESS_MODE__SHIFT) & CP_DRAW_INDX_OFFSET_0_TESS_MODE__MASK; +} + +#define REG_CP_DRAW_INDX_OFFSET_1 0x00000001 +#define CP_DRAW_INDX_OFFSET_1_NUM_INSTANCES__MASK 0xffffffff +#define CP_DRAW_INDX_OFFSET_1_NUM_INSTANCES__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_OFFSET_1_NUM_INSTANCES(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_OFFSET_1_NUM_INSTANCES__SHIFT) & CP_DRAW_INDX_OFFSET_1_NUM_INSTANCES__MASK; +} + +#define REG_CP_DRAW_INDX_OFFSET_2 0x00000002 +#define CP_DRAW_INDX_OFFSET_2_NUM_INDICES__MASK 0xffffffff +#define CP_DRAW_INDX_OFFSET_2_NUM_INDICES__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_OFFSET_2_NUM_INDICES(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_OFFSET_2_NUM_INDICES__SHIFT) & CP_DRAW_INDX_OFFSET_2_NUM_INDICES__MASK; +} + +#define REG_CP_DRAW_INDX_OFFSET_3 0x00000003 + +#define REG_CP_DRAW_INDX_OFFSET_4 0x00000004 +#define CP_DRAW_INDX_OFFSET_4_INDX_BASE__MASK 0xffffffff +#define CP_DRAW_INDX_OFFSET_4_INDX_BASE__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_OFFSET_4_INDX_BASE(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_OFFSET_4_INDX_BASE__SHIFT) & CP_DRAW_INDX_OFFSET_4_INDX_BASE__MASK; +} + +#define REG_CP_DRAW_INDX_OFFSET_5 0x00000005 +#define CP_DRAW_INDX_OFFSET_5_INDX_SIZE__MASK 0xffffffff +#define CP_DRAW_INDX_OFFSET_5_INDX_SIZE__SHIFT 0 +static inline uint32_t CP_DRAW_INDX_OFFSET_5_INDX_SIZE(uint32_t val) +{ + return ((val) << CP_DRAW_INDX_OFFSET_5_INDX_SIZE__SHIFT) & CP_DRAW_INDX_OFFSET_5_INDX_SIZE__MASK; +} + +#define REG_A4XX_CP_DRAW_INDIRECT_0 0x00000000 +#define A4XX_CP_DRAW_INDIRECT_0_PRIM_TYPE__MASK 0x0000003f +#define A4XX_CP_DRAW_INDIRECT_0_PRIM_TYPE__SHIFT 0 +static inline uint32_t A4XX_CP_DRAW_INDIRECT_0_PRIM_TYPE(enum pc_di_primtype val) +{ + return ((val) << A4XX_CP_DRAW_INDIRECT_0_PRIM_TYPE__SHIFT) & A4XX_CP_DRAW_INDIRECT_0_PRIM_TYPE__MASK; +} +#define A4XX_CP_DRAW_INDIRECT_0_SOURCE_SELECT__MASK 0x000000c0 +#define A4XX_CP_DRAW_INDIRECT_0_SOURCE_SELECT__SHIFT 6 +static inline uint32_t A4XX_CP_DRAW_INDIRECT_0_SOURCE_SELECT(enum pc_di_src_sel val) +{ + return ((val) << A4XX_CP_DRAW_INDIRECT_0_SOURCE_SELECT__SHIFT) & A4XX_CP_DRAW_INDIRECT_0_SOURCE_SELECT__MASK; +} +#define A4XX_CP_DRAW_INDIRECT_0_VIS_CULL__MASK 0x00000300 +#define A4XX_CP_DRAW_INDIRECT_0_VIS_CULL__SHIFT 8 +static inline uint32_t A4XX_CP_DRAW_INDIRECT_0_VIS_CULL(enum pc_di_vis_cull_mode val) +{ + return ((val) << A4XX_CP_DRAW_INDIRECT_0_VIS_CULL__SHIFT) & A4XX_CP_DRAW_INDIRECT_0_VIS_CULL__MASK; +} +#define A4XX_CP_DRAW_INDIRECT_0_INDEX_SIZE__MASK 0x00000c00 +#define A4XX_CP_DRAW_INDIRECT_0_INDEX_SIZE__SHIFT 10 +static inline uint32_t A4XX_CP_DRAW_INDIRECT_0_INDEX_SIZE(enum a4xx_index_size val) +{ + return ((val) << A4XX_CP_DRAW_INDIRECT_0_INDEX_SIZE__SHIFT) & A4XX_CP_DRAW_INDIRECT_0_INDEX_SIZE__MASK; +} +#define A4XX_CP_DRAW_INDIRECT_0_TESS_MODE__MASK 0x01f00000 +#define A4XX_CP_DRAW_INDIRECT_0_TESS_MODE__SHIFT 20 +static inline uint32_t A4XX_CP_DRAW_INDIRECT_0_TESS_MODE(uint32_t val) +{ + return ((val) << A4XX_CP_DRAW_INDIRECT_0_TESS_MODE__SHIFT) & A4XX_CP_DRAW_INDIRECT_0_TESS_MODE__MASK; +} + +#define REG_A4XX_CP_DRAW_INDIRECT_1 0x00000001 +#define A4XX_CP_DRAW_INDIRECT_1_INDIRECT__MASK 0xffffffff +#define A4XX_CP_DRAW_INDIRECT_1_INDIRECT__SHIFT 0 +static inline uint32_t A4XX_CP_DRAW_INDIRECT_1_INDIRECT(uint32_t val) +{ + return ((val) << A4XX_CP_DRAW_INDIRECT_1_INDIRECT__SHIFT) & A4XX_CP_DRAW_INDIRECT_1_INDIRECT__MASK; +} + + +#define REG_A5XX_CP_DRAW_INDIRECT_2 0x00000002 +#define A5XX_CP_DRAW_INDIRECT_2_INDIRECT_HI__MASK 0xffffffff +#define A5XX_CP_DRAW_INDIRECT_2_INDIRECT_HI__SHIFT 0 +static inline uint32_t A5XX_CP_DRAW_INDIRECT_2_INDIRECT_HI(uint32_t val) +{ + return ((val) << A5XX_CP_DRAW_INDIRECT_2_INDIRECT_HI__SHIFT) & A5XX_CP_DRAW_INDIRECT_2_INDIRECT_HI__MASK; +} + +#define REG_A4XX_CP_DRAW_INDX_INDIRECT_0 0x00000000 +#define A4XX_CP_DRAW_INDX_INDIRECT_0_PRIM_TYPE__MASK 0x0000003f +#define A4XX_CP_DRAW_INDX_INDIRECT_0_PRIM_TYPE__SHIFT 0 +static inline uint32_t A4XX_CP_DRAW_INDX_INDIRECT_0_PRIM_TYPE(enum pc_di_primtype val) +{ + return ((val) << A4XX_CP_DRAW_INDX_INDIRECT_0_PRIM_TYPE__SHIFT) & A4XX_CP_DRAW_INDX_INDIRECT_0_PRIM_TYPE__MASK; +} +#define A4XX_CP_DRAW_INDX_INDIRECT_0_SOURCE_SELECT__MASK 0x000000c0 +#define A4XX_CP_DRAW_INDX_INDIRECT_0_SOURCE_SELECT__SHIFT 6 +static inline uint32_t A4XX_CP_DRAW_INDX_INDIRECT_0_SOURCE_SELECT(enum pc_di_src_sel val) +{ + return ((val) << A4XX_CP_DRAW_INDX_INDIRECT_0_SOURCE_SELECT__SHIFT) & A4XX_CP_DRAW_INDX_INDIRECT_0_SOURCE_SELECT__MASK; +} +#define A4XX_CP_DRAW_INDX_INDIRECT_0_VIS_CULL__MASK 0x00000300 +#define A4XX_CP_DRAW_INDX_INDIRECT_0_VIS_CULL__SHIFT 8 +static inline uint32_t A4XX_CP_DRAW_INDX_INDIRECT_0_VIS_CULL(enum pc_di_vis_cull_mode val) +{ + return ((val) << A4XX_CP_DRAW_INDX_INDIRECT_0_VIS_CULL__SHIFT) & A4XX_CP_DRAW_INDX_INDIRECT_0_VIS_CULL__MASK; +} +#define A4XX_CP_DRAW_INDX_INDIRECT_0_INDEX_SIZE__MASK 0x00000c00 +#define A4XX_CP_DRAW_INDX_INDIRECT_0_INDEX_SIZE__SHIFT 10 +static inline uint32_t A4XX_CP_DRAW_INDX_INDIRECT_0_INDEX_SIZE(enum a4xx_index_size val) +{ + return ((val) << A4XX_CP_DRAW_INDX_INDIRECT_0_INDEX_SIZE__SHIFT) & A4XX_CP_DRAW_INDX_INDIRECT_0_INDEX_SIZE__MASK; +} +#define A4XX_CP_DRAW_INDX_INDIRECT_0_TESS_MODE__MASK 0x01f00000 +#define A4XX_CP_DRAW_INDX_INDIRECT_0_TESS_MODE__SHIFT 20 +static inline uint32_t A4XX_CP_DRAW_INDX_INDIRECT_0_TESS_MODE(uint32_t val) +{ + return ((val) << A4XX_CP_DRAW_INDX_INDIRECT_0_TESS_MODE__SHIFT) & A4XX_CP_DRAW_INDX_INDIRECT_0_TESS_MODE__MASK; +} + + +#define REG_A4XX_CP_DRAW_INDX_INDIRECT_1 0x00000001 +#define A4XX_CP_DRAW_INDX_INDIRECT_1_INDX_BASE__MASK 0xffffffff +#define A4XX_CP_DRAW_INDX_INDIRECT_1_INDX_BASE__SHIFT 0 +static inline uint32_t A4XX_CP_DRAW_INDX_INDIRECT_1_INDX_BASE(uint32_t val) +{ + return ((val) << A4XX_CP_DRAW_INDX_INDIRECT_1_INDX_BASE__SHIFT) & A4XX_CP_DRAW_INDX_INDIRECT_1_INDX_BASE__MASK; +} + +#define REG_A4XX_CP_DRAW_INDX_INDIRECT_2 0x00000002 +#define A4XX_CP_DRAW_INDX_INDIRECT_2_INDX_SIZE__MASK 0xffffffff +#define A4XX_CP_DRAW_INDX_INDIRECT_2_INDX_SIZE__SHIFT 0 +static inline uint32_t A4XX_CP_DRAW_INDX_INDIRECT_2_INDX_SIZE(uint32_t val) +{ + return ((val) << A4XX_CP_DRAW_INDX_INDIRECT_2_INDX_SIZE__SHIFT) & A4XX_CP_DRAW_INDX_INDIRECT_2_INDX_SIZE__MASK; +} + +#define REG_A4XX_CP_DRAW_INDX_INDIRECT_3 0x00000003 +#define A4XX_CP_DRAW_INDX_INDIRECT_3_INDIRECT__MASK 0xffffffff +#define A4XX_CP_DRAW_INDX_INDIRECT_3_INDIRECT__SHIFT 0 +static inline uint32_t A4XX_CP_DRAW_INDX_INDIRECT_3_INDIRECT(uint32_t val) +{ + return ((val) << A4XX_CP_DRAW_INDX_INDIRECT_3_INDIRECT__SHIFT) & A4XX_CP_DRAW_INDX_INDIRECT_3_INDIRECT__MASK; +} + + +#define REG_A5XX_CP_DRAW_INDX_INDIRECT_1 0x00000001 +#define A5XX_CP_DRAW_INDX_INDIRECT_1_INDX_BASE_LO__MASK 0xffffffff +#define A5XX_CP_DRAW_INDX_INDIRECT_1_INDX_BASE_LO__SHIFT 0 +static inline uint32_t A5XX_CP_DRAW_INDX_INDIRECT_1_INDX_BASE_LO(uint32_t val) +{ + return ((val) << A5XX_CP_DRAW_INDX_INDIRECT_1_INDX_BASE_LO__SHIFT) & A5XX_CP_DRAW_INDX_INDIRECT_1_INDX_BASE_LO__MASK; +} + +#define REG_A5XX_CP_DRAW_INDX_INDIRECT_2 0x00000002 +#define A5XX_CP_DRAW_INDX_INDIRECT_2_INDX_BASE_HI__MASK 0xffffffff +#define A5XX_CP_DRAW_INDX_INDIRECT_2_INDX_BASE_HI__SHIFT 0 +static inline uint32_t A5XX_CP_DRAW_INDX_INDIRECT_2_INDX_BASE_HI(uint32_t val) +{ + return ((val) << A5XX_CP_DRAW_INDX_INDIRECT_2_INDX_BASE_HI__SHIFT) & A5XX_CP_DRAW_INDX_INDIRECT_2_INDX_BASE_HI__MASK; +} + +#define REG_A5XX_CP_DRAW_INDX_INDIRECT_3 0x00000003 +#define A5XX_CP_DRAW_INDX_INDIRECT_3_MAX_INDICES__MASK 0xffffffff +#define A5XX_CP_DRAW_INDX_INDIRECT_3_MAX_INDICES__SHIFT 0 +static inline uint32_t A5XX_CP_DRAW_INDX_INDIRECT_3_MAX_INDICES(uint32_t val) +{ + return ((val) << A5XX_CP_DRAW_INDX_INDIRECT_3_MAX_INDICES__SHIFT) & A5XX_CP_DRAW_INDX_INDIRECT_3_MAX_INDICES__MASK; +} + +#define REG_A5XX_CP_DRAW_INDX_INDIRECT_4 0x00000004 +#define A5XX_CP_DRAW_INDX_INDIRECT_4_INDIRECT_LO__MASK 0xffffffff +#define A5XX_CP_DRAW_INDX_INDIRECT_4_INDIRECT_LO__SHIFT 0 +static inline uint32_t A5XX_CP_DRAW_INDX_INDIRECT_4_INDIRECT_LO(uint32_t val) +{ + return ((val) << A5XX_CP_DRAW_INDX_INDIRECT_4_INDIRECT_LO__SHIFT) & A5XX_CP_DRAW_INDX_INDIRECT_4_INDIRECT_LO__MASK; +} + +#define REG_A5XX_CP_DRAW_INDX_INDIRECT_5 0x00000005 +#define A5XX_CP_DRAW_INDX_INDIRECT_5_INDIRECT_HI__MASK 0xffffffff +#define A5XX_CP_DRAW_INDX_INDIRECT_5_INDIRECT_HI__SHIFT 0 +static inline uint32_t A5XX_CP_DRAW_INDX_INDIRECT_5_INDIRECT_HI(uint32_t val) +{ + return ((val) << A5XX_CP_DRAW_INDX_INDIRECT_5_INDIRECT_HI__SHIFT) & A5XX_CP_DRAW_INDX_INDIRECT_5_INDIRECT_HI__MASK; +} + +static inline uint32_t REG_CP_SET_DRAW_STATE_(uint32_t i0) { return 0x00000000 + 0x3*i0; } + +static inline uint32_t REG_CP_SET_DRAW_STATE__0(uint32_t i0) { return 0x00000000 + 0x3*i0; } +#define CP_SET_DRAW_STATE__0_COUNT__MASK 0x0000ffff +#define CP_SET_DRAW_STATE__0_COUNT__SHIFT 0 +static inline uint32_t CP_SET_DRAW_STATE__0_COUNT(uint32_t val) +{ + return ((val) << CP_SET_DRAW_STATE__0_COUNT__SHIFT) & CP_SET_DRAW_STATE__0_COUNT__MASK; +} +#define CP_SET_DRAW_STATE__0_DIRTY 0x00010000 +#define CP_SET_DRAW_STATE__0_DISABLE 0x00020000 +#define CP_SET_DRAW_STATE__0_DISABLE_ALL_GROUPS 0x00040000 +#define CP_SET_DRAW_STATE__0_LOAD_IMMED 0x00080000 +#define CP_SET_DRAW_STATE__0_GROUP_ID__MASK 0x1f000000 +#define CP_SET_DRAW_STATE__0_GROUP_ID__SHIFT 24 +static inline uint32_t CP_SET_DRAW_STATE__0_GROUP_ID(uint32_t val) +{ + return ((val) << CP_SET_DRAW_STATE__0_GROUP_ID__SHIFT) & CP_SET_DRAW_STATE__0_GROUP_ID__MASK; +} + +static inline uint32_t REG_CP_SET_DRAW_STATE__1(uint32_t i0) { return 0x00000001 + 0x3*i0; } +#define CP_SET_DRAW_STATE__1_ADDR_LO__MASK 0xffffffff +#define CP_SET_DRAW_STATE__1_ADDR_LO__SHIFT 0 +static inline uint32_t CP_SET_DRAW_STATE__1_ADDR_LO(uint32_t val) +{ + return ((val) << CP_SET_DRAW_STATE__1_ADDR_LO__SHIFT) & CP_SET_DRAW_STATE__1_ADDR_LO__MASK; +} + +static inline uint32_t REG_CP_SET_DRAW_STATE__2(uint32_t i0) { return 0x00000002 + 0x3*i0; } +#define CP_SET_DRAW_STATE__2_ADDR_HI__MASK 0xffffffff +#define CP_SET_DRAW_STATE__2_ADDR_HI__SHIFT 0 +static inline uint32_t CP_SET_DRAW_STATE__2_ADDR_HI(uint32_t val) +{ + return ((val) << CP_SET_DRAW_STATE__2_ADDR_HI__SHIFT) & CP_SET_DRAW_STATE__2_ADDR_HI__MASK; +} + +#define REG_CP_SET_BIN_0 0x00000000 + +#define REG_CP_SET_BIN_1 0x00000001 +#define CP_SET_BIN_1_X1__MASK 0x0000ffff +#define CP_SET_BIN_1_X1__SHIFT 0 +static inline uint32_t CP_SET_BIN_1_X1(uint32_t val) +{ + return ((val) << CP_SET_BIN_1_X1__SHIFT) & CP_SET_BIN_1_X1__MASK; +} +#define CP_SET_BIN_1_Y1__MASK 0xffff0000 +#define CP_SET_BIN_1_Y1__SHIFT 16 +static inline uint32_t CP_SET_BIN_1_Y1(uint32_t val) +{ + return ((val) << CP_SET_BIN_1_Y1__SHIFT) & CP_SET_BIN_1_Y1__MASK; +} + +#define REG_CP_SET_BIN_2 0x00000002 +#define CP_SET_BIN_2_X2__MASK 0x0000ffff +#define CP_SET_BIN_2_X2__SHIFT 0 +static inline uint32_t CP_SET_BIN_2_X2(uint32_t val) +{ + return ((val) << CP_SET_BIN_2_X2__SHIFT) & CP_SET_BIN_2_X2__MASK; +} +#define CP_SET_BIN_2_Y2__MASK 0xffff0000 +#define CP_SET_BIN_2_Y2__SHIFT 16 +static inline uint32_t CP_SET_BIN_2_Y2(uint32_t val) +{ + return ((val) << CP_SET_BIN_2_Y2__SHIFT) & CP_SET_BIN_2_Y2__MASK; +} + +#define REG_CP_SET_BIN_DATA_0 0x00000000 +#define CP_SET_BIN_DATA_0_BIN_DATA_ADDR__MASK 0xffffffff +#define CP_SET_BIN_DATA_0_BIN_DATA_ADDR__SHIFT 0 +static inline uint32_t CP_SET_BIN_DATA_0_BIN_DATA_ADDR(uint32_t val) +{ + return ((val) << CP_SET_BIN_DATA_0_BIN_DATA_ADDR__SHIFT) & CP_SET_BIN_DATA_0_BIN_DATA_ADDR__MASK; +} + +#define REG_CP_SET_BIN_DATA_1 0x00000001 +#define CP_SET_BIN_DATA_1_BIN_SIZE_ADDRESS__MASK 0xffffffff +#define CP_SET_BIN_DATA_1_BIN_SIZE_ADDRESS__SHIFT 0 +static inline uint32_t CP_SET_BIN_DATA_1_BIN_SIZE_ADDRESS(uint32_t val) +{ + return ((val) << CP_SET_BIN_DATA_1_BIN_SIZE_ADDRESS__SHIFT) & CP_SET_BIN_DATA_1_BIN_SIZE_ADDRESS__MASK; +} + +#define REG_CP_SET_BIN_DATA5_0 0x00000000 +#define CP_SET_BIN_DATA5_0_VSC_SIZE__MASK 0x003f0000 +#define CP_SET_BIN_DATA5_0_VSC_SIZE__SHIFT 16 +static inline uint32_t CP_SET_BIN_DATA5_0_VSC_SIZE(uint32_t val) +{ + return ((val) << CP_SET_BIN_DATA5_0_VSC_SIZE__SHIFT) & CP_SET_BIN_DATA5_0_VSC_SIZE__MASK; +} +#define CP_SET_BIN_DATA5_0_VSC_N__MASK 0x07c00000 +#define CP_SET_BIN_DATA5_0_VSC_N__SHIFT 22 +static inline uint32_t CP_SET_BIN_DATA5_0_VSC_N(uint32_t val) +{ + return ((val) << CP_SET_BIN_DATA5_0_VSC_N__SHIFT) & CP_SET_BIN_DATA5_0_VSC_N__MASK; +} + +#define REG_CP_SET_BIN_DATA5_1 0x00000001 +#define CP_SET_BIN_DATA5_1_BIN_DATA_ADDR_LO__MASK 0xffffffff +#define CP_SET_BIN_DATA5_1_BIN_DATA_ADDR_LO__SHIFT 0 +static inline uint32_t CP_SET_BIN_DATA5_1_BIN_DATA_ADDR_LO(uint32_t val) +{ + return ((val) << CP_SET_BIN_DATA5_1_BIN_DATA_ADDR_LO__SHIFT) & CP_SET_BIN_DATA5_1_BIN_DATA_ADDR_LO__MASK; +} + +#define REG_CP_SET_BIN_DATA5_2 0x00000002 +#define CP_SET_BIN_DATA5_2_BIN_DATA_ADDR_HI__MASK 0xffffffff +#define CP_SET_BIN_DATA5_2_BIN_DATA_ADDR_HI__SHIFT 0 +static inline uint32_t CP_SET_BIN_DATA5_2_BIN_DATA_ADDR_HI(uint32_t val) +{ + return ((val) << CP_SET_BIN_DATA5_2_BIN_DATA_ADDR_HI__SHIFT) & CP_SET_BIN_DATA5_2_BIN_DATA_ADDR_HI__MASK; +} + +#define REG_CP_SET_BIN_DATA5_3 0x00000003 +#define CP_SET_BIN_DATA5_3_BIN_SIZE_ADDRESS_LO__MASK 0xffffffff +#define CP_SET_BIN_DATA5_3_BIN_SIZE_ADDRESS_LO__SHIFT 0 +static inline uint32_t CP_SET_BIN_DATA5_3_BIN_SIZE_ADDRESS_LO(uint32_t val) +{ + return ((val) << CP_SET_BIN_DATA5_3_BIN_SIZE_ADDRESS_LO__SHIFT) & CP_SET_BIN_DATA5_3_BIN_SIZE_ADDRESS_LO__MASK; +} + +#define REG_CP_SET_BIN_DATA5_4 0x00000004 +#define CP_SET_BIN_DATA5_4_BIN_SIZE_ADDRESS_HI__MASK 0xffffffff +#define CP_SET_BIN_DATA5_4_BIN_SIZE_ADDRESS_HI__SHIFT 0 +static inline uint32_t CP_SET_BIN_DATA5_4_BIN_SIZE_ADDRESS_HI(uint32_t val) +{ + return ((val) << CP_SET_BIN_DATA5_4_BIN_SIZE_ADDRESS_HI__SHIFT) & CP_SET_BIN_DATA5_4_BIN_SIZE_ADDRESS_HI__MASK; +} + +#define REG_CP_REG_TO_MEM_0 0x00000000 +#define CP_REG_TO_MEM_0_REG__MASK 0x0000ffff +#define CP_REG_TO_MEM_0_REG__SHIFT 0 +static inline uint32_t CP_REG_TO_MEM_0_REG(uint32_t val) +{ + return ((val) << CP_REG_TO_MEM_0_REG__SHIFT) & CP_REG_TO_MEM_0_REG__MASK; +} +#define CP_REG_TO_MEM_0_CNT__MASK 0x3ff80000 +#define CP_REG_TO_MEM_0_CNT__SHIFT 19 +static inline uint32_t CP_REG_TO_MEM_0_CNT(uint32_t val) +{ + return ((val) << CP_REG_TO_MEM_0_CNT__SHIFT) & CP_REG_TO_MEM_0_CNT__MASK; +} +#define CP_REG_TO_MEM_0_64B 0x40000000 +#define CP_REG_TO_MEM_0_ACCUMULATE 0x80000000 + +#define REG_CP_REG_TO_MEM_1 0x00000001 +#define CP_REG_TO_MEM_1_DEST__MASK 0xffffffff +#define CP_REG_TO_MEM_1_DEST__SHIFT 0 +static inline uint32_t CP_REG_TO_MEM_1_DEST(uint32_t val) +{ + return ((val) << CP_REG_TO_MEM_1_DEST__SHIFT) & CP_REG_TO_MEM_1_DEST__MASK; +} + +#define REG_CP_MEM_TO_MEM_0 0x00000000 +#define CP_MEM_TO_MEM_0_NEG_A 0x00000001 +#define CP_MEM_TO_MEM_0_NEG_B 0x00000002 +#define CP_MEM_TO_MEM_0_NEG_C 0x00000004 +#define CP_MEM_TO_MEM_0_DOUBLE 0x20000000 + +#define REG_CP_COND_WRITE_0 0x00000000 +#define CP_COND_WRITE_0_FUNCTION__MASK 0x00000007 +#define CP_COND_WRITE_0_FUNCTION__SHIFT 0 +static inline uint32_t CP_COND_WRITE_0_FUNCTION(enum cp_cond_function val) +{ + return ((val) << CP_COND_WRITE_0_FUNCTION__SHIFT) & CP_COND_WRITE_0_FUNCTION__MASK; +} +#define CP_COND_WRITE_0_POLL_MEMORY 0x00000010 +#define CP_COND_WRITE_0_WRITE_MEMORY 0x00000100 + +#define REG_CP_COND_WRITE_1 0x00000001 +#define CP_COND_WRITE_1_POLL_ADDR__MASK 0xffffffff +#define CP_COND_WRITE_1_POLL_ADDR__SHIFT 0 +static inline uint32_t CP_COND_WRITE_1_POLL_ADDR(uint32_t val) +{ + return ((val) << CP_COND_WRITE_1_POLL_ADDR__SHIFT) & CP_COND_WRITE_1_POLL_ADDR__MASK; +} + +#define REG_CP_COND_WRITE_2 0x00000002 +#define CP_COND_WRITE_2_REF__MASK 0xffffffff +#define CP_COND_WRITE_2_REF__SHIFT 0 +static inline uint32_t CP_COND_WRITE_2_REF(uint32_t val) +{ + return ((val) << CP_COND_WRITE_2_REF__SHIFT) & CP_COND_WRITE_2_REF__MASK; +} + +#define REG_CP_COND_WRITE_3 0x00000003 +#define CP_COND_WRITE_3_MASK__MASK 0xffffffff +#define CP_COND_WRITE_3_MASK__SHIFT 0 +static inline uint32_t CP_COND_WRITE_3_MASK(uint32_t val) +{ + return ((val) << CP_COND_WRITE_3_MASK__SHIFT) & CP_COND_WRITE_3_MASK__MASK; +} + +#define REG_CP_COND_WRITE_4 0x00000004 +#define CP_COND_WRITE_4_WRITE_ADDR__MASK 0xffffffff +#define CP_COND_WRITE_4_WRITE_ADDR__SHIFT 0 +static inline uint32_t CP_COND_WRITE_4_WRITE_ADDR(uint32_t val) +{ + return ((val) << CP_COND_WRITE_4_WRITE_ADDR__SHIFT) & CP_COND_WRITE_4_WRITE_ADDR__MASK; +} + +#define REG_CP_COND_WRITE_5 0x00000005 +#define CP_COND_WRITE_5_WRITE_DATA__MASK 0xffffffff +#define CP_COND_WRITE_5_WRITE_DATA__SHIFT 0 +static inline uint32_t CP_COND_WRITE_5_WRITE_DATA(uint32_t val) +{ + return ((val) << CP_COND_WRITE_5_WRITE_DATA__SHIFT) & CP_COND_WRITE_5_WRITE_DATA__MASK; +} + +#define REG_CP_COND_WRITE5_0 0x00000000 +#define CP_COND_WRITE5_0_FUNCTION__MASK 0x00000007 +#define CP_COND_WRITE5_0_FUNCTION__SHIFT 0 +static inline uint32_t CP_COND_WRITE5_0_FUNCTION(enum cp_cond_function val) +{ + return ((val) << CP_COND_WRITE5_0_FUNCTION__SHIFT) & CP_COND_WRITE5_0_FUNCTION__MASK; +} +#define CP_COND_WRITE5_0_POLL_MEMORY 0x00000010 +#define CP_COND_WRITE5_0_WRITE_MEMORY 0x00000100 + +#define REG_CP_COND_WRITE5_1 0x00000001 +#define CP_COND_WRITE5_1_POLL_ADDR_LO__MASK 0xffffffff +#define CP_COND_WRITE5_1_POLL_ADDR_LO__SHIFT 0 +static inline uint32_t CP_COND_WRITE5_1_POLL_ADDR_LO(uint32_t val) +{ + return ((val) << CP_COND_WRITE5_1_POLL_ADDR_LO__SHIFT) & CP_COND_WRITE5_1_POLL_ADDR_LO__MASK; +} + +#define REG_CP_COND_WRITE5_2 0x00000002 +#define CP_COND_WRITE5_2_POLL_ADDR_HI__MASK 0xffffffff +#define CP_COND_WRITE5_2_POLL_ADDR_HI__SHIFT 0 +static inline uint32_t CP_COND_WRITE5_2_POLL_ADDR_HI(uint32_t val) +{ + return ((val) << CP_COND_WRITE5_2_POLL_ADDR_HI__SHIFT) & CP_COND_WRITE5_2_POLL_ADDR_HI__MASK; +} + +#define REG_CP_COND_WRITE5_3 0x00000003 +#define CP_COND_WRITE5_3_REF__MASK 0xffffffff +#define CP_COND_WRITE5_3_REF__SHIFT 0 +static inline uint32_t CP_COND_WRITE5_3_REF(uint32_t val) +{ + return ((val) << CP_COND_WRITE5_3_REF__SHIFT) & CP_COND_WRITE5_3_REF__MASK; +} + +#define REG_CP_COND_WRITE5_4 0x00000004 +#define CP_COND_WRITE5_4_MASK__MASK 0xffffffff +#define CP_COND_WRITE5_4_MASK__SHIFT 0 +static inline uint32_t CP_COND_WRITE5_4_MASK(uint32_t val) +{ + return ((val) << CP_COND_WRITE5_4_MASK__SHIFT) & CP_COND_WRITE5_4_MASK__MASK; +} + +#define REG_CP_COND_WRITE5_5 0x00000005 +#define CP_COND_WRITE5_5_WRITE_ADDR_LO__MASK 0xffffffff +#define CP_COND_WRITE5_5_WRITE_ADDR_LO__SHIFT 0 +static inline uint32_t CP_COND_WRITE5_5_WRITE_ADDR_LO(uint32_t val) +{ + return ((val) << CP_COND_WRITE5_5_WRITE_ADDR_LO__SHIFT) & CP_COND_WRITE5_5_WRITE_ADDR_LO__MASK; +} + +#define REG_CP_COND_WRITE5_6 0x00000006 +#define CP_COND_WRITE5_6_WRITE_ADDR_HI__MASK 0xffffffff +#define CP_COND_WRITE5_6_WRITE_ADDR_HI__SHIFT 0 +static inline uint32_t CP_COND_WRITE5_6_WRITE_ADDR_HI(uint32_t val) +{ + return ((val) << CP_COND_WRITE5_6_WRITE_ADDR_HI__SHIFT) & CP_COND_WRITE5_6_WRITE_ADDR_HI__MASK; +} + +#define REG_CP_COND_WRITE5_7 0x00000007 +#define CP_COND_WRITE5_7_WRITE_DATA__MASK 0xffffffff +#define CP_COND_WRITE5_7_WRITE_DATA__SHIFT 0 +static inline uint32_t CP_COND_WRITE5_7_WRITE_DATA(uint32_t val) +{ + return ((val) << CP_COND_WRITE5_7_WRITE_DATA__SHIFT) & CP_COND_WRITE5_7_WRITE_DATA__MASK; +} + +#define REG_CP_DISPATCH_COMPUTE_0 0x00000000 + +#define REG_CP_DISPATCH_COMPUTE_1 0x00000001 +#define CP_DISPATCH_COMPUTE_1_X__MASK 0xffffffff +#define CP_DISPATCH_COMPUTE_1_X__SHIFT 0 +static inline uint32_t CP_DISPATCH_COMPUTE_1_X(uint32_t val) +{ + return ((val) << CP_DISPATCH_COMPUTE_1_X__SHIFT) & CP_DISPATCH_COMPUTE_1_X__MASK; +} + +#define REG_CP_DISPATCH_COMPUTE_2 0x00000002 +#define CP_DISPATCH_COMPUTE_2_Y__MASK 0xffffffff +#define CP_DISPATCH_COMPUTE_2_Y__SHIFT 0 +static inline uint32_t CP_DISPATCH_COMPUTE_2_Y(uint32_t val) +{ + return ((val) << CP_DISPATCH_COMPUTE_2_Y__SHIFT) & CP_DISPATCH_COMPUTE_2_Y__MASK; +} + +#define REG_CP_DISPATCH_COMPUTE_3 0x00000003 +#define CP_DISPATCH_COMPUTE_3_Z__MASK 0xffffffff +#define CP_DISPATCH_COMPUTE_3_Z__SHIFT 0 +static inline uint32_t CP_DISPATCH_COMPUTE_3_Z(uint32_t val) +{ + return ((val) << CP_DISPATCH_COMPUTE_3_Z__SHIFT) & CP_DISPATCH_COMPUTE_3_Z__MASK; +} + +#define REG_CP_SET_RENDER_MODE_0 0x00000000 +#define CP_SET_RENDER_MODE_0_MODE__MASK 0x000001ff +#define CP_SET_RENDER_MODE_0_MODE__SHIFT 0 +static inline uint32_t CP_SET_RENDER_MODE_0_MODE(enum render_mode_cmd val) +{ + return ((val) << CP_SET_RENDER_MODE_0_MODE__SHIFT) & CP_SET_RENDER_MODE_0_MODE__MASK; +} + +#define REG_CP_SET_RENDER_MODE_1 0x00000001 +#define CP_SET_RENDER_MODE_1_ADDR_0_LO__MASK 0xffffffff +#define CP_SET_RENDER_MODE_1_ADDR_0_LO__SHIFT 0 +static inline uint32_t CP_SET_RENDER_MODE_1_ADDR_0_LO(uint32_t val) +{ + return ((val) << CP_SET_RENDER_MODE_1_ADDR_0_LO__SHIFT) & CP_SET_RENDER_MODE_1_ADDR_0_LO__MASK; +} + +#define REG_CP_SET_RENDER_MODE_2 0x00000002 +#define CP_SET_RENDER_MODE_2_ADDR_0_HI__MASK 0xffffffff +#define CP_SET_RENDER_MODE_2_ADDR_0_HI__SHIFT 0 +static inline uint32_t CP_SET_RENDER_MODE_2_ADDR_0_HI(uint32_t val) +{ + return ((val) << CP_SET_RENDER_MODE_2_ADDR_0_HI__SHIFT) & CP_SET_RENDER_MODE_2_ADDR_0_HI__MASK; +} + +#define REG_CP_SET_RENDER_MODE_3 0x00000003 +#define CP_SET_RENDER_MODE_3_VSC_ENABLE 0x00000008 +#define CP_SET_RENDER_MODE_3_GMEM_ENABLE 0x00000010 + +#define REG_CP_SET_RENDER_MODE_4 0x00000004 + +#define REG_CP_SET_RENDER_MODE_5 0x00000005 +#define CP_SET_RENDER_MODE_5_ADDR_1_LEN__MASK 0xffffffff +#define CP_SET_RENDER_MODE_5_ADDR_1_LEN__SHIFT 0 +static inline uint32_t CP_SET_RENDER_MODE_5_ADDR_1_LEN(uint32_t val) +{ + return ((val) << CP_SET_RENDER_MODE_5_ADDR_1_LEN__SHIFT) & CP_SET_RENDER_MODE_5_ADDR_1_LEN__MASK; +} + +#define REG_CP_SET_RENDER_MODE_6 0x00000006 +#define CP_SET_RENDER_MODE_6_ADDR_1_LO__MASK 0xffffffff +#define CP_SET_RENDER_MODE_6_ADDR_1_LO__SHIFT 0 +static inline uint32_t CP_SET_RENDER_MODE_6_ADDR_1_LO(uint32_t val) +{ + return ((val) << CP_SET_RENDER_MODE_6_ADDR_1_LO__SHIFT) & CP_SET_RENDER_MODE_6_ADDR_1_LO__MASK; +} + +#define REG_CP_SET_RENDER_MODE_7 0x00000007 +#define CP_SET_RENDER_MODE_7_ADDR_1_HI__MASK 0xffffffff +#define CP_SET_RENDER_MODE_7_ADDR_1_HI__SHIFT 0 +static inline uint32_t CP_SET_RENDER_MODE_7_ADDR_1_HI(uint32_t val) +{ + return ((val) << CP_SET_RENDER_MODE_7_ADDR_1_HI__SHIFT) & CP_SET_RENDER_MODE_7_ADDR_1_HI__MASK; +} + +#define REG_CP_COMPUTE_CHECKPOINT_0 0x00000000 +#define CP_COMPUTE_CHECKPOINT_0_ADDR_0_LO__MASK 0xffffffff +#define CP_COMPUTE_CHECKPOINT_0_ADDR_0_LO__SHIFT 0 +static inline uint32_t CP_COMPUTE_CHECKPOINT_0_ADDR_0_LO(uint32_t val) +{ + return ((val) << CP_COMPUTE_CHECKPOINT_0_ADDR_0_LO__SHIFT) & CP_COMPUTE_CHECKPOINT_0_ADDR_0_LO__MASK; +} + +#define REG_CP_COMPUTE_CHECKPOINT_1 0x00000001 +#define CP_COMPUTE_CHECKPOINT_1_ADDR_0_HI__MASK 0xffffffff +#define CP_COMPUTE_CHECKPOINT_1_ADDR_0_HI__SHIFT 0 +static inline uint32_t CP_COMPUTE_CHECKPOINT_1_ADDR_0_HI(uint32_t val) +{ + return ((val) << CP_COMPUTE_CHECKPOINT_1_ADDR_0_HI__SHIFT) & CP_COMPUTE_CHECKPOINT_1_ADDR_0_HI__MASK; +} + +#define REG_CP_COMPUTE_CHECKPOINT_2 0x00000002 + +#define REG_CP_COMPUTE_CHECKPOINT_3 0x00000003 +#define CP_COMPUTE_CHECKPOINT_3_ADDR_1_LEN__MASK 0xffffffff +#define CP_COMPUTE_CHECKPOINT_3_ADDR_1_LEN__SHIFT 0 +static inline uint32_t CP_COMPUTE_CHECKPOINT_3_ADDR_1_LEN(uint32_t val) +{ + return ((val) << CP_COMPUTE_CHECKPOINT_3_ADDR_1_LEN__SHIFT) & CP_COMPUTE_CHECKPOINT_3_ADDR_1_LEN__MASK; +} + +#define REG_CP_COMPUTE_CHECKPOINT_4 0x00000004 + +#define REG_CP_COMPUTE_CHECKPOINT_5 0x00000005 +#define CP_COMPUTE_CHECKPOINT_5_ADDR_1_LO__MASK 0xffffffff +#define CP_COMPUTE_CHECKPOINT_5_ADDR_1_LO__SHIFT 0 +static inline uint32_t CP_COMPUTE_CHECKPOINT_5_ADDR_1_LO(uint32_t val) +{ + return ((val) << CP_COMPUTE_CHECKPOINT_5_ADDR_1_LO__SHIFT) & CP_COMPUTE_CHECKPOINT_5_ADDR_1_LO__MASK; +} + +#define REG_CP_COMPUTE_CHECKPOINT_6 0x00000006 +#define CP_COMPUTE_CHECKPOINT_6_ADDR_1_HI__MASK 0xffffffff +#define CP_COMPUTE_CHECKPOINT_6_ADDR_1_HI__SHIFT 0 +static inline uint32_t CP_COMPUTE_CHECKPOINT_6_ADDR_1_HI(uint32_t val) +{ + return ((val) << CP_COMPUTE_CHECKPOINT_6_ADDR_1_HI__SHIFT) & CP_COMPUTE_CHECKPOINT_6_ADDR_1_HI__MASK; +} + +#define REG_CP_COMPUTE_CHECKPOINT_7 0x00000007 + +#define REG_CP_PERFCOUNTER_ACTION_0 0x00000000 + +#define REG_CP_PERFCOUNTER_ACTION_1 0x00000001 +#define CP_PERFCOUNTER_ACTION_1_ADDR_0_LO__MASK 0xffffffff +#define CP_PERFCOUNTER_ACTION_1_ADDR_0_LO__SHIFT 0 +static inline uint32_t CP_PERFCOUNTER_ACTION_1_ADDR_0_LO(uint32_t val) +{ + return ((val) << CP_PERFCOUNTER_ACTION_1_ADDR_0_LO__SHIFT) & CP_PERFCOUNTER_ACTION_1_ADDR_0_LO__MASK; +} + +#define REG_CP_PERFCOUNTER_ACTION_2 0x00000002 +#define CP_PERFCOUNTER_ACTION_2_ADDR_0_HI__MASK 0xffffffff +#define CP_PERFCOUNTER_ACTION_2_ADDR_0_HI__SHIFT 0 +static inline uint32_t CP_PERFCOUNTER_ACTION_2_ADDR_0_HI(uint32_t val) +{ + return ((val) << CP_PERFCOUNTER_ACTION_2_ADDR_0_HI__SHIFT) & CP_PERFCOUNTER_ACTION_2_ADDR_0_HI__MASK; +} + +#define REG_CP_EVENT_WRITE_0 0x00000000 +#define CP_EVENT_WRITE_0_EVENT__MASK 0x000000ff +#define CP_EVENT_WRITE_0_EVENT__SHIFT 0 +static inline uint32_t CP_EVENT_WRITE_0_EVENT(enum vgt_event_type val) +{ + return ((val) << CP_EVENT_WRITE_0_EVENT__SHIFT) & CP_EVENT_WRITE_0_EVENT__MASK; +} +#define CP_EVENT_WRITE_0_TIMESTAMP 0x40000000 + +#define REG_CP_EVENT_WRITE_1 0x00000001 +#define CP_EVENT_WRITE_1_ADDR_0_LO__MASK 0xffffffff +#define CP_EVENT_WRITE_1_ADDR_0_LO__SHIFT 0 +static inline uint32_t CP_EVENT_WRITE_1_ADDR_0_LO(uint32_t val) +{ + return ((val) << CP_EVENT_WRITE_1_ADDR_0_LO__SHIFT) & CP_EVENT_WRITE_1_ADDR_0_LO__MASK; +} + +#define REG_CP_EVENT_WRITE_2 0x00000002 +#define CP_EVENT_WRITE_2_ADDR_0_HI__MASK 0xffffffff +#define CP_EVENT_WRITE_2_ADDR_0_HI__SHIFT 0 +static inline uint32_t CP_EVENT_WRITE_2_ADDR_0_HI(uint32_t val) +{ + return ((val) << CP_EVENT_WRITE_2_ADDR_0_HI__SHIFT) & CP_EVENT_WRITE_2_ADDR_0_HI__MASK; +} + +#define REG_CP_EVENT_WRITE_3 0x00000003 + +#define REG_CP_BLIT_0 0x00000000 +#define CP_BLIT_0_OP__MASK 0x0000000f +#define CP_BLIT_0_OP__SHIFT 0 +static inline uint32_t CP_BLIT_0_OP(enum cp_blit_cmd val) +{ + return ((val) << CP_BLIT_0_OP__SHIFT) & CP_BLIT_0_OP__MASK; +} + +#define REG_CP_BLIT_1 0x00000001 +#define CP_BLIT_1_SRC_X1__MASK 0x00003fff +#define CP_BLIT_1_SRC_X1__SHIFT 0 +static inline uint32_t CP_BLIT_1_SRC_X1(uint32_t val) +{ + return ((val) << CP_BLIT_1_SRC_X1__SHIFT) & CP_BLIT_1_SRC_X1__MASK; +} +#define CP_BLIT_1_SRC_Y1__MASK 0x3fff0000 +#define CP_BLIT_1_SRC_Y1__SHIFT 16 +static inline uint32_t CP_BLIT_1_SRC_Y1(uint32_t val) +{ + return ((val) << CP_BLIT_1_SRC_Y1__SHIFT) & CP_BLIT_1_SRC_Y1__MASK; +} + +#define REG_CP_BLIT_2 0x00000002 +#define CP_BLIT_2_SRC_X2__MASK 0x00003fff +#define CP_BLIT_2_SRC_X2__SHIFT 0 +static inline uint32_t CP_BLIT_2_SRC_X2(uint32_t val) +{ + return ((val) << CP_BLIT_2_SRC_X2__SHIFT) & CP_BLIT_2_SRC_X2__MASK; +} +#define CP_BLIT_2_SRC_Y2__MASK 0x3fff0000 +#define CP_BLIT_2_SRC_Y2__SHIFT 16 +static inline uint32_t CP_BLIT_2_SRC_Y2(uint32_t val) +{ + return ((val) << CP_BLIT_2_SRC_Y2__SHIFT) & CP_BLIT_2_SRC_Y2__MASK; +} + +#define REG_CP_BLIT_3 0x00000003 +#define CP_BLIT_3_DST_X1__MASK 0x00003fff +#define CP_BLIT_3_DST_X1__SHIFT 0 +static inline uint32_t CP_BLIT_3_DST_X1(uint32_t val) +{ + return ((val) << CP_BLIT_3_DST_X1__SHIFT) & CP_BLIT_3_DST_X1__MASK; +} +#define CP_BLIT_3_DST_Y1__MASK 0x3fff0000 +#define CP_BLIT_3_DST_Y1__SHIFT 16 +static inline uint32_t CP_BLIT_3_DST_Y1(uint32_t val) +{ + return ((val) << CP_BLIT_3_DST_Y1__SHIFT) & CP_BLIT_3_DST_Y1__MASK; +} + +#define REG_CP_BLIT_4 0x00000004 +#define CP_BLIT_4_DST_X2__MASK 0x00003fff +#define CP_BLIT_4_DST_X2__SHIFT 0 +static inline uint32_t CP_BLIT_4_DST_X2(uint32_t val) +{ + return ((val) << CP_BLIT_4_DST_X2__SHIFT) & CP_BLIT_4_DST_X2__MASK; +} +#define CP_BLIT_4_DST_Y2__MASK 0x3fff0000 +#define CP_BLIT_4_DST_Y2__SHIFT 16 +static inline uint32_t CP_BLIT_4_DST_Y2(uint32_t val) +{ + return ((val) << CP_BLIT_4_DST_Y2__SHIFT) & CP_BLIT_4_DST_Y2__MASK; +} + +#define REG_CP_EXEC_CS_0 0x00000000 + +#define REG_CP_EXEC_CS_1 0x00000001 +#define CP_EXEC_CS_1_NGROUPS_X__MASK 0xffffffff +#define CP_EXEC_CS_1_NGROUPS_X__SHIFT 0 +static inline uint32_t CP_EXEC_CS_1_NGROUPS_X(uint32_t val) +{ + return ((val) << CP_EXEC_CS_1_NGROUPS_X__SHIFT) & CP_EXEC_CS_1_NGROUPS_X__MASK; +} + +#define REG_CP_EXEC_CS_2 0x00000002 +#define CP_EXEC_CS_2_NGROUPS_Y__MASK 0xffffffff +#define CP_EXEC_CS_2_NGROUPS_Y__SHIFT 0 +static inline uint32_t CP_EXEC_CS_2_NGROUPS_Y(uint32_t val) +{ + return ((val) << CP_EXEC_CS_2_NGROUPS_Y__SHIFT) & CP_EXEC_CS_2_NGROUPS_Y__MASK; +} + +#define REG_CP_EXEC_CS_3 0x00000003 +#define CP_EXEC_CS_3_NGROUPS_Z__MASK 0xffffffff +#define CP_EXEC_CS_3_NGROUPS_Z__SHIFT 0 +static inline uint32_t CP_EXEC_CS_3_NGROUPS_Z(uint32_t val) +{ + return ((val) << CP_EXEC_CS_3_NGROUPS_Z__SHIFT) & CP_EXEC_CS_3_NGROUPS_Z__MASK; +} + +#define REG_A4XX_CP_EXEC_CS_INDIRECT_0 0x00000000 + + +#define REG_A4XX_CP_EXEC_CS_INDIRECT_1 0x00000001 +#define A4XX_CP_EXEC_CS_INDIRECT_1_ADDR__MASK 0xffffffff +#define A4XX_CP_EXEC_CS_INDIRECT_1_ADDR__SHIFT 0 +static inline uint32_t A4XX_CP_EXEC_CS_INDIRECT_1_ADDR(uint32_t val) +{ + return ((val) << A4XX_CP_EXEC_CS_INDIRECT_1_ADDR__SHIFT) & A4XX_CP_EXEC_CS_INDIRECT_1_ADDR__MASK; +} + +#define REG_A4XX_CP_EXEC_CS_INDIRECT_2 0x00000002 +#define A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEX__MASK 0x00000ffc +#define A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEX__SHIFT 2 +static inline uint32_t A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEX(uint32_t val) +{ + return ((val) << A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEX__SHIFT) & A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEX__MASK; +} +#define A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEY__MASK 0x003ff000 +#define A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEY__SHIFT 12 +static inline uint32_t A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEY(uint32_t val) +{ + return ((val) << A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEY__SHIFT) & A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEY__MASK; +} +#define A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEZ__MASK 0xffc00000 +#define A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEZ__SHIFT 22 +static inline uint32_t A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEZ(uint32_t val) +{ + return ((val) << A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEZ__SHIFT) & A4XX_CP_EXEC_CS_INDIRECT_2_LOCALSIZEZ__MASK; +} + + +#define REG_A5XX_CP_EXEC_CS_INDIRECT_1 0x00000001 +#define A5XX_CP_EXEC_CS_INDIRECT_1_ADDR_LO__MASK 0xffffffff +#define A5XX_CP_EXEC_CS_INDIRECT_1_ADDR_LO__SHIFT 0 +static inline uint32_t A5XX_CP_EXEC_CS_INDIRECT_1_ADDR_LO(uint32_t val) +{ + return ((val) << A5XX_CP_EXEC_CS_INDIRECT_1_ADDR_LO__SHIFT) & A5XX_CP_EXEC_CS_INDIRECT_1_ADDR_LO__MASK; +} + +#define REG_A5XX_CP_EXEC_CS_INDIRECT_2 0x00000002 +#define A5XX_CP_EXEC_CS_INDIRECT_2_ADDR_HI__MASK 0xffffffff +#define A5XX_CP_EXEC_CS_INDIRECT_2_ADDR_HI__SHIFT 0 +static inline uint32_t A5XX_CP_EXEC_CS_INDIRECT_2_ADDR_HI(uint32_t val) +{ + return ((val) << A5XX_CP_EXEC_CS_INDIRECT_2_ADDR_HI__SHIFT) & A5XX_CP_EXEC_CS_INDIRECT_2_ADDR_HI__MASK; +} + +#define REG_A5XX_CP_EXEC_CS_INDIRECT_3 0x00000003 +#define A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEX__MASK 0x00000ffc +#define A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEX__SHIFT 2 +static inline uint32_t A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEX(uint32_t val) +{ + return ((val) << A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEX__SHIFT) & A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEX__MASK; +} +#define A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEY__MASK 0x003ff000 +#define A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEY__SHIFT 12 +static inline uint32_t A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEY(uint32_t val) +{ + return ((val) << A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEY__SHIFT) & A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEY__MASK; +} +#define A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEZ__MASK 0xffc00000 +#define A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEZ__SHIFT 22 +static inline uint32_t A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEZ(uint32_t val) +{ + return ((val) << A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEZ__SHIFT) & A5XX_CP_EXEC_CS_INDIRECT_3_LOCALSIZEZ__MASK; +} + + +#endif /* ADRENO_PM4_XML */ diff --git a/selfdrive/modeld/thneed/debug/include/adreno_pm4types.h b/selfdrive/modeld/thneed/debug/include/adreno_pm4types.h new file mode 100644 index 0000000000..aefffdd577 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/include/adreno_pm4types.h @@ -0,0 +1,473 @@ +/* Copyright (c) 2002,2007-2015, The Linux Foundation. All rights reserved. + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 and + * only version 2 as published by the Free Software Foundation. + * + * This program 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 General Public License for more details. + * + */ +#ifndef __ADRENO_PM4TYPES_H +#define __ADRENO_PM4TYPES_H + +//#include "adreno.h" + +#define CP_PKT_MASK 0xc0000000 + +#define CP_TYPE0_PKT ((unsigned int)0 << 30) +#define CP_TYPE3_PKT ((unsigned int)3 << 30) +#define CP_TYPE4_PKT ((unsigned int)4 << 28) +#define CP_TYPE7_PKT ((unsigned int)7 << 28) + +#define PM4_TYPE4_PKT_SIZE_MAX 128 + +/* type3 packets */ + +/* Enable preemption flag */ +#define CP_PREEMPT_ENABLE 0x1C +/* Preemption token command on which preemption occurs */ +#define CP_PREEMPT_TOKEN 0x1E +/* Bit to set in CP_PREEMPT_TOKEN ordinal for interrupt on preemption */ +#define CP_PREEMPT_ORDINAL_INTERRUPT 24 +/* copy from ME scratch RAM to a register */ +#define CP_SCRATCH_TO_REG 0x4d + +/* Copy from REG to ME scratch RAM */ +#define CP_REG_TO_SCRATCH 0x4a + +/* Wait for memory writes to complete */ +#define CP_WAIT_MEM_WRITES 0x12 + +/* Conditional execution based on register comparison */ +#define CP_COND_REG_EXEC 0x47 + +/* Memory to REG copy */ +#define CP_MEM_TO_REG 0x42 + +/* initialize CP's micro-engine */ +#define CP_ME_INIT 0x48 + +/* skip N 32-bit words to get to the next packet */ +#define CP_NOP 0x10 + +/* indirect buffer dispatch. same as IB, but init is pipelined */ +#define CP_INDIRECT_BUFFER_PFD 0x37 + +/* wait for the IDLE state of the engine */ +#define CP_WAIT_FOR_IDLE 0x26 + +/* wait until a register or memory location is a specific value */ +#define CP_WAIT_REG_MEM 0x3c + +/* wait until a register location is equal to a specific value */ +#define CP_WAIT_REG_EQ 0x52 + +/* switches SMMU pagetable, used on a5xx only */ +#define CP_SMMU_TABLE_UPDATE 0x53 + +/* wait until a read completes */ +#define CP_WAIT_UNTIL_READ 0x5c + +/* wait until all base/size writes from an IB_PFD packet have completed */ +#define CP_WAIT_IB_PFD_COMPLETE 0x5d + +/* register read/modify/write */ +#define CP_REG_RMW 0x21 + +/* Set binning configuration registers */ +#define CP_SET_BIN_DATA 0x2f + +/* reads register in chip and writes to memory */ +#define CP_REG_TO_MEM 0x3e + +/* write N 32-bit words to memory */ +#define CP_MEM_WRITE 0x3d + +/* write CP_PROG_COUNTER value to memory */ +#define CP_MEM_WRITE_CNTR 0x4f + +/* conditional execution of a sequence of packets */ +#define CP_COND_EXEC 0x44 + +/* conditional write to memory or register */ +#define CP_COND_WRITE 0x45 + +/* generate an event that creates a write to memory when completed */ +#define CP_EVENT_WRITE 0x46 + +/* generate a VS|PS_done event */ +#define CP_EVENT_WRITE_SHD 0x58 + +/* generate a cache flush done event */ +#define CP_EVENT_WRITE_CFL 0x59 + +/* generate a z_pass done event */ +#define CP_EVENT_WRITE_ZPD 0x5b + + +/* initiate fetch of index buffer and draw */ +#define CP_DRAW_INDX 0x22 + +/* draw using supplied indices in packet */ +#define CP_DRAW_INDX_2 0x36 + +/* initiate fetch of index buffer and binIDs and draw */ +#define CP_DRAW_INDX_BIN 0x34 + +/* initiate fetch of bin IDs and draw using supplied indices */ +#define CP_DRAW_INDX_2_BIN 0x35 + +/* New draw packets defined for A4XX */ +#define CP_DRAW_INDX_OFFSET 0x38 +#define CP_DRAW_INDIRECT 0x28 +#define CP_DRAW_INDX_INDIRECT 0x29 +#define CP_DRAW_AUTO 0x24 + +/* begin/end initiator for viz query extent processing */ +#define CP_VIZ_QUERY 0x23 + +/* fetch state sub-blocks and initiate shader code DMAs */ +#define CP_SET_STATE 0x25 + +/* load constant into chip and to memory */ +#define CP_SET_CONSTANT 0x2d + +/* load sequencer instruction memory (pointer-based) */ +#define CP_IM_LOAD 0x27 + +/* load sequencer instruction memory (code embedded in packet) */ +#define CP_IM_LOAD_IMMEDIATE 0x2b + +/* load constants from a location in memory */ +#define CP_LOAD_CONSTANT_CONTEXT 0x2e + +/* selective invalidation of state pointers */ +#define CP_INVALIDATE_STATE 0x3b + + +/* dynamically changes shader instruction memory partition */ +#define CP_SET_SHADER_BASES 0x4A + +/* sets the 64-bit BIN_MASK register in the PFP */ +#define CP_SET_BIN_MASK 0x50 + +/* sets the 64-bit BIN_SELECT register in the PFP */ +#define CP_SET_BIN_SELECT 0x51 + + +/* updates the current context, if needed */ +#define CP_CONTEXT_UPDATE 0x5e + +/* generate interrupt from the command stream */ +#define CP_INTERRUPT 0x40 + +/* A5XX Enable yield in RB only */ +#define CP_YIELD_ENABLE 0x1C + +/* Enable/Disable/Defer A5x global preemption model */ +#define CP_PREEMPT_ENABLE_GLOBAL 0x69 + +/* Enable/Disable A5x local preemption model */ +#define CP_PREEMPT_ENABLE_LOCAL 0x6A + +/* Yeild token on a5xx similar to CP_PREEMPT on a4xx */ +#define CP_CONTEXT_SWITCH_YIELD 0x6B + +/* Inform CP about current render mode (needed for a5xx preemption) */ +#define CP_SET_RENDER_MODE 0x6C + +/* copy sequencer instruction memory to system memory */ +#define CP_IM_STORE 0x2c + +/* test 2 memory locations to dword values specified */ +#define CP_TEST_TWO_MEMS 0x71 + +/* Write register, ignoring context state for context sensitive registers */ +#define CP_REG_WR_NO_CTXT 0x78 + +/* + * for A4xx + * Write to register with address that does not fit into type-0 pkt + */ +#define CP_WIDE_REG_WRITE 0x74 + + +/* PFP waits until the FIFO between the PFP and the ME is empty */ +#define CP_WAIT_FOR_ME 0x13 + +/* Record the real-time when this packet is processed by PFP */ +#define CP_RECORD_PFP_TIMESTAMP 0x11 + +#define CP_SET_PROTECTED_MODE 0x5f /* sets the register protection mode */ + +/* Used to switch GPU between secure and non-secure modes */ +#define CP_SET_SECURE_MODE 0x66 + +#define CP_BOOTSTRAP_UCODE 0x6f /* bootstraps microcode */ + +/* + * for a3xx + */ + +#define CP_LOAD_STATE 0x30 /* load high level sequencer command */ + +/* Conditionally load a IB based on a flag */ +#define CP_COND_INDIRECT_BUFFER_PFE 0x3A /* prefetch enabled */ +#define CP_COND_INDIRECT_BUFFER_PFD 0x32 /* prefetch disabled */ + +/* Load a buffer with pre-fetch enabled */ +#define CP_INDIRECT_BUFFER_PFE 0x3F + +#define CP_EXEC_CL 0x31 + +/* (A4x) save PM4 stream pointers to execute upon a visible draw */ +#define CP_SET_DRAW_STATE 0x43 + +#define CP_LOADSTATE_DSTOFFSET_SHIFT 0x00000000 +#define CP_LOADSTATE_STATESRC_SHIFT 0x00000010 +#define CP_LOADSTATE_STATEBLOCKID_SHIFT 0x00000013 +#define CP_LOADSTATE_NUMOFUNITS_SHIFT 0x00000016 +#define CP_LOADSTATE_STATETYPE_SHIFT 0x00000000 +#define CP_LOADSTATE_EXTSRCADDR_SHIFT 0x00000002 + +static inline uint pm4_calc_odd_parity_bit(uint val) +{ + return (0x9669 >> (0xf & ((val) ^ + ((val) >> 4) ^ ((val) >> 8) ^ ((val) >> 12) ^ + ((val) >> 16) ^ ((val) >> 20) ^ ((val) >> 24) ^ + ((val) >> 28)))) & 1; +} + +/* + * PM4 packet header functions + * For all the packet functions the passed in count should be the size of the + * payload excluding the header + */ +static inline uint cp_type0_packet(uint regindx, uint cnt) +{ + return CP_TYPE0_PKT | ((cnt-1) << 16) | ((regindx) & 0x7FFF); +} + +static inline uint cp_type3_packet(uint opcode, uint cnt) +{ + return CP_TYPE3_PKT | ((cnt-1) << 16) | (((opcode) & 0xFF) << 8); +} + +static inline uint cp_type4_packet(uint opcode, uint cnt) +{ + return CP_TYPE4_PKT | ((cnt) << 0) | + (pm4_calc_odd_parity_bit(cnt) << 7) | + (((opcode) & 0x3FFFF) << 8) | + ((pm4_calc_odd_parity_bit(opcode) << 27)); +} + +static inline uint cp_type7_packet(uint opcode, uint cnt) +{ + return CP_TYPE7_PKT | ((cnt) << 0) | + (pm4_calc_odd_parity_bit(cnt) << 15) | + (((opcode) & 0x7F) << 16) | + ((pm4_calc_odd_parity_bit(opcode) << 23)); + +} + +#define pkt_is_type0(pkt) (((pkt) & 0XC0000000) == CP_TYPE0_PKT) + +#define type0_pkt_size(pkt) ((((pkt) >> 16) & 0x3FFF) + 1) +#define type0_pkt_offset(pkt) ((pkt) & 0x7FFF) + +/* + * Check both for the type3 opcode and make sure that the reserved bits [1:7] + * and 15 are 0 + */ + +#define pkt_is_type3(pkt) \ + ((((pkt) & 0xC0000000) == CP_TYPE3_PKT) && \ + (((pkt) & 0x80FE) == 0)) + +#define cp_type3_opcode(pkt) (((pkt) >> 8) & 0xFF) +#define type3_pkt_size(pkt) ((((pkt) >> 16) & 0x3FFF) + 1) + +#define pkt_is_type4(pkt) \ + ((((pkt) & 0xF0000000) == CP_TYPE4_PKT) && \ + ((((pkt) >> 27) & 0x1) == \ + pm4_calc_odd_parity_bit(cp_type4_base_index_one_reg_wr(pkt))) \ + && ((((pkt) >> 7) & 0x1) == \ + pm4_calc_odd_parity_bit(type4_pkt_size(pkt)))) + +#define cp_type4_base_index_one_reg_wr(pkt) (((pkt) >> 8) & 0x7FFFF) +#define type4_pkt_size(pkt) ((pkt) & 0x7F) + +#define pkt_is_type7(pkt) \ + ((((pkt) & 0xF0000000) == CP_TYPE7_PKT) && \ + (((pkt) & 0x0F000000) == 0) && \ + ((((pkt) >> 23) & 0x1) == \ + pm4_calc_odd_parity_bit(cp_type7_opcode(pkt))) \ + && ((((pkt) >> 15) & 0x1) == \ + pm4_calc_odd_parity_bit(type7_pkt_size(pkt)))) + +#define cp_type7_opcode(pkt) (((pkt) >> 16) & 0x7F) +#define type7_pkt_size(pkt) ((pkt) & 0x3FFF) + +/* dword base address of the GFX decode space */ +#define SUBBLOCK_OFFSET(reg) ((unsigned int)((reg) - (0x2000))) + +/* gmem command buffer length */ +#define CP_REG(reg) ((0x4 << 16) | (SUBBLOCK_OFFSET(reg))) + +// add these +#define ADRENO_GPUREV(x) 530 +#define lower_32_bits(n) ((uint32_t)(n)) +#define upper_32_bits(n) ((uint32_t)(((n) >> 16) >> 16)) + +/* Return true if the hardware uses the legacy (A4XX and older) PM4 format */ +#define ADRENO_LEGACY_PM4(_d) (ADRENO_GPUREV(_d) < 500) + +/** + * cp_packet - Generic CP packet to support different opcodes on + * different GPU cores. + * @adreno_dev: The adreno device + * @opcode: Operation for cp packet + * @size: size for cp packet + */ +static inline uint cp_packet(struct adreno_device *adreno_dev, + int opcode, uint size) +{ + if (ADRENO_LEGACY_PM4(adreno_dev)) + return cp_type3_packet(opcode, size); + + return cp_type7_packet(opcode, size); +} + +/** + * cp_mem_packet - Generic CP memory packet to support different + * opcodes on different GPU cores. + * @adreno_dev: The adreno device + * @opcode: mem operation for cp packet + * @size: size for cp packet + * @num_mem: num of mem access + */ +static inline uint cp_mem_packet(struct adreno_device *adreno_dev, + int opcode, uint size, uint num_mem) +{ + if (ADRENO_LEGACY_PM4(adreno_dev)) + return cp_type3_packet(opcode, size); + + return cp_type7_packet(opcode, size + num_mem); +} + +/* Return 1 if the command is an indirect buffer of any kind */ +static inline int adreno_cmd_is_ib(struct adreno_device *adreno_dev, + unsigned int cmd) +{ + return cmd == cp_mem_packet(adreno_dev, + CP_INDIRECT_BUFFER_PFE, 2, 1) || + cmd == cp_mem_packet(adreno_dev, + CP_INDIRECT_BUFFER_PFD, 2, 1) || + cmd == cp_mem_packet(adreno_dev, + CP_COND_INDIRECT_BUFFER_PFE, 2, 1) || + cmd == cp_mem_packet(adreno_dev, + CP_COND_INDIRECT_BUFFER_PFD, 2, 1); +} + +/** + * cp_gpuaddr - Generic function to add 64bit and 32bit gpuaddr + * to pm4 commands + * @adreno_dev: The adreno device + * @cmds: command pointer to add gpuaddr + * @gpuaddr: gpuaddr to add + */ +static inline uint cp_gpuaddr(struct adreno_device *adreno_dev, + uint *cmds, uint64_t gpuaddr) +{ + uint *start = cmds; + + if (ADRENO_LEGACY_PM4(adreno_dev)) + *cmds++ = (uint)gpuaddr; + else { + *cmds++ = lower_32_bits(gpuaddr); + *cmds++ = upper_32_bits(gpuaddr); + } + return cmds - start; +} + +/** + * cp_register - Generic function for gpu register operation + * @adreno_dev: The adreno device + * @reg: GPU register + * @size: count for PM4 operation + */ +static inline uint cp_register(struct adreno_device *adreno_dev, + unsigned int reg, unsigned int size) +{ + if (ADRENO_LEGACY_PM4(adreno_dev)) + return cp_type0_packet(reg, size); + + return cp_type4_packet(reg, size); +} + +/** + * cp_wait_for_me - common function for WAIT_FOR_ME + * @adreno_dev: The adreno device + * @cmds: command pointer to add gpuaddr + */ +static inline uint cp_wait_for_me(struct adreno_device *adreno_dev, + uint *cmds) +{ + uint *start = cmds; + + if (ADRENO_LEGACY_PM4(adreno_dev)) { + *cmds++ = cp_type3_packet(CP_WAIT_FOR_ME, 1); + *cmds++ = 0; + } else + *cmds++ = cp_type7_packet(CP_WAIT_FOR_ME, 0); + + return cmds - start; +} + +/** + * cp_wait_for_idle - common function for WAIT_FOR_IDLE + * @adreno_dev: The adreno device + * @cmds: command pointer to add gpuaddr + */ +static inline uint cp_wait_for_idle(struct adreno_device *adreno_dev, + uint *cmds) +{ + uint *start = cmds; + + if (ADRENO_LEGACY_PM4(adreno_dev)) { + *cmds++ = cp_type3_packet(CP_WAIT_FOR_IDLE, 1); + *cmds++ = 0; + } else + *cmds++ = cp_type7_packet(CP_WAIT_FOR_IDLE, 0); + + return cmds - start; +} + +/** + * cp_invalidate_state - common function for invalidating cp + * state + * @adreno_dev: The adreno device + * @cmds: command pointer to add gpuaddr + */ +static inline uint cp_invalidate_state(struct adreno_device *adreno_dev, + uint *cmds) +{ + uint *start = cmds; + + if (ADRENO_GPUREV(adreno_dev) < 500) { + *cmds++ = cp_type3_packet(CP_INVALIDATE_STATE, 1); + *cmds++ = 0x7fff; + } else { + *cmds++ = cp_type7_packet(CP_SET_DRAW_STATE, 3); + *cmds++ = 0x40000; + *cmds++ = 0; + *cmds++ = 0; + } + + return cmds - start; +} + +#endif /* __ADRENO_PM4TYPES_H */ diff --git a/selfdrive/modeld/thneed/debug/main.cc b/selfdrive/modeld/thneed/debug/main.cc new file mode 100644 index 0000000000..07a7d1235b --- /dev/null +++ b/selfdrive/modeld/thneed/debug/main.cc @@ -0,0 +1,733 @@ +#include +#include "include/msm_kgsl.h" +#include +#include +#include +#include +#include + +int run_num = 0; +int ioctl_num = 0; + +void hexdump(uint32_t *d, int len) { + assert((len%4) == 0); + printf(" dumping %p len 0x%x\n", d, len); + for (int i = 0; i < len/4; i++) { + if (i != 0 && (i%0x10) == 0) printf("\n"); + printf("%8x ", d[i]); + } + printf("\n"); +} + +void hexdump8(uint8_t *d, int len) { + printf(" dumping %p len 0x%x\n", d, len); + for (int i = 0; i < len; i++) { + if (i != 0 && (i%0x10) == 0) printf("\n"); + printf("%02x ", d[i]); + } + printf("\n"); +} + + +#include +#include +#include +using namespace std; + +#include "disasm/include/adreno_pm4types.h" + +#define REG_A5XX_TPL1_CS_TEX_CONST_LO 0x0000e760 +#define REG_A5XX_TPL1_CS_TEX_SAMP_LO 0x0000e75c + +class CachedCommand { + public: + CachedCommand(struct kgsl_gpu_command *cmd, int lfd); + void exec(bool wait); + private: + string cmd_0, cmd_1; + int obj_len; + int fd; + + struct kgsl_gpu_command cache; + struct kgsl_command_object cmds[2]; + struct kgsl_command_object objs[1]; +}; + +vector queue_cmds; + +void disassemble(uint32_t *src, int len) { + int i = 0; + while (i < len) { + int pktsize; + int pkttype = -1; + + if (pkt_is_type0(src[i])) { + pkttype = 0; + pktsize = type0_pkt_size(src[i]); + } else if (pkt_is_type3(src[i])) { + pkttype = 3; + pktsize = type3_pkt_size(src[i]); + } else if (pkt_is_type4(src[i])) { + pkttype = 4; + pktsize = type4_pkt_size(src[i]); + } else if (pkt_is_type7(src[i])) { + pkttype = 7; + pktsize = type7_pkt_size(src[i]); + } + printf("%3d: type:%d size:%d ", i, pkttype, pktsize); + + if (pkttype == 7) { + printf("op: %4x ", cp_type7_opcode(src[i])); + } + + if (pkttype == 4) { + printf("reg: %4x ", cp_type4_base_index_one_reg_wr(src[i])); + } + + for (int j = 0; j < pktsize+1; j++) { + printf("%8.8X ", src[i+j]); + } + printf("\n"); + + if (pkttype == 7 && cp_type7_opcode(src[i]) == CP_LOAD_STATE) { + // CP_LOAD_STATE4 + int sz = (src[i+1] & 0xffc00000) >> 22; + uint64_t addr = (uint64_t)(src[i+2] & 0xfffffffc) | ((uint64_t)(src[i+3]) << 32); + hexdump((uint32_t *)addr, sz*4); + } + + if (pkttype == 4 && cp_type4_base_index_one_reg_wr(src[i]) == REG_A5XX_TPL1_CS_TEX_CONST_LO) { + uint64_t addr = (uint64_t)(src[i+1] & 0xffffffff) | ((uint64_t)(src[i+2]) << 32); + hexdump((uint32_t *)addr, 0x40); + } + + if (pkttype == 4 && cp_type4_base_index_one_reg_wr(src[i]) == REG_A5XX_TPL1_CS_TEX_SAMP_LO) { + uint64_t addr = (uint64_t)(src[i+1] & 0xffffffff) | ((uint64_t)(src[i+2]) << 32); + hexdump((uint32_t *)addr, 0x40); + } + + if (pkttype == -1) break; + i += (1+pktsize); + } + assert(i == len); + +} + +int intercept = 1; +int prop_num = 0; + +extern "C" { + +/*void *gsl_memory_alloc_pure(long param_1, long param_2, long *param_3) { + void *(*my_gsl_memory_alloc_pure)(long param_1, long param_2, long *param_3); + my_gsl_memory_alloc_pure = reinterpret_cast(dlsym(RTLD_NEXT, "gsl_memory_alloc_pure")); + + void *ret = my_gsl_memory_alloc_pure(param_1, param_2, param_3); + printf("gsl_memory_alloc_pure: 0x%lx 0x%lx %p = %p\n", param_1, param_2, param_3, ret); + return ret; +}*/ + +void *mmap64(void *addr, size_t len, int prot, int flags, int fildes, off64_t off) { + void *(*my_mmap64)(void *addr, size_t len, int prot, int flags, int fildes, off64_t off); + my_mmap64 = reinterpret_cast(dlsym(RTLD_NEXT, "mmap64")); + + void *ret = my_mmap64(addr, len, prot, flags, fildes, off); + + if (fildes == 3) { + printf("mmap64(addr=%p, len=0x%zx, prot=0x%x, flags=0x%x, fildes=%d, off=0x%lx) = %p\n", addr, len, prot, flags, fildes, off, ret); + } + + return ret; +} + + +pid_t gettid(void); + +#undef ioctl +int ioctl(int filedes, unsigned long request, void *argp) { + int (*my_ioctl)(int filedes, unsigned long request, void *argp); + my_ioctl = reinterpret_cast(dlsym(RTLD_NEXT, "ioctl")); + int skip = 0; + +if (intercept) { + + int tid = gettid(); + + if (request == IOCTL_KGSL_GPU_COMMAND) { + struct kgsl_gpu_command *cmd = (struct kgsl_gpu_command *)argp; + printf("IOCTL_KGSL_GPU_COMMAND(%d): flags: 0x%lx numcmds: %u numobjs: %u numsyncs: %u context_id: %u timestamp: %u\n", + tid, + cmd->flags, + cmd->numcmds, cmd->numobjs, cmd->numsyncs, + cmd->context_id, cmd->timestamp); + + assert(cmd->numcmds == 2); + assert(cmd->numobjs == 1); + assert(cmd->numsyncs == 0); + + //struct kgsl_command_object *obj = (struct kgsl_command_object *)cmd->cmdlist; + //assert(obj[0].size == sizeof(queue_init)); + //memcpy(queue_init, (void*)obj[0].gpuaddr, sizeof(queue_init)); + //string qcmd((char*)obj[1].gpuaddr, obj[1].size); + if (run_num == 3) { + CachedCommand *ccmd = new CachedCommand(cmd, filedes); + queue_cmds.push_back(ccmd); + + //ccmd->exec(); + + //skip = 0; + //printf("command 0x%lx\n", obj[1].gpuaddr); + //disassemble((uint32_t *)qcmd.data(), qcmd.size()/4); + //queue_cmds.push_back(qcmd); + } + + #ifdef DUMP + char tmp[0x100]; + snprintf(tmp, sizeof(tmp), "/tmp/thneed/run_%d_%d", run_num, ioctl_num++); + FILE *f = fopen(tmp, "wb"); + #endif + + // kgsl_cmdbatch_add_cmdlist + for (int i = 0; i < cmd->numcmds; i++) { + struct kgsl_command_object *obj = (struct kgsl_command_object *)cmd->cmdlist; + printf(" cmd: %lx %5lx %5lx flags:%3x %d\n", + obj[i].offset, obj[i].gpuaddr, obj[i].size, obj[i].flags, obj[i].id); + //hexdump((uint32_t *)obj[i].gpuaddr, obj[i].size); + #ifdef DUMP + fwrite(&obj[i].size, sizeof(obj[i].size), 1, f); + fwrite((void*)obj[i].gpuaddr, obj[i].size, 1, f); + #endif + } + + // kgsl_cmdbatch_add_memlist + for (int i = 0; i < cmd->numobjs; i++) { + struct kgsl_command_object *obj = (struct kgsl_command_object *)cmd->objlist; + printf(" obj: %lx %5lx %5lx flags:%3x %d\n", + obj[i].offset, obj[i].gpuaddr, obj[i].size, obj[i].flags, obj[i].id); + //hexdump((uint32_t *)obj[i].gpuaddr, obj[i].size); + + #ifdef DUMP + fwrite(&obj[i].size, sizeof(obj[i].size), 1, f); + fwrite((void*)obj[i].gpuaddr, obj[i].size, 1, f); + #endif + } + + #ifdef DUMP + fclose(f); + #endif + + } else if (request == IOCTL_KGSL_SETPROPERTY) { + struct kgsl_device_getproperty *prop = (struct kgsl_device_getproperty *)argp; + printf("IOCTL_KGSL_SETPROPERTY(%d): 0x%x\n", tid, prop->type); + hexdump8((uint8_t*)prop->value, prop->sizebytes); + if (prop_num == 1) { printf("SKIPPING\n"); skip = 1; } + if (run_num == 3) prop_num++; + //hexdump((unsigned char*)prop->value, prop->sizebytes); + } else if (request == IOCTL_KGSL_GPUOBJ_SYNC) { + struct kgsl_gpuobj_sync *cmd = (struct kgsl_gpuobj_sync *)argp; + struct kgsl_gpuobj_sync_obj *objs = (struct kgsl_gpuobj_sync_obj *)(cmd->objs); + + printf("IOCTL_KGSL_GPUOBJ_SYNC(%d) count:%d ", tid, cmd->count); + for (int i = 0; i < cmd->count; i++) { + printf(" -- offset:0x%lx len:0x%lx id:%d op:%d ", objs[i].offset, objs[i].length, objs[i].id, objs[i].op); + } + printf("\n"); + } else if (request == IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID) { + struct kgsl_device_waittimestamp_ctxtid *cmd = (struct kgsl_device_waittimestamp_ctxtid *)argp; + printf("IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID(%d): context_id: %d timestamp: %d timeout: %d\n", + tid, cmd->context_id, cmd->timestamp, cmd->timeout); + } else if (request == IOCTL_KGSL_GPUOBJ_ALLOC) { + struct kgsl_gpuobj_alloc *cmd = (struct kgsl_gpuobj_alloc *)argp; + printf("IOCTL_KGSL_GPUOBJ_ALLOC: size:0x%lx flags:0x%lx va_len:0x%lx ", cmd->size, cmd->flags, cmd->va_len); + } else if (request == IOCTL_KGSL_GPUOBJ_FREE) { + //printf("IOCTL_KGSL_GPUOBJ_FREE\n"); + } else if (filedes == 3) { + printf("ioctl(%d) %lx\n", tid, request); + } + +} + + int ret; + if (skip) { + ret = 0; + } else { + ret = my_ioctl(filedes, request, argp); + } + + if (request == IOCTL_KGSL_GPUOBJ_ALLOC) { + struct kgsl_gpuobj_alloc *cmd = (struct kgsl_gpuobj_alloc *)argp; + printf("mmapsize:0x%lx id:%d metadata_len:%x metadata:0x%lx = %d\n", cmd->mmapsize, cmd->id, cmd->metadata_len, cmd->metadata, ret); + } + + return ret; +} + +} + +#include +#include "../runners/snpemodel.h" +#include +#include + +static inline uint64_t nanos_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +int global_timestamp = -1; +CachedCommand::CachedCommand(struct kgsl_gpu_command *cmd, int lfd) { + fd = lfd; + assert(cmd->numcmds == 2); + assert(cmd->numobjs == 1); + assert(cmd->numsyncs == 0); + + global_timestamp = cmd->timestamp; + + printf("%p %p %p\n", cmd, (void*)cmd->cmdlist, (void*)cmd->objlist); + + memcpy(cmds, (void *)cmd->cmdlist, sizeof(struct kgsl_command_object)*2); + memcpy(objs, (void *)cmd->objlist, sizeof(struct kgsl_command_object)*1); + cmd_0.assign((char*)cmds[0].gpuaddr, cmds[0].size); + cmd_1.assign((char*)cmds[1].gpuaddr, cmds[1].size); + + + memcpy(&cache, cmd, sizeof(cache)); +} + +// i think you get these with cl_a5x_ringbuffer_alloc +uint64_t base = 0; + +void CachedCommand::exec(bool wait) { + printf("old addr 0x%lx ", cmds[1].gpuaddr); + cmds[1].gpuaddr = base; + printf("using addr 0x%lx with size 0x%4lx ", cmds[1].gpuaddr, cmd_1.size()); + base += (cmd_1.size()+0xff) & (~0xFF); + memcpy((void*)cmds[1].gpuaddr, cmd_1.data(), cmd_1.size()); + + // set up other buffers + memcpy((void*)cmds[0].gpuaddr, cmd_0.data(), cmd_0.size()); + memset((void*)objs[0].gpuaddr, 0, objs[0].size); + + cache.timestamp = ++global_timestamp; + cache.cmdlist = (uint64_t)cmds; + cache.objlist = (uint64_t)objs; + + // run + int ret = ioctl(fd, IOCTL_KGSL_GPU_COMMAND, &cache); + + if (wait) { + struct kgsl_device_waittimestamp_ctxtid wait; + wait.context_id = cache.context_id; + wait.timestamp = cache.timestamp; + wait.timeout = -1; + + uint64_t tb = nanos_since_boot(); + int wret = ioctl(fd, IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID, &wait); + uint64_t te = nanos_since_boot(); + + printf("exec %d wait %d after %lu us\n", ret, wret, (te-tb)/1000); + } else { + printf("CachedCommand::exec got %d\n", ret); + } +} + + +int do_print = 0; + +#define TEMPORAL_SIZE 512 +#define DESIRE_LEN 8 +#define TRAFFIC_CONVENTION_LEN 2 + +FILE *f = NULL; + +cl_program clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) { + cl_program (*my_clCreateProgramWithSource)(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) = NULL; + my_clCreateProgramWithSource = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clCreateProgramWithSource")); + //printf("clCreateProgramWithSource: %d\n", count); + + if (f == NULL) { + f = fopen("/tmp/kernels.cl", "w"); + } + + fprintf(f, "/* ************************ PROGRAM BREAK ****************************/\n"); + for (int i = 0; i < count; i++) { + fprintf(f, "%s\n", strings[i]); + if (i != 0) fprintf(f, "/* ************************ SECTION BREAK ****************************/\n"); + } + fflush(f); + + return my_clCreateProgramWithSource(context, count, strings, lengths, errcode_ret); +} + +map kernels; +map kernel_inputs; +map kernel_outputs; + +cl_kernel clCreateKernel(cl_program program, const char *kernel_name, cl_int *errcode_ret) { + cl_kernel (*my_clCreateKernel)(cl_program program, const char *kernel_name, cl_int *errcode_ret) = NULL; + my_clCreateKernel = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clCreateKernel")); + cl_kernel ret = my_clCreateKernel(program, kernel_name, errcode_ret); + + printf("clCreateKernel: %s -> %p\n", kernel_name, ret); + kernels.insert(make_pair(ret, kernel_name)); + return ret; +} + +typedef struct image { + size_t image_width; + size_t image_height; + size_t image_row_pitch; + cl_mem buffer; +} image; + +map buffers; +map images; + +cl_int clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) { + cl_int (*my_clSetKernelArg)(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) = NULL; + my_clSetKernelArg = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clSetKernelArg")); + + char arg_type[0x100]; + char arg_name[0x100]; + clGetKernelArgInfo(kernel, arg_index, CL_KERNEL_ARG_TYPE_NAME, sizeof(arg_type), arg_type, NULL); + clGetKernelArgInfo(kernel, arg_index, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); + printf(" %s %s", arg_type, arg_name); + + if (arg_size == 1) { + printf(" = %d", *((char*)arg_value)); + } else if (arg_size == 2) { + printf(" = %d", *((short*)arg_value)); + } else if (arg_size == 4) { + if (strcmp(arg_type, "float") == 0) { + printf(" = %f", *((float*)arg_value)); + } else { + printf(" = %d", *((int*)arg_value)); + } + } else if (arg_size == 8) { + cl_mem val = (cl_mem)(*((uintptr_t*)arg_value)); + printf(" = %p", val); + if (strcmp(arg_name, "input") == 0) kernel_inputs[kernel] = val; + if (strcmp(arg_name, "output") == 0) kernel_outputs[kernel] = val; + if (strcmp(arg_name, "accumulator") == 0) assert(kernel_inputs[kernel] = val); + + if (buffers.find(val) != buffers.end()) { + printf(" buffer %zu", buffers[val]); + } + + if (images.find(val) != images.end()) { + printf(" image %zu x %zu rp %zu @ %p", images[val].image_width, images[val].image_height, images[val].image_row_pitch, images[val].buffer); + } + + } else { + printf(" %zu", arg_size); + } + printf("\n"); + cl_int ret = my_clSetKernelArg(kernel, arg_index, arg_size, arg_value); + return ret; +} + +uint64_t start_time = 0; +uint64_t tns = 0; + +int cnt = 0; + +cl_int clEnqueueNDRangeKernel(cl_command_queue command_queue, + cl_kernel kernel, + cl_uint work_dim, + const size_t *global_work_offset, + const size_t *global_work_size, + const size_t *local_work_size, + cl_uint num_events_in_wait_list, + const cl_event *event_wait_list, + cl_event *event) { + + // SNPE doesn't use these + assert(num_events_in_wait_list == 0); + assert(global_work_offset == NULL); + + cl_int (*my_clEnqueueNDRangeKernel)(cl_command_queue, cl_kernel, cl_uint, const size_t *, const size_t *, const size_t *, cl_uint, const cl_event *, cl_event *) = NULL; + my_clEnqueueNDRangeKernel = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clEnqueueNDRangeKernel")); + + + uint64_t tb = nanos_since_boot(); + cl_int ret = my_clEnqueueNDRangeKernel(command_queue, kernel, work_dim, + global_work_offset, global_work_size, local_work_size, + num_events_in_wait_list, event_wait_list, event); + uint64_t te = nanos_since_boot(); + + /*ret = clWaitForEvents(1, event); + assert(ret == CL_SUCCESS); + uint64_t tq = nanos_since_boot();*/ + + if (do_print) { + tns += te-tb; + } + + printf("%10lu %10lu running(%3d) -- %p -- %56s -- %p -> %p %s ", (tb-start_time)/1000, (tns/1000), cnt++, kernel, kernels[kernel].c_str(), kernel_inputs[kernel], kernel_outputs[kernel], + (buffers[kernel_outputs[kernel]] != 0) ? "B" : "I"); + + printf("global -- "); + for (int i = 0; i < work_dim; i++) { + printf("%4zu ", global_work_size[i]); + } + printf("local -- "); + for (int i = 0; i < work_dim; i++) { + printf("%4zu ", local_work_size[i]); + } + printf("\n"); + + return ret; +} + + +cl_mem clCreateBuffer(cl_context context, cl_mem_flags flags, size_t size, void *host_ptr, cl_int *errcode_ret) { + cl_mem (*my_clCreateBuffer)(cl_context context, cl_mem_flags flags, size_t size, void *host_ptr, cl_int *errcode_ret) = NULL; + my_clCreateBuffer = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clCreateBuffer")); + + cl_mem ret = my_clCreateBuffer(context, flags, size, host_ptr, errcode_ret); + buffers[ret] = size; + printf("%p = clCreateBuffer %zu\n", ret, size); + return ret; +} + +cl_mem clCreateImage(cl_context context, cl_mem_flags flags, const cl_image_format *image_format, const cl_image_desc *image_desc, void *host_ptr, cl_int *errcode_ret) { + cl_mem (*my_clCreateImage)(cl_context context, cl_mem_flags flags, const cl_image_format *image_format, const cl_image_desc *image_desc, void *host_ptr, cl_int *errcode_ret) = NULL; + my_clCreateImage = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clCreateImage")); + + // SNPE only uses this + assert(CL_MEM_OBJECT_IMAGE2D == image_desc->image_type); + + // RGBA, HALF FLOAT + assert(CL_RGBA == image_format->image_channel_order); + assert(CL_HALF_FLOAT == image_format->image_channel_data_type); + + map lc = { + {CL_MEM_OBJECT_BUFFER, "CL_MEM_OBJECT_BUFFER"}, + {CL_MEM_OBJECT_IMAGE2D, "CL_MEM_OBJECT_IMAGE2D"}, // all this one + {CL_MEM_OBJECT_IMAGE3D, "CL_MEM_OBJECT_IMAGE3D"}, + {CL_MEM_OBJECT_IMAGE2D_ARRAY, "CL_MEM_OBJECT_IMAGE2D_ARRAY"}, + {CL_MEM_OBJECT_IMAGE1D, "CL_MEM_OBJECT_IMAGE1D"}, + {CL_MEM_OBJECT_IMAGE1D_ARRAY, "CL_MEM_OBJECT_IMAGE1D_ARRAY"}, + {CL_MEM_OBJECT_IMAGE1D_BUFFER, "CL_MEM_OBJECT_IMAGE1D_BUFFER"}}; + + assert(image_desc->image_depth == 0); + assert(image_desc->image_array_size == 0); + assert(image_desc->image_slice_pitch == 0); + //assert(image_desc->image_width * image_desc->image_height * 2 == image_desc->image_row_pitch); + + image img; + img.image_width = image_desc->image_width; + img.image_height = image_desc->image_height; + img.image_row_pitch = image_desc->image_row_pitch; + img.buffer = image_desc->buffer; + + cl_mem ret = my_clCreateImage(context, flags, image_format, image_desc, host_ptr, errcode_ret); + printf("%p = clCreateImage %s -- %p -- %d %d -- %4zu x %4zu x %4zu -- %4zu %4zu %4zu\n", ret, lc[image_desc->image_type].c_str(), + image_desc->buffer, + image_format->image_channel_order, image_format->image_channel_data_type, + image_desc->image_width, image_desc->image_height, image_desc->image_depth, + image_desc->image_array_size, image_desc->image_row_pitch, image_desc->image_slice_pitch + ); + images[ret] = img; + return ret; +} + +cl_int clWaitForEvents(cl_uint num_events, const cl_event *event_list) { + cl_int (*my_clWaitForEvents)(cl_uint num_events, const cl_event *event_list); + my_clWaitForEvents = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clWaitForEvents")); + printf("clWaitForEvents\n"); + return my_clWaitForEvents(num_events, event_list); +} + +cl_int clReleaseEvent(cl_event event) { + cl_int (*my_clReleaseEvent)(cl_event event); + my_clReleaseEvent = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clReleaseEvent")); + printf("clReleaseEvent: %p\n", event); + return my_clReleaseEvent(event); +} + +/*size_t total = 0; + +void *calloc(size_t num, size_t size) { + void *(*my_calloc)(size_t num, size_t size); + my_calloc = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_calloc")); + + void *ret = my_calloc(num, size); + + if (do_print) { + total += num*size; + printf("calloc %p -- total:0x%zx -- num:0x%zx size:0x%zx\n", ret, total, num, size); + } + return ret; +} + +void free(void *ptr) { + void (*my_free)(void *ptr); + my_free = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_free")); + + if (do_print) { + //printf("free: %p\n", ptr); + } else { + my_free(ptr); + } +}*/ + +void *dlsym(void *handle, const char *symbol) { + void *(*my_dlsym)(void *handle, const char *symbol) = (void *(*)(void *handle, const char *symbol))((uintptr_t)dlopen-0x2d4); + if (memcmp("REAL_", symbol, 5) == 0) { + return my_dlsym(handle, symbol+5); + } else if (strcmp("clCreateProgramWithSource", symbol) == 0) { + return (void*)clCreateProgramWithSource; + } else if (strcmp("clCreateKernel", symbol) == 0) { + return (void*)clCreateKernel; + } else if (strcmp("clEnqueueNDRangeKernel", symbol) == 0) { + return (void*)clEnqueueNDRangeKernel; + } else if (strcmp("clSetKernelArg", symbol) == 0) { + return (void*)clSetKernelArg; + } else if (strcmp("clCreateBuffer", symbol) == 0) { + return (void*)clCreateBuffer; + } else if (strcmp("clCreateImage", symbol) == 0) { + return (void*)clCreateImage; + /*} else if (strcmp("clReleaseEvent", symbol) == 0) { + return (void*)clReleaseEvent; + } else if (strcmp("clWaitForEvents", symbol) == 0) { + return (void*)clWaitForEvents;*/ + } else { + //printf("dlsym %s\n", symbol); + return my_dlsym(handle, symbol); + } +} + +int main(int argc, char* argv[]) { + int err; + cl_platform_id platform_id = NULL; + cl_device_id device_id = NULL; + cl_uint num_devices; + cl_uint num_platforms; + + start_time = nanos_since_boot(); + + err = clGetPlatformIDs(1, &platform_id, &num_platforms); + assert(err == 0); + err = clGetDeviceIDs(platform_id, CL_DEVICE_TYPE_DEFAULT, 1, &device_id, &num_devices); + assert(err == 0); + + cl_uint tmp; + + // sweet this is 64! + err = clGetDeviceInfo(device_id, CL_DEVICE_MAX_WRITE_IMAGE_ARGS, sizeof(tmp), &tmp, NULL); + assert(err == 0); + printf("CL_DEVICE_MAX_WRITE_IMAGE_ARGS: %u\n", tmp); + + err = clGetDeviceInfo(device_id, CL_DEVICE_MAX_READ_IMAGE_ARGS, sizeof(tmp), &tmp, NULL); + assert(err == 0); + printf("CL_DEVICE_MAX_READ_IMAGE_ARGS: %u\n", tmp); + + float *output = (float*)calloc(0x10000, sizeof(float)); + SNPEModel mdl(argv[1], output, 0, USE_GPU_RUNTIME); + + float state[TEMPORAL_SIZE]; + mdl.addRecurrent(state, TEMPORAL_SIZE); + + float desire[DESIRE_LEN]; + mdl.addDesire(desire, DESIRE_LEN); + + float traffic_convention[TRAFFIC_CONVENTION_LEN]; + mdl.addTrafficConvention(traffic_convention, TRAFFIC_CONVENTION_LEN); + + float *input = (float*)calloc(0x1000000, sizeof(float));; + printf("************** execute 1 **************\n"); + printf("%p %p %p %p -> %p\n", input, state, desire, traffic_convention, output); + run_num = 1; ioctl_num = 0; + do_print = 0; + start_time = nanos_since_boot(); + mdl.execute(input, 0); + printf("************** execute 2 **************\n"); + run_num = 2; ioctl_num = 0; + do_print = 0; + mdl.execute(input, 0); + printf("************** execute 3 **************\n"); + run_num = 3; ioctl_num = 0; + + do_print = 1; + start_time = nanos_since_boot(); + mdl.execute(input, 0); + do_print = 0; + + struct kgsl_gpuobj_alloc alloc; + memset(&alloc, 0, sizeof(alloc)); + alloc.size = 0x40000; + alloc.flags = 0x10000a00; + int fd = 3; + int ret = ioctl(fd, IOCTL_KGSL_GPUOBJ_ALLOC, &alloc); + void *addr = mmap64(NULL, alloc.mmapsize, 0x3, 0x1, fd, alloc.id*0x1000); + assert(addr != MAP_FAILED); + + intercept = 0; + while (1) { + printf("************** execute 4 **************\n"); + run_num = 4; + base = (uint64_t)addr; + + uint64_t tb = nanos_since_boot(); + int i = 0; + for (auto it = queue_cmds.begin(); it != queue_cmds.end(); ++it) { + printf("run %2d: ", i++); + //(*it)->exec(i == queue_cmds.size()); + (*it)->exec(true); + } + uint64_t te = nanos_since_boot(); + printf("model exec in %lu us\n", (te-tb)/1000); + + break; + } + + /*FILE *f = fopen("/proc/self/maps", "rb"); + char maps[0x100000]; + int len = fread(maps, 1, sizeof(maps), f); + maps[len] = '\0'; + fclose(f); + printf("%s\n", maps);*/ + + printf("buffers: %lu images: %lu\n", buffers.size(), images.size()); + printf("queues: %lu\n", queue_cmds.size()); + + // IOCTL_KGSL_GPU_COMMAND: flags: 0x11 numcmds: 2 numobjs: 1 numsyncs: 0 context_id: 7 timestamp: 77 + /*int ts = 100; + for (auto it = queue_cmds.begin(); it != queue_cmds.end(); ++it) { + auto qcmd = *it; + //disassemble((uint32_t *)qcmd.data(), qcmd.size()/4); + + struct kgsl_command_object cmdlists[2]; + struct kgsl_command_object objlists; + struct kgsl_gpu_command cmd; + uint8_t objs[0xc0]; + memset(objs, 0, 0xc0); + + memset(&cmd, 0, sizeof(cmd)); + memset(&cmdlists, 0, sizeof(struct kgsl_command_object)*2); + memset(&objlists, 0, sizeof(objlists)); + + cmd.flags = 0x11; + cmd.cmdlist = (uint64_t)cmdlists; + cmd.numcmds = 2; + cmd.objlist = (uint64_t)objlists; + cmd.numobjs = 1; + cmd.numsyncs = 0; + cmd.context_id = 7; + cmd.timestamp = ts++; + + cmdlists[0].gpuaddr = (uint64_t)queue_init; + cmdlists[0].size = 0xbc; + cmdlists[0].flags = 1; + cmdlists[1].gpuaddr = (uint64_t)qcmd.data(); + cmdlists[1].size = qcmd.size(); + cmdlists[1].flags = 1; + + objlists.gpuaddr = (uint64_t)objs; + objlists.size = 0xc0; + objlists.flags = 0x18; + }*/ +} + diff --git a/selfdrive/modeld/thneed/debug/test.cc b/selfdrive/modeld/thneed/debug/test.cc new file mode 100644 index 0000000000..b2ac600895 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/test.cc @@ -0,0 +1,95 @@ +#include "../thneed.h" +#include "../../runners/snpemodel.h" + +#define TEMPORAL_SIZE 512 +#define DESIRE_LEN 8 +#define TRAFFIC_CONVENTION_LEN 2 + +void hexdump(uint32_t *d, int len); + +int main(int argc, char* argv[]) { + float *output = (float*)calloc(0x10000, sizeof(float)); + float *golden = (float*)calloc(0x10000, sizeof(float)); + SNPEModel mdl(argv[1], output, 0, USE_GPU_RUNTIME); + + // cmd line test + if (argc > 2) { + for (int i = 2; i < argc; i++) { + float *buf[5]; + FILE *f = fopen(argv[i], "rb"); + + size_t sz; + for (int j = 0; j < 5; j++) { + fread(&sz, 1, sizeof(sz), f); + printf("reading %zu\n", sz); + buf[j] = (float*)malloc(sz); + fread(buf[j], 1, sz, f); + } + + if (sz != 9532) continue; + + mdl.addRecurrent(buf[0], TEMPORAL_SIZE); + mdl.addTrafficConvention(buf[1], TRAFFIC_CONVENTION_LEN); + mdl.addDesire(buf[2], DESIRE_LEN); + mdl.execute(buf[3], 0); + + hexdump((uint32_t*)buf[4], 0x100); + hexdump((uint32_t*)output, 0x100); + + for (int j = 0; j < sz/4; j++) { + if (buf[4][j] != output[j]) { + printf("MISMATCH %d real:%f comp:%f\n", j, buf[4][j], output[j]); + } + } + } + + return 0; + } + + float state[TEMPORAL_SIZE]; + mdl.addRecurrent(state, TEMPORAL_SIZE); + + float desire[DESIRE_LEN]; + mdl.addDesire(desire, DESIRE_LEN); + + float traffic_convention[TRAFFIC_CONVENTION_LEN]; + mdl.addTrafficConvention(traffic_convention, TRAFFIC_CONVENTION_LEN); + + float *input = (float*)calloc(0x1000000, sizeof(float));; + + // first run + printf("************** execute 1 **************\n"); + memset(output, 0, sizeof(output)); + mdl.execute(input, 0); + hexdump((uint32_t *)output, 0x100); + memcpy(golden, output, sizeof(output)); + + // second run + printf("************** execute 2 **************\n"); + memset(output, 0, sizeof(output)); + Thneed *t = new Thneed(); + t->record = 3; // debug print with record + mdl.execute(input, 0); + t->stop(); + hexdump((uint32_t *)output, 0x100); + if (memcmp(golden, output, sizeof(output)) != 0) { printf("FAILURE\n"); return -1; } + + // third run + printf("************** execute 3 **************\n"); + memset(output, 0, sizeof(output)); + t->record = 2; // debug print w/o record + float *inputs[4] = {state, traffic_convention, desire, input}; + t->execute(inputs, output); + hexdump((uint32_t *)output, 0x100); + if (memcmp(golden, output, sizeof(output)) != 0) { printf("FAILURE\n"); return -1; } + + printf("************** execute 4 **************\n"); + memset(output, 0, sizeof(output)); + //t->record = 2; // debug print w/o record + t->execute(inputs, output); + hexdump((uint32_t *)output, 0x100); + if (memcmp(golden, output, sizeof(output)) != 0) { printf("FAILURE\n"); return -1; } + + printf("************** execute done **************\n"); +} + diff --git a/selfdrive/modeld/thneed/debug/thneed b/selfdrive/modeld/thneed/debug/thneed new file mode 100755 index 0000000000..ab2d721bb2 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/thneed @@ -0,0 +1,4 @@ +#!/bin/sh +export LD_LIBRARY_PATH="/data/openpilot/phonelibs/snpe/aarch64/:$HOME/openpilot/phonelibs/snpe/larch64:$HOME/openpilot/phonelibs/snpe/x86_64-linux-clang:$LD_LIBRARY_PATH" +exec ./_thneed $@ + diff --git a/selfdrive/modeld/thneed/include/msm_kgsl.h b/selfdrive/modeld/thneed/include/msm_kgsl.h new file mode 100644 index 0000000000..93582eb066 --- /dev/null +++ b/selfdrive/modeld/thneed/include/msm_kgsl.h @@ -0,0 +1,1449 @@ +#ifndef _UAPI_MSM_KGSL_H +#define _UAPI_MSM_KGSL_H + +#include +#include + +/* + * The KGSL version has proven not to be very useful in userspace if features + * are cherry picked into other trees out of order so it is frozen as of 3.14. + * It is left here for backwards compatabilty and as a reminder that + * software releases are never linear. Also, I like pie. + */ + +#define KGSL_VERSION_MAJOR 3 +#define KGSL_VERSION_MINOR 14 + +/* + * We have traditionally mixed context and issueibcmds / command batch flags + * together into a big flag stew. This worked fine until we started adding a + * lot more command batch flags and we started running out of bits. Turns out + * we have a bit of room in the context type / priority mask that we could use + * for command batches, but that means we need to split out the flags into two + * coherent sets. + * + * If any future definitions are for both context and cmdbatch add both defines + * and link the cmdbatch to the context define as we do below. Otherwise feel + * free to add exclusive bits to either set. + */ + +/* --- context flags --- */ +#define KGSL_CONTEXT_SAVE_GMEM 0x00000001 +#define KGSL_CONTEXT_NO_GMEM_ALLOC 0x00000002 +/* This is a cmdbatch exclusive flag - use the CMDBATCH equivalent instead */ +#define KGSL_CONTEXT_SUBMIT_IB_LIST 0x00000004 +#define KGSL_CONTEXT_CTX_SWITCH 0x00000008 +#define KGSL_CONTEXT_PREAMBLE 0x00000010 +#define KGSL_CONTEXT_TRASH_STATE 0x00000020 +#define KGSL_CONTEXT_PER_CONTEXT_TS 0x00000040 +#define KGSL_CONTEXT_USER_GENERATED_TS 0x00000080 +/* This is a cmdbatch exclusive flag - use the CMDBATCH equivalent instead */ +#define KGSL_CONTEXT_END_OF_FRAME 0x00000100 +#define KGSL_CONTEXT_NO_FAULT_TOLERANCE 0x00000200 +/* This is a cmdbatch exclusive flag - use the CMDBATCH equivalent instead */ +#define KGSL_CONTEXT_SYNC 0x00000400 +#define KGSL_CONTEXT_PWR_CONSTRAINT 0x00000800 + +#define KGSL_CONTEXT_PRIORITY_MASK 0x0000F000 +#define KGSL_CONTEXT_PRIORITY_SHIFT 12 +#define KGSL_CONTEXT_PRIORITY_UNDEF 0 + +#define KGSL_CONTEXT_IFH_NOP 0x00010000 +#define KGSL_CONTEXT_SECURE 0x00020000 + +#define KGSL_CONTEXT_PREEMPT_STYLE_MASK 0x0E000000 +#define KGSL_CONTEXT_PREEMPT_STYLE_SHIFT 25 +#define KGSL_CONTEXT_PREEMPT_STYLE_DEFAULT 0x0 +#define KGSL_CONTEXT_PREEMPT_STYLE_RINGBUFFER 0x1 +#define KGSL_CONTEXT_PREEMPT_STYLE_FINEGRAIN 0x2 + +#define KGSL_CONTEXT_TYPE_MASK 0x01F00000 +#define KGSL_CONTEXT_TYPE_SHIFT 20 +#define KGSL_CONTEXT_TYPE_ANY 0 +#define KGSL_CONTEXT_TYPE_GL 1 +#define KGSL_CONTEXT_TYPE_CL 2 +#define KGSL_CONTEXT_TYPE_C2D 3 +#define KGSL_CONTEXT_TYPE_RS 4 +#define KGSL_CONTEXT_TYPE_UNKNOWN 0x1E + +#define KGSL_CONTEXT_INVALID 0xffffffff + +/* + * --- command batch flags --- + * The bits that are linked to a KGSL_CONTEXT equivalent are either legacy + * definitions or bits that are valid for both contexts and cmdbatches. To be + * safe the other 8 bits that are still available in the context field should be + * omitted here in case we need to share - the other bits are available for + * cmdbatch only flags as needed + */ +#define KGSL_CMDBATCH_MEMLIST 0x00000001 +#define KGSL_CMDBATCH_MARKER 0x00000002 +#define KGSL_CMDBATCH_SUBMIT_IB_LIST KGSL_CONTEXT_SUBMIT_IB_LIST /* 0x004 */ +#define KGSL_CMDBATCH_CTX_SWITCH KGSL_CONTEXT_CTX_SWITCH /* 0x008 */ +#define KGSL_CMDBATCH_PROFILING 0x00000010 +#define KGSL_CMDBATCH_PROFILING_KTIME 0x00000020 +#define KGSL_CMDBATCH_END_OF_FRAME KGSL_CONTEXT_END_OF_FRAME /* 0x100 */ +#define KGSL_CMDBATCH_SYNC KGSL_CONTEXT_SYNC /* 0x400 */ +#define KGSL_CMDBATCH_PWR_CONSTRAINT KGSL_CONTEXT_PWR_CONSTRAINT /* 0x800 */ + +/* + * Reserve bits [16:19] and bits [28:31] for possible bits shared between + * contexts and command batches. Update this comment as new flags are added. + */ + +/* + * gpu_command_object flags - these flags communicate the type of command or + * memory object being submitted for a GPU command + */ + +/* Flags for GPU command objects */ +#define KGSL_CMDLIST_IB 0x00000001U +#define KGSL_CMDLIST_CTXTSWITCH_PREAMBLE 0x00000002U +#define KGSL_CMDLIST_IB_PREAMBLE 0x00000004U + +/* Flags for GPU command memory objects */ +#define KGSL_OBJLIST_MEMOBJ 0x00000008U +#define KGSL_OBJLIST_PROFILE 0x00000010U + +/* Flags for GPU command sync points */ +#define KGSL_CMD_SYNCPOINT_TYPE_TIMESTAMP 0 +#define KGSL_CMD_SYNCPOINT_TYPE_FENCE 1 + +/* --- Memory allocation flags --- */ + +/* General allocation hints */ +#define KGSL_MEMFLAGS_SECURE 0x00000008ULL +#define KGSL_MEMFLAGS_GPUREADONLY 0x01000000U +#define KGSL_MEMFLAGS_GPUWRITEONLY 0x02000000U +#define KGSL_MEMFLAGS_FORCE_32BIT 0x100000000ULL + +/* Memory caching hints */ +#define KGSL_CACHEMODE_MASK 0x0C000000U +#define KGSL_CACHEMODE_SHIFT 26 + +#define KGSL_CACHEMODE_WRITECOMBINE 0 +#define KGSL_CACHEMODE_UNCACHED 1 +#define KGSL_CACHEMODE_WRITETHROUGH 2 +#define KGSL_CACHEMODE_WRITEBACK 3 + +#define KGSL_MEMFLAGS_USE_CPU_MAP 0x10000000ULL + +/* Memory types for which allocations are made */ +#define KGSL_MEMTYPE_MASK 0x0000FF00 +#define KGSL_MEMTYPE_SHIFT 8 + +#define KGSL_MEMTYPE_OBJECTANY 0 +#define KGSL_MEMTYPE_FRAMEBUFFER 1 +#define KGSL_MEMTYPE_RENDERBUFFER 2 +#define KGSL_MEMTYPE_ARRAYBUFFER 3 +#define KGSL_MEMTYPE_ELEMENTARRAYBUFFER 4 +#define KGSL_MEMTYPE_VERTEXARRAYBUFFER 5 +#define KGSL_MEMTYPE_TEXTURE 6 +#define KGSL_MEMTYPE_SURFACE 7 +#define KGSL_MEMTYPE_EGL_SURFACE 8 +#define KGSL_MEMTYPE_GL 9 +#define KGSL_MEMTYPE_CL 10 +#define KGSL_MEMTYPE_CL_BUFFER_MAP 11 +#define KGSL_MEMTYPE_CL_BUFFER_NOMAP 12 +#define KGSL_MEMTYPE_CL_IMAGE_MAP 13 +#define KGSL_MEMTYPE_CL_IMAGE_NOMAP 14 +#define KGSL_MEMTYPE_CL_KERNEL_STACK 15 +#define KGSL_MEMTYPE_COMMAND 16 +#define KGSL_MEMTYPE_2D 17 +#define KGSL_MEMTYPE_EGL_IMAGE 18 +#define KGSL_MEMTYPE_EGL_SHADOW 19 +#define KGSL_MEMTYPE_MULTISAMPLE 20 +#define KGSL_MEMTYPE_KERNEL 255 + +/* + * Alignment hint, passed as the power of 2 exponent. + * i.e 4k (2^12) would be 12, 64k (2^16)would be 16. + */ +#define KGSL_MEMALIGN_MASK 0x00FF0000 +#define KGSL_MEMALIGN_SHIFT 16 + +enum kgsl_user_mem_type { + KGSL_USER_MEM_TYPE_PMEM = 0x00000000, + KGSL_USER_MEM_TYPE_ASHMEM = 0x00000001, + KGSL_USER_MEM_TYPE_ADDR = 0x00000002, + KGSL_USER_MEM_TYPE_ION = 0x00000003, + /* + * ION type is retained for backwards compatibilty but Ion buffers are + * dma-bufs so try to use that naming if we can + */ + KGSL_USER_MEM_TYPE_DMABUF = 0x00000003, + KGSL_USER_MEM_TYPE_MAX = 0x00000007, +}; +#define KGSL_MEMFLAGS_USERMEM_MASK 0x000000e0 +#define KGSL_MEMFLAGS_USERMEM_SHIFT 5 + +/* + * Unfortunately, enum kgsl_user_mem_type starts at 0 which does not + * leave a good value for allocated memory. In the flags we use + * 0 to indicate allocated memory and thus need to add 1 to the enum + * values. + */ +#define KGSL_USERMEM_FLAG(x) (((x) + 1) << KGSL_MEMFLAGS_USERMEM_SHIFT) + +#define KGSL_MEMFLAGS_NOT_USERMEM 0 +#define KGSL_MEMFLAGS_USERMEM_PMEM KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_PMEM) +#define KGSL_MEMFLAGS_USERMEM_ASHMEM \ + KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_ASHMEM) +#define KGSL_MEMFLAGS_USERMEM_ADDR KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_ADDR) +#define KGSL_MEMFLAGS_USERMEM_ION KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_ION) + +/* --- generic KGSL flag values --- */ + +#define KGSL_FLAGS_NORMALMODE 0x00000000 +#define KGSL_FLAGS_SAFEMODE 0x00000001 +#define KGSL_FLAGS_INITIALIZED0 0x00000002 +#define KGSL_FLAGS_INITIALIZED 0x00000004 +#define KGSL_FLAGS_STARTED 0x00000008 +#define KGSL_FLAGS_ACTIVE 0x00000010 +#define KGSL_FLAGS_RESERVED0 0x00000020 +#define KGSL_FLAGS_RESERVED1 0x00000040 +#define KGSL_FLAGS_RESERVED2 0x00000080 +#define KGSL_FLAGS_SOFT_RESET 0x00000100 +#define KGSL_FLAGS_PER_CONTEXT_TIMESTAMPS 0x00000200 + +/* Server Side Sync Timeout in milliseconds */ +#define KGSL_SYNCOBJ_SERVER_TIMEOUT 2000 + +/* + * Reset status values for context + */ +enum kgsl_ctx_reset_stat { + KGSL_CTX_STAT_NO_ERROR = 0x00000000, + KGSL_CTX_STAT_GUILTY_CONTEXT_RESET_EXT = 0x00000001, + KGSL_CTX_STAT_INNOCENT_CONTEXT_RESET_EXT = 0x00000002, + KGSL_CTX_STAT_UNKNOWN_CONTEXT_RESET_EXT = 0x00000003 +}; + +#define KGSL_CONVERT_TO_MBPS(val) \ + (val*1000*1000U) + +/* device id */ +enum kgsl_deviceid { + KGSL_DEVICE_3D0 = 0x00000000, + KGSL_DEVICE_MAX +}; + +struct kgsl_devinfo { + + unsigned int device_id; + /* chip revision id + * coreid:8 majorrev:8 minorrev:8 patch:8 + */ + unsigned int chip_id; + unsigned int mmu_enabled; + unsigned long gmem_gpubaseaddr; + /* + * This field contains the adreno revision + * number 200, 205, 220, etc... + */ + unsigned int gpu_id; + size_t gmem_sizebytes; +}; + +/* + * struct kgsl_devmemstore - this structure defines the region of memory + * that can be mmap()ed from this driver. The timestamp fields are volatile + * because they are written by the GPU + * @soptimestamp: Start of pipeline timestamp written by GPU before the + * commands in concern are processed + * @sbz: Unused, kept for 8 byte alignment + * @eoptimestamp: End of pipeline timestamp written by GPU after the + * commands in concern are processed + * @sbz2: Unused, kept for 8 byte alignment + * @preempted: Indicates if the context was preempted + * @sbz3: Unused, kept for 8 byte alignment + * @ref_wait_ts: Timestamp on which to generate interrupt, unused now. + * @sbz4: Unused, kept for 8 byte alignment + * @current_context: The current context the GPU is working on + * @sbz5: Unused, kept for 8 byte alignment + */ +struct kgsl_devmemstore { + volatile unsigned int soptimestamp; + unsigned int sbz; + volatile unsigned int eoptimestamp; + unsigned int sbz2; + volatile unsigned int preempted; + unsigned int sbz3; + volatile unsigned int ref_wait_ts; + unsigned int sbz4; + unsigned int current_context; + unsigned int sbz5; +}; + +#define KGSL_MEMSTORE_OFFSET(ctxt_id, field) \ + ((ctxt_id)*sizeof(struct kgsl_devmemstore) + \ + offsetof(struct kgsl_devmemstore, field)) + +/* timestamp id*/ +enum kgsl_timestamp_type { + KGSL_TIMESTAMP_CONSUMED = 0x00000001, /* start-of-pipeline timestamp */ + KGSL_TIMESTAMP_RETIRED = 0x00000002, /* end-of-pipeline timestamp*/ + KGSL_TIMESTAMP_QUEUED = 0x00000003, +}; + +/* property types - used with kgsl_device_getproperty */ +#define KGSL_PROP_DEVICE_INFO 0x1 +#define KGSL_PROP_DEVICE_SHADOW 0x2 +#define KGSL_PROP_DEVICE_POWER 0x3 +#define KGSL_PROP_SHMEM 0x4 +#define KGSL_PROP_SHMEM_APERTURES 0x5 +#define KGSL_PROP_MMU_ENABLE 0x6 +#define KGSL_PROP_INTERRUPT_WAITS 0x7 +#define KGSL_PROP_VERSION 0x8 +#define KGSL_PROP_GPU_RESET_STAT 0x9 +#define KGSL_PROP_PWRCTRL 0xE +#define KGSL_PROP_PWR_CONSTRAINT 0x12 +#define KGSL_PROP_UCHE_GMEM_VADDR 0x13 +#define KGSL_PROP_SP_GENERIC_MEM 0x14 +#define KGSL_PROP_UCODE_VERSION 0x15 +#define KGSL_PROP_GPMU_VERSION 0x16 +#define KGSL_PROP_DEVICE_BITNESS 0x18 + +struct kgsl_shadowprop { + unsigned long gpuaddr; + size_t size; + unsigned int flags; /* contains KGSL_FLAGS_ values */ +}; + +struct kgsl_version { + unsigned int drv_major; + unsigned int drv_minor; + unsigned int dev_major; + unsigned int dev_minor; +}; + +struct kgsl_sp_generic_mem { + uint64_t local; + uint64_t pvt; +}; + +struct kgsl_ucode_version { + unsigned int pfp; + unsigned int pm4; +}; + +struct kgsl_gpmu_version { + unsigned int major; + unsigned int minor; + unsigned int features; +}; + +/* Performance counter groups */ + +#define KGSL_PERFCOUNTER_GROUP_CP 0x0 +#define KGSL_PERFCOUNTER_GROUP_RBBM 0x1 +#define KGSL_PERFCOUNTER_GROUP_PC 0x2 +#define KGSL_PERFCOUNTER_GROUP_VFD 0x3 +#define KGSL_PERFCOUNTER_GROUP_HLSQ 0x4 +#define KGSL_PERFCOUNTER_GROUP_VPC 0x5 +#define KGSL_PERFCOUNTER_GROUP_TSE 0x6 +#define KGSL_PERFCOUNTER_GROUP_RAS 0x7 +#define KGSL_PERFCOUNTER_GROUP_UCHE 0x8 +#define KGSL_PERFCOUNTER_GROUP_TP 0x9 +#define KGSL_PERFCOUNTER_GROUP_SP 0xA +#define KGSL_PERFCOUNTER_GROUP_RB 0xB +#define KGSL_PERFCOUNTER_GROUP_PWR 0xC +#define KGSL_PERFCOUNTER_GROUP_VBIF 0xD +#define KGSL_PERFCOUNTER_GROUP_VBIF_PWR 0xE +#define KGSL_PERFCOUNTER_GROUP_MH 0xF +#define KGSL_PERFCOUNTER_GROUP_PA_SU 0x10 +#define KGSL_PERFCOUNTER_GROUP_SQ 0x11 +#define KGSL_PERFCOUNTER_GROUP_SX 0x12 +#define KGSL_PERFCOUNTER_GROUP_TCF 0x13 +#define KGSL_PERFCOUNTER_GROUP_TCM 0x14 +#define KGSL_PERFCOUNTER_GROUP_TCR 0x15 +#define KGSL_PERFCOUNTER_GROUP_L2 0x16 +#define KGSL_PERFCOUNTER_GROUP_VSC 0x17 +#define KGSL_PERFCOUNTER_GROUP_CCU 0x18 +#define KGSL_PERFCOUNTER_GROUP_LRZ 0x19 +#define KGSL_PERFCOUNTER_GROUP_CMP 0x1A +#define KGSL_PERFCOUNTER_GROUP_ALWAYSON 0x1B +#define KGSL_PERFCOUNTER_GROUP_SP_PWR 0x1C +#define KGSL_PERFCOUNTER_GROUP_TP_PWR 0x1D +#define KGSL_PERFCOUNTER_GROUP_RB_PWR 0x1E +#define KGSL_PERFCOUNTER_GROUP_CCU_PWR 0x1F +#define KGSL_PERFCOUNTER_GROUP_UCHE_PWR 0x20 +#define KGSL_PERFCOUNTER_GROUP_CP_PWR 0x21 +#define KGSL_PERFCOUNTER_GROUP_GPMU_PWR 0x22 +#define KGSL_PERFCOUNTER_GROUP_ALWAYSON_PWR 0x23 +#define KGSL_PERFCOUNTER_GROUP_MAX 0x24 + +#define KGSL_PERFCOUNTER_NOT_USED 0xFFFFFFFF +#define KGSL_PERFCOUNTER_BROKEN 0xFFFFFFFE + +/* structure holds list of ibs */ +struct kgsl_ibdesc { + unsigned long gpuaddr; + unsigned long __pad; + size_t sizedwords; + unsigned int ctrl; +}; + +/** + * struct kgsl_cmdbatch_profiling_buffer + * @wall_clock_s: Ringbuffer submission time (seconds). + * If KGSL_CMDBATCH_PROFILING_KTIME is set, time is provided + * in kernel clocks, otherwise wall clock time is used. + * @wall_clock_ns: Ringbuffer submission time (nanoseconds). + * If KGSL_CMDBATCH_PROFILING_KTIME is set time is provided + * in kernel clocks, otherwise wall clock time is used. + * @gpu_ticks_queued: GPU ticks at ringbuffer submission + * @gpu_ticks_submitted: GPU ticks when starting cmdbatch execution + * @gpu_ticks_retired: GPU ticks when finishing cmdbatch execution + * + * This structure defines the profiling buffer used to measure cmdbatch + * execution time + */ +struct kgsl_cmdbatch_profiling_buffer { + uint64_t wall_clock_s; + uint64_t wall_clock_ns; + uint64_t gpu_ticks_queued; + uint64_t gpu_ticks_submitted; + uint64_t gpu_ticks_retired; +}; + +/* ioctls */ +#define KGSL_IOC_TYPE 0x09 + +/* get misc info about the GPU + type should be a value from enum kgsl_property_type + value points to a structure that varies based on type + sizebytes is sizeof() that structure + for KGSL_PROP_DEVICE_INFO, use struct kgsl_devinfo + this structure contaings hardware versioning info. + for KGSL_PROP_DEVICE_SHADOW, use struct kgsl_shadowprop + this is used to find mmap() offset and sizes for mapping + struct kgsl_memstore into userspace. +*/ +struct kgsl_device_getproperty { + unsigned int type; + void __user *value; + size_t sizebytes; +}; + +#define IOCTL_KGSL_DEVICE_GETPROPERTY \ + _IOWR(KGSL_IOC_TYPE, 0x2, struct kgsl_device_getproperty) + +/* IOCTL_KGSL_DEVICE_READ (0x3) - removed 03/2012 + */ + +/* block until the GPU has executed past a given timestamp + * timeout is in milliseconds. + */ +struct kgsl_device_waittimestamp { + unsigned int timestamp; + unsigned int timeout; +}; + +#define IOCTL_KGSL_DEVICE_WAITTIMESTAMP \ + _IOW(KGSL_IOC_TYPE, 0x6, struct kgsl_device_waittimestamp) + +struct kgsl_device_waittimestamp_ctxtid { + unsigned int context_id; + unsigned int timestamp; + unsigned int timeout; +}; + +#define IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID \ + _IOW(KGSL_IOC_TYPE, 0x7, struct kgsl_device_waittimestamp_ctxtid) + +/* DEPRECATED: issue indirect commands to the GPU. + * drawctxt_id must have been created with IOCTL_KGSL_DRAWCTXT_CREATE + * ibaddr and sizedwords must specify a subset of a buffer created + * with IOCTL_KGSL_SHAREDMEM_FROM_PMEM + * flags may be a mask of KGSL_CONTEXT_ values + * timestamp is a returned counter value which can be passed to + * other ioctls to determine when the commands have been executed by + * the GPU. + * + * This fucntion is deprecated - consider using IOCTL_KGSL_SUBMIT_COMMANDS + * instead + */ +struct kgsl_ringbuffer_issueibcmds { + unsigned int drawctxt_id; + unsigned long ibdesc_addr; + unsigned int numibs; + unsigned int timestamp; /*output param */ + unsigned int flags; +}; + +#define IOCTL_KGSL_RINGBUFFER_ISSUEIBCMDS \ + _IOWR(KGSL_IOC_TYPE, 0x10, struct kgsl_ringbuffer_issueibcmds) + +/* read the most recently executed timestamp value + * type should be a value from enum kgsl_timestamp_type + */ +struct kgsl_cmdstream_readtimestamp { + unsigned int type; + unsigned int timestamp; /*output param */ +}; + +#define IOCTL_KGSL_CMDSTREAM_READTIMESTAMP_OLD \ + _IOR(KGSL_IOC_TYPE, 0x11, struct kgsl_cmdstream_readtimestamp) + +#define IOCTL_KGSL_CMDSTREAM_READTIMESTAMP \ + _IOWR(KGSL_IOC_TYPE, 0x11, struct kgsl_cmdstream_readtimestamp) + +/* free memory when the GPU reaches a given timestamp. + * gpuaddr specify a memory region created by a + * IOCTL_KGSL_SHAREDMEM_FROM_PMEM call + * type should be a value from enum kgsl_timestamp_type + */ +struct kgsl_cmdstream_freememontimestamp { + unsigned long gpuaddr; + unsigned int type; + unsigned int timestamp; +}; + +#define IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP \ + _IOW(KGSL_IOC_TYPE, 0x12, struct kgsl_cmdstream_freememontimestamp) + +/* Previous versions of this header had incorrectly defined + IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP as a read-only ioctl instead + of a write only ioctl. To ensure binary compatability, the following + #define will be used to intercept the incorrect ioctl +*/ + +#define IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP_OLD \ + _IOR(KGSL_IOC_TYPE, 0x12, struct kgsl_cmdstream_freememontimestamp) + +/* create a draw context, which is used to preserve GPU state. + * The flags field may contain a mask KGSL_CONTEXT_* values + */ +struct kgsl_drawctxt_create { + unsigned int flags; + unsigned int drawctxt_id; /*output param */ +}; + +#define IOCTL_KGSL_DRAWCTXT_CREATE \ + _IOWR(KGSL_IOC_TYPE, 0x13, struct kgsl_drawctxt_create) + +/* destroy a draw context */ +struct kgsl_drawctxt_destroy { + unsigned int drawctxt_id; +}; + +#define IOCTL_KGSL_DRAWCTXT_DESTROY \ + _IOW(KGSL_IOC_TYPE, 0x14, struct kgsl_drawctxt_destroy) + +/* add a block of pmem, fb, ashmem or user allocated address + * into the GPU address space */ +struct kgsl_map_user_mem { + int fd; + unsigned long gpuaddr; /*output param */ + size_t len; + size_t offset; + unsigned long hostptr; /*input param */ + enum kgsl_user_mem_type memtype; + unsigned int flags; +}; + +#define IOCTL_KGSL_MAP_USER_MEM \ + _IOWR(KGSL_IOC_TYPE, 0x15, struct kgsl_map_user_mem) + +struct kgsl_cmdstream_readtimestamp_ctxtid { + unsigned int context_id; + unsigned int type; + unsigned int timestamp; /*output param */ +}; + +#define IOCTL_KGSL_CMDSTREAM_READTIMESTAMP_CTXTID \ + _IOWR(KGSL_IOC_TYPE, 0x16, struct kgsl_cmdstream_readtimestamp_ctxtid) + +struct kgsl_cmdstream_freememontimestamp_ctxtid { + unsigned int context_id; + unsigned long gpuaddr; + unsigned int type; + unsigned int timestamp; +}; + +#define IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP_CTXTID \ + _IOW(KGSL_IOC_TYPE, 0x17, \ + struct kgsl_cmdstream_freememontimestamp_ctxtid) + +/* add a block of pmem or fb into the GPU address space */ +struct kgsl_sharedmem_from_pmem { + int pmem_fd; + unsigned long gpuaddr; /*output param */ + unsigned int len; + unsigned int offset; +}; + +#define IOCTL_KGSL_SHAREDMEM_FROM_PMEM \ + _IOWR(KGSL_IOC_TYPE, 0x20, struct kgsl_sharedmem_from_pmem) + +/* remove memory from the GPU's address space */ +struct kgsl_sharedmem_free { + unsigned long gpuaddr; +}; + +#define IOCTL_KGSL_SHAREDMEM_FREE \ + _IOW(KGSL_IOC_TYPE, 0x21, struct kgsl_sharedmem_free) + +struct kgsl_cff_user_event { + unsigned char cff_opcode; + unsigned int op1; + unsigned int op2; + unsigned int op3; + unsigned int op4; + unsigned int op5; + unsigned int __pad[2]; +}; + +#define IOCTL_KGSL_CFF_USER_EVENT \ + _IOW(KGSL_IOC_TYPE, 0x31, struct kgsl_cff_user_event) + +struct kgsl_gmem_desc { + unsigned int x; + unsigned int y; + unsigned int width; + unsigned int height; + unsigned int pitch; +}; + +struct kgsl_buffer_desc { + void *hostptr; + unsigned long gpuaddr; + int size; + unsigned int format; + unsigned int pitch; + unsigned int enabled; +}; + +struct kgsl_bind_gmem_shadow { + unsigned int drawctxt_id; + struct kgsl_gmem_desc gmem_desc; + unsigned int shadow_x; + unsigned int shadow_y; + struct kgsl_buffer_desc shadow_buffer; + unsigned int buffer_id; +}; + +#define IOCTL_KGSL_DRAWCTXT_BIND_GMEM_SHADOW \ + _IOW(KGSL_IOC_TYPE, 0x22, struct kgsl_bind_gmem_shadow) + +/* add a block of memory into the GPU address space */ + +/* + * IOCTL_KGSL_SHAREDMEM_FROM_VMALLOC deprecated 09/2012 + * use IOCTL_KGSL_GPUMEM_ALLOC instead + */ + +struct kgsl_sharedmem_from_vmalloc { + unsigned long gpuaddr; /*output param */ + unsigned int hostptr; + unsigned int flags; +}; + +#define IOCTL_KGSL_SHAREDMEM_FROM_VMALLOC \ + _IOWR(KGSL_IOC_TYPE, 0x23, struct kgsl_sharedmem_from_vmalloc) + +/* + * This is being deprecated in favor of IOCTL_KGSL_GPUMEM_CACHE_SYNC which + * supports both directions (flush and invalidate). This code will still + * work, but by definition it will do a flush of the cache which might not be + * what you want to have happen on a buffer following a GPU operation. It is + * safer to go with IOCTL_KGSL_GPUMEM_CACHE_SYNC + */ + +#define IOCTL_KGSL_SHAREDMEM_FLUSH_CACHE \ + _IOW(KGSL_IOC_TYPE, 0x24, struct kgsl_sharedmem_free) + +struct kgsl_drawctxt_set_bin_base_offset { + unsigned int drawctxt_id; + unsigned int offset; +}; + +#define IOCTL_KGSL_DRAWCTXT_SET_BIN_BASE_OFFSET \ + _IOW(KGSL_IOC_TYPE, 0x25, struct kgsl_drawctxt_set_bin_base_offset) + +enum kgsl_cmdwindow_type { + KGSL_CMDWINDOW_MIN = 0x00000000, + KGSL_CMDWINDOW_2D = 0x00000000, + KGSL_CMDWINDOW_3D = 0x00000001, /* legacy */ + KGSL_CMDWINDOW_MMU = 0x00000002, + KGSL_CMDWINDOW_ARBITER = 0x000000FF, + KGSL_CMDWINDOW_MAX = 0x000000FF, +}; + +/* write to the command window */ +struct kgsl_cmdwindow_write { + enum kgsl_cmdwindow_type target; + unsigned int addr; + unsigned int data; +}; + +#define IOCTL_KGSL_CMDWINDOW_WRITE \ + _IOW(KGSL_IOC_TYPE, 0x2e, struct kgsl_cmdwindow_write) + +struct kgsl_gpumem_alloc { + unsigned long gpuaddr; /* output param */ + size_t size; + unsigned int flags; +}; + +#define IOCTL_KGSL_GPUMEM_ALLOC \ + _IOWR(KGSL_IOC_TYPE, 0x2f, struct kgsl_gpumem_alloc) + +struct kgsl_cff_syncmem { + unsigned long gpuaddr; + size_t len; + unsigned int __pad[2]; /* For future binary compatibility */ +}; + +#define IOCTL_KGSL_CFF_SYNCMEM \ + _IOW(KGSL_IOC_TYPE, 0x30, struct kgsl_cff_syncmem) + +/* + * A timestamp event allows the user space to register an action following an + * expired timestamp. Note IOCTL_KGSL_TIMESTAMP_EVENT has been redefined to + * _IOWR to support fences which need to return a fd for the priv parameter. + */ + +struct kgsl_timestamp_event { + int type; /* Type of event (see list below) */ + unsigned int timestamp; /* Timestamp to trigger event on */ + unsigned int context_id; /* Context for the timestamp */ + void __user *priv; /* Pointer to the event specific blob */ + size_t len; /* Size of the event specific blob */ +}; + +#define IOCTL_KGSL_TIMESTAMP_EVENT_OLD \ + _IOW(KGSL_IOC_TYPE, 0x31, struct kgsl_timestamp_event) + +/* A genlock timestamp event releases an existing lock on timestamp expire */ + +#define KGSL_TIMESTAMP_EVENT_GENLOCK 1 + +struct kgsl_timestamp_event_genlock { + int handle; /* Handle of the genlock lock to release */ +}; + +/* A fence timestamp event releases an existing lock on timestamp expire */ + +#define KGSL_TIMESTAMP_EVENT_FENCE 2 + +struct kgsl_timestamp_event_fence { + int fence_fd; /* Fence to signal */ +}; + +/* + * Set a property within the kernel. Uses the same structure as + * IOCTL_KGSL_GETPROPERTY + */ + +#define IOCTL_KGSL_SETPROPERTY \ + _IOW(KGSL_IOC_TYPE, 0x32, struct kgsl_device_getproperty) + +#define IOCTL_KGSL_TIMESTAMP_EVENT \ + _IOWR(KGSL_IOC_TYPE, 0x33, struct kgsl_timestamp_event) + +/** + * struct kgsl_gpumem_alloc_id - argument to IOCTL_KGSL_GPUMEM_ALLOC_ID + * @id: returned id value for this allocation. + * @flags: mask of KGSL_MEM* values requested and actual flags on return. + * @size: requested size of the allocation and actual size on return. + * @mmapsize: returned size to pass to mmap() which may be larger than 'size' + * @gpuaddr: returned GPU address for the allocation + * + * Allocate memory for access by the GPU. The flags and size fields are echoed + * back by the kernel, so that the caller can know if the request was + * adjusted. + * + * Supported flags: + * KGSL_MEMFLAGS_GPUREADONLY: the GPU will be unable to write to the buffer + * KGSL_MEMTYPE*: usage hint for debugging aid + * KGSL_MEMALIGN*: alignment hint, may be ignored or adjusted by the kernel. + * KGSL_MEMFLAGS_USE_CPU_MAP: If set on call and return, the returned GPU + * address will be 0. Calling mmap() will set the GPU address. + */ +struct kgsl_gpumem_alloc_id { + unsigned int id; + unsigned int flags; + size_t size; + size_t mmapsize; + unsigned long gpuaddr; +/* private: reserved for future use*/ + unsigned long __pad[2]; +}; + +#define IOCTL_KGSL_GPUMEM_ALLOC_ID \ + _IOWR(KGSL_IOC_TYPE, 0x34, struct kgsl_gpumem_alloc_id) + +/** + * struct kgsl_gpumem_free_id - argument to IOCTL_KGSL_GPUMEM_FREE_ID + * @id: GPU allocation id to free + * + * Free an allocation by id, in case a GPU address has not been assigned or + * is unknown. Freeing an allocation by id with this ioctl or by GPU address + * with IOCTL_KGSL_SHAREDMEM_FREE are equivalent. + */ +struct kgsl_gpumem_free_id { + unsigned int id; +/* private: reserved for future use*/ + unsigned int __pad; +}; + +#define IOCTL_KGSL_GPUMEM_FREE_ID \ + _IOWR(KGSL_IOC_TYPE, 0x35, struct kgsl_gpumem_free_id) + +/** + * struct kgsl_gpumem_get_info - argument to IOCTL_KGSL_GPUMEM_GET_INFO + * @gpuaddr: GPU address to query. Also set on return. + * @id: GPU allocation id to query. Also set on return. + * @flags: returned mask of KGSL_MEM* values. + * @size: returned size of the allocation. + * @mmapsize: returned size to pass mmap(), which may be larger than 'size' + * @useraddr: returned address of the userspace mapping for this buffer + * + * This ioctl allows querying of all user visible attributes of an existing + * allocation, by either the GPU address or the id returned by a previous + * call to IOCTL_KGSL_GPUMEM_ALLOC_ID. Legacy allocation ioctls may not + * return all attributes so this ioctl can be used to look them up if needed. + * + */ +struct kgsl_gpumem_get_info { + unsigned long gpuaddr; + unsigned int id; + unsigned int flags; + size_t size; + size_t mmapsize; + unsigned long useraddr; +/* private: reserved for future use*/ + unsigned long __pad[4]; +}; + +#define IOCTL_KGSL_GPUMEM_GET_INFO\ + _IOWR(KGSL_IOC_TYPE, 0x36, struct kgsl_gpumem_get_info) + +/** + * struct kgsl_gpumem_sync_cache - argument to IOCTL_KGSL_GPUMEM_SYNC_CACHE + * @gpuaddr: GPU address of the buffer to sync. + * @id: id of the buffer to sync. Either gpuaddr or id is sufficient. + * @op: a mask of KGSL_GPUMEM_CACHE_* values + * @offset: offset into the buffer + * @length: number of bytes starting from offset to perform + * the cache operation on + * + * Sync the L2 cache for memory headed to and from the GPU - this replaces + * KGSL_SHAREDMEM_FLUSH_CACHE since it can handle cache management for both + * directions + * + */ +struct kgsl_gpumem_sync_cache { + unsigned long gpuaddr; + unsigned int id; + unsigned int op; + size_t offset; + size_t length; +}; + +#define KGSL_GPUMEM_CACHE_CLEAN (1 << 0) +#define KGSL_GPUMEM_CACHE_TO_GPU KGSL_GPUMEM_CACHE_CLEAN + +#define KGSL_GPUMEM_CACHE_INV (1 << 1) +#define KGSL_GPUMEM_CACHE_FROM_GPU KGSL_GPUMEM_CACHE_INV + +#define KGSL_GPUMEM_CACHE_FLUSH \ + (KGSL_GPUMEM_CACHE_CLEAN | KGSL_GPUMEM_CACHE_INV) + +/* Flag to ensure backwards compatibility of kgsl_gpumem_sync_cache struct */ +#define KGSL_GPUMEM_CACHE_RANGE (1 << 31U) + +#define IOCTL_KGSL_GPUMEM_SYNC_CACHE \ + _IOW(KGSL_IOC_TYPE, 0x37, struct kgsl_gpumem_sync_cache) + +/** + * struct kgsl_perfcounter_get - argument to IOCTL_KGSL_PERFCOUNTER_GET + * @groupid: Performance counter group ID + * @countable: Countable to select within the group + * @offset: Return offset of the reserved LO counter + * @offset_hi: Return offset of the reserved HI counter + * + * Get an available performance counter from a specified groupid. The offset + * of the performance counter will be returned after successfully assigning + * the countable to the counter for the specified group. An error will be + * returned and an offset of 0 if the groupid is invalid or there are no + * more counters left. After successfully getting a perfcounter, the user + * must call kgsl_perfcounter_put(groupid, contable) when finished with + * the perfcounter to clear up perfcounter resources. + * + */ +struct kgsl_perfcounter_get { + unsigned int groupid; + unsigned int countable; + unsigned int offset; + unsigned int offset_hi; +/* private: reserved for future use */ + unsigned int __pad; /* For future binary compatibility */ +}; + +#define IOCTL_KGSL_PERFCOUNTER_GET \ + _IOWR(KGSL_IOC_TYPE, 0x38, struct kgsl_perfcounter_get) + +/** + * struct kgsl_perfcounter_put - argument to IOCTL_KGSL_PERFCOUNTER_PUT + * @groupid: Performance counter group ID + * @countable: Countable to release within the group + * + * Put an allocated performance counter to allow others to have access to the + * resource that was previously taken. This is only to be called after + * successfully getting a performance counter from kgsl_perfcounter_get(). + * + */ +struct kgsl_perfcounter_put { + unsigned int groupid; + unsigned int countable; +/* private: reserved for future use */ + unsigned int __pad[2]; /* For future binary compatibility */ +}; + +#define IOCTL_KGSL_PERFCOUNTER_PUT \ + _IOW(KGSL_IOC_TYPE, 0x39, struct kgsl_perfcounter_put) + +/** + * struct kgsl_perfcounter_query - argument to IOCTL_KGSL_PERFCOUNTER_QUERY + * @groupid: Performance counter group ID + * @countable: Return active countables array + * @size: Size of active countables array + * @max_counters: Return total number counters for the group ID + * + * Query the available performance counters given a groupid. The array + * *countables is used to return the current active countables in counters. + * The size of the array is passed in so the kernel will only write at most + * size or counter->size for the group id. The total number of available + * counters for the group ID is returned in max_counters. + * If the array or size passed in are invalid, then only the maximum number + * of counters will be returned, no data will be written to *countables. + * If the groupid is invalid an error code will be returned. + * + */ +struct kgsl_perfcounter_query { + unsigned int groupid; + /* Array to return the current countable for up to size counters */ + unsigned int __user *countables; + unsigned int count; + unsigned int max_counters; +/* private: reserved for future use */ + unsigned int __pad[2]; /* For future binary compatibility */ +}; + +#define IOCTL_KGSL_PERFCOUNTER_QUERY \ + _IOWR(KGSL_IOC_TYPE, 0x3A, struct kgsl_perfcounter_query) + +/** + * struct kgsl_perfcounter_query - argument to IOCTL_KGSL_PERFCOUNTER_QUERY + * @groupid: Performance counter group IDs + * @countable: Performance counter countable IDs + * @value: Return performance counter reads + * @size: Size of all arrays (groupid/countable pair and return value) + * + * Read in the current value of a performance counter given by the groupid + * and countable. + * + */ + +struct kgsl_perfcounter_read_group { + unsigned int groupid; + unsigned int countable; + unsigned long long value; +}; + +struct kgsl_perfcounter_read { + struct kgsl_perfcounter_read_group __user *reads; + unsigned int count; +/* private: reserved for future use */ + unsigned int __pad[2]; /* For future binary compatibility */ +}; + +#define IOCTL_KGSL_PERFCOUNTER_READ \ + _IOWR(KGSL_IOC_TYPE, 0x3B, struct kgsl_perfcounter_read) +/* + * struct kgsl_gpumem_sync_cache_bulk - argument to + * IOCTL_KGSL_GPUMEM_SYNC_CACHE_BULK + * @id_list: list of GPU buffer ids of the buffers to sync + * @count: number of GPU buffer ids in id_list + * @op: a mask of KGSL_GPUMEM_CACHE_* values + * + * Sync the cache for memory headed to and from the GPU. Certain + * optimizations can be made on the cache operation based on the total + * size of the working set of memory to be managed. + */ +struct kgsl_gpumem_sync_cache_bulk { + unsigned int __user *id_list; + unsigned int count; + unsigned int op; +/* private: reserved for future use */ + unsigned int __pad[2]; /* For future binary compatibility */ +}; + +#define IOCTL_KGSL_GPUMEM_SYNC_CACHE_BULK \ + _IOWR(KGSL_IOC_TYPE, 0x3C, struct kgsl_gpumem_sync_cache_bulk) + +/* + * struct kgsl_cmd_syncpoint_timestamp + * @context_id: ID of a KGSL context + * @timestamp: GPU timestamp + * + * This structure defines a syncpoint comprising a context/timestamp pair. A + * list of these may be passed by IOCTL_KGSL_SUBMIT_COMMANDS to define + * dependencies that must be met before the command can be submitted to the + * hardware + */ +struct kgsl_cmd_syncpoint_timestamp { + unsigned int context_id; + unsigned int timestamp; +}; + +struct kgsl_cmd_syncpoint_fence { + int fd; +}; + +/** + * struct kgsl_cmd_syncpoint - Define a sync point for a command batch + * @type: type of sync point defined here + * @priv: Pointer to the type specific buffer + * @size: Size of the type specific buffer + * + * This structure contains pointers defining a specific command sync point. + * The pointer and size should point to a type appropriate structure. + */ +struct kgsl_cmd_syncpoint { + int type; + void __user *priv; + size_t size; +}; + +/* Flag to indicate that the cmdlist may contain memlists */ +#define KGSL_IBDESC_MEMLIST 0x1 + +/* Flag to point out the cmdbatch profiling buffer in the memlist */ +#define KGSL_IBDESC_PROFILING_BUFFER 0x2 + +/** + * struct kgsl_submit_commands - Argument to IOCTL_KGSL_SUBMIT_COMMANDS + * @context_id: KGSL context ID that owns the commands + * @flags: + * @cmdlist: User pointer to a list of kgsl_ibdesc structures + * @numcmds: Number of commands listed in cmdlist + * @synclist: User pointer to a list of kgsl_cmd_syncpoint structures + * @numsyncs: Number of sync points listed in synclist + * @timestamp: On entry the a user defined timestamp, on exist the timestamp + * assigned to the command batch + * + * This structure specifies a command to send to the GPU hardware. This is + * similar to kgsl_issueibcmds expect that it doesn't support the legacy way to + * submit IB lists and it adds sync points to block the IB until the + * dependencies are satisified. This entry point is the new and preferred way + * to submit commands to the GPU. The memory list can be used to specify all + * memory that is referrenced in the current set of commands. + */ + +struct kgsl_submit_commands { + unsigned int context_id; + unsigned int flags; + struct kgsl_ibdesc __user *cmdlist; + unsigned int numcmds; + struct kgsl_cmd_syncpoint __user *synclist; + unsigned int numsyncs; + unsigned int timestamp; +/* private: reserved for future use */ + unsigned int __pad[4]; +}; + +#define IOCTL_KGSL_SUBMIT_COMMANDS \ + _IOWR(KGSL_IOC_TYPE, 0x3D, struct kgsl_submit_commands) + +/** + * struct kgsl_device_constraint - device constraint argument + * @context_id: KGSL context ID + * @type: type of constraint i.e pwrlevel/none + * @data: constraint data + * @size: size of the constraint data + */ +struct kgsl_device_constraint { + unsigned int type; + unsigned int context_id; + void __user *data; + size_t size; +}; + +/* Constraint Type*/ +#define KGSL_CONSTRAINT_NONE 0 +#define KGSL_CONSTRAINT_PWRLEVEL 1 + +/* PWRLEVEL constraint level*/ +/* set to min frequency */ +#define KGSL_CONSTRAINT_PWR_MIN 0 +/* set to max frequency */ +#define KGSL_CONSTRAINT_PWR_MAX 1 + +struct kgsl_device_constraint_pwrlevel { + unsigned int level; +}; + +/** + * struct kgsl_syncsource_create - Argument to IOCTL_KGSL_SYNCSOURCE_CREATE + * @id: returned id for the syncsource that was created. + * + * This ioctl creates a userspace sync timeline. + */ + +struct kgsl_syncsource_create { + unsigned int id; +/* private: reserved for future use */ + unsigned int __pad[3]; +}; + +#define IOCTL_KGSL_SYNCSOURCE_CREATE \ + _IOWR(KGSL_IOC_TYPE, 0x40, struct kgsl_syncsource_create) + +/** + * struct kgsl_syncsource_destroy - Argument to IOCTL_KGSL_SYNCSOURCE_DESTROY + * @id: syncsource id to destroy + * + * This ioctl creates a userspace sync timeline. + */ + +struct kgsl_syncsource_destroy { + unsigned int id; +/* private: reserved for future use */ + unsigned int __pad[3]; +}; + +#define IOCTL_KGSL_SYNCSOURCE_DESTROY \ + _IOWR(KGSL_IOC_TYPE, 0x41, struct kgsl_syncsource_destroy) + +/** + * struct kgsl_syncsource_create_fence - Argument to + * IOCTL_KGSL_SYNCSOURCE_CREATE_FENCE + * @id: syncsource id + * @fence_fd: returned sync_fence fd + * + * Create a fence that may be signaled by userspace by calling + * IOCTL_KGSL_SYNCSOURCE_SIGNAL_FENCE. There are no order dependencies between + * these fences. + */ +struct kgsl_syncsource_create_fence { + unsigned int id; + int fence_fd; +/* private: reserved for future use */ + unsigned int __pad[4]; +}; + +/** + * struct kgsl_syncsource_signal_fence - Argument to + * IOCTL_KGSL_SYNCSOURCE_SIGNAL_FENCE + * @id: syncsource id + * @fence_fd: sync_fence fd to signal + * + * Signal a fence that was created by a IOCTL_KGSL_SYNCSOURCE_CREATE_FENCE + * call using the same syncsource id. This allows a fence to be shared + * to other processes but only signaled by the process owning the fd + * used to create the fence. + */ +#define IOCTL_KGSL_SYNCSOURCE_CREATE_FENCE \ + _IOWR(KGSL_IOC_TYPE, 0x42, struct kgsl_syncsource_create_fence) + +struct kgsl_syncsource_signal_fence { + unsigned int id; + int fence_fd; +/* private: reserved for future use */ + unsigned int __pad[4]; +}; + +#define IOCTL_KGSL_SYNCSOURCE_SIGNAL_FENCE \ + _IOWR(KGSL_IOC_TYPE, 0x43, struct kgsl_syncsource_signal_fence) + +/** + * struct kgsl_cff_sync_gpuobj - Argument to IOCTL_KGSL_CFF_SYNC_GPUOBJ + * @offset: Offset into the GPU object to sync + * @length: Number of bytes to sync + * @id: ID of the GPU object to sync + */ +struct kgsl_cff_sync_gpuobj { + uint64_t offset; + uint64_t length; + unsigned int id; +}; + +#define IOCTL_KGSL_CFF_SYNC_GPUOBJ \ + _IOW(KGSL_IOC_TYPE, 0x44, struct kgsl_cff_sync_gpuobj) + +/** + * struct kgsl_gpuobj_alloc - Argument to IOCTL_KGSL_GPUOBJ_ALLOC + * @size: Size in bytes of the object to allocate + * @flags: mask of KGSL_MEMFLAG_* bits + * @va_len: Size in bytes of the virtual region to allocate + * @mmapsize: Returns the mmap() size of the object + * @id: Returns the GPU object ID of the new object + * @metadata_len: Length of the metdata to copy from the user + * @metadata: Pointer to the user specified metadata to store for the object + */ +struct kgsl_gpuobj_alloc { + uint64_t size; + uint64_t flags; + uint64_t va_len; + uint64_t mmapsize; + unsigned int id; + unsigned int metadata_len; + uint64_t metadata; +}; + +/* Let the user know that this header supports the gpuobj metadata */ +#define KGSL_GPUOBJ_ALLOC_METADATA_MAX 64 + +#define IOCTL_KGSL_GPUOBJ_ALLOC \ + _IOWR(KGSL_IOC_TYPE, 0x45, struct kgsl_gpuobj_alloc) + +/** + * struct kgsl_gpuobj_free - Argument to IOCTL_KGLS_GPUOBJ_FREE + * @flags: Mask of: KGSL_GUPOBJ_FREE_ON_EVENT + * @priv: Pointer to the private object if KGSL_GPUOBJ_FREE_ON_EVENT is + * specified + * @id: ID of the GPU object to free + * @type: If KGSL_GPUOBJ_FREE_ON_EVENT is specified, the type of asynchronous + * event to free on + * @len: Length of the data passed in priv + */ +struct kgsl_gpuobj_free { + uint64_t flags; + uint64_t __user priv; + unsigned int id; + unsigned int type; + unsigned int len; +}; + +#define KGSL_GPUOBJ_FREE_ON_EVENT 1 + +#define KGSL_GPU_EVENT_TIMESTAMP 1 +#define KGSL_GPU_EVENT_FENCE 2 + +/** + * struct kgsl_gpu_event_timestamp - Specifies a timestamp event to free a GPU + * object on + * @context_id: ID of the timestamp event to wait for + * @timestamp: Timestamp of the timestamp event to wait for + */ +struct kgsl_gpu_event_timestamp { + unsigned int context_id; + unsigned int timestamp; +}; + +/** + * struct kgsl_gpu_event_fence - Specifies a fence ID to to free a GPU object on + * @fd: File descriptor for the fence + */ +struct kgsl_gpu_event_fence { + int fd; +}; + +#define IOCTL_KGSL_GPUOBJ_FREE \ + _IOW(KGSL_IOC_TYPE, 0x46, struct kgsl_gpuobj_free) + +/** + * struct kgsl_gpuobj_info - argument to IOCTL_KGSL_GPUOBJ_INFO + * @gpuaddr: GPU address of the object + * @flags: Current flags for the object + * @size: Size of the object + * @va_len: VA size of the object + * @va_addr: Virtual address of the object (if it is mapped) + * id - GPU object ID of the object to query + */ +struct kgsl_gpuobj_info { + uint64_t gpuaddr; + uint64_t flags; + uint64_t size; + uint64_t va_len; + uint64_t va_addr; + unsigned int id; +}; + +#define IOCTL_KGSL_GPUOBJ_INFO \ + _IOWR(KGSL_IOC_TYPE, 0x47, struct kgsl_gpuobj_info) + +/** + * struct kgsl_gpuobj_import - argument to IOCTL_KGSL_GPUOBJ_IMPORT + * @priv: Pointer to the private data for the import type + * @priv_len: Length of the private data + * @flags: Mask of KGSL_MEMFLAG_ flags + * @type: Type of the import (KGSL_USER_MEM_TYPE_*) + * @id: Returns the ID of the new GPU object + */ +struct kgsl_gpuobj_import { + uint64_t __user priv; + uint64_t priv_len; + uint64_t flags; + unsigned int type; + unsigned int id; +}; + +/** + * struct kgsl_gpuobj_import_dma_buf - import a dmabuf object + * @fd: File descriptor for the dma-buf object + */ +struct kgsl_gpuobj_import_dma_buf { + int fd; +}; + +/** + * struct kgsl_gpuobj_import_useraddr - import an object based on a useraddr + * @virtaddr: Virtual address of the object to import + */ +struct kgsl_gpuobj_import_useraddr { + uint64_t virtaddr; +}; + +#define IOCTL_KGSL_GPUOBJ_IMPORT \ + _IOWR(KGSL_IOC_TYPE, 0x48, struct kgsl_gpuobj_import) + +/** + * struct kgsl_gpuobj_sync_obj - Individual GPU object to sync + * @offset: Offset within the GPU object to sync + * @length: Number of bytes to sync + * @id: ID of the GPU object to sync + * @op: Cache operation to execute + */ + +struct kgsl_gpuobj_sync_obj { + uint64_t offset; + uint64_t length; + unsigned int id; + unsigned int op; +}; + +/** + * struct kgsl_gpuobj_sync - Argument for IOCTL_KGSL_GPUOBJ_SYNC + * @objs: Pointer to an array of kgsl_gpuobj_sync_obj structs + * @obj_len: Size of each item in the array + * @count: Number of items in the array + */ + +struct kgsl_gpuobj_sync { + uint64_t __user objs; + unsigned int obj_len; + unsigned int count; +}; + +#define IOCTL_KGSL_GPUOBJ_SYNC \ + _IOW(KGSL_IOC_TYPE, 0x49, struct kgsl_gpuobj_sync) + +/** + * struct kgsl_command_object - GPU command object + * @offset: GPU address offset of the object + * @gpuaddr: GPU address of the object + * @size: Size of the object + * @flags: Current flags for the object + * @id - GPU command object ID + */ +struct kgsl_command_object { + uint64_t offset; + uint64_t gpuaddr; + uint64_t size; + unsigned int flags; + unsigned int id; +}; + +/** + * struct kgsl_command_syncpoint - GPU syncpoint object + * @priv: Pointer to the type specific buffer + * @size: Size of the type specific buffer + * @type: type of sync point defined here + */ +struct kgsl_command_syncpoint { + uint64_t __user priv; + uint64_t size; + unsigned int type; +}; + +/** + * struct kgsl_command_object - Argument for IOCTL_KGSL_GPU_COMMAND + * @flags: Current flags for the object + * @cmdlist: List of kgsl_command_objects for submission + * @cmd_size: Size of kgsl_command_objects structure + * @numcmds: Number of kgsl_command_objects in command list + * @objlist: List of kgsl_command_objects for tracking + * @obj_size: Size of kgsl_command_objects structure + * @numobjs: Number of kgsl_command_objects in object list + * @synclist: List of kgsl_command_syncpoints + * @sync_size: Size of kgsl_command_syncpoint structure + * @numsyncs: Number of kgsl_command_syncpoints in syncpoint list + * @context_id: Context ID submittin ghte kgsl_gpu_command + * @timestamp: Timestamp for the submitted commands + */ +struct kgsl_gpu_command { + uint64_t flags; + uint64_t __user cmdlist; + unsigned int cmdsize; + unsigned int numcmds; + uint64_t __user objlist; + unsigned int objsize; + unsigned int numobjs; + uint64_t __user synclist; + unsigned int syncsize; + unsigned int numsyncs; + unsigned int context_id; + unsigned int timestamp; +}; + +#define IOCTL_KGSL_GPU_COMMAND \ + _IOWR(KGSL_IOC_TYPE, 0x4A, struct kgsl_gpu_command) + +/** + * struct kgsl_preemption_counters_query - argument to + * IOCTL_KGSL_PREEMPTIONCOUNTER_QUERY + * @counters: Return preemption counters array + * @size_user: Size allocated by userspace + * @size_priority_level: Size of preemption counters for each + * priority level + * @max_priority_level: Return max number of priority levels + * + * Query the available preemption counters. The array counters + * is used to return preemption counters. The size of the array + * is passed in so the kernel will only write at most size_user + * or max available preemption counters. The total number of + * preemption counters is returned in max_priority_level. If the + * array or size passed in are invalid, then an error is + * returned back. + */ +struct kgsl_preemption_counters_query { + uint64_t __user counters; + unsigned int size_user; + unsigned int size_priority_level; + unsigned int max_priority_level; +}; + +#define IOCTL_KGSL_PREEMPTIONCOUNTER_QUERY \ + _IOWR(KGSL_IOC_TYPE, 0x4B, struct kgsl_preemption_counters_query) + +/** + * struct kgsl_gpuobj_set_info - argument for IOCTL_KGSL_GPUOBJ_SET_INFO + * @flags: Flags to indicate which paramaters to change + * @metadata: If KGSL_GPUOBJ_SET_INFO_METADATA is set, a pointer to the new + * metadata + * @id: GPU memory object ID to change + * @metadata_len: If KGSL_GPUOBJ_SET_INFO_METADATA is set, the length of the + * new metadata string + * @type: If KGSL_GPUOBJ_SET_INFO_TYPE is set, the new type of the memory object + */ + +#define KGSL_GPUOBJ_SET_INFO_METADATA (1 << 0) +#define KGSL_GPUOBJ_SET_INFO_TYPE (1 << 1) + +struct kgsl_gpuobj_set_info { + uint64_t flags; + uint64_t metadata; + unsigned int id; + unsigned int metadata_len; + unsigned int type; +}; + +#define IOCTL_KGSL_GPUOBJ_SET_INFO \ + _IOW(KGSL_IOC_TYPE, 0x4C, struct kgsl_gpuobj_set_info) + +#endif /* _UAPI_MSM_KGSL_H */ diff --git a/selfdrive/modeld/thneed/thneed.cc b/selfdrive/modeld/thneed/thneed.cc new file mode 100644 index 0000000000..826015999f --- /dev/null +++ b/selfdrive/modeld/thneed/thneed.cc @@ -0,0 +1,363 @@ +#include "thneed.h" +#include +#include +#include +#include +#include +#include + +Thneed *g_thneed = NULL; +int g_fd = -1; +std::map, std::string> g_args; + +static inline uint64_t nanos_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; } + +void hexdump(uint32_t *d, int len) { + assert((len%4) == 0); + printf(" dumping %p len 0x%x\n", d, len); + for (int i = 0; i < len/4; i++) { + if (i != 0 && (i%0x10) == 0) printf("\n"); + printf("%8x ", d[i]); + } + printf("\n"); +} + +extern "C" { + +int (*my_ioctl)(int filedes, unsigned long request, void *argp) = NULL; +#undef ioctl +int ioctl(int filedes, unsigned long request, void *argp) { + if (my_ioctl == NULL) my_ioctl = reinterpret_cast(dlsym(RTLD_NEXT, "ioctl")); + Thneed *thneed = g_thneed; + + // save the fd + if (request == IOCTL_KGSL_GPUOBJ_ALLOC) g_fd = filedes; + + if (thneed != NULL) { + if (request == IOCTL_KGSL_GPU_COMMAND) { + struct kgsl_gpu_command *cmd = (struct kgsl_gpu_command *)argp; + if (thneed->record & 1) { + thneed->timestamp = cmd->timestamp; + thneed->context_id = cmd->context_id; + CachedCommand *ccmd = new CachedCommand(thneed, cmd); + thneed->cmds.push_back(ccmd); + } + if (thneed->record & 2) { + printf("IOCTL_KGSL_GPU_COMMAND: flags: 0x%lx context_id: %u timestamp: %u\n", + cmd->flags, + cmd->context_id, cmd->timestamp); + } + } else if (request == IOCTL_KGSL_GPUOBJ_SYNC) { + struct kgsl_gpuobj_sync *cmd = (struct kgsl_gpuobj_sync *)argp; + struct kgsl_gpuobj_sync_obj *objs = (struct kgsl_gpuobj_sync_obj *)(cmd->objs); + + if (thneed->record & 2) { + printf("IOCTL_KGSL_GPUOBJ_SYNC count:%d ", cmd->count); + for (int i = 0; i < cmd->count; i++) { + printf(" -- offset:0x%lx len:0x%lx id:%d op:%d ", objs[i].offset, objs[i].length, objs[i].id, objs[i].op); + } + printf("\n"); + } + + if (thneed->record & 1) { + struct kgsl_gpuobj_sync_obj *new_objs = (struct kgsl_gpuobj_sync_obj *)malloc(sizeof(struct kgsl_gpuobj_sync_obj)*cmd->count); + memcpy(new_objs, objs, sizeof(struct kgsl_gpuobj_sync_obj)*cmd->count); + thneed->syncobjs.push_back(std::make_pair(cmd->count, new_objs)); + } + } else if (request == IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID) { + struct kgsl_device_waittimestamp_ctxtid *cmd = (struct kgsl_device_waittimestamp_ctxtid *)argp; + if (thneed->record & 2) { + printf("IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID: context_id: %d timestamp: %d timeout: %d\n", + cmd->context_id, cmd->timestamp, cmd->timeout); + } + } else if (request == IOCTL_KGSL_SETPROPERTY) { + if (thneed->record & 2) { + struct kgsl_device_getproperty *prop = (struct kgsl_device_getproperty *)argp; + printf("IOCTL_KGSL_SETPROPERTY: 0x%x sizebytes:%zu\n", prop->type, prop->sizebytes); + if (thneed->record & 4) { + hexdump((uint32_t *)prop->value, prop->sizebytes); + if (prop->type == KGSL_PROP_PWR_CONSTRAINT) { + struct kgsl_device_constraint *constraint = (struct kgsl_device_constraint *)prop->value; + hexdump((uint32_t *)constraint->data, constraint->size); + } + } + } + } + } + + int ret = my_ioctl(filedes, request, argp); + if (ret != 0) printf("ioctl returned %d with errno %d\n", ret, errno); + return ret; +} + +} + +GPUMalloc::GPUMalloc(int size, int fd) { + struct kgsl_gpuobj_alloc alloc; + memset(&alloc, 0, sizeof(alloc)); + alloc.size = size; + alloc.flags = 0x10000a00; + int ret = ioctl(fd, IOCTL_KGSL_GPUOBJ_ALLOC, &alloc); + void *addr = mmap64(NULL, alloc.mmapsize, 0x3, 0x1, fd, alloc.id*0x1000); + assert(addr != MAP_FAILED); + + base = (uint64_t)addr; + remaining = size; +} + +void *GPUMalloc::alloc(int size) { + if (size > remaining) return NULL; + remaining -= size; + void *ret = (void*)base; + base += (size+0xff) & (~0xFF); + return ret; +} + +CachedCommand::CachedCommand(Thneed *lthneed, struct kgsl_gpu_command *cmd) { + thneed = lthneed; + assert(cmd->numcmds == 2); + assert(cmd->numobjs == 1); + assert(cmd->numsyncs == 0); + + memcpy(cmds, (void *)cmd->cmdlist, sizeof(struct kgsl_command_object)*2); + memcpy(objs, (void *)cmd->objlist, sizeof(struct kgsl_command_object)*1); + + memcpy(&cache, cmd, sizeof(cache)); + cache.cmdlist = (uint64_t)cmds; + cache.objlist = (uint64_t)objs; + + for (int i = 0; i < cmd->numcmds; i++) { + void *nn = thneed->ram->alloc(cmds[i].size); + memcpy(nn, (void*)cmds[i].gpuaddr, cmds[i].size); + cmds[i].gpuaddr = (uint64_t)nn; + } + + for (int i = 0; i < cmd->numobjs; i++) { + void *nn = thneed->ram->alloc(objs[i].size); + memset(nn, 0, objs[i].size); + objs[i].gpuaddr = (uint64_t)nn; + } +} + +void CachedCommand::exec(bool wait) { + cache.timestamp = ++thneed->timestamp; + int ret = ioctl(thneed->fd, IOCTL_KGSL_GPU_COMMAND, &cache); + + if (wait) { + struct kgsl_device_waittimestamp_ctxtid wait; + wait.context_id = cache.context_id; + wait.timestamp = cache.timestamp; + wait.timeout = -1; + + uint64_t tb = nanos_since_boot(); + int wret = ioctl(thneed->fd, IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID, &wait); + uint64_t te = nanos_since_boot(); + + if (thneed->record & 2) printf("exec %d wait %d after %lu us\n", ret, wret, (te-tb)/1000); + } else { + if (thneed->record & 2) printf("CachedCommand::exec got %d\n", ret); + } + + assert(ret == 0); +} + +Thneed::Thneed() { + assert(g_fd != -1); + fd = g_fd; + ram = new GPUMalloc(0x40000, fd); + record = 1; + timestamp = -1; + g_thneed = this; +} + +void Thneed::stop() { + record = 0; +} + +//#define SAVE_LOG + +void Thneed::execute(float **finputs, float *foutput) { + #ifdef SAVE_LOG + char fn[0x100]; + snprintf(fn, sizeof(fn), "/tmp/thneed_log_%d", timestamp); + FILE *f = fopen(fn, "wb"); + #endif + + // ****** copy inputs + for (int idx = 0; idx < inputs.size(); ++idx) { + size_t sz; + clGetMemObjectInfo(inputs[idx], CL_MEM_SIZE, sizeof(sz), &sz, NULL); + + #ifdef SAVE_LOG + fwrite(&sz, 1, sizeof(sz), f); + fwrite(finputs[idx], 1, sz, f); + #endif + + if (record & 2) printf("copying %lu -- %p -> %p\n", sz, finputs[idx], inputs[idx]); + clEnqueueWriteBuffer(command_queue, inputs[idx], CL_TRUE, 0, sz, finputs[idx], 0, NULL, NULL); + } + + // ****** set power constraint + struct kgsl_device_constraint_pwrlevel pwrlevel; + pwrlevel.level = KGSL_CONSTRAINT_PWR_MAX; + + struct kgsl_device_constraint constraint; + constraint.type = KGSL_CONSTRAINT_PWRLEVEL; + constraint.context_id = context_id; + constraint.data = (void*)&pwrlevel; + constraint.size = sizeof(pwrlevel); + + struct kgsl_device_getproperty prop; + prop.type = KGSL_PROP_PWR_CONSTRAINT; + prop.value = (void*)&constraint; + prop.sizebytes = sizeof(constraint); + int ret = ioctl(fd, IOCTL_KGSL_SETPROPERTY, &prop); + assert(ret == 0); + + // ****** run commands + int i = 0; + for (auto it = cmds.begin(); it != cmds.end(); ++it) { + if (record & 2) printf("run %2d: ", i); + (*it)->exec((++i) == cmds.size()); + } + + // ****** sync objects + for (auto it = syncobjs.begin(); it != syncobjs.end(); ++it) { + struct kgsl_gpuobj_sync cmd; + + cmd.objs = (uint64_t)it->second; + cmd.obj_len = it->first * sizeof(struct kgsl_gpuobj_sync_obj); + cmd.count = it->first; + + ret = ioctl(fd, IOCTL_KGSL_GPUOBJ_SYNC, &cmd); + assert(ret == 0); + } + + // ****** copy outputs + size_t sz; + clGetMemObjectInfo(output, CL_MEM_SIZE, sizeof(sz), &sz, NULL); + if (record & 2) printf("copying %lu for output %p -> %p\n", sz, output, foutput); + clEnqueueReadBuffer(command_queue, output, CL_TRUE, 0, sz, foutput, 0, NULL, NULL); + + #ifdef SAVE_LOG + fwrite(&sz, 1, sizeof(sz), f); + fwrite(foutput, 1, sz, f); + fclose(f); + #endif + + // ****** unset power constraint + constraint.type = KGSL_CONSTRAINT_NONE; + constraint.data = NULL; + constraint.size = 0; + + ret = ioctl(fd, IOCTL_KGSL_SETPROPERTY, &prop); + assert(ret == 0); +} + +cl_int (*my_clSetKernelArg)(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) = NULL; +cl_int clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) { + if (my_clSetKernelArg == NULL) my_clSetKernelArg = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clSetKernelArg")); + if (arg_value != NULL) { + g_args[std::make_pair(kernel, arg_index)] = std::string((char*)arg_value, arg_size); + } + cl_int ret = my_clSetKernelArg(kernel, arg_index, arg_size, arg_value); + return ret; +} + +cl_int (*my_clEnqueueNDRangeKernel)(cl_command_queue, cl_kernel, cl_uint, const size_t *, const size_t *, const size_t *, cl_uint, const cl_event *, cl_event *) = NULL; +cl_int clEnqueueNDRangeKernel(cl_command_queue command_queue, + cl_kernel kernel, + cl_uint work_dim, + const size_t *global_work_offset, + const size_t *global_work_size, + const size_t *local_work_size, + cl_uint num_events_in_wait_list, + const cl_event *event_wait_list, + cl_event *event) { + + if (my_clEnqueueNDRangeKernel == NULL) my_clEnqueueNDRangeKernel = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clEnqueueNDRangeKernel")); + Thneed *thneed = g_thneed; + + // SNPE doesn't use these + assert(num_events_in_wait_list == 0); + assert(global_work_offset == NULL); + + char name[0x100]; + clGetKernelInfo(kernel, CL_KERNEL_FUNCTION_NAME, sizeof(name), name, NULL); + + cl_uint num_args; + clGetKernelInfo(kernel, CL_KERNEL_NUM_ARGS, sizeof(num_args), &num_args, NULL); + + if (thneed != NULL && thneed->record & 1) { + thneed->command_queue = command_queue; + for (int i = 0; i < num_args; i++) { + char arg_name[0x100]; + clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); + std::string arg = g_args[std::make_pair(kernel, i)]; + + if (strcmp(arg_name, "input") == 0 && strcmp(name, "zero_pad_image_float") == 0) { + cl_mem mem; + memcpy(&mem, (void*)arg.data(), sizeof(mem)); + thneed->inputs.push_back(mem); + } + + if (strcmp(arg_name, "output") == 0 && strcmp(name, "image2d_to_buffer_float") == 0) { + cl_mem mem; + memcpy(&mem, (void*)arg.data(), sizeof(mem)); + thneed->output = mem; + } + } + } + + if (thneed != NULL && thneed->record & 4) { + // extreme debug + printf("%s -- %p\n", name, kernel); + for (int i = 0; i < num_args; i++) { + char arg_type[0x100]; + char arg_name[0x100]; + clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_TYPE_NAME, sizeof(arg_type), arg_type, NULL); + clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); + std::string arg = g_args[std::make_pair(kernel, i)]; + printf(" %s %s", arg_type, arg_name); + void *arg_value = (void*)arg.data(); + int arg_size = arg.size(); + if (arg_size == 1) { + printf(" = %d", *((char*)arg_value)); + } else if (arg_size == 2) { + printf(" = %d", *((short*)arg_value)); + } else if (arg_size == 4) { + if (strcmp(arg_type, "float") == 0) { + printf(" = %f", *((float*)arg_value)); + } else { + printf(" = %d", *((int*)arg_value)); + } + } else if (arg_size == 8) { + cl_mem val = (cl_mem)(*((uintptr_t*)arg_value)); + printf(" = %p", val); + } + printf("\n"); + } + } + + cl_int ret = my_clEnqueueNDRangeKernel(command_queue, kernel, work_dim, + global_work_offset, global_work_size, local_work_size, + num_events_in_wait_list, event_wait_list, event); + return ret; +} + +void *dlsym(void *handle, const char *symbol) { + void *(*my_dlsym)(void *handle, const char *symbol) = (void *(*)(void *handle, const char *symbol))((uintptr_t)dlopen-0x2d4); + if (memcmp("REAL_", symbol, 5) == 0) { + return my_dlsym(handle, symbol+5); + } else if (strcmp("clEnqueueNDRangeKernel", symbol) == 0) { + return (void*)clEnqueueNDRangeKernel; + } else if (strcmp("clSetKernelArg", symbol) == 0) { + return (void*)clSetKernelArg; + } else { + return my_dlsym(handle, symbol); + } +} + diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h new file mode 100644 index 0000000000..9f35f5dcfb --- /dev/null +++ b/selfdrive/modeld/thneed/thneed.h @@ -0,0 +1,50 @@ +#pragma once + +#include +#include "include/msm_kgsl.h" +#include +#include + +class Thneed; + +class GPUMalloc { + public: + GPUMalloc(int size, int fd); + void *alloc(int size); + private: + uint64_t base; + int remaining; +}; + +class CachedCommand { + public: + CachedCommand(Thneed *lthneed, struct kgsl_gpu_command *cmd); + void exec(bool wait); + private: + struct kgsl_gpu_command cache; + struct kgsl_command_object cmds[2]; + struct kgsl_command_object objs[1]; + Thneed *thneed; +}; + +class Thneed { + public: + Thneed(); + void stop(); + void execute(float **finputs, float *foutput); + + std::vector inputs; + cl_mem output; + + cl_command_queue command_queue; + int context_id; + + // protected? + int record; + int timestamp; + GPUMalloc *ram; + std::vector cmds; + std::vector > syncobjs; + int fd; +}; + From ed5284f9b3768df8693b7e14e5e5285c9c64d10f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 13:53:36 -0700 Subject: [PATCH 007/656] turn locationd back on --- selfdrive/manager.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index c2db758233..1fe4a02780 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -236,7 +236,7 @@ car_started_processes = [ 'modeld', 'proclogd', 'ubloxd', - #'locationd', + 'locationd', ] if WEBCAM: From 1260b701d4f41c7ee5c1540155f853a869dab585 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 14:16:53 -0700 Subject: [PATCH 008/656] bump rednose --- rednose_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rednose_repo b/rednose_repo index d3a79c6a42..a6c02b647b 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit d3a79c6a421b4eec952eeb8d1546a4c3c3ff030e +Subproject commit a6c02b647b288f4f7e50326996b38f7e21dc483c From 2cc218e144bec84d5992e45076adf00d56988f84 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 14:22:36 -0700 Subject: [PATCH 009/656] lane kf was not built --- selfdrive/locationd/models/SConscript | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/locationd/models/SConscript b/selfdrive/locationd/models/SConscript index c8b5c93f7a..0a197ffda8 100644 --- a/selfdrive/locationd/models/SConscript +++ b/selfdrive/locationd/models/SConscript @@ -17,6 +17,7 @@ if arch != "aarch64": 'pos_computer_4': ('#rednose/helpers/lst_sq_computer.py', 'generated'), 'pos_computer_5': ('#rednose/helpers/lst_sq_computer.py', 'generated'), 'feature_handler_5': ('#rednose/helpers/feature_handler.py', 'generated'), + 'lane': ('#xx/pipeline/lib/ekf/lane_kf.py', 'generated'), }) found = {} From a4ffd8c226ab1f286334c1cee9a90a03cbaec91a Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Fri, 15 May 2020 14:24:04 -0700 Subject: [PATCH 010/656] way cleaner --- selfdrive/locationd/locationd.py | 62 ++++++++----------------- selfdrive/locationd/models/constants.py | 2 + selfdrive/locationd/models/live_kf.py | 5 +- 3 files changed, 26 insertions(+), 43 deletions(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 7075fdf3f0..6b9106db9f 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -147,21 +147,20 @@ class Localizer(): #fix.gpsTimeOfWeek = self.time.tow fix.unixTimestampMillis = self.unix_timestamp_millis - if self.filter_ready and self.calibrated: + if np.limalg.norm(fix.positionECEF.std) < 50 and self.calibrated: fix.status = 'valid' - elif self.filter_ready: + elif np.limalg.norm(fix.positionECEF.std) < 50: fix.status = 'uncalibrated' else: fix.status = 'uninitialized' return fix def update_kalman(self, time, kind, meas): - if self.filter_ready: - try: - self.kf.predict_and_observe(time, kind, meas) - except KalmanError: - cloudlog.error("Error in predict and observe, kalman reset") - self.reset_kalman() + try: + self.kf.predict_and_observe(time, kind, meas) + except KalmanError: + cloudlog.error("Error in predict and observe, kalman reset") + self.reset_kalman() #idx = bisect_right([x[0] for x in self.observation_buffer], time) #self.observation_buffer.insert(idx, (time, kind, meas)) #while len(self.observation_buffer) > 0 and self.observation_buffer[-1][0] - self.observation_buffer[0][0] > self.max_age: @@ -171,40 +170,19 @@ class Localizer(): def handle_gps(self, current_time, log): self.converter = coord.LocalCoord.from_geodetic([log.latitude, log.longitude, log.altitude]) fix_ecef = self.converter.ned2ecef([0, 0, 0]) + vel_ecef = self.converter.ned2ecef_matrix.dot(np.array(log.vNED)) #self.time = GPSTime.from_datetime(datetime.utcfromtimestamp(log.timestamp*1e-3)) self.unix_timestamp_millis = log.timestamp + gps_est_error = np.sqrt((self.kf.x[0] - fix_ecef[0])**2 + + (self.kf.x[1] - fix_ecef[1])**2 + + (self.kf.x[2] - fix_ecef[2])**2) + if gps_est_error > 50: + cloudlog.error("Locationd vs ubloxLocation difference too large, kalman reset") + self.reset_kalman(current_time) - # TODO initing with bad bearing not allowed, maybe not bad? - if not self.filter_ready and log.speed > 5: - self.filter_ready = True - initial_ecef = fix_ecef - gps_bearing = math.radians(log.bearing) - initial_pose_ecef = ecef_euler_from_ned(initial_ecef, [0, 0, gps_bearing]) - initial_pose_ecef_quat = quat_from_euler(initial_pose_ecef) - gps_speed = log.speed - quat_uncertainty = 0.2**2 - - initial_state = LiveKalman.initial_x - initial_covs_diag = LiveKalman.initial_P_diag - - initial_state[States.ECEF_POS] = initial_ecef - initial_state[States.ECEF_ORIENTATION] = initial_pose_ecef_quat - initial_state[States.ECEF_VELOCITY] = rot_from_quat(initial_pose_ecef_quat).dot(np.array([gps_speed, 0, 0])) - - initial_covs_diag[States.ECEF_POS_ERR] = 10**2 - initial_covs_diag[States.ECEF_ORIENTATION_ERR] = quat_uncertainty - initial_covs_diag[States.ECEF_VELOCITY_ERR] = 1**2 - self.kf.init_state(initial_state, covs=np.diag(initial_covs_diag), filter_time=current_time) - cloudlog.info("Filter initialized") - elif self.filter_ready: - self.update_kalman(current_time, ObservationKind.ECEF_POS, fix_ecef) - gps_est_error = np.sqrt((self.kf.x[0] - fix_ecef[0])**2 + - (self.kf.x[1] - fix_ecef[1])**2 + - (self.kf.x[2] - fix_ecef[2])**2) - if gps_est_error > 50: - cloudlog.error("Locationd vs ubloxLocation difference too large, kalman reset") - self.reset_kalman() + self.update_kalman(current_time, ObservationKind.ECEF_POS, fix_ecef) + self.update_kalman(current_time, ObservationKind.ECEF_VEL, vel_ecef) def handle_car_state(self, current_time, log): self.speed_counter += 1 @@ -256,9 +234,9 @@ class Localizer(): self.calib_from_device = self.device_from_calib.T self.calibrated = log.calStatus == 1 - def reset_kalman(self): - self.filter_time = None - self.filter_ready = False + def reset_kalman(self, current_time=None): + self.filter_time = current_time + self.kf.init_state(self.kf.x, covs=np.diag(LiveKalman.initial_P_diag), filter_time=current_time) self.observation_buffer = [] self.gyro_counter = 0 @@ -292,7 +270,7 @@ def locationd_thread(sm, pm, disabled_logs=[]): elif sock == "liveCalibration": localizer.handle_live_calib(t, sm[sock]) - if localizer.filter_ready and sm.updated['gpsLocationExternal']: + if sm.updated['gpsLocationExternal']: t = sm.logMonoTime['gpsLocationExternal'] msg = messaging.new_message('liveLocationKalman') msg.logMonoTime = t diff --git a/selfdrive/locationd/models/constants.py b/selfdrive/locationd/models/constants.py index 8b99fce649..ab2a2252f4 100644 --- a/selfdrive/locationd/models/constants.py +++ b/selfdrive/locationd/models/constants.py @@ -27,6 +27,7 @@ class ObservationKind: PSEUDORANGE_RATE_GLONASS = 21 PSEUDORANGE = 22 PSEUDORANGE_RATE = 23 + ECEF_VEL = 31 ROAD_FRAME_XY_SPEED = 24 # (x, y) [m/s] ROAD_FRAME_YAW_RATE = 25 # [rad/s] @@ -36,6 +37,7 @@ class ObservationKind: STEER_RATIO = 29 # [-] ROAD_FRAME_X_SPEED = 30 # (x) [m/s] + names = [ 'Unknown', 'No observation', diff --git a/selfdrive/locationd/models/live_kf.py b/selfdrive/locationd/models/live_kf.py index 299d6b25c4..1b40724cc4 100755 --- a/selfdrive/locationd/models/live_kf.py +++ b/selfdrive/locationd/models/live_kf.py @@ -172,6 +172,7 @@ class LiveKalman(): h_speed_sym = sp.Matrix([speed * odo_scale]) h_pos_sym = sp.Matrix([x, y, z]) + h_vel_sym = sp.Matrix([vx, vy, vz]) h_imu_frame_sym = sp.Matrix(imu_angles) h_relative_motion = sp.Matrix(quat_rot.T * v) @@ -181,6 +182,7 @@ class LiveKalman(): [h_phone_rot_sym, ObservationKind.NO_ROT, None], [h_acc_sym, ObservationKind.PHONE_ACCEL, None], [h_pos_sym, ObservationKind.ECEF_POS, None], + [h_vel_sym, ObservationKind.ECEF_VEL, None], [h_relative_motion, ObservationKind.CAMERA_ODO_TRANSLATION, None], [h_phone_rot_sym, ObservationKind.CAMERA_ODO_ROTATION, None], [h_imu_frame_sym, ObservationKind.IMU_FRAME, None]] @@ -197,7 +199,8 @@ class LiveKalman(): ObservationKind.CAMERA_ODO_ROTATION: np.diag([0.05**2, 0.05**2, 0.05**2]), ObservationKind.IMU_FRAME: np.diag([0.05**2, 0.05**2, 0.05**2]), ObservationKind.NO_ROT: np.diag([0.00025**2, 0.00025**2, 0.00025**2]), - ObservationKind.ECEF_POS: np.diag([5**2, 5**2, 5**2])} + ObservationKind.ECEF_POS: np.diag([5**2, 5**2, 5**2]), + ObservationKind.ECEF_VEL: np.diag([1**2, 1**2, 1**2])} # init filter self.filter = EKF_sym(generated_dir, self.name, self.Q, self.initial_x, np.diag(self.initial_P_diag), self.dim_state, self.dim_state_err) From 273e81715a045b9aac07796973493aad86f7a3e6 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Fri, 15 May 2020 14:29:34 -0700 Subject: [PATCH 011/656] xRevert "way cleaner" This reverts commit a4ffd8c226ab1f286334c1cee9a90a03cbaec91a. --- selfdrive/locationd/locationd.py | 62 +++++++++++++++++-------- selfdrive/locationd/models/constants.py | 2 - selfdrive/locationd/models/live_kf.py | 5 +- 3 files changed, 43 insertions(+), 26 deletions(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 6b9106db9f..7075fdf3f0 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -147,20 +147,21 @@ class Localizer(): #fix.gpsTimeOfWeek = self.time.tow fix.unixTimestampMillis = self.unix_timestamp_millis - if np.limalg.norm(fix.positionECEF.std) < 50 and self.calibrated: + if self.filter_ready and self.calibrated: fix.status = 'valid' - elif np.limalg.norm(fix.positionECEF.std) < 50: + elif self.filter_ready: fix.status = 'uncalibrated' else: fix.status = 'uninitialized' return fix def update_kalman(self, time, kind, meas): - try: - self.kf.predict_and_observe(time, kind, meas) - except KalmanError: - cloudlog.error("Error in predict and observe, kalman reset") - self.reset_kalman() + if self.filter_ready: + try: + self.kf.predict_and_observe(time, kind, meas) + except KalmanError: + cloudlog.error("Error in predict and observe, kalman reset") + self.reset_kalman() #idx = bisect_right([x[0] for x in self.observation_buffer], time) #self.observation_buffer.insert(idx, (time, kind, meas)) #while len(self.observation_buffer) > 0 and self.observation_buffer[-1][0] - self.observation_buffer[0][0] > self.max_age: @@ -170,19 +171,40 @@ class Localizer(): def handle_gps(self, current_time, log): self.converter = coord.LocalCoord.from_geodetic([log.latitude, log.longitude, log.altitude]) fix_ecef = self.converter.ned2ecef([0, 0, 0]) - vel_ecef = self.converter.ned2ecef_matrix.dot(np.array(log.vNED)) #self.time = GPSTime.from_datetime(datetime.utcfromtimestamp(log.timestamp*1e-3)) self.unix_timestamp_millis = log.timestamp - gps_est_error = np.sqrt((self.kf.x[0] - fix_ecef[0])**2 + - (self.kf.x[1] - fix_ecef[1])**2 + - (self.kf.x[2] - fix_ecef[2])**2) - if gps_est_error > 50: - cloudlog.error("Locationd vs ubloxLocation difference too large, kalman reset") - self.reset_kalman(current_time) - self.update_kalman(current_time, ObservationKind.ECEF_POS, fix_ecef) - self.update_kalman(current_time, ObservationKind.ECEF_VEL, vel_ecef) + # TODO initing with bad bearing not allowed, maybe not bad? + if not self.filter_ready and log.speed > 5: + self.filter_ready = True + initial_ecef = fix_ecef + gps_bearing = math.radians(log.bearing) + initial_pose_ecef = ecef_euler_from_ned(initial_ecef, [0, 0, gps_bearing]) + initial_pose_ecef_quat = quat_from_euler(initial_pose_ecef) + gps_speed = log.speed + quat_uncertainty = 0.2**2 + + initial_state = LiveKalman.initial_x + initial_covs_diag = LiveKalman.initial_P_diag + + initial_state[States.ECEF_POS] = initial_ecef + initial_state[States.ECEF_ORIENTATION] = initial_pose_ecef_quat + initial_state[States.ECEF_VELOCITY] = rot_from_quat(initial_pose_ecef_quat).dot(np.array([gps_speed, 0, 0])) + + initial_covs_diag[States.ECEF_POS_ERR] = 10**2 + initial_covs_diag[States.ECEF_ORIENTATION_ERR] = quat_uncertainty + initial_covs_diag[States.ECEF_VELOCITY_ERR] = 1**2 + self.kf.init_state(initial_state, covs=np.diag(initial_covs_diag), filter_time=current_time) + cloudlog.info("Filter initialized") + elif self.filter_ready: + self.update_kalman(current_time, ObservationKind.ECEF_POS, fix_ecef) + gps_est_error = np.sqrt((self.kf.x[0] - fix_ecef[0])**2 + + (self.kf.x[1] - fix_ecef[1])**2 + + (self.kf.x[2] - fix_ecef[2])**2) + if gps_est_error > 50: + cloudlog.error("Locationd vs ubloxLocation difference too large, kalman reset") + self.reset_kalman() def handle_car_state(self, current_time, log): self.speed_counter += 1 @@ -234,9 +256,9 @@ class Localizer(): self.calib_from_device = self.device_from_calib.T self.calibrated = log.calStatus == 1 - def reset_kalman(self, current_time=None): - self.filter_time = current_time - self.kf.init_state(self.kf.x, covs=np.diag(LiveKalman.initial_P_diag), filter_time=current_time) + def reset_kalman(self): + self.filter_time = None + self.filter_ready = False self.observation_buffer = [] self.gyro_counter = 0 @@ -270,7 +292,7 @@ def locationd_thread(sm, pm, disabled_logs=[]): elif sock == "liveCalibration": localizer.handle_live_calib(t, sm[sock]) - if sm.updated['gpsLocationExternal']: + if localizer.filter_ready and sm.updated['gpsLocationExternal']: t = sm.logMonoTime['gpsLocationExternal'] msg = messaging.new_message('liveLocationKalman') msg.logMonoTime = t diff --git a/selfdrive/locationd/models/constants.py b/selfdrive/locationd/models/constants.py index ab2a2252f4..8b99fce649 100644 --- a/selfdrive/locationd/models/constants.py +++ b/selfdrive/locationd/models/constants.py @@ -27,7 +27,6 @@ class ObservationKind: PSEUDORANGE_RATE_GLONASS = 21 PSEUDORANGE = 22 PSEUDORANGE_RATE = 23 - ECEF_VEL = 31 ROAD_FRAME_XY_SPEED = 24 # (x, y) [m/s] ROAD_FRAME_YAW_RATE = 25 # [rad/s] @@ -37,7 +36,6 @@ class ObservationKind: STEER_RATIO = 29 # [-] ROAD_FRAME_X_SPEED = 30 # (x) [m/s] - names = [ 'Unknown', 'No observation', diff --git a/selfdrive/locationd/models/live_kf.py b/selfdrive/locationd/models/live_kf.py index 1b40724cc4..299d6b25c4 100755 --- a/selfdrive/locationd/models/live_kf.py +++ b/selfdrive/locationd/models/live_kf.py @@ -172,7 +172,6 @@ class LiveKalman(): h_speed_sym = sp.Matrix([speed * odo_scale]) h_pos_sym = sp.Matrix([x, y, z]) - h_vel_sym = sp.Matrix([vx, vy, vz]) h_imu_frame_sym = sp.Matrix(imu_angles) h_relative_motion = sp.Matrix(quat_rot.T * v) @@ -182,7 +181,6 @@ class LiveKalman(): [h_phone_rot_sym, ObservationKind.NO_ROT, None], [h_acc_sym, ObservationKind.PHONE_ACCEL, None], [h_pos_sym, ObservationKind.ECEF_POS, None], - [h_vel_sym, ObservationKind.ECEF_VEL, None], [h_relative_motion, ObservationKind.CAMERA_ODO_TRANSLATION, None], [h_phone_rot_sym, ObservationKind.CAMERA_ODO_ROTATION, None], [h_imu_frame_sym, ObservationKind.IMU_FRAME, None]] @@ -199,8 +197,7 @@ class LiveKalman(): ObservationKind.CAMERA_ODO_ROTATION: np.diag([0.05**2, 0.05**2, 0.05**2]), ObservationKind.IMU_FRAME: np.diag([0.05**2, 0.05**2, 0.05**2]), ObservationKind.NO_ROT: np.diag([0.00025**2, 0.00025**2, 0.00025**2]), - ObservationKind.ECEF_POS: np.diag([5**2, 5**2, 5**2]), - ObservationKind.ECEF_VEL: np.diag([1**2, 1**2, 1**2])} + ObservationKind.ECEF_POS: np.diag([5**2, 5**2, 5**2])} # init filter self.filter = EKF_sym(generated_dir, self.name, self.Q, self.initial_x, np.diag(self.initial_P_diag), self.dim_state, self.dim_state_err) From 53c0214a65f032e7124f756a4531c639875a8dbb Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Fri, 15 May 2020 14:31:50 -0700 Subject: [PATCH 012/656] Add VW Golf 2015 --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 1d2e08de02..50aa2b3417 100644 --- a/README.md +++ b/README.md @@ -158,7 +158,7 @@ Community Maintained Cars and Features | Nissan | X-Trail 2018 | Propilot | Stock | 0mph | 0mph | | Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | | Subaru | Impreza 2018-20 | EyeSight | Stock | 0mph | 0mph | -| Volkswagen| Golf 2016-193 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Golf 2015-193 | Driver Assistance | Stock | 0mph | 0mph | 1Requires a [panda](https://comma.ai/shop/products/panda-obd-ii-dongle) and [community built giraffe](https://zoneos.com/volt/). ***NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).***
2Requires a [panda](https://comma.ai/shop/products/panda-obd-ii-dongle) and open sourced [Hyundai giraffe](https://github.com/commaai/neo/tree/master/giraffe/hyundai), designed for the 2019 Sante Fe; pinout may differ for other Hyundai and Kia models.
From 896bd1b5c72aa2e80c498067c299e643478559bf Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 15:37:51 -0700 Subject: [PATCH 013/656] use base class in car_kf --- rednose_repo | 2 +- selfdrive/locationd/models/car_kf.py | 63 +++++----------------------- 2 files changed, 12 insertions(+), 53 deletions(-) diff --git a/rednose_repo b/rednose_repo index a6c02b647b..e50846d845 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit a6c02b647b288f4f7e50326996b38f7e21dc483c +Subproject commit e50846d845f7fe542e2538476258b926b2643398 diff --git a/selfdrive/locationd/models/car_kf.py b/selfdrive/locationd/models/car_kf.py index 7907670383..26df70a0bf 100755 --- a/selfdrive/locationd/models/car_kf.py +++ b/selfdrive/locationd/models/car_kf.py @@ -1,16 +1,16 @@ #!/usr/bin/env python3 import sys - import math + import numpy as np import sympy as sp -from selfdrive.locationd.models.constants import ObservationKind +from rednose import KalmanFilter from rednose.helpers.ekf_sym import EKF_sym, gen_code +from selfdrive.locationd.models.constants import ObservationKind i = 0 - def _slice(n): global i s = slice(i, i + n) @@ -31,10 +31,10 @@ class States(): STEER_ANGLE = _slice(1) # [rad] -class CarKalman(): +class CarKalman(KalmanFilter): name = 'car' - x_initial = np.array([ + initial_x = np.array([ 1.0, 15.0, 0.0, @@ -66,7 +66,6 @@ class CarKalman(): ObservationKind.ROAD_FRAME_X_SPEED: np.atleast_2d(0.1**2), } - maha_test_kinds = [] # [ObservationKind.ROAD_FRAME_YAW_RATE, ObservationKind.ROAD_FRAME_XY_SPEED] global_vars = [ sp.Symbol('mass'), sp.Symbol('rotational_inertia'), @@ -78,9 +77,8 @@ class CarKalman(): @staticmethod def generate_code(generated_dir): - dim_state = CarKalman.x_initial.shape[0] + dim_state = CarKalman.initial_x.shape[0] name = CarKalman.name - maha_test_kinds = CarKalman.maha_test_kinds # globals m, j, aF, aR, cF_orig, cR_orig = CarKalman.global_vars @@ -137,57 +135,18 @@ class CarKalman(): [sp.Matrix([x]), ObservationKind.STIFFNESS, None], ] - gen_code(generated_dir, name, f_sym, dt, state_sym, obs_eqs, dim_state, dim_state, maha_test_kinds=maha_test_kinds, global_vars=CarKalman.global_vars) + gen_code(generated_dir, name, f_sym, dt, state_sym, obs_eqs, dim_state, dim_state, global_vars=CarKalman.global_vars) def __init__(self, generated_dir, steer_ratio=15, stiffness_factor=1, angle_offset=0): - self.dim_state = self.x_initial.shape[0] - x_init = self.x_initial + dim_state = self.initial_x.shape[0] + dim_state_err = self.initial_P_diag.shape[0] + x_init = self.initial_x x_init[States.STEER_RATIO] = steer_ratio x_init[States.STIFFNESS] = stiffness_factor x_init[States.ANGLE_OFFSET] = angle_offset # init filter - self.filter = EKF_sym(generated_dir, self.name, self.Q, self.x_initial, self.P_initial, self.dim_state, self.dim_state, maha_test_kinds=self.maha_test_kinds, global_vars=self.global_vars) - - @property - def x(self): - return self.filter.state() - - @property - def P(self): - return self.filter.covs() - - def predict(self, t): - return self.filter.predict(t) - - def rts_smooth(self, estimates): - return self.filter.rts_smooth(estimates, norm_quats=False) - - def get_R(self, kind, n): - obs_noise = self.obs_noise[kind] - dim = obs_noise.shape[0] - R = np.zeros((n, dim, dim)) - for i in range(n): - R[i, :, :] = obs_noise - return R - - def init_state(self, state, covs_diag=None, covs=None, filter_time=None): - if covs_diag is not None: - P = np.diag(covs_diag) - elif covs is not None: - P = covs - else: - P = self.filter.covs() - self.filter.init_state(state, P, filter_time) - - def predict_and_observe(self, t, kind, data, R=None): - if len(data) > 0: - data = np.atleast_2d(data) - - if R is None: - R = self.get_R(kind, len(data)) - - self.filter.predict_and_update_batch(t, kind, data, R) + self.filter = EKF_sym(generated_dir, self.name, self.Q, self.initial_x, self.P_initial, dim_state, dim_state_err, global_vars=self.global_vars) if __name__ == "__main__": From d08c2d084f808d38ac9b8055894fd4deb57f7632 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 15:48:23 -0700 Subject: [PATCH 014/656] Lower modeld cpu threshold thanks to thneed --- common/manager_helpers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/manager_helpers.py b/common/manager_helpers.py index a8cfb3df05..1bd0f211dc 100644 --- a/common/manager_helpers.py +++ b/common/manager_helpers.py @@ -6,7 +6,7 @@ def print_cpu_usage(first_proc, last_proc): r = 0 procs = [ ("selfdrive.controls.controlsd", 59.46), - ("./_modeld", 48.94), + ("./_modeld", 6.75), ("./loggerd", 28.49), ("selfdrive.controls.plannerd", 19.77), ("selfdrive.controls.radard", 9.54), From b9b8e61e93a5f8878b0421a6002b7f2d0ea32be9 Mon Sep 17 00:00:00 2001 From: Chris Souers Date: Fri, 15 May 2020 19:36:07 -0400 Subject: [PATCH 015/656] Add ECM ID for 2018 Civic Hatchback (#1518) --- selfdrive/car/honda/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 05db8c023b..7e432fd654 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -368,6 +368,7 @@ FW_VERSIONS = { b'37805-5AN-A830\x00\x00', b'37805-5AN-A840\x00\x00', b'37805-5AN-A930\x00\x00', + b'37805-5AN-A940\x00\x00', b'37805-5AN-A950\x00\x00', b'37805-5AN-AH20\x00\x00', b'37805-5AN-L940\x00\x00', From 5677f45a655b1d065f77f55e37b300e10dadcfd0 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Fri, 15 May 2020 17:41:10 -0700 Subject: [PATCH 016/656] Update README for Hyundai car harness Remove panda / giraffe mention in footnotes where possible Car harnesses now available, removed subscript for known HKG models; left subscript for not known models --- README.md | 19 +++++++++---------- 1 file changed, 9 insertions(+), 10 deletions(-) diff --git a/README.md b/README.md index 50aa2b3417..c3c7a90e23 100644 --- a/README.md +++ b/README.md @@ -135,18 +135,18 @@ Community Maintained Cars and Features | Chrysler | Pacifica Hybrid 2017-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Chrysler | Pacifica Hybrid 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | | Genesis | G80 20182 | All | Stock | 0mph | 0mph | -| Genesis | G90 20182 | All | Stock | 0mph | 0mph | -| GMC | Acadia Denali 20183| Adaptive Cruise | openpilot | 0mph | 7mph | +| Genesis | G90 2018 | All | Stock | 0mph | 0mph | +| GMC | Acadia Denali 20182| Adaptive Cruise | openpilot | 0mph | 7mph | | Holden | Astra 20171 | Adaptive Cruise | openpilot | 0mph | 7mph | | Hyundai | Elantra 2017-192 | SCC + LKAS | Stock | 19mph | 34mph | | Hyundai | Genesis 2015-162 | SCC + LKAS | Stock | 19mph | 37mph | | Hyundai | Ioniq 20172 | SCC + LKAS | Stock | 0mph | 32mph | -| Hyundai | Ioniq 2019 EV2 | SCC + LKAS | Stock | 0mph | 32mph | +| Hyundai | Ioniq 2019 Electric | SCC + LKAS | Stock | 0mph | 32mph | | Hyundai | Kona 2017-192 | SCC + LKAS | Stock | 22mph | 0mph | | Hyundai | Kona 2019 EV2 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Palisade 20202 | All | Stock | 0mph | 0mph | -| Hyundai | Santa Fe 20192 | All | Stock | 0mph | 0mph | -| Hyundai | Sonata 20202 | All | Stock | 0mph | 0mph | +| Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | +| Hyundai | Sonata 2020 | All | Stock | 0mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019 | Adaptive Cruise | Stock | 0mph | 39mph | | Kia | Forte 20182 | SCC + LKAS | Stock | 0mph | 0mph | @@ -154,15 +154,14 @@ Community Maintained Cars and Features | Kia | Optima 20192 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Sorento 20182 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Stinger 20182 | SCC + LKAS | Stock | 0mph | 0mph | -| Nissan | Leaf 2019 | Propilot | Stock | 0mph | 0mph | -| Nissan | X-Trail 2018 | Propilot | Stock | 0mph | 0mph | +| Nissan | Leaf 20192 | Propilot | Stock | 0mph | 0mph | +| Nissan | X-Trail 20182 | Propilot | Stock | 0mph | 0mph | | Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | | Subaru | Impreza 2018-20 | EyeSight | Stock | 0mph | 0mph | -| Volkswagen| Golf 2015-193 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Golf 2015-19 | Driver Assistance | Stock | 0mph | 0mph | 1Requires a [panda](https://comma.ai/shop/products/panda-obd-ii-dongle) and [community built giraffe](https://zoneos.com/volt/). ***NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).***
-2Requires a [panda](https://comma.ai/shop/products/panda-obd-ii-dongle) and open sourced [Hyundai giraffe](https://github.com/commaai/neo/tree/master/giraffe/hyundai), designed for the 2019 Sante Fe; pinout may differ for other Hyundai and Kia models.
-3Requires a [custom connector](https://community.comma.ai/wiki/index.php/Volkswagen#Integration_at_R242_Camera) for the [car harness](https://comma.ai/shop/products/car-harness)
+2May require a custom connector for the developer [car harness](https://comma.ai/shop/products/car-harness)
Although it's not upstream, there's a community of people getting openpilot to run on Tesla's [here](https://tinkla.us/) From c18891b936a964493393242020783482e5467ac5 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 15 May 2020 18:29:22 -0700 Subject: [PATCH 017/656] Alert callback functions were returning tuples --- selfdrive/controls/lib/events.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 78ccd2575d..512d0044bd 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -164,7 +164,7 @@ def below_steer_speed_alert(CP, sm, metric): "TAKE CONTROL", "Steer Unavailable Below %d %s" % (speed, unit), AlertStatus.userPrompt, AlertSize.mid, - Priority.MID, VisualAlert.steerRequired, AudibleAlert.none, 0., 0.4, .3), + Priority.MID, VisualAlert.steerRequired, AudibleAlert.none, 0., 0.4, .3) def calibration_incomplete_alert(CP, sm, metric): speed = int(Filter.MIN_SPEED * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH)) @@ -173,7 +173,7 @@ def calibration_incomplete_alert(CP, sm, metric): "Calibration in Progress: %d" % sm['liveCalibration'].calPerc, "Drive Above %d %s" % (speed, unit), AlertStatus.normal, AlertSize.mid, - Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2) EVENTS = { # ********** events with no alerts ********** From 7abcf71f922c9bbff2f71b69c2946e7a57fecc53 Mon Sep 17 00:00:00 2001 From: Chris Souers Date: Fri, 15 May 2020 21:30:19 -0400 Subject: [PATCH 018/656] These lines are an unlabeled duplicate of the 4 below it. (#1519) --- selfdrive/car/honda/values.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 7e432fd654..83f2c66a9f 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -439,10 +439,6 @@ FW_VERSIONS = { b'36161-TGL-G050\x00\x00', b'36161-TGG-A080\x00\x00', ], - (Ecu.unknown, 0x18daeff1, None): [ - b'38897-TBA-A110\x00\x00', - b'38897-TBA-A020\x00\x00', - ], (Ecu.gateway, 0x18daeff1, None): [ b'38897-TBA-A110\x00\x00', b'38897-TBA-A020\x00\x00', From 135385c5fb47ca1b9efaf3ae9e388b44cd6e538d Mon Sep 17 00:00:00 2001 From: Andre Volmensky Date: Sat, 16 May 2020 17:14:10 +0900 Subject: [PATCH 019/656] Bugfix: Reset saturated_count if angle no longer saturated (#1522) --- selfdrive/controls/controlsd.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index e529054013..93353d0690 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -364,6 +364,8 @@ class Controls: if angle_control_saturated and not CS.steeringPressed and self.active: self.saturated_count += 1 + else: + self.saturated_count = 0 # Send a "steering required alert" if saturation count has reached the limit if (lac_log.saturated and not CS.steeringPressed) or \ From 31346264b539312a7bff8563f7d7b7fbb33b72fb Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Sat, 16 May 2020 21:38:38 -0700 Subject: [PATCH 020/656] Faster CI (#1527) --- Dockerfile.openpilot | 23 +++++++---------------- 1 file changed, 7 insertions(+), 16 deletions(-) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index a9f58f752c..defc0ca4c4 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -1,7 +1,7 @@ FROM ubuntu:16.04 ENV PYTHONUNBUFFERED 1 -RUN apt-get update && apt-get install -y \ +RUN apt-get update && apt-get install -y --no-install-recommends \ autoconf \ build-essential \ bzip2 \ @@ -37,11 +37,9 @@ RUN apt-get update && apt-get install -y \ opencl-headers \ python-dev \ python-pip \ - screen \ sudo \ - vim \ - wget - + wget \ + && rm -rf /var/lib/apt/lists/* RUN sed -i -e 's/# en_US.UTF-8 UTF-8/en_US.UTF-8 UTF-8/' /etc/locale.gen && locale-gen ENV LANG en_US.UTF-8 @@ -51,16 +49,13 @@ ENV LC_ALL en_US.UTF-8 RUN curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash ENV PATH="/root/.pyenv/bin:/root/.pyenv/shims:${PATH}" -RUN pyenv install 3.8.2 -RUN pyenv global 3.8.2 +RUN pyenv install 3.8.2 && pyenv global 3.8.2 RUN pyenv rehash RUN pip install pipenv==2018.11.26 -COPY Pipfile /tmp/ -COPY Pipfile.lock /tmp/ +COPY Pipfile Pipfile.lock /tmp/ -RUN python --version RUN cd /tmp && pipenv install --system --deploy # Install subset of dev dependencies needed for CI @@ -71,24 +66,20 @@ ENV PYTHONPATH /tmp/openpilot:${PYTHONPATH} RUN mkdir -p /tmp/openpilot -COPY ./flake8_openpilot.sh /tmp/openpilot/ -COPY ./pylint_openpilot.sh /tmp/openpilot/ -COPY ./.pylintrc /tmp/openpilot/ - -COPY ./.coveragerc-app /tmp/openpilot/ +COPY ./flake8_openpilot.sh ./pylint_openpilot.sh ./.pylintrc ./.coveragerc-app /tmp/openpilot/ COPY ./pyextra /tmp/openpilot/pyextra COPY ./phonelibs /tmp/openpilot/phonelibs COPY ./external /tmp/openpilot/external COPY ./laika /tmp/openpilot/laika COPY ./laika_repo /tmp/openpilot/laika_repo +COPY ./rednose /tmp/openpilot/rednose COPY ./tools /tmp/openpilot/tools COPY ./release /tmp/openpilot/release COPY ./common /tmp/openpilot/common COPY ./opendbc /tmp/openpilot/opendbc COPY ./cereal /tmp/openpilot/cereal COPY ./panda /tmp/openpilot/panda -COPY ./rednose /tmp/openpilot/rednose COPY ./selfdrive /tmp/openpilot/selfdrive COPY SConstruct /tmp/openpilot/SConstruct From ce8b629fb0fc989d99fa38f49eb96e552dc6e728 Mon Sep 17 00:00:00 2001 From: Noel Schenk Date: Sun, 17 May 2020 06:59:28 +0200 Subject: [PATCH 021/656] tensorflow-gpu==2.1 update (#1525) not available on current used python version --- tools/ubuntu_setup.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/ubuntu_setup.sh b/tools/ubuntu_setup.sh index a70def87a2..27e9d6d78e 100755 --- a/tools/ubuntu_setup.sh +++ b/tools/ubuntu_setup.sh @@ -89,7 +89,7 @@ pipenv install --system --deploy pip install -r tools/requirements.txt # to make modeld work on PC with nvidia GPU -pip install tensorflow-gpu==2.1 +pip install tensorflow-gpu==2.2 # for loggerd to work on ubuntu # TODO: PC should log somewhere else From a415fe1ebec7bf54cf2cdea31b75dd90b0c8809b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 17 May 2020 13:32:26 -0700 Subject: [PATCH 022/656] capnp is no longer in external --- tools/openpilot_env.sh | 3 --- 1 file changed, 3 deletions(-) diff --git a/tools/openpilot_env.sh b/tools/openpilot_env.sh index ccf76db2bc..95f3b12ece 100644 --- a/tools/openpilot_env.sh +++ b/tools/openpilot_env.sh @@ -6,9 +6,6 @@ if [ -z "$OPENPILOT_ENV" ]; then export PATH="$HOME/.pyenv/bin:$PATH" eval "$(pyenv init -)" eval "$(pyenv virtualenv-init -)" - - export PATH="$PATH:$HOME/openpilot/external/capnp/bin" - export LD_LIBRARY_PATH="$LD_LIBRARY_PATH:$HOME/openpilot/external/capnp/lib" elif [[ "$unamestr" == 'Darwin' ]]; then # msgq doesn't work on mac export ZMQ=1 From 2063a370d37311375ae6c868c6567aa76f6806d2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 17 May 2020 14:01:38 -0700 Subject: [PATCH 023/656] don't need external in CI, compressed docker image is 50MB smaller --- Dockerfile.openpilot | 2 -- 1 file changed, 2 deletions(-) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index defc0ca4c4..39d56cdaf5 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -61,7 +61,6 @@ RUN cd /tmp && pipenv install --system --deploy # Install subset of dev dependencies needed for CI RUN pip install matplotlib==3.1.1 dictdiffer==0.8.0 fastcluster==1.1.25 aenum==2.2.1 lru-dict==1.1.6 scipy==1.4.1 tenacity==5.1.1 azure-common==1.1.23 azure-nspkg==3.0.2 azure-storage-blob==2.1.0 azure-storage-common==2.1.0 azure-storage-nspkg==3.1.0 pycurl==7.43.0.3 coverage==5.1 -ENV PATH="/tmp/openpilot/external/bin:${PATH}" ENV PYTHONPATH /tmp/openpilot:${PYTHONPATH} RUN mkdir -p /tmp/openpilot @@ -70,7 +69,6 @@ COPY ./flake8_openpilot.sh ./pylint_openpilot.sh ./.pylintrc ./.coveragerc-app / COPY ./pyextra /tmp/openpilot/pyextra COPY ./phonelibs /tmp/openpilot/phonelibs -COPY ./external /tmp/openpilot/external COPY ./laika /tmp/openpilot/laika COPY ./laika_repo /tmp/openpilot/laika_repo COPY ./rednose /tmp/openpilot/rednose From 1c982a5e91846e494c0ec1c06fdab3966ccb38b8 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 17 May 2020 14:29:25 -0700 Subject: [PATCH 024/656] add github actions status badge to README --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index c3c7a90e23..391c937a8e 100644 --- a/README.md +++ b/README.md @@ -327,6 +327,7 @@ NO WARRANTY EXPRESSED OR IMPLIED.** +![Openpilot Tests](https://github.com/commaai/openpilot/workflows/Openpilot%20Tests/badge.svg) [![Total alerts](https://img.shields.io/lgtm/alerts/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/alerts/) [![Language grade: Python](https://img.shields.io/lgtm/grade/python/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/context:python) [![Language grade: C/C++](https://img.shields.io/lgtm/grade/cpp/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/context:cpp) From 6c4663029374d0e6a8e66304fe460395f8c98ecb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 17 May 2020 14:22:20 -0700 Subject: [PATCH 025/656] no pip cache in docker build, compressed docker image is 70MB smaller --- Dockerfile.openpilot | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 39d56cdaf5..3c65d655c8 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -52,14 +52,14 @@ ENV PATH="/root/.pyenv/bin:/root/.pyenv/shims:${PATH}" RUN pyenv install 3.8.2 && pyenv global 3.8.2 RUN pyenv rehash -RUN pip install pipenv==2018.11.26 +RUN pip install --no-cache-dir pipenv==2018.11.26 COPY Pipfile Pipfile.lock /tmp/ RUN cd /tmp && pipenv install --system --deploy # Install subset of dev dependencies needed for CI -RUN pip install matplotlib==3.1.1 dictdiffer==0.8.0 fastcluster==1.1.25 aenum==2.2.1 lru-dict==1.1.6 scipy==1.4.1 tenacity==5.1.1 azure-common==1.1.23 azure-nspkg==3.0.2 azure-storage-blob==2.1.0 azure-storage-common==2.1.0 azure-storage-nspkg==3.1.0 pycurl==7.43.0.3 coverage==5.1 +RUN pip install --no-cache-dir matplotlib==3.1.1 dictdiffer==0.8.0 fastcluster==1.1.25 aenum==2.2.1 lru-dict==1.1.6 scipy==1.4.1 tenacity==5.1.1 azure-common==1.1.23 azure-nspkg==3.0.2 azure-storage-blob==2.1.0 azure-storage-common==2.1.0 azure-storage-nspkg==3.1.0 pycurl==7.43.0.3 coverage==5.1 ENV PYTHONPATH /tmp/openpilot:${PYTHONPATH} From 81686547cc10dc129fb921f938dc496455613e33 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Sun, 17 May 2020 20:59:53 -0700 Subject: [PATCH 026/656] Locationd cleanup (#1517) * way cleaner take 2 * cleanup * be more relaxed * just let it be * don't drive backwards or upside down * do this more * vNED sometyimes invalid * use reasonble stds * stability in nonlinear zone * previous metrics were without publishing --- common/manager_helpers.py | 2 +- selfdrive/locationd/locationd.py | 111 +++++++++++------------- selfdrive/locationd/models/constants.py | 3 + selfdrive/locationd/models/live_kf.py | 43 +++++---- 4 files changed, 81 insertions(+), 78 deletions(-) diff --git a/common/manager_helpers.py b/common/manager_helpers.py index 1bd0f211dc..e5ae067035 100644 --- a/common/manager_helpers.py +++ b/common/manager_helpers.py @@ -12,7 +12,7 @@ def print_cpu_usage(first_proc, last_proc): ("selfdrive.controls.radard", 9.54), ("./_ui", 9.54), ("./camerad", 7.07), - ("selfdrive.locationd.locationd", 7.13), + ("selfdrive.locationd.locationd", 13.96), ("./_sensord", 6.17), ("selfdrive.controls.dmonitoringd", 5.48), ("./boardd", 3.63), diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 7075fdf3f0..b8359a49b0 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -1,16 +1,14 @@ #!/usr/bin/env python3 -import math - import numpy as np import sympy as sp import cereal.messaging as messaging import common.transformations.coordinates as coord -from common.transformations.orientation import (ecef_euler_from_ned, - euler_from_quat, - ned_euler_from_ecef, - quat_from_euler, - rot_from_quat, rot_from_euler) +from common.transformations.orientation import ecef_euler_from_ned, \ + euler_from_quat, \ + ned_euler_from_ecef, \ + quat_from_euler, \ + rot_from_quat, rot_from_euler from rednose.helpers import KalmanError from selfdrive.locationd.models.live_kf import LiveKalman, States, ObservationKind from selfdrive.locationd.models.constants import GENERATED_DIR @@ -147,21 +145,20 @@ class Localizer(): #fix.gpsTimeOfWeek = self.time.tow fix.unixTimestampMillis = self.unix_timestamp_millis - if self.filter_ready and self.calibrated: + if np.linalg.norm(fix.positionECEF.std) < 50 and self.calibrated: fix.status = 'valid' - elif self.filter_ready: + elif np.linalg.norm(fix.positionECEF.std) < 50: fix.status = 'uncalibrated' else: fix.status = 'uninitialized' return fix - def update_kalman(self, time, kind, meas): - if self.filter_ready: - try: - self.kf.predict_and_observe(time, kind, meas) - except KalmanError: - cloudlog.error("Error in predict and observe, kalman reset") - self.reset_kalman() + def update_kalman(self, time, kind, meas, R=None): + try: + self.kf.predict_and_observe(time, kind, meas, R=R) + except KalmanError: + cloudlog.error("Error in predict and observe, kalman reset") + self.reset_kalman() #idx = bisect_right([x[0] for x in self.observation_buffer], time) #self.observation_buffer.insert(idx, (time, kind, meas)) #while len(self.observation_buffer) > 0 and self.observation_buffer[-1][0] - self.observation_buffer[0][0] > self.max_age: @@ -169,42 +166,38 @@ class Localizer(): # self.observation_buffer.pop(0) def handle_gps(self, current_time, log): + # ignore the message if the fix is invalid + if log.flags % 2 == 0: + return self.converter = coord.LocalCoord.from_geodetic([log.latitude, log.longitude, log.altitude]) - fix_ecef = self.converter.ned2ecef([0, 0, 0]) + ecef_pos = self.converter.ned2ecef([0, 0, 0]) + ecef_vel = self.converter.ned2ecef_matrix.dot(np.array(log.vNED)) + ecef_pos_R = np.diag([(3*log.verticalAccuracy)**2]*3) + ecef_vel_R = np.diag([(log.speedAccuracy)**2]*3) + #self.time = GPSTime.from_datetime(datetime.utcfromtimestamp(log.timestamp*1e-3)) self.unix_timestamp_millis = log.timestamp + gps_est_error = np.sqrt((self.kf.x[0] - ecef_pos[0])**2 + + (self.kf.x[1] - ecef_pos[1])**2 + + (self.kf.x[2] - ecef_pos[2])**2) + + orientation_ecef = euler_from_quat(self.kf.x[States.ECEF_ORIENTATION]) + orientation_ned = ned_euler_from_ecef(ecef_pos, orientation_ecef) + orientation_ned_gps = np.array([0, 0, np.radians(log.bearing)]) + orientation_error = np.mod(orientation_ned - orientation_ned_gps - np.pi, 2*np.pi) - np.pi + if np.linalg.norm(ecef_vel) > 5 and np.linalg.norm(orientation_error) > 1: + cloudlog.error("Locationd vs ubloxLocation orientation difference too large, kalman reset") + initial_pose_ecef_quat = quat_from_euler(ecef_euler_from_ned(ecef_pos, orientation_ned_gps)) + self.reset_kalman(init_orient=initial_pose_ecef_quat) + self.update_kalman(current_time, ObservationKind.ECEF_ORIENTATION_FROM_GPS, initial_pose_ecef_quat) + elif gps_est_error > 50: + cloudlog.error("Locationd vs ubloxLocation position difference too large, kalman reset") + self.reset_kalman() + + self.update_kalman(current_time, ObservationKind.ECEF_POS, ecef_pos, R=ecef_pos_R) + self.update_kalman(current_time, ObservationKind.ECEF_VEL, ecef_vel, R=ecef_vel_R) - # TODO initing with bad bearing not allowed, maybe not bad? - if not self.filter_ready and log.speed > 5: - self.filter_ready = True - initial_ecef = fix_ecef - gps_bearing = math.radians(log.bearing) - initial_pose_ecef = ecef_euler_from_ned(initial_ecef, [0, 0, gps_bearing]) - initial_pose_ecef_quat = quat_from_euler(initial_pose_ecef) - gps_speed = log.speed - quat_uncertainty = 0.2**2 - - initial_state = LiveKalman.initial_x - initial_covs_diag = LiveKalman.initial_P_diag - - initial_state[States.ECEF_POS] = initial_ecef - initial_state[States.ECEF_ORIENTATION] = initial_pose_ecef_quat - initial_state[States.ECEF_VELOCITY] = rot_from_quat(initial_pose_ecef_quat).dot(np.array([gps_speed, 0, 0])) - - initial_covs_diag[States.ECEF_POS_ERR] = 10**2 - initial_covs_diag[States.ECEF_ORIENTATION_ERR] = quat_uncertainty - initial_covs_diag[States.ECEF_VELOCITY_ERR] = 1**2 - self.kf.init_state(initial_state, covs=np.diag(initial_covs_diag), filter_time=current_time) - cloudlog.info("Filter initialized") - elif self.filter_ready: - self.update_kalman(current_time, ObservationKind.ECEF_POS, fix_ecef) - gps_est_error = np.sqrt((self.kf.x[0] - fix_ecef[0])**2 + - (self.kf.x[1] - fix_ecef[1])**2 + - (self.kf.x[2] - fix_ecef[2])**2) - if gps_est_error > 50: - cloudlog.error("Locationd vs ubloxLocation difference too large, kalman reset") - self.reset_kalman() def handle_car_state(self, current_time, log): self.speed_counter += 1 @@ -222,12 +215,12 @@ class Localizer(): rot_device_std = self.device_from_calib.dot(log.rotStd) self.update_kalman(current_time, ObservationKind.CAMERA_ODO_ROTATION, - np.concatenate([rot_device, rot_device_std])) + np.concatenate([rot_device, 10*rot_device_std])) trans_device = self.device_from_calib.dot(log.trans) trans_device_std = self.device_from_calib.dot(log.transStd) self.update_kalman(current_time, ObservationKind.CAMERA_ODO_TRANSLATION, - np.concatenate([trans_device, trans_device_std])) + np.concatenate([trans_device, 10*trans_device_std])) def handle_sensors(self, current_time, log): # TODO does not yet account for double sensor readings in the log @@ -236,10 +229,6 @@ class Localizer(): if sensor_reading.sensor == 5 and sensor_reading.type == 16: self.gyro_counter += 1 if self.gyro_counter % SENSOR_DECIMATION == 0: - if max(abs(self.kf.x[States.IMU_OFFSET])) > 0.07: - cloudlog.info('imu frame angles exceeded, correcting') - self.update_kalman(current_time, ObservationKind.IMU_FRAME, [0, 0, 0]) - v = sensor_reading.gyroUncalibrated.v self.update_kalman(current_time, ObservationKind.PHONE_GYRO, [-v[2], -v[1], -v[0]]) @@ -256,9 +245,14 @@ class Localizer(): self.calib_from_device = self.device_from_calib.T self.calibrated = log.calStatus == 1 - def reset_kalman(self): - self.filter_time = None - self.filter_ready = False + def reset_kalman(self, current_time=None, init_orient=None): + self.filter_time = current_time + init_x = LiveKalman.initial_x + # too nonlinear to init on completely wrong + if init_orient is not None: + init_x[3:7] = init_orient + self.kf.init_state(init_x, covs=np.diag(LiveKalman.initial_P_diag), filter_time=current_time) + self.observation_buffer = [] self.gyro_counter = 0 @@ -269,7 +263,8 @@ class Localizer(): def locationd_thread(sm, pm, disabled_logs=[]): if sm is None: - sm = messaging.SubMaster(['gpsLocationExternal', 'sensorEvents', 'cameraOdometry', 'liveCalibration']) + socks = ['gpsLocationExternal', 'sensorEvents', 'cameraOdometry', 'liveCalibration'] + sm = messaging.SubMaster(socks) if pm is None: pm = messaging.PubMaster(['liveLocationKalman']) @@ -292,7 +287,7 @@ def locationd_thread(sm, pm, disabled_logs=[]): elif sock == "liveCalibration": localizer.handle_live_calib(t, sm[sock]) - if localizer.filter_ready and sm.updated['gpsLocationExternal']: + if sm.updated['gpsLocationExternal']: t = sm.logMonoTime['gpsLocationExternal'] msg = messaging.new_message('liveLocationKalman') msg.logMonoTime = t diff --git a/selfdrive/locationd/models/constants.py b/selfdrive/locationd/models/constants.py index 8b99fce649..f0096aadb8 100644 --- a/selfdrive/locationd/models/constants.py +++ b/selfdrive/locationd/models/constants.py @@ -27,6 +27,8 @@ class ObservationKind: PSEUDORANGE_RATE_GLONASS = 21 PSEUDORANGE = 22 PSEUDORANGE_RATE = 23 + ECEF_VEL = 31 + ECEF_ORIENTATION_FROM_GPS = 32 ROAD_FRAME_XY_SPEED = 24 # (x, y) [m/s] ROAD_FRAME_YAW_RATE = 25 # [rad/s] @@ -36,6 +38,7 @@ class ObservationKind: STEER_RATIO = 29 # [-] ROAD_FRAME_X_SPEED = 30 # (x) [m/s] + names = [ 'Unknown', 'No observation', diff --git a/selfdrive/locationd/models/live_kf.py b/selfdrive/locationd/models/live_kf.py index 299d6b25c4..c8d4c7ed24 100755 --- a/selfdrive/locationd/models/live_kf.py +++ b/selfdrive/locationd/models/live_kf.py @@ -1,11 +1,11 @@ #!/usr/bin/env python3 + import sys import numpy as np import sympy as sp from selfdrive.locationd.models.constants import ObservationKind -from rednose.helpers import KalmanError from rednose.helpers.ekf_sym import EKF_sym, gen_code from rednose.helpers.sympy_helpers import euler_rotate, quat_matrix_r, quat_rotate @@ -46,9 +46,9 @@ class LiveKalman(): 0, 0, 0]) # state covariance - initial_P_diag = np.array([10000**2, 10000**2, 10000**2, - 10**2, 10**2, 10**2, - 10**2, 10**2, 10**2, + initial_P_diag = np.array([1e14, 1e14, 1e14, + 1e6, 1e6, 1e6, + 1e4, 1e4, 1e4, 1**2, 1**2, 1**2, 0.05**2, 0.05**2, 0.05**2, 0.02**2, @@ -57,8 +57,8 @@ class LiveKalman(): # process noise Q = np.diag([0.03**2, 0.03**2, 0.03**2, - 0.0**2, 0.0**2, 0.0**2, - 0.0**2, 0.0**2, 0.0**2, + 0.001**2, 0.001*2, 0.001**2, + 0.01**2, 0.01**2, 0.01**2, 0.1**2, 0.1**2, 0.1**2, (0.005 / 100)**2, (0.005 / 100)**2, (0.005 / 100)**2, (0.02 / 100)**2, @@ -172,6 +172,8 @@ class LiveKalman(): h_speed_sym = sp.Matrix([speed * odo_scale]) h_pos_sym = sp.Matrix([x, y, z]) + h_vel_sym = sp.Matrix([vx, vy, vz]) + h_orientation_sym = q h_imu_frame_sym = sp.Matrix(imu_angles) h_relative_motion = sp.Matrix(quat_rot.T * v) @@ -181,6 +183,8 @@ class LiveKalman(): [h_phone_rot_sym, ObservationKind.NO_ROT, None], [h_acc_sym, ObservationKind.PHONE_ACCEL, None], [h_pos_sym, ObservationKind.ECEF_POS, None], + [h_vel_sym, ObservationKind.ECEF_VEL, None], + [h_orientation_sym, ObservationKind.ECEF_ORIENTATION_FROM_GPS, None], [h_relative_motion, ObservationKind.CAMERA_ODO_TRANSLATION, None], [h_phone_rot_sym, ObservationKind.CAMERA_ODO_ROTATION, None], [h_imu_frame_sym, ObservationKind.IMU_FRAME, None]] @@ -197,7 +201,9 @@ class LiveKalman(): ObservationKind.CAMERA_ODO_ROTATION: np.diag([0.05**2, 0.05**2, 0.05**2]), ObservationKind.IMU_FRAME: np.diag([0.05**2, 0.05**2, 0.05**2]), ObservationKind.NO_ROT: np.diag([0.00025**2, 0.00025**2, 0.00025**2]), - ObservationKind.ECEF_POS: np.diag([5**2, 5**2, 5**2])} + ObservationKind.ECEF_POS: np.diag([5**2, 5**2, 5**2]), + ObservationKind.ECEF_VEL: np.diag([.5**2, .5**2, .5**2]), + ObservationKind.ECEF_ORIENTATION_FROM_GPS: np.diag([.2**2, .2**2, .2**2, .2**2])} # init filter self.filter = EKF_sym(generated_dir, self.name, self.Q, self.initial_x, np.diag(self.initial_P_diag), self.dim_state, self.dim_state_err) @@ -226,25 +232,24 @@ class LiveKalman(): P = self.filter.covs() self.filter.init_state(state, P, filter_time) - def predict_and_observe(self, t, kind, data): - if len(data) > 0: - data = np.atleast_2d(data) + def predict_and_observe(self, t, kind, meas, R=None): + if len(meas) > 0: + meas = np.atleast_2d(meas) if kind == ObservationKind.CAMERA_ODO_TRANSLATION: - r = self.predict_and_update_odo_trans(data, t, kind) + r = self.predict_and_update_odo_trans(meas, t, kind) elif kind == ObservationKind.CAMERA_ODO_ROTATION: - r = self.predict_and_update_odo_rot(data, t, kind) + r = self.predict_and_update_odo_rot(meas, t, kind) elif kind == ObservationKind.ODOMETRIC_SPEED: - r = self.predict_and_update_odo_speed(data, t, kind) + r = self.predict_and_update_odo_speed(meas, t, kind) else: - r = self.filter.predict_and_update_batch(t, kind, data, self.get_R(kind, len(data))) + if R is None: + R = self.get_R(kind, len(meas)) + elif len(R.shape) == 2: + R = R[None] + r = self.filter.predict_and_update_batch(t, kind, meas, R) # Normalize quats quat_norm = np.linalg.norm(self.filter.x[3:7, 0]) - - # Should not continue if the quats behave this weirdly - if not (0.1 < quat_norm < 10): - raise KalmanError("Kalman filter quaternions unstable") - self.filter.x[States.ECEF_ORIENTATION, 0] = self.filter.x[States.ECEF_ORIENTATION, 0] / quat_norm return r From 78a352a8ca8a948e86e7c752732e470f89d92280 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Sun, 17 May 2020 23:13:17 -0700 Subject: [PATCH 027/656] This isn't bigmodel, but there's a lot of good stuff here (#1532) * bigmodel * more debug print * debugging bigmodel * remove the tanh, debugging * print images/buffers * disassemble the command queues * decompiler * dump the shaders * full disasm * support patching kernel and fixing convolution_horizontal_reduced_reads_1x1 * microbenchmark * 42 GFLOPS, 1 GB/s * gemm benchmark * 75 GFLOPS vs 42 GFLOPS * 115 GFLOPS * oops, never mind * gemm image is slow * this is pretty hopeless * gemm image gets 62 GFLOPS * this is addictive and still a waste of time * cleanup cleanup * that hook was dumb * tabbing * more tabbing Co-authored-by: Comma Device --- .../thneed/debug/decompiler/disasm-a3xx.c | 1426 ++++++++++++++ .../thneed/debug/decompiler/instr-a3xx.h | 1119 +++++++++++ .../modeld/thneed/debug/decompiler/ir3.h | 1755 +++++++++++++++++ .../thneed/debug/decompiler/shader_enums.h | 906 +++++++++ .../thneed/debug/decompiler/util/bitset.h | 261 +++ .../thneed/debug/decompiler/util/list.h | 262 +++ .../thneed/debug/decompiler/util/macros.h | 346 ++++ selfdrive/modeld/thneed/debug/disassembler.cc | 132 ++ .../thneed/debug/microbenchmark/gemm.cl | 51 + .../thneed/debug/microbenchmark/gemm_image.cl | 75 + .../modeld/thneed/debug/microbenchmark/go.c | 314 +++ .../modeld/thneed/debug/microbenchmark/run.sh | 2 + selfdrive/modeld/thneed/debug/test.cc | 34 +- selfdrive/modeld/thneed/thneed.cc | 107 +- selfdrive/modeld/thneed/thneed.h | 3 +- 15 files changed, 6770 insertions(+), 23 deletions(-) create mode 100644 selfdrive/modeld/thneed/debug/decompiler/disasm-a3xx.c create mode 100644 selfdrive/modeld/thneed/debug/decompiler/instr-a3xx.h create mode 100644 selfdrive/modeld/thneed/debug/decompiler/ir3.h create mode 100644 selfdrive/modeld/thneed/debug/decompiler/shader_enums.h create mode 100644 selfdrive/modeld/thneed/debug/decompiler/util/bitset.h create mode 100644 selfdrive/modeld/thneed/debug/decompiler/util/list.h create mode 100644 selfdrive/modeld/thneed/debug/decompiler/util/macros.h create mode 100644 selfdrive/modeld/thneed/debug/disassembler.cc create mode 100644 selfdrive/modeld/thneed/debug/microbenchmark/gemm.cl create mode 100644 selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl create mode 100644 selfdrive/modeld/thneed/debug/microbenchmark/go.c create mode 100755 selfdrive/modeld/thneed/debug/microbenchmark/run.sh diff --git a/selfdrive/modeld/thneed/debug/decompiler/disasm-a3xx.c b/selfdrive/modeld/thneed/debug/decompiler/disasm-a3xx.c new file mode 100644 index 0000000000..1b40fb7fc0 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/decompiler/disasm-a3xx.c @@ -0,0 +1,1426 @@ +/* + * Copyright (c) 2013 Rob Clark + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice (including the next + * paragraph) shall be included in all copies or substantial portions of the + * Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +#include +#include +#include +#include +#include +#include + +//#include + +#include "util/macros.h" +#include "instr-a3xx.h" + +/* bitmask of debug flags */ +enum debug_t { + PRINT_RAW = 0x1, /* dump raw hexdump */ + PRINT_VERBOSE = 0x2, + EXPAND_REPEAT = 0x4, +}; + +static enum debug_t debug = PRINT_RAW | PRINT_VERBOSE | EXPAND_REPEAT; + +static const char *levels[] = { + "", + "\t", + "\t\t", + "\t\t\t", + "\t\t\t\t", + "\t\t\t\t\t", + "\t\t\t\t\t\t", + "\t\t\t\t\t\t\t", + "\t\t\t\t\t\t\t\t", + "\t\t\t\t\t\t\t\t\t", + "x", + "x", + "x", + "x", + "x", + "x", +}; + +static const char *component = "xyzw"; + +static const char *type[] = { + [TYPE_F16] = "f16", + [TYPE_F32] = "f32", + [TYPE_U16] = "u16", + [TYPE_U32] = "u32", + [TYPE_S16] = "s16", + [TYPE_S32] = "s32", + [TYPE_U8] = "u8", + [TYPE_S8] = "s8", +}; + +struct disasm_ctx { + FILE *out; + int level; + unsigned gpu_id; + + /* current instruction repeat flag: */ + unsigned repeat; + /* current instruction repeat indx/offset (for --expand): */ + unsigned repeatidx; + + unsigned instructions; +}; + +static const char *float_imms[] = { + "0.0", + "0.5", + "1.0", + "2.0", + "e", + "pi", + "1/pi", + "1/log2(e)", + "log2(e)", + "1/log2(10)", + "log2(10)", + "4.0", +}; + +static void print_reg(struct disasm_ctx *ctx, reg_t reg, bool full, + bool is_float, bool r, + bool c, bool im, bool neg, bool abs, bool addr_rel) +{ + const char type = c ? 'c' : 'r'; + + // XXX I prefer - and || for neg/abs, but preserving format used + // by libllvm-a3xx for easy diffing.. + + if (abs && neg) + fprintf(ctx->out, "(absneg)"); + else if (neg) + fprintf(ctx->out, "(neg)"); + else if (abs) + fprintf(ctx->out, "(abs)"); + + if (r) + fprintf(ctx->out, "(r)"); + + if (im) { + if (is_float && full && reg.iim_val < ARRAY_SIZE(float_imms)) { + fprintf(ctx->out, "(%s)", float_imms[reg.iim_val]); + } else { + fprintf(ctx->out, "%d", reg.iim_val); + } + } else if (addr_rel) { + /* I would just use %+d but trying to make it diff'able with + * libllvm-a3xx... + */ + if (reg.iim_val < 0) + fprintf(ctx->out, "%s%c", full ? "" : "h", type, -reg.iim_val); + else if (reg.iim_val > 0) + fprintf(ctx->out, "%s%c", full ? "" : "h", type, reg.iim_val); + else + fprintf(ctx->out, "%s%c", full ? "" : "h", type); + } else if ((reg.num == REG_A0) && !c) { + /* This matches libllvm output, the second (scalar) address register + * seems to be called a1.x instead of a0.y. + */ + fprintf(ctx->out, "a%d.x", reg.comp); + } else if ((reg.num == REG_P0) && !c) { + fprintf(ctx->out, "p0.%c", component[reg.comp]); + } else { + fprintf(ctx->out, "%s%c%d.%c", full ? "" : "h", type, reg.num, component[reg.comp]); + } +} + +static unsigned regidx(reg_t reg) +{ + return (4 * reg.num) + reg.comp; +} + +static reg_t idxreg(unsigned idx) +{ + return (reg_t){ + .comp = idx & 0x3, + .num = idx >> 2, + }; +} + +static void print_reg_dst(struct disasm_ctx *ctx, reg_t reg, bool full, bool addr_rel) +{ + reg = idxreg(regidx(reg) + ctx->repeatidx); + print_reg(ctx, reg, full, false, false, false, false, false, false, addr_rel); +} + +/* TODO switch to using reginfo struct everywhere, since more readable + * than passing a bunch of bools to print_reg_src + */ + +struct reginfo { + reg_t reg; + bool full; + bool r; + bool c; + bool f; /* src reg is interpreted as float, used for printing immediates */ + bool im; + bool neg; + bool abs; + bool addr_rel; +}; + +static void print_src(struct disasm_ctx *ctx, struct reginfo *info) +{ + reg_t reg = info->reg; + + if (info->r) + reg = idxreg(regidx(info->reg) + ctx->repeatidx); + + print_reg(ctx, reg, info->full, info->f, info->r, info->c, info->im, + info->neg, info->abs, info->addr_rel); +} + +//static void print_dst(struct disasm_ctx *ctx, struct reginfo *info) +//{ +// print_reg_dst(ctx, info->reg, info->full, info->addr_rel); +//} + +static void print_instr_cat0(struct disasm_ctx *ctx, instr_t *instr) +{ + static const struct { + const char *suffix; + int nsrc; + bool idx; + } brinfo[7] = { + [BRANCH_PLAIN] = { "r", 1, false }, + [BRANCH_OR] = { "rao", 2, false }, + [BRANCH_AND] = { "raa", 2, false }, + [BRANCH_CONST] = { "rac", 0, true }, + [BRANCH_ANY] = { "any", 1, false }, + [BRANCH_ALL] = { "all", 1, false }, + [BRANCH_X] = { "rax", 0, false }, + }; + instr_cat0_t *cat0 = &instr->cat0; + + switch (instr_opc(instr, ctx->gpu_id)) { + case OPC_KILL: + case OPC_PREDT: + case OPC_PREDF: + fprintf(ctx->out, " %sp0.%c", cat0->inv0 ? "!" : "", + component[cat0->comp0]); + break; + case OPC_B: + fprintf(ctx->out, "%s", brinfo[cat0->brtype].suffix); + if (brinfo[cat0->brtype].idx) { + fprintf(ctx->out, ".%u", cat0->idx); + } + if (brinfo[cat0->brtype].nsrc >= 1) { + fprintf(ctx->out, " %sp0.%c,", cat0->inv0 ? "!" : "", + component[cat0->comp0]); + } + if (brinfo[cat0->brtype].nsrc >= 2) { + fprintf(ctx->out, " %sp0.%c,", cat0->inv1 ? "!" : "", + component[cat0->comp1]); + } + fprintf(ctx->out, " #%d", cat0->a3xx.immed); + break; + case OPC_JUMP: + case OPC_CALL: + case OPC_BKT: + case OPC_GETONE: + case OPC_SHPS: + fprintf(ctx->out, " #%d", cat0->a3xx.immed); + break; + } + + if ((debug & PRINT_VERBOSE) && (cat0->dummy3|cat0->dummy4)) + fprintf(ctx->out, "\t{0: %x,%x}", cat0->dummy3, cat0->dummy4); +} + +static void print_instr_cat1(struct disasm_ctx *ctx, instr_t *instr) +{ + instr_cat1_t *cat1 = &instr->cat1; + + if (cat1->ul) + fprintf(ctx->out, "(ul)"); + + if (cat1->src_type == cat1->dst_type) { + if ((cat1->src_type == TYPE_S16) && (((reg_t)cat1->dst).num == REG_A0)) { + /* special case (nmemonic?): */ + fprintf(ctx->out, "mova"); + } else { + fprintf(ctx->out, "mov.%s%s", type[cat1->src_type], type[cat1->dst_type]); + } + } else { + fprintf(ctx->out, "cov.%s%s", type[cat1->src_type], type[cat1->dst_type]); + } + + fprintf(ctx->out, " "); + + if (cat1->even) + fprintf(ctx->out, "(even)"); + + if (cat1->pos_inf) + fprintf(ctx->out, "(pos_infinity)"); + + print_reg_dst(ctx, (reg_t)(cat1->dst), type_size(cat1->dst_type) == 32, + cat1->dst_rel); + + fprintf(ctx->out, ", "); + + /* ugg, have to special case this.. vs print_reg().. */ + if (cat1->src_im) { + if (type_float(cat1->src_type)) + fprintf(ctx->out, "(%f)", cat1->fim_val); + else if (type_uint(cat1->src_type)) + fprintf(ctx->out, "0x%08x", cat1->uim_val); + else + fprintf(ctx->out, "%d", cat1->iim_val); + } else if (cat1->src_rel && !cat1->src_c) { + /* I would just use %+d but trying to make it diff'able with + * libllvm-a3xx... + */ + char type = cat1->src_rel_c ? 'c' : 'r'; + const char *full = (type_size(cat1->src_type) == 32) ? "" : "h"; + if (cat1->off < 0) + fprintf(ctx->out, "%s%c", full, type, -cat1->off); + else if (cat1->off > 0) + fprintf(ctx->out, "%s%c", full, type, cat1->off); + else + fprintf(ctx->out, "%s%c", full, type); + } else { + struct reginfo src = { + .reg = (reg_t)cat1->src, + .full = type_size(cat1->src_type) == 32, + .r = cat1->src_r, + .c = cat1->src_c, + .im = cat1->src_im, + }; + print_src(ctx, &src); + } + + if ((debug & PRINT_VERBOSE) && (cat1->must_be_0)) + fprintf(ctx->out, "\t{1: %x}", cat1->must_be_0); +} + +static void print_instr_cat2(struct disasm_ctx *ctx, instr_t *instr) +{ + instr_cat2_t *cat2 = &instr->cat2; + int opc = _OPC(2, cat2->opc); + static const char *cond[] = { + "lt", + "le", + "gt", + "ge", + "eq", + "ne", + "?6?", + }; + + switch (opc) { + case OPC_CMPS_F: + case OPC_CMPS_U: + case OPC_CMPS_S: + case OPC_CMPV_F: + case OPC_CMPV_U: + case OPC_CMPV_S: + fprintf(ctx->out, ".%s", cond[cat2->cond]); + break; + } + + fprintf(ctx->out, " "); + if (cat2->ei) + fprintf(ctx->out, "(ei)"); + print_reg_dst(ctx, (reg_t)(cat2->dst), cat2->full ^ cat2->dst_half, false); + fprintf(ctx->out, ", "); + + struct reginfo src1 = { + .full = cat2->full, + .r = cat2->repeat ? cat2->src1_r : 0, + .f = is_cat2_float(opc), + .im = cat2->src1_im, + .abs = cat2->src1_abs, + .neg = cat2->src1_neg, + }; + + if (cat2->c1.src1_c) { + src1.reg = (reg_t)(cat2->c1.src1); + src1.c = true; + } else if (cat2->rel1.src1_rel) { + src1.reg = (reg_t)(cat2->rel1.src1); + src1.c = cat2->rel1.src1_c; + src1.addr_rel = true; + } else { + src1.reg = (reg_t)(cat2->src1); + } + print_src(ctx, &src1); + + struct reginfo src2 = { + .r = cat2->repeat ? cat2->src2_r : 0, + .full = cat2->full, + .f = is_cat2_float(opc), + .abs = cat2->src2_abs, + .neg = cat2->src2_neg, + .im = cat2->src2_im, + }; + switch (opc) { + case OPC_ABSNEG_F: + case OPC_ABSNEG_S: + case OPC_CLZ_B: + case OPC_CLZ_S: + case OPC_SIGN_F: + case OPC_FLOOR_F: + case OPC_CEIL_F: + case OPC_RNDNE_F: + case OPC_RNDAZ_F: + case OPC_TRUNC_F: + case OPC_NOT_B: + case OPC_BFREV_B: + case OPC_SETRM: + case OPC_CBITS_B: + /* these only have one src reg */ + break; + default: + fprintf(ctx->out, ", "); + if (cat2->c2.src2_c) { + src2.reg = (reg_t)(cat2->c2.src2); + src2.c = true; + } else if (cat2->rel2.src2_rel) { + src2.reg = (reg_t)(cat2->rel2.src2); + src2.c = cat2->rel2.src2_c; + src2.addr_rel = true; + } else { + src2.reg = (reg_t)(cat2->src2); + } + print_src(ctx, &src2); + break; + } +} + +static void print_instr_cat3(struct disasm_ctx *ctx, instr_t *instr) +{ + instr_cat3_t *cat3 = &instr->cat3; + bool full = instr_cat3_full(cat3); + + fprintf(ctx->out, " "); + print_reg_dst(ctx, (reg_t)(cat3->dst), full ^ cat3->dst_half, false); + fprintf(ctx->out, ", "); + + struct reginfo src1 = { + .r = cat3->repeat ? cat3->src1_r : 0, + .full = full, + .neg = cat3->src1_neg, + }; + if (cat3->c1.src1_c) { + src1.reg = (reg_t)(cat3->c1.src1); + src1.c = true; + } else if (cat3->rel1.src1_rel) { + src1.reg = (reg_t)(cat3->rel1.src1); + src1.c = cat3->rel1.src1_c; + src1.addr_rel = true; + } else { + src1.reg = (reg_t)(cat3->src1); + } + print_src(ctx, &src1); + + fprintf(ctx->out, ", "); + struct reginfo src2 = { + .reg = (reg_t)cat3->src2, + .full = full, + .r = cat3->repeat ? cat3->src2_r : 0, + .c = cat3->src2_c, + .neg = cat3->src2_neg, + }; + print_src(ctx, &src2); + + fprintf(ctx->out, ", "); + struct reginfo src3 = { + .r = cat3->src3_r, + .full = full, + .neg = cat3->src3_neg, + }; + if (cat3->c2.src3_c) { + src3.reg = (reg_t)(cat3->c2.src3); + src3.c = true; + } else if (cat3->rel2.src3_rel) { + src3.reg = (reg_t)(cat3->rel2.src3); + src3.c = cat3->rel2.src3_c; + src3.addr_rel = true; + } else { + src3.reg = (reg_t)(cat3->src3); + } + print_src(ctx, &src3); +} + +static void print_instr_cat4(struct disasm_ctx *ctx, instr_t *instr) +{ + instr_cat4_t *cat4 = &instr->cat4; + + fprintf(ctx->out, " "); + print_reg_dst(ctx, (reg_t)(cat4->dst), cat4->full ^ cat4->dst_half, false); + fprintf(ctx->out, ", "); + + struct reginfo src = { + .r = cat4->src_r, + .im = cat4->src_im, + .full = cat4->full, + .neg = cat4->src_neg, + .abs = cat4->src_abs, + }; + if (cat4->c.src_c) { + src.reg = (reg_t)(cat4->c.src); + src.c = true; + } else if (cat4->rel.src_rel) { + src.reg = (reg_t)(cat4->rel.src); + src.c = cat4->rel.src_c; + src.addr_rel = true; + } else { + src.reg = (reg_t)(cat4->src); + } + print_src(ctx, &src); + + if ((debug & PRINT_VERBOSE) && (cat4->dummy1|cat4->dummy2)) + fprintf(ctx->out, "\t{4: %x,%x}", cat4->dummy1, cat4->dummy2); +} + +static void print_instr_cat5(struct disasm_ctx *ctx, instr_t *instr) +{ + static const struct { + bool src1, src2, samp, tex; + } info[0x1f] = { + [opc_op(OPC_ISAM)] = { true, false, true, true, }, + [opc_op(OPC_ISAML)] = { true, true, true, true, }, + [opc_op(OPC_ISAMM)] = { true, false, true, true, }, + [opc_op(OPC_SAM)] = { true, false, true, true, }, + [opc_op(OPC_SAMB)] = { true, true, true, true, }, + [opc_op(OPC_SAML)] = { true, true, true, true, }, + [opc_op(OPC_SAMGQ)] = { true, false, true, true, }, + [opc_op(OPC_GETLOD)] = { true, false, true, true, }, + [opc_op(OPC_CONV)] = { true, true, true, true, }, + [opc_op(OPC_CONVM)] = { true, true, true, true, }, + [opc_op(OPC_GETSIZE)] = { true, false, false, true, }, + [opc_op(OPC_GETBUF)] = { false, false, false, true, }, + [opc_op(OPC_GETPOS)] = { true, false, false, true, }, + [opc_op(OPC_GETINFO)] = { false, false, false, true, }, + [opc_op(OPC_DSX)] = { true, false, false, false, }, + [opc_op(OPC_DSY)] = { true, false, false, false, }, + [opc_op(OPC_GATHER4R)] = { true, false, true, true, }, + [opc_op(OPC_GATHER4G)] = { true, false, true, true, }, + [opc_op(OPC_GATHER4B)] = { true, false, true, true, }, + [opc_op(OPC_GATHER4A)] = { true, false, true, true, }, + [opc_op(OPC_SAMGP0)] = { true, false, true, true, }, + [opc_op(OPC_SAMGP1)] = { true, false, true, true, }, + [opc_op(OPC_SAMGP2)] = { true, false, true, true, }, + [opc_op(OPC_SAMGP3)] = { true, false, true, true, }, + [opc_op(OPC_DSXPP_1)] = { true, false, false, false, }, + [opc_op(OPC_DSYPP_1)] = { true, false, false, false, }, + [opc_op(OPC_RGETPOS)] = { true, false, false, false, }, + [opc_op(OPC_RGETINFO)] = { false, false, false, false, }, + }; + + static const struct { + bool indirect; + bool bindless; + bool use_a1; + bool uniform; + } desc_features[8] = { + [CAT5_NONUNIFORM] = { .indirect = true, }, + [CAT5_UNIFORM] = { .indirect = true, .uniform = true, }, + [CAT5_BINDLESS_IMM] = { .bindless = true, }, + [CAT5_BINDLESS_UNIFORM] = { + .bindless = true, + .indirect = true, + .uniform = true, + }, + [CAT5_BINDLESS_NONUNIFORM] = { + .bindless = true, + .indirect = true, + }, + [CAT5_BINDLESS_A1_IMM] = { + .bindless = true, + .use_a1 = true, + }, + [CAT5_BINDLESS_A1_UNIFORM] = { + .bindless = true, + .indirect = true, + .uniform = true, + .use_a1 = true, + }, + [CAT5_BINDLESS_A1_NONUNIFORM] = { + .bindless = true, + .indirect = true, + .use_a1 = true, + }, + }; + + instr_cat5_t *cat5 = &instr->cat5; + int i; + + bool desc_indirect = + cat5->is_s2en_bindless && + desc_features[cat5->s2en_bindless.desc_mode].indirect; + bool bindless = + cat5->is_s2en_bindless && + desc_features[cat5->s2en_bindless.desc_mode].bindless; + bool use_a1 = + cat5->is_s2en_bindless && + desc_features[cat5->s2en_bindless.desc_mode].use_a1; + bool uniform = + cat5->is_s2en_bindless && + desc_features[cat5->s2en_bindless.desc_mode].uniform; + + if (cat5->is_3d) fprintf(ctx->out, ".3d"); + if (cat5->is_a) fprintf(ctx->out, ".a"); + if (cat5->is_o) fprintf(ctx->out, ".o"); + if (cat5->is_p) fprintf(ctx->out, ".p"); + if (cat5->is_s) fprintf(ctx->out, ".s"); + if (desc_indirect) fprintf(ctx->out, ".s2en"); + if (uniform) fprintf(ctx->out, ".uniform"); + + if (bindless) { + unsigned base = (cat5->s2en_bindless.base_hi << 1) | cat5->base_lo; + fprintf(ctx->out, ".base%d", base); + } + + fprintf(ctx->out, " "); + + switch (_OPC(5, cat5->opc)) { + case OPC_DSXPP_1: + case OPC_DSYPP_1: + break; + default: + fprintf(ctx->out, "(%s)", type[cat5->type]); + break; + } + + fprintf(ctx->out, "("); + for (i = 0; i < 4; i++) + if (cat5->wrmask & (1 << i)) + fprintf(ctx->out, "%c", "xyzw"[i]); + fprintf(ctx->out, ")"); + + print_reg_dst(ctx, (reg_t)(cat5->dst), type_size(cat5->type) == 32, false); + + if (info[cat5->opc].src1) { + fprintf(ctx->out, ", "); + struct reginfo src = { .reg = (reg_t)(cat5->src1), .full = cat5->full }; + print_src(ctx, &src); + } + + if (cat5->is_o || info[cat5->opc].src2) { + fprintf(ctx->out, ", "); + struct reginfo src = { .reg = (reg_t)(cat5->src2), .full = cat5->full }; + print_src(ctx, &src); + } + if (cat5->is_s2en_bindless) { + if (!desc_indirect) { + if (info[cat5->opc].samp) { + if (use_a1) + fprintf(ctx->out, ", s#%d", cat5->s2en_bindless.src3); + else + fprintf(ctx->out, ", s#%d", cat5->s2en_bindless.src3 & 0xf); + } + + if (info[cat5->opc].tex && !use_a1) { + fprintf(ctx->out, ", t#%d", cat5->s2en_bindless.src3 >> 4); + } + } + } else { + if (info[cat5->opc].samp) + fprintf(ctx->out, ", s#%d", cat5->norm.samp); + if (info[cat5->opc].tex) + fprintf(ctx->out, ", t#%d", cat5->norm.tex); + } + + if (desc_indirect) { + fprintf(ctx->out, ", "); + struct reginfo src = { .reg = (reg_t)(cat5->s2en_bindless.src3), .full = bindless }; + print_src(ctx, &src); + } + + if (use_a1) + fprintf(ctx->out, ", a1.x"); + + if (debug & PRINT_VERBOSE) { + if (cat5->is_s2en_bindless) { + if ((debug & PRINT_VERBOSE) && cat5->s2en_bindless.dummy1) + fprintf(ctx->out, "\t{5: %x}", cat5->s2en_bindless.dummy1); + } else { + if ((debug & PRINT_VERBOSE) && cat5->norm.dummy1) + fprintf(ctx->out, "\t{5: %x}", cat5->norm.dummy1); + } + } +} + +static void print_instr_cat6_a3xx(struct disasm_ctx *ctx, instr_t *instr) +{ + instr_cat6_t *cat6 = &instr->cat6; + char sd = 0, ss = 0; /* dst/src address space */ + bool nodst = false; + struct reginfo dst, src1, src2; + int src1off = 0, dstoff = 0; + + memset(&dst, 0, sizeof(dst)); + memset(&src1, 0, sizeof(src1)); + memset(&src2, 0, sizeof(src2)); + + switch (_OPC(6, cat6->opc)) { + case OPC_RESINFO: + case OPC_RESFMT: + dst.full = type_size(cat6->type) == 32; + src1.full = type_size(cat6->type) == 32; + src2.full = type_size(cat6->type) == 32; + break; + case OPC_L2G: + case OPC_G2L: + dst.full = true; + src1.full = true; + src2.full = true; + break; + case OPC_STG: + case OPC_STL: + case OPC_STP: + case OPC_STLW: + case OPC_STIB: + dst.full = type_size(cat6->type) == 32; + src1.full = type_size(cat6->type) == 32; + src2.full = type_size(cat6->type) == 32; + break; + default: + dst.full = type_size(cat6->type) == 32; + src1.full = true; + src2.full = true; + break; + } + + switch (_OPC(6, cat6->opc)) { + case OPC_PREFETCH: + break; + case OPC_RESINFO: + fprintf(ctx->out, ".%dd", cat6->ldgb.d + 1); + break; + case OPC_LDGB: + fprintf(ctx->out, ".%s", cat6->ldgb.typed ? "typed" : "untyped"); + fprintf(ctx->out, ".%dd", cat6->ldgb.d + 1); + fprintf(ctx->out, ".%s", type[cat6->type]); + fprintf(ctx->out, ".%d", cat6->ldgb.type_size + 1); + break; + case OPC_STGB: + case OPC_STIB: + fprintf(ctx->out, ".%s", cat6->stgb.typed ? "typed" : "untyped"); + fprintf(ctx->out, ".%dd", cat6->stgb.d + 1); + fprintf(ctx->out, ".%s", type[cat6->type]); + fprintf(ctx->out, ".%d", cat6->stgb.type_size + 1); + break; + case OPC_ATOMIC_ADD: + case OPC_ATOMIC_SUB: + case OPC_ATOMIC_XCHG: + case OPC_ATOMIC_INC: + case OPC_ATOMIC_DEC: + case OPC_ATOMIC_CMPXCHG: + case OPC_ATOMIC_MIN: + case OPC_ATOMIC_MAX: + case OPC_ATOMIC_AND: + case OPC_ATOMIC_OR: + case OPC_ATOMIC_XOR: + ss = cat6->g ? 'g' : 'l'; + fprintf(ctx->out, ".%s", cat6->ldgb.typed ? "typed" : "untyped"); + fprintf(ctx->out, ".%dd", cat6->ldgb.d + 1); + fprintf(ctx->out, ".%s", type[cat6->type]); + fprintf(ctx->out, ".%d", cat6->ldgb.type_size + 1); + fprintf(ctx->out, ".%c", ss); + break; + default: + dst.im = cat6->g && !cat6->dst_off; + fprintf(ctx->out, ".%s", type[cat6->type]); + break; + } + fprintf(ctx->out, " "); + + switch (_OPC(6, cat6->opc)) { + case OPC_STG: + sd = 'g'; + break; + case OPC_STP: + sd = 'p'; + break; + case OPC_STL: + case OPC_STLW: + sd = 'l'; + break; + + case OPC_LDG: + case OPC_LDC: + ss = 'g'; + break; + case OPC_LDP: + ss = 'p'; + break; + case OPC_LDL: + case OPC_LDLW: + case OPC_LDLV: + ss = 'l'; + break; + + case OPC_L2G: + ss = 'l'; + sd = 'g'; + break; + + case OPC_G2L: + ss = 'g'; + sd = 'l'; + break; + + case OPC_PREFETCH: + ss = 'g'; + nodst = true; + break; + } + + if ((_OPC(6, cat6->opc) == OPC_STGB) || (_OPC(6, cat6->opc) == OPC_STIB)) { + struct reginfo src3; + + memset(&src3, 0, sizeof(src3)); + + src1.reg = (reg_t)(cat6->stgb.src1); + src2.reg = (reg_t)(cat6->stgb.src2); + src2.im = cat6->stgb.src2_im; + src3.reg = (reg_t)(cat6->stgb.src3); + src3.im = cat6->stgb.src3_im; + src3.full = true; + + fprintf(ctx->out, "g[%u], ", cat6->stgb.dst_ssbo); + print_src(ctx, &src1); + fprintf(ctx->out, ", "); + print_src(ctx, &src2); + fprintf(ctx->out, ", "); + print_src(ctx, &src3); + + if (debug & PRINT_VERBOSE) + fprintf(ctx->out, " (pad0=%x, pad3=%x)", cat6->stgb.pad0, cat6->stgb.pad3); + + return; + } + + if (is_atomic(_OPC(6, cat6->opc))) { + + src1.reg = (reg_t)(cat6->ldgb.src1); + src1.im = cat6->ldgb.src1_im; + src2.reg = (reg_t)(cat6->ldgb.src2); + src2.im = cat6->ldgb.src2_im; + dst.reg = (reg_t)(cat6->ldgb.dst); + + print_src(ctx, &dst); + fprintf(ctx->out, ", "); + if (ss == 'g') { + struct reginfo src3; + memset(&src3, 0, sizeof(src3)); + + src3.reg = (reg_t)(cat6->ldgb.src3); + src3.full = true; + + /* For images, the ".typed" variant is used and src2 is + * the ivecN coordinates, ie ivec2 for 2d. + * + * For SSBOs, the ".untyped" variant is used and src2 is + * a simple dword offset.. src3 appears to be + * uvec2(offset * 4, 0). Not sure the point of that. + */ + + fprintf(ctx->out, "g[%u], ", cat6->ldgb.src_ssbo); + print_src(ctx, &src1); /* value */ + fprintf(ctx->out, ", "); + print_src(ctx, &src2); /* offset/coords */ + fprintf(ctx->out, ", "); + print_src(ctx, &src3); /* 64b byte offset.. */ + + if (debug & PRINT_VERBOSE) { + fprintf(ctx->out, " (pad0=%x, pad3=%x, mustbe0=%x)", cat6->ldgb.pad0, + cat6->ldgb.pad3, cat6->ldgb.mustbe0); + } + } else { /* ss == 'l' */ + fprintf(ctx->out, "l["); + print_src(ctx, &src1); /* simple byte offset */ + fprintf(ctx->out, "], "); + print_src(ctx, &src2); /* value */ + + if (debug & PRINT_VERBOSE) { + fprintf(ctx->out, " (src3=%x, pad0=%x, pad3=%x, mustbe0=%x)", + cat6->ldgb.src3, cat6->ldgb.pad0, + cat6->ldgb.pad3, cat6->ldgb.mustbe0); + } + } + + return; + } else if (_OPC(6, cat6->opc) == OPC_RESINFO) { + dst.reg = (reg_t)(cat6->ldgb.dst); + + print_src(ctx, &dst); + fprintf(ctx->out, ", "); + fprintf(ctx->out, "g[%u]", cat6->ldgb.src_ssbo); + + return; + } else if (_OPC(6, cat6->opc) == OPC_LDGB) { + + src1.reg = (reg_t)(cat6->ldgb.src1); + src1.im = cat6->ldgb.src1_im; + src2.reg = (reg_t)(cat6->ldgb.src2); + src2.im = cat6->ldgb.src2_im; + dst.reg = (reg_t)(cat6->ldgb.dst); + + print_src(ctx, &dst); + fprintf(ctx->out, ", "); + fprintf(ctx->out, "g[%u], ", cat6->ldgb.src_ssbo); + print_src(ctx, &src1); + fprintf(ctx->out, ", "); + print_src(ctx, &src2); + + if (debug & PRINT_VERBOSE) + fprintf(ctx->out, " (pad0=%x, pad3=%x, mustbe0=%x)", cat6->ldgb.pad0, cat6->ldgb.pad3, cat6->ldgb.mustbe0); + + return; + } else if (_OPC(6, cat6->opc) == OPC_LDG && cat6->a.src1_im && cat6->a.src2_im) { + struct reginfo src3; + + memset(&src3, 0, sizeof(src3)); + src1.reg = (reg_t)(cat6->a.src1); + src2.reg = (reg_t)(cat6->a.src2); + src2.im = cat6->a.src2_im; + src3.reg = (reg_t)(cat6->a.off); + src3.full = true; + dst.reg = (reg_t)(cat6->d.dst); + + print_src(ctx, &dst); + fprintf(ctx->out, ", g["); + print_src(ctx, &src1); + fprintf(ctx->out, "+"); + print_src(ctx, &src3); + fprintf(ctx->out, "], "); + print_src(ctx, &src2); + + return; + } + if (cat6->dst_off) { + dst.reg = (reg_t)(cat6->c.dst); + dstoff = cat6->c.off; + } else { + dst.reg = (reg_t)(cat6->d.dst); + } + + if (cat6->src_off) { + src1.reg = (reg_t)(cat6->a.src1); + src1.im = cat6->a.src1_im; + src2.reg = (reg_t)(cat6->a.src2); + src2.im = cat6->a.src2_im; + src1off = cat6->a.off; + } else { + src1.reg = (reg_t)(cat6->b.src1); + src1.im = cat6->b.src1_im; + src2.reg = (reg_t)(cat6->b.src2); + src2.im = cat6->b.src2_im; + } + + if (!nodst) { + if (sd) + fprintf(ctx->out, "%c[", sd); + /* note: dst might actually be a src (ie. address to store to) */ + print_src(ctx, &dst); + if (cat6->dst_off && cat6->g) { + struct reginfo dstoff_reg = {0}; + dstoff_reg.reg = (reg_t) cat6->c.off; + dstoff_reg.full = true; + fprintf(ctx->out, "+"); + print_src(ctx, &dstoff_reg); + } else if (dstoff) + fprintf(ctx->out, "%+d", dstoff); + if (sd) + fprintf(ctx->out, "]"); + fprintf(ctx->out, ", "); + } + + if (ss) + fprintf(ctx->out, "%c[", ss); + + /* can have a larger than normal immed, so hack: */ + if (src1.im) { + fprintf(ctx->out, "%u", src1.reg.dummy13); + } else { + print_src(ctx, &src1); + } + + if (cat6->src_off && cat6->g) + print_src(ctx, &src2); + else if (src1off) + fprintf(ctx->out, "%+d", src1off); + if (ss) + fprintf(ctx->out, "]"); + + switch (_OPC(6, cat6->opc)) { + case OPC_RESINFO: + case OPC_RESFMT: + break; + default: + fprintf(ctx->out, ", "); + print_src(ctx, &src2); + break; + } +} + +static void print_instr_cat6_a6xx(struct disasm_ctx *ctx, instr_t *instr) +{ + instr_cat6_a6xx_t *cat6 = &instr->cat6_a6xx; + struct reginfo src1, src2, ssbo; + bool uses_type = _OPC(6, cat6->opc) != OPC_LDC; + + static const struct { + bool indirect; + bool bindless; + const char *name; + } desc_features[8] = { + [CAT6_IMM] = { + .name = "imm" + }, + [CAT6_UNIFORM] = { + .indirect = true, + .name = "uniform" + }, + [CAT6_NONUNIFORM] = { + .indirect = true, + .name = "nonuniform" + }, + [CAT6_BINDLESS_IMM] = { + .bindless = true, + .name = "imm" + }, + [CAT6_BINDLESS_UNIFORM] = { + .bindless = true, + .indirect = true, + .name = "uniform" + }, + [CAT6_BINDLESS_NONUNIFORM] = { + .bindless = true, + .indirect = true, + .name = "nonuniform" + }, + }; + + bool indirect_ssbo = desc_features[cat6->desc_mode].indirect; + bool bindless = desc_features[cat6->desc_mode].bindless; + bool type_full = cat6->type != TYPE_U16; + + + memset(&src1, 0, sizeof(src1)); + memset(&src2, 0, sizeof(src2)); + memset(&ssbo, 0, sizeof(ssbo)); + + if (uses_type) { + fprintf(ctx->out, ".%s", cat6->typed ? "typed" : "untyped"); + fprintf(ctx->out, ".%dd", cat6->d + 1); + fprintf(ctx->out, ".%s", type[cat6->type]); + } else { + fprintf(ctx->out, ".offset%d", cat6->d); + } + fprintf(ctx->out, ".%u", cat6->type_size + 1); + + fprintf(ctx->out, ".%s", desc_features[cat6->desc_mode].name); + if (bindless) + fprintf(ctx->out, ".base%d", cat6->base); + fprintf(ctx->out, " "); + + src2.reg = (reg_t)(cat6->src2); + src2.full = type_full; + print_src(ctx, &src2); + fprintf(ctx->out, ", "); + + src1.reg = (reg_t)(cat6->src1); + src1.full = true; // XXX + print_src(ctx, &src1); + fprintf(ctx->out, ", "); + ssbo.reg = (reg_t)(cat6->ssbo); + ssbo.im = !indirect_ssbo; + ssbo.full = true; + print_src(ctx, &ssbo); + + if (debug & PRINT_VERBOSE) { + fprintf(ctx->out, " (pad1=%x, pad2=%x, pad3=%x, pad4=%x, pad5=%x)", + cat6->pad1, cat6->pad2, cat6->pad3, cat6->pad4, cat6->pad5); + } +} + +static void print_instr_cat6(struct disasm_ctx *ctx, instr_t *instr) +{ + if (!is_cat6_legacy(instr, ctx->gpu_id)) { + print_instr_cat6_a6xx(ctx, instr); + if (debug & PRINT_VERBOSE) + fprintf(ctx->out, " NEW"); + } else { + print_instr_cat6_a3xx(ctx, instr); + if (debug & PRINT_VERBOSE) + fprintf(ctx->out, " LEGACY"); + } +} +static void print_instr_cat7(struct disasm_ctx *ctx, instr_t *instr) +{ + instr_cat7_t *cat7 = &instr->cat7; + + if (cat7->g) + fprintf(ctx->out, ".g"); + if (cat7->l) + fprintf(ctx->out, ".l"); + + if (_OPC(7, cat7->opc) == OPC_FENCE) { + if (cat7->r) + fprintf(ctx->out, ".r"); + if (cat7->w) + fprintf(ctx->out, ".w"); + } +} + +/* size of largest OPC field of all the instruction categories: */ +#define NOPC_BITS 6 + +static const struct opc_info { + uint16_t cat; + uint16_t opc; + const char *name; + void (*print)(struct disasm_ctx *ctx, instr_t *instr); +} opcs[1 << (3+NOPC_BITS)] = { +#define OPC(cat, opc, name) [(opc)] = { (cat), (opc), #name, print_instr_cat##cat } + /* category 0: */ + OPC(0, OPC_NOP, nop), + OPC(0, OPC_B, b), + OPC(0, OPC_JUMP, jump), + OPC(0, OPC_CALL, call), + OPC(0, OPC_RET, ret), + OPC(0, OPC_KILL, kill), + OPC(0, OPC_END, end), + OPC(0, OPC_EMIT, emit), + OPC(0, OPC_CUT, cut), + OPC(0, OPC_CHMASK, chmask), + OPC(0, OPC_CHSH, chsh), + OPC(0, OPC_FLOW_REV, flow_rev), + OPC(0, OPC_PREDT, predt), + OPC(0, OPC_PREDF, predf), + OPC(0, OPC_PREDE, prede), + OPC(0, OPC_BKT, bkt), + OPC(0, OPC_STKS, stks), + OPC(0, OPC_STKR, stkr), + OPC(0, OPC_XSET, xset), + OPC(0, OPC_XCLR, xclr), + OPC(0, OPC_GETONE, getone), + OPC(0, OPC_DBG, dbg), + OPC(0, OPC_SHPS, shps), + OPC(0, OPC_SHPE, shpe), + + /* category 1: */ + OPC(1, OPC_MOV, ), + + /* category 2: */ + OPC(2, OPC_ADD_F, add.f), + OPC(2, OPC_MIN_F, min.f), + OPC(2, OPC_MAX_F, max.f), + OPC(2, OPC_MUL_F, mul.f), + OPC(2, OPC_SIGN_F, sign.f), + OPC(2, OPC_CMPS_F, cmps.f), + OPC(2, OPC_ABSNEG_F, absneg.f), + OPC(2, OPC_CMPV_F, cmpv.f), + OPC(2, OPC_FLOOR_F, floor.f), + OPC(2, OPC_CEIL_F, ceil.f), + OPC(2, OPC_RNDNE_F, rndne.f), + OPC(2, OPC_RNDAZ_F, rndaz.f), + OPC(2, OPC_TRUNC_F, trunc.f), + OPC(2, OPC_ADD_U, add.u), + OPC(2, OPC_ADD_S, add.s), + OPC(2, OPC_SUB_U, sub.u), + OPC(2, OPC_SUB_S, sub.s), + OPC(2, OPC_CMPS_U, cmps.u), + OPC(2, OPC_CMPS_S, cmps.s), + OPC(2, OPC_MIN_U, min.u), + OPC(2, OPC_MIN_S, min.s), + OPC(2, OPC_MAX_U, max.u), + OPC(2, OPC_MAX_S, max.s), + OPC(2, OPC_ABSNEG_S, absneg.s), + OPC(2, OPC_AND_B, and.b), + OPC(2, OPC_OR_B, or.b), + OPC(2, OPC_NOT_B, not.b), + OPC(2, OPC_XOR_B, xor.b), + OPC(2, OPC_CMPV_U, cmpv.u), + OPC(2, OPC_CMPV_S, cmpv.s), + OPC(2, OPC_MUL_U24, mul.u24), + OPC(2, OPC_MUL_S24, mul.s24), + OPC(2, OPC_MULL_U, mull.u), + OPC(2, OPC_BFREV_B, bfrev.b), + OPC(2, OPC_CLZ_S, clz.s), + OPC(2, OPC_CLZ_B, clz.b), + OPC(2, OPC_SHL_B, shl.b), + OPC(2, OPC_SHR_B, shr.b), + OPC(2, OPC_ASHR_B, ashr.b), + OPC(2, OPC_BARY_F, bary.f), + OPC(2, OPC_MGEN_B, mgen.b), + OPC(2, OPC_GETBIT_B, getbit.b), + OPC(2, OPC_SETRM, setrm), + OPC(2, OPC_CBITS_B, cbits.b), + OPC(2, OPC_SHB, shb), + OPC(2, OPC_MSAD, msad), + + /* category 3: */ + OPC(3, OPC_MAD_U16, mad.u16), + OPC(3, OPC_MADSH_U16, madsh.u16), + OPC(3, OPC_MAD_S16, mad.s16), + OPC(3, OPC_MADSH_M16, madsh.m16), + OPC(3, OPC_MAD_U24, mad.u24), + OPC(3, OPC_MAD_S24, mad.s24), + OPC(3, OPC_MAD_F16, mad.f16), + OPC(3, OPC_MAD_F32, mad.f32), + OPC(3, OPC_SEL_B16, sel.b16), + OPC(3, OPC_SEL_B32, sel.b32), + OPC(3, OPC_SEL_S16, sel.s16), + OPC(3, OPC_SEL_S32, sel.s32), + OPC(3, OPC_SEL_F16, sel.f16), + OPC(3, OPC_SEL_F32, sel.f32), + OPC(3, OPC_SAD_S16, sad.s16), + OPC(3, OPC_SAD_S32, sad.s32), + + /* category 4: */ + OPC(4, OPC_RCP, rcp), + OPC(4, OPC_RSQ, rsq), + OPC(4, OPC_LOG2, log2), + OPC(4, OPC_EXP2, exp2), + OPC(4, OPC_SIN, sin), + OPC(4, OPC_COS, cos), + OPC(4, OPC_SQRT, sqrt), + OPC(4, OPC_HRSQ, hrsq), + OPC(4, OPC_HLOG2, hlog2), + OPC(4, OPC_HEXP2, hexp2), + + /* category 5: */ + OPC(5, OPC_ISAM, isam), + OPC(5, OPC_ISAML, isaml), + OPC(5, OPC_ISAMM, isamm), + OPC(5, OPC_SAM, sam), + OPC(5, OPC_SAMB, samb), + OPC(5, OPC_SAML, saml), + OPC(5, OPC_SAMGQ, samgq), + OPC(5, OPC_GETLOD, getlod), + OPC(5, OPC_CONV, conv), + OPC(5, OPC_CONVM, convm), + OPC(5, OPC_GETSIZE, getsize), + OPC(5, OPC_GETBUF, getbuf), + OPC(5, OPC_GETPOS, getpos), + OPC(5, OPC_GETINFO, getinfo), + OPC(5, OPC_DSX, dsx), + OPC(5, OPC_DSY, dsy), + OPC(5, OPC_GATHER4R, gather4r), + OPC(5, OPC_GATHER4G, gather4g), + OPC(5, OPC_GATHER4B, gather4b), + OPC(5, OPC_GATHER4A, gather4a), + OPC(5, OPC_SAMGP0, samgp0), + OPC(5, OPC_SAMGP1, samgp1), + OPC(5, OPC_SAMGP2, samgp2), + OPC(5, OPC_SAMGP3, samgp3), + OPC(5, OPC_DSXPP_1, dsxpp.1), + OPC(5, OPC_DSYPP_1, dsypp.1), + OPC(5, OPC_RGETPOS, rgetpos), + OPC(5, OPC_RGETINFO, rgetinfo), + + + /* category 6: */ + OPC(6, OPC_LDG, ldg), + OPC(6, OPC_LDL, ldl), + OPC(6, OPC_LDP, ldp), + OPC(6, OPC_STG, stg), + OPC(6, OPC_STL, stl), + OPC(6, OPC_STP, stp), + OPC(6, OPC_LDIB, ldib), + OPC(6, OPC_G2L, g2l), + OPC(6, OPC_L2G, l2g), + OPC(6, OPC_PREFETCH, prefetch), + OPC(6, OPC_LDLW, ldlw), + OPC(6, OPC_STLW, stlw), + OPC(6, OPC_RESFMT, resfmt), + OPC(6, OPC_RESINFO, resinfo), + OPC(6, OPC_ATOMIC_ADD, atomic.add), + OPC(6, OPC_ATOMIC_SUB, atomic.sub), + OPC(6, OPC_ATOMIC_XCHG, atomic.xchg), + OPC(6, OPC_ATOMIC_INC, atomic.inc), + OPC(6, OPC_ATOMIC_DEC, atomic.dec), + OPC(6, OPC_ATOMIC_CMPXCHG, atomic.cmpxchg), + OPC(6, OPC_ATOMIC_MIN, atomic.min), + OPC(6, OPC_ATOMIC_MAX, atomic.max), + OPC(6, OPC_ATOMIC_AND, atomic.and), + OPC(6, OPC_ATOMIC_OR, atomic.or), + OPC(6, OPC_ATOMIC_XOR, atomic.xor), + OPC(6, OPC_LDGB, ldgb), + OPC(6, OPC_STGB, stgb), + OPC(6, OPC_STIB, stib), + OPC(6, OPC_LDC, ldc), + OPC(6, OPC_LDLV, ldlv), + + OPC(7, OPC_BAR, bar), + OPC(7, OPC_FENCE, fence), + +#undef OPC +}; + +#define GETINFO(instr) (&(opcs[((instr)->opc_cat << NOPC_BITS) | instr_opc(instr, ctx->gpu_id)])) + +// XXX hack.. probably should move this table somewhere common: +#include "ir3.h" +const char *ir3_instr_name(struct ir3_instruction *instr) +{ + if (opc_cat(instr->opc) == -1) return "??meta??"; + return opcs[instr->opc].name; +} + +static void print_single_instr(struct disasm_ctx *ctx, instr_t *instr) +{ + const char *name = GETINFO(instr)->name; + uint32_t opc = instr_opc(instr, ctx->gpu_id); + + if (name) { + fprintf(ctx->out, "%s", name); + GETINFO(instr)->print(ctx, instr); + } else { + fprintf(ctx->out, "unknown(%d,%d)", instr->opc_cat, opc); + + switch (instr->opc_cat) { + case 0: print_instr_cat0(ctx, instr); break; + case 1: print_instr_cat1(ctx, instr); break; + case 2: print_instr_cat2(ctx, instr); break; + case 3: print_instr_cat3(ctx, instr); break; + case 4: print_instr_cat4(ctx, instr); break; + case 5: print_instr_cat5(ctx, instr); break; + case 6: print_instr_cat6(ctx, instr); break; + case 7: print_instr_cat7(ctx, instr); break; + } + } +} + +static bool print_instr(struct disasm_ctx *ctx, uint32_t *dwords, int n) +{ + instr_t *instr = (instr_t *)dwords; + uint32_t opc = instr_opc(instr, ctx->gpu_id); + unsigned nop = 0; + unsigned cycles = ctx->instructions; + + if (debug & PRINT_VERBOSE) { + fprintf(ctx->out, "%s%04d:%04d[%08xx_%08xx] ", levels[ctx->level], + n, cycles++, dwords[1], dwords[0]); + } + + /* NOTE: order flags are printed is a bit fugly.. but for now I + * try to match the order in llvm-a3xx disassembler for easy + * diff'ing.. + */ + + ctx->repeat = instr_repeat(instr); + ctx->instructions += 1 + ctx->repeat; + + if (instr->sync) { + fprintf(ctx->out, "(sy)"); + } + if (instr->ss && ((instr->opc_cat <= 4) || (instr->opc_cat == 7))) { + fprintf(ctx->out, "(ss)"); + } + if (instr->jmp_tgt) + fprintf(ctx->out, "(jp)"); + if ((instr->opc_cat == 0) && instr->cat0.eq) + fprintf(ctx->out, "(eq)"); + if (instr_sat(instr)) + fprintf(ctx->out, "(sat)"); + if (ctx->repeat) + fprintf(ctx->out, "(rpt%d)", ctx->repeat); + else if ((instr->opc_cat == 2) && (instr->cat2.src1_r || instr->cat2.src2_r)) + nop = (instr->cat2.src2_r * 2) + instr->cat2.src1_r; + else if ((instr->opc_cat == 3) && (instr->cat3.src1_r || instr->cat3.src2_r)) + nop = (instr->cat3.src2_r * 2) + instr->cat3.src1_r; + ctx->instructions += nop; + if (nop) + fprintf(ctx->out, "(nop%d) ", nop); + + if (instr->ul && ((2 <= instr->opc_cat) && (instr->opc_cat <= 4))) + fprintf(ctx->out, "(ul)"); + + print_single_instr(ctx, instr); + fprintf(ctx->out, "\n"); + + if ((instr->opc_cat <= 4) && (debug & EXPAND_REPEAT)) { + int i; + for (i = 0; i < nop; i++) { + if (debug & PRINT_VERBOSE) { + fprintf(ctx->out, "%s%04d:%04d[ ] ", + levels[ctx->level], n, cycles++); + } + fprintf(ctx->out, "nop\n"); + } + for (i = 0; i < ctx->repeat; i++) { + ctx->repeatidx = i + 1; + if (debug & PRINT_VERBOSE) { + fprintf(ctx->out, "%s%04d:%04d[ ] ", + levels[ctx->level], n, cycles++); + } + print_single_instr(ctx, instr); + fprintf(ctx->out, "\n"); + } + ctx->repeatidx = 0; + } + + return (instr->opc_cat == 0) && (opc == OPC_END); +} + +int disasm_a3xx(uint32_t *dwords, int sizedwords, int level, FILE *out, unsigned gpu_id) +{ + struct disasm_ctx ctx; + int i; + int nop_count = 0; + + //assert((sizedwords % 2) == 0); + + memset(&ctx, 0, sizeof(ctx)); + ctx.out = out; + ctx.level = level; + ctx.gpu_id = gpu_id; + + for (i = 0; i < sizedwords; i += 2) { + print_instr(&ctx, &dwords[i], i/2); + if (dwords[i] == 0 && dwords[i + 1] == 0) + nop_count++; + else + nop_count = 0; + if (nop_count > 3) + break; + } + + return 0; +} + +int main(int argc, char *argv[]) { + uint32_t buf[0x10000]; + FILE *f = fopen(argv[1], "rb"); + if (argc > 2) { + int seek = atoi(argv[2]); + printf("skip %d\n", seek); + fread(buf, 1, seek , f); + } + int len = fread(buf, 1, sizeof(buf), f); + fclose(f); + + disasm_a3xx(buf, len/4, 0, stdout, 0); +} + diff --git a/selfdrive/modeld/thneed/debug/decompiler/instr-a3xx.h b/selfdrive/modeld/thneed/debug/decompiler/instr-a3xx.h new file mode 100644 index 0000000000..e4f548d639 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/decompiler/instr-a3xx.h @@ -0,0 +1,1119 @@ +/* + * Copyright (c) 2013 Rob Clark + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice (including the next + * paragraph) shall be included in all copies or substantial portions of the + * Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +#ifndef INSTR_A3XX_H_ +#define INSTR_A3XX_H_ + +#define PACKED __attribute__((__packed__)) + +#include +#include +#include +#include + +/* size of largest OPC field of all the instruction categories: */ +#define NOPC_BITS 6 + +#define _OPC(cat, opc) (((cat) << NOPC_BITS) | opc) + +typedef enum { + /* category 0: */ + OPC_NOP = _OPC(0, 0), + OPC_B = _OPC(0, 1), + OPC_JUMP = _OPC(0, 2), + OPC_CALL = _OPC(0, 3), + OPC_RET = _OPC(0, 4), + OPC_KILL = _OPC(0, 5), + OPC_END = _OPC(0, 6), + OPC_EMIT = _OPC(0, 7), + OPC_CUT = _OPC(0, 8), + OPC_CHMASK = _OPC(0, 9), + OPC_CHSH = _OPC(0, 10), + OPC_FLOW_REV = _OPC(0, 11), + + OPC_BKT = _OPC(0, 16), + OPC_STKS = _OPC(0, 17), + OPC_STKR = _OPC(0, 18), + OPC_XSET = _OPC(0, 19), + OPC_XCLR = _OPC(0, 20), + OPC_GETONE = _OPC(0, 21), + OPC_DBG = _OPC(0, 22), + OPC_SHPS = _OPC(0, 23), /* shader prologue start */ + OPC_SHPE = _OPC(0, 24), /* shader prologue end */ + + OPC_PREDT = _OPC(0, 29), /* predicated true */ + OPC_PREDF = _OPC(0, 30), /* predicated false */ + OPC_PREDE = _OPC(0, 31), /* predicated end */ + + /* category 1: */ + OPC_MOV = _OPC(1, 0), + + /* category 2: */ + OPC_ADD_F = _OPC(2, 0), + OPC_MIN_F = _OPC(2, 1), + OPC_MAX_F = _OPC(2, 2), + OPC_MUL_F = _OPC(2, 3), + OPC_SIGN_F = _OPC(2, 4), + OPC_CMPS_F = _OPC(2, 5), + OPC_ABSNEG_F = _OPC(2, 6), + OPC_CMPV_F = _OPC(2, 7), + /* 8 - invalid */ + OPC_FLOOR_F = _OPC(2, 9), + OPC_CEIL_F = _OPC(2, 10), + OPC_RNDNE_F = _OPC(2, 11), + OPC_RNDAZ_F = _OPC(2, 12), + OPC_TRUNC_F = _OPC(2, 13), + /* 14-15 - invalid */ + OPC_ADD_U = _OPC(2, 16), + OPC_ADD_S = _OPC(2, 17), + OPC_SUB_U = _OPC(2, 18), + OPC_SUB_S = _OPC(2, 19), + OPC_CMPS_U = _OPC(2, 20), + OPC_CMPS_S = _OPC(2, 21), + OPC_MIN_U = _OPC(2, 22), + OPC_MIN_S = _OPC(2, 23), + OPC_MAX_U = _OPC(2, 24), + OPC_MAX_S = _OPC(2, 25), + OPC_ABSNEG_S = _OPC(2, 26), + /* 27 - invalid */ + OPC_AND_B = _OPC(2, 28), + OPC_OR_B = _OPC(2, 29), + OPC_NOT_B = _OPC(2, 30), + OPC_XOR_B = _OPC(2, 31), + /* 32 - invalid */ + OPC_CMPV_U = _OPC(2, 33), + OPC_CMPV_S = _OPC(2, 34), + /* 35-47 - invalid */ + OPC_MUL_U24 = _OPC(2, 48), /* 24b mul into 32b result */ + OPC_MUL_S24 = _OPC(2, 49), /* 24b mul into 32b result with sign extension */ + OPC_MULL_U = _OPC(2, 50), + OPC_BFREV_B = _OPC(2, 51), + OPC_CLZ_S = _OPC(2, 52), + OPC_CLZ_B = _OPC(2, 53), + OPC_SHL_B = _OPC(2, 54), + OPC_SHR_B = _OPC(2, 55), + OPC_ASHR_B = _OPC(2, 56), + OPC_BARY_F = _OPC(2, 57), + OPC_MGEN_B = _OPC(2, 58), + OPC_GETBIT_B = _OPC(2, 59), + OPC_SETRM = _OPC(2, 60), + OPC_CBITS_B = _OPC(2, 61), + OPC_SHB = _OPC(2, 62), + OPC_MSAD = _OPC(2, 63), + + /* category 3: */ + OPC_MAD_U16 = _OPC(3, 0), + OPC_MADSH_U16 = _OPC(3, 1), + OPC_MAD_S16 = _OPC(3, 2), + OPC_MADSH_M16 = _OPC(3, 3), /* should this be .s16? */ + OPC_MAD_U24 = _OPC(3, 4), + OPC_MAD_S24 = _OPC(3, 5), + OPC_MAD_F16 = _OPC(3, 6), + OPC_MAD_F32 = _OPC(3, 7), + OPC_SEL_B16 = _OPC(3, 8), + OPC_SEL_B32 = _OPC(3, 9), + OPC_SEL_S16 = _OPC(3, 10), + OPC_SEL_S32 = _OPC(3, 11), + OPC_SEL_F16 = _OPC(3, 12), + OPC_SEL_F32 = _OPC(3, 13), + OPC_SAD_S16 = _OPC(3, 14), + OPC_SAD_S32 = _OPC(3, 15), + + /* category 4: */ + OPC_RCP = _OPC(4, 0), + OPC_RSQ = _OPC(4, 1), + OPC_LOG2 = _OPC(4, 2), + OPC_EXP2 = _OPC(4, 3), + OPC_SIN = _OPC(4, 4), + OPC_COS = _OPC(4, 5), + OPC_SQRT = _OPC(4, 6), + /* NOTE that these are 8+opc from their highp equivs, so it's possible + * that the high order bit in the opc field has been repurposed for + * half-precision use? But note that other ops (rcp/lsin/cos/sqrt) + * still use the same opc as highp + */ + OPC_HRSQ = _OPC(4, 9), + OPC_HLOG2 = _OPC(4, 10), + OPC_HEXP2 = _OPC(4, 11), + + /* category 5: */ + OPC_ISAM = _OPC(5, 0), + OPC_ISAML = _OPC(5, 1), + OPC_ISAMM = _OPC(5, 2), + OPC_SAM = _OPC(5, 3), + OPC_SAMB = _OPC(5, 4), + OPC_SAML = _OPC(5, 5), + OPC_SAMGQ = _OPC(5, 6), + OPC_GETLOD = _OPC(5, 7), + OPC_CONV = _OPC(5, 8), + OPC_CONVM = _OPC(5, 9), + OPC_GETSIZE = _OPC(5, 10), + OPC_GETBUF = _OPC(5, 11), + OPC_GETPOS = _OPC(5, 12), + OPC_GETINFO = _OPC(5, 13), + OPC_DSX = _OPC(5, 14), + OPC_DSY = _OPC(5, 15), + OPC_GATHER4R = _OPC(5, 16), + OPC_GATHER4G = _OPC(5, 17), + OPC_GATHER4B = _OPC(5, 18), + OPC_GATHER4A = _OPC(5, 19), + OPC_SAMGP0 = _OPC(5, 20), + OPC_SAMGP1 = _OPC(5, 21), + OPC_SAMGP2 = _OPC(5, 22), + OPC_SAMGP3 = _OPC(5, 23), + OPC_DSXPP_1 = _OPC(5, 24), + OPC_DSYPP_1 = _OPC(5, 25), + OPC_RGETPOS = _OPC(5, 26), + OPC_RGETINFO = _OPC(5, 27), + + /* category 6: */ + OPC_LDG = _OPC(6, 0), /* load-global */ + OPC_LDL = _OPC(6, 1), + OPC_LDP = _OPC(6, 2), + OPC_STG = _OPC(6, 3), /* store-global */ + OPC_STL = _OPC(6, 4), + OPC_STP = _OPC(6, 5), + OPC_LDIB = _OPC(6, 6), + OPC_G2L = _OPC(6, 7), + OPC_L2G = _OPC(6, 8), + OPC_PREFETCH = _OPC(6, 9), + OPC_LDLW = _OPC(6, 10), + OPC_STLW = _OPC(6, 11), + OPC_RESFMT = _OPC(6, 14), + OPC_RESINFO = _OPC(6, 15), + OPC_ATOMIC_ADD = _OPC(6, 16), + OPC_ATOMIC_SUB = _OPC(6, 17), + OPC_ATOMIC_XCHG = _OPC(6, 18), + OPC_ATOMIC_INC = _OPC(6, 19), + OPC_ATOMIC_DEC = _OPC(6, 20), + OPC_ATOMIC_CMPXCHG = _OPC(6, 21), + OPC_ATOMIC_MIN = _OPC(6, 22), + OPC_ATOMIC_MAX = _OPC(6, 23), + OPC_ATOMIC_AND = _OPC(6, 24), + OPC_ATOMIC_OR = _OPC(6, 25), + OPC_ATOMIC_XOR = _OPC(6, 26), + OPC_LDGB = _OPC(6, 27), + OPC_STGB = _OPC(6, 28), + OPC_STIB = _OPC(6, 29), + OPC_LDC = _OPC(6, 30), + OPC_LDLV = _OPC(6, 31), + + /* category 7: */ + OPC_BAR = _OPC(7, 0), + OPC_FENCE = _OPC(7, 1), + + /* meta instructions (category -1): */ + /* placeholder instr to mark shader inputs: */ + OPC_META_INPUT = _OPC(-1, 0), + /* The "collect" and "split" instructions are used for keeping + * track of instructions that write to multiple dst registers + * (split) like texture sample instructions, or read multiple + * consecutive scalar registers (collect) (bary.f, texture samp) + * + * A "split" extracts a scalar component from a vecN, and a + * "collect" gathers multiple scalar components into a vecN + */ + OPC_META_SPLIT = _OPC(-1, 2), + OPC_META_COLLECT = _OPC(-1, 3), + + /* placeholder for texture fetches that run before FS invocation + * starts: + */ + OPC_META_TEX_PREFETCH = _OPC(-1, 4), + +} opc_t; + +#define opc_cat(opc) ((int)((opc) >> NOPC_BITS)) +#define opc_op(opc) ((unsigned)((opc) & ((1 << NOPC_BITS) - 1))) + +typedef enum { + TYPE_F16 = 0, + TYPE_F32 = 1, + TYPE_U16 = 2, + TYPE_U32 = 3, + TYPE_S16 = 4, + TYPE_S32 = 5, + TYPE_U8 = 6, + TYPE_S8 = 7, // XXX I assume? +} type_t; + +static inline uint32_t type_size(type_t type) +{ + switch (type) { + case TYPE_F32: + case TYPE_U32: + case TYPE_S32: + return 32; + case TYPE_F16: + case TYPE_U16: + case TYPE_S16: + return 16; + case TYPE_U8: + case TYPE_S8: + return 8; + default: + assert(0); /* invalid type */ + return 0; + } +} + +static inline int type_float(type_t type) +{ + return (type == TYPE_F32) || (type == TYPE_F16); +} + +static inline int type_uint(type_t type) +{ + return (type == TYPE_U32) || (type == TYPE_U16) || (type == TYPE_U8); +} + +static inline int type_sint(type_t type) +{ + return (type == TYPE_S32) || (type == TYPE_S16) || (type == TYPE_S8); +} + +typedef union PACKED { + /* normal gpr or const src register: */ + struct PACKED { + uint32_t comp : 2; + uint32_t num : 10; + }; + /* for immediate val: */ + int32_t iim_val : 11; + /* to make compiler happy: */ + uint32_t dummy32; + uint32_t dummy10 : 10; + int32_t idummy10 : 10; + uint32_t dummy11 : 11; + uint32_t dummy12 : 12; + uint32_t dummy13 : 13; + uint32_t dummy8 : 8; + int32_t idummy13 : 13; + int32_t idummy8 : 8; +} reg_t; + +/* special registers: */ +#define REG_A0 61 /* address register */ +#define REG_P0 62 /* predicate register */ + +static inline int reg_special(reg_t reg) +{ + return (reg.num == REG_A0) || (reg.num == REG_P0); +} + +typedef enum { + BRANCH_PLAIN = 0, /* br */ + BRANCH_OR = 1, /* brao */ + BRANCH_AND = 2, /* braa */ + BRANCH_CONST = 3, /* brac */ + BRANCH_ANY = 4, /* bany */ + BRANCH_ALL = 5, /* ball */ + BRANCH_X = 6, /* brax ??? */ +} brtype_t; + +typedef struct PACKED { + /* dword0: */ + union PACKED { + struct PACKED { + int16_t immed : 16; + uint32_t dummy1 : 16; + } a3xx; + struct PACKED { + int32_t immed : 20; + uint32_t dummy1 : 12; + } a4xx; + struct PACKED { + int32_t immed : 32; + } a5xx; + }; + + /* dword1: */ + uint32_t idx : 5; /* brac.N index */ + uint32_t brtype : 3; /* branch type, see brtype_t */ + uint32_t repeat : 3; + uint32_t dummy3 : 1; + uint32_t ss : 1; + uint32_t inv1 : 1; + uint32_t comp1 : 2; + uint32_t eq : 1; + uint32_t opc_hi : 1; /* at least one bit */ + uint32_t dummy4 : 2; + uint32_t inv0 : 1; + uint32_t comp0 : 2; /* component for first src */ + uint32_t opc : 4; + uint32_t jmp_tgt : 1; + uint32_t sync : 1; + uint32_t opc_cat : 3; +} instr_cat0_t; + +typedef struct PACKED { + /* dword0: */ + union PACKED { + /* for normal src register: */ + struct PACKED { + uint32_t src : 11; + /* at least low bit of pad must be zero or it will + * look like a address relative src + */ + uint32_t pad : 21; + }; + /* for address relative: */ + struct PACKED { + int32_t off : 10; + uint32_t src_rel_c : 1; + uint32_t src_rel : 1; + uint32_t unknown : 20; + }; + /* for immediate: */ + int32_t iim_val; + uint32_t uim_val; + float fim_val; + }; + + /* dword1: */ + uint32_t dst : 8; + uint32_t repeat : 3; + uint32_t src_r : 1; + uint32_t ss : 1; + uint32_t ul : 1; + uint32_t dst_type : 3; + uint32_t dst_rel : 1; + uint32_t src_type : 3; + uint32_t src_c : 1; + uint32_t src_im : 1; + uint32_t even : 1; + uint32_t pos_inf : 1; + uint32_t must_be_0 : 2; + uint32_t jmp_tgt : 1; + uint32_t sync : 1; + uint32_t opc_cat : 3; +} instr_cat1_t; + +typedef struct PACKED { + /* dword0: */ + union PACKED { + struct PACKED { + uint32_t src1 : 11; + uint32_t must_be_zero1: 2; + uint32_t src1_im : 1; /* immediate */ + uint32_t src1_neg : 1; /* negate */ + uint32_t src1_abs : 1; /* absolute value */ + }; + struct PACKED { + uint32_t src1 : 10; + uint32_t src1_c : 1; /* relative-const */ + uint32_t src1_rel : 1; /* relative address */ + uint32_t must_be_zero : 1; + uint32_t dummy : 3; + } rel1; + struct PACKED { + uint32_t src1 : 12; + uint32_t src1_c : 1; /* const */ + uint32_t dummy : 3; + } c1; + }; + + union PACKED { + struct PACKED { + uint32_t src2 : 11; + uint32_t must_be_zero2: 2; + uint32_t src2_im : 1; /* immediate */ + uint32_t src2_neg : 1; /* negate */ + uint32_t src2_abs : 1; /* absolute value */ + }; + struct PACKED { + uint32_t src2 : 10; + uint32_t src2_c : 1; /* relative-const */ + uint32_t src2_rel : 1; /* relative address */ + uint32_t must_be_zero : 1; + uint32_t dummy : 3; + } rel2; + struct PACKED { + uint32_t src2 : 12; + uint32_t src2_c : 1; /* const */ + uint32_t dummy : 3; + } c2; + }; + + /* dword1: */ + uint32_t dst : 8; + uint32_t repeat : 2; + uint32_t sat : 1; + uint32_t src1_r : 1; /* doubles as nop0 if repeat==0 */ + uint32_t ss : 1; + uint32_t ul : 1; /* dunno */ + uint32_t dst_half : 1; /* or widen/narrow.. ie. dst hrN <-> rN */ + uint32_t ei : 1; + uint32_t cond : 3; + uint32_t src2_r : 1; /* doubles as nop1 if repeat==0 */ + uint32_t full : 1; /* not half */ + uint32_t opc : 6; + uint32_t jmp_tgt : 1; + uint32_t sync : 1; + uint32_t opc_cat : 3; +} instr_cat2_t; + +typedef struct PACKED { + /* dword0: */ + union PACKED { + struct PACKED { + uint32_t src1 : 11; + uint32_t must_be_zero1: 2; + uint32_t src2_c : 1; + uint32_t src1_neg : 1; + uint32_t src2_r : 1; /* doubles as nop1 if repeat==0 */ + }; + struct PACKED { + uint32_t src1 : 10; + uint32_t src1_c : 1; + uint32_t src1_rel : 1; + uint32_t must_be_zero : 1; + uint32_t dummy : 3; + } rel1; + struct PACKED { + uint32_t src1 : 12; + uint32_t src1_c : 1; + uint32_t dummy : 3; + } c1; + }; + + union PACKED { + struct PACKED { + uint32_t src3 : 11; + uint32_t must_be_zero2: 2; + uint32_t src3_r : 1; + uint32_t src2_neg : 1; + uint32_t src3_neg : 1; + }; + struct PACKED { + uint32_t src3 : 10; + uint32_t src3_c : 1; + uint32_t src3_rel : 1; + uint32_t must_be_zero : 1; + uint32_t dummy : 3; + } rel2; + struct PACKED { + uint32_t src3 : 12; + uint32_t src3_c : 1; + uint32_t dummy : 3; + } c2; + }; + + /* dword1: */ + uint32_t dst : 8; + uint32_t repeat : 2; + uint32_t sat : 1; + uint32_t src1_r : 1; /* doubles as nop0 if repeat==0 */ + uint32_t ss : 1; + uint32_t ul : 1; + uint32_t dst_half : 1; /* or widen/narrow.. ie. dst hrN <-> rN */ + uint32_t src2 : 8; + uint32_t opc : 4; + uint32_t jmp_tgt : 1; + uint32_t sync : 1; + uint32_t opc_cat : 3; +} instr_cat3_t; + +static inline bool instr_cat3_full(instr_cat3_t *cat3) +{ + switch (_OPC(3, cat3->opc)) { + case OPC_MAD_F16: + case OPC_MAD_U16: + case OPC_MAD_S16: + case OPC_SEL_B16: + case OPC_SEL_S16: + case OPC_SEL_F16: + case OPC_SAD_S16: + case OPC_SAD_S32: // really?? + return false; + default: + return true; + } +} + +typedef struct PACKED { + /* dword0: */ + union PACKED { + struct PACKED { + uint32_t src : 11; + uint32_t must_be_zero1: 2; + uint32_t src_im : 1; /* immediate */ + uint32_t src_neg : 1; /* negate */ + uint32_t src_abs : 1; /* absolute value */ + }; + struct PACKED { + uint32_t src : 10; + uint32_t src_c : 1; /* relative-const */ + uint32_t src_rel : 1; /* relative address */ + uint32_t must_be_zero : 1; + uint32_t dummy : 3; + } rel; + struct PACKED { + uint32_t src : 12; + uint32_t src_c : 1; /* const */ + uint32_t dummy : 3; + } c; + }; + uint32_t dummy1 : 16; /* seem to be ignored */ + + /* dword1: */ + uint32_t dst : 8; + uint32_t repeat : 2; + uint32_t sat : 1; + uint32_t src_r : 1; + uint32_t ss : 1; + uint32_t ul : 1; + uint32_t dst_half : 1; /* or widen/narrow.. ie. dst hrN <-> rN */ + uint32_t dummy2 : 5; /* seem to be ignored */ + uint32_t full : 1; /* not half */ + uint32_t opc : 6; + uint32_t jmp_tgt : 1; + uint32_t sync : 1; + uint32_t opc_cat : 3; +} instr_cat4_t; + +/* With is_bindless_s2en = 1, this determines whether bindless is enabled and + * if so, how to get the (base, index) pair for both sampler and texture. + * There is a single base embedded in the instruction, which is always used + * for the texture. + */ +typedef enum { + /* Use traditional GL binding model, get texture and sampler index + * from src3 which is not presumed to be uniform. This is + * backwards-compatible with earlier generations, where this field was + * always 0 and nonuniform-indexed sampling always worked. + */ + CAT5_NONUNIFORM = 0, + + /* The sampler base comes from the low 3 bits of a1.x, and the sampler + * and texture index come from src3 which is presumed to be uniform. + */ + CAT5_BINDLESS_A1_UNIFORM = 1, + + /* The texture and sampler share the same base, and the sampler and + * texture index come from src3 which is *not* presumed to be uniform. + */ + CAT5_BINDLESS_NONUNIFORM = 2, + + /* The sampler base comes from the low 3 bits of a1.x, and the sampler + * and texture index come from src3 which is *not* presumed to be + * uniform. + */ + CAT5_BINDLESS_A1_NONUNIFORM = 3, + + /* Use traditional GL binding model, get texture and sampler index + * from src3 which is presumed to be uniform. + */ + CAT5_UNIFORM = 4, + + /* The texture and sampler share the same base, and the sampler and + * texture index come from src3 which is presumed to be uniform. + */ + CAT5_BINDLESS_UNIFORM = 5, + + /* The texture and sampler share the same base, get sampler index from low + * 4 bits of src3 and texture index from high 4 bits. + */ + CAT5_BINDLESS_IMM = 6, + + /* The sampler base comes from the low 3 bits of a1.x, and the texture + * index comes from the next 8 bits of a1.x. The sampler index is an + * immediate in src3. + */ + CAT5_BINDLESS_A1_IMM = 7, +} cat5_desc_mode_t; + +typedef struct PACKED { + /* dword0: */ + union PACKED { + /* normal case: */ + struct PACKED { + uint32_t full : 1; /* not half */ + uint32_t src1 : 8; + uint32_t src2 : 8; + uint32_t dummy1 : 4; /* seem to be ignored */ + uint32_t samp : 4; + uint32_t tex : 7; + } norm; + /* s2en case: */ + struct PACKED { + uint32_t full : 1; /* not half */ + uint32_t src1 : 8; + uint32_t src2 : 8; + uint32_t dummy1 : 2; + uint32_t base_hi : 2; + uint32_t src3 : 8; + uint32_t desc_mode : 3; + } s2en_bindless; + /* same in either case: */ + // XXX I think, confirm this + struct PACKED { + uint32_t full : 1; /* not half */ + uint32_t src1 : 8; + uint32_t src2 : 8; + uint32_t pad : 15; + }; + }; + + /* dword1: */ + uint32_t dst : 8; + uint32_t wrmask : 4; /* write-mask */ + uint32_t type : 3; + uint32_t base_lo : 1; /* used with bindless */ + uint32_t is_3d : 1; + + uint32_t is_a : 1; + uint32_t is_s : 1; + uint32_t is_s2en_bindless : 1; + uint32_t is_o : 1; + uint32_t is_p : 1; + + uint32_t opc : 5; + uint32_t jmp_tgt : 1; + uint32_t sync : 1; + uint32_t opc_cat : 3; +} instr_cat5_t; + +/* dword0 encoding for src_off: [src1 + off], src2: */ +typedef struct PACKED { + /* dword0: */ + uint32_t mustbe1 : 1; + int32_t off : 13; + uint32_t src1 : 8; + uint32_t src1_im : 1; + uint32_t src2_im : 1; + uint32_t src2 : 8; + + /* dword1: */ + uint32_t dword1; +} instr_cat6a_t; + +/* dword0 encoding for !src_off: [src1], src2 */ +typedef struct PACKED { + /* dword0: */ + uint32_t mustbe0 : 1; + uint32_t src1 : 13; + uint32_t ignore0 : 8; + uint32_t src1_im : 1; + uint32_t src2_im : 1; + uint32_t src2 : 8; + + /* dword1: */ + uint32_t dword1; +} instr_cat6b_t; + +/* dword1 encoding for dst_off: */ +typedef struct PACKED { + /* dword0: */ + uint32_t dword0; + + /* note: there is some weird stuff going on where sometimes + * cat6->a.off is involved.. but that seems like a bug in + * the blob, since it is used even if !cat6->src_off + * It would make sense for there to be some more bits to + * bring us to 11 bits worth of offset, but not sure.. + */ + int32_t off : 8; + uint32_t mustbe1 : 1; + uint32_t dst : 8; + uint32_t pad1 : 15; +} instr_cat6c_t; + +/* dword1 encoding for !dst_off: */ +typedef struct PACKED { + /* dword0: */ + uint32_t dword0; + + uint32_t dst : 8; + uint32_t mustbe0 : 1; + uint32_t idx : 8; + uint32_t pad0 : 15; +} instr_cat6d_t; + +/* ldgb and atomics.. + * + * ldgb: pad0=0, pad3=1 + * atomic .g: pad0=1, pad3=1 + * .l: pad0=1, pad3=0 + */ +typedef struct PACKED { + /* dword0: */ + uint32_t pad0 : 1; + uint32_t src3 : 8; + uint32_t d : 2; + uint32_t typed : 1; + uint32_t type_size : 2; + uint32_t src1 : 8; + uint32_t src1_im : 1; + uint32_t src2_im : 1; + uint32_t src2 : 8; + + /* dword1: */ + uint32_t dst : 8; + uint32_t mustbe0 : 1; + uint32_t src_ssbo : 8; + uint32_t pad2 : 3; // type + uint32_t g : 1; + uint32_t pad3 : 1; + uint32_t pad4 : 10; // opc/jmp_tgt/sync/opc_cat +} instr_cat6ldgb_t; + +/* stgb, pad0=0, pad3=2 + */ +typedef struct PACKED { + /* dword0: */ + uint32_t mustbe1 : 1; // ??? + uint32_t src1 : 8; + uint32_t d : 2; + uint32_t typed : 1; + uint32_t type_size : 2; + uint32_t pad0 : 9; + uint32_t src2_im : 1; + uint32_t src2 : 8; + + /* dword1: */ + uint32_t src3 : 8; + uint32_t src3_im : 1; + uint32_t dst_ssbo : 8; + uint32_t pad2 : 3; // type + uint32_t pad3 : 2; + uint32_t pad4 : 10; // opc/jmp_tgt/sync/opc_cat +} instr_cat6stgb_t; + +typedef union PACKED { + instr_cat6a_t a; + instr_cat6b_t b; + instr_cat6c_t c; + instr_cat6d_t d; + instr_cat6ldgb_t ldgb; + instr_cat6stgb_t stgb; + struct PACKED { + /* dword0: */ + uint32_t src_off : 1; + uint32_t pad1 : 31; + + /* dword1: */ + uint32_t pad2 : 8; + uint32_t dst_off : 1; + uint32_t pad3 : 8; + uint32_t type : 3; + uint32_t g : 1; /* or in some cases it means dst immed */ + uint32_t pad4 : 1; + uint32_t opc : 5; + uint32_t jmp_tgt : 1; + uint32_t sync : 1; + uint32_t opc_cat : 3; + }; +} instr_cat6_t; + +/* Similar to cat5_desc_mode_t, describes how the descriptor is loaded. + */ +typedef enum { + /* Use old GL binding model with an immediate index. */ + CAT6_IMM = 0, + + CAT6_UNIFORM = 1, + + CAT6_NONUNIFORM = 2, + + /* Use the bindless model, with an immediate index. + */ + CAT6_BINDLESS_IMM = 4, + + /* Use the bindless model, with a uniform register index. + */ + CAT6_BINDLESS_UNIFORM = 5, + + /* Use the bindless model, with a register index that isn't guaranteed + * to be uniform. This presumably checks if the indices are equal and + * splits up the load/store, because it works the way you would + * expect. + */ + CAT6_BINDLESS_NONUNIFORM = 6, +} cat6_desc_mode_t; + +/** + * For atomic ops (which return a value): + * + * pad1=1, pad3=c, pad5=3 + * src1 - vecN offset/coords + * src2.x - is actually dest register + * src2.y - is 'data' except for cmpxchg where src2.y is 'compare' + * and src2.z is 'data' + * + * For stib (which does not return a value): + * pad1=0, pad3=c, pad5=2 + * src1 - vecN offset/coords + * src2 - value to store + * + * For ldib: + * pad1=1, pad3=c, pad5=2 + * src1 - vecN offset/coords + * + * for ldc (load from UBO using descriptor): + * pad1=0, pad3=8, pad5=2 + * + * pad2 and pad5 are only observed to be 0. + */ +typedef struct PACKED { + /* dword0: */ + uint32_t pad1 : 1; + uint32_t base : 3; + uint32_t pad2 : 2; + uint32_t desc_mode : 3; + uint32_t d : 2; + uint32_t typed : 1; + uint32_t type_size : 2; + uint32_t opc : 5; + uint32_t pad3 : 5; + uint32_t src1 : 8; /* coordinate/offset */ + + /* dword1: */ + uint32_t src2 : 8; /* or the dst for load instructions */ + uint32_t pad4 : 1; //mustbe0 ?? + uint32_t ssbo : 8; /* ssbo/image binding point */ + uint32_t type : 3; + uint32_t pad5 : 7; + uint32_t jmp_tgt : 1; + uint32_t sync : 1; + uint32_t opc_cat : 3; +} instr_cat6_a6xx_t; + +typedef struct PACKED { + /* dword0: */ + uint32_t pad1 : 32; + + /* dword1: */ + uint32_t pad2 : 12; + uint32_t ss : 1; /* maybe in the encoding, but blob only uses (sy) */ + uint32_t pad3 : 6; + uint32_t w : 1; /* write */ + uint32_t r : 1; /* read */ + uint32_t l : 1; /* local */ + uint32_t g : 1; /* global */ + uint32_t opc : 4; /* presumed, but only a couple known OPCs */ + uint32_t jmp_tgt : 1; /* (jp) */ + uint32_t sync : 1; /* (sy) */ + uint32_t opc_cat : 3; +} instr_cat7_t; + +typedef union PACKED { + instr_cat0_t cat0; + instr_cat1_t cat1; + instr_cat2_t cat2; + instr_cat3_t cat3; + instr_cat4_t cat4; + instr_cat5_t cat5; + instr_cat6_t cat6; + instr_cat6_a6xx_t cat6_a6xx; + instr_cat7_t cat7; + struct PACKED { + /* dword0: */ + uint32_t pad1 : 32; + + /* dword1: */ + uint32_t pad2 : 12; + uint32_t ss : 1; /* cat1-cat4 (cat0??) and cat7 (?) */ + uint32_t ul : 1; /* cat2-cat4 (and cat1 in blob.. which may be bug??) */ + uint32_t pad3 : 13; + uint32_t jmp_tgt : 1; + uint32_t sync : 1; + uint32_t opc_cat : 3; + + }; +} instr_t; + +static inline uint32_t instr_repeat(instr_t *instr) +{ + switch (instr->opc_cat) { + case 0: return instr->cat0.repeat; + case 1: return instr->cat1.repeat; + case 2: return instr->cat2.repeat; + case 3: return instr->cat3.repeat; + case 4: return instr->cat4.repeat; + default: return 0; + } +} + +static inline bool instr_sat(instr_t *instr) +{ + switch (instr->opc_cat) { + case 2: return instr->cat2.sat; + case 3: return instr->cat3.sat; + case 4: return instr->cat4.sat; + default: return false; + } +} + +/* We can probably drop the gpu_id arg, but keeping it for now so we can + * assert if we see something we think should be new encoding on an older + * gpu. + */ +static inline bool is_cat6_legacy(instr_t *instr, unsigned gpu_id) +{ + instr_cat6_a6xx_t *cat6 = &instr->cat6_a6xx; + + /* At least one of these two bits is pad in all the possible + * "legacy" cat6 encodings, and a analysis of all the pre-a6xx + * cmdstream traces I have indicates that the pad bit is zero + * in all cases. So we can use this to detect new encoding: + */ + if ((cat6->pad3 & 0x8) && (cat6->pad5 & 0x2)) { + assert(gpu_id >= 600); + assert(instr->cat6.opc == 0); + return false; + } + + return true; +} + +static inline uint32_t instr_opc(instr_t *instr, unsigned gpu_id) +{ + switch (instr->opc_cat) { + case 0: return instr->cat0.opc | instr->cat0.opc_hi << 4; + case 1: return 0; + case 2: return instr->cat2.opc; + case 3: return instr->cat3.opc; + case 4: return instr->cat4.opc; + case 5: return instr->cat5.opc; + case 6: + if (!is_cat6_legacy(instr, gpu_id)) + return instr->cat6_a6xx.opc; + return instr->cat6.opc; + case 7: return instr->cat7.opc; + default: return 0; + } +} + +static inline bool is_mad(opc_t opc) +{ + switch (opc) { + case OPC_MAD_U16: + case OPC_MAD_S16: + case OPC_MAD_U24: + case OPC_MAD_S24: + case OPC_MAD_F16: + case OPC_MAD_F32: + return true; + default: + return false; + } +} + +static inline bool is_madsh(opc_t opc) +{ + switch (opc) { + case OPC_MADSH_U16: + case OPC_MADSH_M16: + return true; + default: + return false; + } +} + +static inline bool is_atomic(opc_t opc) +{ + switch (opc) { + case OPC_ATOMIC_ADD: + case OPC_ATOMIC_SUB: + case OPC_ATOMIC_XCHG: + case OPC_ATOMIC_INC: + case OPC_ATOMIC_DEC: + case OPC_ATOMIC_CMPXCHG: + case OPC_ATOMIC_MIN: + case OPC_ATOMIC_MAX: + case OPC_ATOMIC_AND: + case OPC_ATOMIC_OR: + case OPC_ATOMIC_XOR: + return true; + default: + return false; + } +} + +static inline bool is_ssbo(opc_t opc) +{ + switch (opc) { + case OPC_RESFMT: + case OPC_RESINFO: + case OPC_LDGB: + case OPC_STGB: + case OPC_STIB: + return true; + default: + return false; + } +} + +static inline bool is_isam(opc_t opc) +{ + switch (opc) { + case OPC_ISAM: + case OPC_ISAML: + case OPC_ISAMM: + return true; + default: + return false; + } +} + + +static inline bool is_cat2_float(opc_t opc) +{ + switch (opc) { + case OPC_ADD_F: + case OPC_MIN_F: + case OPC_MAX_F: + case OPC_MUL_F: + case OPC_SIGN_F: + case OPC_CMPS_F: + case OPC_ABSNEG_F: + case OPC_CMPV_F: + case OPC_FLOOR_F: + case OPC_CEIL_F: + case OPC_RNDNE_F: + case OPC_RNDAZ_F: + case OPC_TRUNC_F: + return true; + + default: + return false; + } +} + +static inline bool is_cat3_float(opc_t opc) +{ + switch (opc) { + case OPC_MAD_F16: + case OPC_MAD_F32: + case OPC_SEL_F16: + case OPC_SEL_F32: + return true; + default: + return false; + } +} + +int disasm_a3xx(uint32_t *dwords, int sizedwords, int level, FILE *out, unsigned gpu_id); + +#endif /* INSTR_A3XX_H_ */ diff --git a/selfdrive/modeld/thneed/debug/decompiler/ir3.h b/selfdrive/modeld/thneed/debug/decompiler/ir3.h new file mode 100644 index 0000000000..278dc96362 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/decompiler/ir3.h @@ -0,0 +1,1755 @@ +/* + * Copyright (c) 2013 Rob Clark + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice (including the next + * paragraph) shall be included in all copies or substantial portions of the + * Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +#ifndef IR3_H_ +#define IR3_H_ + +#include +#include + +#include "shader_enums.h" +#include "util/list.h" + +/*#include "util/bitscan.h" +#include "util/list.h" +#include "util/set.h" +#include "util/u_debug.h"*/ + +#include "instr-a3xx.h" + +/* low level intermediate representation of an adreno shader program */ + +struct ir3_compiler; +struct ir3; +struct ir3_instruction; +struct ir3_block; + +struct ir3_info { + uint32_t gpu_id; + uint16_t sizedwords; + uint16_t instrs_count; /* expanded to account for rpt's */ + uint16_t nops_count; /* # of nop instructions, including nopN */ + uint16_t mov_count; + uint16_t cov_count; + /* NOTE: max_reg, etc, does not include registers not touched + * by the shader (ie. vertex fetched via VFD_DECODE but not + * touched by shader) + */ + int8_t max_reg; /* highest GPR # used by shader */ + int8_t max_half_reg; + int16_t max_const; + + /* number of sync bits: */ + uint16_t ss, sy; + + /* estimate of number of cycles stalled on (ss) */ + uint16_t sstall; + + uint16_t last_baryf; /* instruction # of last varying fetch */ +}; + +struct ir3_register { + enum { + IR3_REG_CONST = 0x001, + IR3_REG_IMMED = 0x002, + IR3_REG_HALF = 0x004, + /* high registers are used for some things in compute shaders, + * for example. Seems to be for things that are global to all + * threads in a wave, so possibly these are global/shared by + * all the threads in the wave? + */ + IR3_REG_HIGH = 0x008, + IR3_REG_RELATIV= 0x010, + IR3_REG_R = 0x020, + /* Most instructions, it seems, can do float abs/neg but not + * integer. The CP pass needs to know what is intended (int or + * float) in order to do the right thing. For this reason the + * abs/neg flags are split out into float and int variants. In + * addition, .b (bitwise) operations, the negate is actually a + * bitwise not, so split that out into a new flag to make it + * more clear. + */ + IR3_REG_FNEG = 0x040, + IR3_REG_FABS = 0x080, + IR3_REG_SNEG = 0x100, + IR3_REG_SABS = 0x200, + IR3_REG_BNOT = 0x400, + IR3_REG_EVEN = 0x800, + IR3_REG_POS_INF= 0x1000, + /* (ei) flag, end-input? Set on last bary, presumably to signal + * that the shader needs no more input: + */ + IR3_REG_EI = 0x2000, + /* meta-flags, for intermediate stages of IR, ie. + * before register assignment is done: + */ + IR3_REG_SSA = 0x4000, /* 'instr' is ptr to assigning instr */ + IR3_REG_ARRAY = 0x8000, + + } flags; + + /* used for cat5 instructions, but also for internal/IR level + * tracking of what registers are read/written by an instruction. + * wrmask may be a bad name since it is used to represent both + * src and dst that touch multiple adjacent registers. + */ + unsigned wrmask : 16; /* up to vec16 */ + + /* for relative addressing, 32bits for array size is too small, + * but otoh we don't need to deal with disjoint sets, so instead + * use a simple size field (number of scalar components). + * + * Note the size field isn't important for relative const (since + * we don't have to do register allocation for constants). + */ + unsigned size : 15; + + bool merged : 1; /* half-regs conflict with full regs (ie >= a6xx) */ + + /* normal registers: + * the component is in the low two bits of the reg #, so + * rN.x becomes: (N << 2) | x + */ + uint16_t num; + union { + /* immediate: */ + int32_t iim_val; + uint32_t uim_val; + float fim_val; + /* relative: */ + struct { + uint16_t id; + int16_t offset; + } array; + }; + + /* For IR3_REG_SSA, src registers contain ptr back to assigning + * instruction. + * + * For IR3_REG_ARRAY, the pointer is back to the last dependent + * array access (although the net effect is the same, it points + * back to a previous instruction that we depend on). + */ + struct ir3_instruction *instr; +}; + +/* + * Stupid/simple growable array implementation: + */ +#define DECLARE_ARRAY(type, name) \ + unsigned name ## _count, name ## _sz; \ + type * name; + +#define array_insert(ctx, arr, val) do { \ + if (arr ## _count == arr ## _sz) { \ + arr ## _sz = MAX2(2 * arr ## _sz, 16); \ + arr = reralloc_size(ctx, arr, arr ## _sz * sizeof(arr[0])); \ + } \ + arr[arr ##_count++] = val; \ + } while (0) + +struct ir3_instruction { + struct ir3_block *block; + opc_t opc; + enum { + /* (sy) flag is set on first instruction, and after sample + * instructions (probably just on RAW hazard). + */ + IR3_INSTR_SY = 0x001, + /* (ss) flag is set on first instruction, and first instruction + * to depend on the result of "long" instructions (RAW hazard): + * + * rcp, rsq, log2, exp2, sin, cos, sqrt + * + * It seems to synchronize until all in-flight instructions are + * completed, for example: + * + * rsq hr1.w, hr1.w + * add.f hr2.z, (neg)hr2.z, hc0.y + * mul.f hr2.w, (neg)hr2.y, (neg)hr2.y + * rsq hr2.x, hr2.x + * (rpt1)nop + * mad.f16 hr2.w, hr2.z, hr2.z, hr2.w + * nop + * mad.f16 hr2.w, (neg)hr0.w, (neg)hr0.w, hr2.w + * (ss)(rpt2)mul.f hr1.x, (r)hr1.x, hr1.w + * (rpt2)mul.f hr0.x, (neg)(r)hr0.x, hr2.x + * + * The last mul.f does not have (ss) set, presumably because the + * (ss) on the previous instruction does the job. + * + * The blob driver also seems to set it on WAR hazards, although + * not really clear if this is needed or just blob compiler being + * sloppy. So far I haven't found a case where removing the (ss) + * causes problems for WAR hazard, but I could just be getting + * lucky: + * + * rcp r1.y, r3.y + * (ss)(rpt2)mad.f32 r3.y, (r)c9.x, r1.x, (r)r3.z + * + */ + IR3_INSTR_SS = 0x002, + /* (jp) flag is set on jump targets: + */ + IR3_INSTR_JP = 0x004, + IR3_INSTR_UL = 0x008, + IR3_INSTR_3D = 0x010, + IR3_INSTR_A = 0x020, + IR3_INSTR_O = 0x040, + IR3_INSTR_P = 0x080, + IR3_INSTR_S = 0x100, + IR3_INSTR_S2EN = 0x200, + IR3_INSTR_G = 0x400, + IR3_INSTR_SAT = 0x800, + /* (cat5/cat6) Bindless */ + IR3_INSTR_B = 0x1000, + /* (cat5-only) Get some parts of the encoding from a1.x */ + IR3_INSTR_A1EN = 0x2000, + /* meta-flags, for intermediate stages of IR, ie. + * before register assignment is done: + */ + IR3_INSTR_MARK = 0x4000, + IR3_INSTR_UNUSED= 0x8000, + } flags; + uint8_t repeat; + uint8_t nop; +#ifdef DEBUG + unsigned regs_max; +#endif + unsigned regs_count; + struct ir3_register **regs; + union { + struct { + char inv; + char comp; + int immed; + struct ir3_block *target; + } cat0; + struct { + type_t src_type, dst_type; + } cat1; + struct { + enum { + IR3_COND_LT = 0, + IR3_COND_LE = 1, + IR3_COND_GT = 2, + IR3_COND_GE = 3, + IR3_COND_EQ = 4, + IR3_COND_NE = 5, + } condition; + } cat2; + struct { + unsigned samp, tex; + unsigned tex_base : 3; + type_t type; + } cat5; + struct { + type_t type; + int src_offset; + int dst_offset; + int iim_val : 3; /* for ldgb/stgb, # of components */ + unsigned d : 3; /* for ldc, component offset */ + bool typed : 1; + unsigned base : 3; + } cat6; + struct { + unsigned w : 1; /* write */ + unsigned r : 1; /* read */ + unsigned l : 1; /* local */ + unsigned g : 1; /* global */ + } cat7; + /* for meta-instructions, just used to hold extra data + * before instruction scheduling, etc + */ + struct { + int off; /* component/offset */ + } split; + struct { + /* for output collects, this maps back to the entry in the + * ir3_shader_variant::outputs table. + */ + int outidx; + } collect; + struct { + unsigned samp, tex; + unsigned input_offset; + unsigned samp_base : 3; + unsigned tex_base : 3; + } prefetch; + struct { + /* maps back to entry in ir3_shader_variant::inputs table: */ + int inidx; + /* for sysvals, identifies the sysval type. Mostly so we can + * identify the special cases where a sysval should not be DCE'd + * (currently, just pre-fs texture fetch) + */ + gl_system_value sysval; + } input; + }; + + /* When we get to the RA stage, we need instruction's position/name: */ + uint16_t ip; + uint16_t name; + + /* used for per-pass extra instruction data. + * + * TODO we should remove the per-pass data like this and 'use_count' + * and do something similar to what RA does w/ ir3_ra_instr_data.. + * ie. use the ir3_count_instructions pass, and then use instr->ip + * to index into a table of pass-private data. + */ + void *data; + + /** + * Valid if pass calls ir3_find_ssa_uses().. see foreach_ssa_use() + */ + struct set *uses; + + int sun; /* Sethi–Ullman number, used by sched */ + int use_count; /* currently just updated/used by cp */ + + /* Used during CP and RA stages. For collect and shader inputs/ + * outputs where we need a sequence of consecutive registers, + * keep track of each src instructions left (ie 'n-1') and right + * (ie 'n+1') neighbor. The front-end must insert enough mov's + * to ensure that each instruction has at most one left and at + * most one right neighbor. During the copy-propagation pass, + * we only remove mov's when we can preserve this constraint. + * And during the RA stage, we use the neighbor information to + * allocate a block of registers in one shot. + * + * TODO: maybe just add something like: + * struct ir3_instruction_ref { + * struct ir3_instruction *instr; + * unsigned cnt; + * } + * + * Or can we get away without the refcnt stuff? It seems like + * it should be overkill.. the problem is if, potentially after + * already eliminating some mov's, if you have a single mov that + * needs to be grouped with it's neighbors in two different + * places (ex. shader output and a collect). + */ + struct { + struct ir3_instruction *left, *right; + uint16_t left_cnt, right_cnt; + } cp; + + /* an instruction can reference at most one address register amongst + * it's src/dst registers. Beyond that, you need to insert mov's. + * + * NOTE: do not write this directly, use ir3_instr_set_address() + */ + struct ir3_instruction *address; + + /* Tracking for additional dependent instructions. Used to handle + * barriers, WAR hazards for arrays/SSBOs/etc. + */ + DECLARE_ARRAY(struct ir3_instruction *, deps); + + /* + * From PoV of instruction scheduling, not execution (ie. ignores global/ + * local distinction): + * shared image atomic SSBO everything + * barrier()/ - R/W R/W R/W R/W X + * groupMemoryBarrier() + * memoryBarrier() - R/W R/W + * (but only images declared coherent?) + * memoryBarrierAtomic() - R/W + * memoryBarrierBuffer() - R/W + * memoryBarrierImage() - R/W + * memoryBarrierShared() - R/W + * + * TODO I think for SSBO/image/shared, in cases where we can determine + * which variable is accessed, we don't need to care about accesses to + * different variables (unless declared coherent??) + */ + enum { + IR3_BARRIER_EVERYTHING = 1 << 0, + IR3_BARRIER_SHARED_R = 1 << 1, + IR3_BARRIER_SHARED_W = 1 << 2, + IR3_BARRIER_IMAGE_R = 1 << 3, + IR3_BARRIER_IMAGE_W = 1 << 4, + IR3_BARRIER_BUFFER_R = 1 << 5, + IR3_BARRIER_BUFFER_W = 1 << 6, + IR3_BARRIER_ARRAY_R = 1 << 7, + IR3_BARRIER_ARRAY_W = 1 << 8, + } barrier_class, barrier_conflict; + + /* Entry in ir3_block's instruction list: */ + struct list_head node; + +#ifdef DEBUG + uint32_t serialno; +#endif + + // TODO only computerator/assembler: + int line; +}; + +static inline struct ir3_instruction * +ir3_neighbor_first(struct ir3_instruction *instr) +{ + int cnt = 0; + while (instr->cp.left) { + instr = instr->cp.left; + if (++cnt > 0xffff) { + debug_assert(0); + break; + } + } + return instr; +} + +static inline int ir3_neighbor_count(struct ir3_instruction *instr) +{ + int num = 1; + + debug_assert(!instr->cp.left); + + while (instr->cp.right) { + num++; + instr = instr->cp.right; + if (num > 0xffff) { + debug_assert(0); + break; + } + } + + return num; +} + +struct ir3 { + struct ir3_compiler *compiler; + gl_shader_stage type; + + DECLARE_ARRAY(struct ir3_instruction *, inputs); + DECLARE_ARRAY(struct ir3_instruction *, outputs); + + /* Track bary.f (and ldlv) instructions.. this is needed in + * scheduling to ensure that all varying fetches happen before + * any potential kill instructions. The hw gets grumpy if all + * threads in a group are killed before the last bary.f gets + * a chance to signal end of input (ei). + */ + DECLARE_ARRAY(struct ir3_instruction *, baryfs); + + /* Track all indirect instructions (read and write). To avoid + * deadlock scenario where an address register gets scheduled, + * but other dependent src instructions cannot be scheduled due + * to dependency on a *different* address register value, the + * scheduler needs to ensure that all dependencies other than + * the instruction other than the address register are scheduled + * before the one that writes the address register. Having a + * convenient list of instructions that reference some address + * register simplifies this. + */ + DECLARE_ARRAY(struct ir3_instruction *, a0_users); + + /* same for a1.x: */ + DECLARE_ARRAY(struct ir3_instruction *, a1_users); + + /* and same for instructions that consume predicate register: */ + DECLARE_ARRAY(struct ir3_instruction *, predicates); + + /* Track texture sample instructions which need texture state + * patched in (for astc-srgb workaround): + */ + DECLARE_ARRAY(struct ir3_instruction *, astc_srgb); + + /* List of blocks: */ + struct list_head block_list; + + /* List of ir3_array's: */ + struct list_head array_list; + + unsigned max_sun; /* max Sethi–Ullman number */ + +#ifdef DEBUG + unsigned block_count, instr_count; +#endif +}; + +struct ir3_array { + struct list_head node; + unsigned length; + unsigned id; + + struct nir_register *r; + + /* To avoid array write's from getting DCE'd, keep track of the + * most recent write. Any array access depends on the most + * recent write. This way, nothing depends on writes after the + * last read. But all the writes that happen before that have + * something depending on them + */ + struct ir3_instruction *last_write; + + /* extra stuff used in RA pass: */ + unsigned base; /* base vreg name */ + unsigned reg; /* base physical reg */ + uint16_t start_ip, end_ip; + + /* Indicates if half-precision */ + bool half; +}; + +struct ir3_array * ir3_lookup_array(struct ir3 *ir, unsigned id); + +struct ir3_block { + struct list_head node; + struct ir3 *shader; + + const struct nir_block *nblock; + + struct list_head instr_list; /* list of ir3_instruction */ + + /* each block has either one or two successors.. in case of + * two successors, 'condition' decides which one to follow. + * A block preceding an if/else has two successors. + */ + struct ir3_instruction *condition; + struct ir3_block *successors[2]; + + struct set *predecessors; /* set of ir3_block */ + + uint16_t start_ip, end_ip; + + /* Track instructions which do not write a register but other- + * wise must not be discarded (such as kill, stg, etc) + */ + DECLARE_ARRAY(struct ir3_instruction *, keeps); + + /* used for per-pass extra block data. Mainly used right + * now in RA step to track livein/liveout. + */ + void *data; + +#ifdef DEBUG + uint32_t serialno; +#endif +}; + +static inline uint32_t +block_id(struct ir3_block *block) +{ +#ifdef DEBUG + return block->serialno; +#else + return (uint32_t)(unsigned long)block; +#endif +} + +struct ir3 * ir3_create(struct ir3_compiler *compiler, gl_shader_stage type); +void ir3_destroy(struct ir3 *shader); +void * ir3_assemble(struct ir3 *shader, + struct ir3_info *info, uint32_t gpu_id); +void * ir3_alloc(struct ir3 *shader, int sz); + +struct ir3_block * ir3_block_create(struct ir3 *shader); + +struct ir3_instruction * ir3_instr_create(struct ir3_block *block, opc_t opc); +struct ir3_instruction * ir3_instr_create2(struct ir3_block *block, + opc_t opc, int nreg); +struct ir3_instruction * ir3_instr_clone(struct ir3_instruction *instr); +void ir3_instr_add_dep(struct ir3_instruction *instr, struct ir3_instruction *dep); +const char *ir3_instr_name(struct ir3_instruction *instr); + +struct ir3_register * ir3_reg_create(struct ir3_instruction *instr, + int num, int flags); +struct ir3_register * ir3_reg_clone(struct ir3 *shader, + struct ir3_register *reg); + +void ir3_instr_set_address(struct ir3_instruction *instr, + struct ir3_instruction *addr); + +static inline bool ir3_instr_check_mark(struct ir3_instruction *instr) +{ + if (instr->flags & IR3_INSTR_MARK) + return true; /* already visited */ + instr->flags |= IR3_INSTR_MARK; + return false; +} + +void ir3_block_clear_mark(struct ir3_block *block); +void ir3_clear_mark(struct ir3 *shader); + +unsigned ir3_count_instructions(struct ir3 *ir); +unsigned ir3_count_instructions_ra(struct ir3 *ir); + +void ir3_find_ssa_uses(struct ir3 *ir, void *mem_ctx, bool falsedeps); + +//#include "util/set.h" +#define foreach_ssa_use(__use, __instr) \ + for (struct ir3_instruction *__use = (void *)~0; \ + __use && (__instr)->uses; __use = NULL) \ + set_foreach ((__instr)->uses, __entry) \ + if ((__use = (void *)__entry->key)) + +#define MAX_ARRAYS 16 + +/* comp: + * 0 - x + * 1 - y + * 2 - z + * 3 - w + */ +static inline uint32_t regid(int num, int comp) +{ + return (num << 2) | (comp & 0x3); +} + +static inline uint32_t reg_num(struct ir3_register *reg) +{ + return reg->num >> 2; +} + +static inline uint32_t reg_comp(struct ir3_register *reg) +{ + return reg->num & 0x3; +} + +#define INVALID_REG regid(63, 0) +#define VALIDREG(r) ((r) != INVALID_REG) +#define CONDREG(r, val) COND(VALIDREG(r), (val)) + +static inline bool is_flow(struct ir3_instruction *instr) +{ + return (opc_cat(instr->opc) == 0); +} + +static inline bool is_kill(struct ir3_instruction *instr) +{ + return instr->opc == OPC_KILL; +} + +static inline bool is_nop(struct ir3_instruction *instr) +{ + return instr->opc == OPC_NOP; +} + +static inline bool is_same_type_reg(struct ir3_register *reg1, + struct ir3_register *reg2) +{ + unsigned type_reg1 = (reg1->flags & (IR3_REG_HIGH | IR3_REG_HALF)); + unsigned type_reg2 = (reg2->flags & (IR3_REG_HIGH | IR3_REG_HALF)); + + if (type_reg1 ^ type_reg2) + return false; + else + return true; +} + +/* Is it a non-transformative (ie. not type changing) mov? This can + * also include absneg.s/absneg.f, which for the most part can be + * treated as a mov (single src argument). + */ +static inline bool is_same_type_mov(struct ir3_instruction *instr) +{ + struct ir3_register *dst; + + switch (instr->opc) { + case OPC_MOV: + if (instr->cat1.src_type != instr->cat1.dst_type) + return false; + /* If the type of dest reg and src reg are different, + * it shouldn't be considered as same type mov + */ + if (!is_same_type_reg(instr->regs[0], instr->regs[1])) + return false; + break; + case OPC_ABSNEG_F: + case OPC_ABSNEG_S: + if (instr->flags & IR3_INSTR_SAT) + return false; + /* If the type of dest reg and src reg are different, + * it shouldn't be considered as same type mov + */ + if (!is_same_type_reg(instr->regs[0], instr->regs[1])) + return false; + break; + default: + return false; + } + + dst = instr->regs[0]; + + /* mov's that write to a0 or p0.x are special: */ + if (dst->num == regid(REG_P0, 0)) + return false; + if (reg_num(dst) == REG_A0) + return false; + + if (dst->flags & (IR3_REG_RELATIV | IR3_REG_ARRAY)) + return false; + + return true; +} + +/* A move from const, which changes size but not type, can also be + * folded into dest instruction in some cases. + */ +static inline bool is_const_mov(struct ir3_instruction *instr) +{ + if (instr->opc != OPC_MOV) + return false; + + if (!(instr->regs[1]->flags & IR3_REG_CONST)) + return false; + + type_t src_type = instr->cat1.src_type; + type_t dst_type = instr->cat1.dst_type; + + return (type_float(src_type) && type_float(dst_type)) || + (type_uint(src_type) && type_uint(dst_type)) || + (type_sint(src_type) && type_sint(dst_type)); +} + +static inline bool is_alu(struct ir3_instruction *instr) +{ + return (1 <= opc_cat(instr->opc)) && (opc_cat(instr->opc) <= 3); +} + +static inline bool is_sfu(struct ir3_instruction *instr) +{ + return (opc_cat(instr->opc) == 4); +} + +static inline bool is_tex(struct ir3_instruction *instr) +{ + return (opc_cat(instr->opc) == 5); +} + +static inline bool is_tex_or_prefetch(struct ir3_instruction *instr) +{ + return is_tex(instr) || (instr->opc == OPC_META_TEX_PREFETCH); +} + +static inline bool is_mem(struct ir3_instruction *instr) +{ + return (opc_cat(instr->opc) == 6); +} + +static inline bool is_barrier(struct ir3_instruction *instr) +{ + return (opc_cat(instr->opc) == 7); +} + +static inline bool +is_half(struct ir3_instruction *instr) +{ + return !!(instr->regs[0]->flags & IR3_REG_HALF); +} + +static inline bool +is_high(struct ir3_instruction *instr) +{ + return !!(instr->regs[0]->flags & IR3_REG_HIGH); +} + +static inline bool +is_store(struct ir3_instruction *instr) +{ + /* these instructions, the "destination" register is + * actually a source, the address to store to. + */ + switch (instr->opc) { + case OPC_STG: + case OPC_STGB: + case OPC_STIB: + case OPC_STP: + case OPC_STL: + case OPC_STLW: + case OPC_L2G: + case OPC_G2L: + return true; + default: + return false; + } +} + +static inline bool is_load(struct ir3_instruction *instr) +{ + switch (instr->opc) { + case OPC_LDG: + case OPC_LDGB: + case OPC_LDIB: + case OPC_LDL: + case OPC_LDP: + case OPC_L2G: + case OPC_LDLW: + case OPC_LDC: + case OPC_LDLV: + /* probably some others too.. */ + return true; + default: + return false; + } +} + +static inline bool is_input(struct ir3_instruction *instr) +{ + /* in some cases, ldlv is used to fetch varying without + * interpolation.. fortunately inloc is the first src + * register in either case + */ + switch (instr->opc) { + case OPC_LDLV: + case OPC_BARY_F: + return true; + default: + return false; + } +} + +static inline bool is_bool(struct ir3_instruction *instr) +{ + switch (instr->opc) { + case OPC_CMPS_F: + case OPC_CMPS_S: + case OPC_CMPS_U: + return true; + default: + return false; + } +} + +static inline bool is_meta(struct ir3_instruction *instr) +{ + return (opc_cat(instr->opc) == -1); +} + +static inline unsigned dest_regs(struct ir3_instruction *instr) +{ + if ((instr->regs_count == 0) || is_store(instr) || is_flow(instr)) + return 0; + + return util_last_bit(instr->regs[0]->wrmask); +} + +static inline bool +writes_gpr(struct ir3_instruction *instr) +{ + if (dest_regs(instr) == 0) + return false; + /* is dest a normal temp register: */ + struct ir3_register *reg = instr->regs[0]; + debug_assert(!(reg->flags & (IR3_REG_CONST | IR3_REG_IMMED))); + if ((reg_num(reg) == REG_A0) || + (reg->num == regid(REG_P0, 0))) + return false; + return true; +} + +static inline bool writes_addr0(struct ir3_instruction *instr) +{ + if (instr->regs_count > 0) { + struct ir3_register *dst = instr->regs[0]; + return dst->num == regid(REG_A0, 0); + } + return false; +} + +static inline bool writes_addr1(struct ir3_instruction *instr) +{ + if (instr->regs_count > 0) { + struct ir3_register *dst = instr->regs[0]; + return dst->num == regid(REG_A0, 1); + } + return false; +} + +static inline bool writes_pred(struct ir3_instruction *instr) +{ + if (instr->regs_count > 0) { + struct ir3_register *dst = instr->regs[0]; + return reg_num(dst) == REG_P0; + } + return false; +} + +/* returns defining instruction for reg */ +/* TODO better name */ +static inline struct ir3_instruction *ssa(struct ir3_register *reg) +{ + if (reg->flags & (IR3_REG_SSA | IR3_REG_ARRAY)) { + return reg->instr; + } + return NULL; +} + +static inline bool conflicts(struct ir3_instruction *a, + struct ir3_instruction *b) +{ + return (a && b) && (a != b); +} + +static inline bool reg_gpr(struct ir3_register *r) +{ + if (r->flags & (IR3_REG_CONST | IR3_REG_IMMED)) + return false; + if ((reg_num(r) == REG_A0) || (reg_num(r) == REG_P0)) + return false; + return true; +} + +static inline type_t half_type(type_t type) +{ + switch (type) { + case TYPE_F32: return TYPE_F16; + case TYPE_U32: return TYPE_U16; + case TYPE_S32: return TYPE_S16; + case TYPE_F16: + case TYPE_U16: + case TYPE_S16: + return type; + default: + assert(0); + return ~0; + } +} + +/* some cat2 instructions (ie. those which are not float) can embed an + * immediate: + */ +static inline bool ir3_cat2_int(opc_t opc) +{ + switch (opc) { + case OPC_ADD_U: + case OPC_ADD_S: + case OPC_SUB_U: + case OPC_SUB_S: + case OPC_CMPS_U: + case OPC_CMPS_S: + case OPC_MIN_U: + case OPC_MIN_S: + case OPC_MAX_U: + case OPC_MAX_S: + case OPC_CMPV_U: + case OPC_CMPV_S: + case OPC_MUL_U24: + case OPC_MUL_S24: + case OPC_MULL_U: + case OPC_CLZ_S: + case OPC_ABSNEG_S: + case OPC_AND_B: + case OPC_OR_B: + case OPC_NOT_B: + case OPC_XOR_B: + case OPC_BFREV_B: + case OPC_CLZ_B: + case OPC_SHL_B: + case OPC_SHR_B: + case OPC_ASHR_B: + case OPC_MGEN_B: + case OPC_GETBIT_B: + case OPC_CBITS_B: + case OPC_BARY_F: + return true; + + default: + return false; + } +} + +/* map cat2 instruction to valid abs/neg flags: */ +static inline unsigned ir3_cat2_absneg(opc_t opc) +{ + switch (opc) { + case OPC_ADD_F: + case OPC_MIN_F: + case OPC_MAX_F: + case OPC_MUL_F: + case OPC_SIGN_F: + case OPC_CMPS_F: + case OPC_ABSNEG_F: + case OPC_CMPV_F: + case OPC_FLOOR_F: + case OPC_CEIL_F: + case OPC_RNDNE_F: + case OPC_RNDAZ_F: + case OPC_TRUNC_F: + case OPC_BARY_F: + return IR3_REG_FABS | IR3_REG_FNEG; + + case OPC_ADD_U: + case OPC_ADD_S: + case OPC_SUB_U: + case OPC_SUB_S: + case OPC_CMPS_U: + case OPC_CMPS_S: + case OPC_MIN_U: + case OPC_MIN_S: + case OPC_MAX_U: + case OPC_MAX_S: + case OPC_CMPV_U: + case OPC_CMPV_S: + case OPC_MUL_U24: + case OPC_MUL_S24: + case OPC_MULL_U: + case OPC_CLZ_S: + return 0; + + case OPC_ABSNEG_S: + return IR3_REG_SABS | IR3_REG_SNEG; + + case OPC_AND_B: + case OPC_OR_B: + case OPC_NOT_B: + case OPC_XOR_B: + case OPC_BFREV_B: + case OPC_CLZ_B: + case OPC_SHL_B: + case OPC_SHR_B: + case OPC_ASHR_B: + case OPC_MGEN_B: + case OPC_GETBIT_B: + case OPC_CBITS_B: + return IR3_REG_BNOT; + + default: + return 0; + } +} + +/* map cat3 instructions to valid abs/neg flags: */ +static inline unsigned ir3_cat3_absneg(opc_t opc) +{ + switch (opc) { + case OPC_MAD_F16: + case OPC_MAD_F32: + case OPC_SEL_F16: + case OPC_SEL_F32: + return IR3_REG_FNEG; + + case OPC_MAD_U16: + case OPC_MADSH_U16: + case OPC_MAD_S16: + case OPC_MADSH_M16: + case OPC_MAD_U24: + case OPC_MAD_S24: + case OPC_SEL_S16: + case OPC_SEL_S32: + case OPC_SAD_S16: + case OPC_SAD_S32: + /* neg *may* work on 3rd src.. */ + + case OPC_SEL_B16: + case OPC_SEL_B32: + + default: + return 0; + } +} + +#define MASK(n) ((1 << (n)) - 1) + +/* iterator for an instructions's sources (reg), also returns src #: */ +#define foreach_src_n(__srcreg, __n, __instr) \ + if ((__instr)->regs_count) \ + for (unsigned __cnt = (__instr)->regs_count - 1, __n = 0; __n < __cnt; __n++) \ + if ((__srcreg = (__instr)->regs[__n + 1])) + +/* iterator for an instructions's sources (reg): */ +#define foreach_src(__srcreg, __instr) \ + foreach_src_n(__srcreg, __i, __instr) + +static inline unsigned __ssa_src_cnt(struct ir3_instruction *instr) +{ + unsigned cnt = instr->regs_count + instr->deps_count; + if (instr->address) + cnt++; + return cnt; +} + +static inline struct ir3_instruction ** +__ssa_srcp_n(struct ir3_instruction *instr, unsigned n) +{ + if (n == (instr->regs_count + instr->deps_count)) + return &instr->address; + if (n >= instr->regs_count) + return &instr->deps[n - instr->regs_count]; + if (ssa(instr->regs[n])) + return &instr->regs[n]->instr; + return NULL; +} + +static inline bool __is_false_dep(struct ir3_instruction *instr, unsigned n) +{ + if (n == (instr->regs_count + instr->deps_count)) + return false; + if (n >= instr->regs_count) + return true; + return false; +} + +#define foreach_ssa_srcp_n(__srcp, __n, __instr) \ + for (struct ir3_instruction **__srcp = (void *)~0; __srcp; __srcp = NULL) \ + for (unsigned __cnt = __ssa_src_cnt(__instr), __n = 0; __n < __cnt; __n++) \ + if ((__srcp = __ssa_srcp_n(__instr, __n))) + +#define foreach_ssa_srcp(__srcp, __instr) \ + foreach_ssa_srcp_n(__srcp, __i, __instr) + +/* iterator for an instruction's SSA sources (instr), also returns src #: */ +#define foreach_ssa_src_n(__srcinst, __n, __instr) \ + foreach_ssa_srcp_n(__srcp, __n, __instr) \ + if ((__srcinst = *__srcp)) + +/* iterator for an instruction's SSA sources (instr): */ +#define foreach_ssa_src(__srcinst, __instr) \ + foreach_ssa_src_n(__srcinst, __i, __instr) + +/* iterators for shader inputs: */ +#define foreach_input_n(__ininstr, __cnt, __ir) \ + for (unsigned __cnt = 0; __cnt < (__ir)->inputs_count; __cnt++) \ + if ((__ininstr = (__ir)->inputs[__cnt])) +#define foreach_input(__ininstr, __ir) \ + foreach_input_n(__ininstr, __i, __ir) + +/* iterators for shader outputs: */ +#define foreach_output_n(__outinstr, __cnt, __ir) \ + for (unsigned __cnt = 0; __cnt < (__ir)->outputs_count; __cnt++) \ + if ((__outinstr = (__ir)->outputs[__cnt])) +#define foreach_output(__outinstr, __ir) \ + foreach_output_n(__outinstr, __i, __ir) + +/* iterators for instructions: */ +#define foreach_instr(__instr, __list) \ + list_for_each_entry(struct ir3_instruction, __instr, __list, node) +#define foreach_instr_rev(__instr, __list) \ + list_for_each_entry_rev(struct ir3_instruction, __instr, __list, node) +#define foreach_instr_safe(__instr, __list) \ + list_for_each_entry_safe(struct ir3_instruction, __instr, __list, node) + +/* iterators for blocks: */ +#define foreach_block(__block, __list) \ + list_for_each_entry(struct ir3_block, __block, __list, node) +#define foreach_block_safe(__block, __list) \ + list_for_each_entry_safe(struct ir3_block, __block, __list, node) +#define foreach_block_rev(__block, __list) \ + list_for_each_entry_rev(struct ir3_block, __block, __list, node) + +/* iterators for arrays: */ +#define foreach_array(__array, __list) \ + list_for_each_entry(struct ir3_array, __array, __list, node) + +/* Check if condition is true for any src instruction. + */ +static inline bool +check_src_cond(struct ir3_instruction *instr, bool (*cond)(struct ir3_instruction *)) +{ + struct ir3_register *reg; + + /* Note that this is also used post-RA so skip the ssa iterator: */ + foreach_src (reg, instr) { + struct ir3_instruction *src = reg->instr; + + if (!src) + continue; + + /* meta:split/collect aren't real instructions, the thing that + * we actually care about is *their* srcs + */ + if ((src->opc == OPC_META_SPLIT) || (src->opc == OPC_META_COLLECT)) { + if (check_src_cond(src, cond)) + return true; + } else { + if (cond(src)) + return true; + } + } + + return false; +} + +/* dump: */ +void ir3_print(struct ir3 *ir); +void ir3_print_instr(struct ir3_instruction *instr); + +/* delay calculation: */ +int ir3_delayslots(struct ir3_instruction *assigner, + struct ir3_instruction *consumer, unsigned n, bool soft); +unsigned ir3_delay_calc(struct ir3_block *block, struct ir3_instruction *instr, + bool soft, bool pred); +void ir3_remove_nops(struct ir3 *ir); + +/* dead code elimination: */ +struct ir3_shader_variant; +void ir3_dce(struct ir3 *ir, struct ir3_shader_variant *so); + +/* fp16 conversion folding */ +void ir3_cf(struct ir3 *ir); + +/* copy-propagate: */ +void ir3_cp(struct ir3 *ir, struct ir3_shader_variant *so); + +/* group neighbors and insert mov's to resolve conflicts: */ +void ir3_group(struct ir3 *ir); + +/* Sethi–Ullman numbering: */ +void ir3_sun(struct ir3 *ir); + +/* scheduling: */ +void ir3_sched_add_deps(struct ir3 *ir); +int ir3_sched(struct ir3 *ir); + +struct ir3_context; +int ir3_postsched(struct ir3_context *ctx); + +bool ir3_a6xx_fixup_atomic_dests(struct ir3 *ir, struct ir3_shader_variant *so); + +/* register assignment: */ +struct ir3_ra_reg_set * ir3_ra_alloc_reg_set(struct ir3_compiler *compiler); +int ir3_ra(struct ir3_shader_variant *v, struct ir3_instruction **precolor, unsigned nprecolor); + +/* legalize: */ +void ir3_legalize(struct ir3 *ir, struct ir3_shader_variant *so, int *max_bary); + +static inline bool +ir3_has_latency_to_hide(struct ir3 *ir) +{ + /* VS/GS/TCS/TESS co-exist with frag shader invocations, but we don't + * know the nature of the fragment shader. Just assume it will have + * latency to hide: + */ + if (ir->type != MESA_SHADER_FRAGMENT) + return true; + + foreach_block (block, &ir->block_list) { + foreach_instr (instr, &block->instr_list) { + if (is_tex_or_prefetch(instr)) + return true; + + if (is_load(instr)) { + switch (instr->opc) { + case OPC_LDLV: + case OPC_LDL: + case OPC_LDLW: + break; + default: + return true; + } + } + } + } + + return false; +} + +/* ************************************************************************* */ +/* instruction helpers */ + +/* creates SSA src of correct type (ie. half vs full precision) */ +static inline struct ir3_register * __ssa_src(struct ir3_instruction *instr, + struct ir3_instruction *src, unsigned flags) +{ + struct ir3_register *reg; + if (src->regs[0]->flags & IR3_REG_HALF) + flags |= IR3_REG_HALF; + reg = ir3_reg_create(instr, 0, IR3_REG_SSA | flags); + reg->instr = src; + reg->wrmask = src->regs[0]->wrmask; + return reg; +} + +static inline struct ir3_register * __ssa_dst(struct ir3_instruction *instr) +{ + struct ir3_register *reg = ir3_reg_create(instr, 0, 0); + reg->flags |= IR3_REG_SSA; + return reg; +} + +static inline struct ir3_instruction * +create_immed_typed(struct ir3_block *block, uint32_t val, type_t type) +{ + struct ir3_instruction *mov; + unsigned flags = (type_size(type) < 32) ? IR3_REG_HALF : 0; + + mov = ir3_instr_create(block, OPC_MOV); + mov->cat1.src_type = type; + mov->cat1.dst_type = type; + __ssa_dst(mov)->flags |= flags; + ir3_reg_create(mov, 0, IR3_REG_IMMED | flags)->uim_val = val; + + return mov; +} + +static inline struct ir3_instruction * +create_immed(struct ir3_block *block, uint32_t val) +{ + return create_immed_typed(block, val, TYPE_U32); +} + +static inline struct ir3_instruction * +create_uniform_typed(struct ir3_block *block, unsigned n, type_t type) +{ + struct ir3_instruction *mov; + unsigned flags = (type_size(type) < 32) ? IR3_REG_HALF : 0; + + mov = ir3_instr_create(block, OPC_MOV); + mov->cat1.src_type = type; + mov->cat1.dst_type = type; + __ssa_dst(mov)->flags |= flags; + ir3_reg_create(mov, n, IR3_REG_CONST | flags); + + return mov; +} + +static inline struct ir3_instruction * +create_uniform(struct ir3_block *block, unsigned n) +{ + return create_uniform_typed(block, n, TYPE_F32); +} + +static inline struct ir3_instruction * +create_uniform_indirect(struct ir3_block *block, int n, + struct ir3_instruction *address) +{ + struct ir3_instruction *mov; + + mov = ir3_instr_create(block, OPC_MOV); + mov->cat1.src_type = TYPE_U32; + mov->cat1.dst_type = TYPE_U32; + __ssa_dst(mov); + ir3_reg_create(mov, 0, IR3_REG_CONST | IR3_REG_RELATIV)->array.offset = n; + + ir3_instr_set_address(mov, address); + + return mov; +} + +static inline struct ir3_instruction * +ir3_MOV(struct ir3_block *block, struct ir3_instruction *src, type_t type) +{ + struct ir3_instruction *instr = ir3_instr_create(block, OPC_MOV); + __ssa_dst(instr); + if (src->regs[0]->flags & IR3_REG_ARRAY) { + struct ir3_register *src_reg = __ssa_src(instr, src, IR3_REG_ARRAY); + src_reg->array = src->regs[0]->array; + } else { + __ssa_src(instr, src, src->regs[0]->flags & IR3_REG_HIGH); + } + debug_assert(!(src->regs[0]->flags & IR3_REG_RELATIV)); + instr->cat1.src_type = type; + instr->cat1.dst_type = type; + return instr; +} + +static inline struct ir3_instruction * +ir3_COV(struct ir3_block *block, struct ir3_instruction *src, + type_t src_type, type_t dst_type) +{ + struct ir3_instruction *instr = ir3_instr_create(block, OPC_MOV); + unsigned dst_flags = (type_size(dst_type) < 32) ? IR3_REG_HALF : 0; + unsigned src_flags = (type_size(src_type) < 32) ? IR3_REG_HALF : 0; + + debug_assert((src->regs[0]->flags & IR3_REG_HALF) == src_flags); + + __ssa_dst(instr)->flags |= dst_flags; + __ssa_src(instr, src, 0); + instr->cat1.src_type = src_type; + instr->cat1.dst_type = dst_type; + debug_assert(!(src->regs[0]->flags & IR3_REG_ARRAY)); + return instr; +} + +static inline struct ir3_instruction * +ir3_NOP(struct ir3_block *block) +{ + return ir3_instr_create(block, OPC_NOP); +} + +#define IR3_INSTR_0 0 + +#define __INSTR0(flag, name, opc) \ +static inline struct ir3_instruction * \ +ir3_##name(struct ir3_block *block) \ +{ \ + struct ir3_instruction *instr = \ + ir3_instr_create(block, opc); \ + instr->flags |= flag; \ + return instr; \ +} +#define INSTR0F(f, name) __INSTR0(IR3_INSTR_##f, name##_##f, OPC_##name) +#define INSTR0(name) __INSTR0(0, name, OPC_##name) + +#define __INSTR1(flag, name, opc) \ +static inline struct ir3_instruction * \ +ir3_##name(struct ir3_block *block, \ + struct ir3_instruction *a, unsigned aflags) \ +{ \ + struct ir3_instruction *instr = \ + ir3_instr_create(block, opc); \ + __ssa_dst(instr); \ + __ssa_src(instr, a, aflags); \ + instr->flags |= flag; \ + return instr; \ +} +#define INSTR1F(f, name) __INSTR1(IR3_INSTR_##f, name##_##f, OPC_##name) +#define INSTR1(name) __INSTR1(0, name, OPC_##name) + +#define __INSTR2(flag, name, opc) \ +static inline struct ir3_instruction * \ +ir3_##name(struct ir3_block *block, \ + struct ir3_instruction *a, unsigned aflags, \ + struct ir3_instruction *b, unsigned bflags) \ +{ \ + struct ir3_instruction *instr = \ + ir3_instr_create(block, opc); \ + __ssa_dst(instr); \ + __ssa_src(instr, a, aflags); \ + __ssa_src(instr, b, bflags); \ + instr->flags |= flag; \ + return instr; \ +} +#define INSTR2F(f, name) __INSTR2(IR3_INSTR_##f, name##_##f, OPC_##name) +#define INSTR2(name) __INSTR2(0, name, OPC_##name) + +#define __INSTR3(flag, name, opc) \ +static inline struct ir3_instruction * \ +ir3_##name(struct ir3_block *block, \ + struct ir3_instruction *a, unsigned aflags, \ + struct ir3_instruction *b, unsigned bflags, \ + struct ir3_instruction *c, unsigned cflags) \ +{ \ + struct ir3_instruction *instr = \ + ir3_instr_create2(block, opc, 4); \ + __ssa_dst(instr); \ + __ssa_src(instr, a, aflags); \ + __ssa_src(instr, b, bflags); \ + __ssa_src(instr, c, cflags); \ + instr->flags |= flag; \ + return instr; \ +} +#define INSTR3F(f, name) __INSTR3(IR3_INSTR_##f, name##_##f, OPC_##name) +#define INSTR3(name) __INSTR3(0, name, OPC_##name) + +#define __INSTR4(flag, name, opc) \ +static inline struct ir3_instruction * \ +ir3_##name(struct ir3_block *block, \ + struct ir3_instruction *a, unsigned aflags, \ + struct ir3_instruction *b, unsigned bflags, \ + struct ir3_instruction *c, unsigned cflags, \ + struct ir3_instruction *d, unsigned dflags) \ +{ \ + struct ir3_instruction *instr = \ + ir3_instr_create2(block, opc, 5); \ + __ssa_dst(instr); \ + __ssa_src(instr, a, aflags); \ + __ssa_src(instr, b, bflags); \ + __ssa_src(instr, c, cflags); \ + __ssa_src(instr, d, dflags); \ + instr->flags |= flag; \ + return instr; \ +} +#define INSTR4F(f, name) __INSTR4(IR3_INSTR_##f, name##_##f, OPC_##name) +#define INSTR4(name) __INSTR4(0, name, OPC_##name) + +/* cat0 instructions: */ +INSTR1(B) +INSTR0(JUMP) +INSTR1(KILL) +INSTR0(END) +INSTR0(CHSH) +INSTR0(CHMASK) +INSTR1(PREDT) +INSTR0(PREDF) +INSTR0(PREDE) + +/* cat2 instructions, most 2 src but some 1 src: */ +INSTR2(ADD_F) +INSTR2(MIN_F) +INSTR2(MAX_F) +INSTR2(MUL_F) +INSTR1(SIGN_F) +INSTR2(CMPS_F) +INSTR1(ABSNEG_F) +INSTR2(CMPV_F) +INSTR1(FLOOR_F) +INSTR1(CEIL_F) +INSTR1(RNDNE_F) +INSTR1(RNDAZ_F) +INSTR1(TRUNC_F) +INSTR2(ADD_U) +INSTR2(ADD_S) +INSTR2(SUB_U) +INSTR2(SUB_S) +INSTR2(CMPS_U) +INSTR2(CMPS_S) +INSTR2(MIN_U) +INSTR2(MIN_S) +INSTR2(MAX_U) +INSTR2(MAX_S) +INSTR1(ABSNEG_S) +INSTR2(AND_B) +INSTR2(OR_B) +INSTR1(NOT_B) +INSTR2(XOR_B) +INSTR2(CMPV_U) +INSTR2(CMPV_S) +INSTR2(MUL_U24) +INSTR2(MUL_S24) +INSTR2(MULL_U) +INSTR1(BFREV_B) +INSTR1(CLZ_S) +INSTR1(CLZ_B) +INSTR2(SHL_B) +INSTR2(SHR_B) +INSTR2(ASHR_B) +INSTR2(BARY_F) +INSTR2(MGEN_B) +INSTR2(GETBIT_B) +INSTR1(SETRM) +INSTR1(CBITS_B) +INSTR2(SHB) +INSTR2(MSAD) + +/* cat3 instructions: */ +INSTR3(MAD_U16) +INSTR3(MADSH_U16) +INSTR3(MAD_S16) +INSTR3(MADSH_M16) +INSTR3(MAD_U24) +INSTR3(MAD_S24) +INSTR3(MAD_F16) +INSTR3(MAD_F32) +/* NOTE: SEL_B32 checks for zero vs nonzero */ +INSTR3(SEL_B16) +INSTR3(SEL_B32) +INSTR3(SEL_S16) +INSTR3(SEL_S32) +INSTR3(SEL_F16) +INSTR3(SEL_F32) +INSTR3(SAD_S16) +INSTR3(SAD_S32) + +/* cat4 instructions: */ +INSTR1(RCP) +INSTR1(RSQ) +INSTR1(HRSQ) +INSTR1(LOG2) +INSTR1(HLOG2) +INSTR1(EXP2) +INSTR1(HEXP2) +INSTR1(SIN) +INSTR1(COS) +INSTR1(SQRT) + +/* cat5 instructions: */ +INSTR1(DSX) +INSTR1(DSXPP_1) +INSTR1(DSY) +INSTR1(DSYPP_1) +INSTR1F(3D, DSX) +INSTR1F(3D, DSY) +INSTR1(RGETPOS) + +static inline struct ir3_instruction * +ir3_SAM(struct ir3_block *block, opc_t opc, type_t type, + unsigned wrmask, unsigned flags, struct ir3_instruction *samp_tex, + struct ir3_instruction *src0, struct ir3_instruction *src1) +{ + struct ir3_instruction *sam; + + sam = ir3_instr_create(block, opc); + sam->flags |= flags; + __ssa_dst(sam)->wrmask = wrmask; + if (flags & IR3_INSTR_S2EN) { + __ssa_src(sam, samp_tex, IR3_REG_HALF); + } + if (src0) { + __ssa_src(sam, src0, 0); + } + if (src1) { + __ssa_src(sam, src1, 0); + } + sam->cat5.type = type; + + return sam; +} + +/* cat6 instructions: */ +INSTR2(LDLV) +INSTR3(LDG) +INSTR3(LDL) +INSTR3(LDLW) +INSTR3(STG) +INSTR3(STL) +INSTR3(STLW) +INSTR1(RESINFO) +INSTR1(RESFMT) +INSTR2(ATOMIC_ADD) +INSTR2(ATOMIC_SUB) +INSTR2(ATOMIC_XCHG) +INSTR2(ATOMIC_INC) +INSTR2(ATOMIC_DEC) +INSTR2(ATOMIC_CMPXCHG) +INSTR2(ATOMIC_MIN) +INSTR2(ATOMIC_MAX) +INSTR2(ATOMIC_AND) +INSTR2(ATOMIC_OR) +INSTR2(ATOMIC_XOR) +INSTR2(LDC) +#if GPU >= 600 +INSTR3(STIB); +INSTR2(LDIB); +INSTR3F(G, ATOMIC_ADD) +INSTR3F(G, ATOMIC_SUB) +INSTR3F(G, ATOMIC_XCHG) +INSTR3F(G, ATOMIC_INC) +INSTR3F(G, ATOMIC_DEC) +INSTR3F(G, ATOMIC_CMPXCHG) +INSTR3F(G, ATOMIC_MIN) +INSTR3F(G, ATOMIC_MAX) +INSTR3F(G, ATOMIC_AND) +INSTR3F(G, ATOMIC_OR) +INSTR3F(G, ATOMIC_XOR) +#elif GPU >= 400 +INSTR3(LDGB) +INSTR4(STGB) +INSTR4(STIB) +INSTR4F(G, ATOMIC_ADD) +INSTR4F(G, ATOMIC_SUB) +INSTR4F(G, ATOMIC_XCHG) +INSTR4F(G, ATOMIC_INC) +INSTR4F(G, ATOMIC_DEC) +INSTR4F(G, ATOMIC_CMPXCHG) +INSTR4F(G, ATOMIC_MIN) +INSTR4F(G, ATOMIC_MAX) +INSTR4F(G, ATOMIC_AND) +INSTR4F(G, ATOMIC_OR) +INSTR4F(G, ATOMIC_XOR) +#endif + +INSTR4F(G, STG) + +/* cat7 instructions: */ +INSTR0(BAR) +INSTR0(FENCE) + +/* meta instructions: */ +INSTR0(META_TEX_PREFETCH); + +/* ************************************************************************* */ +/* split this out or find some helper to use.. like main/bitset.h.. */ + +#include +#include "util/bitset.h" + +#define MAX_REG 256 + +typedef BITSET_DECLARE(regmask_t, 2 * MAX_REG); + +static inline bool +__regmask_get(regmask_t *regmask, struct ir3_register *reg, unsigned n) +{ + if (reg->merged) { + /* a6xx+ case, with merged register file, we track things in terms + * of half-precision registers, with a full precisions register + * using two half-precision slots: + */ + if (reg->flags & IR3_REG_HALF) { + return BITSET_TEST(*regmask, n); + } else { + n *= 2; + return BITSET_TEST(*regmask, n) || BITSET_TEST(*regmask, n+1); + } + } else { + /* pre a6xx case, with separate register file for half and full + * precision: + */ + if (reg->flags & IR3_REG_HALF) + n += MAX_REG; + return BITSET_TEST(*regmask, n); + } +} + +static inline void +__regmask_set(regmask_t *regmask, struct ir3_register *reg, unsigned n) +{ + if (reg->merged) { + /* a6xx+ case, with merged register file, we track things in terms + * of half-precision registers, with a full precisions register + * using two half-precision slots: + */ + if (reg->flags & IR3_REG_HALF) { + BITSET_SET(*regmask, n); + } else { + n *= 2; + BITSET_SET(*regmask, n); + BITSET_SET(*regmask, n+1); + } + } else { + /* pre a6xx case, with separate register file for half and full + * precision: + */ + if (reg->flags & IR3_REG_HALF) + n += MAX_REG; + BITSET_SET(*regmask, n); + } +} + +static inline void regmask_init(regmask_t *regmask) +{ + memset(regmask, 0, sizeof(*regmask)); +} + +static inline void regmask_set(regmask_t *regmask, struct ir3_register *reg) +{ + if (reg->flags & IR3_REG_RELATIV) { + for (unsigned i = 0; i < reg->size; i++) + __regmask_set(regmask, reg, reg->array.offset + i); + } else { + for (unsigned mask = reg->wrmask, n = reg->num; mask; mask >>= 1, n++) + if (mask & 1) + __regmask_set(regmask, reg, n); + } +} + +static inline void regmask_or(regmask_t *dst, regmask_t *a, regmask_t *b) +{ + unsigned i; + for (i = 0; i < ARRAY_SIZE(*dst); i++) + (*dst)[i] = (*a)[i] | (*b)[i]; +} + +static inline bool regmask_get(regmask_t *regmask, + struct ir3_register *reg) +{ + if (reg->flags & IR3_REG_RELATIV) { + for (unsigned i = 0; i < reg->size; i++) + if (__regmask_get(regmask, reg, reg->array.offset + i)) + return true; + } else { + for (unsigned mask = reg->wrmask, n = reg->num; mask; mask >>= 1, n++) + if (mask & 1) + if (__regmask_get(regmask, reg, n)) + return true; + } + return false; +} + +/* ************************************************************************* */ + +#endif /* IR3_H_ */ diff --git a/selfdrive/modeld/thneed/debug/decompiler/shader_enums.h b/selfdrive/modeld/thneed/debug/decompiler/shader_enums.h new file mode 100644 index 0000000000..b33a91727a --- /dev/null +++ b/selfdrive/modeld/thneed/debug/decompiler/shader_enums.h @@ -0,0 +1,906 @@ +/* + * Mesa 3-D graphics library + * + * Copyright (C) 1999-2008 Brian Paul All Rights Reserved. + * Copyright (C) 2009 VMware, Inc. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS + * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR + * OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, + * ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR + * OTHER DEALINGS IN THE SOFTWARE. + */ + +#ifndef SHADER_ENUMS_H +#define SHADER_ENUMS_H + +#include + +/* Project-wide (GL and Vulkan) maximum. */ +#define MAX_DRAW_BUFFERS 8 + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Shader stages. + * + * The order must match how shaders are ordered in the pipeline. + * The GLSL linker assumes that if i is the maximum number of + * invocations in a sub-group. The maximum + * supported in this extension is 64." + * + * The spec defines this as a uniform. However, it's highly unlikely that + * implementations actually treat it as a uniform (which is loaded from a + * constant buffer). Most likely, this is an implementation-wide constant, + * or perhaps something that depends on the shader stage. + */ + SYSTEM_VALUE_SUBGROUP_SIZE, + + /** + * From the GL_ARB_shader_ballot spec: + * + * "The variable holds the index of the + * invocation within sub-group. This variable is in the range 0 to + * -1, where is the total + * number of invocations in a sub-group." + */ + SYSTEM_VALUE_SUBGROUP_INVOCATION, + + /** + * From the GL_ARB_shader_ballot spec: + * + * "The variables provide a bitmask for all + * invocations, with one bit per invocation starting with the least + * significant bit, according to the following table, + * + * variable equation for bit values + * -------------------- ------------------------------------ + * gl_SubGroupEqMaskARB bit index == gl_SubGroupInvocationARB + * gl_SubGroupGeMaskARB bit index >= gl_SubGroupInvocationARB + * gl_SubGroupGtMaskARB bit index > gl_SubGroupInvocationARB + * gl_SubGroupLeMaskARB bit index <= gl_SubGroupInvocationARB + * gl_SubGroupLtMaskARB bit index < gl_SubGroupInvocationARB + */ + SYSTEM_VALUE_SUBGROUP_EQ_MASK, + SYSTEM_VALUE_SUBGROUP_GE_MASK, + SYSTEM_VALUE_SUBGROUP_GT_MASK, + SYSTEM_VALUE_SUBGROUP_LE_MASK, + SYSTEM_VALUE_SUBGROUP_LT_MASK, + /*@}*/ + + /** + * Builtin variables added by VK_KHR_subgroups + */ + /*@{*/ + SYSTEM_VALUE_NUM_SUBGROUPS, + SYSTEM_VALUE_SUBGROUP_ID, + /*@}*/ + + /*@}*/ + + /** + * \name Vertex shader system values + */ + /*@{*/ + /** + * OpenGL-style vertex ID. + * + * Section 2.11.7 (Shader Execution), subsection Shader Inputs, of the + * OpenGL 3.3 core profile spec says: + * + * "gl_VertexID holds the integer index i implicitly passed by + * DrawArrays or one of the other drawing commands defined in section + * 2.8.3." + * + * Section 2.8.3 (Drawing Commands) of the same spec says: + * + * "The commands....are equivalent to the commands with the same base + * name (without the BaseVertex suffix), except that the ith element + * transferred by the corresponding draw call will be taken from + * element indices[i] + basevertex of each enabled array." + * + * Additionally, the overview in the GL_ARB_shader_draw_parameters spec + * says: + * + * "In unextended GL, vertex shaders have inputs named gl_VertexID and + * gl_InstanceID, which contain, respectively the index of the vertex + * and instance. The value of gl_VertexID is the implicitly passed + * index of the vertex being processed, which includes the value of + * baseVertex, for those commands that accept it." + * + * gl_VertexID gets basevertex added in. This differs from DirectX where + * SV_VertexID does \b not get basevertex added in. + * + * \note + * If all system values are available, \c SYSTEM_VALUE_VERTEX_ID will be + * equal to \c SYSTEM_VALUE_VERTEX_ID_ZERO_BASE plus + * \c SYSTEM_VALUE_BASE_VERTEX. + * + * \sa SYSTEM_VALUE_VERTEX_ID_ZERO_BASE, SYSTEM_VALUE_BASE_VERTEX + */ + SYSTEM_VALUE_VERTEX_ID, + + /** + * Instanced ID as supplied to gl_InstanceID + * + * Values assigned to gl_InstanceID always begin with zero, regardless of + * the value of baseinstance. + * + * Section 11.1.3.9 (Shader Inputs) of the OpenGL 4.4 core profile spec + * says: + * + * "gl_InstanceID holds the integer instance number of the current + * primitive in an instanced draw call (see section 10.5)." + * + * Through a big chain of pseudocode, section 10.5 describes that + * baseinstance is not counted by gl_InstanceID. In that section, notice + * + * "If an enabled vertex attribute array is instanced (it has a + * non-zero divisor as specified by VertexAttribDivisor), the element + * index that is transferred to the GL, for all vertices, is given by + * + * floor(instance/divisor) + baseinstance + * + * If an array corresponding to an attribute required by a vertex + * shader is not enabled, then the corresponding element is taken from + * the current attribute state (see section 10.2)." + * + * Note that baseinstance is \b not included in the value of instance. + */ + SYSTEM_VALUE_INSTANCE_ID, + + /** + * Vulkan InstanceIndex. + * + * InstanceIndex = gl_InstanceID + gl_BaseInstance + */ + SYSTEM_VALUE_INSTANCE_INDEX, + + /** + * DirectX-style vertex ID. + * + * Unlike \c SYSTEM_VALUE_VERTEX_ID, this system value does \b not include + * the value of basevertex. + * + * \sa SYSTEM_VALUE_VERTEX_ID, SYSTEM_VALUE_BASE_VERTEX + */ + SYSTEM_VALUE_VERTEX_ID_ZERO_BASE, + + /** + * Value of \c basevertex passed to \c glDrawElementsBaseVertex and similar + * functions. + * + * \sa SYSTEM_VALUE_VERTEX_ID, SYSTEM_VALUE_VERTEX_ID_ZERO_BASE + */ + SYSTEM_VALUE_BASE_VERTEX, + + /** + * Depending on the type of the draw call (indexed or non-indexed), + * is the value of \c basevertex passed to \c glDrawElementsBaseVertex and + * similar, or is the value of \c first passed to \c glDrawArrays and + * similar. + * + * \note + * It can be used to calculate the \c SYSTEM_VALUE_VERTEX_ID as + * \c SYSTEM_VALUE_VERTEX_ID_ZERO_BASE plus \c SYSTEM_VALUE_FIRST_VERTEX. + * + * \sa SYSTEM_VALUE_VERTEX_ID_ZERO_BASE, SYSTEM_VALUE_VERTEX_ID + */ + SYSTEM_VALUE_FIRST_VERTEX, + + /** + * If the Draw command used to start the rendering was an indexed draw + * or not (~0/0). Useful to calculate \c SYSTEM_VALUE_BASE_VERTEX as + * \c SYSTEM_VALUE_IS_INDEXED_DRAW & \c SYSTEM_VALUE_FIRST_VERTEX. + */ + SYSTEM_VALUE_IS_INDEXED_DRAW, + + /** + * Value of \c baseinstance passed to instanced draw entry points + * + * \sa SYSTEM_VALUE_INSTANCE_ID + */ + SYSTEM_VALUE_BASE_INSTANCE, + + /** + * From _ARB_shader_draw_parameters: + * + * "Additionally, this extension adds a further built-in variable, + * gl_DrawID to the shading language. This variable contains the index + * of the draw currently being processed by a Multi* variant of a + * drawing command (such as MultiDrawElements or + * MultiDrawArraysIndirect)." + * + * If GL_ARB_multi_draw_indirect is not supported, this is always 0. + */ + SYSTEM_VALUE_DRAW_ID, + /*@}*/ + + /** + * \name Geometry shader system values + */ + /*@{*/ + SYSTEM_VALUE_INVOCATION_ID, /**< (Also in Tessellation Control shader) */ + /*@}*/ + + /** + * \name Fragment shader system values + */ + /*@{*/ + SYSTEM_VALUE_FRAG_COORD, + SYSTEM_VALUE_POINT_COORD, + SYSTEM_VALUE_FRONT_FACE, + SYSTEM_VALUE_SAMPLE_ID, + SYSTEM_VALUE_SAMPLE_POS, + SYSTEM_VALUE_SAMPLE_MASK_IN, + SYSTEM_VALUE_HELPER_INVOCATION, + SYSTEM_VALUE_COLOR0, + SYSTEM_VALUE_COLOR1, + /*@}*/ + + /** + * \name Tessellation Evaluation shader system values + */ + /*@{*/ + SYSTEM_VALUE_TESS_COORD, + SYSTEM_VALUE_VERTICES_IN, /**< Tessellation vertices in input patch */ + SYSTEM_VALUE_PRIMITIVE_ID, + SYSTEM_VALUE_TESS_LEVEL_OUTER, /**< TES input */ + SYSTEM_VALUE_TESS_LEVEL_INNER, /**< TES input */ + SYSTEM_VALUE_TESS_LEVEL_OUTER_DEFAULT, /**< TCS input for passthru TCS */ + SYSTEM_VALUE_TESS_LEVEL_INNER_DEFAULT, /**< TCS input for passthru TCS */ + /*@}*/ + + /** + * \name Compute shader system values + */ + /*@{*/ + SYSTEM_VALUE_LOCAL_INVOCATION_ID, + SYSTEM_VALUE_LOCAL_INVOCATION_INDEX, + SYSTEM_VALUE_GLOBAL_INVOCATION_ID, + SYSTEM_VALUE_GLOBAL_INVOCATION_INDEX, + SYSTEM_VALUE_WORK_GROUP_ID, + SYSTEM_VALUE_NUM_WORK_GROUPS, + SYSTEM_VALUE_LOCAL_GROUP_SIZE, + SYSTEM_VALUE_GLOBAL_GROUP_SIZE, + SYSTEM_VALUE_WORK_DIM, + SYSTEM_VALUE_USER_DATA_AMD, + /*@}*/ + + /** Required for VK_KHR_device_group */ + SYSTEM_VALUE_DEVICE_INDEX, + + /** Required for VK_KHX_multiview */ + SYSTEM_VALUE_VIEW_INDEX, + + /** + * Driver internal vertex-count, used (for example) for drivers to + * calculate stride for stream-out outputs. Not externally visible. + */ + SYSTEM_VALUE_VERTEX_CNT, + + /** + * Required for AMD_shader_explicit_vertex_parameter and also used for + * varying-fetch instructions. + * + * The _SIZE value is "primitive size", used to scale i/j in primitive + * space to pixel space. + */ + SYSTEM_VALUE_BARYCENTRIC_PERSP_PIXEL, + SYSTEM_VALUE_BARYCENTRIC_PERSP_SAMPLE, + SYSTEM_VALUE_BARYCENTRIC_PERSP_CENTROID, + SYSTEM_VALUE_BARYCENTRIC_PERSP_SIZE, + SYSTEM_VALUE_BARYCENTRIC_LINEAR_PIXEL, + SYSTEM_VALUE_BARYCENTRIC_LINEAR_CENTROID, + SYSTEM_VALUE_BARYCENTRIC_LINEAR_SAMPLE, + SYSTEM_VALUE_BARYCENTRIC_PULL_MODEL, + + /** + * IR3 specific geometry shader and tesselation control shader system + * values that packs invocation id, thread id and vertex id. Having this + * as a nir level system value lets us do the unpacking in nir. + */ + SYSTEM_VALUE_GS_HEADER_IR3, + SYSTEM_VALUE_TCS_HEADER_IR3, + + SYSTEM_VALUE_MAX /**< Number of values */ +} gl_system_value; + +const char *gl_system_value_name(gl_system_value sysval); + +/** + * The possible interpolation qualifiers that can be applied to a fragment + * shader input in GLSL. + * + * Note: INTERP_MODE_NONE must be 0 so that memsetting the + * ir_variable data structure to 0 causes the default behavior. + */ +enum glsl_interp_mode +{ + INTERP_MODE_NONE = 0, + INTERP_MODE_SMOOTH, + INTERP_MODE_FLAT, + INTERP_MODE_NOPERSPECTIVE, + INTERP_MODE_EXPLICIT, + INTERP_MODE_COUNT /**< Number of interpolation qualifiers */ +}; + +enum glsl_interface_packing { + GLSL_INTERFACE_PACKING_STD140, + GLSL_INTERFACE_PACKING_SHARED, + GLSL_INTERFACE_PACKING_PACKED, + GLSL_INTERFACE_PACKING_STD430 +}; + +const char *glsl_interp_mode_name(enum glsl_interp_mode qual); + +/** + * Fragment program results + */ +typedef enum +{ + FRAG_RESULT_DEPTH = 0, + FRAG_RESULT_STENCIL = 1, + /* If a single color should be written to all render targets, this + * register is written. No FRAG_RESULT_DATAn will be written. + */ + FRAG_RESULT_COLOR = 2, + FRAG_RESULT_SAMPLE_MASK = 3, + + /* FRAG_RESULT_DATAn are the per-render-target (GLSL gl_FragData[n] + * or ARB_fragment_program fragment.color[n]) color results. If + * any are written, FRAG_RESULT_COLOR will not be written. + * FRAG_RESULT_DATA1 and up are simply for the benefit of + * gl_frag_result_name() and not to be construed as an upper bound + */ + FRAG_RESULT_DATA0 = 4, + FRAG_RESULT_DATA1, + FRAG_RESULT_DATA2, + FRAG_RESULT_DATA3, + FRAG_RESULT_DATA4, + FRAG_RESULT_DATA5, + FRAG_RESULT_DATA6, + FRAG_RESULT_DATA7, +} gl_frag_result; + +const char *gl_frag_result_name(gl_frag_result result); + +#define FRAG_RESULT_MAX (FRAG_RESULT_DATA0 + MAX_DRAW_BUFFERS) + +/** + * \brief Layout qualifiers for gl_FragDepth. + * + * Extension AMD_conservative_depth allows gl_FragDepth to be redeclared with + * a layout qualifier. + * + * \see enum ir_depth_layout + */ +enum gl_frag_depth_layout +{ + FRAG_DEPTH_LAYOUT_NONE, /**< No layout is specified. */ + FRAG_DEPTH_LAYOUT_ANY, + FRAG_DEPTH_LAYOUT_GREATER, + FRAG_DEPTH_LAYOUT_LESS, + FRAG_DEPTH_LAYOUT_UNCHANGED +}; + +/** + * \brief Buffer access qualifiers + */ +enum gl_access_qualifier +{ + ACCESS_COHERENT = (1 << 0), + ACCESS_RESTRICT = (1 << 1), + ACCESS_VOLATILE = (1 << 2), + ACCESS_NON_READABLE = (1 << 3), + ACCESS_NON_WRITEABLE = (1 << 4), + + /** The access may use a non-uniform buffer or image index */ + ACCESS_NON_UNIFORM = (1 << 5), + + /* This has the same semantics as NIR_INTRINSIC_CAN_REORDER, only to be + * used with loads. In other words, it means that the load can be + * arbitrarily reordered, or combined with other loads to the same address. + * It is implied by ACCESS_NON_WRITEABLE together with ACCESS_RESTRICT, and + * a lack of ACCESS_COHERENT and ACCESS_VOLATILE. + */ + ACCESS_CAN_REORDER = (1 << 6), + + /** Use as little cache space as possible. */ + ACCESS_STREAM_CACHE_POLICY = (1 << 7), +}; + +/** + * \brief Blend support qualifiers + */ +enum gl_advanced_blend_mode +{ + BLEND_NONE = 0x0000, + + BLEND_MULTIPLY = 0x0001, + BLEND_SCREEN = 0x0002, + BLEND_OVERLAY = 0x0004, + BLEND_DARKEN = 0x0008, + BLEND_LIGHTEN = 0x0010, + BLEND_COLORDODGE = 0x0020, + BLEND_COLORBURN = 0x0040, + BLEND_HARDLIGHT = 0x0080, + BLEND_SOFTLIGHT = 0x0100, + BLEND_DIFFERENCE = 0x0200, + BLEND_EXCLUSION = 0x0400, + BLEND_HSL_HUE = 0x0800, + BLEND_HSL_SATURATION = 0x1000, + BLEND_HSL_COLOR = 0x2000, + BLEND_HSL_LUMINOSITY = 0x4000, + + BLEND_ALL = 0x7fff, +}; + +enum blend_func +{ + BLEND_FUNC_ADD, + BLEND_FUNC_SUBTRACT, + BLEND_FUNC_REVERSE_SUBTRACT, + BLEND_FUNC_MIN, + BLEND_FUNC_MAX, +}; + +enum blend_factor +{ + BLEND_FACTOR_ZERO, + BLEND_FACTOR_SRC_COLOR, + BLEND_FACTOR_DST_COLOR, + BLEND_FACTOR_SRC_ALPHA, + BLEND_FACTOR_DST_ALPHA, + BLEND_FACTOR_CONSTANT_COLOR, + BLEND_FACTOR_CONSTANT_ALPHA, + BLEND_FACTOR_SRC_ALPHA_SATURATE, +}; + +enum gl_tess_spacing +{ + TESS_SPACING_UNSPECIFIED, + TESS_SPACING_EQUAL, + TESS_SPACING_FRACTIONAL_ODD, + TESS_SPACING_FRACTIONAL_EVEN, +}; + +/** + * A compare function enum for use in compiler lowering passes. This is in + * the same order as GL's compare functions (shifted down by GL_NEVER), and is + * exactly the same as gallium's PIPE_FUNC_*. + */ +enum compare_func +{ + COMPARE_FUNC_NEVER, + COMPARE_FUNC_LESS, + COMPARE_FUNC_EQUAL, + COMPARE_FUNC_LEQUAL, + COMPARE_FUNC_GREATER, + COMPARE_FUNC_NOTEQUAL, + COMPARE_FUNC_GEQUAL, + COMPARE_FUNC_ALWAYS, +}; + +/** + * Arrangements for grouping invocations from NV_compute_shader_derivatives. + * + * The extension provides new layout qualifiers that support two different + * arrangements of compute shader invocations for the purpose of derivative + * computation. When specifying + * + * layout(derivative_group_quadsNV) in; + * + * compute shader invocations are grouped into 2x2x1 arrays whose four local + * invocation ID values follow the pattern: + * + * +-----------------+------------------+ + * | (2x+0, 2y+0, z) | (2x+1, 2y+0, z) | + * +-----------------+------------------+ + * | (2x+0, 2y+1, z) | (2x+1, 2y+1, z) | + * +-----------------+------------------+ + * + * where Y increases from bottom to top. When specifying + * + * layout(derivative_group_linearNV) in; + * + * compute shader invocations are grouped into 2x2x1 arrays whose four local + * invocation index values follow the pattern: + * + * +------+------+ + * | 4n+0 | 4n+1 | + * +------+------+ + * | 4n+2 | 4n+3 | + * +------+------+ + * + * If neither layout qualifier is specified, derivatives in compute shaders + * return zero, which is consistent with the handling of built-in texture + * functions like texture() in GLSL 4.50 compute shaders. + */ +enum gl_derivative_group { + DERIVATIVE_GROUP_NONE = 0, + DERIVATIVE_GROUP_QUADS, + DERIVATIVE_GROUP_LINEAR, +}; + +enum float_controls +{ + FLOAT_CONTROLS_DEFAULT_FLOAT_CONTROL_MODE = 0x0000, + FLOAT_CONTROLS_DENORM_PRESERVE_FP16 = 0x0001, + FLOAT_CONTROLS_DENORM_PRESERVE_FP32 = 0x0002, + FLOAT_CONTROLS_DENORM_PRESERVE_FP64 = 0x0004, + FLOAT_CONTROLS_DENORM_FLUSH_TO_ZERO_FP16 = 0x0008, + FLOAT_CONTROLS_DENORM_FLUSH_TO_ZERO_FP32 = 0x0010, + FLOAT_CONTROLS_DENORM_FLUSH_TO_ZERO_FP64 = 0x0020, + FLOAT_CONTROLS_SIGNED_ZERO_INF_NAN_PRESERVE_FP16 = 0x0040, + FLOAT_CONTROLS_SIGNED_ZERO_INF_NAN_PRESERVE_FP32 = 0x0080, + FLOAT_CONTROLS_SIGNED_ZERO_INF_NAN_PRESERVE_FP64 = 0x0100, + FLOAT_CONTROLS_ROUNDING_MODE_RTE_FP16 = 0x0200, + FLOAT_CONTROLS_ROUNDING_MODE_RTE_FP32 = 0x0400, + FLOAT_CONTROLS_ROUNDING_MODE_RTE_FP64 = 0x0800, + FLOAT_CONTROLS_ROUNDING_MODE_RTZ_FP16 = 0x1000, + FLOAT_CONTROLS_ROUNDING_MODE_RTZ_FP32 = 0x2000, + FLOAT_CONTROLS_ROUNDING_MODE_RTZ_FP64 = 0x4000, +}; + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif /* SHADER_ENUMS_H */ diff --git a/selfdrive/modeld/thneed/debug/decompiler/util/bitset.h b/selfdrive/modeld/thneed/debug/decompiler/util/bitset.h new file mode 100644 index 0000000000..264144c39b --- /dev/null +++ b/selfdrive/modeld/thneed/debug/decompiler/util/bitset.h @@ -0,0 +1,261 @@ +/* + * Mesa 3-D graphics library + * + * Copyright (C) 2006 Brian Paul All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS + * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR + * OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, + * ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR + * OTHER DEALINGS IN THE SOFTWARE. + */ + +/** + * \file bitset.h + * \brief Bitset of arbitrary size definitions. + * \author Michal Krol + */ + +#ifndef BITSET_H +#define BITSET_H + +//#include "util/bitscan.h" +//#include "util/macros.h" + +/**************************************************************************** + * generic bitset implementation + */ + +#define BITSET_WORD unsigned int +#define BITSET_WORDBITS (sizeof (BITSET_WORD) * 8) + +/* bitset declarations + */ +#define BITSET_WORDS(bits) (((bits) + BITSET_WORDBITS - 1) / BITSET_WORDBITS) +#define BITSET_DECLARE(name, bits) BITSET_WORD name[BITSET_WORDS(bits)] + +/* bitset operations + */ +#define BITSET_COPY(x, y) memcpy( (x), (y), sizeof (x) ) +#define BITSET_EQUAL(x, y) (memcmp( (x), (y), sizeof (x) ) == 0) +#define BITSET_ZERO(x) memset( (x), 0, sizeof (x) ) +#define BITSET_ONES(x) memset( (x), 0xff, sizeof (x) ) + +#define BITSET_BITWORD(b) ((b) / BITSET_WORDBITS) +#define BITSET_BIT(b) (1u << ((b) % BITSET_WORDBITS)) + +/* single bit operations + */ +#define BITSET_TEST(x, b) (((x)[BITSET_BITWORD(b)] & BITSET_BIT(b)) != 0) +#define BITSET_SET(x, b) ((x)[BITSET_BITWORD(b)] |= BITSET_BIT(b)) +#define BITSET_CLEAR(x, b) ((x)[BITSET_BITWORD(b)] &= ~BITSET_BIT(b)) + +#define BITSET_MASK(b) (((b) % BITSET_WORDBITS == 0) ? ~0 : BITSET_BIT(b) - 1) +#define BITSET_RANGE(b, e) ((BITSET_MASK((e) + 1)) & ~(BITSET_BIT(b) - 1)) + +/* bit range operations + */ +#define BITSET_TEST_RANGE(x, b, e) \ + (BITSET_BITWORD(b) == BITSET_BITWORD(e) ? \ + (((x)[BITSET_BITWORD(b)] & BITSET_RANGE(b, e)) != 0) : \ + (assert (!"BITSET_TEST_RANGE: bit range crosses word boundary"), 0)) +#define BITSET_SET_RANGE(x, b, e) \ + (BITSET_BITWORD(b) == BITSET_BITWORD(e) ? \ + ((x)[BITSET_BITWORD(b)] |= BITSET_RANGE(b, e)) : \ + (assert (!"BITSET_SET_RANGE: bit range crosses word boundary"), 0)) +#define BITSET_CLEAR_RANGE(x, b, e) \ + (BITSET_BITWORD(b) == BITSET_BITWORD(e) ? \ + ((x)[BITSET_BITWORD(b)] &= ~BITSET_RANGE(b, e)) : \ + (assert (!"BITSET_CLEAR_RANGE: bit range crosses word boundary"), 0)) + +/* Get first bit set in a bitset. + */ +static inline int +__bitset_ffs(const BITSET_WORD *x, int n) +{ + int i; + + for (i = 0; i < n; i++) { + if (x[i]) + return ffs(x[i]) + BITSET_WORDBITS * i; + } + + return 0; +} + +#define BITSET_FFS(x) __bitset_ffs(x, ARRAY_SIZE(x)) + +static inline unsigned +__bitset_next_set(unsigned i, BITSET_WORD *tmp, + const BITSET_WORD *set, unsigned size) +{ + unsigned bit, word; + + /* NOTE: The initial conditions for this function are very specific. At + * the start of the loop, the tmp variable must be set to *set and the + * initial i value set to 0. This way, if there is a bit set in the first + * word, we ignore the i-value and just grab that bit (so 0 is ok, even + * though 0 may be returned). If the first word is 0, then the value of + * `word` will be 0 and we will go on to look at the second word. + */ + word = BITSET_BITWORD(i); + while (*tmp == 0) { + word++; + + if (word >= BITSET_WORDS(size)) + return size; + + *tmp = set[word]; + } + + /* Find the next set bit in the non-zero word */ + bit = ffs(*tmp) - 1; + + /* Unset the bit */ + *tmp &= ~(1ull << bit); + + return word * BITSET_WORDBITS + bit; +} + +/** + * Iterates over each set bit in a set + * + * @param __i iteration variable, bit number + * @param __set the bitset to iterate (will not be modified) + * @param __size number of bits in the set to consider + */ +#define BITSET_FOREACH_SET(__i, __set, __size) \ + for (BITSET_WORD __tmp = *(__set), *__foo = &__tmp; __foo != NULL; __foo = NULL) \ + for (__i = 0; \ + (__i = __bitset_next_set(__i, &__tmp, __set, __size)) < __size;) + +#ifdef __cplusplus + +/** + * Simple C++ wrapper of a bitset type of static size, with value semantics + * and basic bitwise arithmetic operators. The operators defined below are + * expected to have the same semantics as the same operator applied to other + * fundamental integer types. T is the name of the struct to instantiate + * it as, and N is the number of bits in the bitset. + */ +#define DECLARE_BITSET_T(T, N) struct T { \ + EXPLICIT_CONVERSION \ + operator bool() const \ + { \ + for (unsigned i = 0; i < BITSET_WORDS(N); i++) \ + if (words[i]) \ + return true; \ + return false; \ + } \ + \ + T & \ + operator=(int x) \ + { \ + const T c = {{ (BITSET_WORD)x }}; \ + return *this = c; \ + } \ + \ + friend bool \ + operator==(const T &b, const T &c) \ + { \ + return BITSET_EQUAL(b.words, c.words); \ + } \ + \ + friend bool \ + operator!=(const T &b, const T &c) \ + { \ + return !(b == c); \ + } \ + \ + friend bool \ + operator==(const T &b, int x) \ + { \ + const T c = {{ (BITSET_WORD)x }}; \ + return b == c; \ + } \ + \ + friend bool \ + operator!=(const T &b, int x) \ + { \ + return !(b == x); \ + } \ + \ + friend T \ + operator~(const T &b) \ + { \ + T c; \ + for (unsigned i = 0; i < BITSET_WORDS(N); i++) \ + c.words[i] = ~b.words[i]; \ + return c; \ + } \ + \ + T & \ + operator|=(const T &b) \ + { \ + for (unsigned i = 0; i < BITSET_WORDS(N); i++) \ + words[i] |= b.words[i]; \ + return *this; \ + } \ + \ + friend T \ + operator|(const T &b, const T &c) \ + { \ + T d = b; \ + d |= c; \ + return d; \ + } \ + \ + T & \ + operator&=(const T &b) \ + { \ + for (unsigned i = 0; i < BITSET_WORDS(N); i++) \ + words[i] &= b.words[i]; \ + return *this; \ + } \ + \ + friend T \ + operator&(const T &b, const T &c) \ + { \ + T d = b; \ + d &= c; \ + return d; \ + } \ + \ + bool \ + test(unsigned i) const \ + { \ + return BITSET_TEST(words, i); \ + } \ + \ + T & \ + set(unsigned i) \ + { \ + BITSET_SET(words, i); \ + return *this; \ + } \ + \ + T & \ + clear(unsigned i) \ + { \ + BITSET_CLEAR(words, i); \ + return *this; \ + } \ + \ + BITSET_WORD words[BITSET_WORDS(N)]; \ + } + +#endif + +#endif diff --git a/selfdrive/modeld/thneed/debug/decompiler/util/list.h b/selfdrive/modeld/thneed/debug/decompiler/util/list.h new file mode 100644 index 0000000000..7f36e8c39d --- /dev/null +++ b/selfdrive/modeld/thneed/debug/decompiler/util/list.h @@ -0,0 +1,262 @@ +/************************************************************************** + * + * Copyright 2006 VMware, Inc., Bismarck, ND. USA. + * All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the + * "Software"), to deal in the Software without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sub license, and/or sell copies of the Software, and to + * permit persons to whom the Software is furnished to do so, subject to + * the following conditions: + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT. IN NO EVENT SHALL + * THE COPYRIGHT HOLDERS, AUTHORS AND/OR ITS SUPPLIERS BE LIABLE FOR ANY CLAIM, + * DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR + * OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE + * USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * The above copyright notice and this permission notice (including the + * next paragraph) shall be included in all copies or substantial portions + * of the Software. + * + **************************************************************************/ + +/** + * \file + * List macros heavily inspired by the Linux kernel + * list handling. No list looping yet. + * + * Is not threadsafe, so common operations need to + * be protected using an external mutex. + */ + +#ifndef _UTIL_LIST_H_ +#define _UTIL_LIST_H_ + + +#include +#include +#include + +#ifdef DEBUG +# define list_assert(cond, msg) assert(cond && msg) +#else +# define list_assert(cond, msg) (void)(0 && (cond)) +#endif + +struct list_head +{ + struct list_head *prev; + struct list_head *next; +}; + +static inline void list_inithead(struct list_head *item) +{ + item->prev = item; + item->next = item; +} + +static inline void list_add(struct list_head *item, struct list_head *list) +{ + item->prev = list; + item->next = list->next; + list->next->prev = item; + list->next = item; +} + +static inline void list_addtail(struct list_head *item, struct list_head *list) +{ + item->next = list; + item->prev = list->prev; + list->prev->next = item; + list->prev = item; +} + +static inline bool list_is_empty(const struct list_head *list); + +static inline void list_replace(struct list_head *from, struct list_head *to) +{ + if (list_is_empty(from)) { + list_inithead(to); + } else { + to->prev = from->prev; + to->next = from->next; + from->next->prev = to; + from->prev->next = to; + } +} + +static inline void list_del(struct list_head *item) +{ + item->prev->next = item->next; + item->next->prev = item->prev; + item->prev = item->next = NULL; +} + +static inline void list_delinit(struct list_head *item) +{ + item->prev->next = item->next; + item->next->prev = item->prev; + item->next = item; + item->prev = item; +} + +static inline bool list_is_empty(const struct list_head *list) +{ + return list->next == list; +} + +/** + * Returns whether the list has exactly one element. + */ +static inline bool list_is_singular(const struct list_head *list) +{ + return list->next != NULL && list->next != list && list->next->next == list; +} + +static inline unsigned list_length(const struct list_head *list) +{ + struct list_head *node; + unsigned length = 0; + for (node = list->next; node != list; node = node->next) + length++; + return length; +} + +static inline void list_splice(struct list_head *src, struct list_head *dst) +{ + if (list_is_empty(src)) + return; + + src->next->prev = dst; + src->prev->next = dst->next; + dst->next->prev = src->prev; + dst->next = src->next; +} + +static inline void list_splicetail(struct list_head *src, struct list_head *dst) +{ + if (list_is_empty(src)) + return; + + src->prev->next = dst; + src->next->prev = dst->prev; + dst->prev->next = src->next; + dst->prev = src->prev; +} + +static inline void list_validate(const struct list_head *list) +{ + struct list_head *node; + assert(list->next->prev == list && list->prev->next == list); + for (node = list->next; node != list; node = node->next) + assert(node->next->prev == node && node->prev->next == node); +} + +#define LIST_ENTRY(__type, __item, __field) \ + ((__type *)(((char *)(__item)) - offsetof(__type, __field))) + +/** + * Cast from a pointer to a member of a struct back to the containing struct. + * + * 'sample' MUST be initialized, or else the result is undefined! + */ +#ifndef container_of +#define container_of(ptr, sample, member) \ + (void *)((char *)(ptr) \ + - ((char *)&(sample)->member - (char *)(sample))) +#endif + +#define list_first_entry(ptr, type, member) \ + LIST_ENTRY(type, (ptr)->next, member) + +#define list_last_entry(ptr, type, member) \ + LIST_ENTRY(type, (ptr)->prev, member) + + +#define LIST_FOR_EACH_ENTRY(pos, head, member) \ + for (pos = NULL, pos = container_of((head)->next, pos, member); \ + &pos->member != (head); \ + pos = container_of(pos->member.next, pos, member)) + +#define LIST_FOR_EACH_ENTRY_SAFE(pos, storage, head, member) \ + for (pos = NULL, pos = container_of((head)->next, pos, member), \ + storage = container_of(pos->member.next, pos, member); \ + &pos->member != (head); \ + pos = storage, storage = container_of(storage->member.next, storage, member)) + +#define LIST_FOR_EACH_ENTRY_SAFE_REV(pos, storage, head, member) \ + for (pos = NULL, pos = container_of((head)->prev, pos, member), \ + storage = container_of(pos->member.prev, pos, member); \ + &pos->member != (head); \ + pos = storage, storage = container_of(storage->member.prev, storage, member)) + +#define LIST_FOR_EACH_ENTRY_FROM(pos, start, head, member) \ + for (pos = NULL, pos = container_of((start), pos, member); \ + &pos->member != (head); \ + pos = container_of(pos->member.next, pos, member)) + +#define LIST_FOR_EACH_ENTRY_FROM_REV(pos, start, head, member) \ + for (pos = NULL, pos = container_of((start), pos, member); \ + &pos->member != (head); \ + pos = container_of(pos->member.prev, pos, member)) + +#define list_for_each_entry(type, pos, head, member) \ + for (type *pos = LIST_ENTRY(type, (head)->next, member), \ + *__next = LIST_ENTRY(type, pos->member.next, member); \ + &pos->member != (head); \ + pos = LIST_ENTRY(type, pos->member.next, member), \ + list_assert(pos == __next, "use _safe iterator"), \ + __next = LIST_ENTRY(type, __next->member.next, member)) + +#define list_for_each_entry_safe(type, pos, head, member) \ + for (type *pos = LIST_ENTRY(type, (head)->next, member), \ + *__next = LIST_ENTRY(type, pos->member.next, member); \ + &pos->member != (head); \ + pos = __next, \ + __next = LIST_ENTRY(type, __next->member.next, member)) + +#define list_for_each_entry_rev(type, pos, head, member) \ + for (type *pos = LIST_ENTRY(type, (head)->prev, member), \ + *__prev = LIST_ENTRY(type, pos->member.prev, member); \ + &pos->member != (head); \ + pos = LIST_ENTRY(type, pos->member.prev, member), \ + list_assert(pos == __prev, "use _safe iterator"), \ + __prev = LIST_ENTRY(type, __prev->member.prev, member)) + +#define list_for_each_entry_safe_rev(type, pos, head, member) \ + for (type *pos = LIST_ENTRY(type, (head)->prev, member), \ + *__prev = LIST_ENTRY(type, pos->member.prev, member); \ + &pos->member != (head); \ + pos = __prev, \ + __prev = LIST_ENTRY(type, __prev->member.prev, member)) + +#define list_for_each_entry_from(type, pos, start, head, member) \ + for (type *pos = LIST_ENTRY(type, (start), member); \ + &pos->member != (head); \ + pos = LIST_ENTRY(type, pos->member.next, member)) + +#define list_for_each_entry_from_safe(type, pos, start, head, member) \ + for (type *pos = LIST_ENTRY(type, (start), member), \ + *__next = LIST_ENTRY(type, pos->member.next, member); \ + &pos->member != (head); \ + pos = __next, \ + __next = LIST_ENTRY(type, __next->member.next, member)) + +#define list_for_each_entry_from_rev(type, pos, start, head, member) \ + for (type *pos = LIST_ENTRY(type, (start), member); \ + &pos->member != (head); \ + pos = LIST_ENTRY(type, pos->member.prev, member)) + +#define list_pair_for_each_entry(type, pos1, pos2, head1, head2, member) \ + for (type *pos1 = LIST_ENTRY(type, (head1)->next, member), \ + *pos2 = LIST_ENTRY(type, (head2)->next, member); \ + &pos1->member != (head1) && &pos2->member != (head2); \ + pos1 = LIST_ENTRY(type, pos1->member.next, member), \ + pos2 = LIST_ENTRY(type, pos2->member.next, member)) + +#endif /*_UTIL_LIST_H_*/ diff --git a/selfdrive/modeld/thneed/debug/decompiler/util/macros.h b/selfdrive/modeld/thneed/debug/decompiler/util/macros.h new file mode 100644 index 0000000000..a36bdd411e --- /dev/null +++ b/selfdrive/modeld/thneed/debug/decompiler/util/macros.h @@ -0,0 +1,346 @@ +/* + * Copyright © 2014 Intel Corporation + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice (including the next + * paragraph) shall be included in all copies or substantial portions of the + * Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS + * IN THE SOFTWARE. + */ + +#ifndef UTIL_MACROS_H +#define UTIL_MACROS_H + +#include + +/* Compute the size of an array */ +#ifndef ARRAY_SIZE +# define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0])) +#endif + +/* For compatibility with Clang's __has_builtin() */ +#ifndef __has_builtin +# define __has_builtin(x) 0 +#endif + +/** + * __builtin_expect macros + */ +#if !defined(HAVE___BUILTIN_EXPECT) +# define __builtin_expect(x, y) (x) +#endif + +#ifndef likely +# ifdef HAVE___BUILTIN_EXPECT +# define likely(x) __builtin_expect(!!(x), 1) +# define unlikely(x) __builtin_expect(!!(x), 0) +# else +# define likely(x) (x) +# define unlikely(x) (x) +# endif +#endif + + +/** + * Static (compile-time) assertion. + * Basically, use COND to dimension an array. If COND is false/zero the + * array size will be -1 and we'll get a compilation error. + */ +#define STATIC_ASSERT(COND) \ + do { \ + (void) sizeof(char [1 - 2*!(COND)]); \ + } while (0) + + +/** + * Unreachable macro. Useful for suppressing "control reaches end of non-void + * function" warnings. + */ +#if defined(HAVE___BUILTIN_UNREACHABLE) || __has_builtin(__builtin_unreachable) +#define unreachable(str) \ +do { \ + assert(!str); \ + __builtin_unreachable(); \ +} while (0) +#elif defined (_MSC_VER) +#define unreachable(str) \ +do { \ + assert(!str); \ + __assume(0); \ +} while (0) +#else +#define unreachable(str) assert(!str) +#endif + +/** + * Assume macro. Useful for expressing our assumptions to the compiler, + * typically for purposes of silencing warnings. + */ +#if __has_builtin(__builtin_assume) +#define assume(expr) \ +do { \ + assert(expr); \ + __builtin_assume(expr); \ +} while (0) +#elif defined HAVE___BUILTIN_UNREACHABLE +#define assume(expr) ((expr) ? ((void) 0) \ + : (assert(!"assumption failed"), \ + __builtin_unreachable())) +#elif defined (_MSC_VER) +#define assume(expr) __assume(expr) +#else +#define assume(expr) assert(expr) +#endif + +/* Attribute const is used for functions that have no effects other than their + * return value, and only rely on the argument values to compute the return + * value. As a result, calls to it can be CSEed. Note that using memory + * pointed to by the arguments is not allowed for const functions. + */ +#ifdef HAVE_FUNC_ATTRIBUTE_CONST +#define ATTRIBUTE_CONST __attribute__((__const__)) +#else +#define ATTRIBUTE_CONST +#endif + +#ifdef HAVE_FUNC_ATTRIBUTE_FLATTEN +#define FLATTEN __attribute__((__flatten__)) +#else +#define FLATTEN +#endif + +#ifdef HAVE_FUNC_ATTRIBUTE_FORMAT +#define PRINTFLIKE(f, a) __attribute__ ((format(__printf__, f, a))) +#else +#define PRINTFLIKE(f, a) +#endif + +#ifdef HAVE_FUNC_ATTRIBUTE_MALLOC +#define MALLOCLIKE __attribute__((__malloc__)) +#else +#define MALLOCLIKE +#endif + +/* Forced function inlining */ +/* Note: Clang also sets __GNUC__ (see other cases below) */ +#ifndef ALWAYS_INLINE +# if defined(__GNUC__) +# define ALWAYS_INLINE inline __attribute__((always_inline)) +# elif defined(_MSC_VER) +# define ALWAYS_INLINE __forceinline +# else +# define ALWAYS_INLINE inline +# endif +#endif + +/* Used to optionally mark structures with misaligned elements or size as + * packed, to trade off performance for space. + */ +#ifdef HAVE_FUNC_ATTRIBUTE_PACKED +#define PACKED __attribute__((__packed__)) +#else +#define PACKED +#endif + +/* Attribute pure is used for functions that have no effects other than their + * return value. As a result, calls to it can be dead code eliminated. + */ +#ifdef HAVE_FUNC_ATTRIBUTE_PURE +#define ATTRIBUTE_PURE __attribute__((__pure__)) +#else +#define ATTRIBUTE_PURE +#endif + +#ifdef HAVE_FUNC_ATTRIBUTE_RETURNS_NONNULL +#define ATTRIBUTE_RETURNS_NONNULL __attribute__((__returns_nonnull__)) +#else +#define ATTRIBUTE_RETURNS_NONNULL +#endif + +#ifndef NORETURN +# ifdef _MSC_VER +# define NORETURN __declspec(noreturn) +# elif defined HAVE_FUNC_ATTRIBUTE_NORETURN +# define NORETURN __attribute__((__noreturn__)) +# else +# define NORETURN +# endif +#endif + +#ifdef __cplusplus +/** + * Macro function that evaluates to true if T is a trivially + * destructible type -- that is, if its (non-virtual) destructor + * performs no action and all member variables and base classes are + * trivially destructible themselves. + */ +# if (defined(__clang__) && defined(__has_feature)) +# if __has_feature(has_trivial_destructor) +# define HAS_TRIVIAL_DESTRUCTOR(T) __has_trivial_destructor(T) +# endif +# elif defined(__GNUC__) +# if ((__GNUC__ > 4) || ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 3))) +# define HAS_TRIVIAL_DESTRUCTOR(T) __has_trivial_destructor(T) +# endif +# elif defined(_MSC_VER) && !defined(__INTEL_COMPILER) +# define HAS_TRIVIAL_DESTRUCTOR(T) __has_trivial_destructor(T) +# endif +# ifndef HAS_TRIVIAL_DESTRUCTOR + /* It's always safe (if inefficient) to assume that a + * destructor is non-trivial. + */ +# define HAS_TRIVIAL_DESTRUCTOR(T) (false) +# endif +#endif + +/** + * PUBLIC/USED macros + * + * If we build the library with gcc's -fvisibility=hidden flag, we'll + * use the PUBLIC macro to mark functions that are to be exported. + * + * We also need to define a USED attribute, so the optimizer doesn't + * inline a static function that we later use in an alias. - ajax + */ +#ifndef PUBLIC +# if defined(__GNUC__) +# define PUBLIC __attribute__((visibility("default"))) +# define USED __attribute__((used)) +# elif defined(_MSC_VER) +# define PUBLIC __declspec(dllexport) +# define USED +# else +# define PUBLIC +# define USED +# endif +#endif + +/** + * UNUSED marks variables (or sometimes functions) that have to be defined, + * but are sometimes (or always) unused beyond that. A common case is for + * a function parameter to be used in some build configurations but not others. + * Another case is fallback vfuncs that don't do anything with their params. + * + * Note that this should not be used for identifiers used in `assert()`; + * see ASSERTED below. + */ +#ifdef HAVE_FUNC_ATTRIBUTE_UNUSED +#define UNUSED __attribute__((unused)) +#else +#define UNUSED +#endif + +/** + * Use ASSERTED to indicate that an identifier is unused outside of an `assert()`, + * so that assert-free builds don't get "unused variable" warnings. + */ +#ifdef NDEBUG +#define ASSERTED UNUSED +#else +#define ASSERTED +#endif + +#ifdef HAVE_FUNC_ATTRIBUTE_WARN_UNUSED_RESULT +#define MUST_CHECK __attribute__((warn_unused_result)) +#else +#define MUST_CHECK +#endif + +#if defined(__GNUC__) +#define ATTRIBUTE_NOINLINE __attribute__((noinline)) +#else +#define ATTRIBUTE_NOINLINE +#endif + + +/** + * Check that STRUCT::FIELD can hold MAXVAL. We use a lot of bitfields + * in Mesa/gallium. We have to be sure they're of sufficient size to + * hold the largest expected value. + * Note that with MSVC, enums are signed and enum bitfields need one extra + * high bit (always zero) to ensure the max value is handled correctly. + * This macro will detect that with MSVC, but not GCC. + */ +#define ASSERT_BITFIELD_SIZE(STRUCT, FIELD, MAXVAL) \ + do { \ + ASSERTED STRUCT s; \ + s.FIELD = (MAXVAL); \ + assert((int) s.FIELD == (MAXVAL) && "Insufficient bitfield size!"); \ + } while (0) + + +/** Compute ceiling of integer quotient of A divided by B. */ +#define DIV_ROUND_UP( A, B ) ( ((A) + (B) - 1) / (B) ) + +/** Clamp X to [MIN,MAX]. Turn NaN into MIN, arbitrarily. */ +#define CLAMP( X, MIN, MAX ) ( (X)>(MIN) ? ((X)>(MAX) ? (MAX) : (X)) : (MIN) ) + +/** Minimum of two values: */ +#define MIN2( A, B ) ( (A)<(B) ? (A) : (B) ) + +/** Maximum of two values: */ +#define MAX2( A, B ) ( (A)>(B) ? (A) : (B) ) + +/** Minimum and maximum of three values: */ +#define MIN3( A, B, C ) ((A) < (B) ? MIN2(A, C) : MIN2(B, C)) +#define MAX3( A, B, C ) ((A) > (B) ? MAX2(A, C) : MAX2(B, C)) + +/** Align a value to a power of two */ +#define ALIGN_POT(x, pot_align) (((x) + (pot_align) - 1) & ~((pot_align) - 1)) + +/** + * Macro for declaring an explicit conversion operator. Defaults to an + * implicit conversion if C++11 is not supported. + */ +#if __cplusplus >= 201103L +#define EXPLICIT_CONVERSION explicit +#elif defined(__cplusplus) +#define EXPLICIT_CONVERSION +#endif + +/** Set a single bit */ +#define BITFIELD_BIT(b) (1u << (b)) +/** Set all bits up to excluding bit b */ +#define BITFIELD_MASK(b) \ + ((b) == 32 ? (~0u) : BITFIELD_BIT((b) % 32) - 1) +/** Set count bits starting from bit b */ +#define BITFIELD_RANGE(b, count) \ + (BITFIELD_MASK((b) + (count)) & ~BITFIELD_MASK(b)) + +/** Set a single bit */ +#define BITFIELD64_BIT(b) (1ull << (b)) +/** Set all bits up to excluding bit b */ +#define BITFIELD64_MASK(b) \ + ((b) == 64 ? (~0ull) : BITFIELD64_BIT(b) - 1) +/** Set count bits starting from bit b */ +#define BITFIELD64_RANGE(b, count) \ + (BITFIELD64_MASK((b) + (count)) & ~BITFIELD64_MASK(b)) + +/* TODO: In future we should try to move this to u_debug.h once header + * dependencies are reorganised to allow this. + */ +enum pipe_debug_type +{ + PIPE_DEBUG_TYPE_OUT_OF_MEMORY = 1, + PIPE_DEBUG_TYPE_ERROR, + PIPE_DEBUG_TYPE_SHADER_INFO, + PIPE_DEBUG_TYPE_PERF_INFO, + PIPE_DEBUG_TYPE_INFO, + PIPE_DEBUG_TYPE_FALLBACK, + PIPE_DEBUG_TYPE_CONFORMANCE, +}; + +#endif /* UTIL_MACROS_H */ diff --git a/selfdrive/modeld/thneed/debug/disassembler.cc b/selfdrive/modeld/thneed/debug/disassembler.cc new file mode 100644 index 0000000000..c1f7e6332c --- /dev/null +++ b/selfdrive/modeld/thneed/debug/disassembler.cc @@ -0,0 +1,132 @@ +#include "debug/include/adreno_pm4types.h" +#define REG_A5XX_TPL1_CS_TEX_CONST_LO 0x0000e760 +#define REG_A5XX_TPL1_CS_TEX_SAMP_LO 0x0000e75c +#define REG_A5XX_SP_CS_CTRL_REG0 0x0000e5f0 + +std::map regs = { + {0x0000e760, "REG_A5XX_TPL1_CS_TEX_CONST_LO"}, + {0x0000e75c, "REG_A5XX_TPL1_CS_TEX_SAMP_LO"}, + {0x00000e06, "REG_A5XX_HLSQ_MODE_CNTL"}, + {0x00000e91, "REG_A5XX_UCHE_CACHE_INVALIDATE_MIN_LO"}, + {0x00000ec2, "REG_A5XX_SP_MODE_CNTL"}, + {0x0000e580, "REG_A5XX_SP_SP_CNTL"}, + {0x0000e5f0, "REG_A5XX_SP_CS_CTRL_REG0"}, + {0x0000e796, "REG_A5XX_HLSQ_CS_CNTL"}, + {0x0000e784, "REG_A5XX_HLSQ_CONTROL_0_REG"}, + {0x0000e7b0, "REG_A5XX_HLSQ_CS_NDRANGE_0"}, + {0x0000e7b9, "REG_A5XX_HLSQ_CS_KERNEL_GROUP_X"}, + {0x00000cdd, "REG_A5XX_VSC_RESOLVE_CNTL"}, +}; + +std::map ops = { + {33, "CP_REG_RMW"}, + {62, "CP_REG_TO_MEM"}, + {49, "CP_RUN_OPENCL"}, + {16, "CP_NOP"}, + {38, "CP_WAIT_FOR_IDLE"}, + {110, "CP_COMPUTE_CHECKPOINT"}, + {48, "CP_LOAD_STATE"}, +}; + +void CachedCommand::disassemble() { + uint32_t *src = (uint32_t *)cmds[1].gpuaddr; + int len = cmds[1].size/4; + printf("disassemble %p %d\n", src, len); + + int i = 0; + while (i < len) { + int pktsize; + int pkttype = -1; + + if (pkt_is_type0(src[i])) { + pkttype = 0; + pktsize = type0_pkt_size(src[i]); + } else if (pkt_is_type3(src[i])) { + pkttype = 3; + pktsize = type3_pkt_size(src[i]); + } else if (pkt_is_type4(src[i])) { + pkttype = 4; + pktsize = type4_pkt_size(src[i]); + } else if (pkt_is_type7(src[i])) { + pkttype = 7; + pktsize = type7_pkt_size(src[i]); + } + printf("%3d: type:%d size:%d ", i, pkttype, pktsize); + + if (pkttype == 7) { + int op = cp_type7_opcode(src[i]); + if (ops.find(op) != ops.end()) { + printf("%-40s ", ops[op].c_str()); + } else { + printf("op: %4d ", op); + } + } + + if (pkttype == 4) { + int reg = cp_type4_base_index_one_reg_wr(src[i]); + if (regs.find(reg) != regs.end()) { + printf("%-40s ", regs[reg].c_str()); + } else { + printf("reg: %4x ", reg); + } + } + + for (int j = 0; j < pktsize+1; j++) { + printf("%8.8X ", src[i+j]); + } + printf("\n"); + + uint64_t addr; + if (pkttype == 7) { + switch (cp_type7_opcode(src[i])) { + case CP_LOAD_STATE: + int dst_off = src[i+1] & 0x1FFF; + int state_src = (src[i+1] >> 16) & 3; + int state_block = (src[i+1] >> 18) & 7; + int state_type = src[i+2] & 3; + int num_unit = (src[i+1] & 0xffc00000) >> 22; + printf(" dst_off: %x state_src: %d state_block: %d state_type: %d num_unit: %d\n", + dst_off, state_src, state_block, state_type, num_unit); + addr = (uint64_t)(src[i+2] & 0xfffffffc) | ((uint64_t)(src[i+3]) << 32); + if (state_block == 5 && state_type == 0) { + if (!(addr&0xFFF)) { + int len = 0x1000; + if (num_unit >= 32) len += 0x1000; + //hexdump((uint32_t *)addr, len); + char fn[0x100]; + snprintf(fn, sizeof(fn), "/tmp/0x%lx.shader", addr); + printf("dumping %s\n", fn); + FILE *f = fopen(fn, "wb"); + // groups of 16 instructions + fwrite((void*)addr, 1, len, f); + fclose(f); + } + } + break; + } + } + + /*if (pkttype == 4) { + switch (cp_type4_base_index_one_reg_wr(src[i])) { + case REG_A5XX_SP_CS_CTRL_REG0: + addr = (uint64_t)(src[i+4] & 0xfffffffc) | ((uint64_t)(src[i+5]) << 32); + hexdump((uint32_t *)addr, 0x1000); + break; + } + }*/ + + /*if (pkttype == 4 && cp_type4_base_index_one_reg_wr(src[i]) == REG_A5XX_TPL1_CS_TEX_CONST_LO) { + uint64_t addr = (uint64_t)(src[i+1] & 0xffffffff) | ((uint64_t)(src[i+2]) << 32); + hexdump((uint32_t *)addr, 0x40); + } + + if (pkttype == 4 && cp_type4_base_index_one_reg_wr(src[i]) == REG_A5XX_TPL1_CS_TEX_SAMP_LO) { + uint64_t addr = (uint64_t)(src[i+1] & 0xffffffff) | ((uint64_t)(src[i+2]) << 32); + hexdump((uint32_t *)addr, 0x40); + }*/ + + if (pkttype == -1) break; + i += (1+pktsize); + } + assert(i == len); +} diff --git a/selfdrive/modeld/thneed/debug/microbenchmark/gemm.cl b/selfdrive/modeld/thneed/debug/microbenchmark/gemm.cl new file mode 100644 index 0000000000..6a55406aee --- /dev/null +++ b/selfdrive/modeld/thneed/debug/microbenchmark/gemm.cl @@ -0,0 +1,51 @@ +// https://github.com/moskewcz/boda/issues/13 + +#define USE_FP16 + +#ifdef USE_FP16 + #define up(x) x + #define down(x) x + #define xtype half8 + #define skip 128 +#else + #define up(x) convert_float8(x) + #define down(x) convert_half8(x) + #define xtype float8 + #define skip 128 +#endif + +#pragma OPENCL EXTENSION cl_khr_fp16 : enable +__kernel void gemm(const int M, const int N, const int K, + global const half8* a, global const half8* b, global half8* c ) +{ + xtype c_r[8] = {0,0,0,0,0,0,0,0}; + + int const a_off_thr = get_global_id(0); + int const b_off_thr = get_global_id(1); + + int a_off = a_off_thr; + int b_off = b_off_thr; + for( int k = 0; k < 1024; k += 1 ) { + xtype a_r = up(a[a_off]); + xtype b_r = up(b[b_off]); + + c_r[0] += a_r.s0*b_r; + c_r[1] += a_r.s1*b_r; + c_r[2] += a_r.s2*b_r; + c_r[3] += a_r.s3*b_r; + c_r[4] += a_r.s4*b_r; + c_r[5] += a_r.s5*b_r; + c_r[6] += a_r.s6*b_r; + c_r[7] += a_r.s7*b_r; + + a_off += skip; + b_off += skip; + } + + int c_off = a_off_thr*1024 + b_off_thr; + for (int i = 0; i < 8; i++) { + c[c_off] = down(c_r[i]); + c_off += skip; + } +} + diff --git a/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl b/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl new file mode 100644 index 0000000000..46b6bf6ef8 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl @@ -0,0 +1,75 @@ +// https://github.com/moskewcz/boda/issues/13 + +//#define USE_FP16 + +#ifdef USE_FP16 + #define xtype half4 + #define read_imagep read_imageh + #define write_imagep write_imageh +#else + #define xtype float4 + #define read_imagep read_imagef + #define write_imagep write_imagef +#endif + +#pragma OPENCL EXTENSION cl_khr_fp16 : enable +__kernel void gemm(const int M, const int N, const int K, + read_only image2d_t A, + read_only image2d_t B, + write_only image2d_t C) +{ + const sampler_t smp = CLK_NORMALIZED_COORDS_FALSE | + CLK_ADDRESS_CLAMP | + CLK_FILTER_NEAREST; + + xtype c_r[4] = {0,0,0,0}; + xtype a_r[4], b_r[4]; + + int const a_off_thr = get_global_id(0); + int const b_off_thr = get_global_id(1); + + int2 a_samp = {0, a_off_thr}; + int2 b_samp = {0, b_off_thr}; + + for (short k = 0; k < K/4; k++) { + for (short i = 0; i < 4; ++i) { + a_r[i] = read_imagep(A, smp, a_samp); + b_r[i] = read_imagep(B, smp, b_samp); + ++a_samp.x; + ++b_samp.x; + } + + for (short i = 0; i < 4; ++i) { + float4 ov = c_r[i]; + + ov.x += a_r[i].x * b_r[0].x; + ov.x += a_r[i].y * b_r[0].y; + ov.x += a_r[i].z * b_r[0].z; + ov.x += a_r[i].w * b_r[0].w; + + ov.y += a_r[i].x * b_r[1].x; + ov.y += a_r[i].y * b_r[1].y; + ov.y += a_r[i].z * b_r[1].z; + ov.y += a_r[i].w * b_r[1].w; + + ov.z += a_r[i].x * b_r[2].x; + ov.z += a_r[i].y * b_r[2].y; + ov.z += a_r[i].z * b_r[2].z; + ov.z += a_r[i].w * b_r[2].w; + + ov.w += a_r[i].x * b_r[3].x; + ov.w += a_r[i].y * b_r[3].y; + ov.w += a_r[i].z * b_r[3].z; + ov.w += a_r[i].w * b_r[3].w; + + c_r[i] = ov; + } + } + + int2 c_samp = {a_off_thr, b_off_thr*4}; + for (short i = 0; i < 4; i++) { + write_imagep(C, c_samp, c_r[i]); + ++c_samp.y; + } +} + diff --git a/selfdrive/modeld/thneed/debug/microbenchmark/go.c b/selfdrive/modeld/thneed/debug/microbenchmark/go.c new file mode 100644 index 0000000000..5635085638 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/microbenchmark/go.c @@ -0,0 +1,314 @@ +#include +#include +#include +#include +#include + +/* +block7b_project_conv (Conv2D) (None, 8, 16, 352) 743424 block7b_activation[0][0] +8448*8*4 = 8*16*2112 = 270336 = input = 128*2112 +2112*88*4 = 743424 = weights = 2112*352 +1408*8*4 = 8*16*352 = 45056 = output = 128*352 + +FLOPS = 128*2112*352 = 95158272 = 95 MFLOPS +RAM = 128*2112 + 2112*352 + 128*352 = 1058816 = 1 M accesses + +# 22 groups +128*2112 + 2112*16 + 128*16 = 306176 +306176*22 = 6735872 real accesses + +This is a 128x2112 by 2112x352 matrix multiply + +work_size = {88, 4, 8} +Each kernel run computes 16 outputs + +0x7f7e8a6380 convolution_horizontal_reduced_reads_1x1 -- 88 4 8 -- 4 4 8 + image2d_t input = 0x7f7f490b00 image 8448 x 8 rp 67840 + short startPackedInputChannel = 0 + short numPackedInputChannelsForGroup = 528 + short totalNumPackedInputChannels = 528 + short packedOuputChannelOffset = 0 + short totalNumPackedOutputChannels = 88 + image2d_t weights = 0x7f7f52fb80 image 2112 x 88 rp 16896 + float* biases = 0x7f7f564d80 buffer 1408 + short filterSizeX = 1 + short filterSizeY = 1 + image2d_t output = 0x7f7f490e80 image 1408 x 8 rp 11264 + short paddingX = 0 + short paddingY = 0 + short strideX = 1 + short strideY = 1 + short neuron = 0 + float a = 1.000000 + float b = 1.000000 + float min_clamp = 0.000000 + float max_clamp = 0.000000 + float* parameters = 0x0 + float* batchNormBiases = 0x0 + short numOutputColumns = 16 +*/ + +#define GEMM +#define IMAGE + +void dump_maps() { + FILE *f = fopen("/proc/self/maps", "rb"); + char maps[0x100000]; + int len = fread(maps, 1, sizeof(maps), f); + maps[len] = '\0'; + maps[0x800] = '\0'; + fclose(f); + printf("%s\n", maps); +} + +static inline uint64_t nanos_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +int main(int argc, char *argv[]) { + cl_int err; + + // cl init + cl_device_id device_id; + cl_context context; + cl_command_queue q; + { + cl_platform_id platform_id[2]; + cl_uint num_devices; + cl_uint num_platforms; + + err = clGetPlatformIDs(sizeof(platform_id)/sizeof(cl_platform_id), platform_id, &num_platforms); + assert(err == 0); + + err = clGetDeviceIDs(platform_id[0], CL_DEVICE_TYPE_DEFAULT, 1, &device_id, &num_devices); + assert(err == 0); + + context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); + assert(err == 0); + + q = clCreateCommandQueue(context, device_id, 0, &err); + assert(err == 0); + } + printf("cl ready\n"); + + char tmp[0x10000]; + memset(tmp, 0, sizeof(tmp)); + FILE *f = fopen(argv[1], "rb"); + fread(tmp, 1, sizeof(tmp), f); + fclose(f); + + const char *strings[1]; + size_t lengths[1]; + strings[0] = tmp; + lengths[0] = strlen(tmp); + + cl_program prog = clCreateProgramWithSource(context, 1, strings, lengths, &err); + assert(err == 0); + printf("creating program\n"); + + err = clBuildProgram(prog, 1, &device_id, "-D AVANTE_IS_GPU_A530_64", NULL, NULL); + + if (err != 0) { + printf("got err %d\n", err); + size_t length; + char buffer[2048]; + clGetProgramBuildInfo(prog, device_id, CL_PROGRAM_BUILD_LOG, sizeof(buffer), buffer, &length); + buffer[length] = '\0'; + printf("%s\n", buffer); + } + assert(err == 0); + printf("built program\n"); + + +#ifdef GEMM + // 128x2112 by 2112x352 + int M,N,K; + + M = N = K = 1024; + //M = 128; K = 2112; N = 352; + + cl_kernel kern = clCreateKernel(prog, "gemm", &err); + assert(err == 0); + printf("creating kernel %p\n", kern); + + cl_mem A,B,C; + A = clCreateBuffer(context, CL_MEM_READ_WRITE, M*K*2, NULL, &err); + assert(err == 0); + B = clCreateBuffer(context, CL_MEM_READ_WRITE, K*N*2, NULL, &err); + assert(err == 0); + C = clCreateBuffer(context, CL_MEM_READ_WRITE, M*N*2, NULL, &err); + assert(err == 0); + printf("created buffers\n"); + +#ifdef IMAGE + cl_image_format fmt; + fmt.image_channel_order = CL_RGBA; + fmt.image_channel_data_type = CL_HALF_FLOAT; + + cl_image_desc desc; + desc.image_type = CL_MEM_OBJECT_IMAGE2D; + desc.image_depth = 0; desc.image_slice_pitch = 0; desc.num_mip_levels = 0; desc.num_samples = 0; + + desc.image_width = K; desc.image_height = M/4; + desc.buffer = A; + desc.image_row_pitch = desc.image_width*8; + A = clCreateImage(context, CL_MEM_READ_WRITE, &fmt, &desc, NULL, &err); + assert(err == 0); + + desc.image_width = K; desc.image_height = N/4; + desc.buffer = B; desc.image_row_pitch = desc.image_width*8; + B = clCreateImage(context, CL_MEM_READ_WRITE, &fmt, &desc, NULL, &err); + assert(err == 0); + + desc.image_width = M/4; desc.image_height = N; + desc.buffer = C; desc.image_row_pitch = desc.image_width*8; + C = clCreateImage(context, CL_MEM_READ_WRITE, &fmt, &desc, NULL, &err); + assert(err == 0); + printf("created images\n"); +#endif + + clSetKernelArg(kern, 0, sizeof(int), &M); + clSetKernelArg(kern, 1, sizeof(int), &N); + clSetKernelArg(kern, 2, sizeof(int), &K); + + clSetKernelArg(kern, 3, sizeof(cl_mem), &A); + clSetKernelArg(kern, 4, sizeof(cl_mem), &B); + clSetKernelArg(kern, 5, sizeof(cl_mem), &C); + printf("set args\n"); + +#ifdef IMAGE + size_t global_work_size[3] = {M/4, N/4, 1}; + size_t local_work_size[3] = {4, 64, 1}; +#else + size_t global_work_size[3] = {128, 128, 1}; + size_t local_work_size[3] = {2, 128, 1}; +#endif + +#else + cl_kernel kern = clCreateKernel(prog, "convolution_horizontal_reduced_reads_1x1", &err); + assert(err == 0); + printf("creating kernel\n"); + + cl_mem input; + cl_mem weights; + cl_mem weights_buffer; + cl_mem biases; + cl_mem outputs; + + cl_image_format fmt; + fmt.image_channel_order = CL_RGBA; + fmt.image_channel_data_type = CL_HALF_FLOAT; + + cl_image_desc desc; + desc.image_type = CL_MEM_OBJECT_IMAGE2D; + desc.image_depth = 0; desc.image_slice_pitch = 0; desc.num_mip_levels = 0; desc.num_samples = 0; + desc.buffer = NULL; + + biases = clCreateBuffer(context, CL_MEM_READ_WRITE, 1408, NULL, &err); + assert(err == 0); + + desc.image_width = 8448; desc.image_height = 8; desc.image_row_pitch = 67840; + desc.buffer = clCreateBuffer(context, CL_MEM_READ_WRITE, desc.image_height * desc.image_row_pitch, NULL, &err); + assert(err == 0); + input = clCreateImage(context, CL_MEM_READ_WRITE, &fmt, &desc, NULL, &err); + assert(err == 0); + + desc.image_width = 2112; desc.image_height = 88; desc.image_row_pitch = 16896; + weights_buffer = desc.buffer = clCreateBuffer(context, CL_MEM_READ_WRITE, desc.image_height * desc.image_row_pitch, NULL, &err); + assert(err == 0); + weights = clCreateImage(context, CL_MEM_READ_WRITE, &fmt, &desc, NULL, &err); + assert(err == 0); + + desc.image_width = 1408; desc.image_height = 8; desc.image_row_pitch = 11264; + desc.buffer = clCreateBuffer(context, CL_MEM_READ_WRITE, desc.image_height * desc.image_row_pitch, NULL, &err); + assert(err == 0); + outputs = clCreateImage(context, CL_MEM_READ_WRITE, &fmt, &desc, NULL, &err); + assert(err == 0); + + void *n = NULL; + uint16_t v; + float fl; + + clSetKernelArg(kern, 0, sizeof(cl_mem), &input); + v = 0; clSetKernelArg(kern, 1, sizeof(v), &v); + v = 528; clSetKernelArg(kern, 2, sizeof(v), &v); + v = 528; clSetKernelArg(kern, 3, sizeof(v), &v); + v = 0; clSetKernelArg(kern, 4, sizeof(v), &v); + v = 88; clSetKernelArg(kern, 5, sizeof(v), &v); + clSetKernelArg(kern, 6, sizeof(cl_mem), &weights); + //clSetKernelArg(kern, 6, sizeof(cl_mem), &weights_buffer); + clSetKernelArg(kern, 7, sizeof(cl_mem), &biases); + v = 1; clSetKernelArg(kern, 8, sizeof(v), &v); + v = 1; clSetKernelArg(kern, 9, sizeof(v), &v); + clSetKernelArg(kern, 10, sizeof(cl_mem), &outputs); + v = 0; clSetKernelArg(kern, 11, sizeof(v), &v); + v = 0; clSetKernelArg(kern, 12, sizeof(v), &v); + v = 1; clSetKernelArg(kern, 13, sizeof(v), &v); + v = 1; clSetKernelArg(kern, 14, sizeof(v), &v); + v = 0; clSetKernelArg(kern, 15, sizeof(v), &v); + fl = 1.0; clSetKernelArg(kern, 16, sizeof(fl), &fl); + fl = 0.0; clSetKernelArg(kern, 17, sizeof(fl), &fl); + fl = 0.0; clSetKernelArg(kern, 18, sizeof(fl), &fl); + fl = 0.0; clSetKernelArg(kern, 19, sizeof(fl), &fl); + clSetKernelArg(kern, 20, sizeof(n), &n); + clSetKernelArg(kern, 21, sizeof(n), &n); + v = 16; clSetKernelArg(kern, 22, sizeof(v), &v); + + size_t global_work_size[3] = {88, 4, 8}; + size_t local_work_size[3] = {4, 4, 8}; +#endif + + printf("ready to enqueue\n"); + for (int i = 0; i < 20; i++) { + cl_event event; + err = clEnqueueNDRangeKernel(q, kern, 3, NULL, global_work_size, local_work_size, 0, NULL, &event); + assert(err == 0); + + uint64_t tb = nanos_since_boot(); + err = clWaitForEvents(1, &event); + assert(err == 0); + uint64_t te = nanos_since_boot(); + uint64_t us = (te-tb)/1000; + + float s = 1000000.0/us; + +#ifdef GEMM + float flops = M*N*K*s; + float rams = (M*N + N*K + M*K)*s; +#else + float flops = 95158272.0*s; + float rams = 1058816.0*s; + //float rams = 6735872.0*s; +#endif + + printf("%2d: wait %lu us -- %.2f GFLOPS -- %.2f GB/s\n", i, us, flops/1e9, rams*2/1e9); + } + + size_t binary_size = 0; + err = clGetProgramInfo(prog, CL_PROGRAM_BINARY_SIZES, sizeof(binary_size), &binary_size, NULL); + assert(err == 0); + assert(binary_size > 0); + + uint8_t *binary_buf = (uint8_t *)malloc(binary_size); + assert(binary_buf); + + uint8_t* bufs[1] = { binary_buf, }; + err = clGetProgramInfo(prog, CL_PROGRAM_BINARIES, sizeof(bufs), &bufs, NULL); + assert(err == 0); + + FILE *g = fopen("/tmp/bin.bin", "wb"); + fwrite(binary_buf, 1, binary_size, g); + fclose(g); + + /*dump_maps(); + for (uint64_t i = 0x7ffbd2000; i < 0x800000000; i += 0x1000) { + uint64_t cmd = *((uint64_t*)i); + printf("%llx: %llx\n", i, cmd); + }*/ + + + return 0; +} + diff --git a/selfdrive/modeld/thneed/debug/microbenchmark/run.sh b/selfdrive/modeld/thneed/debug/microbenchmark/run.sh new file mode 100755 index 0000000000..f77d27d817 --- /dev/null +++ b/selfdrive/modeld/thneed/debug/microbenchmark/run.sh @@ -0,0 +1,2 @@ +#!/usr/bin/env bash +gcc -I/data/openpilot/phonelibs/opencl/include -L/system/vendor/lib64 -lOpenCL -lCB -lgsl go.c diff --git a/selfdrive/modeld/thneed/debug/test.cc b/selfdrive/modeld/thneed/debug/test.cc index b2ac600895..6f185b9f00 100644 --- a/selfdrive/modeld/thneed/debug/test.cc +++ b/selfdrive/modeld/thneed/debug/test.cc @@ -8,8 +8,9 @@ void hexdump(uint32_t *d, int len); int main(int argc, char* argv[]) { - float *output = (float*)calloc(0x10000, sizeof(float)); - float *golden = (float*)calloc(0x10000, sizeof(float)); + #define OUTPUT_SIZE 0x10000 + float *output = (float*)calloc(OUTPUT_SIZE, sizeof(float)); + float *golden = (float*)calloc(OUTPUT_SIZE, sizeof(float)); SNPEModel mdl(argv[1], output, 0, USE_GPU_RUNTIME); // cmd line test @@ -59,36 +60,39 @@ int main(int argc, char* argv[]) { // first run printf("************** execute 1 **************\n"); - memset(output, 0, sizeof(output)); + memset(output, 0, OUTPUT_SIZE * sizeof(float)); mdl.execute(input, 0); hexdump((uint32_t *)output, 0x100); - memcpy(golden, output, sizeof(output)); + memcpy(golden, output, OUTPUT_SIZE * sizeof(float)); // second run printf("************** execute 2 **************\n"); - memset(output, 0, sizeof(output)); + memset(output, 0, OUTPUT_SIZE * sizeof(float)); Thneed *t = new Thneed(); - t->record = 3; // debug print with record + t->record = 7; // debug print with record mdl.execute(input, 0); t->stop(); hexdump((uint32_t *)output, 0x100); - if (memcmp(golden, output, sizeof(output)) != 0) { printf("FAILURE\n"); return -1; } + if (memcmp(golden, output, OUTPUT_SIZE * sizeof(float)) != 0) { printf("FAILURE\n"); return -1; } // third run printf("************** execute 3 **************\n"); - memset(output, 0, sizeof(output)); + memset(output, 0, OUTPUT_SIZE * sizeof(float)); t->record = 2; // debug print w/o record float *inputs[4] = {state, traffic_convention, desire, input}; - t->execute(inputs, output); + t->execute(inputs, output, true); hexdump((uint32_t *)output, 0x100); - if (memcmp(golden, output, sizeof(output)) != 0) { printf("FAILURE\n"); return -1; } + if (memcmp(golden, output, OUTPUT_SIZE * sizeof(float)) != 0) { printf("FAILURE\n"); return -1; } printf("************** execute 4 **************\n"); - memset(output, 0, sizeof(output)); - //t->record = 2; // debug print w/o record - t->execute(inputs, output); - hexdump((uint32_t *)output, 0x100); - if (memcmp(golden, output, sizeof(output)) != 0) { printf("FAILURE\n"); return -1; } + while (1) { + memset(output, 0, OUTPUT_SIZE * sizeof(float)); + //t->record = 2; // debug print w/o record + t->execute(inputs, output); + hexdump((uint32_t *)output, 0x100); + if (memcmp(golden, output, OUTPUT_SIZE * sizeof(float)) != 0) { printf("FAILURE\n"); return -1; } + break; + } printf("************** execute done **************\n"); } diff --git a/selfdrive/modeld/thneed/thneed.cc b/selfdrive/modeld/thneed/thneed.cc index 826015999f..785463780e 100644 --- a/selfdrive/modeld/thneed/thneed.cc +++ b/selfdrive/modeld/thneed/thneed.cc @@ -13,7 +13,8 @@ std::map, std::string> g_args; static inline uint64_t nanos_since_boot() { struct timespec t; clock_gettime(CLOCK_BOOTTIME, &t); - return t.tv_sec * 1000000000ULL + t.tv_nsec; } + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} void hexdump(uint32_t *d, int len) { assert((len%4) == 0); @@ -43,10 +44,12 @@ int ioctl(int filedes, unsigned long request, void *argp) { thneed->timestamp = cmd->timestamp; thneed->context_id = cmd->context_id; CachedCommand *ccmd = new CachedCommand(thneed, cmd); + //ccmd->disassemble(); thneed->cmds.push_back(ccmd); } if (thneed->record & 2) { - printf("IOCTL_KGSL_GPU_COMMAND: flags: 0x%lx context_id: %u timestamp: %u\n", + printf("IOCTL_KGSL_GPU_COMMAND(%2zu): flags: 0x%lx context_id: %u timestamp: %u\n", + thneed->cmds.size(), cmd->flags, cmd->context_id, cmd->timestamp); } @@ -179,7 +182,10 @@ void Thneed::stop() { //#define SAVE_LOG -void Thneed::execute(float **finputs, float *foutput) { +void Thneed::execute(float **finputs, float *foutput, bool slow) { + uint64_t tb, te; + if (record & 2) tb = nanos_since_boot(); + #ifdef SAVE_LOG char fn[0x100]; snprintf(fn, sizeof(fn), "/tmp/thneed_log_%d", timestamp); @@ -197,7 +203,7 @@ void Thneed::execute(float **finputs, float *foutput) { #endif if (record & 2) printf("copying %lu -- %p -> %p\n", sz, finputs[idx], inputs[idx]); - clEnqueueWriteBuffer(command_queue, inputs[idx], CL_TRUE, 0, sz, finputs[idx], 0, NULL, NULL); + //clEnqueueWriteBuffer(command_queue, inputs[idx], CL_TRUE, 0, sz, finputs[idx], 0, NULL, NULL); } // ****** set power constraint @@ -220,8 +226,9 @@ void Thneed::execute(float **finputs, float *foutput) { // ****** run commands int i = 0; for (auto it = cmds.begin(); it != cmds.end(); ++it) { + ++i; if (record & 2) printf("run %2d: ", i); - (*it)->exec((++i) == cmds.size()); + (*it)->exec((i == cmds.size()) || slow); } // ****** sync objects @@ -255,6 +262,11 @@ void Thneed::execute(float **finputs, float *foutput) { ret = ioctl(fd, IOCTL_KGSL_SETPROPERTY, &prop); assert(ret == 0); + + if (record & 2) { + te = nanos_since_boot(); + printf("model exec in %lu us\n", (te-tb)/1000); + } } cl_int (*my_clSetKernelArg)(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) = NULL; @@ -311,10 +323,19 @@ cl_int clEnqueueNDRangeKernel(cl_command_queue command_queue, } } } - + if (thneed != NULL && thneed->record & 2) { + printf("%p %56s -- ", kernel, name); + for (int i = 0; i < work_dim; i++) { + printf("%4zu ", global_work_size[i]); + } + printf(" -- "); + for (int i = 0; i < work_dim; i++) { + printf("%4zu ", local_work_size[i]); + } + printf("\n"); + } if (thneed != NULL && thneed->record & 4) { // extreme debug - printf("%s -- %p\n", name, kernel); for (int i = 0; i < num_args; i++) { char arg_type[0x100]; char arg_name[0x100]; @@ -337,6 +358,29 @@ cl_int clEnqueueNDRangeKernel(cl_command_queue command_queue, } else if (arg_size == 8) { cl_mem val = (cl_mem)(*((uintptr_t*)arg_value)); printf(" = %p", val); + if (val != NULL) { + if (strcmp("image2d_t", arg_type) == 0 || strcmp("image1d_t", arg_type) == 0) { + cl_image_format format; + size_t width, height, depth, array_size, row_pitch, slice_pitch; + clGetImageInfo(val, CL_IMAGE_FORMAT, sizeof(format), &format, NULL); + assert(format.image_channel_data_type == CL_HALF_FLOAT); + clGetImageInfo(val, CL_IMAGE_WIDTH, sizeof(width), &width, NULL); + clGetImageInfo(val, CL_IMAGE_HEIGHT, sizeof(height), &height, NULL); + clGetImageInfo(val, CL_IMAGE_DEPTH, sizeof(depth), &depth, NULL); + clGetImageInfo(val, CL_IMAGE_ARRAY_SIZE, sizeof(array_size), &array_size, NULL); + clGetImageInfo(val, CL_IMAGE_ROW_PITCH, sizeof(row_pitch), &row_pitch, NULL); + clGetImageInfo(val, CL_IMAGE_SLICE_PITCH, sizeof(slice_pitch), &slice_pitch, NULL); + assert(depth == 0); + assert(array_size == 0); + assert(slice_pitch == 0); + + printf(" image %zu x %zu rp %zu", width, height, row_pitch); + } else { + size_t sz; + clGetMemObjectInfo(val, CL_MEM_SIZE, sizeof(sz), &sz, NULL); + printf(" buffer %zu", sz); + } + } } printf("\n"); } @@ -345,6 +389,53 @@ cl_int clEnqueueNDRangeKernel(cl_command_queue command_queue, cl_int ret = my_clEnqueueNDRangeKernel(command_queue, kernel, work_dim, global_work_offset, global_work_size, local_work_size, num_events_in_wait_list, event_wait_list, event); + + /*uint64_t tb = nanos_since_boot(); + clWaitForEvents(1, event); + uint64_t te = nanos_since_boot(); + if (thneed != NULL && thneed->record & 2) { + printf(" wait %lu us\n", (te-tb)/1000); + }*/ + + return ret; +} + +//#define SAVE_KERNELS + +#ifdef SAVE_KERNELS + std::map program_source; +#endif + +cl_program (*my_clCreateProgramWithSource)(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) = NULL; +cl_program clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) { + if (my_clCreateProgramWithSource == NULL) my_clCreateProgramWithSource = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clCreateProgramWithSource")); + assert(count == 1); + size_t my_lengths[1]; + my_lengths[0] = lengths[0]; + +#ifdef SAVE_KERNELS + char fn[0x100]; + snprintf(fn, sizeof(fn), "/tmp/program_%zu.cl", strlen(strings[0])); + FILE *f = fopen(fn, "wb"); + fprintf(f, "%s", strings[0]); + fclose(f); + + char tmp[0x10000]; + memset(tmp, 0, sizeof(tmp)); + snprintf(fn, sizeof(fn), "/tmp/patched_%zu.cl", strlen(strings[0])); + FILE *g = fopen(fn, "rb"); + if (g != NULL) { + printf("LOADING PATCHED PROGRAM %s\n", fn); + fread(tmp, 1, sizeof(tmp), g); + fclose(g); + strings[0] = tmp; + my_lengths[0] = strlen(tmp); + } + + program_source[ret] = strings[0]; +#endif + + cl_program ret = my_clCreateProgramWithSource(context, count, strings, my_lengths, errcode_ret); return ret; } @@ -356,6 +447,8 @@ void *dlsym(void *handle, const char *symbol) { return (void*)clEnqueueNDRangeKernel; } else if (strcmp("clSetKernelArg", symbol) == 0) { return (void*)clSetKernelArg; + } else if (strcmp("clCreateProgramWithSource", symbol) == 0) { + return (void*)clCreateProgramWithSource; } else { return my_dlsym(handle, symbol); } diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h index 9f35f5dcfb..89e8522570 100644 --- a/selfdrive/modeld/thneed/thneed.h +++ b/selfdrive/modeld/thneed/thneed.h @@ -20,6 +20,7 @@ class CachedCommand { public: CachedCommand(Thneed *lthneed, struct kgsl_gpu_command *cmd); void exec(bool wait); + void disassemble(); private: struct kgsl_gpu_command cache; struct kgsl_command_object cmds[2]; @@ -31,7 +32,7 @@ class Thneed { public: Thneed(); void stop(); - void execute(float **finputs, float *foutput); + void execute(float **finputs, float *foutput, bool slow=false); std::vector inputs; cl_mem output; From b9a4e8c8827a3eb6d2c400f5c1f5e73b3a6c85fb Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Mon, 18 May 2020 02:01:05 -0500 Subject: [PATCH 028/656] Added fwdCamera f/w for RX350 ICE (#1531) * Update values.py @mikoko#7438 / @mikokolee DongleID/route f2df066cef1b3647|2020-05-17--16-43-43 * Added missing commas --- selfdrive/car/toyota/values.py | 25 +++++++++++++++++++------ 1 file changed, 19 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index d5d759ca37..cb08bf60d6 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -821,12 +821,25 @@ FW_VERSIONS = { ], }, CAR.LEXUS_RX: { - (Ecu.engine, 0x700, None): [b'\x01896630E41200\x00\x00\x00\x00'], - (Ecu.esp, 0x7b0, None): [b'F152648473\x00\x00\x00\x00\x00\x00'], - (Ecu.dsu, 0x791, None): [b'881514810500\x00\x00\x00\x00'], - (Ecu.eps, 0x7a1, None): [b'8965B0E012\x00\x00\x00\x00\x00\x00'], - (Ecu.fwdRadar, 0x750, 0xf): [b'8821F4701100\x00\x00\x00\x00'], - (Ecu.fwdCamera, 0x750, 0x6d): [b'8646F4802001\x00\x00\x00\x00'], + (Ecu.engine, 0x700, None): [ + b'\x01896630E41200\x00\x00\x00\x00', + ], + (Ecu.esp, 0x7b0, None): [ + b'F152648473\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514810500\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B0E012\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4701100\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4802001\x00\x00\x00\x00', + b'8646F4802100\x00\x00\x00\x00', + ], }, CAR.LEXUS_RXH: { (Ecu.engine, 0x7e0, None): [ From 6daa255c448f6491f49ee3534fab3797d2c14332 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Mon, 18 May 2020 02:02:37 -0500 Subject: [PATCH 029/656] Add fwdCamera f/w for CAR.COROLLAH_TSS2 (#1526) * Add fwdCamera f/w for CAR.COROLLAH_TSS2 @jamcar23#7629 DongleID/route 095142f13f39faf9|2020-05-16--15-54-21 * Forgot x008646G26011A0 to x008646G2601400 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index cb08bf60d6..7cccaceff5 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -502,6 +502,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', ], From 4b13a58a93a8a47d32b65cc3502845634df20f80 Mon Sep 17 00:00:00 2001 From: eFini Date: Mon, 18 May 2020 17:02:55 +1000 Subject: [PATCH 030/656] use constant max speed limit (#1521) --- selfdrive/car/interfaces.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 65a302000d..ca83cabb7d 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -7,9 +7,11 @@ from selfdrive.car import gen_empty_fingerprint from selfdrive.config import Conversions as CV from selfdrive.controls.lib.events import Events from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX GearShifter = car.CarState.GearShifter EventName = car.CarEvent.EventName +MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS # 144 + 4 = 92 mph # generic car and radar interfaces @@ -102,7 +104,7 @@ class CarInterfaceBase(): events.add(EventName.stockFcw) if cs_out.stockAeb: events.add(EventName.stockAeb) - if cs_out.vEgo > 92 * CV.MPH_TO_MS: + if cs_out.vEgo > MAX_CTRL_SPEED: events.add(EventName.speedTooHigh) if cs_out.steerError: From 495e0c4648b5c3d20709bb3e08f83dad62725c2d Mon Sep 17 00:00:00 2001 From: Comma Device Date: Mon, 18 May 2020 17:10:08 +0000 Subject: [PATCH 031/656] wtf, how was that commented out and the tests still passed --- selfdrive/modeld/thneed/thneed.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/thneed/thneed.cc b/selfdrive/modeld/thneed/thneed.cc index 785463780e..6bacd5440d 100644 --- a/selfdrive/modeld/thneed/thneed.cc +++ b/selfdrive/modeld/thneed/thneed.cc @@ -203,7 +203,7 @@ void Thneed::execute(float **finputs, float *foutput, bool slow) { #endif if (record & 2) printf("copying %lu -- %p -> %p\n", sz, finputs[idx], inputs[idx]); - //clEnqueueWriteBuffer(command_queue, inputs[idx], CL_TRUE, 0, sz, finputs[idx], 0, NULL, NULL); + clEnqueueWriteBuffer(command_queue, inputs[idx], CL_TRUE, 0, sz, finputs[idx], 0, NULL, NULL); } // ****** set power constraint From e14dfa3beca9897dafa776fdd68c5076d7a31d4e Mon Sep 17 00:00:00 2001 From: eFini Date: Tue, 19 May 2020 03:15:30 +1000 Subject: [PATCH 032/656] use buttonEvent.type instead of string (#1533) --- selfdrive/controls/lib/drive_helpers.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 629d072e82..ea7002475f 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -1,5 +1,6 @@ from common.numpy_fast import clip, interp from selfdrive.config import Conversions as CV +from cereal import car # kph V_CRUISE_MAX = 144 @@ -35,9 +36,9 @@ def update_v_cruise(v_cruise_kph, buttonEvents, enabled): # would have the effect of both enabling and changing speed is checked after the state transition for b in buttonEvents: if enabled and not b.pressed: - if b.type == "accelCruise": + if b.type == car.CarState.ButtonEvent.Type.accelCruise: v_cruise_kph += V_CRUISE_DELTA - (v_cruise_kph % V_CRUISE_DELTA) - elif b.type == "decelCruise": + elif b.type == car.CarState.ButtonEvent.Type.decelCruise: v_cruise_kph -= V_CRUISE_DELTA - ((V_CRUISE_DELTA - v_cruise_kph) % V_CRUISE_DELTA) v_cruise_kph = clip(v_cruise_kph, V_CRUISE_MIN, V_CRUISE_MAX) @@ -47,7 +48,7 @@ def update_v_cruise(v_cruise_kph, buttonEvents, enabled): def initialize_v_cruise(v_ego, buttonEvents, v_cruise_last): for b in buttonEvents: # 250kph or above probably means we never had a set speed - if b.type == "accelCruise" and v_cruise_last < 250: + if b.type == car.CarState.ButtonEvent.Type.accelCruise and v_cruise_last < 250: return v_cruise_last return int(round(clip(v_ego * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN, V_CRUISE_MAX))) From 52fe671c53faf2b2c72402c5c16ec09f2d0eacbb Mon Sep 17 00:00:00 2001 From: Hylke Jellema Date: Mon, 18 May 2020 19:41:19 +0200 Subject: [PATCH 033/656] More RAV4H_TSS2 FW (#1523) --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 7cccaceff5..4b16485d0b 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -750,6 +750,7 @@ FW_VERSIONS = { b'F152642531\x00\x00\x00\x00\x00\x00', b'F152642532\x00\x00\x00\x00\x00\x00', b'F152642521\x00\x00\x00\x00\x00\x00', + b'F152642541\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B42170\x00\x00\x00\x00\x00\x00', From 6c0ad1e67567e149cdf9e00ab7ae43f4cc5bc579 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Mon, 18 May 2020 11:34:29 -0700 Subject: [PATCH 034/656] add thneed self test (#1535) * add thneed self test * don't do the memset in thneed, shouldn't matter though Co-authored-by: Comma Device --- selfdrive/modeld/runners/snpemodel.cc | 26 ++++++++++++++++++++++---- selfdrive/modeld/runners/snpemodel.h | 4 +++- 2 files changed, 25 insertions(+), 5 deletions(-) diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index bab7432207..4f3d8f58a3 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -9,8 +9,9 @@ void PrintErrorStringAndExit() { std::exit(EXIT_FAILURE); } -SNPEModel::SNPEModel(const char *path, float *loutput, size_t output_size, int runtime) { +SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime) { output = loutput; + output_size = loutput_size; #ifdef QCOM if (runtime==USE_GPU_RUNTIME) { Runtime = zdl::DlSystem::Runtime_t::GPU; @@ -102,6 +103,7 @@ SNPEModel::SNPEModel(const char *path, float *loutput, size_t output_size, int r void SNPEModel::addRecurrent(float *state, int state_size) { recurrent = state; + recurrent_size = state_size; recurrentBuffer = this->addExtra(state, state_size, 3); } @@ -134,21 +136,37 @@ std::unique_ptr SNPEModel::addExtra(float *state, in void SNPEModel::execute(float *net_input_buf, int buf_size) { #ifdef USE_THNEED if (Runtime == zdl::DlSystem::Runtime_t::GPU) { + float *inputs[4] = {recurrent, trafficConvention, desire, net_input_buf}; if (thneed == NULL) { assert(inputBuffer->setBufferAddress(net_input_buf)); if (!snpe->execute(inputMap, outputMap)) { PrintErrorStringAndExit(); } + memset(recurrent, 0, recurrent_size*sizeof(float)); thneed = new Thneed(); - //thneed->record = 3; if (!snpe->execute(inputMap, outputMap)) { PrintErrorStringAndExit(); } thneed->stop(); - //thneed->record = 2; printf("thneed cached\n"); + + // doing self test + float *outputs_golden = (float *)malloc(output_size*sizeof(float)); + memcpy(outputs_golden, output, output_size*sizeof(float)); + memset(output, 0, output_size*sizeof(float)); + memset(recurrent, 0, recurrent_size*sizeof(float)); + thneed->execute(inputs, output); + + if (memcmp(output, outputs_golden, output_size*sizeof(float)) == 0) { + printf("thneed selftest passed\n"); + } else { + for (int i = 0; i < output_size; i++) { + printf("mismatch %3d: %f %f\n", i, output[i], outputs_golden[i]); + } + assert(false); + } + free(outputs_golden); } else { - float *inputs[4] = {recurrent, trafficConvention, desire, net_input_buf}; thneed->execute(inputs, output); } } else { diff --git a/selfdrive/modeld/runners/snpemodel.h b/selfdrive/modeld/runners/snpemodel.h index 496ad51db2..11aa14ccb5 100644 --- a/selfdrive/modeld/runners/snpemodel.h +++ b/selfdrive/modeld/runners/snpemodel.h @@ -23,7 +23,7 @@ class SNPEModel : public RunModel { public: - SNPEModel(const char *path, float *loutput, size_t output_size, int runtime); + SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime); ~SNPEModel() { if (model_data) free(model_data); } @@ -51,10 +51,12 @@ private: zdl::DlSystem::UserBufferMap outputMap; std::unique_ptr outputBuffer; float *output; + size_t output_size; // recurrent and desire std::unique_ptr addExtra(float *state, int state_size, int idx); float *recurrent; + size_t recurrent_size; std::unique_ptr recurrentBuffer; float *trafficConvention; std::unique_ptr trafficConventionBuffer; From e864d1af2fbc191c50af99a33cf252b3d56bc4bd Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Mon, 18 May 2020 14:37:47 -0700 Subject: [PATCH 035/656] update --- common/window.py | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/common/window.py b/common/window.py index f93f532cb4..5af3d83cd0 100644 --- a/common/window.py +++ b/common/window.py @@ -1,5 +1,6 @@ import sys import pygame +import cv2 class Window(): def __init__(self, w, h, caption="window", double=False): @@ -9,20 +10,20 @@ class Window(): pygame.display.set_caption(caption) self.double = double if self.double: - self.screen = pygame.display.set_mode((w*2,h*2), pygame.DOUBLEBUF) + self.screen = pygame.display.set_mode((w*2,h*2)) else: - self.screen = pygame.display.set_mode((w,h), pygame.DOUBLEBUF) - self.camera_surface = pygame.surface.Surface((w,h), 0, 24).convert() + self.screen = pygame.display.set_mode((w,h)) def draw(self, out): - pygame.surfarray.blit_array(self.camera_surface, out.swapaxes(0,1)) + pygame.event.pump() if self.double: - camera_surface_2x = pygame.transform.scale2x(self.camera_surface) - self.screen.blit(camera_surface_2x, (0, 0)) + out2 = cv2.resize(out, (self.w*2, self.h*2)) + pygame.surfarray.blit_array(self.screen, out2.swapaxes(0,1)) else: - self.screen.blit(self.camera_surface, (0, 0)) + pygame.surfarray.blit_array(self.screen, out.swapaxes(0,1)) pygame.display.flip() - + + def getkey(self): while 1: event = pygame.event.wait() @@ -40,7 +41,7 @@ class Window(): if __name__ == "__main__": import numpy as np - win = Window(200, 200) + win = Window(200, 200, double=True) img = np.zeros((200,200,3), np.uint8) while 1: print("draw") From 6d72a5e1f9608d9f21c156be86adf0481938cff9 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Mon, 18 May 2020 14:38:12 -0700 Subject: [PATCH 036/656] bump rednose --- rednose_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rednose_repo b/rednose_repo index e50846d845..9cfff6ba92 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit e50846d845f7fe542e2538476258b926b2643398 +Subproject commit 9cfff6ba929398155cfb5888db500ebd86a45910 From 92f07b92ab1d5f395dbc2783f04112ebdbb8a5bd Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Mon, 18 May 2020 16:22:04 -0700 Subject: [PATCH 037/656] Add missing Civic Hatch FW (#1539) --- selfdrive/car/honda/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 83f2c66a9f..c9933e2a1c 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -378,6 +378,7 @@ FW_VERSIONS = { b'37805-5AW-G720\x00\x00', b'37805-5AZ-E850\x00\x00', b'37805-5BB-L640\x00\x00', + b'37805-5AN-AG20\x00\x00', ], (Ecu.transmission, 0x18da1ef1, None): [ b'28101-5CG-A920\x00\x00', @@ -424,6 +425,7 @@ FW_VERSIONS = { b'78109-TGG-A810\x00\x00', b'78109-TGG-A820\x00\x00', b'78109-TGL-G120\x00\x00', + b'78109-TGG-A610\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36802-TBA-A150\x00\x00', From 9228e964a0805017f540c6df456d18deec9d1292 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 18 May 2020 19:50:02 -0700 Subject: [PATCH 038/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 6b19fa4961..5307bf7277 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 6b19fa4961d5dc6e6ea77987eb3a99ce28b0f5cd +Subproject commit 5307bf7277c267075aa03799c8749a60463c8804 From 8d46c0fa8a4ce2779de435ff5f5c2cc8b9cc07ad Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 18 May 2020 19:56:33 -0700 Subject: [PATCH 039/656] apks need capnpc-java --- external/bin/capnpc-java | Bin 0 -> 3052120 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100755 external/bin/capnpc-java diff --git a/external/bin/capnpc-java b/external/bin/capnpc-java new file mode 100755 index 0000000000000000000000000000000000000000..55af5b5763d002bd1aa3d5cc3bef8f39105d20ec GIT binary patch literal 3052120 zcmbq+31HO4_5XsPcxFXv@uES~6EzwXbU{<`z=R_hD#r?m;DN@%TGn-SJyxl$ zHXgN9t6i|&A zfk3IyS&y@NBd!py;C}6-o zZF>_@kNSPre?e1ll4)-sITszE1?`je=f8tz&zg3`VF%BianS5pa~l>Nv}o)R2OV+P zs0H&z9U^*@Kg*tSdKHTYto=*znKF;SfAk&FKfUOe$&06)_54<+ZFl^z^Bz92WAYB= zq)otow!g0~50vf(kU0K31OKhNdW#qCnBMxQMdL1dY*5|M`-CvSpP9f9?}v6W1nUp~ zHwf7u{-6QyTMmH#cz|}_fr9<lOH zLkGau48VWi0q~Il_{WOKReGE0M7{8U-{Dq;QxaG%I`Kn`CA6)m%|4rfBOLV z^9R6}3}Cm40p$GS0Cw160REp3z^8Tq{6WyS6#w=9w<&^ue|G)`@@(6?FyOlekmp*^ z`r~syr32Xcy#dOX4&V>x3}Bz%4&b*}4d6fYg;M<2``+Nm?RNC*Y0$DK8ydPeR1+6!kbsIQ%W)`Syh z&zoC&*3@aUYXjA%UQ#{D5Kf#ub-{w#1zNt}(hKL$s;>=@bD+AqcK-ai^Qvdhn?ALE z*1Wj^(`5CWhWgq?L|+tGFzdpp)B7Pd%oQ@^Tu?t_`T++}%p<_@!a4KiRxhZZI={ZU zI#7M?SwB8~bf~&|`l3Zsr_H)#^yo48OcAT=FOAez&zd`PUIj{>S%1ip)sv=G*Uzsd zazQO>Pn|oXdVcM+sk5ifonAXFd}jUVv98G6c{6IOr%hc@duFJ5(wS(d`ocwvsw1`Y z7tEVGb@r_KORFz|$$B?_2n1O$tDp8E-qh*~8>Y^mQ9X6qy!rM0R2^MieaW1G>(=I#YZpzgjfm;1 z&z&(le2FPK4P8CA8a+0>P8y?HaFuxrt7q5Fy|BKHojPxR__XOpl!m#}r#4(zS6}V; zSx!@DOV8I9D5i;8*xoj9*0^4xKt1%Lwm5AnOhztXdG6__omoG&8eUpIb=GW16`nt9 zPA&SdZt8-%>d3s=v!-7<`mpK=)pKiW*|kJh%$YNXHT@<|I;6r1sC_cOc6KfL+Nk54 zVAkAkv+TKZ7lOOkcYdu1Y#{TwxTgyIpoiCk&e=?5<0#WFZkRQnLWzN#Ap#f?7fzpE zy?_H^bfCIw?!sBH=A_yM4RdNqoUS8fL1g}{x%D#x3+m@%h{0>Y9m8h&Mb*>mE~=gh z3kK#~G-K9$7O0;$8|2zWv+4tLYUfO^n;(eGi`32yTv%HlnKdIYYr%rZ)akWaa)v%; z2IkC}8VSrqkp+S2(nTb|LyQ(vF~XJKg4+6k1cggj0{@pr=0pMw7>M9gmdi>5(=`uRo}@xyA-fHE(*bO8k+hdJ{usSQk>KD~AU#!EGg zVnW88sk7z=7R)uanTc=^=y%Tq|C_y_8bVZ0oiSs6;FJ?jtUeS`@|5x8PB^jpkWq)a zPlvfrqYEDo8Fjd#Cr?JT!$yrB8#r{n067OzY%AnLsg!DS z0)w#g`y)u)N0#Eh@ZOhh$(je70;F$=&z8R3tXW$J(8d@?-z2cX)GtH*5klWAP;Tnn za^tPoE^it*&A<&i&f1*%{Mf7iTht?e*01Zn4Kwhtz%*0-#ou3qPeTJ28@PVIo3Mr7 zByfeRPYJa?9s%V)*zq5^gU+)oQ-=T84*yk-=^r2Q@Z+?o{LPUh&Kc?CX{9 z_VA~A_^ijrZ25(1*8^0`?!8H{>jC0VC&K(2S*GnW|3TgCzfunmL%M(adU*8&C51dZ zmMreySPySZEwnNZPo3?*N)Jz&?7y&wx49S6CVO}|g!@jg@@nH{ z7KvxOhu6%N64!b7AA0389)6^U-{9eQ@bH};en$_V_3%4+_`HYT*~52x_#b)rKzYG$ zck%GUJp8U6KIq{~J^V-yznh0I_3*oU_G;o;LBevF52@$h3ke7lD~(!;Ow@JD(0jE6tk!*B5L%yHU( zogV%ei^MbQ;g9w3c@KY_hwt|A$9wpIiT{j|CwTZ_9{xlRAN24idH9hYzQV(odiaw) z{JtLk6b~Qr@Rc5ZtcMSK_%aVa-osZe**L5+KJ=x%j|o&p+v|sBmtZ!jT(V}^YOfGJ z_8k5+iuCNY27gO-EyE|mbu5(Y?7_diRuSfumdgnI2w_fTxpsl?C(J10-s8lQ%o-Z4G?>sK$ufYu2bNn2y;rwWduHi zFsG7SyTJPs<`j}k3%omFP93=>fp;X#DI=E@csOBB6}d)%w;;?ZA{P;OFkwy&xf+50 zvln1a3AwPq|0K+*AXg^vM}#>AdKzhWK3m zYwG_r;Znk#0ke^3wWak0`pGugaI+y=S`kydEbgon2qX;uJ=Q08xLYN^r*Dmn>gc*u+X@Peq%n+Pw z5_m_#486Iez{3eM;x7@LA(J z+H3Z#3RHGHmEVJpj@9Mmf$VLN>+_i&8RkWl!e-(pGkw)OLKSyoI` zpjrc(>&UkLbCAOLeC+4=9IHrHCaRJUV_9YFWfqxvz+iM{uXv|g6Deqqq z$1t^pl2oF5M&+SuE=+nCz~hWDuihBOBvu(~Z9(b&Oqze!m~>D*thq_a(p4y*y9qN} zWg^O{!pirD_bFeLvrT0pB@~tN*<67Ti>{+oaeY9@8=z-pEZRwIER`)Lu2EuMiQRl8 zQUWDR4e6MFq1e*)lBJ!}H_;lEKv_zGk>~-4CIqy(7+Gm}2?hq7VNiWl?q=;&m^!6p zq}Em&`xyMtk7@8IZPmZc&qM5_&AU$2uJid#R(|Nbj_eC$6pOa2O7c*)rf2_y15b!! zwCuJabW1YK3|TanVRdw}e6ud=6Y52;hV@E&!vCX>F? zPWu|nEg=@ou;sWu(DE+YFWSecVYGLFc%~5Hx3Q|_GJ=eoC|~yX()Ri@VV?G4H+h`( zh(!bCY98%s?eQY>yuOcgs0z@LJs(xOZboJHpr^!|52*x2iEdC04Degoqu zJ7z-DD$f0tvA?i8cFu?$rEBgN<2;RGY2#dv5Mw&7`&lUoQb%?p@zHh!ZglwmTA?HR zA7bOE5FP{+BoJF(|Cd35aj`YyVlQ*O8s*F$BfH=0Z zg#G&6x^}FLt+u7QanxNI+rWl*?e6KxUiPJo#LDx^&o7@cMP?4Q!POg=VcCs{x9C48 zfjKU=UaS$V5ja(cM=zVSbYgZad5pas9fCFYlZ3Nb7}uy*vh?F&fxsVOF(?+jK^S#p zcN4=zlK|VA_Q$*p*)Cc~0|~BjNqewug~6X$gfDGN8~o8l_)y!U2ERuUzO3z!2ESzy zKHT=C!GG4_w_DS;#^7Hs!bjSkGx*g$KHJ!~-ryhb@I$#=X?xjFZuBWlq`YA$3w;VF z(6+Y?Wr|N}C*?y!Ink$NNZDv8`}vekQob;h5}%SMf+eR76IX_|fAVb5L`v9DUhyeuQl=P6t50bsWtySf<5M!ETxcjUpVCQ6 z#8Bq>lsqX54W-JbAo(9?yV6jO_9?uL*S6G9cJnEvq+Dw#oB5OwDc2jy$7?(rl#!A$ zlox$Un3UTMWu;H4A>|H3`IS$JkaDk~M14vlDJu-+BA=2ZMF`#XhB-l;aI$x=+cFaHHPv7pMqm6j7CHG?^B))f~3qfl(&6KDJcsLrNgI$NV&pL9`q??q{Iy6W}gx! zrOvV|?tL@v)pNd!BkS za1s_Xo9#Z>ENiab*weGB4*AnI5}urS&A2yS5D8Y zt$3>x%geXS8uiDxj2L^WGM0%=K#LXG%6P>(Y;f>dmazNL07S(naI?LYE>eePKZT6X ztWFl?HewBV6h)4s3d_%+d|c8#jA}f0`8MRzjm2Rp;r9c=wR>&Z}OVD35$;9 z5|&%9SaSpqUxzG~@$nR~5WmsLw|+QBK~*DA8H4&#P!;Jma09!J>^-e4Q_1jxhi>(_MdsWufPiH%ajbM^J zh~_h3-)@?}YXs1-r@>D35HnV8KY}}7-3-071xkp#9og+*2{fW*;}fz48z0^^N;d*v z+>yPDbz&R3@Q0fN=-QEer3X^$=3p?KAv@(GI?I%9(=W8>3am$9(K_xEW6d@4NQLp} zZP-M#R17Obqsi8fZ4EhHGMpzu3WNQ7DJY&&D0aMG0 zi9;~(K};%fIUk9XKnYVrx@8QCQJHgTCOTCjrTm0?9+`-%A(NJ)eot4nym-Z~%O1UG z(_d5``LtM~{tD5PE~r93&XS^fNA}bASt3g;CN zM2aP%O`?Lxvnz%w%pnBy$Mx#PXcxH)E8eZmf7qmZ-FtUB@#gjtZ=@&QBo$8?YMRPs zzqEPPXcw`ACckX2i9pwXEdpsup(FeC69P7h#2wkM5Y%!}F}=|O8+#U^2fNO{SukrW z<56|eS64l22IT>07GuVhyi?h$L6BnunBz@wQ-FfbERZ ze~EbNUme*8u)e2zT8FK~5n4r~pKjDK&t8xHH9K|@LKt#j=uVM=|cdlMA` ztKPz&wo;JDXbqK<=&Ov6TfUvqu2Y0VltE6n>xZhbbY&5rE7@?_i<9p2_nOiNr_OnK>63L)v52r0%cMR9#-w)s7hisE#g#_1IzL$it^ z@v3i}4r!Rw&?b&ho0d2oBmvUy{vXjt$^l&cXMirFvsz7GW6G{U(ije#>}Sj*$!jC? z_$Ijua3Oigm=O^Z95a$;)uGbUu%f4-si$FiPXlVpuo=|ghE1NznXGKwq(2j?s(6yp zHMg9Isy3ou?B61UmH7ezduK&IqAzP!w1o}XRAfi?etJspu_k4p(OXK)h~ZNkM8uRp zHt>iD!}rv&*6f+DXsjKI0-m8BeU64=KC#`zg0I_$vw&6NEs9%wLSWLciK_O>M02MI zw0_l%#@)vVe|t>e8RunfSd0gKE`3~V)h^XLvR6R8-2UP*#-bhB>D?+@JgV*{3Qi%? zS{?aJ#7Ztpq(qVXPV71r!>8*29Ya=~XHnjcH7m*|j}^w6_078(gLQzM@h+Au_rGn2 z0#}mWibVrub42^4MjnYU9^+%t$$0b~7hxS2EMrVQ;lZMDu?5@qVjPpYZd`mO9b3^z zr~iGH1qYr;UO|?}V>FG7WKf8-GARDXMDmY|dyj}DMUJPamXUltz0#g(v?@K3*J5Ie zxL9T!v)&!qr${hI1hxyMQ^Q}1pdmBZ_fk;Uq1x%qMQRLshHAiNqiNyi2l+ogWaqY& zm|52a3!fhp=!jm2(l8$6tq|)ihU~GY9%&xQD)p^R0U7d4-xz0De^E4E9(=U zV1tV>#U`|l(RZC$dmn{6B&d*=dTze`=Z73){S1@s2jGs;a#rwP5U10ZO8?_09m1VsT~a9I#{B+hz>K?B-om&$# zBJ_WZwpl!8GQRaM=7D9Xby7}${wbUi7cJYap6fyi^&hu!O3?} z*H6J(OLk-@P@@>Pt?B}z^(msJEAt)>>*?K6B0hziRdZ_9|E%yR%G+7Nw!a}=@L1dS zb-V-1cq+6Q?Xh^t8}nMadd5k+)l58D-8f`j@WO4YI}OXPX(RhzY75C*!2%4!V9iwCZ)XsYhT zX*la9s($7%uLi1XyI#msS#C+ivO&3HU>`7IEnlQ(#0ny*HB6oIM)JeYT|9(&B8ldj zXr%Ym@lm5Adj{q~33lvC?$bgTyDKE8|ryCbu>MOAbhyajBoZ5zf(D=%!tZ@Y@*tWqoXZ zP*J%L5KAQldputN4m{D%%Qj(Qn&Qt7vK&SaGG#hYpC!gn-@|9R*}7sYxuafT@uaYj zy~AOz!6-LufKisLsWcYBz9@vmUKR%Fgh6m(TzpX|&eUBMs>{HY2~SYPX}hDqw2*IG zt}%ZZgG{WsQ68y?JQAGau-2->!*7a7xP;5WO#RSYqZwZEvm0=P97Bd~$e%WZs&Ff- zG9D%4wwuig_SPR^Df)NZ<+OzR4B;~p)_8=63?U2;%{|}|?4iYjB;4c?>E?^4P}iQk6_!_$i`3c2)2!JtTDDl+vC)WmqzQ5uU)uC;nZp|C=READzPcK;|?;_1Q`z!i`lNQ zv1tSGFtcXe`g4{612Fy5{TwQi=V^Q0sI~(#mk>i)>55c6`ytp2g*z#qP3a}lBCV)5 z`)lcdc4Fe1SuwjQO2k_cPiHTAP4;3k{aE3A6SYYqRooYsMx2s~W~sphMJL1@7kj3> zdknDJZ;z?S<&6X8-U3xdw1gp+euU)6DqY&@Fzm>__kwhdw5$eK zv3+^B@#Hlfl4zi^E(dcyJcTh_?7bU=$emf-%;7J6i`(3vgWK#&Q!?MvTa=6fM|>as zPWpF|eu?`E`n`!|?YHSS*NF5Rh~)GeLH$l1NWRMNCEvZ>Me=?8>wlRg?HGXik2sNQnO;gTSkIaXq?8 zoQj;Jq)vO9d55#7IUs+#!L+A2FMqT0m(6f9iRAuyHEx&KM6B7+7fpjbx6@D>)y>4D z28!V8Wz?=RMq{s;#b`YRGs7>>GBGocrCQjA4QB~X`IVaW<2)wQil+Sv>A!cuE7`S^ ztEB6MCyc}VRl3Moemf4i1?Y|JoZDe>Cc7&d*?s5VLn&m5x&E(Io@sE2D6WPYA;%%RtpxYtt_StxymK}K-`6^3( zArVs>*$xSincVaCVY)vYGxw}l^i&k>w`3hl@_q|^Rn-2eWK}$-xV&2`YRWS2ZkCUD zq~C$H-Bd%7e0lzceU- zv(KB_xu4lY<}UTTMqArx;4>Iz8Q{_n#Bi}b0A|pSD$p`^!h5lRh1RdgQMU=xW^2-# zVU@Td&3+|r4gh7Z@*lmVBud9s6tk_;4CC-OrM`}4b8^)zrM>0kNt5SL&?Sv9IsGy$X%aVce(T6?@(g5= z*-SOZ+fHc1hH9(klwZ>8Qu=eS0lQ zg#f=~(EyD$};}-42^S~f}x)&7`l_T zeSZ-Qz2{9Zbi9fg-x0muQ;fu@6Ejjy2oS5SZ9ZmRmehl%P? z3JFY2es0x*D;=1svJc-lJYc8GB^$>|{pb5y^Ler61JFQOwhK!roN2QOra#|?zKt_k zShXQ{jks?7y0@Tmt{s!a%0`P6MJ)wVmvr}AFE$ZXr) z!Kc1pskYt!-s)*&MpDMz#{Rocy|s7UCq1gXz*nevuTQEek|*Yq=uesd;ZK|MmbJa8 zaVb`#X5dPmGj$34>2EjCpS<(2!h0`L=(+~yPy4`?vOitz`xCRn-`OD|hs#Qd4q>m~ zKaujx=Nw`(3ew^4^r_AvY7Di}r#gq2WvJ79s&j~o4D}?R>KwwhySGnu4q@9J=2M+R z*mgg<#nZ?+gl+eEpXwaK)_usM8i%kIZ}v&*5LTW=KIz*W0*i=(L&zzEMsn%vrS))# z)rtS@5SK4-4zWFaA$##t)*xXIM>YR%*D8#6sy>XxRX)DY#@#X zLf+rnLV{rKc8rmD#YVn1Ibuoo;QEEw(?%PC)R1yzd8WQkSeiHnyFDfxXxK34I0 zf&bUYQQ+0xc*Wm9>W)=>6|eaG=!&lv?i{be$L_>dgX2}7$1C!KGDkkO&>Z;uNW|#c zUU-IwpsrjlL=gPlbv6jX<@?w07a~u#Ai=eQ*of>u^jy4!PAvC{io{%Ll)gnVR60nd zFOIf1T&aRwQKawzqS1f~Z`HrT3yf|d)&G*sl=W^<{pgBrTnp%>?oI7bw>3_6wMVbs z*u;>D>%d$g;X1H9WaI140`ihH&QObz8fV63ubyTV94(vW*oV665iDGz9S1HmP4=RG z)Xa{G^k#^`W{-}nG{~`vN2R{KoG2NSA7>e>^|EkLtH<6ctwy*$jcNAS>;}==Ydixl zzL8oWmaG$^+4Hg@?K z2=*=ED|1i64M5jKyQE%>wcbTZ5Xxk=t%-PDL=RyqtB^M+$8i|eij87xml60Qj(KCz zrGnJNOpy(Te;7bMgKvVPb2_qd9x=qs20vA)3w&uA#CQHkB2t&q_m%egg=_;~z?;cj z*s2*ivXPy!U1>+F$;w`DhnKb5lP|7D5G&lf_`6dU@6Pl(S|rvgQp7anACvcQeYcZy zFmbz(bhq@+F~6h(s7kWaMJkPF%R;>P0~(s|-Y29=+^8#hYymyAY)5t-3vw~5$I`zN z@J*UYC%NgCDf>BdF$nU-ec)ODHSs7@zG#JVa@X;?$FS0TID0$0$51|ZqORF= zXx}BsSQBnFPhi&i<0`;cuc2vitZQekf;TS7N*6W$0wYXcm#C!Lkpdhde9H}vK9cZK z3*+-5eD=M$TZ8Dn5=ELz<&g@?BQX*Wobd+akr;+YUl(t*Tlk)+aqhxZmRs+I9L9#X zVgnV69z({7)-pcg!Wa%g#+7l?wrpy5=#*kL-%{+Gzq6QxmUz`j9Y#O=v#=I@unCv; zRG);LhRCw?ICzufQTM_Jo`W4IPsEaub}=eDZpZa0=I0V}0P1iLO3p5-EiD>}OPNKj z>1iomHP*KP_*uO`jo6ug$*9!_g&cO3_Rwq;}1mT+~bm%}DPgQff<$ z=WOPAZH7WjtRwevF*K7F_Ul)zGR@4`$u+|O>Y91$Inl7x$33UGfRB5exVY8265_B5 z23?t$TJJbfoNg6|jZCcjuL1?xU=OM>vF;mCM9|kn!1b#-<+(Py451qKD5C>8DUTG1 zDjFSPUlp;&7jc9yVoM_i6MVF>AR-Hk8>omA(*GygSxrB_)^T@- zH?MlQCL{NsJY2iMJ?!Bc4ekyPS7UH74_9Vz4ZxYG`_W^Fx)seZb@6@sES)CSD#z2Y z<{*^#ACd1+xguI22HK8m$e4Z~Oe{5)+Q-eAY$S-tCzg#XJ+5@Ub8yJ3UePels7$R& z)WYl$A8t;KPIwmO_^m&ip;fG_M)^$y;sN=F30XR5JlsrkQhLzN3$rPy;oViRV-t)f z*74<zN^)b>pG$M zT)-C$)?b7C$y;?pQ(x@-)3D|^!)Y?s;dk~*Eo^cr zqrM|@qv!)DYF))PbUYg>96{O!8w*9%&5lN^wytgZJW8eOvCJcIvjZN6NQKA%Q(=Ae zUGLaU;CnXx+_8H(?d>$a2fwfRUQ0jxu5tYMe#CMtkGUz9m1Q%(MUOXO<&mhvqp#~L zu_OB^*3vvk%x<-$d()DiZG$Upnlf!1Yt9nMv~7mz@={)GxeDK{h^`XCRfez`2{TDZ zR5ZfZl)t#}*?*8VVk5ixPlMskFuC5XovNaNt_#YpEUCl1)HzmkFw5i)*TO zWVa`==rX~BOc)hve*wmNnIK4?2m9P(WG^?=CG}ABMxYsYIQ7;IhKksceTed5w}bbL zX;QsRK#o1lS^3*3e>ccqdTCGdI{Dj-bv1{>Vf_*&0-NQ22=tz_L+K6@$wwLV~^(2(H+%DZ!xI(ZNLpa$r!uIA0)0+v+ z8dw9o5?Yv#@2%hA1VLTz_ z@!A)w;q4W}`bwVP<3$%p-1dx-XqQImIFSh9P_&eG{_rIUs&^ul5piUdX#(U+uZgpg z89Hz*A8HKlNF?~k=3~(#;yD3gtUw7BNcQ6GPqSi0Bb-NSC7M~ZyoCo_+)F%XI<5Q(KJfGZRft^j|oAiIl&XR3O(Cl=z{FLFJ@q$gOTZG&ld z8|g9sPMCBQ(jx`i;sDOvbqxNEYRU+PdsrzC0gt38iH5f=7VC(s(eO3euyuj?d;us1 zn|L?r+~;{(_K=sbS%!<`6Y$=y@j75faONYMFUs5hwqLc zIi@_sAV_TqV=?NIh2mk>Qdcfl4?BplP`w9P6)BIaKde^pu${SI#FZsrorgVv%TnlF zaTIL&3hhk%T>2|0u9LcfghWE=;u;UXDjr5=aGiBRH`_Je!?sWR9;O2M9(F;y$dpI@ zwocQlJ=|_2T4fL=%xF>j#MQQ{QlVqVydX?6Wb&b5@|i3lT6O3oNJ7`A<Q4sN0q|?Y7uWXCFta#$a=fwt@@u zLd^cTf+8l|u^`VI>_5@IVCl+@tDp ztkJdu^#dWxAzXC5@_!lYPZ>1UN5c=XuXh@*jY-2+tS&fO?r3SaRV44PH_SlYsTkA$J#uWrB5Jft&zf_X#?Wcs~wwR9q%ng?NIf83rmXOtUF9g2< z4O+0sb~?SV5%)?+>M{zU!_};>|F=c{qSv})#l_p;IxUp191p$GlwNe0Y>e;`XIakz z&ALjqYQA=P!2-7{Nz{O5PlA*y(VI53pNsdq@XlS4lh){n?l<0-`qH|1e*$ibOlcD{U3o*TdPUQwa`MVcSaq zubhoPrCzy!i8>pig}PRvH6G4}qw78?Qq_i~)G8WN%q1Gc5XrcOlPYlXi+ohk|F=k_sJCP( z?+@^ddwVX?;}zi0kxe18=FU(=pakaehIah*N@*W8`o z+X9}fTMxkX<^tF9v&(;Mzv8!hM-10k>%Q;P-}<%DxT870ei(?8wbwA70)6B$akEFnRnwjnHY1X#oqIB{gmwoD_+%SO=zh(|M*-Xfl%K9;( z9V!Dn@D>u=DLN0xnGbAk`TpN~=(I!M?4y$oeFe~LkKC8E%e;CDm-Vp@Xe3UXXco`H z-X4|ewmh;5Kh}aj*lK2gm{>Pb0Tz;cG~}6BH&u~oDIuqbiG-9WU-<=s2{)sISS0oh zJL&!5GE;<|Hf7jXX%KwlA(2nCG#+m(9W&RMQ(_t0A>uV#JSRR7l--%}DnBJK0(93_ z2ro%$TM@M7(8&)i`Wzn}cIXp)bkLy>P=VE;x-j`t7QA#3HRz(TFdnS|!?U7q)D%^p zRF@R{rC4YZ+?T^>Qr+{4q*_F36HkXG)v1BCblq!S)w(McppKJFx234r04->@rKn^v z*YcGYgA;d7!V&M|zRykS)oa=jFN_-O$%p33;2;BnzfzDb5=<&cX$W4epmY8a%~6oF!7ro$>;GH=UrXn_CAlATCt>8Kh*`fP?y3PM1+7cat+brn*q z{Yp7irQ{9OlBKtq46w04MSr5s!ikI%H8Y^7ym{_KorF5*U@h&7y7B=rxey@gz7%!% zK%$O>IQ9-@$wmA86YM6L)16&&Xc*_(#<2MTrR7a{CoR7z0n%z|U)n8I zS|LE%%YFiBFN7HV8uobzjtm?6!nnbJdf}KF?Gq|qWC`cV#VP8}x`kbgm z9@``t@|2eLMcqtA6#_)P1Xl%evmr#kKJW<+I|?3KSuE>%68jkT>n_Erw2=X&E%Ml1 zCAFN=(!R9ktPsNr0n)C!5Yj${g=W9f-VK4A$KI*SQ9Hb@0j-a$S3p+hvB?2NE%Mmg zRa7nQi~7)SL{uR_)E`mQ9R?Eh9Eel!*e^^X(>TE~B=!-u>m$XQ80$+ru*d$u#8@fq zOB+yW(VzqiY`_&$~}dDg+4mY%PR*9=X?kg?v^T{l_yidr2v z9~qXjhQ7_Ifj}iKm_9EO$pY4Yo%RBiSE;^HAJE;R5Fqc4louhx$V;<%ap_vLPTLI< zp|H%^@{+B2#{h?fToe`7W3QqhWx|37w-;9Mfkn4K_}sG1u3Zz`#tm)53Qv?+x;vR}~i@k3B->I~PES*F-=7C`_jM2rKZLASCzlSDV* zf?SR24zcYcvnIGlN0*X((}s0dC}idpV7AJ3lsXLouCnR>F)&%)28b^edWDD ztp~UD>m4n2s=rcfbcJ81>nBhT zdnLPePj>B^?AkfmwL`LN`()R4$*y3sYwKj!7Rj#7l3hdiGfwDXyI7w)M+QOCEEZ2e zz_yX2{zQ}us~JgmUkD`EF%u~z8BVga+Wa12CIpyq5xobSP+3EEWDmt<0(1|<5ZB#@ z@hvKR?JD3Ut+Hq@i7vz9#%kInS4 zDIYU=@EuLSoGt+}7|fEYSV%T4BK?PdwQL8)?{H#XezBZ~w}TbN$2vT;O(apGitNbl za~;cc08@%LaNu>qTz3%_v9~dY@|)`a!%*0=0sg(2I<8$xUyF<&yt<*>sh);Zs`?*( z#RjPz8&viQl2>($Q%lO=U7R)N9ubF;O&&^SL|)Nr7P?_=l$HUD);txCD?Ogtz+y%D zq|I>|Yi*PU9OT5wIC1tAacI|qIA-gV63)2jhQf84M^1$Bd7|8Lv{~dI9i_|jjXWO5 zn`f?#h-;($PTH_2cM-pczT)LB!n#&vC1h-e`CIJ-{e~$E8jDZeP(L+tqS;W}jKx6^ zg&7Oo`bx&)Yz7Eigf2+cWjkVjmCE+n%U98;LtzL!hUjAxeGKM#hlthIuR0CStbAJ_Oqct+h6pRti4ciyGy=vG zzHqnGhQc%S8(&jFu~{_0_^-}&Mh%sq^pqvcX7Q!~>3CB>9)70rAIK@KjZ(>iXM~(y zTZmrNy`YzFl@kf!oM>iYrx%2zcZBPzr5o1kL4%w!WMfz=bb{qS(UWb&e&;EwQ+#iJZI93*rrt|PnoGL!6Ut&WD^(UyL6u09=(6RFtxp(7eOU1OuT>!(ID)xG!>3V zg&t3Jvsh7F`1C=j)<)G_uOyu`TSJ=iR@K{RY5QLICYo8+L6nw{O3f+i&Orv9B`#ojR?8iDJDVOow0K9yN}C|q|ThZg2J z432P}BoFX56nsBiH(x1v@C%zHTQoxe#c6Pl&&aTeEn2mFrN$Obt7ZSm9rM*|lG?i> zABN_+=gI6ST?g=oP^n_+$Mq%Po}>!EjX{x$rC$mzZE$-4*Vrm<+}J8kE#!zH50NT8 zjjiJRLJAvF?p$dwW5CxG%p34I1!*8Qy$nnC##RYs!bHX{@b{uvW2;0uWzI1T{B?qt zK-kzSVNu9IL!P7D*$pgxfdLu50iK~?scCyFXwhgq$?w7eI#1gT@Z40p?yh5XTO(C>hd#HzRfZ&Uxn7@QL!3 z*YdBPJD^Vks|I1==3cUw-;Oojc^FtrU*@AT4n5sRryY8{k4`%D;Xp%uGg{;rAuxkO&zp)l zSh(atC3}KEnJ3yc09R5I>*UKMae)uYPON)TMplA43_L;CaSS20ab!-clVb&3#zQL; zZ8I4G%u+*}$!nc7DQ4=&ML8zYIn%e1s%H}i?k;08En^a$am$6W%xjW;qdEJEW%d zjfRX=hQ$inj4VFRG9g3OI!>Fka5mZ``!=H?BNZXVhKhA7ucg8`58IJHv3vCzyh1Ol z1Qgz8x$mSf{hBM4S2DF83RsJFmJ#!6{Im(_ap^rPJ)Lk7&hSE3Pue0 zLj{ut9HwB}fd8H(LfR1Y7?yi>fsr>wUPh6MrSHjn$SA-jp9XH}>w;p)AnNzZDPwAV zbF(mJ#3%Jer84Fc{HZByzy%8C4LC!=pwYfc!H@w@R!|Nkz-kP@+_=5$Ts*iWs$Z6j zc>U#44jXq!z&RBACyCw?sNblRKy5kw9?3EkUna|1NrCBaDPy~|JqBbcDz;^%%kjGt zALD)z-nO-G*-IsjxU0_{9*|IN>R^gV>-1OCBL{}&F1F$H;Su|+#iDO_vlb_I^ z>BL)wc+11&C!#@&B$s2n_cUlD+fBQl*3pf`wG0*+9w&$%HwF6(zE1Y>6gC zEnP2}t}IgP6sTq5STxc{H(fND1cWY{On>T?pJ>=rp?O_af~tmXc7=g7Y?gvX0OJ@8 zq+vghMrjPsxc@ti@x}=f0Ry@e61_31Z$1^aK`xJG0Ju~^N<^?hL2(9vhy0jZamfPHB^kO>GG{4RnoWC9|F&!&QxOn~s0p$0yy@D8h=8Yq?F-jTgq z@RAyk@=3#ICL)i?6;v$kK?=q$oYJPi9pefMr;NeHfP*F2LzMk81=+_0FH$gR!1GOE z%r~S?Fog|xoGEO;gB9c)#=@lvW(>Hkf_VcDR*;>|!k<-&R5l3zE+!zIgw&Tn&3(9& zU18y(Zj!|RPlH>rg`vqm{|sb}zzL+|XPgAP5^N9X@(nS8Ru zW0G;`SA2BZq1%0Q(xHFrqazM|laCHN^yNM}6RGRy0e56uaR&q&V0uUQ*zHrZ{vOO|i>dCM6F$ zOsZ?*K-A3Hq`C(bpeyxCtLU;Mm0=we*I~i5iXJ4$Ds_@MNHAA-^&laYmS$`sLIBOi z^_TB3%|r%jhU=>Sn+f~PgaptOsobb8Xwz3UlVb@=ouc%OreaNA#h5UUj&df<2w>V# ztC_q?niONGe)1~^oGzm;q<3f7`J9%HJ3*tU0S{J?jgVTZVBUb+DoC+O9jqWVC-_;p zunHUSJq05Md`ZEi0oN*+HsIq5W(>GO!Mp)~t{`2B4PC1sosr<>3Wg0hTR}!hQl}`$ z=tS^z1%pPT;}r}UFr;AEfV(LeG2n0oZKh)r1DXl`^DLTEH1Rpti!*Mu)_r(*Ft@ru#>*Sp(F-u@sgtZaO$B1IMHWVTrU&pzx(Bw;_bek?qgdk=YHk@ z-5i}awu)U!mOkU>145tMxnhgOw4Ln5-833>)Qwk=%7r#|>h4_Zssl0jO-7&;Uk1#f z@bmZJl8<9|igF=X&}9T}I+~k(*_XT9EaoMUXqaxNPPD@#EGG9?(8qZWzeIEl={QP~ zVv-Y>@eAez^dbwsBaB^z?*vLqx@j2=wBdKo#^c_bHqW zGLS$e%U(_!$o&aORzrRDbPK(zESp)_?T=wRx2a=D4cE2EtQ4hL!*zdGfD?h+?r~2V zuIo|?C)BVzistc*qyTO{A4XrYrY484Xelf)ldh}EMNGNK;gpCt>K;Pn;d0>;NZ3(_ z3YDkQOvo4&bz-+iQY>7wUk2>d&&i&4 z9dO}g-ZCud&|x1Pap)s~hU;{4xSMtF5G=}N-Jze{w^7EWr1Z{xh{dQQ=!yK7?1R)%q$i?UOm4PR%kZTQ24T8kLm0kwX81~_ z)>4s3hVQmN;qaxY#4SnCoPY7~y%qYbjnb3_-_C%U4&VJ2(L%H^naC`l=b$zycnY!W%QD+>*g<{ z*z|~kQV~ZzOQ>{|0yXTYM+lYvki;jDAj4FdV1~ zIN9M4DGZ0x9$+!*2znw22~g}v9S&MdhQsjNIGfQ191d&BYn0XV7PDl%_1$ApeCO4m&o`LbNcMbP5xj;TG+Y?L}eh8#HaNY_G|1 z)2zkrP;@2h`)0VWW-s)~aHr9T4&!O{l$$P5&?@PuCkd6FQlLg0b#I~4fjpf#V$mr& zESg!^>dZ!a>0C4(Oop4S_ccJ@4EJ3%c07Ct3D7kk=;M8Tyr++M_3@5A-quGaA9@qg zzx$}iMQ$vt^T$HO^>k{mx|=u_s6WR78^Tzq)UlwI zTAM^784F)d=UAYbq)SPF7I+koh0CGO+9=IfutCt-V4L|k?lRXtTT68)XnahG^0?BA zveqpk_}ptzU>0^^q5NMLcB>|df7Ik&@fUU(CuQBmkh1s&XW9`@BT?=Wx#>UYh@(i9 zTSyq{M!(`|fMxxekF7c#zvHTo!VI*k+xN$+n-eaNC7=%I8zbJTF5}Rb`RKGmPY2q~ zJ(`Ugb*x#{^?i>!#fqAGmR*?)Q}i#Nw1ZpdQ5>gl(L#?B^#mc;KQ)n!f>JfkS_n+RT}e8Dpa6W?_( z`N)bu@OjhRi-MO0gW#J?yFZh5Wj!JI8iSuFcv)@;K4|zKdN29QYNWAM)+UXuvQlYm zm35004w=FiNTaf>5q#L-PX->k%i@x{NL#Xg*J4;XQI}n%x-9Pn&lMH%n+aZ4|AOa& zjQD?yqHMA`5PZfo_ln?U?;!XZvxtu$#qzSX5PYe@FA%)!JOrONe8%9tpT<_%m^8M^ zHl?vuHZ6^6o{n=_`lhXh|Zw=6a7PLp;E*PWRX zpm?VWzHn}tH+;6aoASuHWn-&&t&mF4h z+yRbk8xMh>{a!dL-_9N`X;c{I;jEUQA5f@k-ws*U1o;YITV2M)8pM9aE1EQlHhZ|V z!QJKIG6t9MaCWr(`)VjVrNk*~ni++Su+=7HBtIS1bGx{rou=p}UeSmtx(AECwTqpXkdr=nH%AT|^2I)R zup>tdd6G|lcWcW$X~>8A`O7~H`gE^lxgEmZ9S;{Y#{7$i3mM!h4`=)PKHzc( zY#xwXy|LA~QhZb?g60y?Qm#s3jJM?+D`C= zaS}2|ivQiSc$`EGpLYe{_lneQvTiO6nNqWOxJvMSuSlKvb2F4=03kdfy1^9I1Jb6s zdNjxG=K#wXTn%uxm%~Qf@g6Q>aAQ4O(%|;=aA9-fDd^!M2KUt-g*K7~m-TRIgZrC@ z%NSg{hszt>?>wAcCNKAJO=gKaenz2PyAX(=Tn2pXPn?F4`-d_A`fRB<80t^Z{X!Y;~4Al(Kv=#>L2da z${5^k9xiWiTYEU0CHRwF4%_gXG+W-z(!QyJ=LJ`sDrga0ajM{6;QC7yOh#kUuX0U;%0}Ep_ zne?BQV8iA9GO(Sdqyq#PkCSLsGM+IEc;9mD|X@l$Va5lAYm0e!@i}SDgaYHDCx4&@XXDlD~*W@C&uRQQ?&^`1M z3RBT&nZ7YWm^M<{=fSk!pPS?N)|8=->2;RBXe^# zqaHLY+3va>DTDio#gzc@<=y@Ku-w?L(eNg(=JhCQoq}(|k=teDrr*l_4_H2XY6Zo$ z-xAN?&srx7p4LjqS~Zu+Lw*S+mf#O=`rnI4iy*H+RW$JcPTCc0 zOwy>pLX6r&O>n_=d-ifJNjd+v1o*C<4{UOh%VwIQ3c_nHG&c0e|HuR2lU5B zsFjq_A6L~k1n<5azN&rzx+it6M6ZLXk?1GpO4MbVEL8(_WEWz$7K@$_#=bI5fK}u& zi0rg)bm;x4i7{WImDSNaYvC3EOW9u`rM)IvfF=SUcN-F&D8;+j?R?hhPut<=5A}!b z@N1+jg&upcN=`@0pd|ScHEN`IW|IMTRgip0ZMjaUodz7FR5nfOKYu7xibe2UfVrhI z-s!=%h3A2`9&DRw@o=`S@ocM*JG5;kyrQ<@OFf)zy%sn#C|)}e0vUVu`cC>?Paw&C zC;gc?fx@@PFJ6aV7ijN2D&iIGmGQD+_%+JOIPWBYA0Ei5UlnI7soT z4LuE&Jq=|&4P$#6LOl)p_B53CG>q(N2$ple%E9QC_do{zCTzR{wI=YV0X2(TKQwz) zd69e&@B4n={7(-@ANTVu_IrV|{nh#J$kqD}_i;n|=la*O@5i-jLuI^SLwSp`UcYMB z^M)(iX*^_Z{S3g+fN|gDLm5$N6%9SD(K} zM38T3Yvj$uetdp37=KTn_qgsq0N2-#{oY*lX9`8ucSiRwYqY?XQR#bn-Us1t>$!(a z&smRqq_(){_8R^jdMl`(9ZvP zR6cvgx7nt*SKoGCv28Zr_B+_-y`ZzrIq1vmqep*l+f;2>N&jnGD}99<+ZS4M6i3B# zz`Eeqr3g~^1(k+8f>c(9f&3&2zFb0<=}!X%vP@dXa7zI2|7^=EPyaSsGQ{ylbjIkg z=;C5qww8PcTP{Z-<7Zo=>$7!7eQ#UpOi=JM%GDM)UZn)y}R{#3~>c{YKK^;{}c1 zDyqt0noO6sluF;MU$uwnqvICo?-ixFw*1-F5Y|}fa(wPO63sx?j_m3`06IWtMJakd z$^MTRoyNMlU1}Fw_5G=$VPhf9k~MYbOZdTX&a(wiAPJb0A$)i8Bzus*V*~du6A3F?I#fw0E=msb`0mB04K6xRq*ed>%x}kpK zQDgeU?uiPR$!uezDrU5l+X18<D{2T$To-aeP4yXBX01Dk$ag6I&|E z3-e?z)-KYgLtLoUIw1t(uy&L z%Kze(!Zhz|Ek9Xq#9JMK;&J|_SQQ3GvzBWO%C#8TKHPbfTs8?4gD*+IV`V4b-{N;? z(7#TXZb~UVs=`a~Z#_*~76Qrzwil2LSnX5QPTB*gzf)RKP-xC(11L0D6$&zw4|${; zeT7077b&FWT9XBZ{(Ph;lu?C9C{}3kc=}07=~3+*QE20-qJa<~^1-INj6$UfN_(Jw zyqJYOg?_o|01AzklF`sW3f)nxkd|u=enmS<4}CROdx#iV1dn2ceuvlNK?n;ys{SMj z?W76`0U}?(^*s*$g)_d(Q9)@B)SXq#u!`xKW&P38d_)PJ1GFe1sRXaxUkSmpP2(4`LVyxy3qM8?czl1u<=)Gs!HhImg)+Wt-7sH* zL`Dpmk}^8TB4=o5VJ)=sDVW5oN@2?|LV^}~RFY;X22J8cLg|F14N^Cxk>>-UCzLMn z_&vQvMD+1XV5N+NfY??X9<8}i~E1d8{yQ$DlStj2CvK#9oc5wO>r%TU5i&si(+jPtRiCAC}Wl}+~U!KbgcJQWemS?f#1E#FVCx-iPU?ljM9bQ+{GTh3`(hYzsx+B zI!2Jp+|cp{$v9=5R@Pc9p>$#W671-#kaVms7uIHeZ#A{UGCrGG3TvQYb$7A<5{V=f zWL`32p0xJFqVKT?8%l`Jx)oY2C_p!Wx=@)g%7gL5x;YAD2*|f%P8K&=zp7E59ocud zVOp}W(TN>#Vy|Il&ACfjB7?ZgHJ8eG4pa0*>Rq+4(!~r(&>g>!<5#czOpk>M{Qh}~ zctBA3y`%h;F8rQd=<(w{U+u9y!LQ^oS%NId4?;#A@gbTtiPtw*$RgJu@RhJ?Zm!_U zTNctP7&DFX?8rtZ4=xDI3(4BRYNT3354wGrjC;F%8%~9srfFC4T2!>YB<kd~S zi6$r39i@O4lOIC^YpJ7OCy~go4%?IB=8O8$2ALFwmC7R`z%l@JX~R`8pC}L_Amc7+ zT&~5q+{&{t?yg=Fz$CUdnnZ8maf3dt*GEDh*Xbj!k8AZ2)5kJC27Z;wth66>6J^A8 zK^FNIZI@9sg1&a^@W;NQNR$O{Kv5Qyuuc&wIK{CGI3H3-&=X-^=fF3R00ciRCT~D( zk6p>yD3#zFP;3ZqKrP|}?`uk>*5ucKbRGElD82zjUCrzmauOdQ5>tQ56O^jaq|8xh z=#}i&hp;LQW2b%`DyzT!_ZTWmV;NG$kvc(gZ%fH?B1@S z=N| z{>q@Ps&N=)Z9``oO4?C&B&D@LNjge^lqX2Razgcsk|RvW>gWWP75z3q0QrH3O3Dd| znkZ2Rx17lQt1xM2xZfO&$R`3O9qwk}%>J&P-((twb=nr<_u9B-yL~PKGVdi2OT;nv z*d=DfahT}1h8^x$hYLB}ehwFOxF0wiZy>12202{D;XXb})Hl;mX~Cl}iZCK46t{^qDyy%6j5s@t^K3@TT%zr#c@r*?(qd7iOZ&gPkgk(T z3f&)XcVMXgKla`PzV0#mA5W{Tpp{@y#u9sLo7iS*YDp0;8d4f+F9u~WK|>iOq@mY! z2_tl@wT&{CSlXtgZMx`-*;*_js3P>}f?d5|k3a8yRKag_WGGh>)Gt2SE`OSfTnNCA(6^qx0 zpp1mhA;JIEg6T1ERspHBPf|xs#zo~+^dCWm{yJaE;jQt>u1%gO!#$VR08uR;^AB)< z6m{~VmlTOgl#gl9m`aIRWM0Ikyr(ba^74gw@t0OCFZ~YEqS4mnV>Z;6LWvoqFKLL7 z%R!60jM10|d9k0I5IT35(j=x4FJsagQYq29mkO~;f05<#Qm!$@{vwt2>oulOVy56_ zOj<(%HA|xnJudkIyc#4>yYbpOc_}_vIWQ^8CGa2()B+DRDTLus`cfw^6ZNH-dBhAS zi7JfVO?Wz6(<#1c0dDcc#8PcDCBRHYUVAsx)eWko9UF_FI&hdq!F*r0L%d@VAH2S_ zhWL4fpv2hp4-!kleEmpY$va;c>uaTXov*KT=JgqUZ7{E8=Ss;f=Ji&MO`F$i^_5t& zlS4U)K8od!L|mp0+QlW=js^n{!#cVh_`|4hP*O?c;bEJxfo39mE! zKHZCxq2k?1c)3Y`$vF%c=dXH}xPsNQ#4)UvONEu0N|X3L6mHB7>vjstq$HZy2^uR7 zHe!cqY$1G7CSDhWkeDtiUys$q<>obgw!~JN*S$5i&b%(x*aq|ZTa%X#J&J0DS4*x; z>@VL6lk~kAJ5yuRCiX*(r325{aauB+d%n)q*mCoFyy42c-fv=Ib(wgymRx6IYc;mP zyl$a+Tg>ZO8k;t+c^b=cG>bY^V>!m=>&IiHM&;&pCygyMbRB#v3H7Zsu~Rj1oq1jH z4P$lUYBo|<&yoo(Y4iq@<{hM|o+a~L65e9M&p}buvt&A~dX`L%RnL;Cvg%nfaVCk= zCULzKBJ*kzUWlHF%#Rlaq@&{NMy4(%_7siP&Kh&1S{HS!Q_cYMYHZu?nz+)uZlkX> zwk-KKrl_Cv^|ck+?&fu#zUs7V%6VE}#SKH=$$O~G&`-hZ>!T!ZgL$3#wH9Sw|A|*j z_p4S8;qEqqKAnvP^YU%Fxwwxchs+=Ol93#&9?y?tSIChUu} zN4LR*U44cJJ1vI^p6^SVHepZr!U|2FbB8ai*o6HqSY){guJk3XG+`(D!s<*|%oo;R z!rsGq8Y>*+(gbhrOPV%eYx%+oP0#V&mtMt-P1r}iuyPajiZ86vgw61Um75;qg8z8s z)tPiR`O-C*u<^by+gt8s^MEgb0w&NY< zOP4n3PW7cLG+p6$rv@uzf`9KzT5iH#3?{8K!Rz>wnoe>)++qu7ok{n}axbjGgk2IW zvc&{9`jVzi*zjP|Lemc>eMyT=*jB-$pA{3EJGDd}^~Lf?4#5NaN_c{9csw}>5C3KoJtiP~wasRdH`@9W zgf#UwS+BdeWi4QiIIh?sbp5*6_7OKzWc8y+Mkf_!%QQ9k`?402m>gftIadm7LKEYL zH6~67hk7L+zZkV6rvFgFXekI6*XumT$D46QxfHLs%fz_uM)*f8V>`{NmcpcFn672b zOwneZ_VOW8uGJOsyiSsf2tTCgz3 zji>-1B^D55ZYTh1kP}o3M}1g3iyA_-G{VCdtD{3gPo@vnw8HVY81&FnCM z{7vsuEH(rQ$dZ2ngap1*o(qJb808Bz$nZ)o5O%*u5OP7dZ|w{qY=>??2*UYa3J7g} z5T4sM2MA2rT@VIAAt)82YiPS=*XX>HstqJzRtXy|lcpPW{NWVD zbBEz`YoV4D9JiehK&Kz9V&V&_ViC%8<^An#SU_!_KkRvic{+eOP;K}6(JK5*Y`?2X z21ksEvtCJRfqrGCtZBrU$p{;>NFtIXIbzIWyogL(%TS+^taqL$31|CQHf3VoQgDw+ zc=P(SzLFYaAHeIfX}H$+p-H#juUm?a7d+06mnyPAp&D0ETdGVd=gZe)hYT=$9K z#$0^;tG<#HU(dyB`?fA<7Cy{zN*8#496fJeC-#n3ovn>bf6y|d@$ou{uSPojCvplV z?1KhbhGSho5{H@~j7YuE?+nu}A?#ltGf69do>0Ib9)X%{sJ(zl)B9@)6Hvmk$GMIr z>6%Qsdy#J0ZEkRz3BFFtZfENDziO5|Q~UG1qFuo{-WOJ4(jCmO{Wb4s6SliAU9}0@ z!WTB#gstrht2R7+|B+iI?T}INj}c}tICfn)Do^zX5bn9efPaG2*PZJ5CV{xV*c6L$ zu>TE?cZ}Xl-!{Pnclo&?Q%uMoZHU=zyQB9myKOhM?tqD<2WCx_ren$SArdS=%FyRMFRIc+0Vj!?>qga0pMP}u9ES%+d!yx% z9D|2nd0XXBcp>My&1mmmi)FMY6By|ES%~grGU{2eIkmP{CNuCcF~s|i4$RkBDG*}w zS4^#`X95Et+%H%v-Lv#e*bgI<>=LmqrXEqQ?Xs?flLj!fB+l$=v0EsM@N%8tod|v`KKH`o6a3-JkC0$dJ%C*TD8ck6~ z6y(~pN2l#wGN8K$63NMoNZci<6Pheh-ywk_1;a)TtH7xG(D>WN<4&0o=+uB!N~E-WOn8_8}bwY-bgqQ_cavov>`$I{=Hza#1 z#A~N$i^&6&x7<@2WwMl0KZTEkra|OLjcn1#RxMfHlC_#c2waO~WUW2c0A#WS?W9BVK+>Vin_*vjdjKmYFgN1$XEo95d{AJs7zphC3!7 zLGM0nMv{LUVK4J$@XyR^vG6my$eeV!MRxmAY+cpbd@3h{IQR4_>{YzBi6RuQZ{|Z& z&3@jv4R^jFP)Q1KD}JqDnB;dKu#_x_%w#d{!~ppOXW}6 z==*+h(m^5s!+Co8#=@}R93jG2OaRH>V);8r{uasKf%4a)v}QjLtXWVD-pa`v3QcP% zmFD#$eYF|V=+R^%t9QYKXQ7KV9cvU!*kTR-=ry+QvMcdRu-cinJzm>FlWL&EMrqH$ z9;P#Wbqa{oTdnp9#|eZQVVDvK?^8x30&HHQuiEPVlG7hbucAe!od4v*FQs+&wZ?4C zD>543>Kx@tWxTdQZG}8QamLzeD?|a*ZsOZnA`B_#3yn-`q!>o14BrB}bO$IyDo1&k z_!OhY?MVeY7a=I}! z7BEYMUrv9b1;N4@BS3x;UfcgHv_`&`o7T+FgjPC2t3Y)^BmA^(P+AfJTBqZcRaJ|D zkL!H^9x*6G`v1;+&QuYttUBLZwxywC+(_8ZWfo3DA-u)Y@TMm7paBD6PQ(T7^TPVyjhM|Zo03AQOgDMbmE1qk{&mgZxmz!oJ~rvx=#2p)B^kD!zrPdQERAkbe! z8682x1QThv_l$kfAnffrP`o{53HOxiYn^1k-Y$KuG_U{E*K+fEr@j`O*QCB$QT;+T z+M2-vzU58cyiHYS@_S@nH-4;sfm`>MD%IkXBkEhCb&VgDCHcEV3)3lSjzd1 zNpW1+ByBNCix`Y8T_!kfg4bd&M#Cn!(BQUQ27HE{scv+OiGIZwZRt0dxF<8j)tR{Z z3~`kv?$Qi#2RS$f4LZkR70n_BvN96I2=&8B|23c9gOrV))_-8M&r*{DA%D1^TubxYwkZf6e(7Prm z=v)$|8!m;5Z%S1lk!X6{kvZi+-t zXXVQj{M0;o)Tc!sk{x(p?uN?)SgCgys5d~g;%5Zf+6Eb+=uHe;&K0+%Sc3Eu%lH-` zOVD2QhIK@KBnxW2_oQSe6C{y9h8TSduKfg)&AL|J495g(l31 zLWa#K;onA7)r{uWgsb3==DyW$G#1)yAb;dT>*pPmIHL&7%&M^+hQ4VylA8d{?9r3Z zc=6g!d%iy=P~b$(63U6BETJUsQjBV)qL>O1#1vF8H*6$)nKmFYtb7=bxB2Ep&UlXO z)3GwtQqDj2742bicpD0XbjN?8|7L0oKKJ10638WLwFxE7EE#edRP;8Gb%N=h(eeDw&VSPMLOKjc{$|KHhx;4r|4fuL4S z)8G^wtE$TL<=g$uDH#T8*tr;$nxj*0*eH%v_4IKOb0^FaXzd`rVSq%j026%EQl33t zV6D`6$pmLc;-$mC7aoXGDMz5@`MR$ZE%+v9nXJ;_IE;r>_7F089Wmw^I?Ff?#}_%n zXwOJI#0WsK#h)NVY-|Ih@dZym&x6s-)|dN&T)2n&11;Rwyaw3O&x0sQ%+-A(!YW>m z$E*@!$r5Al*I2U4*IV$q>=t%<3g5yKTtnznsmF_{Qg`#OPo;M8tJGucfo0alZSbG( zH!8(RlBB3hQ}@*cGlw`};?t1(-vzTi3TDxDFV;IAlKxA1<5&>femuD028ob=!}Azn zS^mHuXu*8}fqq&3;T`l^XWG0#aEdRNY0dgTkPy7u7v#3)dHz64a1;XD`#QfoD<-hm zwA1nh(nKPL{?4Fa!cr)md<)n(T&63jzZdS(!-&&h+upCjoZm`wR2dAS}S7=fz zN0)-6?VqhM4M29YrbRc-3e^$5q?Xbj8KzezxpI*QrrI|SGWw6VJvYGCcEx=1EnWUa zY4l&Oej#0c8eP7*JBj^Q&GHhvxEkq?Aa{4jm%%Rc=-fQk1h~f-d_@NS+Jrx zhV{VN_id|+`biT3XV&6a0xP%)tPv(o!cB=-+{4v!=kyvjG9aVN{$*s8tDJ%B6#F^_ ze)hAj{JAUAC(+raT)T@wpECrnIo8=AiQ7f;J=JwSR~SEgB}{c}ICr6}RgtZlrh&8` zTbmU8eb_v21(EAQgVeW>PBA`JEM~mEC4=vfuwRlbVlls{Z>gJ*B)u`-FE)x(ArVM7 zSGwq0m6-Y=R1+-17;RZH8+Gw4V#>TqhfuF2NSAiq5=|#MqdOZC?gob$yx$3vyHaL- zGap{$7aFO;UhfEb?ZoUpA|bHVcDfRP9eZG?v>M%#mM5{Lh?P*(=OOHiWurIVI`!!_ zI+~Z>9ou`JUV3~uk~CnQy4nD7FH;)d^<9iWz+;|Npgx}u*l~I2Tijq$9|Mc+=UQre zTWYUgzU9Pc{@m{lm)fBrYJ2#oo!2$Baz$&D0OIbb+6QPYdsoA38!es%)^R14Tf0f!YjS5;6NYsSSKz zEn4L#<>cwG2*lNqFVe;b%<5Dn^Z^R%Q%&RMi*@x=*tA~cAsXq|93%Ib`essftu8|{ zE_>ZZu0_W6K5C7^8bOO_X*R&7$6oR?m}^m4@-rqlOO_)^aI*jNod zHC;$gwblahV?xX@hiOv0E{h4!^`l9`Qj)}5k08Hhcc|)fQZC0fO|rAZQ)m74IiN4a z)+I3?9}5CxVji*T>!EUyuwuy;dJ+FbOIt>g^_?7E1iaV1j%K{gnCE4@P%}13Me0{* zMvWJFevbSm^eXa1t(emITik-X^hy$Ko9~kBf(f5MD3`r0`UFo$%RY;_ z)h&7NGeYCWlzB1pY>eB~t-k}eb`s_g^?qzkp7X`|YV@El*pBR>$=JmVf89D|wvK21 z;)U6YJ~z_~v$ZWb!exJRFzJl@6m@WS&dFX5sqc7L&a^Drzlheaq#DHQ$Ket2vbcXL z$pkZhCpkr&3Z%EyJy3UHc9gwZvUIXh`Ue?e?$~U{kV2zU&W8-Q>O0nk{+pq^5nb3o z!K^{b`RO@6*(luDMJ}+Ap=RT08Kv{OPj|1^AU2NpZ}9PCx0vv`rs%iwnVjKqvIuY* zf}~YA9n%LobD45B{A5MvTxUyKtvkVs)A!>Qoe69ozO!cho$D1$n24}M#htftHMjzSumhyhhC^1x>SlM>BIroDo?=dDi@_R z`SAG1w&Sh?p(4-cC&%N!@g$)HQ~Wh#pc<4QuVvBeWZ}%O5IchNyO@cEj8G_$UX1vs zP!PESt6%~=Nfk-#!}bgE!IT>#s&DX~$GBgR-(!f0-5Pk|_he$X5pTS-f_#Au-Ik#g zWc1P?hq6-6o?s!16#tvIf-A#KhT+qwES?kt1d-xlJPT{sNcq@U3m79DY5|a?+Sq}K zbT0LSVGZKY5z!NP0z3g>*sh`z2)ZffID~Sh3uTBrS5zN0Y)0PU6y`$wo%x_&lqZvE zpD2I-H(qzrz_Jwc?fylcDo7J@AkA>|XTqiso7cj<42&XMNS5GirX<^nrc0t=?O$J? ziw{2GE|^daNZT*;_e1!D$)lF76Dqd=Z-7P~Qv z5##LA7SgS&mXG0lSA5naIjcOC=flG0GgZq&WH{iKm#S^WuM$)uW&`s|V(PTH4L1D; zL?@DB;S+aFWEYl@5@LyZX2%3e3j+P4QpxMo3GB6%((%_bO{``fR9}$YMI=o(k>k!P zrqPJU+dvNfiiFfQk^r^=@Bz6vmbu`ou}iBXww|-i1A-Ae84I8CsCdEV^Ab71-Tfbvg?*t>C)5x^o zSKq-0mXYOQzI-Ot{u0U9xeTQ6VEIH?tJfkWL7_VA<_qaS4`{?<3K zevJD64Hup%m9bhXfnxMeiJ-j z47VPtL)k}g%@PdQstF`V>q4fKfHb!@2pL=VYZ+_J@#b#Mlyfs9q-*L0Hprka@}=** zLJU{C3bJBzcTuh^iN*rUl{SlT#T)2-1?DMNw%xvBtmSGGq_Yt}GXh+>z}N_Ln~2a% z)C=Z`B-^iZDpwjhr>5mEJ=so~ZRwoK)r`)mE%8tdISD!nFJ2QW{!;hpPx{b{!LyhukqL7u(p-s!U3wiJ z36z%~YB^nqRN==+?nI2qQf#I~?Ib*0MW2o#UL8191x`6@JSW;)EY(Oku~+1^1rkiA zhh5*Fy@wPLoTt0A{X+B#cFIy}h4dFeOs&Ih8~oqCRclK%`7EY3&3Dx-=~rI%!Yuu{ z39f#$l9frA5plkGJJ55Wn=SOsvK2Ai7GDBRoplrM?7eda*iG1U+Nt>QS;NuRvACS| z4EHnmU=<_P`!LqM&!a4}tUAVd60FBdZV~Qtz93%p5|S*fHtA3PH`s(UFr7CQbpt~a zNfw`|7Y?u}B1zn@kRA2)`g!zG&B06DO#cOig9WD?oQLQH7XArsZ*@}&LZV}l!FJ`6 z>kVm2fw1BoK-kaQU$tav3*stc7Mvy9M66pC9&Z zJP1{__%YR!J1s0`p(!R=+Gc?I`@zy!@U<#z&OvuR>9h}iz;5%8j!*ZZTvV1IRc+5oUL!|&sb2~%gI4^@; zS1eXT?`G)G(uoE2P3VtHP(p)P7{2e#jj z!i9A%e5)(*J`zGhb#3~mYx!c*1X_Ogz!w%4V%%k$9R*>=7a5J_oQxKCW-O6rCt8ta zx8GMNlqS`7?_eR1mdYmJ_1FZi;hT;?D;UoR-2Tb;Ezx8z1isjSp-xqszcExIFxYY1 z{4bf>c};Nam885;uff-4OrIsLLl`jY27z2@H-=-QL79XVa^hT1-#&riPXc2A`0+=Z zcA1atbl547fuZ8bZ&I)AxBdb)3B0a-2muj(a_O1WYoCKM;C%=JE#6Zjc)uoQPbE^dt#=#DHC-55O~cHi6Cm1HTwsW%szxd}0mWMA z5Q*@|Kc(@bHD2`8+H8|aDn56P`jgj^RSr<`#X-p;v7aIqj7T8~;T)ec>#S<&tZMG8 zYQm?)I;$EwtEO~TO*VYyZvh7RQ8|~EuM!uq61FSBUY2J_(lCROBxo%&^$^68^}f8% zA}{-J4N5t0)~Jz?lmR2*e!Eh*h5+0Ruf=w}Hv6r}ZcN18jXez|25js} ztd4poKLInR;x)gGHSUC zHuQ!HV5Wx}gG%H)kN=3`69C)y*!c&_)iB317Y-H4DAZN>AOVG+mZPUdh;I7A+y&a zp^M%FS9A}(N|YFo**_zrK`(z1&^!H=9z^fty0FI28y`lmpD++cZ*7Klh2Em5>@8>c z2E7T7N>5OQ?~y>I^+LhsAJl6kS0*8@1`vln|1y^oV& z^bRJufaYE&41{Ix28MQpUgwSx^eUOppqG!jW<~E6By=_R^UJ!2-n2(T=sk&y2E8L* z0(uX>(1YkbAm2&$+r4~}3!pb#7zm?R&d{#V+c=8e?#yS9B1zcKk+B7Zr+(o5dVi0$$kw>1qLg-Br{ zpZ%jWpG44S<)vMgPu%*=Oja3b^?+z^N7vT83{T@ z7v1dr$clCaSD_)D_ZIkDGdu$^mc-2{ebq;EP1lBdh;8{*wt$Tr!;nb-dM-n|vT^rb zO*jKHW=Alev2p);05#6mzy1>mT^rXtwtF`27L*vUaW^8P0d?o+0qV8$GupUSn{T}O znlO6*!uKhI=rDSIB$@y(#zSK<_*xbkVyGTy@7gIR+&L&>O+( zs7QVR;G9F}^&ol&)rQfVA~zxV=Vg~OBqDohhIWPCYt<3-7Bing?;IGOtg`nz0nGSz z!;z~y=nX`P0rWNy=Eb*b0C3Jab9)fIeiOpzox}T_0-F0cLn7!s#n7(M`{v3Bdbcp2 zL2u`KbD;MX61uXtuDoXK=jYmQkz1zW6chEZ%B?iztmDN%7RscBXxW*nt zZzMhr9Yn8jOc*`hLlf29JhIgldY@btLGNRhX3)C~E`CJEB?P+|bR zZG?HTdrbh&`R()`L~o5w}#OB6c+&)*}EFRIqy&HLG)V3h0)uGPrh-ZFPa}SyZ^zM1ak6v)2g56i(-x>0&th*KO zgn9?;<-$LOQQtz+gi+s=p20!gbeKptJw!JtkvlCAbqxUjHA{yVq(5}!s{gMcJPcffC@36n+kl6wO z%%Hb3a&-s2j+;a1eRCR_7kgO;;GFg+dl0>UjSZuB7|8`R{sv(nEPFRIv@7)9zc_;4 zSmrb6^+#Q^+RN9F(AD@aPVF9gGj9r^Hx(HTdPhA4^d4*ILG-3v6h^N<$pz3W7Y4%U zjbvz7=&cb&@Au4S(0jEm2YP=)LKnRT>;>|Kr$1DbmYG8*)L1F>`d@UZ)=8jh2Hq8i0pN+e1l%yjf!4IyH_EA8O^;Axw?biekd`3-rgjq zn!5zRIlDcc5xr*4?c*yrGTkowaqmX7S$!BS0kTKyrjrFco22@E zmTETB)^iyEa%m%{N~Ap&$C+o7P)hm=vDn`^4p3ENRifOZvB?K0lmI4#LEZAzSv9G% zs;;wYVrNygSufaoEXc{-pi;Jv%PMkdnqa^UEY02Tdnd>)J60JLFw7d3E+foCMhLXK zUHH9|v{fW!U>U*Qdc^ACEO*jv6*uo>ZnBbc?`gv^3RAwV+E!t`%X;%&e!Xk) zewz&YNq0kF%xvtA?%(}8Vts2xSh7TAXN?i@m*q6*B^4>Emnz`+0`J(c0Q~285dfPY zEeXury(^DfS1}uvjmP;lR;7L9P3w&k1L*yNn-L9qw*xrmyN9Bh#y!<`$9kdySM7|$X+hu}E~&k{U~@r>a)1Uk{-on=5tZpmrt(u61MK5o5DryL2Ufb`^uCR9uY zMop#{*p5*1EM~G|4lbfVupAJWSwunP=}p`@CHlbA@$$MiU$O6e*vMG?1IBLyo#)1L z6oF#gl1DHdzl0Jjc?eURq84A&hsYyMKxnsW-_&=a^D!hcDDR0AZO)DV0LsZT^!gxo zIQU<|_-^bGRpYi&7_TSSCq^*d*@wh_VlZ5cH|MJ#<9Zs!D8_p+T@>R-nA%`G4b9Lc z#y3e5x3V=`0I##tga0#(4|{5rFg~3%V3mW?cDE0SNm5A{<4gGJ$9T={GGcrq(?v1f zjHwOAg-FsR#_gUQp9^@M)cu(-79|gy4#{=SX*DhMF|0$}Z=usihb{DQNfWlv!(#fW@5Dbm?(I?}VyPt~A|t4b%9V`oqM%7{5A(c7@+=w?^Uye$ODSi{EQUc2EB9LZJcqn}m!; z{`Q&-{Oa!RIsA^HmlKe`^bukFhD(|-e&r193cp?IBlvB~+8F$vx*|7zV+As6|G-#x z^!Fqb8o+N9Yh>&npmWOa>N)&2+A@q^Ls=NV{*oq)Um-)g!f&TrBKW<-@~!@kg+@XZH__%_zfgQWB&l1Q+Q|3;kRV-Fn*Q8!}z@{X~OumFtjWD2LCOB-|Z~l z+P}+l)|ebRe;WExjhqpP9Bk1+0&O3{t?}oy({Sjc4qg+ ze&bv_v-i|^9sXzEnSJ0jxprosh1l52oW5NDel$+Do!Q?U=9LELXX0h3fwwdJ-P&9` zv-br6Xf}5q@mQ2a$sZ*12)=94#zszG7J-ftemDC-vSQ>PP3IK;9qkvGhjV&q+sT&d zsYUXrABaa}uccTHFvmyvWBivQ8r>@sX^T zH+yr06xoJk+?kC9T4@|jr$tJFUT;c-YOAeM;pvtGdiHsz!nT2O-UC5Yvnya3GH z+L*Bgr3R3ckFWD~W83T_k=?Z5H-O4H;x>N^VhB_ya|!0``sF0vof*6|-SVD3-*_^p z2Ycj`4-tL#%^3}sG+~PvV`x_vv1|&l4(#Hd$nuRvEV=|`^xZYO6TYN ztr8rOymYavR63Mdh>WH^PDfKXv+FZi#8sQ!-eQw5ep`@Qz$5H0X~OvBGqfxG4u2?u zUyS7&{MxE=<9DAxW_si~rQO3XfkFd4@-@h4@Z08A;CIC>J%`^18;9}x;Gi&mFH4#* ze$5Q+3cmyY5y3B?wK4cj9-AA#(*!bu-<4pjJ08v9C^UfI!K{&5^iKetv)|vs_`xO= zaeW}3o>;onZ^iA^7|{G{p6Jxe6UXjYFs*bcLZ-!VIZWxdHRHeS9Q$^n;#<@ztuy3P zV1O~B-~Jm0&4w`secaikq2W6lp19dvUEn% zi8&hHjmJANQ1r9<-iG%UG)mjp3*=XvH$><)hC@r6FWygI3h}_jle{>qw3%0F;YO^P zXOKr+y8Ai;8_cBW+mEC5O#V2M@+Yq|lN557*>@WvTTN+8Nqa3q$!0#;x#C;|gJQvL zO;{+{-yd~4qvAXu9%kVWnOHamEbt=5Sm4G+8gPf#n4p+868yQ5SH~@wgH9;V+4Uy0 zZ+!mn_`hQD51p|afgm`anP1L}pJWF2A0~`5jNT26;hy0Uq_XF9q{px`Q@D#rIuAb5 zv4kMffhlVula8fI^4V;4cJA8TGUBF7loaZH)$aX1MYcLwMDGl;TiZ02_r9Ro_>w0B zdNsB8ZR|qkS^Nwj9=2Qie-zEAeOM9r!aFdtLJ8OdO88Zg)LlJwh!V<&HBTJHkOnEKvff z5H6-tUWgroL;@=S++q0{nUHcinFBJK(C-V+n7r5JcuzTNY7^p8dAr(H3=~^YIQ}68 zrJg@YnvEpCAve7KeY}%5_EZTkcEprg_A%a zfhMhiu|$V0baw@=8L?TM^RR(l+9o)H6?T8j13u0|y4pPqbcZ0X&Z@?eEM^66C ztgcK#ULq>F0J3SaBGO)&vpzwSD{~_23ARyelkt=2rqZsQl0h_=+(QLmRzX7gALmKP zrO?@^g!DG;nngm4GP!GYK6~j`9=W#$76yWXFCBFP%m%eZ8vw6HK+|9ZvXJDshT{cY z$g9_w3YjM|Ga&I+d5*Rj5POb^mBb?7SNdXKpC(?c|8638p{I$3KZOLQUpo8-^h^J^ z9(GGjot5b#D-!<7X{Usimj=Mo8Wc}Or%**(siJ+4fQn9YRWxy|GypS0SYa4~R5wmi&o4Z>`PK7IQTRKh@w#`c#Q%4lNB7u!`1ZPkV*$!i3M- zXw4)QwUru*45F>n&~zSdL1&Ol2R~gpObG!mgAh_fA&_A0@bxq3oYgRqT#@mp7NR6$ zk><9o5$n~GQQn2b$ytoinG8oEAv4Be!Po;)V_+>oPgvc?3Qwmnfu2F9J~8YGzR6gn zpe9!LSCg}Cl&P-dtPc%p-kjry=aHp{6bP_qDcKbc2pRV!QvO=*gtJ5!jJHpf927WIJcv_>Rp3@?5 z;RYpT4bf9$yQ;Tpvx-x&j{6=)YJ69-ic^=m`}iiu z0{6MSj~Fl^1$67KhwI-5P+4ab*F^=qDa6qzeA(f&j+j>BBXEJ+aMV^Npu~K_!9r#< zd4?&(ZQD1Ots3rh;i;sfgUf3m6V68y(24t|3+*-a9IU_-D|fEl0M&#KhSqCCgNpNJ z{j+CG9BA|ULbKXkvwRE$Yzp_b;JWxpepf*KoXMiyDQ6BFjVobeN6=NqE_vp&^aK&lqGZ z!-(O85#I6jQV>T?kRY&r9dv^BC5MXN!L`8e-WqX&#+dOQ*Q!@dsz*T{!&3b*8!I5y zOS+Ki{5p~PuB3Y7zi_TxcBh7kRz|8f1>{+!x;7})^UlY_cvh+YK&05JHE!aS z_ijn`Hv?R$Za{-L>s;N1R6mK1A)8d6xSqzXqEwHFNcF4j0jX{)k4W{049Y6i17KmJ zQhnC)Y*PI?VqB@d9>lwp>a)n9N_8cmb6%?MA*sGOgRMRwBGrXmNc92Tv(@{f;LK8e z7D=v*R8PT&2eV4`crC5iSl`bfeA%UX2@?Bl^%Y2s_UMkSKH8J&chDftURQP@)$b0- zF4cVsR!gc6jYxF|)|Fr_t*vf8A|ll(24$7%JMbyOs8rvyESpsSf*4n-r-68vQhgIS zRH?ol&^h0Y4@h-*{%rKRc4u2S=8CK_7yDz1vU_)Jt2Fve#=157)lrGhoy|Hbd7A>l zv9s$icYioM{qkRTRC4-S89eFkj7suRqYlBBlU{ATF(mdLePX?uGtIula?Dn*bGC?b z3(9S!V=zG9(T1xyTiyRiz>X0{V77WE41Q4}#yE(}I9q)P4NP>lx}^f8WuC2`$|!gd zoZ$&hn8%OEz`_)4!1B*lyK-;G2B>@^wy@5egjpFBis^wuJY;TR@B6@b{+GI`VFzn1EF^bEyr~!unyEq97$=~QWo51(d zah7aLmt<{#bD%qSuj@iUiBn9rWSMq?@K&)kr0uQ)BWAjHScSqg1TZxtUlZ~*0_i5C zZ8meN`(6v~uNaSMuExBoZ8Wk>6L2OMqdA$$y&RKL)0dRxNUW4*W$MG zB|dSB%!vuFkn9!*uwikn;BRIzM8-^95g7<|o-qV}W**1s*6ZBq*3Ax(4o7SfYd!a4 zPB5aeAd$3GR6tR59l;0M0KE!`zVw->6Ozm8Bl61mT8Q~Orh%Uacr-iwteNG$5b~#T zYxH;tKk-X>O{hi~%VTHp!G^~2fCku8jX-LdC+7P=iFZ3XccDvz?aUA-LA$AusDYi> z0W=`!Suy2a_%OP@1?t%ClGCPS2mKc2)r`JFnscf=+W-<%2DkP%u#YkuU*(nVd^=nIyKP-V2yl_<%W4OVN$EePgD6;antGSy`cR_qjR7>5(bR zoI+#uty`S;RnA4wSWyUgCSNK#!_&xSE?fhRl658P>opO}nHO&*YZjY1>q^!IV8%|> zL|3xz^2M%^>S879V|+=*3=FPv3mCxbEv5K+gP*1-D!b3Qk9~4pcZCdE zN9*eiElqQk84eol7>tiBA@>ubj!ra|+!Ot1nZ|+`oTNe!{My*`rEE@mNwxqWi-IvhEX2>Dj1nX`KbL&S6wZjkG#+Fx?jM z=(2;AN;hA0WhO9A3V44jVa7qQSg6HTAj*<$#!U*>^z ztZIWR3nkz`-@b!#Bd}+CjRq>}-Pw8VC01NKb+HAvawvg9@eiGvZ8L1Nm=~M-`Tlg4 zUh8msa3&G=iJfu_Mr7a~LCH$^E->Ky4K<-xnsTPP{4fPKJIOa)Y6_bPdh|m}vETM#HUi&d{}WNhKZ(KgF=FJ)y?}3FEIGc=c?MK5 ztwx6$VK~W3cU*i8g3uO|EmndssEP;wPx5Kb-W|i#K!@ZK>tpcLzO7Vxr1KZCb{@|T^C%yq~b7;No&ZpbF8QO;TII7paEj@`-7{}Nl_BlP$2({Fz% zLj1`;hlr!Fpybke(*2SahP_lsZe+Ov1ASADm5uvW=(-Tba)uN|{F^yLS5;A*nZvB2 zuq0Pez;;)ZrKc)gWy)(j>r!S(LfQ7NL`+pw1_mi-=}(Z7l^d&6?q$a+#2S*B$sOti zkz{*t@PalOTH0~(VD~Lq*T5az!h(2sng~)z`}mA-!L+KvV~k=PYr5|C<1uT{%2@*~E95^UY!5HZ>DqMcy`d}O6?Y=djT#jw zT4~#|QxK3{+3XAlS-zqim4NY{n1>hnDP@bBBWCR$%R?YpT3L`}m^oPFd}J(ndl4#w zc14+?${b?~@~lA5;rXnko*U0EO)^!F{|%mNSX-ML&r&-RlNHaIrZT?P|Dd6wlNH=Ymo*M2X%d~RV1^6>Qa6`YcRdK8LaV~6dU;*7Nqh$Zr4HOmmZR;(8d zVOkZubFt5i4uRQd6%Q&-AH(}dq8%ojVR%FS7C;GujDMKxzG#1>h9ieJYv*A7dr+=I2QRWF9etc-N=J_LxTQ|WXPs%yyTlV-URD4ndK~>zk%bs|}=W3LSHW~z4 zX#AAZpZP$Oq{Wlg2#P(yX@bWs954MQl&%g51G~YNkG9p02(HCvu&4v6nIXSQ|53bB1_@m_UUv`S3SjLhx8yorBAIJZp#DB13OIz~?8n$R>@fvBX; zp;Gwm(fpB(&Xq3X&mi46rh~cD0aL*=nO|Ax429A$ktfRIz}Q5Harog|N&Pz4L3y?7lmCGCT9_UqNR3S&yAMV})opyW=Oj%yu5XN-}$!H`o!QBq}n` zw(M%j>>|sw?Y%`Wy}9C{*i=Jv_TQA*O$<#@-)u6wmf1t~>&fhnpb(bXZ{Pa0WcJM+ zJej?LRC?OZ9@WoUC!fq-WTDP3vxkpbC7J!CuS?F8**+e*ke#LdM%R#KvNW&-0^@>$ z8*Y%!FAy$g?8J|2i`6*2gPp!T0BaX?IR(nzKjjSj+`53673N4MRt6 z&8p=XPa*myw-%UD8M`)IzSdst_tv%diu6$h$A+tmU30e#0nygxAxL@$-uMqDMFVp0y1+8afhs z;h6(XWxU8I5Ty#~EzUVUFJ9_035jsv7IkT3)#7;dJN0-S9{<=Z9ACr8ngvCHleR@J zV{tlQW@x9Qhz)T;fO6p0!0`4Ku4=bzo0Su@LUPq|e47V6%)*TiX!oglK}0<-xA3=+ z3>#`Ca%e3h#~u(%=zFq`)2g^mRkNlX+yQHGkLQ^x6(-8^%xPztQ{%4K-gdeMOfp$_XmZlh4~}oeoh)N&C|lw@gAYSVku`9amm~$^7%u@E_^@WcKP0GsU*g^-2u3rtH5mEo%JT za{+Cp!TLxIhqEc^Q9l9VlGFNS9<1Z5jx2}iq1Hf0(;ve083yaWLwIzs{-F+n!-MtS zOw6jYWVDrf>YOq#BYQu^H%~?4@L;_Of!RQDE2zbupvB5yy+jA=Bn{L((tmK%ph>zM ztRD#C+SC}Vo5he|yAUty`s%>oF$kR3`Q}^)KfpA5bRGPQ5h0^f30a>M(K_^4uoP!4 zvYl^(8RRsYK~9qy`f1MU_s0q)s7bQ(*ENY;!$? z8lkyHBheJn`{7mF4NqFV;f@x_ZWmPBCo0X9b6Zc9Uk3t#Nrl_WSJr&Ax_%(7axU|+ zc{j{Qqcui7Yd%gj#jce3SjoA*mXouXk1TV2lbJq)`Iw0CsQGB~ECSWl+MpAdnDPig z^>jGPT;Hxt95x@DAh4U}!#~%T&3yRh`nonBcb?=kAO3Yk)UPTH{iEK6?Z_ZAD>C>vv>`Qm^iHVGZENLweNYaVP6nmS+8N^ z?rQyY&A+bJ9}&{}O-b)p)cTpJ9x6Yg^^e4?*4qOFF*s3;Fum|>;Nir}0{7at?$!j; zhA516^$D+u9+A^4IArFrmK&}|hlOa2f17&Y@H=ubHSYPqbr;EU*mRt3k%JJ;?i~aY z)NGxq-q<@1>)IE-PjfFMZ}9ENYK$c}>n+83!*UeYLg(udp8Dg;%o>s)UfQs%f`cls zTGQ5x*9rZZzoR34uw7Lyc>*kFrW>e+(A_;qS5N`dm=+sW;T&+R3`Yy$!A&NUeVJG$ z3VuYE>EqwlS!N zL2-6g=wrF13#_FXagG}SpMnu}NE2`pF9Z*!0}hUdQ3Ei-wnhJ)a!^N`P8ZX_OBIM$ zv@R^|M3d6XHls)#85E(`ZqHsQMd`*?VXXfhmSgMvwC~Gm`K~~zM4m|?QWwFYg0+}r zR=Y6fEV$u)5zs)mtoT4QGKxnWEtkMQcNJ)o5xBMHufD-Cchk+D$D+6dgJbtxPLWB~ z@rB2BRu1W`Ebgov)LB{7Svjz?vaquNY?8?f0=_wY05g{RVFFT zM{w%L(S}7ni}T|qC@nArRM3t_N;&7Fp`8~FAp7c9Loc(QFpK)wYxz}|a`Io-s-aCi zrd8=VE3Z{M7?J3fR-HP`6_f61)ycw9k7(5fEGpg;gAQYZ=FRRQtum(xqFS|ki3`{2 zXw@c%ds_A59=WvYOP^LPl9ai%>VCO!%s;Vev}zz4+PP?dPpcw}yphrBhW~R-x^z~L zY0|Dz)XMcwKj@*7?)6U_@8^m}_cZCw=T^UR?CxPQN3f`#)TBJ&tq1z2XLJQFs!7g1 zE?ldlNnai6Y0|#C<1f0J#VC`oobHxA{jI?{7^!!+zy zTH)uaSMHtB@R0ZRc%mg_-4R2+=!meb;D!bCpJdmQ9TB$4D;?@&Iol7ENDxPsxzoz! zFIie{_7vTYlgMUFh@l)wyWY5M5tG?6PQ@NG-Pj0Bg3yIMI$vGbqYKrAJ$j(Jutyi+ zISBEC@GQm?*p&>4#Sa`JOkv!+Y;$^H7{=;IvY-~K2qhZ zT)QX$%9Qiuv>stw2cnQa**8^Q?mWVs@!Va{b3wy}2sFj^-iqngu?ak)_XPnV5yr9T_z^)vf&w z`}=|ZDIIQt^`DnM(U`R8I`P6i{OiO~$DvE7VK;EZD;><%U+XiJV=NBokPR81qk2)F zp<<|lF30*-BIcF;g z^v6&9Z-G8-wdw!*K#$cOFRKT1uhp)osNO0|^i_|qZbMt3S7in*g>J{ry>&fH@Z}dP zlX{)6{i$Jw>~=ey!M}M|*|6rfu`mo(ZGH=?Q@m|(yx|OUlp@oQ_`DC@Sy*BJoO9-F)49{w3Hdt!@0fpX8fR_VwIg@{{oDZBcLEZbc`LUi+sS!LNQC z%CkXgUE?hiOJ9!Yq_)`1A8F9g_sb_thJ$$8hzuH3v@0Kk3#R4$vGnDFTbeLb*-Fyr zC=XMZGVDV0O4=a+p?x5hk<-1}A49rUSL~LvT_|87V}088Ru718w%&wtxMPPjSBH0X zEq>~^9y|+Hj8d@YA<;(~k|t9&o_KsTgAY_<1KJ{&xi}0+JFf*1G2My4tJ-+^9u>J_ zLrH}*8m?Q>C?QJ&Tk29NQ_^cT(tl|04{{x>S053aa3AmH+SumG!+-7Spdi;Z`+-R` zLWrK)Jy-yGGtwl}kv~Ik=$1bnwUq&=l<#u2M6zY&>Z(94m#e3cD+5=46b=dGbm^@? zu(iV(Zk3$%1I3hT4c(D??Y6H7l&I3B{9W6G>n-(*LSwhlgem6|Fa+VniK<&{TtH_g zG*#_AtZ@n&WJWXo%uM6Y>^|@{<`iv*4}=Z)vXBPOmUizxpo4h=;C~p}I%IokAw=P$ z@&~a=IXi4^J1%rF*t?=0%*CA`!D@vR~{of zK15tzzmwOwAc7KX-_f~3$U+}0X!w3(4c}risfI7;I~Zv_3LSSgpO>_o>Ao;+it@yo zg|$?cMbu{y>t%l8v?2U33S48M`;#^yOKGNLrWGowl7S$7WyFFQz6tPsCW;Ti~7bG-Q*C~YM{q$k^OmQs$^SR z1%By+RUi!U@joX@f7ag=fk8BF@v1ixrEkPbmx5+%qNHeO>C%f2;BTxp6ecQ`&i#Ci z_+r^xM2RYOAo~T=S`(#9YueV7!ApGZ>mSEk&`^H|sjXT?Y0Od;n%#GSL6Kk&gyI#; zQBt~Kddap0)0>8tF2DGXd{2xU#0TgOOdtg>icR(>J_r)b@GQn_$1r-rDd$?8UGj|H zmOS)?NPlY(+LD36%4d|p4ya*729et@b8@j+%9&-wQNBl+a@sX(z^zUi$0BDd2uh1F6XG_uu>R>U!iSYgYTX#{KLz|xhP|ESuY=yDfUROp z`DA-By_2D(lf8ZhmtJ9SfB}C!fP&~rUUaA%DyaRt8ZtM_2Y*DCov`l^yI&WU&LPY$ zwLg(soZaDMdkF_@Jzd*mSu=dHIk99_6WMx`g_r}Tr=t%&G~P6$XnS;YWAJD8BOp0v zGJZMRI@-~hq|3iz`K|4FEaMd5TL)6?C)BSR+t+zyGwCPBxFaJYfH0I0QAkh4K-kNC zJRujfn-#EMypp*B5#S<+ ztZI=#;~YA!&SoeQ4kHYCurt1SBik7_VieUS_vZz;7tYYx1}1mN-6FUftPm!2JnoL> zxCZk)5f0gDdHl&l5I3^B=iI;8(DH~5J}b>32Iv6I57p_*OmkxwlPJy0{4~)+db4!s zT|3XL>FDJfn`CfSI^dd^R653Wzva+|{(Hv29nhzj;m_>37!l1GgI`X08;5v$k#mOK z|8F@f=ta~lC^*2ZVy6xr`T=z@!)C>MPL zTx6BHmP}H2Ha*pBl3vKI{-TLdsq3?WmGnkl_Z3>JiP(~x;P%-Onb8ct%S%oCBV2XS zM8BPQ0r?_YsCMF8ZuHDxC(c>la%OcfOsVC|43tjEPU*TVl=A$PMDv^~Q*^1Zp`R7| z?W3moH^hP!wQ07&-fs^ZP4h-5P3P{>G|z_8>;eG8<=huaGd)8&Z()_!&(G@tp0mmm z=WC?B{FZYQ9dBi}V)uf0HhFrcFx+aHtn~+&SdY+r5SV9`;X8BCEa?`_^)uCTw_G%D z%R%$yg6`Dwd(0L@>NyMTl(n8W=b$;NTQqmfgzcfZXeM*eT)M8Wo+{HXm`Yi>e*xJ& zc@;SeYwGsP4Gw;rF!kSAZ9>~FR>Fe5!!c2AmS87@EPHj#?Ciw%QN=B}TUg3Ahrm#r)Sa|Zw_4~jyOJA42lSLsY*H^6LLqNIt z2A}5gb8|-5+%%ai0T2Di?A%<2A~W^8>9r%=RED^DYp@?1<#=#tO!0JvG@FOY*&j{h z*$ycO@|K1erRgO$QB!L=*3IR4tvd+X@ZH8%RWE)-L6VZ*)=TExJYdD5bn!F3O`wd2g5Ux?NHJ zm>p~w?W{V!;?oQ|p5zDOviY{Bxf&IQ@o@O@C{p?Uu!bdCr$hgGSJUx&J^6mVjU_NH&HI=o8?SGyGYlfsA)h5NEnct=OH{c=(Gjuh^6 zDLm2w3NMG8`)9IJ7^f80%tfJKFeprODa1%2`Ed}Xks{KWT6!a;ke`dfj-=4yQux;* zP}nI%VRx)*W|r1x;H#q@*2+bploUR9DNG=R7x1MNe@ho{lZ^sLJ)p35E()Vbq0eSk z^d({^8ID50w)eJxscaB*txS!5eoPSY#6%+^br!&q_M56iZfz++ExGedi!i? zF1kNrbbxC2&sFV7to8wJwO@Dz)m|eLV>bhfEUwh7tui|=dkCY}1JA|jk;>_S5JH!I zm;s@+z=%a?4iaQQXlAc&BJ>tEQ~{v@xe$7i2#s?Qdgx^!^w9?y7^?(qSrGaG{#PdV zZarbNI|%KfoUR)}XjCRfJ_9Nip}UYE145JXdQiJnR^$57*urq5Z!*6=+*;8 zi|FB*=^pH-D~LMJz88dKmn{fMptUoN=q8wKfw}Ar$U!#G>)5TWctt(0$5({$$V9U+ z6U}>2)2uW{z+F?3j?(;Nw`e}}u2CZYY}Zb?Xb#UobKx((dMf@y4FT(6J_d;m;U6AF z=3AcpqsZF;P8P+Uhaxj6_7FceB88byfAF0Q2n+_btfcU$ zbQcKpvpo3`s0S=r5NJY?nGpEB#|_p`;#J?GPS}n0Ev}ieGuvieC4s$ORr-k-J%%5N z&%6<5?3-El#K^ivGk7LZ|4yUG9@KKX;5O)YD|&JL&?g0 zO%uNImU8;-wq9f(l^<29sY&}zaWt(RQR`+Q*)PRCLQ?i4NRRw!rHXw<;%b`a$<`W( zo>}zA%b5{yyRFK7I0FHy6R%o|D2KeijJnJmGDOlM02@q79qfOT%@asb)6}1-I#yuQ z*`~f7oX@@rwsZ&QM4$xtyl;?`dV25fQ_t^;`ekA2fA^@b9i|>!^Al-1lXWyyhzIdx zt(s77T&MNSPCEqNi9oxXNop@Un#vGrz_;5-1x0>>C0^EQWV6|#Cwby5iC^j_)X8z! zvx9CUaS{`?U_G%FpItpP{y21I z9hx_}JkP%;NN0;WKsJrfxxfZvZ_Htk1^N0*5uO0$FzhUnufG)IS!BNUG6>w-Z&kai zt=x^LeWjt8;AeBa5Kzv4QAcU0-H2IBbMAHN-0(jhcxD`5G)X^Cl`DH4F1U!xQ3LqO1Y+Z1mgF z&MGYHpuKjZq-;%%*ZG;ou+Q&&@3RtsF2lZgJ+d>Cg9}4=f4T+k*1X^#;x;MJ`XZT2 z%P(bosLsy^qJM+j1qgAX>e+GqzxQUcvMh5OQHPRhv>I z^Z{sw)Lq~_^Ox*6SAVw(ICm;DZ4f0V+;G2>0=t9rOPO$fAV<+}eCzT`oO@LJ3Z@6X zQ4L*S2(}d4b~F^@Eob6b5E{s@gay+pmY=!mY8aX4Fk0BOrHXwcY5B{W&!a2G8NV)AKN@F08_JDsDl6?b9~Bzn?`nbKh$vQX4b57hOm?rio@pjP&z#^mey|c2l!R-7B9s&1?!c{IOZG7 z{e6o!<;M;xY|TushrS68i;J1xKEpU>^f!RRpv}GW5_V7fBpzYC#qVtBhW1J9pWng| z6o*!C!CVNxMKzHqB}*sI{sNOUj9=#^ba%;$$rOLH>;DUmS`*l&Agd`- z&Kb0SD1y0f#3AbTKllzP#e9($GI9;|*oBv!7^xonk}rRWZbaYe3-Kkn5#8u5d^B%& z-9pR}yQdsX4`a^or36j(EMJ!}w3@Qf zLTh#l7k@hc?-0#D`6Xo~;u`$?h4ST!>*K3qk?;4;zTf*~`90Q#Cvn#tEsqXWcpkPF zm6bs?O;7}U;r2fwnJ`Y?=`+L?!QS+(+HwQY=f8Mqu&c~}d?%nwzXw%UqCz!283TiC zaTl*_oY=L%Jp~`4aab$QPYQ7M6eh#7QD2ZLE=pkr=hKCPYhLkY?XRtEG~cOMssrgv zwr3LdIc4K&&^{UB)SjnfU7fyKBqQ{Ur>`~}9jOLOHGNQ^WDG3S@_AN|doknVUk=+m zZ2U}=A{0IX&3iI1Zo5Tgu}z06!JRJ?9M@a42vRg5mMtTCWyR*5Q?kb`&k;9mZU*^O zOoe7QX7AWTki*DKfv@MaHL)e5Pv%7(1-F@%@v1F{HI6zQo3h8@&&oMIv%d`m#?bVW@uU8*KiZD)s`Hel&5UI?);P7*Nh_a5EB~1@* zBGw+@)B~@0S7u$>Y4_y4k3*@I>z`PZ5Gn_-$EvKEf!A-9p`fa{Z^E5!To(}R*rk*Z zoTE{dVQ?GO#p+`pDj$2k6zbq)Gy|VC7O2K`qoVJ@3aIZqpfl9NQDP~V`E zNT9h>&IC!2a*_z1Sb7iCznV~-;^v!d6mbK|hwqXn%W(3x;vSs3MO4Zecoxg!_sWCa zVbw=g(0z9t_*XZ0P`{~He7@5vwBCsoJkf%J9GvuzH^ugz2jhmjI<{p{EHSDO$w6(= z94rSk@jE%Vg$nO8K;1ji&-D!&n#K}9r9W4m;&wrbCn-f<^sFRDWh4o2qLBR>)|3*Z z--5HP;mgNm;lh5XXM^-wW*WS)sOR{bHCqsw+t%Cg_aYi93JLft2Y-#|Q5wSH!jWyF z0&~Pwr~+6{h(A_t!H-nSK8iRODZC%KJt;Cb|_kn6(&GcN-{I7@Pn zTl(HA)b5_o*UCZet$FC^vq($Ts*o$rN$zgU7iA;Y&n0JsQ+oQ0*6*#Au(zko3`*zb z5$TN3ku{CBg6SuXBc##pZ9vTftg8`td8V_diskjP21Byb9zQ(wINp#*-%S%VyHlWMq2Wi%=8r2 zRiww8-h7gCqtf$m{r0q8d1qovZhOB(-(&i3kcZn(IXmA5JL9USf=tJXk~;`)goE8F zt|aA@+#Q4T3oLz$@inB+J;7E-G4aB!!L4AxcSBRqw_30H+pIP5(CAzN7KpX63 zadbv8Hj8nev}6_flG2>yuF64f@T!nIKPS0Ia*&((rdzw<_$22C6x--KrqH*@td2AL zeq1ldpn20})C?gEI*TJcDxq=M5=^-x<0lxrcypkmt@oN`-v}~r26`ygsO{vGY)$11 z6^umQ4BkXI^E(WjXTOElIr(K6(Qh)jkgJ%;dl6|uq_DOv3q5l9a+5x5=Ma!HVE3~L z$R%$OLeW`{3OEOqZMTg(uixEtA+)9dCRAYRQ@=V|?RQ(WN=Y+}R(tPUXnln~BpX_X zzP|Ekg;2N;)dvbsJo&4m@abI^h5bo0jKZhAa-ncm4ipYtyxJ(-iRuG|hoK2p`g}OK zb8_t`dvkKW_zZKGZ)Hg7o3H!pKhUUzfD`_Ir?|x; zl~nvoGR`~r@!3|G5X_NaVp--&c#*1@lab8i?)nN^!-HE~o2%b|Z4Hmo&85=*9cuSu zfxs&;I5qp-B2SvKm55#zAYA&B5o7eggzNl&)(NnF)8d@tPbLVP^d8s1qs&2|>&gcH+SxN~K zqx0s8p&4t?(adWLNu)G>b#P9ZrJ4|Hl?{hK`%4VPE%(P6>zix!&>iQ37wB%bFADVG z@W&f&FjtIXB3A&TnqR}LHgOdU>k%#3#T__Zpj%WLVR1h*hWIFO34&a{{R|2TgDghl zR0d0`l(QubvAB6D=V-Cy?ghfKJHdQX&%Ho+I`X#fsk?YUCgpsVn zfk6d+l)@lhvg*eT@*+=ceW2Y2?9u?J%>-`@{r2w7?kl&nhTZwv7hItacg!W)n%R~z z(XJ`yXOVAQ$bSUaA@B(S_M|E2QE8o&GhO)wL$uP;xIdtG#k(}_9JLayVW!f}S((a# zkWl7Gh8&!Ty7S8jEnEzXv(pjk_$`QyQ_~lre6dG4)Q$sltm^0Ii0e>F(%Q#p?<~J7 z-wU*SA;8AcoZ6ccbCfqBQ=HE?yZn34;%HrO{eSGed7NZJ_BLLlF=g%K%P4zdm@>As zjk0H>Mz-lDF(_M0V=K#$=%y@9wpL^*Nm`1sjkK3NF>PwlB$_M?(u}3-iJ>oTNqgDf z=bY!n&6`-l}@9+Eh{Qk*^6ZeS|Cr(71II-ND$l;&%s{ZD|M|qc`j%dJlE=u#v z%iQn;xOCOeujkB#^%sxUwETbFN7;h14f9bZRpoO1!eo=qmL0FQ3&T?90rwuvzkXLi zI>3l7v^hp2n}(W>zp>Q7|1+GLPCt&78`kNkJyN4|$WS}&xFfk~@5_=L{}JD&gKS1z zgC4yb*_DZc3U(|t@tu+?D*BU#55YR+Z3s5rfG6FZ%w6=l4Y;ey-k zSTMNQNvV$I2V^zV-KozqvJt?4oX^Zi8q3v$rOQ(EPPqIki7M2SvQfaoJ`74ptt!f%n{ROiHiI$4$r$kd+z?)g+?52Z#+D&yBof}giTWY z>VQC&qPLQ~41@3;PMjD(Sp9W#jd-T@njNndjC|#LK&PyXOt(eveM&rlg@?S+=>IFh z7FCIduW8ldulpz%iiID3FQa-pFXATM;84;PEQ+sPr(|_(V7AvKQ0=<(wg;X5#_h)c z&}jo>)LmcT>YCUGhb)IzK6@ch2-?X8iyPEGBh32{^_HC!Heoe{a7191(;@fro-MeWr?v3kTZ0=i#O@Fva za^t^cCNCbFKBpE-M8tyCJljr<#eAgqf&X*^zgMXIM9l_X|@&}JN zHkV+`gv>9;jNkN?$%~K23z!qSW_!=}fXxRJx;$yD?a?Um?>?DP%Dh3q?@s6{3wSwz zy(tBZ;>NJsW}k*o-}VjlC&F8__0Bd|+N}(qr@Cqj>c`z-x1{NuS*B z`fgBH|Go8L(~_#lVLrfKwQ@nF{#q>I1{VxTA8b-CIGniul#|ZzfZ3LHYHbp-6uq;C zXp`O(1LJn2%$B|PC7-qJq0b5^1_lUkV2dv;hRMFA|1I*)X%ueKK8mO_Q#~_-?KZ48 zz68OrWLQEvjKA-=jO(J{`@BjLT+W<|r><{R`}TjfKiAz|^V=bUb{L!oCn+v9s?G_r z=q#ICvcm3oq|2*Xi@MK!ey^+>;jdk$ySH;L4es8CAqh;-NdHQSj^&s3A@nUKPo@(8 zj|)D&cX%5CBF#D^c&BYAN5B(33>6#Jep3SN_v+iylY;H{YM}ibM=LFclTCl+Fs!e9 zKT=;=C{WhxgY{)CTV?34Hr+a682>+w#Q#PlLSGe8hHL}Z)@5tu?>Nq-4ba+{v%pK= zADX-pSZdN2x zdf6L>tow~V4qIt~hG}kdm9JJJv!gGytJRie)~>N>@ArzQ)-|;k0%xIwG#rN1gf6|? zJE2Q&2BR9NQm3qbgNo*oTGzyoanA~6T_vtP8v2t(jK5%gKt8$)*clf~h(Cz)FAs+; zqqmc0MB}J8krMQE=7mg>vCt(eDJ-(&o-m$y@+nP(dFIRESs$LE4n=QgE3FBojqefz z+8fJEEudYoAm1&A&0!p?O)2e;&vM|~FcWB7SA|}5O(5vHR}tU;vp6vOy6up8U-!Lb zzS8B=!>a>byXP8KgAcJ?iD#xVuKUi#ciW{VyJH%jk!gi`j}!X9vt(va9`7eC=d<+?_v3XNP>wJ`|pdWOMLp%v^NV zIErMi-0_nnd-5|%c1G>?U`;#HDFuV?35Lo zgv}8%Zeqo-yppfd=~esO_^z+U+t--{IfCWdAg>#NQgwG;@nlbyEzkL;6udfLBbpX?T4*$sDC zWP2TLF3#sLd*r*6X?z1(M*Fxub+nf;HZk$~qkTa47H}Na8Z-v2DarDPS%TeYUJJn? zpS65#%vUqyEB|DXyU|4sHYZ+6du#1obEde-D5b9R(@XuWmMUlXSRkS7VTbq^3t)sb z>>YhSxyDBwQPbW*J>MXYMksajYNlY{8XaayZ_4ZgfQTl*0w3Dm5ToR?Hd`r+}&`VGl?S>qX( zTqn)8RcY$`SE$~s!_dyvvIk}We1U0Rq1_G{n1G~ef5a_PTyz?RO~TpmxhU?7G8K1! zbhzTU(vT)}ire#;5f#_xlIs+=@b!K()+;Uw*#=+^M!Uz#ff+3OgUMR97#}B2bc!X_ zm3#hmu3WjZ)q$dFCWBxf(hY~!lqmDn*Ihr!TR++UOi?el2A$dMw1Z9vs=lMlls51gbXeV2Sz5mB4z{mo z&15B`dRy1B+$`-_)hU#x`zlzK1Xd*IE%*oOmxRsyQp5=Bl1s1o@A$ljoq+O#KJO~1 z-&}p(b9Vm`pZAC3|1Camzp!yW?^@_LbMtw-wM_GQzlZL;J+B_-^ZsX64cU%54Ze=y zHCGKz*zHF&IP zUTdAD<8sb6s$7_lYVQCTHSPU8_i(YTFa_f~_*Dn&N=lS zmM~&*a;OGi%JDkV%P7OOfOkXY+B0xeI2M+%`)1c|Kli zBV}%u$2VFbEBj^|rW|sMgN;fRy?0+^)^YmB1?-_PEOq3ey%ES>s=`juT z8XAfXVf(yAo_Du4AsS&cjA%2W!<#}Ka3VY|~Nm!J_i+$;%? zyUb00uC^(n#x!Pz{+VrSnnEO(vO{*6cKaHG?_Yk~<5|M~uz}{b*6=&g-L^Th0n0`M z;$)%PiB>epFBeCl%a(NPx83ZpXiPL}4vm_{)RKzX1v;&fuG!bH(SMyj9=X|bXm&KYUL~n(cGu#Wsd;VoJ*4npvj@#* zpxK|g9L>JwWvG|-zm@T3jUwz@=` zaI#3q62aws^iw6qSxoKt3Lvwo{0 z7076Sj8XzxujVT5TJvTE`+C)N8yMz_6lCW%HNkgetZ`@{Zz+GiceElZh)Yi<_5 z>XLDIdkMzT8yCZCsvd>ySfG1SVC{4@RV?K}NJ> zBXW>Y8Ihthq{@ht?l63mNve#pV{A`<4EA0Dj!GMK@!ohhxd3$XGmdS%Ni{`Q7C`&Bk!QPT-x=slcO&B2a<&cvneMr3c6Lxz=Sl)7NlH^uH{M-jgRoaxuP+bJ4pKE_O^chJ!GPcXw)Y*7QaH zE<5Fcs)2Mp4$3Zihf7wjsh2`$^N#8nxyShz#eK(EEc+1qQM>AJMnZ$0HVray1mc`& zkcmp7IcJPYKZ-Ca{ivByvFu?+BZxLJDwaLOXcW;#M2Gh|NtG&nZ!LMQ-ZG-G=;|5J z?BoJa{@MrrsEsn!}`m6Q$$lbdr57kYfkA?+Fv+678I`4Y3l8lSo7s|m#;I+!g^U) zOeyTcKTpsp1f>W{6BIYlE?<~L{?^uZDJ`na0PomN$0CvpXOdhx$R%N*o1Zi;HpF!t zEXjJc0|QGgGGaKW6dVr9Dl?-bJUAQ*i2B1JFT}1G7dfWRlrAmfMAV`l%Gn~)^jTuR zl?jxWITp;E=HTL!bc5k2CAsBtfW+YrOX)R3Xwn=o$J>TJ&rN}J=A2DZ^i~g~Iqpjc zM>X*=8>T-TV<|+c*_o+jc&f7ZRlt3sy#3GA!YG>e zo_AAi0$8&kS-`s@>(}+ib^5KD`EP1#6g&m^e9e({y0Kr5Y_7ILjr~xg$PaZ+#48uA zy+Ji{gH_dWmQ{HdR@tda)$!@ysE&J%mQZ#G!L8^mYIhyF_OH<(O2a=eS(Y<3i|o2$ zL!XMnzaz!u-;r>TCl!<@b(gP>Iv0I%`mDeg>m#ViAZjw&0oBRRS%Y<{C}mXG1LvU1 z9%>$0W%Hph+oPZRR|Q1kcdgT`q2aFi*DO8Fr4;dT^eM37VT2;us(rhQ)1R zv>DL|qQNdTs9zG5RMFR$9>X;6{S-LJ{0)mst<&v~{b||Ct1esfmT?_sM4!@Ct%?J_ z`&-6lWYiw%Z&P$y#$PZa`me5crDh^fvt|6~NGTEh(%RTK?VKz!_KGpKj2}Hl z26t=5NAM(RPjvPI>!s4#_fp81#$(lUW@-+$0;^kW)8Q7+&f|WMAiwjjxW+TFtAb7Q z30?1rSl^t9yj<97zV3bHEhPVs5hk6D0g*YVtgi))n>6C4;E&rCXR9~JsGwyCT0cmx zSbgN)^=h~4#qv7WwD)tmAvQJrFYG^BFOt3$>@QppORDH$etAg^;eqR_h$V<94zO#z z7xc6cmn3=S?YdLKa(CGd)^of*>pG2V!nFs;{Ls#yHL$n2CX8Fg%bC%28f^+l^C>hZ zQbmxF_Ae#mhl5OB=xi0%dW?MRc4{82j+V#1B#hq9+VtAwF*~;nvC)CUTRn~wyIhdx8>H(EZW+T2X!}E z`@S>Xnt+Z^$@Z{TI6yU7K(h}(G@Y1^vn+QZ3zeS}siif-!=26KFTAnJQ_(zbQ%f}f&6C*N zR3^xipqnd1fMQnM!7Q#s&>%soVSqMtLI*dsE`<#Oqo^_XtFBFo-bdZn zPRR?=V2KrQ7P@R<$wD#Tl3p-6FCnjC*%kkv(a6Sqfw3|_2+~%!(>_v?+i7n}95XlA z)ULmFp0k6P9#?BDcLdorD2EJg^UU`LuD~<5y@7sP^v)(&q8p!qC0F)zn49W`nt7eU z0mbEwCpjKI9}TO1W$+wp0q=KUGSbx&u^ZUpgq#j)}M0>Cso(8&?2D>o`3Z9;5 z65K=RIs=S0Au9SrY8cUeM1zuXx|UQC?htc_$8%3CiuOQBF$ub@SG%t!;4ADGXcuM2 zaT{k^DmX22KRNzmMFmNB0Hcevg$^ZmOW zZ7b{aEmiYL6~vtqCX~X}R;>7Icg?n-K2+|^RPnS+uq>JzE|@LSZ@LIPO@UwUuL{%* zHNJp<*9Tn#=g0!1#!iN^ycbf?nE#E9k#{2p$LQE={7!Y)ph3^jw?btq2r%|M4Kig( z*&7=lMg+UGPaFQx5^z2_5UcRh$n1l{-x=7dtHPCa95VYUg3W^idCIRMl1D&j# zq;KZUD!hXZ2Y`x-q88I^Men7Hl}nUdV&tN=1L$p?{PDdR78N0=g&eh99r^}A85S2JrzV0_?Eua31O%ajzQ&P~{5rw0it6XX%pVW2z8l>0duZs^Vg4HA?x(ESC1jwh!AK?4M( z4fK+|Gc;tI-vr@hSdl4fphx~9oJ0c=H4o~Lti7LNdJXg3!z^t--P-ERkx?HROB>&{%!Vq%%oS z2SEh`z4$3XU&=;1PM`^DCuqPxv+fpB5)IyMFpz{5c`x0^r6Vyyl#X#TMDseehE<{ihK|=t#ooVrjv8q3ie16iAcH%V5aEU4xq&n%!byQNC&wXD*eD+L?}k6K^KU+o za$Y_W6ZCIR2)Z=23u^dWA(tWkyY{UO(oYT>sHIR81n^{1y51WbPCw9%fk}ns;}|fC!ADSQ{)3F8?D}q9zS^juXNmK z%KEt|%YSp=r}e1??3JarYHx+PJ;}>$3*n)wRTX8lzij5Jn(oh26)UM%B(DoqUvS*Y z)N}yz)u`zV%lA%`@|;ICWrWiRed@+3qp9hIEAhR5_hQ6P)6(njv8prW-c0rGoYT@D zQ4-e*W%KF|l@!y{MYl8a7t3ho8ayw5(ms3M1xj^U6(Leaji+kGtm8F}NRcQeC;v9y4mW36$IK zPFsgH0gp_7c`Frk`qHYPf{je{F85Y-Q2C+jR4$yH*1QU}i%YJPt!0>O@?Vg4fG}?_ z9KLRQrL(07eL{%i_K)!`?v(HXM(~bt>M-%x1fsB3IvrK`+K$_RVh8 zpdHo!zIhj<$WYh*j9cn_hi!(4WA70izq3JVHgNp?2V}ulrUk?Ohi@UVw+B2#Yzw(} zjbzIP;y|96jXJ*nFE7yztFnL1atX7jW(m4Go#XhzjgCv!xQtUZ`ZwgRw}ZS{lckyJHUJxx zCoWVwF2Sw4p}3YLinOge6@goKA<1c5cbS=@2LE!Lw9}b4pfvrsq<;+EyOZSLcHP+$ zpQoE~e*n^L9ixUgyO6Bx0bd`59d z3(^$aZ|Y~X2`W-QoqN4~Ol?MLj?oCBy^OXXnq@SKXd2Ps{YFwn>@E8kF3_mWkWj_D zujwimfVQ&nJ)lmRX|AVDuy&;tpto-jPGS`E*5W%+n<^myd)&mLR#HvL?KiCkp6qGf z%#!LM*IoP6Y6G;M32_jGsO`L}CV<8oCzDh=hQB$jY6a*hbL79`R+M%b|8nMlDdv&e zDeWmNu7Qft(ObQW`o>!X{cyBuucCR~ffbv!=>6?_Q%rE{XTu$lSiOz9xpwrTHy@I@ zH1@y?OJfy|w~?_l)&gw5R5zw|>sMB+ama@d%VS)6n<4#PQX>|M9%|R4+uW!FAsTZV zQds{@fJkQZrc2z0e2v-juZSkWQaaF{K)Qi|hR4yHWaU8k_y`Py35N# zN+?`lNpx0Pn(7ywRIjlo1kMd}3;ov)sUFIUC`IpDbv*0rfE&GQ-$Kya1hFaHB<4o%FKqOFrrulK$#%(x z_=S1~6>PmTcGK2#Be&1w`3;K-vGuf3&YHY^U9phD!eAG^EksxN@9GfpNcC;6T} z!FE%>0KI-Ci@V_m=?8T;&C^z$y^YgSlqtpH(&VJ=2Trfq?7!41DpQi64uX1((;u`r zC?+`5KK5G`NxKIa9ivMC{2|E_$|ylb?PSzvjF$Bo(Y&ZpPLWaGFzKsUx1A(euG+GT zqKLE96T%n9meeBRETWA?6fAqf~par%m&2th3bl?;@-iGuu^pfEwr z1PvPK3w1*9MFN6C1T_&uDUs}6^Zcv4ReI` z^$n3scV-ArV82v2T*8-}nT!^Y=}|s(XUcdWj!TIl+!?utS$k~+bk1N|3sV**T?k7p zY!XIGE2?7@w}hyBAYsi${bM(y?$c)JkaktX-$!mM0^7+IE{xe@2xb$wQCiuOEqcKe8`n7@Amim#e4eazA)a|E#%fC_BxUUVI^oO~BZQ$jN zrA+(Uz>WZWH^Ro(f1|8suS&e2f&c%yK+fhlIrHo8>?0K=HR^SN;WJ`Ha$o?=zK-G1 zi>kQ^>$q^I>n#R4=Mn+c+4Rq&DuEUaMrWCEJA#ZtWMsxIW{j@aGjW+UOEzov{to5h zy;}o(ZZ{Op;FY8Xaxv@IW}w^5>L0?QXz+SC+Wmuke3o4+_{?2eF`8HUJ-DWBoM!a8 zigEC(9bJJHOByC>rG2%CGNQ%rQJap-ZwC5>sc`~9oM3u%3c*ZlpfAiK-%e0oCG6=} zE5&Oj(Btm95W&&n!dhI8Ae|Je=lHi6r-R5TOHeO4^;&V;7pQ@&|Dc>w1f>be8R)Ky zod#$URRhayjl^!=l7UDMUqeO{DN>S*I>;z*j1Kb|<+ah2(KA~qqkh92Y;}u~QG$%x z$*5qU(;hI1e9vm~cvPU97knVjA~x6Vw3OB>PA+ZaQZg7n~r+^;rQP9cJt2pTfb zYQEf&sv6JQ5;?19_~&b{#j+pCKYoU|{EY8BM|vX?*1wgp4x@D-cG)vV}4# zgf1CfurP07&cdvPDGMvEFr)KECrI-GLEIiD?O{~t8b4r@JTx_JmYOw8{J=?b9lklj z>M{C0B&7&>I+0|>$gN0ncw+<0@}gb>4huQrnf=8utnX&jy6R0y#@&!{X2^Nhw3?PIhJ(Hx@*M0**P1!0!aB%*0XI}lAFI($--RMFa!S2DbO0Uc=# zs?4573A)Jzpue6kAeoD@HW#fX%7&3OE|blEmh}T-=4rc)MU@a-p1sF$DH)eXw?m=b zc5kZaby)v+`d*c#tR$}&ceD23vW}A_xbtw~rYepq3z+^(r6jz{!Ah0LXi$RcvZwF> zL2Fay0zm@=X=8xHk;ds)>LA?ZN z=K!Zk=TW9LKGp?jil8(>W#jacx)??80&+?cq{_n#Xwo( zG@hK|1ho+~WT4*rDbxI{U6i00K@Cb3z26$AAI4~L5rSF>YBbP}_mk5-TPP?@P%}Xx z15L~dNF1n;_C=kI{=5ki`E~|27)4Gj&Qy|2M$5|dC^ug7$AxF<$NtOJ72t)CkG}XH z#)uO!v&4rp3l`=r%vqSVFlAxV!i0usvu*#1+DxC7^d&BOpTT7ZDMd&(d|OE#*}N!m zd(Wh1y)}N$He7G9+F1IE-#>wsobwkimd zvQQ^F#eK(;7 zNa4Ior~;`FseV$}te0nbQejekqI!LvV zN|H*DYA4lBDnTkqs*M!3b*1z;sT8RgsWho5sVu1$QoW=iq;jO1N%fHmlgg870yTWf zlT;awUv)ElaE^+TPjp5ER}}LjCrIJt?dAUi1$8p0#22HVJU)+dyY( z8DhmERV()428z*IL5{!Mx!yXvt2vC4k*@#nLYFbRQbECG;CW()aZX}@4{c-a)K!&B zgj`xEj;b0(-EaYGlc3CDf|?0xGft0xL(sSPE2j`aO#~$jblX`1l8RMe0Bs&$nibP7 zfYLU#(mwf4HPk>xjbxNGMsME9(iY_AT}2D;8Ik~NMFV}LlRZ8tK~80YJc3dNdPLU& zc-8q^Ev`h+AVFyZU1yvokyC-70fMpyikeK9{a!VYC#avGUIX3IpZ6 zhPkgto?u#}NI5d%92qp8TA|Jq&pCf9=GG#y~A3s6uG3yWxznw&G*=XMI{O9AgE*@_dh~|_bI0YLG1($8tAOF z$z$sfox(p}Pb*e7%+glcQ{QkDkx?5Nc?Ozup)e|Xs}K|=C`M4lKu=@|I-Q^hK`jIg z8R#nG^upI#T$rF{g4Bqkm}$moGja+M)I^ZleSlWTv$*4TQ4KT@)JTv{6#%8r6p)S* z^`cY*AFYc-O#L!t0Ml!uWL1h(`C5{Dh9rO)GSJpOBl@<==z22J84Qdzx4NxJMrAVc z$VewWfcDT6M(HD2>m%bg)jpzgBmmdj-u)&kX}wD1GDt2_6KB73DSH!(DiAb4P|QF_ z%pvGBy)WCDC#avGxPcBnLqMXTWK}~?uA`N2Gt9?kgKzpu8!bmhePom{P|*hVcbGjf zxnv3IC8*s%HyEb`Ii(0n6O=U2&yCZ0mhV5ieSq^f}@)>aK<4KvwB$@gDs<)UO1BcomeE$=hp_KEh9)5s`im}RVP zUy)ISj9SR3&p;ch*xDx5No&DD@4g2797Yz8S3&pXLQ!WlzVPr!os+PGC(9> z)aZ(7Dq?if)EzcDFVAbX$99mjAZ(9`e+ZL<=hCevG)uekZAXw>k`(UpbX}5CxR5K8 zlsX6*vb;wA%<>xf$*+{NXj#B-k(3q^@>!C3BOf7IG4gK9t78zpn~+%8Ykv-WigE1e zE21{<;uIP-MqidOxsQ_!H5+fD4=HyaJaJ1(SIbx+%~f@yVH{komkXftR@VgsX%$!h zHR@$>su;u*Cxg?+tU#JmN}e2QUW9iVx-fv3p(b@p5iij-x5rBO^w!Z=!Z;q|3bFPd z0TbQCae58I2&CW>l8^DMq7+b}%YS z{v@MuMB5paC4Yj^1fp$>%920MXcEyFqq5|WYP2)O1#%0iG^q$FHYi`s#Vt=h3-eiy zR1>K_QXx`#QjMhgNi~ovkQ##R!w4K8RUuU(<$(%z7=Fe;Ql+iVnaXhYSEUW=UdUBO z0G+GrfTFi-ML{7o13gU=;9%Z3{YE*}&COT*QZXtm7;T_yGkhhc^>&li{i$sI}X&gMN!+@!Qw&s`ad_tyWDZ0b_amQ&7jaf{8q+M-P^cP zEAGRS1SEQ-;ZWCPx7Cn{CADErQ1=D;q)1uH&5d^d_;sf=OY8hl5??mC?dvlr_wiR<~(n6ego) zGU_$Zy}DN|9SL?(x!k(8cBGsEw#!gMY4a7yrHNen478LlPEtF*GCFA$tykVKms-6_ z?`ypp$f%Kw`VDmAX)J9+%3RT8erW+qY6FGM*mrWdR3^xipnCi|?F8YZovkX87gkKk z7*(`G7QMe9nNH^*p1|o;;qXCc!DaYO2Yl2<_|WMLBPvc&$U^4?$*`C73Th=`nIV19 zk|h=_%v+eVPzHr$${L-rFlk}J!nlP|3oBM=#OS=yVbb(PL-sH!4{O}B8=pXXPn)GS zwR(Da>q=5}|0Uo*krdWq$j&7xB@3A%>D+;%Ns3bB=^uo|YCzkk#)-NDcKqE7)R+fP zFV~k0HBOXBEv%No6X(D1PRx7V6L=F_!HIcb3+Keto?+Vm zNp1C#e{?x-Z$8~-UHj~JrT_aMRV_%prk~3CZSkHyD~<9NR#YC3@V9SEK~#P=NZx$H z1Ydn+O+FAhY>sTrNud#2PClr|RN_|Yt6zQc?0L9d5?-N7k&lDIJQTgnj$`tC&#Rn} zUEe{KciBom!2V^o}^GNTbh2N@M7sl;d$(E&!qNh&ZJ zN3@?&agy?kCJ^moRGg$7qe(=285Jifi|8;l`$x2EPNUlHnk{Op`=Xh0fo@Ba1tgX@ zYnFJk6{L>-5pB1cYTUWyP9podJLpvj!DY_nj!Vh7yt;k=awnUJ69mN{%*0> z9-!@8c?uh>fE&Jol{kTy0rZEl=Cdq)+WC8(Dm&p5T%p50@-Pm>}jO;E)^ zAKTP$6FDUb>L6&yKzo^su^|1q1VQZtH7JEOq;X1+Q=FhSf*K9<#P!tIBwdHtC*^u# z1ceMVZVEw-%SkBbB2D(>bbE*4YMv8EG`XjR*~11p>KMr;Gh#?Bvrf{_FN;KeTpaVB z3Ws;$B!^9S?pQa|fK2ky%PfBM?II!MGno4IF$v>D=o@N67r;isyoEUnvlgZ-Oj?+b zkaLrLOL&z*G8+}$b`EyUCaqS|e`Tg9R^Fg1#(cFXQov1rgjoAOluZ#^CkiDN^s7DpH<|`pKx-K(j9=Xji_T zm?NlPEO4Dk@72}BziZAY|$(IleWP-*Qz)OJ%+)!h_yciY)1f1?V` z^4TCM+u13R%JJC%Dcjj8kjnE}KPlVU$&)JZSsy9e*~yVA@mVjaK~h;#Wm0KU9;p;5 zbnOPzsDsoHsU)ce-KFhp2Q}RINvhcOGi)SjlQh-^|0PueXkE=Kh^3aOHj!`YZ#~32}%)^CTP$=+n58E;Ma7M1a%NpHqbhUio!($6>Si< ze@Nx_40E~mk)n5iB&(BFu_vopOWgXhwnTzOw6lmI13ljEiV%xvU2J_8p`#eB^{6rG zBcnJOwULpIdVnHFOLqLZ0YOoMVg#v`z{7QH`}2OjbQdA0g&?&m0QF`~B!7$OEP2tr zy4N_{w&Oa;B}^{O`i)t8VOR12+(sma=Ksx z?W`5CZSXME#L%bns&RyNe^Sy4SdviS(!q4Knh`D6SNak8F@FOHhfRL4w*0 z^su=rClgd4Xn>%EfmSn4x4x+DpC_oFpmqbDV4OA}ryN0j1SJjBW5e~X^;H8|f_e$+ zFi`4Xr-4YdC(T|=HIOpQN7~!)SMW&Y23Q(TunBm9HGdML}jjqU%9 zXPe5!uP@stsv&T4Wi^NT!Ez@%=5%j$jh))ex~rzT?d_)DE!&|{uZ z^FWomPff%PbY_-39$!mju)jHR-(V4K;4?Q_`^VLk|G8xS^ar=DG!Tad3N;vd{+5R)a&nd=H(d;N zn2L@~&DswwUbu!+kt_{{`1YqKqZs$RHRu`CAS1>FeRDtqJp#7A$!S3U;2|$i`*;td zvNTXr+}#>Ml!jhc|5*Z}NTt=#)qjeqair>Oz}0_}sR^XEGb&4i1fxkr+ZdIlL0qHm z&^JcPmIhH$wlruVWlMtysT>{fW>U5^2$Qmi4UUFfQMHu3SpwGDt2_Q_<=s&uh;ps6fyFLE5$`YJ-OtksN1D&tV3G_*kvIO-K)NY_p%p#slPAP)Y1SJg= zGfqDvrzAlg1a%nbEj#Gms#zh1bC}*IRRBV}2V5XEyXskAWp8;+#Z*dM?$_Tl% zkW1b`$M56nmDGN(j9wd~_3Agwd6wiC2CK_P;g2pTX@|A7P@ zO;7_tjRchpG|A4w9)>T4K2p(S=fV#f=z+b3lZ?kmRqiz?ciAxOYKJU(pU>wUSPxI+ z+MpDOYl9l-H~Om^+OoJ8&o5-540oYrG)q`PCJD<7=YDz{vCKKkl(jHrVba2cg%v9# zZgk%0C~5kv5qp@lhhd>>e9KHmWarl4PjyJDnK&s;#958Hi8xKl zCgKz+n}|C|*+iTqWfO5bDVvBBq--K?BV`kDoRm$(F;X@WM@hjNL#>@Hqy|YvNR>%7 zlk!M~NmWQSks2ZuB4vAYjieg6W7j|`L~7^@X_(F?QWa8RQXVN-caf}2Dne?IR12vR zsVJ!dQZZ5mQn)xST>441k;;=wkm@7VPAW$#NvfAr2dONn6sa_+G^rG+EU6Asy`++) za-`Zx^^r=D%9Cm%)lVu;sz546YJgOfREbmzsXd+A+TG#K4El?)dP>jah5-MO9)31AbA(WwfO>A7Un z^U*)o=~*iWE>BG%m;HF0FhR`(X>S1N z>3s-FlT(PGCW5pB0d!r0pqC%j;u;8QBuM)lK%K^ED{`uQEqUDAIND7Cx++Uf57?zI zf;}qbNPP6u0fGXWHd-daRY7ZGm2Lk-9$!hhWRE% zMu%|Qvp_}zWRx(_je8UH2bPv6sGp#A108N!`sxwYQjVZLf|3SW;v}n^?+lKSjRc%L z7$9N$iy!L+qq?_oQU+Sq`O0lRki%J`4jW;Ot!Vk0e6VyRa)kt3r2#P2pTZZN?M$bx9^0fYCyhPj7BLL zW?dU^{SR{hkWnKU4I1dVxMbIETV=Eb8I=u_IfY_>^{q0hebdG>&<7pHNRBa8oY!Tu z3SV0@z!r8Y@FcI=@a>x(zTeO}WT4O6Sk!HlneY1WO?8~m%cP8z0U_V+X@(g9!6A{pjPD=o^>^75_)?iWjd+1^0sPGxD|e519`5!6SJ z`WFysOXKv#Lkh|g)Ju@MBmf<+A{D)@Z&y%?pfo}1#Q^l_9xUz_a!L}^L6AB=03By5 zom=1#K?4bb+6ju9;9u`3oTO<()u!G53tA+@ENo-)!UvU6oQ&GYNF6eic8AZ1izroP z6B)G`qg##9xnvY2qZk<_47AK1tXqko2th3bwHs(DTUcKAwu%%csF|RoflfWn)r~&6 zigaWHjgn!Wunoa|$S6ccO=OfZ(CNEVq%A2@13`@hr44l6odn&`t{slAp!VoXruZ0& zfx0I;k+QOI;TZVjGa4nsEU_0EZC}v3@vYb%eeboKUO3eKu{sHucnK;ENuHiT3A*XE z1GMv=a>^6bPf)*s9=3zHH}tdk{A55^Pai=A1Kl=3ij%$+ zuU2kpR&KyB_qS1`7)8pmv|chQ8R#INQK-u3Z=b4`1`V^n)ooicN|8~TjLHU@I@y<~ z>Pj6Ub{t-kVaC{eyS;3l;)N74>L8y(< zS}1OxfFnkSEeu)MV4-+ey1`+gI7>o{FC?M(JQ5a+7OzF<97FC=WGyjeVba2oWlk6! zw=im9#KN$JAqz{ek5Wj3(OIJ_Fat>E+l^%sGfEZ~EQ}jCZ*=gvve6|A3l`=r%vmS{S@Rh!<5B38d+wUw z=#sTyLg<DH=Q<17fo<~fsz)hsVGA$gY)65HrdK;6F7 z#Gm1ebX)xJuBTJMTOS}p&Ayb=#$$Nm_NAOkW(3llUaktHIpt&mX(iLp34t`}SR(F0 zfi&r)lD2aoEo*682GUBFwq_trMwR4UI*=yARMLJHNXuH<2k&dGYhK|j*|TTx%&)hp zbtdt`?%>6+oA%%$!QC{R!C?<;>Hz)-r+~w;{@@Cn=WqRzbAb~nP_N#8^v~ar1@}MH zf5F!P|0)gSpT7<0$*+8>p8uw@uRI>%6^Hd9k9);o+WXuLn8_QCGoo5AUU%k|TI}q} z)h%4GmAzi@3t{Hr9V|U!Q*H8yjd!Z_g01ZT0viE#NSc5bY%7dLk?JujJ9}kDp%wRf zf$Z#Q%XPOV5FH>ucJ>O01~tY5EJ+o`ENY9Ei~gcB7Irm}?7jl0TmZUjJ4waV?>qJ@ zN`qmYVO;JsE*FwZg(|@kLO_ECdP+~PgbUQIQ*1#_pRny=fYrx=q&THm*>5q zJVE^gY2yL3t#SJHZq;Fqpgw}Mu>p$rQQ-$q(g{6FP%lB+IRN@fCvPmmj75>Wn^T|zv zgfAoPp9cY}_jtEak{54(BXP>lr;KsqCa>im3S_g31J;9fXs!4lmhW*5NOxJSBn#33BG4RZkLwhG>&d0Jm?UqlgQQ%j)D( zAeRAhX;2FHUrn9`DNmlDeu5eewAZy1I=PpQ`W!)h1ceOr`>jnsL6dgxJF224!@OkU zIdrF1EK5ecWE3{gJ=?RiV+l$TlqRUzK+74YYq?F8B&dU+h=G#EX-#rU5Y$dki-FEQ ziN)QtkX9~EP#Zx}10BDWt6acHy!N&~&~UY1)4nsdC*vtIyHU+b=xKJZ$h!h*mWZt0~Fxyo|)1c?iB(ILthJ@Rn~1{1*mZ ztfrCO020hR96dkG!{6qsHxE2HnW?SZHAAGv+^o&nMWx|}4HDsKB;^?$4K|WG8mdY< z8f+DHG~&dHqY-1Y1<@#@;%KxmDvm}3(cz8o_p?4bc;=?d{1s~^V#0Md4w_Nros6(6|DpZ%@NeGn*wLr3B#J) z7?n1LX&I8BIt{L<=b6DlGgdyFS$$9Lh&`$N@19m!P=s)?q1UKX(OZ2SL9bC@=`;Wh zvZ#=OHYgJGiyO7C7YG_4sL4QUw+N_i_+9Y2cAl_d{-VA{(Mz(lJQ?+qQL}*_u=_@9 z{Zr-65!6Re#6W*EPHT`;mY`mOS`2i-f9}zohj_Z8sL4C@4o%P>;5J<#E1WZUz;A{&t%)pU_0|A zE3VYBZf_DL^2Prcr_)Al0i8}87!9L&Y=z#8s17Nv+jaPH-L771cdJaNy8h*hvFZ_b z>x;4KLGx;?uEn`-@0X=;cdM-1^Nc1D?L&0S zY$T~ci?A0PLrVmgt@b6iOMXx;6{)Ll5mZ8e7Ew^pB7FA_;MF(or)##N*R=#D0PItc zi>He7cMA@5vIM8mCtlXRp~^x@ADL^>$4ZsRXpoHDlHeGd`un&NE)X<8kTwQ5U1yvo zkyDBzv9JSzdT?!vLOy3I_*Ua%6g<8q81|rM~-rYON2i zC5f_XU)zt+`AGU!vgqwQ2w|%>X-6e#M7EK*ZG6mq&EEuMy-k|Gnnre?z91@An{@dQ zY|@us1Z|S6`Tuvi9sjf*d*n6RV{46!8*1GV>nNfNotr)vbyWXu?Zq~B#Ep26UeOL# z?{-|TprDb_m)@&x$LDbR#PFR_R9VX8;z@wRf2E4vZR#u(y+bH)i6AtWfIOJy_aei;v*YM@*zI%%ixS zoU-K9OHM5Y`kRgV`3Oo8lqN_=AJlV;aXN^gBtabn#gxJ!%;A*jov&2z1VQZt#SL`V zx=sT+q^W`Bp4X;r1LnW(b}VrvG&p@$(Cs+!S%~AB2>*YhB*)}_5+BL!*m=$lwd;$G z1&J?nVD9qYUt^==?i!xetS}l0mY#UWXBg^>ei|I={AWA-8=D>p{l8wr$LMrOPYgN| zgXQ=&gZ@jqiE{Ph6*LwI_?}lUaD;dg5C4u5CT5HDv?qVPRBV-M8sV2H$=nmom9{5>!|BlXdnMi%~Ex2fv0wtE>C( zwqgy(-KesZ$YqdR+LbDLPp)OM*#G(JINylkBn`8xRjTVx%BVm_17xH_3wqp8{hOlq zK0$ec`Uy%YRrKDNM3D~OZvgwJx`HLWHR`-tI6?o#to-#e#L5tqTA7kugKf>6{9OUgiZl7`c@-Mrq z{(tQk)ViirFd8Z%+H)%ILm-D@U7>7sYoM8fR(drtdnn4o4BB{dPymbTg3rt-MMQMpQ}kM}e0vF9@7!6~4p zi9B4}Wx;dUB>CmjDzT^$Q-nweS5al)zk@3){w2KJM8R{}!p-VCqNgmQoh*c26_=tQ z=fzKfo$90LbxRzxy*#Q}O8Wo%?sDx9r0Y9SB~IcbD_yj&K1AR7{Rct2EiPKed{Wby zbZhiQ9NDqZRe=8gGn#(@6q?_bZXv97bRorW!r9U-Y)d!vFIgz&gn_+7$*AnRW*Lnl znr0MxUO)2JU7uNlb>6Qn64i!s-|JE?sOI-;Sc~`_sGT~~5&^i)xNJ=>5prpf0K-*e z0jS?`2|7P3laW>km~$$`UN}Yq8i zx%&j~ct9XkFEG#OVx;K({1Wy?7S_bVv^fB}NcUG|@RV#q_;gvwR$Zrlxf?}ZL73ZT ztnB~Ys;Aobtu7!DC#$8XIIB@)_6Dp|HzT9fxhAY=ZQa|JWvlzKKBIV*(Mx~Rx_iLj zwQ2d!^ago|?;U8+qpWxvN(KiKZE$2}Mo9SQ8KQAH*AUH0SaP(6(8oln{q$L~A4>^} z-VRTocvmxgyN;yflxAO>B%2Cvf|88eKwMl&I#=^a+z#M^199x>oiOrqPN9S4N`3Zm ze=wR-@!CWn&6R&kAk7KU8%T4KoL)_%IL9Kv2KNecFu0F@H#oTG@g~UwD^m-PPnF)$ zTDJGd3!<58?AdL6hW@4Bt*pOE5|tMPMz~2b8?Ut4cLe6`R!i$@l;yha;j%og?m^Mp z^&EXRnk;|TuluwPz)%iVr{4vM31Jh$ zFv2iGSiM+ttb3P8tScVzr`LJ^M(FreS@$JQtEpd~w8Ndh7X0UOGs%E>$m2O z{qjOBzieG6E6efEYm1X$~ zA}%o%;I-w)cMS>rlNH3&;c?w}0*-jc?|ReT$5h{dDXv3DwEo{Irnq*cG6@8j;@ULO z?<#^_2xc-S&pE}(WIap;zW;ZkZKo|J7kvBys}Ki_Zz_ zLgkUMkiPRyOvHpNG_q-tRPK$hXh zyNX*b9;|*QL-YhIUBJgJ@=$pWD$k17EKMM0ncuajtfXcZLqY#eptb?V^3(lipcT9~ z{^>V`Kl0>bj^cbY()Vmpf%I!NXc-6%@iO8&$u6}988wWyOD)gYG7XG|(O%-g1sjQO zsPpUoY9|h>>z-$;QBm;~4GJ7Wn=cHa|`x(euRbsX^hb8?Ck)FuIzt_Hfp=B*7@MGN3Co1hp$ z5d*!yqHq+i0DVR$^W7iO$xCz%2Q{eyI}*PqDtnod8H39{V3Ko_@YIyLsc)^KO&%sw zyu0zR&k?7M@)gh(xY}85&I&pe(oFqLVBBcH=gQC$asv2^YKL=E02UGyZ+=l-A=~i zF!F%%WQO3f1gsa+ckl4+JASVX98qFVU3bG-h03ww>T~ICQ|P=RkK8 z@nBC1aQUTBB#vN+&Xr9dIV`o^{uZrGe zYk&>(XxcX{Iu60~d7I$R)!cQ4g>vIK(0F{v1K!$>z&aMaSC@6|A^FAc*(z$%sF`m+bLVc1BsbX52BNr1gW1KquhfP=F}n2oF@ zg3Ao!axuAN$)%TElE!7saxC)k`=#Y&pH!=X><21;c!0;N5GiI)GkeOimse(XlQcEE%mQ+HmOXysnNPb=pk2j&5h6RUrfB*T9h$hg(NX5#h79AGjdAp5v^qNRIGrkbXBp3_$ z>w5%DEBK+rN7xgXeDs{dxF6t(m<6P5&e>N@@$Kb6nk($`K$%KVVeNQRf<%Qop2nw5iB}t^;J%H$N`y#2LlQHIM zOvZar7?5FA6;E>}I9M-B3w1bs| z*L9WARqLrZ4P?|vMiqNlT++k|eq?K1N+i0$#F&@fD!Kf*QCacRn)H)rN?p}KzEld+ z8Pflh;nV%nRZLLq|0u~O{IkSy15Jbp?j}w4ZwR>_aTbuS=eQnmTs4jC4ia|U>RlY2 z!8`PYV2_a1)_=hL*?()Q`N^4LVOn!_?$6RT6FhagKF;ECFRJX^pILU`<$a`&Q+S-l z>GqLs?d)UumS#TGr20>O z=@fb1gEs)HZQj}o|Gq5S1K2ZwpTAokE6JRDL8a(zfu%Kf1(MH8{pAn+YQOE+|EzPv z{>6Q$A$>Oo=OpR@I~{P3^aArZCe&`L={{7!^6koeP60VlPT#_;LXPkl_%9ts-IMzRDo0FzA^S(?v0 zQYlguQXQm*NF_<(lM%wR9aPY!4C>toNtNDn{~`>}I9$Pe>6YJB#pa=b_R-r6IR3s` zL4|K65C3r!=Epz>D<_%nbG9u|x>K#Dii)BR-CVK(U|X8%GQKa9Nq47K4w&6+2*0kU z5cWT|J^DSxZu|BQ4&`;c3L}|~t*`@Fm}(G=HZy1TWa;%-0#W2X3A#H~=>Wa3nUkoj zUV=)r7bWVmYF%N*;h@8`?tD|Zrm*&q zBnj#us9>P5U$R56rRFpEr|aU5~0|z>}|+q8z86 zq(wBah(;EnmIR=y;5D*{aJ7g=7NLemFgllt7-j8b+G~D!FSuggRtyd>=g(pIEbj|f zG`VL;%~7Y?HGnqq3**{T8C`a})l{IS1a&BdZ|j=h@|yZB_Hl-u zUV>5vDlO=QEo+0TjyIvOX<*>;s|a{aNOJgJ3Q;r{s3l~SC1!!)RM{$@DZZzKd3z|9 zNa&o=Vo-$68lAE*X`zg6Ej>Oe3fg)>qZbSYuC@S@2yP z*I^crH?CZjRzn82%yRV_8%T4N`{t%9&ed>sAk9_tAAvNQ4xG6K(xlb2{(&^<1Cn-e zAgyd^(*tRon%Dsewlw_oajZagd<-7=XgA2*9swPWf9q!XhU-(n zD{mLoi)?ya88NwMo1M<-#+Uf-HLJz+TFm{{lbSn)$HCR&jh6cl+%}VClenQ0;5}9= z0`rclD889m8fvV5wV0nzK(LCk&{N~EoG9>LS}i^oLIHuz@?xLQVQ#C%oWR^_aeFkA zcXhF5wOH$p|FpH^CcmaK&gbcInX3zb?bv2s&Jt5p-z7Zu*N)%X3DzFWTEMe`Sa)k$ zx*y#Yd<1#2=7SEaYe!6zs{c<~ME|Y_{Mg#D0UH2ZU2QZl^4js_NBz}Rt%hnS*#zkw zBT~(5R8usgK?8md8`m9S+pt*iG~k~RbFnfgMvq6%B}T(=AR&vS%3`I!Xav!IMq3cg zGa5y-k5O5yv{QMXuW2NiVYc|awp(i&qH zWBB$lQt!Ht#496!?*Bo$U9iVD-=O_f3kBdoz4|PU0>_n(itXfu`EJSx%%VDMirzo2 z7iO~UuNA?QKPr1%2Hj6(;P!k^ujn2gya{@wjo+c86_jGjqzO_*fz#4X(BO{U$x}!A z0>eAp8qCm4c6xvmI6FK&kp8N!QI@GQQx-<#fw)Fcl7vZ1&l{aEI&Pt~ir}IyztU*k zvo{h`|2~dS{WlO_yc%LV-Qv}El57rq`k$mQlo5IhNhw#zD=e>(=U84doTpk|Ba=#U zL-Ih0W7PxsYW9=Ip8fz_opJE|&_v>`G$f2Sh3khXFl&B?on7UF;F{@bgn z*__Z`AgyAOKO0CBWefX4AWd3E>t9V{MJ_{vxhvZ}gemY!jHBv7e)Tlt-+6y;7g+Il zvwv^T-z=x&pf3i%o8a`t+ug(e<*4>%z~;-ddVk|xo?2JK>7(^)scO*h-Y%7|Zjray z_T z9S`sf_9q@ocj;FeFdz5g88*VR0^xj|X0!=5Foo#w*-uhMsAU&mcn!C*%9`xn+E*?B z6^2ZGzQ6Zt)>=yxE-RDEDOYGCl*naJ0(;p5pc5UJU?aRCI>6MVIe=*vM$%9b)tcJ4 z?`{Iu?oN1qDsoIQm^39Bo&^gVU}4k`ZtnPnRrERSHw)`W3XG*l31g|v!xs|J_R5WK z!oZZ30Wm{~3iOLl%+o6}#k;$Ig7{8Y+yEizTKv;1P0!$$seAYl>x_Kx8lAacgN%Mio1IxdyiMmahll9mVYGWMqvBj<85QR;&8Rq+ zDMq7+b}%Z=Ws*^GF54Lu=Q6=)0?{@`#kq_#D$Zq$QE@J#8gLV2*1^)u->1-s`PpW}bfs}r$AKRLw?7s_2r0l;7xG?1(2>3hU`j-PZ z{v}fXr2wzuk{bA2wAwjDszAzi!uv__B5G%zR7h=7XCJ91QaMs#QoW@3@>FM*RD{pc zqS0OA40`Bwv~omZ(CdNJU9? zkcyE?f(lMP1A2}ksWSN-_la07d~RYFWmNb|lHG^fl@T5u@B=}u2Pr5|P`?CNS{bL6 zl#{p#S=*6FU!wL_MFp2tRu$edvBawr%eB{nB^Fr5OCvWQ$IZMb}IoEy1a@IRgYm{S+`dFiW15Nl?Kq7Fc zD)3$41x5wK+^_4eqBntzvSidtMgs;K<1>;8&$M$G8I=t4gGuy%nEMX+DvPE4SkPE5 z9DD2$Td>9+dk~{X1&sxbs2F=h#CR`gz!pR_Aw;8s#vXgb77G{)5WVP$J?K?qkNrhZ zgEcCW|1`A`dEs~|7;gsgTe;=TUcv015nX`sjSZ>``1tgCZBVDttY_OE*I%K0l(L{Q7Sv@# zpLCIr8_8@jiAqSM#s*e$)*?%L+^HoMk|;?cwNDUTZzUD8qW~!-CY+fM}>+P$DSknd?+a>YPAx zN-f*w?WVKkEEbf_g4CaZ=;>c5rO~XdvrF>0JL(I?C4tBtH>}bX!-*Xv^5h30tr0!< zt!rDG&Ve+P8bFqcjb;VSi5U}FYGXm|EU3hY#`*=-1qF3X)wY!y&HUfV_SlnDNG&X= zl?9a2)fn@3SU$mr35>=6?-iVIU>Vze(X{fZH zo}xl(Fq%mc5rCyTcToi>XF(M#sL_ayF{0y1R7#>U5;Ymo)St-rp{2@FF^Nh@)NDk* z9l+{jM*#l5kVHumwHVROdTX=r&GjnfdpYvmYBYUyGKY7UxXhK$f(lqrn-Lx97gVgP zBU;c?*Qx;8jph@?#Ug-*UQ&*7Sx_De>M)}1HV`81+@PRGjwEU1bFl^RjYJiqz6X{-fp$%4v^=4PL!IG|aMH04I~fLYtF zB6t?lbVU|=#q9lpx zjA+g8S<*rtD9tBP0g393Xq1(-B}>XBQ67mJjA-9QtZtRlwNDZx${|ss5smSjC=-F0 zKDY`%#79Q+x%L~jJq3(un&>)a&W1hGgt*IbT1^(K$!0YzMzpfr&Wfh@t5u>-1yAjg zAIzPM=#;)}dh28*>L8IvqBbL%qxUwe$?7<(eZMssZU+rk5R?ThzDkbTsagzf%n)kq zf8$3MMVt65_ZisLvu;|9bb}E|q$l_~OSd5ekaVS_W%s(=5E4NNqSVsG_FHJb`SzRZ z@J64ow8R#YKg-gc@MV(juwNPICEaFe8LuVXVrdz6CEaA{gryrCz5Q0&uMA~EUvBAA z`z^NLLi?4WL+J7y-qN|2PFOl&=`8#0MDI&Jw_D%g()Qb8zfJaA2gf4x4VD&XBGpQBSK4E*R7 zQQpUEpu~v(K`hC;nUuOEc^#8=mb`+=HcM7mUiF|jMrL^}In44}@({~w$-OKuge?_q zYk4iXk>#~yKg(;$EXxapkh}{gX%j?WB>5?mqE3>0lgTzq&S8>)FHZ4TUg)Y2-(z_# zdA;SeWR>OBxl+m-Yk4g>LX$l3I$WM{uuIK+NUQ%2e80=E`II&951mBIE`aNXZ6!nG zCK}fxYY-E?A<8=7muhXf>mCnDx2Wg(=szKtXr8pPB?J?#6xahHSe?P@L$Ef3T^53g zrAXfL5Uki>$A@5IaYC02!P*SAa|k9DE_AsenCsP5LonC1U06Hz+iQ702P`H?>%Esk z)WrsyLF$Nb#qS9hH-_lj40d@4#wl~k`)3GNY`QQ!fKefa0AOpUKV$pTJN#a(oz|Y# zuGa?*96sl`%my^PGQzzPfl326wyol( z3K^RGlOC>J&wVB=<7Q1|U3QYS5%8^R8rzN6fymIyX@b>VC* zt!qSC)L>!oJ68b0jT9`-mxCPV<-bbu)mVR52KO%L9wr7-42bsL^^1qWeNLE@o2-@6 zaR2k=eo@i2_D$xmr)%vbJ4(p7X#U4N==hSmGcTH_FMf+Il&Pbb>8bkZZCRLKw`+=9 z3poFP6m&uN6sQZ$g6C3p6CZP-7L9zArR)Yi%2IYc9@8~Mpwh;{I!#J>+i~qIDrGGN zLa_-dBPUgk~|Ys$PQKgMm%O!4b_DUgg|~@J^BWAylpcB)%3F- zA8}t+78s|txZ9_+^&q-KuKCCBj+`P>Bi;K?A}K*4Ue@2kkJNchg8a~e{FkIUzGO)^ z9In-6kw{G^cu{J1E9r|Pw4_c=x*O*@4EfcECZF)>>O&_2$QPyLg*;V6_llF&g%|Q9 zf9>>AshL~qB7Z~#7qv)OP-qD~^eEEMm!EzSPA1IB$Izk~(cCvC_*F#@J#8_6V{QsL z%0{7d=bjF`3)(vEj5xXI-C_RjrzAR))9N-7wW~n<%S4~DG5K`(P>7&~M5^X+)|yIryW5QEB_2I$B2hC- z$~B@v%9Bh$M8}NpX_tbB;IhVjJ+idPp~`my3uOmK6{TP z-M@#HR7s*L5)~TJiB?h$ODZQ(1&NYI)Mpv??}$sZq*4-T^^EBoS|pEqK2-m0WXW*k!n)joZT`Qy0#w3 z&W}h`IZTP#SQQu)epFf@nu{r&lyuSH42G`K1+p0Y3DGB`w4^4M)Xb9dHI?#)DNiv& zfA(T+eSy&&?PPec7SzCk8d*@G5w(2G+QyQojzsk&N*d87Pm$=r10=|M9W5$0%y`Sb z2eVf)dlj>n7}1utnK79!hLn@2f<&c8RQ0yh5wq^^F47j2fyTFP)Xy*fz_hg}_g%2R z)3moAmS);VTnJvAW5pRoP0|W?lV{u%r7a47-zUwq{~?qaP5XxnVy68m02Xo9+ziwH z^2V@fBa}$EV-=z;r;c0Pjh}PJF2?N}dX|gFC_;CpRS$ijdPpO#AZr+0Jp?a|%A12l zbzvLSH`j3Q5AG$vf63YtS_VF&Pc_oc7n0Q(Go*fS zO;JP5kjDLMhCYB#pfx3HE^0oac>n4*yk~|a>?F(yEy)T0&XL^7-TythZ*s!?94T_! zbI|g6a;uQMR9m&l_CbA;jB&*t_Beh<8cH_a$F`^eR#GVm_vqqlmY)grY+n%e3i9L zIksJfnIohViqHyum9<^JO39sq`vw68kxDiGy2a=|-fcMjYZ~Gh1qbn)Z*>|oq1Uh0 z&Q>|#I_nd~vHAQo3a^E)iyq^WXyB@!O;)#64?!D*F&=g*wVj8BXKGto?DTuu>$Mfg z&vWY+N>}NNwqvAeJ5yu&cyq3I=hh{{M}xG3^C#PNmC@|4q%E^(j(b z8o)~<44ZjVUUu5M3|HbXJy<~nxL$598+!8&ni&=&Z(QIQKd*h0SGWPgOc(IdS zf1HmzLKC_2%b$8S3H`f5!>Q+`=sfSk>(Ko1bEJJZ`WHR7sTUICqYfu8n+0w9)3`5@ zPn@t8qw&=!fmo>zK}vq9_AY?)6+)6K%rprIGg*^h z73C-P}7^Xh*U} znhv7ZguzGU?4TrL#{JwBX8|#%M72{F|uOtlMBeGUavGkm7DBvZ&#oCD@0Gq`z{k6Fn9a51gPXSW<@zW$H>e-M8!C5NHD^fwunC z77B?4+I-AGK%CD<$V)FL468!)EcC@T?J6x)Khp+3(+(%4`O&@;4Ly+P7Wz~FnvloL z9giC=UPYDzl^tZ&^4vz7RwJ-3YWaO~mTGE9K#M{=Q-F zH?hRftrq4zDbf$F$1FAU=NJ(s_aAEtI=0p*BIWHdsI_)T9Y(oItf-VrUM}#-{0++~ zM@kXnqy|~wv#UEJo)zQY)h>*pca(l~F5$oRHs;#uN<_LXtDd$za?61mSSAAxHWV_ zUg7U4TCCAJEm~X*$$7_K1@T3rMTt4g2Z){H{5=ipPrc`Gq%BQ-UMf~(YkzLh+*$Yu zFG^pA^(KXh5cIvktmz+C%B?JgCK_K=U&oaaK4O0{3(^KG1Cjd-Or$WYFXRQW1BG}M-4m?TwKk;ppG*k7bx+}gV zoTa>ZT=>!s0TOZ>2ivQ4Wy9%pE{fCw9N|sw#nYv<}S+jyx`8SCYcBqF$&GLhn z4vpwRJ=u`*w&FTw1Bn_*RA)rbzu;KvREV;)4cV>-1XFlXVJy%oC$+UrLRLFfOUv{g zMQ|a#_>yW#Fu) zI-RrV+{r}DJ&oXfm?E4b7(7 zT)a_M#%Xm)8}Z#UG%q?(Un)&d46Mwd3 zOB-p*Hv~%;MIBGU%cG$>#d%%2Qp0;$+K7hX?_Uw{)>DaCV1Se!K`GK#EZ>SAy@aAG zwP=4A_kVq6*Ppzl&Fs9(eHC?cY2!_2uM8h=M`qV&aViL79PIY8meH$0tX;4K5p~L& zD8_7ayer|Cqps&0VEy@XKGYUc?QvD=*=MM7udEkQ*YK*;iyH%#VO44+zj+cy@#U16 z9DJr%s&P-P&>!8@!BnaYDePI43XoH&5kJ@tDiUVm#*Xu>_9^K9=G!8;@Zvwj&ur0HMBU#(A|gHy*}mDIhwdgW~EsT8WC) zySgY%YX#AMM)W3$ETq)3x;An@Vq)}E~F^M2B^nnY^O0A^Lt-7sPT^oto2q9-yZZjyv_xBND+gf2YvqrBo+Iu^PxDv3{21XRLJJ z1jI_qUmA&(A}cIt=hEB{Zdjo4jRM!fXc=}t2d|Gl%iw+{jd$Mle`X&1v>fyc@0zR& zTU+8h`1oCxG7tV`D5N>BPFnNd?3y%5F>W5bDLP% zXofwc1evnOT7z%SaJU-v`AX6otytD*Gtjwb>uA&(U)Y>?$ zf*ri#z8GcXx3#|vC+^E6oJ{`Y&Ie137F;Tv7Q-iU)vaN*HhS~yV;6?4CKpyI)#9I& zCR-kOl*My|_7g7Z%o@Fug8V4o3$2R_WkRe{>Oef+DLiirA%&)%SpE#=3l^Q?OCIq( zARi-}AzIGu*NF@`rJB$JhIHlNsa1oCt=l8{JGsB}tblu0e&#(GX=^{c&dcp6Z`Pfg z4TS_TyBMzfBalsWk9E%reC4%*)6K%uPRC&1Z$?(XSuNEs%$8EU{STLFqTRS)T)a30 z;hFY|q{s;{u+D4$?Dg!G3OnBs8ft)Q;Iu=s>rpVK^XA$?n_$I zewv(vYLt!5H5|YOhkVEgw_+TH5w{v!{+}kRKN7&NFe)DLHHy2nvUb6(hYr+?HA7`| zUDNF_pF9@u33HP6wb(%0F{A4D1a{FQ5ZzagK>Uq%Ml;ZXF&(msl1V*KHS7%NxlgTV zbG1{h$d&;!P2XOw2<+Ut4my-bR>NY4=5V`oXfA#worm8X{O02~7rzDg%?oT4VD3f! z3BF#wJTqTA{U7tSQxAOIbpGEZFO#-Yrh!6Djum<=-mLG9l2D0>s>k=MpF-Hb__G|1+?pf3|dKd?V7H8`rz8B+|dC>4g( zog#xdI`Z2J{pvaj$^j5;xC7B|1_r^RuBzhDal3M~v>vjJ9EQ|Q5&2lB#OoT6_B~Ak z8z~pW3K=O42!i%@9H<$6CR|}Xay1#v*VwUoq3B@|eVs6oquk+aijMDyf^d%`D#=hvSk%vjMDo2R zD@B$s9;{wj9vNe(VVz0;EJQr2uO7MpMaet>!d6+<3|)XDO@Ep$G=IX;)btPt0>s_d zw=C}7v*>|-*W1w`oU6J_4=o`i%6jq+gv?LiyiQZlbK^3Mc5p{OM>|8e2GD=hEhz+K$Oibp>Vl;i8VL(TAX< z4k0^KZCqRlu*%2F&a{Euj~+m545sdr>?2^Ur>JB8Lw+rOoKTox@4Nm}ai#SgrJ-fX z@h>Jf)Eea^B!nO!oR)h}7|kOq5Dy72)s8Cacv{bYQE58^O0-*@{;GW_dzC#y(;HhtIuEMviIwxq)8CC_r+Opolxn98_11p zFIkHNqCpp5DSXIa6q}|`L4lz$$HrEAJ`iWgImsz4W>L;^te@Y~YgKL1K4hSrx>t)I zN}Erj-<#3zO)#IvFo&Ue@*xvs42J8rdGfKxfz4{j%FT=Mig^$7;{ErPtRh)dqUtm0 z0G$^%inMm`lzH(SU{QU_d)R~X*RBR}%4;Z+iLjdmPllRDX2G{<(d|OH=12%!9bt49 zeEbOQ2saCsc8kj8sIIHJ;%(Bfd=3!@CMxxk9AvA06GPpEIXPzAZh0Zk8F;$5pgJk9 zl=ds5U7Ic&hz4d}HrRY0Cmv|Bis!5%6^|D5aD!ld)vw!MlDZ@y@rV-!a^fo^T9683 zMbSRhCgymk@RAhv8fPA%CcPTn$M$!wD_7Vf5Z0M zGn5h8cF*zg?$Bx`ujEcm>j`4iq~1A+x_uAgR==e0f(5~@tkM0!TWl2&{KyesmFg)h zMBDsV%P0!U=#AgnOJxQpDy}hjWost^+XrkX>T2S%@blue;CUBh<6x+^`dcBBku-KF zbdt*Sgm479y{Mb93$&oJ;XTUPxoD7ta1NTt1*Xn{9bW~w>0Y=ez8~?#)YL@?-_dtshEYc-UkN; z*89n4&YP))zM-x~t#?1sB+V6DwR_;SbQ6uWE=OCJ@+uH;S>L%kcjQ1qz1ZOr&US}g zRx3aM#VFrf0m_iXH-Rl#E6Hm3Wq$uce9Zpxj$5^aoBmnqGf33}VZnp*fObj`V#`t~ z2xWUWSu<6S0jNg}mP`lWWpw7GLcvy-2onfVLw9c(3doZyH`) zOFD8~5-qI=7+-ANbDjF?i1_B(=K!8R38oztW2@yVWiA!xQWl)&?`Dk4Tur&YP|EeW z&Q0oD<;t=iwAUoQ98;wRZVi?0 z!$*UL$UAE9+KwFJF|ad#KOR&WF-R;5W)t=Oo&%5|0kr@spV;}Bs^$MMZsxHneoR0>@yux;34^eeqpP;|w71r2A zii6D9>oRZm74ddVv89z;rE@X*BYK5Hho>3Wv4+}-C^N1ldW9=@CKJxg)xPFpy6)IY z^9obOAcrHz=U1c^0ps4yWV}+O8Fi{pe@Mn3J|T_q2189DsyANYt(~L-Io0jF!s(LP zgjtJil)x(-B=0esS2$MQ_6^+n7N|Mu71mS;B6Ytr*3>q|y}|-?8`@h1Gf@g-rz(G!$Hb>@GapTUz?$# zz?-GLtNNI{7oXu+&JQPq=h>`C$;8tmRK;Qm!_`iEP5>@@*bh2@-!l8;|~} zRe9F;yfmDZD0jefGJZYVg%y_PlFj!|vwcfSDfshw}!}8M6FAhjmFO#hi0Tt>N{b< zjPyRHF?%m+koMfbv@SRxS0-r4 zoASQfHMVoR|M9^zO)2JUWl%!Q5}`7hF%|)*h^ zWy%tQtO}gB63MgXuV_HG7vyF^8TaQ^C;lOx0}FX_3ReM((3<2jE%W;{FRxK1DyfCC z1?HcqhEx(4Lij2>t*)14yK$*xfV!m2wRXLZV}GLIANE4}G506W6>N2p2tQFjP? z_>I_rM0K)`Ya0~)Qh$p$lY9`^MC7q!u&mqnX!Fdy@}V8(tnurdb?_p4kME5CkgIAS znRCFKWQG^Rs4kE0o$(&t7jKj|XNAy@BYOY7_>M!Y0Rk0^%iE<@P*RY!a--A znTK6>kqDJL@(pn^DenNiAdlti5&+j=Gc5t!ZpGEgtT!n4(^OLs&kw)U|f?#HTR|%q$eK`xSl=6mx4;O%I1qY)79)PzpL9|Gx7VScR z_fZnMu(sH={OcpsMk+#c@=RmwvNs5G_>BBuS;fjkakNpiU)U4HG^2R^;+`lL8^zs~ zJy9HC%3VF6CyINF;@`(O^^b?NTTW$LnlLx`Gjs2BTj4qwZu;Co``1mnUlFB?&KjR2 z2u$0YgT7h9y4xe0OL6e)8D`kqzD^}x@i0~5CJ>dVb*H@54YlASPS#x-dhH7;#y+BAB|>EO+gr@UvRfMCjb)obK#0$B)iH`-8T5$8` zWI;UITVmwf@t4N*jmeZ`?s-ht>HM?F<|od6e}?>z={z@2?OHN5#T7O?D_Yno_R)Fe=@WBb)A!KJ*T)7fu$k?wBX zL1K?M$`v$YqM=SCD%_kAhT5N~aI;Rby1w38XKu_^ zxtj*nyFajndUx$3dUx(LXbf{sDRMaSl=qPo5J=+RS4esIjy<^xcjR@gl*FWDnj|hT z)Hy_jB~faqqlgMi;ux#zJ9WysP2)OxE6cSJbD1PCl28(v4*#FHk&^^BI#d$h94OwB zJ+2F{;Z3AhTT~KmU*tU*_5xkI7h4Woesv0Y@8z;hGY2$zrjHXq!$HQW_PGk7W(GEJ zoR$SY;%nS-T9yn%Nh!;Qr=2#FHU!WG*?QaopK}n!9#Y)}CGhulu8}YmHy24CX(5sE zX7KzX4KDp%!k;$8z_kuxuE}4W77S)u1bY4kiKw~rv){p(aNUx`u$6vieLMi$Sr>g$ z-YSUsGmlLV7)7E-ip?yDTdPNkn~mb8eR>KN*VOHNT*`J(PZX1l;%&$;K9?H5pqW0B zfyMMSP~!K~>lqUVt9+g1fIT#Yx;rMiY2)JWj_+ zSSkOi{nfz3yxwT2(L{xLzQj<+5*6nCJUz0M^18Q3Yr{d7Yg6XZwy3LFS zpg7Dnr25w(vb#UecT?9(JdZ;(buMefO&#O{Zgv}vI-=Pw;MVpGIw|l`S~c4Elln=W z2H#pF=RXJa%12GRR=7=hkAWrMN9F6PaL*f3H{HWb=j2N8RMe4SL#n^*5$d{f^u@lD z!Iss-b6pzj+fpW%Eqiz77seu8mhsH5Y)g4Bt_ddPq!P@1;)`-xa=B#9k%%Cd(VJo= zq6`+;`gkwyr}7G&0Cww^w%$~H85=$83z<&GsE@2yny`<&Tp?i}Ia(ocA31zIVRDH+@}Pskb?<%TR%mv_M{bPvxJ3!) zBj>7XRv$U85I*v)eR}01|6viFwI~nyX8Xi36z6(h{L^54G~ghss~d+V=CSvA94>SJB0YOl#Y7j{vP{=^$YvXwiQb zvt^q^YDNsv^V;?ye$5TGw*A2#Y9HDz#t^`03^DsLtr6` zlyoJ&##MeQewafg|_96bP7GBv; ziVL)G;@Ubcm@ddG5S6A2hZLh~)54jOFKCg|!U2(*m#Br$_hmzLx}qb}(fGbQ%Cwqu zQ5Cd8wQ%=Gv}Po69_E-x&6%|@OGiBMu5m5A4xgWhXyFgwBcg>K#=f`~-l*PMJ=-8C zhATG`wD$3;c3+|v$}2qSn%E(Yx=wE~La)kNq6*_0f#{N7Gw5X~swiqHdU;8x{H5sSy;fYHm*1?>lU_bH1XY_}ZvKx*i=19=9I1JUdbzD%Gt^DH zV%9D_>E-PYY0avaj~o@LIkR4t=@^npFDGNl8_~<-z(+(ci%~&bFPD`Lq<6f(phvyz z-1V>O<#1_~^s29yt3M5|pFuAtqmJ}Bft&%(c;-E92hqds>q?v*Y%HC(h3ce4izPP5 z>bnQB`0*EZ*bZCS8kAv&tw5RvV;mYx;$4+Zj}bLVKYz`tRfBupVf$hw*5tO#RF(2p zQzb5wmZa^l%|949963JEBdi93xbZ2nFn7N+fvj%atq|c3THf;x+kuWd|1@g*j;iIx zns{FiTdMFr(L%!u9#G6+rvt0MAYCOsXn^neBdF%<6pCfeOI*hWv~Y~ z5!ye!%7!K?<2e0@cdzW>trb|4Q*gD1oW4u2hxZRe4o8l+0fp7T99}6{U_skDB&u54$<;e0yk>%o%r_?{5^oXb(>xs!Tb1sKRZG(Kj^a|B=ZaN_CLw z!5;p=q(5#CL%?6e9`-}UaeMd?0kw?=x9r%XJ$#z~U)aMflcb99fbf_sQDm@(3sB8c z?BP$$n8QQmFC|j>V>uQVL@I+;=_yiKsR*U-_QW*{oBazA@;KS*rR&Wm-lG9D)1(lZQ2%x@t8BxH@^SA@H11jS@E&)f~ z1wHGM7MxOz7T|YFuwptETdF+FC~m^FS3X7V66S(4E@zRmPD-B(Hf`%vIqb{-uJz75 zhOEV=dSgXLqU)VE3q^HNcroorQiT`MF5TU{U9jG{Evdvz&@tRY@9mz@=F3Q>GSQ@S zljRP__JqpiwIxTM@;;UVg62MYAGy0{Kw5L}D`Rs9szZ-- z(S??)oVmiyz56>B_}gx2%{{Jom8wBfEQ<_J6>F?~;~Q&!QWtUwigk&r{fg%T&*Ad7*kD?(-yBTX2^} zKC$?ZfSm|gk)BDhw=GJ0B)bnMQvK3)?~$xexU|)Mvam<3(%E9BukFcY?U1-!)-Hm# z%i8gn7B^G1cP@>LG=KYTj%v9NZgl{F8%rYzM4^7t((z!1d07Rt$K@~ z-W)*r=yw{Ye4mfY37ah!I3mTc`GRd zrbj9Kc9&VS)SdF?i$|A>3~+KpjFl%xa98Hw>MsSqSiBMKPd+9nSN6DDEA8~XHX`M< zXq(iic7c+4bz5XMs@Rx(>J=eHNi6C~?WT+mk#9f4D(O*ZmHIAfRZ^(=+2TSz=3?k9z+;-O`91Oc-l{c~=p3g=j}inq`u%zv zL86pSktP!)O6lC^Sc1Z1>gfbU#(#psgGwPmqLh_7+rc#iJ=|?_(66SH76R)4IXO%9 zQd%n7F!K&k9&zI;20-pt$Q(daMu6M^2zA$Se}zK0;TkmaTtf3yp1wSeBQ%##C%7U& zqk6uRLc)5!iHvyAWOoiKA4LqV;Q_3gS}71W2@J0OS=!NOSJi4g5LKa7g%x|V`5T5} zUyy%}4@27=>e$Vp+mCPBlWs#Tcr8;{FSrHPAr&8wh*Dqp3-07wVY2By+5d?#H1CmS40jV0HinZqHxC=bC8P=)!$^X{#&9e_VPiOe zps+FQL{M*xVXvPv7{euh^hHnk=dGGp%2m@#bSNp6Pd zffp&zTEb3$3x$M@VNH0_-Wo&J&VR}n-ucNlhQa+|4EN^tWDF74e1UrKl=sW8?wknt zi%`5T=L=vXUq0?A!m3(^IWJa?bGk(&(-Zn*r+4+pBm8z3Cav(>oicZ&-}d;J10iad-w(_w6k1c#G#A7oa!?w(IX>yVB#*5FXu@8~pGrn2U0{XHVJ!~xP zc?P#=0II$WpO9D1Q{FvzTgl8zB49RR6Kt~ZI z)}t*1XdppiJ=#)$wj)TaM_UZg`UHvfXv+cGhc$}zhy;YSpLSIfhV_`Up4cFm)Wk;o z;6`;Z4TaQ96^L%|zo~otdgJ!j-#d$<@DdIemvJmeE?{@=M-K2KsLxVRc-N zTN!qFVq@}L)v#Z#uX$r~&9Zu{5qTmq49oY;n^@_CnlU2hWb=5qa_(_rb2%ts?nS;%gvwZro|%HPwa zj!ip;(_kHcxzc~;j$px&$S(yRP;|N^$&pnY!*A!=6HHtm_Up zY!R`st}C*7KNLq7?YbPxxTmD#v z15x3wyR(Fn*^?ZGyY4*8HG;Wk8F}XxHs3Mc7ev9$P0;H)++^Cb@vT1TjpWIdn^);iP= zq`b=&BIA>DU!xTwfn=xAj7Gg&CGRpwv6e2Ape*y5`zVCpjtu;39-)=w!ugcV*p3Q9 zbEE{@ck234C))#>C(vV>Cz~F{K4d?3TcFstff|p_0O%QWQBFY zoMQ0=T4ZFi$vN3(^D^B?Vtnj#rTrK8fvMwXoN zPLrTHSV>x-F|_(vjdIYyJM%@=)IgnV-q_4HOecnmNF@g8`nG{(i6JUyDC-zfi2*8y z0F5J+7@lw{qThj38UdmKs-G!UN|_gdP$4z^#+RH>3k_fc7SQ}$0GI$d#h3D)&@FM? zf0o|JNmE(%scUJ=s*uYy_ObVg`gYT_MjvIlwqvev;}5aA{_~6QgEibh2pd_hF8$cG zE<8G6tYx`wWv;MLyeVYkIp$K~=qSRuVy1VAHpC8=tOGmWqOPd)`yf2#C{n1}rLJhx zZ6dDd8Yv)<-}y(1Cg58rAh@9vN@#pC-RGEmt;kh2^)3)pe(a z_!0SibS(>fV+}1ZtW0kmK@QJmuCV+XE!WM=W%7e7?|H8M;XEh5QWcTP?<~o0+C^7R zq{{D*$tpiWuyZ1Va-i3ng9W&$2wrIG21v$YSe5dnzH z&9!p+y(ccKnm;&RnH$SmDmN&wd?MhDm0DMngT z+m0XKwf-!N*0^4+&SlN)S__TaJt0@;TAir2-63$T&NqFmLx8&0s0@%9X)Jg^P{M1iw9(?RjyYn+e9}inEO3Sf9dIDBP;~|K(h9Xf$yC zKm+l3z+5*#S{|R{9K4bEBd#n4Mt>@4D@6B$IOf-YE_XycsM~~R$_0WJZmvy zIPfhXl?*YhM)h5uFsMUIi-A@rmAJ%a1HDKp7ubUL2Ep`pt~l#+x<}`j5-8d^t-(X6 z8*g{HAelk0Pay;-pl`93Lo=aArj z%2Gtmw;F0oqQde%*9ts@1%~BbX1Nxs+teY-$$wAFwH9;95as$|N6YmzbA|h(kLCJ! zRcW{!%~8QEWv;l}XKs|@XrQCixUZKmSKM3PwhHEo4@dz)*Ilh=l5oUY8H{(`Ns}r5 zp~_?21UAOku|>usbhaBeh0QJRy38Bvx)lxk`zqRci7q@-)WveV4#i4LZlS1*MgscG zP!|vt?z$N@B$>tn!(I2FCadhxkpJ!$Jjj={Rq6w=la z>YUC<&_?HqBSFW&#r4rJg@osdyJ{{8T)M2YHq$!8bH#7XX3j}4KX<&zCO+Fh|8(N7NJn~N;tylbCCO{AAj z+C-uz;~VDhd|=&WTc3##L#OE}rIh!r@EJY%RB*X;4Q@DELEU+n!R;+qGjoL*UDk4a z&_{DA!#e&^oifdGcQgLnf;Y#%&vg7#Ii?*M+IvGt!;z=F2c&>N$XD+#vcmY6-lkJ0 zvP~uAF5IT$EY}ZTsU*T}+Rk$IkF*H`L(e91%KMaga4zV_<#klB2FdxrO7VEr?|AP> zD6h$s_tmC&4!ZsE%gj7{-FSSE^V?2=>OjNI;$l;lI;9c6t+kntEz_||d@P|jj4-5n z;gD(%M($4p=Wncjv$yYt?}%nb&H-%+{@ntbR)c!mBgX@1zJS5EUM4P(qa zPe4U9&$KU<+_4`-#&1O6GJdH`Uc0VwAA@kdGY`JA6~412Y^?N`Eut-teWCr{n-3gZ z{w_N=_`ty{9qRwIpw)#RncVY(I}1M+V*S8DIfUyx8Cb#n2U?IyrfdcEWUX;e*0j8O zvdHI2Vx!AZ=ShXQAs&lZ8CD{5{@#^HvGldt1KSvp=38=;4TQtUqU8QM z_s}3d*QkD%H}$w%kYk{YNF|Y<3nJbkl|+2mM%ASOv`&_?4D>Lm#EM<)@&>6e0CEWg z600Va9Q1=RhSw=qTIxFG_;*YR%tu4z{B_DdD(Pn4$xrV1$6 z{*>jqow@3Oa&nkuxejEmusp7|TxT&?ST0qTYqfOw9A~+9VXm;8j<8(sf2sx%me=N% ztGj!dEcBGhO`W@lEAvL!u(v6u$P(r)AF6X#ZAn|gEL{g`;K=djs}vB3_Kr&^+Uv+d zShP3jrx&pLOvb~a9cj5rnJX;XQ!Ll->K^qvDW__?TCS~_D=gY=E!XqRB?C#8^>CKu z`f;%eDJ0P3+Dsc&-T!f-E!C=Z+^m)SJ*{q@eZGp8 z+?1 zZZp}r?ER`|5#$|T_1q1f&5d`;6}-wk_4w-5ugSuA_s!zpq0pzbFXi&jG5-_+*?4z0 z>dHJxcwUzujO+lP%x|*)wVOY6mJ?n*2Yn$CM4DF@-7%RgSU{+cj;jL|VmEjB><`k@OpL!m=RdVPIUH1BHLMRhPJ2{bzm2n~ zjFY1I7%gz{8v2+7J@m0qeyV>RT>bsv>TiX^>vH_aOGd@;LAmG&&{^76Rj-|(S>Bb4 zdZk{=hSjU@8$GGlEvJUG@GDdmpA=14P=-jV9+4ELkwdF63$4VNAdv$0GDQv2^+)HM z8?LGP1I?gB25HnUgEsZ+4|&&)FV{Jd=8{Bo!s*vLq!OKIP@U-cXnx1*PA9;u`o=BZ zQJrvQ9Wz$CDBOp~6h!)PS0#|CE1HSV@+lTRjT74(U>WD3e4PKqIOX596wF?m*9l@i zrR!F<+9k_q={cDfM|!)D_snmAPnc7-6o)bK1d$kaL*MCX`M&=sQq=z56UB43!2dqj z%c;bPpb^8ge#fpbJ8J2@b`eohc zrgPWmvPHdhQ9cNo`B;F*CO#J8v5}8SJT~yL7?1UQEWx8JfTd}oA2H@j;2jLvPiP$O zPJNU6ly^I!>M(*)a_DLzQ@5%rZIeFOmr(V2!BMdRgsQ>?I{<4Cs#+c_-2IVI{jUUD zDhL#ss|<)Y@E4!oA(aF$Di~1BAqZMT0Ri*~LE?o~PypRZka%Gg7(maqi-G7Zk19BT zDo7<3S7$9djUZT@9h2tSjFc|<^<$V^sdArMrCFle`NLi@D>T_BP&Bn9<#{_(JxLW0Q1GLFk|-w7^;q_aChEhs4+x^yY-r#DAo1Jh77W< zdrz}m`!ZL!n-4bBW<;Y;k@TAQA!o1HyZ-K@F)Z|_LnN9n8~t`W_KEhaXm5mo=9j4%8llSYg%>~LaZ8Zp?gg~Y}*Vmrh3 zCpM-L3BxY0*oa1~Xbj)>mRefakl*_!xqa<>)uXUR%r?|xM1?itE<@E571oGqLtR8v zSR*QTpj30nMpz?`v|I-=S6Cwo47CkWfkt3bLXF5YDH+k~G$LO+T{WU>AsT7(b?%4| zsT$EfLN$Vrl=p@Bo51}%im&G|Omj-y00`H+oFi+YIGmcru~o zgf^?kN_m3`EhDtWpt}-UN~rV7JF>PCLfedXWzrTC+HTMvp-JE@Noa>bKLV72hi8yi z6e5$DPJ=wfoQ2HUWzZShYfB3Vb$+w~P)@eg=4@hA@v8KMlqt|72M+C?UWt6&(<}6E zx&DB6y0DG;y<3kX=H&hSd%+()cmEcxV1QoGtk>d%}Mjz1~frO5gm7xIu8CK2Tyt zRrm2Lh`KX``~jH;KBGm?WYL*SY8}7mCJSU6zZHAZqH|Fez*_W`cpsEWjQ9FxGe}Gu zM!YQTkuRoH+5A^Os5=4Tp1+qEn6Xrf%G`=B%EgIe6l618N_6F5{_&V}j_^@4MqXI+ zuaW!xyIuvbLxzhsr@YS3dkRm_Jc|^2LD}LHk?{-u*UnfjBQblh234gYyn6aPQ)S-e zA(HTy^G+s}*hh|0t-GQ$C$h%$_V4Qd8$jhu;0MtVp8aqZ-a(Lf?k?D&2<=sZWP=40 z&hXmh($82v|C}jzhPBHhx2DKHcui;`joe}+tIk@WJck>*q2;=Vxx$U^Jd3$rnyambO4Sds#@xk>gDd5oVwqYivdN-LLL9BEK(3u(|JjohH8z2Qb$d<_gQN z$#UJrTw(d0`xpy+=GQd&jk8>%m@6#56Ag7FQDOP*Z>R#IOnw;fdp=`1w#CV>RJB~? zx1!|lX%+ITlU05sPkBFPBN^!RvuC=&(e?Mk3ULFO=>9DV39mPv@u=j&+}yXdv7lk# zkZaaAHcw>i);FEy9o5biD?Wo@FYA-X3dgqo96DZd)bk!D8d&J6k0PjZ6fNZbVj$aTq`h_GOT{3=UwfSW@fO9yXL50Q907DuxoYrK4UR*1iRXA zO94Tfp5B~oI#OgG-KoFwbTWSFmuYP}43{E_ByQBntj_hF@JlS$VCJ$mEpb=7_8Dta z5r!N!^o=C5b%93qg3;D2b0YY)UG3H60*av9KRQjAlC1zI`o@REe8s4e))`NMCc3Nr z6b`-7#8rG|j@Rf=COHYsxT}3aw!gMYvPi6&cH{Z+Xr_yS(43Ta`0|0>X*GZ?rxP8u zy9Yej-HKmjw7d9;+BHsRH$DKCGB3D2qbIoVjw0@`NRN5CaE}(=&#c!dK;NFhdRvvI zY9+jvwOIYBl>i^XSptSt#>X5yN~jNLE*?wxn1@FR`T@rc$CN=&_X;G@KM&= z^7&YdM>t6#D8XYcA4~C=!^bi_Ciqy6$80`U;4w=dCsrclMGEh7ppc1GOyK~hr0ST$ z2@Xl|D#M955hbYx;;<|vsYa&Sm}+7QeIqy?-VMvH8a)9R1;F^j;>xfL?>rU z=nZZxd6h=uZUm_^=vYEMYn4H_<(qn)gjN`I9YVVZEjQ>ggl38EW8=i2^B0M=+2o2H z2bSI}g@0B3vy&+VV6LI8RkY1K7jbhZ-uv0ODK#DfO?6<0~1#igt*+n}EjT1KcU56XR& z&~idmi2!|q&Rz&kt)3p(42ouRT{9XS^;zcsU-GN-2$kLAc?tD!2lXc zki@F0WdQ9*kc=g&Y5<+a;$^T?eFJC%QppmFD4j5|5<#-G(xHu=*dQ33-^R~|qM*=r zfz(VDNc>&j#WSQ0a!pjd=9VF_&V)93WBQr3l##f~jxy{o>OFZ(w}uNSU~3e+2f5R^NP+C+JHmP;3Id{MaVy3m=1j^wB<_eqGTtnSYRM^yJ7^;q_ zu*uzIs4+x^P45~#Y=qbC$wt@&PqSS6GFR9X4>r_hL^+exAWtkY^QzBK zqS;Srkf%1uAg^JuG+)D_OMgTTM~?MxDIl=gxAj0$${U5?AC{+10Yjr^PkGITEhg3z zaA37n$5X}^exSP6NvyNl5r!R3Y|Ls08@77+P(n1=SZGmZr*UwJq9f zYPCm65jK)?kAg_G+MSO8ca9wQeIVQbtsBPsDi=0V`{R8V`X2gG{|A18z~DzY-G=RH zLR|#$3Tdkdb)m)#LMsV%F-ZfV6@+%k59Bt9&~idOgYt_I6UzwgH0W^BmJ*7#XbDL| zO9;&}ecqAKVnW^cvH_t$lIH0Y&-CJ0R$bR?nKggWnYG@)69mKg03tgUO2_FJhzw<2vPp=AbL zlTeS)a)T~D+AU#K7-WG$WWlP^Anz$e=B-r@g5yq{-_{wVRS!VPJh@&VHsfv3F-LL= z6n83secYy?f9v#bmHw^NzZLqoT>qBo-%|ZsqJN9^Z&Lpj>fZwWo3DTK^lz^I&C$OJ z{hO_Sv-Gcsse8JJrF*)F0h>lc^;mgF_(Q&5{tDw7Kc@`?sdy1>PGk=5-`>z*ZEt@d zSpI4;*h?5Y-SU?f0lmMlS!}soOkneOF%7SLr&rVP0oZ!zHzNz5o_8ni-ks4mZHwWr zo^{&cJN2b-eekE?Y!jy8@8EioUX5vSaupDqfEw=8EaKeMvja4rZ>hnlE%mI^kJBW# zybWA$3p0B>szHb=>#U=Em9z@`!lmhw3t2i?3H-B8dukHvsobdA21#A9k@8dChL2=C z>vYoZ%lPNpm2Qpu{m!Y9e#vmwsqHPmmwwi1xCV80>aiHb`fDeJIE~iRmynX%u$O1~ zy?o+yh()&g+Isy>r0u|Ad>!VmDn`yXQN_q++E6~KRpp!5?80k9m4N~<+ zG2U;CE5;^G5yd#-h`3@bo+=Rd7b?aMO5iI-e@*&|u?CVM#aJFAYlcH`tN#{LjNg{#W?}@B>XZ({N7okKy zDzGaU_`CW&cYd_r6HNR4p2c+7A#AVH%}Bq$_qCSNn|}Z7o_N0xcqr2E!;0hmKKZ&x zzwfRDe!p*}Nx$FMM>5p!t3H^q-#_n)_4~5-3R~Lm=S%-)==a%kd)4o|YuIZ2zAuXX zySi%3yl7XQ#e%ZeU3H}r z_+530CjG7|M>5n^C&77UFwy1WU3HAIrCs%kbV-J;TC*)bhr;*nvDp9x0jdO2zNiJdeaAw-x=?N-=;kNHR_gcn2z_x?>KOEEU>AP2}9+!4U>J2(J zq+cPjH7YUt8p`jZ<}KxIx^B)3d-FD3!5vQatrojne4of(z7m-7uAJf|2Q2Qg(t$(Y zruzchbdk5|?$&}-TI;>8(rS&rO?UFEDy`VtbW4-euwj_9#jcY*uLn_Op@yiak`Prh z`k@KO=if$Lm7e#P2;^KxP*m74>_wiPH zMFpDFqw4-^)+*3&Q$s`Vi`d4)(A)0`KPJ23LE$$#_&)jaUlHSzp9#ZI924XGcT}vs z5#yt`#l_flPawwft0H3D@Suno`(m&S#JEFTjQ`LcQZZgC;>sY#mtIN}qkC_)H|q23 zr_pvl!gO!i{nV}Tc4vj!y))Ln=*CoiHb;_fO!Z@J3=u)QXW-;;9UFIo=*R|}=V7`x zx{vqGi|LJXM<)EYm1gQ{SM_vV604qym4po2a-_k6Is7LkN~BGBU6PD`m+9e86eOG4 z;GE0yDczb9OF~{Q`Pp~mqes^7y~RXg?*Ju2Rqdjuu2SBt^eVFt6yc=2PhYT+2vzIy zF>N=~o9}yDP3}WWYQB|siQchpE+2D1(}k!(AAvVVp7I`*0s=u?FZ=9ZVf%FMMjSxy zhDW%=GFi`_<+htChgz8fDr@`sTk#JjeTW-jFZJpzfh*63x%1^BGVzizdEs< zu4=?a+PX%ox^G$6kZz8Br|caZLY}{$WC|KT9sId%dT^NXron5v^#P|U#|JZwKB9-l zePr>Wk9TkisEpq!3xb*P3p`Ps>X}Jx*mTvP>Zt{qs?Em__TKaKM{jt9DI}nJIfCcg zbqPF%y&~V4W^pO+W(nDYBN3azH$$mmQT}n6_oVZAd{C;BCjX&vzAmy#)dG5)R0x** zqlo9esVXV)lClG;D@i5m4Z@aWynrBymmp3aw@c~vv%Gi*!Ym=IvD=`dHuJ9=g*DlV zWOKx3C?H%nyd1T15_t``=s$y4^+W$w2J4Z_wd`d*8-(kY(_46}<*Hz=a7$0LJBaGu zNNaJK<=T(A!Yv;?c@0dHC+_}O}AKOt0qzCWfUgmjPP+K0IsP@q$Tv6ky><_ZgGj~W&@ac-KB z23fA%m@6!#JVR|jlnDtQr03T%PpEf7DpxtEkmf&&T1`*5&`zWZ>E%7dkN8Vq?Hwwl zglXvA1I3kyi*RautwIoX`?`L@BAz|Gwj9`=Feg`ZUyF(OAAj+)*!X+@ z`e5;s!ohimj|1nXMZjV&3FZfRbFlb1;W@am^f!&eKJ5R?JNs^zKr?Vec{&pK$3RRd zs}ou#$>1>X3w%jWr4$?@Z6dUSw4Jtoe4|2(Dv{kY&=mw#0n}lj(F93XwHxRpg2X+w z8R#;Njn(nC8t7bt#M0b~bsjS|0n}_%YY~LV#KuEz9ryOmzLlraq?`#PP;|m1RR4$I zu-vSS#N{{6u*(q}ljFhr&?js*OMHU88Q~u`-^Q>j5F3+gU&DHw#f0Vi!`>|RRieUj zZa37UM1|!&(@@tF6_)$si`d4!HK>lr{{}<#Co0?zBdx##SYWt64mZ@+M7e%Z_uupV z?h~$MH@Hjq)U&;Cqq=|fO?3ac+B53es`08m`kWBNtWrSGbsy?Upp-X8ry=pKn{C)* zh>dmKReMp!6Q0S`b>|xPG-6|2ccfttRBXgF3JkRkQQ@xJ&`_%p74Eua4fXTW!i>J^ z;7sOMy=Xh-U9G+|(sdsh>O7*tUH8bIY~9@~Fx++58EO(yLDykW>iK^6)~j9DF+kC- zJ6eh`o8q8Eq;}n|@?vLj;D3+|5`0%*j#Hz`x4yhC zrFPbUF3U5}W26!z$~8~}L1H{kEVTs53^^95Q}{%Kn$T z(Ue=B@O^`8#=Vt9wR3tJZcdZsn#5e;W=%EJIYfnTF2gF zxo%{xuq0{>bqP^nNt7GvRH950aFLWmrUNo}PZo~lfQ-gfoc!-3`Fo1n*N_)e9XW0; zkT;D3UHfJiab@8s{e6Xqn{rzFA|TNy{o0EK5|7ev*PL=|hclGhaV&tdf~2Usxu>z$ zNE=*)uJ7r{+O@^#{QjOFpZEO|ZR>q}z9;14ZUUl&Qr@;0-`(Pa@`0ZJSY4#Lo~mZJ zp3i1vbUoqtyaekpSYu#JIh}FjRK||AO>n|kV`$W$+6HyWy2en?#~etDgNUB*uOc)L zP&#!z-%n3oQ~+o>2@3I8#z!nRx;F%h@mNA=2_B32Sc=CaAItDq$j5R#7VxnGkNNuO z&iCgrRizHo-V<==`*VOxcZjW$1LB(`v2GAduXdgED5KqA`2Af2Vq0eMU-N$WRi#z` zSL44DegmPZayVIS)l48%U6GwlLFH!?S|BP_;~%R&hEP?#;ONdkLbcn2BR(gQvtpK@ za!0v`5L!a0b^)N>uPDEzglca9x-n_X2rV^!-z2RnUhoFMOhPM2tKEeX?p0_}C7Ph! z2GA6Os>Fh<#PI~x0i@jss!;?<=&jue(A86fM~&OGPXW4^AoWC6)-KGb9>_rb36l6M zA?(>3AXr-h!P++32rbr@G)r`CX`L#mS4Nvw#U}97qE9LB?oPqsB}`=`t{YbvHbJZo zeK@vfd5_tFYPQ28;%PZn*7&-zyJ6QLHl{P{8}_Fr%^TC5Kadu#-XS)oLmwOVNn&HV z^sHfTA~vQ|)Ai&Kj_B+B!(EW!bnAM<<`Nszu`{gXfh;+uYsXpM&(&{oWfm*TCabM2 zZy)9@rS2{eOb5T)p3-*!QH zGnMi-(pE%tb)2D=BPy)3L#)6pSzuUqcQn+hL^&PSP(oBUb0~4@M5=79#rPUZ+&fuA z2~}cF58G6JI>#9C0&+NV+?gr`1ZqC(8>;!yI(Lbyd4pjKh>fXv`F0flsSjmR^CJv< z0I@MO-`TKv#G;#pt9tA9wGF#6u`xC8+LrY$cu?z&srh?`eT~?dn!mPy?L8eaK1{Qi z^*S|gGHjCAn3`8w$)j0vOwC7I-c^~mj3qlY-{0~UFmFuFw=nE_#KzP-+pvoskoHE@ z{F`kkicg3NtN9y-dV#30nm=Kv`-uvx`9peMDCHe+mB=Te=GPi(Yofwxe!3Mnj0J|( z{18L!OH`odh!d&inc~EYE|uyfPV7{bP&HpgiZEZzsWg$Q=JT=p>yu*@L|)KEoM;O5 z{MI5T_kLimK_4bGAxXrG2EAVoL%FvH^9?$cQ22eJEimZWEWsnR(4fZDO&W9{ zp_oVtwAi3q6WT^-i9y#Qw3Se&MBQ5~1T?F1eT?E`cT?E=aT?B|v$mw4ZP)`S-5maY5h`h`DP|opl8sNFb)Rd*n zYw>N?s>3RSSijR?1Hq7s^|c6$^*_`|JKJU0zxe^g`oB!e80%vqk}oG#aUi5E9QpEu zM4MzkU-nY*djwx<=)k!VFDW0huN{hKwXyy7mmUNtc5LEORLavQ@#Tz{?5*NgKak~& z_>BOqoOLv6`}8Y)c&nINQ(FfhW*t@fqwg4_<^&X6wUs-Y<&u$a6_@c*W*wz`M0?## zq5zM@gcjm4$w!%W6!Nhcj|F@z!DBujOYxY;N11ix^06F`Iee_ZV?rO@tRtH#n{|l7 zp}Xy^Vo^Dy?5$!^J)}e>P>QG^QjJWBDk5cX6^lwDWp5RWYKD7|ySa^06FTp;D)np) zmK<8G*564!C|TSZNNAUFXS6>+(ZNX;bQ`r*8T3O!vk9#DLHH0Ti0+JIhQ z&}B$#19`qd=g(HoYyi(Q=v#!^z@2N**@W7Fonz4Z2(^JaVbE(8ssnVkfo5DGRq4x5 zSq3_rRN^I6U(lz+2$F$Vl?I>#36k|HPqYJ|22g42HJ#FGT^EXfogx&*bI;; zl4SgSmNJ2jRU1w@grxL6j+5*%O={F8B=FQ=jk#D4My0$J zwN`i8Nxfl94LeU=wc7x#Gi?55WN+oWR3&0+xw>H&+^N`@dj7a6^S(xGOikZ5Y!k6D zb$#hmX-~>Kl3e9d#mkJV8!hi>=8dUu$w<~){it%4&%7m;cev#(VBVNIA7S;ruQ9wG z6!OD^{+4&q9a?fsz1Oz9w=r)_&A;qVu3DHkrtYnVy@S}8+D|j=WyHqRf3jguCpKmV zqYRrQHf9dRhTTfBMY2@j%;LaL*adBusb)&t>da$3%k|^!A_raEbY{}M37h#YQDJlW z+)%TK3Y*Q{Bbe)Lonc1I=ON2g#av-Cx*H}YO0pd}44YGh^+h}=jX5J*Rg@(P^^6t#M zG0Piic}tl$W_gDic0XcES#qA0oNw68h(-IPk8%yWx?xu!HfDK0Zp8L_w`zN1miM+{ zUs7yQ*z#WekfJzky!=K6rUuJ3g}K55)I>v#B`R!rBMdd1sIcX2ZI>IJr__ z@|Y`Zd0QKY|E^RH!<+Tcp+UnF!T;%oYaDq~&FrOy-Z4g2eLL7E6A$yjfC2 z4M#LiCW%zbyH(!QbmVxc=NS|b45t;!g^ig0xI6j-sf91;;>?GRqqzT*v`vx>M)KA5 zh9td=15h{Q=aRO8w9e_ROlUo!&P)EdfwaWE?VGLb!imWDl?Q}EQd`2Ht)zuG1?obW zM+t>f5vbF;n+Yu^)M@JFgq9JSZ{?N~T1sevL5C4qLa4K%qsdt@q0aKQBW;q>3Yul+RhkQcI4Epx^3e6+5+@NpB_Bz5;LMse9jkGz0RvL5)pq#o^ z8RSxh$kesYAms{?32428paxD|8w@gB>y)W$qd;uxx+|p4sjEQ$>;x3ot%6xxx2k`o ztGcI4*WkKU{ad1cMbx-%RsV`8yQdfEUlCRJbP-MWbP+}O^c?)nJgLon9Y!*KP74M# z@dnz2%#+$CYwx&ogGp_h!A3qAOlq}=YAmB(Boe@6HRYvl!KAkT&1sWby^R$!+Ahp! zJCpdd8eXfN(7BBNE&yhVz}Y9)s`um6_IjK=OrM3~N-X$`nVvGFAM(H~v|UrR!X;** zt@=~jB0$bUoB5anmC@F57D^fDUGmz;yxU3@phow;>X@w%*{b*`vryHmnj)EnRuEc( z$8tWF;<1d6G7Bx`qs&4}_*j9*VmzkL3Oyl!5St}N500Acdx5HYKDrmsb|d=XQH9#z z*k;fV3AI77)u1UtZ7@`^pqfVrwL!4iXm29a2EQhQP9)R@y+(tcL#PdQDngWdETJ~Y z)f?>~LTzxXGw8Mo)j_SwKBD%ZQD2d%0l`CN|dnM;LY+Vq_SH;9d?$9sl- zT(J=~nQf>WhzhIAU52`tsIc1H^dIRM9KwLVjj7Kl%avrVuo`VYoJ^ML;FY(8Md>l=4#E7Rq2;6Nj(KMjxR(#x=3fusahQ)5QLUU7OgL zCN6K-u4`2zVw(8n8m#v{Vq==vYS?FpjcMXE!`@14OcN&?wvyPGCXO=f$;8GqvDmQt zD>kBuyBKN!QDIG7&rp4d3TxtOZ&3L6jgenHt>qlq=c`i!?boPwgf;Q*R22(2>c@q{J_tuyEWgk}?3Z_s=~vj}Z4=z4^9At(dCjRsww&`v^| z4Eimkg|>NwHXF2^&<;Xd4Eh|Q?S!@(^Z`J5fU3{=MD0Z3;=0~BJqS_JGKIbPP!OVO5um%^pVG*7b^X^OM7`wdv=CKxJL3Bx z$8}4#lsDvZcgt#=;vxMIUCJwYF;lGCj1NyCR&A7is@6MrWXD8PwRQNB9TWYjtrVc` znD9|z)p9=O;t>`n1bKKYQxTEzH-- zR4Y?0Otmr9%oGpVPHbYTgSbYfJf<3$>SU^(sV=7Kn95p4`K)4!9}SpT$y9>43a0p} z)QROx1SS z(0(yeOQ<9?+h}hfZ55$e2Ax1?9id&KI4I$4LhA|bH0YK$s3aQ*^$a?Yw2g#z81y9a z&_rmvLDwQ}Goft;-G#I*gti)V-ksWtRzh10%3CqGN{HQ9gU%#vJ87E?dM}|Jgf<%V zYC=6i8w`2@p`C=*8}ud(&HYU=gC0iOEE$-fzXsi%&}>304Z10zI*37k4f^5rD#;wu zmK*e!JG8~Qgq9g}9rBPzXsJP8CT%{UB?g^8LQ5zhwAi4xk=BCwq(Q3*wIIIGp#LJY zm?ab#^aMgJXwNt3frMJHo@dY<2(=(R*Pw@!vvQW3W6(aNwV*s<(C_pmwW3N0H`_oT z5F|l(mVs{2X(>0K#BV`uXOOBMRO;pcdiP9`NRb5F>gxciBb5Z%>hJ)1j8qa_i`SE~ zMvzJlLv^aHOl%PhHe~U$hm0}UkQE3vWHn24L-xcIq+Z>S)!Ye?H<-UjioQl>J?n&N?|1us z>vm=SzVG?|-}8UIJWt+!@9%fceeZJax#!+@sb;d1$^I2=1=tMPBgy^=Y#eM8*#mjq zVuRUGCD=x?8&h{F=qA95sMX}3WAS%wTQ2*)_R~RNpPp)Eu7++Mb>Ewh)@Zies_7JeG zVEZ^;jwZVc*fy}eWQUDGnfJ#sxgBgkb`$C@1KljxBH8s==G!D{mzg#PwukKJ%OK~% zh1OPiu-#=z4R^U!O!TEIP`{?9DZsQFjn@y*X!n>Sm$q%{^Z( zg;G5;*-GWjK`)cN3#>O6{hjP|u-=?BgY3y*y}9WuvipGb=BR_nZUfevtHyMqHC{i` zTEm;O)}!wC5_*fZdvn)f=~4CVZyH+@ox>K9dK^@AF1yvfDO3nvzg+VynbYp2Rx`As zbK9*?pqyJ+IZNiaCTi^qt>|2LGPU}SP;L9%q?_}0rPjL8a&w>UU+R=se*g0H12iLh zYQh|m?O#502%efygilQvX}d-f_0=eOYJz_2W6dC(9$&Oap$fqKN=0-L7p z6zZ-E-89$~+5M@ThHfp`B-uZb-4tvcST{XZk{t}T9&8nLfBXeC`eKsRw*hQ|>^o$; z!8U@eB>Ono2f#Lgb<^VmdYfNbV^3*3>4gl~3hG`!-7}%v3^qpgD6(~6Tfw^Nad)yi zf^7rqrpIM>M^Em3snw_*teYNJr0%ch8k+^{rpI3&MVV(FW@XNSb<^XEKclVYK{pT9 zO^@@adoXl6!Mf@3O6pz&-7c_hdOV$M1K4h`ZhAa`?4DqIz`E%%Np=L-B3L&){*LS_ zU<0sjdi?n()Ts9yYmHv8ZhGu}1g+70sI^8PST{X(Qg;q?#UJVDZsz1Ui|kCW-t;(y zY!g^-dbFpe#d4-!Vx{t?$24_ELN|fyHt@P5S>{(QsPBJVmh52a#-Qs>k1^`DLD!oe zyMIJm&7WwcO5wU`=KKKJ+rWC$u$}XN5c2*HS+GM0nk5BzuH004H`mJuAEyIQB4KifJ^iYvL0jn*-WstJgwM1KBLl7)@cNQQGuV+ksXPT?evlK;uN00on?* zlIZ8(TX~y-CWwCgpp`cR)EVBBkZl55P1(DEHUdo&odL7~Xo~3hK^A-eEeYn?8jMWS!cv08Kj4T#(l|QC3+QPYk}4gy&SS>p!GzLg=`9F1JTX@WG$Hl z+DLRK$W{YwBD%fgi^uIUMAi^FSsUmCO=KxU^fqKGkuSftx>q5uHlm-(lRx|!cOq}v zvq1I`o+7+mdB0SZ58)ZA?~iqgNz1!ocFfx`XUD7^+wIt9$5uNw+c9IuCObCTvB8e@ zcC52wtsT>LOxZDM$7(xP*)d_qN;}5wSYgMQ9s8u3a$D4nfgOu>?6G6F9lPw{%kj~O|A&<&sr7|BD}r7_Fs=i3scUJ z`?K$zwxs*B33*ab3bn)!R&Tt8*pc@c<}(h|HRixCR-Y|b;RA*TxG(9}Oa58Ozg=Fa zYm=XUXdNvNR!8q{;e*UV7lMqrYr^ozUl z(N_ru@WZg>f`RlNnzd{T%hN`9yyCL4Rtd{!OPN4zK;b%nm(bZp35qe>k}|j?l##2> zkfhz<*Q^S`MPu}{;=Q9=J`TUiyQh40u$CE38ppTT?~cmd?*>VYZkb+h!M(jNSclU} zi6v@rnvl~pPOIcJg;Txzoy2KUPOEX6lG7@jrsXt&Q@#6LiPJhcjpMXlPAhQQAg3{$ z>fP@?GwhlsIqkL6sTtfW4v^yA?;=vX``v?78zjxxWvc?IE^xg2-H8 za>D?67-3U+_q!dEy!)*#GHRE2v#?ofA-#Nht=Lca1m#bfl&H_@*#8jaKY{iDZKUe8 z%_ds}+CcO|paIZ&q9+3F1!{dK7oU!N`+(L`b`)f}R7(^62}?sR(NaX$f-IM2Nut{! zUoOe2iGF;sm6uDgDxxbuwh9ZD1kt&W<$DWa?%P?;Bd9 zOQkMCH`+?mUJNm#6WvE4rT*J2PoOLyT@vM}I0I0-Kv_chv3gN^_|Xhe6iYv?U<2sZlO0EPOR&9Q>&X6v*L_9Y zs=5xawPe?!?$;CSx}NR7u?;Mu0?TJ_3@rQvWqt^{-dK3~4z$L>xUM%QZl>-z(DlZ~ z4C)Srt~W-GrtU7#^~TB`WH$iojhRizE(6vZJ1dd>=W*5=-WdA)W7M|*)*DMNk-Y<~ zH>REvE7krTJ=%Jq9-}^>>0U+M6QS#ku`|f-4b~fL2a??itT*O%AiIXKC1dZ$t^+Pbyvi7ySmifn9QQs>iaF*8a zhV`@mLVX{Ht~ab7r|tpJ^@jCj)V%<@Qbui!N?x~->``F7VZATe-NAapdRwwpV7+0z zHrW-y*5bNuitPI*YV_IB)*9Zh{%kf{V@ldu!yDF*Q8x!&Z&=?*_DZmgxUQQ*Gh|N( z>kaE8$R1#9O>{~f#?Kj@bh;L}WNIBjtpv29!+JGRgFr=x^>>TV0-qdZ8AgZo=eMBx zQ}@unCBwRtT63Tk9oDy!x)xM8tYyK0VO?&)@y3pN4IS1wGYK2kM{5?Gi?RC%(uQ@- zLeX&I@*$E7B^d?+>su)>`-iveRshs>|{r*|@y&^s&+rLdZ6|%LEbp~-VP%$(uS&=y$1T+OSAi5jSB+y=>yUfxS zbU#+=415S=s~{WWa9av!0%!%%Pd~64R|1U_eGOi@ z%r?NnFZE4=tZkNsUqLz>vbM1ne*149$l4}c_!Xof__C30*o6=CZvHJ-H;$M2z`{tF|1Hf{)%jst?t&9B7LK(6@r(wy!dT7o8tufJ+;0))U>Qr7F}s! z%12kVEQI??uDRi>Mp|@b#X@vtvzhFuw!9G>aHd?>i5G&WHG{C(+TKOMFGUfe1;6|T z6nx`>1wVpX2b2_C<_{FS-28FPwwjyFAG#%FrLIzCHl|G;%2<(CdP9qhy{q3(vhunn z3l?%KtG|7Nzq!HgOkuvrz@V)~IN0yC2}}pOqGMV<_I@0wRfd!Q<3Mdv=#n1?ntpCL zT3`k8{iT%F%tlKfyTGnWB|~vgu=!y^4ft`O0efQq|G&Nb zNV%!7h()E|bgpMPemUI~Z5R_uAg{bg)e?FGQto9wb%e_N*0-0RuhxsGBMdCVxSSQ4 z^}*LFR|q~Fsek=$-SjPZn`IAHhv&aDI+VJ%L)Yu(FW!W1*FmQ1b$2(}JHdM0{s7ra z!Ft_)HQAHEdS-AY*;=rkInrn#oe6-Ubylmw)x3 z9Xdfp&1T^>X#8V#(!V9|jOM6y3ACbSbjk*pL1)=w)m9PCoF-Che`rO`>J(n(6_|)H_(b#A6U*3ucqz@=z5lT6m{#M>sjLNWOoGXSz;C0b-{X;xFXqK z53o{smiXE0D0304XNfP8od?#l#2ne#U_DE`lI%ssmRRChq>cv_wZ!qHYC%OUalaX8 z{7+>KuF{h8wpRZHGY7JjDiqE{Hv)|V zZDkJ4Kr4W@5j_=X3}`#i@jz`QJFS1(+#P7ItZ?LNIm%W8wH0zW9sdq!5we|>T^48$ z&@Q51{KG|l-43}@BR`GkdWbx0GID3Le?EFvWDpCQ4`D1g%VsduRP_Jd+sk*ii4pzw zx0l!1G+eL26br#hr-l)zRY_dj-0ifI7J(jffUMV^+`s&K?ZVIE(eLQ|ydK8X`0L8O zo1C?mH|JK^5a@{6pBa7D(9?V6kKCQr>&xBQqJnrg**XGWbG2T=cXYZSpm%4jkMSLy zJkX?|W+l^VQgWIFs&{A2&hQE*5P z;|-UDvjE0j0CGs*3CkpmefUYeCNkO6O_~An0+1np3rg5a?1ZB{v6o z_1z$)PShGkq^begW+0{31EfyV8cL+z!je;+r8Ss9-%qgYb-K2O6XTB zhfB*S`|IB7%dwCPe|u^)xq`UA- zMTKA$s}A;b*@$)2+8SEX?)wv|A)un&xFM;Z$7&16V;Ix=yYs^#=$$pOw2pS`XD_1e z3!oM4-Vdjv!B5yq|5`NWy7@tBwL;5vw?$*x%jNeOg5jExHwSJu!lE(jZ$x8pa|;%Y zeW9-@g>&E`8%Z*>h+SF0x6JeU7O^_ZxSW;Iw}@|EK)r)8W-p#ayiWF6u%1Qa$=(gt zvxw`+UIx~)h;zv{8e3u!r(LSeBi`7mQ(_UjQ)@?PMJ-}8QtN|?T11@GvY?_C@iIRK zwC;E_mZ(L%^*mbU#nDDZE#l>ADB*Ei>faKJm`$xVXoVIbQ4uVn+y>6;8)`;s5!GQ- zbd+X64}ho$q*=tDpB4=#UI_M4-xa!_p;iigP|x|Op;BZ%%*WC7<8xX+_jZQ!c%Alr zAS{-{2;)V_Hk!xk_n~>94M01Y?<}D8K)Z_@vcGMa!?x?e))<8ZIC`Ww=OP=7NQ8Vyx;#bR%hsUdgQ?^wOqSw z$xc@P&&*=z%acSKgh2{AU*5PnE(}sE3mGbvn`@~pNO^LM1S#u|9uTAq*bU3dexf`f zrsbFKqgWTT@Ple7J)ZHB7^GT75Q9|Vv{JeS4AzVfOZmn3bHnW!$-e9tg;-Ekj+u{1)wRQS)!AX zLmFs1(c^*E0&OEY4rm?FR-(HAtq0mnbQ7QrKr=+w0NMz&iRd;c87J~aq955yZ#5Zd zng&9z0%{gWGP1sT5|FyRIzsmX(uum3(DD1*RI3wonou*ObYe~sy31U&ZBrx(9RVr5 z-QI3Cg6}C6>5jEeb2Kch-hp2l6biMI?7j?IVt~bu7lU*CEH{K6n&f6nr zZ`|)fb{(+Z_}_r+Pou29o*!6->_V`fKlta9XpJYpdVZlm_GYl2e|R*5w)(RzZ`?cg z&QDCE?$M@O6ZIF3r1k_A^&8_zZ3!ysKXxRwCa9<%`Dq1M%Lw_H7ngv}pDatQcT+}1 z{mM`0qx@5b>E9Cn@}dksbplyvIX`3TJasSS*Lkranvq8J^)^6kuXDGdw$7_l1nWGI z7S%5&&aq!yersGa2wl;^EZ|qRTJT-bNV2bj&0=_^?8=2;Fl!LA8u+g0iziUO4|Xw= z$wSwch$ z+s+lmsQb-G^8ry;^v}mo**8H&UD30o9tRb5MfZ`q1ys}(HS!}wkM3pHiiS34Q|m-% zMO{(jIVgXHmA}Ll?MAKbp%uC!*8FCrW)Nmxu3SGzPSR=ng>nWS#5WVLlmk z0p*i*ZA3eO^2xe(qBjBUl*h}Y##y2*K=VLzM5o$QQ|=3zd7>u+%|f=5=pM+S9cUNP z-5}crw43PfA=?VHhv*=n%|MGpzkJx*Apr`RZXD!lw(5LWN}Be9V_h^w_}AJ zV|MJ5LjIPg6Xi`>lg!&OXGb*(`AtPTw%JiTd2xq!s_a(TvB{3wNwQmI$9g-~*-;x= zcB|}|vSU(?<)4JSezG`;$@AlU@6@VUe$%R+E%n4I;igrF*!>5Dn^u;EIOijOr)}4x zetPguvT1ef4g)r={9i%D*3P76c}FxOU-LD;F7Go+ZS;Lc`!gNW2;OHDWWa_=jcCgK zpMCV=_WB2MDFo{QQtxfkiAb#oNWHerKLRbYi8*rh)^;U<7S&o_Ikf`0qGrFa%A~|Q z*RhwE(9OxEOFsy75m8sre;2-rOzVUPe!-=OZnV|QmYH+ z$7Sx*ZTWFsN2Rw}bE7J$+UXm(S6D5h$E;4)wOdKA2A6JMwrl+lI#-G_kkRzSEyKsf zg25~Q;$9GzEmgcCJo&Re`~pdv*;PlY{oyS%`{hfqgC+rG*RoML>{>S9v{L3KGg90+ zg(=%too$fg&Z&6-`~r!&2i!SLB8RljZaA%#Q}aC2Y}YaYv|i9koHod59H+W#S%FjC zwT#)Rd#}}8s60BLyA*Cu)cp>oxnkMG2WReD?nENhBaTFDB8!x{ec7-_%BBX{X+o+K zlATE9k?KM!C#eBLr2nqLo$B7g+X`E)t)}Ys1e&!PVims!8n9MGUm9bwy+E~3RQ6$@ zeLx$D-U2kH1|L3xHyvmNQ0q9!;U4q2?gzH(n8V?at%PhX(chP>>C;5FgKQOKt&=6+ zamcqCXp*ukKsE`qn&>8wO#!VUx)ATbrGc73NWKN29IKU-y&tH#i|_}gt_NzvT<#B0 zb}CRC=Hbu#-MXf=uMPF^2QUwUtPS^Y&fd*X8S>!}$U63x^ETHZ=$fvee@K#xNzFH&lBY7KV*(wk&Ot1Q00 zTCk95JvC6Vb~D!*SyL(9wrgKri=x|hZKfTUvsO0R7LCfu=cd=NX0q(V=X2s@uLbLw zZZW5Bs1Q6-txg;_m%`^q=aKyz*gm~r_`<|&vgd*IO!^|S^JEplXX+I{pv*g9y_{pzBegZC z=#cvpsUe`ELvPy?(Ia!?`nO~VE>ErZH`ivd`_^tKes&K^xB!$JlD5O8BeDDr*U)A4 z8oI1(H*2wF<>4z?_+n!cJ6s@bSvkB$G@N)LxJok!M{UyynqMJ^TiN}I=3ug4t*TP| ziHiOw@it`*hFT5$Q9GDy46HY5zqlK<|6qjKi#KY!$<7DsjoSIgqs-$`DsR+YP2Fbb zdZTvVZ*kolcCzbwqqdH^qoM1K+R?o3A_=#pHL5Y<-Kbrcx^d`wqc%?6EOfn5Tf7UU zdUZ1^l{aeVk$n)XH)>~-Z3F9#+Kb3e1nZ632D0P9dZTvy1hn%vD_ecNQ9FXV3FvyG zb``Qq8(R~d2*17)mHlW_t*kw5;wHp7_F1Gtuy_Zfq7&m>YTXa5=%}4VY9^@YsJ)of zIiRAW_B^?(ua>{I)vjdJ?nA8_XhkQ`Ka$!MR5)s7GYF%$+=`s4-95D=(XMNZMq2JB*->H zw%g`<`I;)w3{dAVcLmx6)b&-xS5}5bpaFAO8?tguEpIQ;7|?p4eMCRWS`KwUW1Ri| zb*z=Q7N`r!9*1liXq>WHpedl0M6U#z1ezdvF3@VARYZ>gS_QP4=n*JG0;n6|J3_V+ zXo|9bglrsWn&>K!tpHj}^wnOgaSUi3(GPAnv`=;fq|NGyzI%+dLod(%XfSDSNGvrXh=BSeb7xTDRE zt#)j-W5$k6c5Jj`gB|PbSZBvtJErZJvSZSY)po41W5SM=c8uGx!j3UJYBNPQa>{R_ z?0<#~uF3QD*%0+2TJR-&ysMpcpZLqqi$5Kr8&2V{J3;17_d2O%A^u|M3feEW(k^Tw zEA0*C3ux)-NB8i{P@@hj^Im9rd0lGG)#}NUKUzQ8OVJ9-d!brGSwm|TWeu%$Ok)iV zd#KShG>o7oA*bkhTSFJk2x|1npB|hh<+K~8DLL)Jsji_rajI+RJWlK6G>6lAInCl! z*U;@a)irb*PMhSk)lS_Sx)~|1p)*LeVujm;6xYy=NVS7&K#FVVdZf69u0x7z=vt&Y zp_fLAYv>eG+PhM+BvL&{RU=hIstTz9sRUBJNL3=$hg2M?7@qv8K&k?%7*cVh`sAZ_ zVpEk!^&*u(DnLp$qqJm2q-6b|sUD<~NOdD6OF-qikV+%fiBv68d8Fk1BbCe{RgY8_ zsRpFlk!nP$4XGxiT9L{i)r?d#QW>OLk!nJ!4XH+?+L3BNDvMM-QaPmRkjf)fi&Q64 zX{5T4N+H#aR1&Ekq^glBB2|S{fK&phUZg6K>O(4yRLr)krdA+@7f`3hkcxxrlW+ZL z{~^_jR0630sVbz3NL3@%gH#f!Zb=Q?$H5RU1RpFTUV@Lnh|@UET&VlH14e!!*biuv zjd|Rd5!vPO!e9od`UMSB{%vo;;ggcGCqeXWpskSYQ!^FWr-8Ns?Irq8EmD8b5D>i< zvRTL$iSAde0T{LoWOIV(iIB}hwwvg51=${;Iiibq zwDJ~#W{G|bGyvL8^dCTbfwmEy3$zbtE765ZTfQ-y68b-)eFbDIfMzIr4$wHzCZb0J ztpwUgbbTz06F?h??f}^;p!GzD0j&mFM|5SNNuaevH%EC>K+{Cu-@$5;2AU$e6l80G zCW&@Hwhm}D(VKwQ1Fa(30<-~Wg6L^L8-Z35Jp^bI&^XaOfM$SJ5IuG&D{nK<7}4KD zwiRff4pXt;K|tGp_7eRvX*sk54T#=>nHp`k@RPvFbd~Zlc#fwi9R< z(T5=01+5NdNyRa6s{+FBv3Aa>xhm4%B62D z(GwT{tgX%^Z<^=^kmXW0MRXKoxx`Hp{q~R64qVz+6MYXTm$X$xp8?9HY=Y?DfpQ63 zN%RJwT)M`IUTkQME?FxG-TA9l!Ir8qLWe_2gG-xF#B9d`(xs_QDgx~UNSCBGvk24| zE=6s65oj$)oig&%Tk>Zw4Ps;n(Zx zMV^NKolO}TuoYyNBU=R93|1`Ibb{-kI}dCt*giUkXUWb6+Xl9m?BfTa%zL0z?O+44 zmr=I?x>>MAvZFu5btl=aMSq&xm%1aMn}=>Ub$91=U;5eFsuOG%*|n+LyNd?;b{bcox!5KA^{R4Gl(5(QQAzMNAgGy_SIM^n#pNNB3%b5?h5^N*c?E7Hf z+}LyzU>nHZOWkJZR)MW2+e&r<*lMtKWKShK8f+45E!krZM18;f(dwH5nc*j) z2Ad+gDRuu2-CD3ovOivf8ofHiYE%cdn(RAd9|T(uwu``QQ2Acs}LALGyw8r~CSZg$cjghUQ?$Xe01=~j#xgyy`Yg>J#<)2W*b)&ofY?*TELSX34%wHV-xc+fKHV z>~&y!!M2f|MfO~70Hw9fUd`Oes5UdwQY)W=nuwFQ!-!{_G zz0PoJ4KJ+t;%cy6YZ~i?7u{s<1nY$v50JeStQT(Fwjb)d<@XrB*riXiHO{1NEp)x` zV*+)*{?2s0Fl0ySt_fW)99fs_cWYRUys+fgt5Dw_uwHmlB>M4TE)hP*IPNG&CTG23OKT?~6iiR^uQmccChBZIDjS6nMp;q6%yW+x| zrK$DK>PAJwoFD9QANke!SWaoix1uH|?##D~%Y_M%$d&$nOMYoScsoKFx z!r)NO!n7HpC1)^DLylM+_u9M~SRN$QS(ZXRqm*%7?%{I9L8I>C04{aI!Q^#{Fi z%ef0|C)wV;QRZgoc7x56?WFD;==Olkk)1_$CfFj_EZHe!o4^KO+sPh7_F%BRVB5&1 z$&Liu2ey^$NS684udKc?_}yl*gQ**XZUxv3*)J|fYkaV(wMHCl6WMOE^TAevZ6te{ z%q-fHZw@ux1lR_$S5vncx>aE7$(~7e0@!M>b!6+vjs}|qTT6EISo9HA67G91X|n55 zHxAu2bW>#G)Xmx|ggms99$Swfe4%S6Rt*=A(?R8Bz3)V$OGpTzCbaP-`WORu=T~r7*M49to zU1W4Hb;m-t6ReAj#!~lRUs`>;z`Dq2D0NqdZZ}vL8O6wcGuX=91J*@GA6$wWy$-er z)zZZU|nQ%8`qSNj$UXwr zi;S{l{|45Jj4mO2p0PF2$Y}Ck&=l)fbxIPPgH{+B$ukIujLJQOu;@L_ zNFyVersd3@96D9A=#PvN{iH=k`(7YLaN>pFuqsK0+fgH|6x?y@-?yr=Vo%N6KGakf z0mdMk1L}6d7QC#rpPB{gw#;4?Pbz3TP`9`CIM6nrF-G%QpsheFh|bd2bv_h3eY;BDWWT)WVJxkL_fILYMcgI zOZ45{trjVubwnS8Y!YZa(RQHKKpTi&0<;QfBhgy%&C)svpiM*%g={6z4AC^uIM8OI zTLY~C+Ddc_ls5*njp%Za?fb#zzjmU%7g-s4fo6%m1vCJfBRU^w5on(1y+C__b`os^ z+6}ae=+*iJoZMms+D-HX$aVtlA=&`hJkTQ16l8Ni1ER~lWVOfw?IpSw3g^l$fkh02=lus)(%Oa^^`3Ftp?ga^jV-)KpTm+ zzF;{dfHo1m5wev)Genz##(_2yJr!sL&{m=+?PjeW1KLJ(cgXhj!G4KW1MLNxCHgy{ z0ni-LWq}rf=81lBq1B=XXeZH6cC|8e1MMO@53*fAyNNyy*-oH6L}x-a541>h{PT9T z9MFL11juHA_7Xh?`L+Y?Bf7K5;t3PtcT0L&sI%y`0|bLQ7i;2^1T~*G1oncWm(9w@v09s zr0LPM@W^H5QLJm09`GoZ|2|ufJuEWURst;@wp?hL5$L)AUw)J)v2=AJPhw#SV{f%} z*}B1=#KNM;p2W%nt&*uFhf{qLD~nTo5(^7A`wnCqP<;}s6{q?nmc$4WQQ6x}8JyM& z+JsYm601>82R>ucrvg&v^WK;0%Z56WgFevKaQ9hJCwc#89djuR=WT5zs&A@l|ECOl zn8S3))=8&IzTHI60?M%6+Cp+T94NzeYZgKG0?IHw&m6V`+Jt;_MAtXe!g6agQ6CIQ zALO^j6X*x=8WR7i<+M?8T`RnO5W1DnKOm)Hw>7FLw%SV6!fk6@f$o8nZa_9sv0Gdu z!|O&u7eh+JYFi@l6}EzXseCouXRTM+X)_v3rSv}Qxvy%DdY`q=*tneaGV2xX>*Zp& zc2&Qt-kPLdx)99y#UAwXy6i=JET|A12wkqgdYJQ#)NO*U*M%9f2ZQyx@(8jc!FpZ# zXR<@VdR_YmvN5n;7gvz|;AgE-NmqYLO)}ZetIdS>Yt7Z^d(_{9yP$Agg3g}zYrRSj1nV-s8 zQ-->g(DkgTmb!n2u4heKll=o&&zjaGTLIRyrtc=ARG<84rShz)hwSrUJ!^V|?7ha8 zSkq0Ut^yUcrYWSFKt-+ToE_A+6oNGtS`X`b-Z_-9)Y=tVQEOWDDOBNLEWh=g0_R{V zsWli{QEOV2*Sh_k0oL@v*~swqA8eF_)+FnBSW~(6{F)L7Vm+TQgE4EGrCHGP;GF`H zW=$8IYSsj#5L~W)E_{z}yp#gpt8~6`eA2~fu6{|ADTtQyvP;{?jrfvpf9u7qM(*2_ zZS+xtB|n{XG#NVhMRGYo(?GM7eGzC1XpU$eXcB0i=q#YsKs$+E3bYDn7tu3;CV+Mm ztp{2Ow1?=PK;uA*M0dx7OBFx^qC-U%&(ilg#N;#@?o))%(tl^OgT}Oq$~)Ev==Zwo z<$U0WEf;sB3{TootGBpAt0Nyguw$hiwRjSEX?eWgfcc$%y6eLEjcW2%hVoHY%*;o= zj`m_0bvYY3e(f;ovMgk@toN20o<&^?e*AH9u)z;MijyjN0N#(f@YwJF_^4~iq1GC* zzLHjSeS4iI2ZUNmT zBD*wLuisWAyXb4XuGfFRZjCZu{JPna*N-orhB9ZN>-A@j>?OvQ^y>^#CxeRi?*We? z&x@BH(9efaYX@jW`}@zNhJuRr`zEB80Tu241Z#K4YXj`y>r+vT7rwIT&e?+nPih9` zgQtz2LHE08$fmo7?*9-xZMLE`uoEu?*J%df5I%n^H2)AQpl>pJvy8i08T}!>71@oz zdM2|5+2z4{CiCqnsQt(PHly%N<_)sXf%Q!0xoVX8NSj3P&6My1``1(Va_D*{Gl}de z#+I1O5u^?P6*ZY*kD#Mxu4vzSTsL6c3C2BYI z9|KILlUj426`G7hNHCdl5zaugNcH+o=yZHyR@}*n>aoJL;*L@Z z%<&m|<{hQTh?$y+tZgznzqb-u*2?Z8q&A{ooUHADUwsT?p*eX&>r`kOwi2Wm^B`Lb zG{+q72AT#cisk`l0@c7la_A&_~rL+tu~EcA(abQcThXK+UCuMv@phZ;rue>WYi=po0Pxf=ypCFNuN`g8MZo8z5Rhem`BB^Ln84PFiejwz+y{^V6 zXwSHuxu#rYGp$S^xW=yPH)*dvg(j>9;nLt<({>&YuX)|4HfeZGJd5nPV7;cELiSK& zOPc%~UUXSBggSn+FDb`ZYE?l?mk?%eLajOng-KzNtB&7wMJ2Vq`oz3@v`bdywc1`7 z&@~@SK!%S&E80bGZh~ex0$S0ox|>=TLCbZSg%R3Q<->?~JJCbV$=jT;L6?OQ)@Rs* zNtjLBs(F#Vxa7p;oxLX|gRobVEMWKZ)^FZG`5oB@z##C(qP@B+wf+dLXs_&Bp%v}b*BelbXXTAuDMr|w0=6oL!YABAq9)=J^N_v`${=#8~u`7U|?+&Ubxt>zW_Jx~I&%|PAw z=sQ+xhwY+pKs_$r2lJ&Hecd95J7j@*nL^P02N!Ad61m%C=1ZxatG&*0*I713m)wl& zHK7!kW(vU+$xBMn2-NwflYmNXv?XjTxcC3(YwPMft*G4Z5fOR+-;S+z)N0~qJLEnP zz8ohLv0hewkptJ6t{L}F$dhVpLatQ{v`dxWnn*~tYRd1<4JTyRW!;0q3E8p`xeIKO zU=#9YpU8xKQBZb5_P>Jn)@Rxvg<$&b`qNOG@+oHoj7otzGw>H`&!+U`;?PgZ1dfhPOEYSTk>;$lOS+7Y3jzYen2 z72&Kq7P4u`b~1+~&|08*q8kFO18OZKMH&pW9;h{zpx@cMaBfa)XAVW6oD18CJ`1!7 zIaq5-4s#4OFKMkR(9M8!&dX4DzO5JVg-Sx_KuW!#wYDfG!*#H=xi7?Bp7HwfOzJL{pjXR;mg{29yHhs-U9WGe$Sw`m>*E#4F8aW(>-F_# zN1#*-zU_BeSlI#g!JzF@P>{w$k4Q&Te6@> zO{jd(^YKG49rx?9Ha(7b!h#+%CImgb*19%5eksp=h@Ao{1c&A&8JgQ}Ea2NunaP+n zhtt^_EaUQ4M*nA#m#6Mc(Dlsi4H-XL_2-IaGM>3TO!gkIp1EC5_HwYExlJN_3RutF z4kNoCSkK%>k=+igXKusD4gu?#+aR((yl2*tk!EbB6@PLVD*G;|sJXpA6ee)CEhtLN zZ4R}v(2APd8Chi5`Gs9e12t!E=TYlaXhqHK3|?zxTq|mBX=;sxR%mV#jltZ?MPm~? zoVmr#&zZSZXcqKch{iygxdr;(S_*y)UmTyZss~x_Ff%pHRcJ z@NjTZ!oy?VEgK&8$FS+ipS3NeL+O9e@5T;{=PIN%)n}e8L9+ByjLGjb+5d=7pR~LR z6@k(@_7c6?UcYmD60W(<14?J;?4$uGouIR)X5>rf=WK7J$=V#-#Y_Ew<)AvdPC{!# zs#Tyop&cwcTZQHb;SIbRb!u5cYd}h!Sv#Q^Aa!DGgg$>v8$zC-FZau^tHjJLWmLBO zFT>s~4{{>zLPN(TYuCm*+Ve_<;3>O=|2v@TlD!qI*XExc1ZTbAO|>w;?O!CD1?%-e zj_f61y}p=TiOFMgT-WQ9)2TbwbW8eXyICmGF<5*@`)FrsRYEJ;SKIM&k3VYdtP_&! zvkGc`Am8SaE{OKs;vpzxGqj?8xQNt=prU>G45@uVxjwb{N4s(f@z1^JLN~)8{&~>i zAL~@aKamOP%P&R4iA(%*pCrR>-;Jes+nl4{?HiGu3)buQZx2KpfBZ(dZhwR9b6~x0 zf0*n&V7+d?NAA_@5U;^?y>6dG-BV1rq}z9v!J~>T|FT|+cKaUG+6h|GZr_=gd;Q@7 z-M$*N20<&@?G@B&hgP)PKeumu%kLen>Rji{8!d-=pw7q67Fo>r&KJ*?Jh6LJWPTZw(FiIaa*`oB z|MwCZk89Q;_dcR^C|@m5=l6C6ng(h^i1EVO4``cfyZ}^w+Q9vutG36Ie$~}Yxe^X& z0c6(*SDdbw=-)NkX?qO|e)Dg+X738a0(7$61(x@VU07fx6uTd7%OeX5zI{W&g4)*y zgarfkgv3K?T#z=y>PXq28AdO|_$302~>Qp_MOrvs;QWLF4gcbMTJ z+d{C}gW9OJ3cw}g`*L`3O`WZ)+G<#}>S)tT>xg~~QaZ}47y{h^NJp0yN1*5RYIwy= zi=~PeLQ1w@<*M@g2?`giOXW+JI(`h9#yeM~8x`l=q1ow11*#L5Ggp%pR)>$e5|>ne z;%fBHzVJd1zG7Y|TC+jdf=Xf48?E7O)XG3BTGMHyjs_L2@dc})7%L5|`8aBA2`y^@ zn_jfy<)@cRYJTt0WK8HA0r$esc!1n17t zd`r6hp?%O2cfCBIk&4%V+OB9+w2>xL>kMc`8|fHQ2ZM?>(jhFyw-Q}@=21$i6BQ;t(SR;MiZN|h#O7xS~NdNeYIb(=RD0c;n?BaS(8F&W!Jo zyY*NmI$Lis8Fg}QK%6BAep9HLmVSqQw1xKEZ;X4J9G{x&x8A+%3i|k?m6$GX*gaY^ zb$N=0+uu4w#F42d9o_OnzZ2VfTXSLwwSCK`{MI+DMZWxeTj<1GQ@r*?=)^1w8L=0e z<25H%{SR?s(_S9n#Pq2=Syd&{Et3NIJ)dIK|MYFunVwct)Ukhz-KmrDTO(4|O}A^2 zH92iepZoyLVEh2hpkQOUMw$Kc|LOO*ch`tMw4@g-z;^+71?^(8yd@=`uR)Vx^*z-+GVxZ?|ZUCZ9^h!%VTH>CfdA2ceC0 zK)NnCoYW__awxeQx-BzY1sO)WWHV~bfmXC@e%%Wt?0L>g8115OS473ngH~RO;kv4e zTCA>_)mA(d}PjYz&-AmzDVW7WhY^lB*Ou+KMVMoIXb^r zhqH{8Rz|;9E2*1q0BqtLsziA!tQ=^{c<2UjKT=Y$5E` z|9Fpkc)ROW1XI?l4`>#QRV~I&)Z8^HTw!hbOP@q@}S6I z0@vwP-Ry&U>%M_ zZHDcv?naY^V4Fo&71!-CyRz<_INSK*&n|p-2K0_0x<}zU^;tu7^jq_Bq|Uini=-nJ zsO&I|Y5Dh0g&3i3rG(Fq?4)4e7KulumyhwBATKFoBYN^=}zfBS8Hk22cm{?IYaXmg7*k4k~2mXYSf9YHsSIwg3Dtis7Q$R&4eJ-g3Kt(HmIH{dLMH^vvQVCGe#@LM1 zAW+dpiIe)|F)N`pj=4u|lk(A1%~fa%w_dT4-+Z09M{6BKPbsr58~JDeIU5IYCtazjPcRwec!8QCp$kwp}0Z1}U{^X9%Z4 zDjFcH2dV#~_;IbvwP@wz$6LNvt`LkESfewO7<9F=B=&0dS5n)7iq>$-dC+NAY`YrL}@XJtP7ZBP2KX%4{h#&1;E+<|HuGI{} z?mo{x3NF8Yd7b84((U`ObTufQx;oeWe~j@~#*f2HCK^AE6PeQZaq)JF`0?Y%K>I90=wBND^P8XPdDB`4`n$R2-+y!bxM+Rz za=$fxoFwh$e*6$EC%eEhzdA2xC6N)eL7TR(dAVov;^j7asH~Ukcg6AqU5|!A|0j3K z2gZS}6jLSIjac$vn+i%S_^B7QoF$Gc2PkT>HvrN}*;(o(fTF|rEI>L5d-uYZLxdO8 zZYqB-{Nzit9Ob>#FJCEF2rkmvln%h|ZD9F#{@un)bO3gcx*SxrI@ggp9aOYh=aV`J zRJ3|Wk=hxQRnuZMtzG$8?b;U9%J~)>W$(292Um2{v!da|3&ASdETJp<+CBMz<`#xi_}e^qAk%%Y6_@mOPoRKI8f1+IGEH}P;3c_y3i8kqOQxET}wp# z&3dZ8B!BaZ-dzpXt1Id&#Nj0Q##X*}dD@Vuclo;@rQYRcLwxTt%`|l#n&Lz~tyevZ z^C8Z&9C?}6Aw=yF-~IJternkACbbwrfAlm*zdHWg*QFat`}lrkNcTX$^2}9Q2JRfgYt41_-~G81XdTd;&P!5;yR}IDPpD>z)yjh&AT@d`X?ZDi;aXTke50EySpRBegaZD`0FY4L96AZgT9W? zwUCm*&KL*3Yf!KcQmqaLpHkWKZ)IIJMRQaKA6SNQIV&>jbw5|G5Zr24_51L%&EeS= z+@qdtKwpy0g7x||NA?o1Uf*6x_5`qAAD>QkELg9v8$Lss|83#5yVvXbJW1Wvq3iYi z2 z;k8!AwW2n2AhouFR@8RJQtJ(Km-b~NXG0rM>!-VHl5)0Wv#6R-`B`+o3t&3#H7lD% zXSUcZYQ}^e4_m{Edv19nI7r`_a^i)cOEU<~?VeB2gf&(`-`pl`hUP!T%IKThVPy9M z>zUgqvfF|6%xxIiAz(do8$|YpJFVM2bNk_Al=+J3`qwwNXEsHd=R(&rx4G0E2VKwH zrc-w^bUkyMOx<-%x5V7`r()U^OU!KtQk#Q{n%huPtAmP~+giNVJ+?NfiJDum2`c!` z9cDODb9*m9%bW$RsLOhQTDL(fG&c!VU~c6?l||=khPpu%S2xV>|7#ZXUDzN3Y38=C zz8UJo<@^8YDMQCOLP}BkR+c{9gz&<-;0i0L`=uD?tCzK^x$gkF0sBsswuSpfjr0Bs zfL5Ca?tgPG2ULz)qE`CbyY0cIsR^KMM5jQu5@8_@qZ zZ)J7quYUdZx3V@lFO2vkQKe2O0hQ8vhL|*XJ&_F=YN#s=jZtR=s59x`KV6 zq-5nf0#fQYs%+@WQ=#@In>~w^AhaB$)KOFtnhPmg$jH!&DU7GM|Lc`&$2nTG@+;Tf z^zObC|9P!VY4O+I2p+9>wt2MZ%5`OG&4gC8I>q78dIVb0_1YWyXqsHB9$L}r-ASz} z(6Va&7c1BICZbkuDQa`>h8O&YmFqtr6%8jY-`dq?30G7*uyik9r1_R~q&Xx%$(K!u%T8?9|NhTh5lgA1Nkf0mqiZl(hZcC zMQ-5A^$wfTe&fpZJpIkO-@bA^UfRcBxgPRl=)EimlHOQ#ssJ4lZY(l*dJPRlTCor)H(L2Ea;eTsv7NX) z`KTF$1wWNVI0i+C7W_a`dkrl3NK(}$1(z{~f|m=qPB{~;XB&rB>ZMhgjftnHWJ}SC z{7-$0(gX{^w~t$ST?fuv-wiF-zBxm5Q^EJi4z@A%$C&_-!${ z@d_>tt`DgcQt~NL%`+*ffu0T>SO{iG@F-SQt4%F7xQTgs_poxB=)wop3i(kbtTIHl z0Mw#)xy4J_`+?@I@9>oek$qV&BP|cq>_N~+fp!5k(-8DzrU*_e53*qO+#1hfKZk+M(N%WYWg z$r6L;dy}ljm5}Ww`V7zn&@Q5rkV6&FPNK&Gtp=JWx)0DK&>Yd7fTnv0Hv?@#85)T` zX%5r&0~!c5nV{_h)DyZMQmta3b%geXl*YTYgwBAJMt5mKM*!0JHbrP1DC#7XB(xkL zUDvm3_setA%E)ul@@Ke?CAnXvh&(54Dy4JwPbX`O>6~3>+HpCnwKI9e+n!b`1gl#? z{PA?qI+&Zcxz&nfbsVA8;Z&c zk6^uV_f#cHbpvwlM$Q77&O_8qLAM8Nob1KaJsi5;cs!2mZeYD}c?fgLbmxA@i?LUT~zV}>XEg6S}_Auwd>u9T5=z8P$ z4zgQ=^~Uqr%y~cL?2YTclHCrhH@^Qwb_iH+oUc#zhnZGpZ@e!>_HD4a-9SbC%5-LUEHaGx zms3fN2Ic&WMd9jR%17a|kJn<@17AZaZR+xysOQiJXe$>I~%O$imoJk5!k$5UzVIK#znmDP+YeY zY!%rCvN5opD@row5y;tdMI)#?|4ge<4{~;{=;t+1qu#5mMxHBrm+UKGJy-O~E1F{= zn1Gynk#iqi!Yt~}gs$g`W>R+x=z6ZGiEJFK=ZezIc_ec7T+vACzIuk$*Kng*TVI- zv7L9M?iSGXT+tTPU2wX!hUbcYT@Cg9>I$o`=ZcDCUj^&AqIqN=1naq?2jzCU+QwMB zZiy>uq2eS{EOA8{YE?oj>WcQG)*jG`x}rU)^}%U+&6=ny+LBZORMZtM%?!Vj)eE;P zT&VMrj1DdQ+n_>MB~di#d=!-jRUQt!K{EBDuBA^aS&u zdJts0fVLAI2U*#dR@p4k%^{lynj<;{Xbxze=u$wlKs$+kx{B3Uo^RKDyNJF9v<+xC z(U)JaR&NE`L-bLgvhl4s6p3Di95O%yqL)Lq31~0Tvw=1O?IXGma%cb=snO)2jdZ?|Qb>kw=F6z!_rW z?h1Frtfj<*Eq}7Mo$UkXE|-1al`bp05A1Jz-8>%~U+>ATNcoMgKP-U6q9scdAo1}M zC03`z7yS~^{phNt)i2NOvD$TX+n*U0`Lx&n5POch-ng-8*Z*X`P%}7fiFgvpS%LkLTE+grGY>~ zqc7^fk*{@;M?PZyi6X9sKXx;L74#r>CQ{ok zT9MRMprUrQa5>cUp^LN)OYCbNslS1W+S$YQ(egsDD>97Q+l{0)1{Jlt3rP(I6}7(u zc&%z&%h{o=jn(|huZ^3>!|bN>**^zV3A z>aK3OC8l~9sqc@`?6G#T?kfaaGtWO*o+YL_gw#r)qNchEGrSEMMosl=y_GKAJq=XU zRC`D@f{L2zUCW@+Zo1G$OlYdIc7myvTRSa0NUx=9rb{V&rk4b(DQ!X|3H< z@vJKAW}kt5WUjkdT$8)5_|o8lQBN$t#M%4V{ZV1}l$W{0mB-ucZB2mL+h#O8 ztkFF~G@Q8nl8&}m*hs@!y2oUd>NV2$zo1T^P8!fiUp%JL@;Vr_qK)(qQpbaeHqvd( z@H%7|ZKNBhwH>sgjnqi3qoBn`l6eD-RBqn5bw4eh_q^CPs=uV?#n$*vG{T2)5`U9q zXrZ6~>^}eH%=mM8PO0<>vS&<2eVZE)&xlOv6J&V0$$x_Ea?upK?^8z-cFZ)pg8yZX zBW*^s{Sp~H|K;~PtG|&t|Mus|hDp2m&ylTledxn5#^k95^UvnP8qXIW_S~ehK1{yd z*_WPHBmYwse3Ygii5-I9t_o#j=t4C8WO14F^ubTd7>K1eku_6Sda3U6kK!!zBuunX z>REnA;!E-LYN=-|QQ~b%OkAQwffDC0QR45En6gBPzm7vWhSe-C^Ym_$*s|aIpJPMhR3W2bIcqX{Wlf=b1v zHX^0dsiYc^lAF<*sz<6FsXC;xNYx^hLn@6_9;p;kok%5->O!g-scxjIkm^Ayfm9Kx zN~AEwPK_hg3$6mGKBQtu$*z=^y6-0&t@xbG)Lx`?t4_E8sY;}ZNF|W!K}x<&qmtc7 zRU_4fR1&F9q*6%bkxC<#L#h_3EK+qywIfxJR2xzaNVOu>h*UFDO-N;s${^K*R5MbI zNVOu>fK(e&^+>fNRfkj-sam9RNTrd=Bb7p`6R9LpT}V|U)s0jYQawl|kSZcoiBy18 z9I0NUDv;_!Duz_dHV~)w{fPcUN`4F1{5?|gLwuU5L`r^qMN=~3<8mb8;~eclQK@!9mw}g%qtXv>8*w~097ZU zZtg6gjX?XYY_(ffhsf#!%_5400#mgu7rcT4MZ0c|IGE6{GBZA1@34n07n@YXtK zL$(OCnds(_4S;5dj)811&?chW1MLIaNc2;@+ve7PL|1~WTPqTM02|d`pmCz>K(-!e1<@BE+W<61^mB{n-KS9dbjXVR-VE6$$o3MQ1~daSAbJMS zW}ro)hXHK`+C%hwT&)dgH_>e%+YYpg=z2i2Ks$*p4>SifPjqACn+KXB`u3&PI-NkX zM1Qh?9!q3dixa&MvfYqvBl;3#dw{kQy%4fRpv^>YfouRYL-at%_5y7pItpkX&_<%0 z0k!p*JTpynFXUUHi#OTpAi8*()y_J29sWg>{&IGN-I++e8_Ap9Xv{!Z9por>J>|q#}R%I~6GV=dE&-Z!HJ@?#`O3m{B z{r^6Ca^LUsuFv*9?|a^J&SgY(`G+Xn&|7sa;5Gnr4Lyo^b(sWDZ|HfY36M@efaVdBg_zDlfaVgC1(;4nfPP0v7G63Z0XmGGkOh}aN@8t$6T(7^ za}L5lq2QhC_){do5cE`#hS`DyUwxZ*n2bS|IGbx9u4UwHrVgF?e1R67!!(q??d z7`f~`4UWp`PP43Rxlu=vT0v@$IgT+#9ZG5ysoh3B*xF4Tt>URBHEGmbquxVm9jRSL z?Ox4ZJ%6tDs*%)Aqb@V*{iHUL+F{g3jrvP<$iAhm_mxKXQ&dJL(pq_!D# zqEYuDwT;wPqaI|`tw@cN+G5oF2PlR4#mbF#Qk#vsnNe>gwS&|qqrU$sx$)#V%8gD^ z8;!c+e%5?4%XX1kXVkl`Y&FX!Nv$^OEmn4CmhC3B%BYtcbzM?>NUbpHSgUy$YtEu0 zD>rJ?%073LjyIdsGNVSU>?ddIh$5tx8ufGg-11UVb4W!eRF9V%^+8f|NsSrxF{3t; znn!BXsQ2DSUhU0Z<&#=q)Jv`Gc$O_7HQ%Tw8g)NXqon2;^|19kH%dv381<`r+2^ZRwv5zlqdvQmy3x$C<)mgAb%B*Vlw~VO?J>uB zt(85EWvfW-HtN|%J&e?9QjqzY~YQ9l7B(;&$PNNRBUOiBx+-M@T!>C_= z!V$f6rgEd1)OMq;FlsBQEu_Yc+Gf-nNNpvx&8YX^Lr(6?cH2m8HR|P7b^^=BNo_G| zg_ZqgtoFH`)Mlebt?Uq%?I5+usQXyir&zX=)JCJOV`bktL&w`iYMoJgTG;1lESn^? z+NkXxlUH+Dwwu%{quy)O>7@3MT4B`dj5>wXK*&*T?QXz!1EEK;mEDbH10l$0EBoS+ z%Bw&qvW1mhU9RH|gd|_VL&7M7FfH_{Gt#Cc`9q*{jP%tJ(k#D@p|J>7&qjKa zB!5V>zmei3`9q^^jdT}D{t)T2zjNTvO%bNy+nlLTX}OUeB*}$LdIw%2rSLoO>-}0f zE!)$%GL7-=7DtTMJ^UO&xQ9=o-qzgsN|bQf6Uob@g46~<*NlhB{d83|6Y8|Ov zM!m&q{w-^6B(>A1mm9T$)Fx6pjCzt$k0G_0)OMprjk*u1Eu_Ycx|312BDIy&Hlwa% z)SlCHyltem8ujlVkQ;B18Yi{IsBip{+_>Oyl|nnI%|?CFsN+fPAhpS;*ICWgthtla zMx$0+*&LSbBDKz_#a4DS%fiA%H>!;~+RDClnD(lh)GDJ6GwMQ8dq}M?>Q{f`ct81# zawCgAyWFUs%;k8mX4z~~%Z$3f%09@l5mHNydYe%jNzEa(*r-<;^#W3JNsSq`%&6l@ z%_B8x)bZARW#x zH>R@PVp4OAdcT!zX4z6wBSvkuvIQ(#MryWEE3E8kEL%=$mQhc$vfq!^@m7%9V{^qm zRyL1it4QrO>Q+YGkko2YT~yWc9>=@t6y-)8sa;m~4Wqt9Y9pzgMt!N7+?c{%HIdq3 z)H|%~4J_MCs*9?sjXIUo7E=2fXlj@?X zAy)PgmTf1s*~)$bs}mplPMLC}gVZLYzJnY6LcNG(J4tOc>VsBxF3Wb2>Y}Q-R`x)a zO_Ew|WiPO@Q&_f})GDKnH)@R39#Siex}Q;ZBQ+3J?Pl#R9;LhrL{;Cu%ki#0S;rfQ zs#f2@@y=k`KvcER%09xffvBq4sIy27L{(QC^&(OOQPpWiEhRM&RUKy314#`;RR>z1 zmyOi%2BNABt?Umc>39QC)epCGyf?9IAgX%l9r9{1%LbyV#a4DA%LbyV8?5XMmJLKz zGpy|PEE|ZbCRo`qS~e}JDzbtfMy2CvQPr=E^gK!asA_8?Jw%d!gXw#@BMuFpMUp?N zde2CgkmQf5o;A`*B>AJNo8KnWW=;}@r$tp)8tDR(Qc)Fd`ZKBuyXoJ$xAah=s;Eq3 zjH(WnDr_f;hs8+LsA~HaDB-f>dry}mnTqXt-jWX5PM5b|_CC=j-T(47*51KQa^!6! z>UQATiPjNyTXl~RttRUB^ll?sMYK!)fZH>ORuD}ZT0yj&Xt$v;_N zd4_G7x0q!4wvK3rpe{s9z!o6T1qs_qMmcvS}{=d4dp=T29>7o7_I-Y1Z(Q-qJ*;(4oxRNwnI~O^9|7tuyrR zuPGnei8dPg{!KczI8iWAN4$V}+lV$B`WW-J5^XWGnP>~qRzs^;Lo?AfLr*2zL^N*b zSfY(Y+YQ~1XdTfGLvx8%6YVr~L!wngyA1tug^sv_XwuN`+3xUbw;}H+A}`wSF=T<3 zl!w-`bT&#PTUb{)>&iCt2B6q3K)#4Wv@SVFmLrHAi9J(iH_0bx@4RNXx88Y8dTrEe zonEW;TBX+ty_V~>Os}PSE!JyHuTi}g=rv!jd3w#&YmQzcdd=2rmR@_HoOp;%uSvaj z>9td@9eQooYh15wdTrHfi(Z@c+N9S;z1HcqTCY`lt$O9#?Rpip#zA4dw(7M-ucDUVzg`>l zTBlc0tKNB4dab}!ju*@8$;C*PKh8oj>Gx9-6w>f&$I7q`%j|q+uBJfdLL?*zmLk~&`=^@ z)84{;P5bqd(64D{50GH)fADp!z4k@lQpb@WlVtjblg>Fup*rN!1qcQ*k&r~ZIgpZ! zZE~STpAzZn5(m&e%q0=7u89EcNJt{vEGsygElNbIt1jgF?rd!l&o&?wU(2s+eUT?+ z<)&$YHW0xtUHhQkY1a!ak=!tIkmHw$e@Y~Oaf}YbKiC6|v^h!sLEo%%AHL4IJY(>K ztkl~_E6LA<3H5a=_1&N37I!ETzoR?a}P4zP3j{+LgR;pUcuC z&b#fU+oQ@IZjb8njz^q7Ek_BLJ&`<7n3>|=NbB9}>Oysyq>D~;cnj-YHhbsi-#6Hz zlQDf-teo)k@AyuVs$R|D-!oR~ahCG)uf<5Wk>uy!@Aa%vBDp_%=;z-BR%!}M8UL^l zBLBh`LVp_O_@^sTE`;`#@}^x}2$84@p)H?N{t-zecREk`=k)qByqY%s>sp`vRwh81 zjGTqMpn3dX*P5@0PGe>=JLwcFQ(~?mvysPH3QlYodKFRI>Tp(Y8QMf%+gedQu&ME= zJ%l2?A=>Y+Yqh@up7j6gTI+(Z?sT+c)z|P0D+lqEH!U}jyyutFAN9V+90TwB0Os4+ z%*mZU@>;=t?xR+nv8=DN%(<51Tz`&SoS=rguI$S6;$5P@U#RbbXDLK3HKo1(iiRZF zP$WKmW9QS?ML(b8sciq#Ck6EBl+HYgZg!5!O23hav&o_bIGda$AkQXqCraN|NIB{g z*WBAG%=2WfZz~j$`a93BIXi7A+)I_wsmxMI;y|%B<+<_d(-o~E>OA?GimJg&4}}}Y z5fVe!-U1p;NDSO*{4WW~tf0L|uGJ@~t&2hHC;)B5Tw=(&r3Yx8Lo}BduqrB`52r}i zu)pD+F5nCN5_;lmLpVX?%@Cu0d8GEZ8r3=;^}fJ@uao5G)dxmeNRppt&l%~DB>8!Ft-XopiHX{l zpNBVEsdHG$&&v;ODjG=6`*}LaO6|{5j<-6m2us6nyZvrQveJD#Lycisp3W=ET+SwvLtA!)R+wTxrlk#) z{bAEmBv;rZ`*X!=jLQByqzcn*PD>;z`>$M#5-xip*&wrg%CJhc7w&bK&H^9O`I65U zrc8AYBanzUg#Ub0ns-caF%I&NAO{ z%Q+)knKY05oJ~g06bWF?5HE^3L*>RfLp>(na4VyZ@eQ}_{3&w=-K5SL!Ukk007_OA zM)8xJ)i>NWGlM+O(!`&o_}Pe`nNtnBiIFmHbmBi{xQa`8lbRd0JVnt`8Cq(3=q*#U zjHrxFJj2IC%Zchxfxb$#f~bxf=upbP?Z0wHm~$|yiNC2GN9_sTFp_5_~TyD|uoZ03f@xyA z$w(C>`NemckxEGNi?Pf|2a@C$=Z^YzCLDn|HbbntS*dkc$}ip>t@HQlx&920dF&-lp2z!P1ASFPmHH;nHEztj z6-3+2*L)S1vD#anIQu{gyNH%CuM_I?L`#WwSPjo!CF8c&KzU1oJD4}dyj_;J4k%-k zq#+k6B2huNA*ZoqlqGu%9Y?f)sPm&^(6%pnu}EX5?W9L;>3;0UlHPgMD2FXey$T0< z=auVKM%X(~M%1e>sqdX9J(geuafoyQafr0(-_tz)FOX@?k}}a;HTCcqgr=WJKC)FR z2BGj1$vg3Iv5P^p3h;b_MBa=+dPgA!nK<(QuQAAkTvc=@#J4301%eE~(H?MH9O3n) ziUuaX%ZLVCTur_@uYhYiig_zoZ>QCJ0MUReJ6`*c=E5SHG0k=T>p1C?zBi)Hs{4eH z-&MUv$nTH1VZ57cZ0A7(DUOInU-HQQsApC6AwsyCM!!()(5 zyviQq~5<5I5>Aqz1&Xoz25LEeaFMbSrxj%Lc?V#i&tI17ezZ z8TS{NlXb-YWD` zYDwwDdbgFTW+}gTZ@-kCAI8qNq4SN_`3fsFhNYaievbOBivKQK%q9yID)QUe;Xk@kWi28qkQC^|?!*9 z=zE0{$rUlJ(7)K2Wu@v^%C8X(Rb=?i?7UwiPO?(RuvAJT))<2{4wec7G065(MPD(< z4-cb6DhAm|oL)*VJKKaA{ure5;$RH&sOAaAAeZ7bNbpuwqTs3JSsnAr3=Guy&kC074DpP0mJO=_0poDlwElhwbcrOn4Q z5wa)GS7-c`uX260HF|^RcGW2+l7|;d=lFqGgQ|Y1W-10(Y|xI(1w&i=uX6o-V`)LA zSq(w-aZuO#?0FpJdHZUUV*Warf?L;~ORl{u!sHUf_2y(NbpT6guXHvT)aQzH)<*1v z+k@Bj$7`GEY@prZid4NTSERSdvqmm^BDsN#BE`119%aWn_Q~k@D|){rk&I?`{BA3C z3rktY;k4NCu!Yl`8(POPGjk3*TM8R9b=4#kT{0c@fOJ`s`2Oj!+F!@AJUjPpGTwvVyl8?ewC{nvsUn{TyLS%X8S;YWDP=p zGp9ZFhb39FY3qe`ljrXXQpQ)gbiXn6=Ah#2n7%p)Zwp!+tH-N?Nbl=(LrD@`>Na-f z$*kLeWZ-64&pvW9Oun)Sd(IVm_U{|IQxd8+UR`fJ8D7`@sk-F-NA;CxO zuIS2|dL+8gC7N}$46+{f?A=d%LA-=fFH))uuB6MC{@9umWayDaA`ntf>}k86G+t@p@Xbia8ZdB$q>LJeoI(HNVqpz0_N*{v*A37E?o3R`LmS z#Yt4^m9f-A#p{bi0Ky2QRe|_ZjRh94MXm9yJ2t?ETkNty(8W28DLcvsmpV}!{)tS$ zW%;Qx5&6h(ut(*S%$j=$sXqtO#Gvpl zn+3{x{r>HEnQTR2Ix*}Hzkw!y8ArhmDRAhu-}g4;jINvfkycf+Dtqu_B_ACFr?zMv zVc@$1;fQLML}In^sRQeC8l?xgExwMsExsDZ;xNy5b8lRHR{cQiJ&PTQsMLS=7V)LQbT;eII%L`0l7BeUOWd zbQ?+j!T!le(@63U`Z^;`A;~}Z^Nn;QNq#1jpDA6$`G=onFk^(3+LERGOmU}ZzTHhb zuguZ#kteGDF}D7@v2sxJTZ9s^`j_D+k|hJk3wOj!!^fs<4Ic}H{R|(YDhZ9nP8fv} zE<3(-D;1=aXVbR(TWlAnKLjT9xx&%a+9X%~|G{L4E- zhJ_W1hUjU^^xZw|;b+5@Nq+uy8EH95#y>={16yJeQ+AA?Qh-yfxXUnkOP<|_Y~ zJ&|mTDgT^aPeK>cPoy2Gh+9(1ppGnei*aX0yK0^#Xfwx5W=kE4|3um#Ma(Wdp?umR z+;Csjb0+>8(M~RTRSzs^erjDAuk?m!zfYu%eF8k`|B18T`wZpJjPc%SH6JZlFSPGTTX)E@?~4!GuI*T4f7C z#K5mR52Qa*B>d~nul(yf@KpQ}+l%0rYwF}F!tX>fDLqJE&5kzGizI2&YVFcu`0dNn zttGemQ*FI>oi!{L&p8LQW9%wmz{WnDWlCl2NX&|-!Lp1X`A~5j^iDd2k z%*Efk=wI66Z#kX;4le#?WD84FA@>^I=i+bbu3?Km3j*@P!alCc;I?t@ZW=wovp~ z-+bfjnu8X*cH_O~R2f_%8Oa>?#6MEJ`|PaZ_0N-s80qIE`S~!^NI&ePrTqNZ#@f1b zU1g}BFIh&aC&|yBSLd=D53oW%pPoO3oj;bP{QSDzN?puS$~SdN!mechKJ-oR7`W&pj=dG^aO$k* zVitTk0k-YAKiu$_>T$!L_05zDylLQ|N5QN9M=ei%l^L}>1P|gS3FrK{0?|og!<`Ye zOx`gxY6w(;PQQ%moO{%i};rSNPo`m@dPvW+YmshbZm zRN02jhgM84E!cBu_WSZq-Gl%sk$ks6_+A*tT!3teXhJ7O~n$@d#WS6R`hJ8Y+y?Hr1GnJtKe_dqy=F7PjlW%@6E!)R(M6k9vIDV+|#%uxaDl^@{k_W%>`_ z^@2gy!%Ez4Tg|F6C;j@8`~8Av7@{0+g-aPxc>mxz@xhP9vBiXq-s$nm9Y(fE3^ji) zbacT#$ChL*d=1G(*+o#<#K#+FH5A^D#&(o8F_@xOQHxmpOCq8~(Rw26w%*EQZ)I0+ zWoK_?M{i|&ZzVF|J)kmE!W1c}^sr`^?Y-waU^A2tw#~o-{DW|)Obw5yW_EKkuE6jyGjBm4L|j3<^TOv*4Zf-Y7ktw}kYwMC)n@u};_Y6_DBR^rbU z$*js_Kt;|h*@_#gzmf9}t)4Pv7rzx`L}Aa=_1gxZ`jzWylVIzXuFRR%rIphgR}N?d zn)FFu#qPG}uyKjq_gQZD-S+xr-#b&FN$L0;=#unrQ>j&e83GK5qZhKB2vzS!h>3p^ za_Us_%csTYWB|yoNF}-_y^_aoynV(Q+q$UJ^Jv_W1FzG2dxPncs8JLuGrt0t1-Ig| z@FFl|Q5_U2S^beZg>LEMez={<9-yvhw)Ns8VUjWf(9Bpw#acfm+w|LW{#Xt2wd_xE zE}O@&&vuRU1UF(|ogeCFa(>X*my?V>0~D7)k>|PF_%jc)P%D2z6Wz(}0{md=e)>hmwP}xJ00(-%)#!&kPb7==K|A+(yQF10kZ4Q; zb|3DHubI%?$Y`ISzu8W^OG-@H$>oOzWO$h(wi1<^LE_c5YXM3qCx z+pMVWCbn3{XJkYS{FP(Kbt!W}v%F)GrxR)dq#Q)9Ygw=vka7~xNam90OF0VY7lc{? z31@|e+YrJM+CH(vFI^?{fTZl|BX61HZJ1rIMbbAEBdcxRvh7Leo40_tZjP8pA~|Ji zv7n$_&NXU`)PQ`7jk+7D0XhB3s2h_Skk=MQUA>jI8<5*qI``ulYElF8>on>kqz2@; zz^JoG4aoC0qh6%cG`ZebA}WMW)aklN7j{m*Q>;{!rTlU}(n!0IUKD9Bf+{n@sC$tbP?_zFx+$pvmFb0QrBnuyE>$LMVfN0) zPGxe%9dhnGTdMF>CKn1qqN>c;>r`ckB$CIA$4WV{Vdw?-yquTYLJ?VTIafGP5m^Q~ ze>w0N;jVc$&#}I7gYdz9sK8n15~8K*1-&!p@uRhdVxrEcH!*LFsPq3<6O9s$%O5y{ zvxycEZ8vlR(R`vEhDM3z5$!Z|H=?;jyA0ieXb#b&p+8*jw%5B2Sp|e=-FgJEZSEE7 z(S=t;vCTam3!@3W^U9E`cV2~FOZ8f;R~c;Yyr^Ca^qQ|%=`23qjVo4~Irvjl-{aqC zTyigjUbCb^^jF(TJ0{|N2RlpE1W!8QO+)TUZKn%G`KcAARspv5ejy5`@o38ySYZy@ zyk9HKcN)PBIlW<_)MBnR2cT8AHgF5ghJK$3SX1PwJC|L(6*;{Xk=}~z-h7-b67zd4 zIrctfOfG^etgzDK{e3q}#rt;0dTm!dzx{`3v~Yo+K|F*^cX5q%K_(J-_YFg7E01dQ@U z?I3ko`Npj_-EQ9yFNNYLM;tlHl zwKGmn;YPIB#1*aFl|go_9Pb7+qOfIZ)baCXj1m#m6S57XgP&Q5og(GwDLNMmTiSGg zQFoB;MGdm+D+~SD-7dmucDoe=NP~$4S>F_NqG=ax8{0eEx>5AXh|&kWxb( zdYXSL2GkCfjDs5xUs0=H9o4e{PDyi|#Dl^ooiI>Pwd*$NRq9r6Qryg5Xc-kIlG9Zm zasNfQUD<`Atsu1@fn)gf-$;gyQ73}NbhUZtF6C`UaGYbN$4I(1$vQV;Z& zprgoAl}c#c+LkN!uMy@z4gI zy@Sm7G8%I30;Wae-MSwwF$s>=YD^-`#4fPLB;Bc)q*GX)bDeW?XhYr8VniT5eL_8= zL?%-Slu9Agmf)1jQ?AWYWfB$O1Z{l>YzKX8Lk)`OgMo&}fn#bbktqgwwA~9qhKvt_ zTWpEVJQM*GW-*X$fq|JWRUWD#5f|gJ4&Z|y%c>i+@&Po3p5cRIZy?@js1*0=O;ZoA zs~)w~J?7%{6$gerea-dsRTXnj)YpZkgsu3CknI*Ik%oeHW|&<+5j|MB)U%CXgqm(f zgRoA*4T7ITC=g7Mh!94nUSkuGaFf8t{RMf&CG@B|aXP(<_^g&PXGbnY1gx zw7cEL>05lcj0-*&5$=!E^JR=s%nYA5SH~tZCOWkl&w4|xZ~_jC`@xSzgiz;2Z!YL= z7ia5tvec!x6x>XA1-y{?e4EKt@-AdPQ$UH$#o!x?MCjg&#GV|aLYHvb@vaQKYeSQ* z5_0&PWz+}~?twy}ocfVVw{!lghOFJ#0A;ct*;MZbAnuE`vVn8Aoss<>xo=dpXiL6DBwSvnNKJ`JRc(VhvLg zBF^@)T<(d(%tZ;{D)cK+f$q{x0wdv0ZL{f&x8PldKZEU>BkI=~3QC8x_R@Pm>qS+A z)$A|*(6V}Gd$B(E#wB6C9#``8d+=2vRG9$b-QrM{r~42-MRk%j(qm|Fs{} zz0iV?G0lE6Y)s$Ex-oQ2zY%3hjcK(!LS?IvF;~hUyfKZ?WM5ZiUz=`Ckx8b?o5rwU|*^fDO zbM&$e?x5AY)^g0ya4c~jG)3fT-l@*qcxqKzBUDW$lIm{j#qppeb%Ohg5*u|eem8<9 zUfAv@@5o~umSOd;g>m39yln3`y~!azd?Q;EF`tK~ftx2d#*+_*?W5Q;M`tRTzTHJp zo;Judq$?$K$bQQ0YjqRJAAi=!*Bai%>-B>+C(4IW^tmTkk!Ygj4V=<|9A<; z<(~Gb%Y51=>tEoEd)h}Vqkj!w1=l(FvGAviwB1X7q}{sje^R>#jr@^z2mDC85r4aG zwiY(Sw&@2&X`YvJlOqbd2HzMw#*#A*=MM^SS#Ufq3$MjsdHx_Pq2~`^s}U$d7ao4I zm<|X6BROi5@&Gx$2D_xe^K?^1+?giFd3!AAmJ2~90Tj8?R| zS`qIR0-uMIEqy+)Xd=j0HzD(RLl(3Sy_BEPZ2Xqq%5NwNw4ny4js{P!p$PGCqBJ7X zl;;$)eZNi0w*Ejb@MzG}J$Uc$;#k|`=e+rt{2v?q5OCp&w2^wUF)Wu1Lwb>;p(0rN zH#FvW=dF=4?;W`nVgH;`OkWrtzC&Gr29qB=mvV+~hkBdWLw2Y?`P%25`sw#!sqWYk zLgKV%Aafy~H2p*5+ylmSS>z18#EZA@OvMl*C%6Nb6s<2-fa+p{5sO~oC?m;sizN5? zgNwR4l&X;vcBhvGqOQ0!H~lpibp@;Wv>7^)in^-gX)`^`gy(>#+8t#%<&;RiriX&y zwXTRH=PL;}N4aviSChEYEE721aEByg&UTAAwTqBzQT;!P>cP82@*#*wrm9BFM_qcl za^y*Yc-$;+1HY+%{({fTK+RJ}UN84&d!f&4pZT-h*=M$!M*IBB6`D;o!%3<@jWAqN z%JDfDI!D)GjxOs9b#%fC->9Z*a*5ND zO3k^ZQ9XWq|3+0eMwB+on~Gk9<@r=c0qZxg zMmpe(S?nn+Fv7gwf2=nZj|Y3Rtnc3J_22HzrTYFN{|x{7HhuEu56e@$NsGl3$(!B} z5sZt3#8LM6=UD$7U#~N`zX!uTe!z{wT)sU|IF>QTAA(T8Ns4g z+yygbO4<>v)25tlAzIIyT=f^voAldH-h7VhNQXIyfuE-P$%{1y{p3S`PVl5 zC+{JhS(Bf6*O%?)nm7i`QG0IPagn3Qi>dpbsEfwrO6rRG1P4uMmc$?q|XJ zS`el*Lk@9~!;^fZO=c=h4_jY`AVDEEwnh|o>iGu7268e&Z*1$mgbwds0)mY3XA2)B z$Y_>I3pFW0MvEl()1=HMt&-doNp2CfNis*1QnsBj2j1hUi>pL(Z*nV|7IdV}gY#|# zDoMYCjNvu9w%+DLZ*iACoWsRHFx(M^?K-?R4SnQ>UxVC~(BWZy>5gyYN-r-s%Sk#% zlD|Px$AG~fr@!TdET3>aT(ja1pWHf5Bnvd@@n*OtJ>Cq_!a{9B&^5N9s18TY^yKO% zQuw<&s4ob;g5T{}D?a>{PpEl(ID~vzdp?|bW*Q$(K+^HyDE*z{!y%g0<3qkCJwE*F z5vj=I!)98zPd=>bA0Nuspzfl?xx#0Q%J0B&4eo^sSMU%HP*FEEEPJyI1L0TWp zE6kTLT_bLZ)Ia|Wu2#7(8y{$Zl{NU(TPcvLsZrReuZSjjaTwIzl#C)>3D*Y*aEj_ zLnP4)f0nk>u97$np>Vh)Uc50)5~W!ZYLb8bL#gmbiQA9exV3!+;==r zi*i+u7YrS1GuklWnQS)dYCruZ*_(;fQC#WY~-^dxpz! z161R)rdfFM44qbM>YnV00?LJ_U5DyS7F$$1Knp$4}-GFj-x%8P#Cz0;=Z3%cooG3j_cq5~aOL7L1PCQ6ntV!`hovEq0{qG2p(Di@k zZq&AoPG@8Y-W|5}pAP7Z4)$#E%b|Cp{`$K#ohg$SQ^?N8qTi&AYVl5H*6{Th)gM6R z&WG%?48Uq#J5f~sp51V}I*;4Byy2E+sJgG4c2|ACXQ`*$9!3<((6&c+oAKU&1*y2y zXJ1g`K7FM6x__N2eH3$sTy*g|1xqc6JPt^wj5m?Pr{wSKC_3*=8BZzIQ}Vb{JthCW z)=nkA3nagvt5KRxRV~7;TBSq7B}hUvsS{?}>tu?W##;Py@~x`X`Jq}J7(Udm@8B(0 zB+0=lJFaDVt%4Sv9Os>43JtBe2fxX&Mj6;GniP&TN%HnwH#4Zazg(%pG3CNlpi1;0 zv!=M$qWW+2Tbg`wIgz}LBaeicv+qG|=wIIf`R;fY8iVdYBWjGZneIfozX5rn_B~!E z1N8!|XK+Y}Hm)xqp|D&Ad-ut1 z>}8UigCsdqD#=^6_e`N!(p8#UO(7=fa;9aTiAuVZ>1w14BpuVVn;-H8I$W!?Pq{Ff z+X=a-hPjesb4?2Wb0oQrCLud0Y|ly3TfS|`0=f?gmGSJ0s^$m!KJbhwNY!-YcyA`^ zt*pi;7ElgP#o)p)56`;D17ZmCv_`Z)OpZF~tBW%yrr;X%XD9mPf8=AK@(1Jk^mIYN zt#@s>{NY1Gk%+3>L&(WmkCF?ZldC8KyQ@-OIko;cq zJiHT}LR1-yQ*wq3GNZv7vNt0dWE8D0bb#KZAD+a--`7c%<#mo@I)%BF%%b@Lj&;ar zhc0p)OPa-W+Ja~%s`15MIr7Q{QNW8&boLRK3P#`MtfyU)$Ah}Yd9(t9O&web^B{*$ z@@dc$e-6>0X{(ZQ6Qci0^z=23B{o-aad&@PfF-RmgiR4+hbz&gsK&>Vb>;aUeECiL zl1QF(f>Vdu4ug&)grKyx-Jmf%AO(L>8#ibd=7P(pmD5eqhs_i+uTk4-==T$)1@{f8 z7DN9|)E??=HuQacFE~vY4_+I(fO+lVQ3PDt+MPu0fm6s`(ccn{!55%s)rM9PjVfAL zC7qp2sDMy~K*tcuCsZ!b(d9@Vi|=F#5&gj_z?+oVa)_10?=<`2!kLVt^AXqLLp zMUr}==6=3bonh|ca{KbP_@oWGi{}#cDnh|0ZS*Qk#}kQq6~6ZBo4tDH3HR_sqF#kZ zz4L@Ez4L?=Bh4)@i@(P{__XQKjS3CNoEJ{l77ibMa`V zeyV!8+E zwL8%}{63kwZH9;U^#w3i_0S4fuJ6f(VN9=8Q=QVsza1+akd<-LR>osr^=?A?ZV1W^ zFE_4NK2_m(;~b%njmwR_{*O}|zxU=~;~P(R=Sace(2sE<4}nkql~#vveAT1EJ@IJ4xUmG)_=2RaPmod8V<>cx zc2=gyv`rQvUGX~ZVZw|1&olcr2MX3A*js*u8%J8Ox9GvZIMjBAdgBN#JZ7RA-#BtO zjy&n?)T5naf%PE%(WJLT_|+|DjtCjXC`oR5G)vARe71s14GkIg0F}XV+P1rd47zd7 z4FxH93mz>6cQTd;I@$U7RK6B`y8rS}KFxU`j8ES`;^ZCV(_~cR<5M?YH-O<5ORvWk z%lJ}vJPu+S;V{?A2kWpV2p!XGCjWq}JCRk5}~mPWT=zP|LaciEo45w+j+y( zT@j3u`}h9s+&)f?{cx$1RtM_uB**bBUpUz`>x@gw;~sX>5<|;Hfp#TBANv zX{j3DG0x48Ia0^(kaP^KQIbq4twNG_8!^~vljLO0DZCWj7~oDirJWl485KBiYAkS{ zXxb{SfBL;S@bM*%DQTv@{N4alwATl;I;I3wcrL2(F=fxc3sY*FZN)RANJa}A_Eu3- zfl#k&-4g0TzN{RoUF+6QWrSp1UVM}%ap z0H{o$&&Ns+Y<0(#)4POZ6@gsElItCP!M1%BjyE0WGncF{kSi*=+L%ig8-NM~x{Hvk zJOJejRLz3d=vzKW*&<+w-l5@^GgS>miY0*m@{v&u^dYv*(@u=-IR9f2XbDUO>O~clgDj`nyF- znEqZOjyZI5^Zkp`^!FUR%>hd1b{w7^<7sQ$^zbiyvA1Ze+i_@SF45Lj%XP+$S`gYQ zZz9MNkzcC0+`dG!p{Eh0&U#idjwsdEGn6sfwA+_(wz3oRQh7ad*_dcC6-+JWnykszojymMf$pL`zSpv<`(9X1vWG@Cb@2At{g&YF;kf< zLP#y<*EeXtvI(ihjAO1WLTWKZsLQw4um^JZtYte*(pomv-=4J$)Ve%tSy%g%VJ#9k z{AcZD&3g^O{e_8g%YE9CIMkv)_Oz_RXHUz1A7)S7x9Yb&y?$Y+JuSI2%$|nJED>r? zH=r8de6XE7`IhqQ7acBAgP1%$y$HvMI3KExmS_fu3R30V4`j?95(TMd z7N9iJatA@xax2nhk|-7hTu;+(l2D!e;xN@V8XUcN7a>|3z4(iS%6vMxfDrA>_P+?3 zk>yH@vj~}y(5Wt)7vC|gGK(K$f8T)(yLtn)*)ZNl6zZF}NReQDcJRO8dOhu&6g zi)&vJ$?QVamL{m1yq-juZSNNs@7-$9`=d3Nc<&a2-W#N9CEmN)peHq#^WIH{UOm&N zOtp=MHZm{uskYA0ONmmYYO4)Bji`C=DnrY(1MZu&6^0ftFLkT7+|ZqfQl)Ck4BeP0 z-FR)Opp@%WAY{)_u5kvEd>dWo$s&zw$5Y-pq;g#%$ZpA)y zvW6a;byttl);frG8`?=!9uP-sNkbPCjT7xM^nRjkL>ar_{5H{6q8*mEnrI7A7h7CD zKsnh=G;VpvGj9`77hx1LZzE9`WaKe#9Z?r&tiD#qR!y|o>ivGCqE$pWHzbmOCt5+Y z(eic>Ehp;YjHPl4%zJBMwdK8&c}q1fBlGJC6%$fFekGw8A$8?v5sDHj6XPr;R6s}_ zdLf~FLh92;vmbec)Ti&jT)BjzQrGs(l|!gNpl_nef(W5}ffm;*luam4pjVNLfkmz) zSKuTN=O^{$^Rx~)YxweeG^e*gaf>EpQQaa1Z`UJ48GihK8DseGXY|fXVvzg@K<~Ux z{oSG0cD=^++NRf5y|(DJS+7lcZPaU>UaR$5rPm6*mg}`lucdk|)@w|!QN0%EHD9lJ zdd<~qj$R{r&Bj&M`8*TSCA{2D&LvG-(h8dno3HwDz-tFQ1BXDN3)1P38ta)(BE5D8 zymr*dT%;VAdhR+{6i6oTc1hl(NeN$k2fSXErII_~mA>mVZ52IIzvs=p&kUV6x4$)P z-mGcvYu;RSM%ui2F<4E_uA7cxE>4k*QO7Y?4~zrarT%O>EVU}NiTVIy{`Q$XqzXHz#!CIY7tT@2bq1M^M3Y_-xti!f>r>)P9B}CUi-H#HYU!d;qNr+CNP<4L@A$kO^ z&(ACxh6vTkaBzZoLl=;pL7AsY?s#wU|R(o0%lXO1mvg(gYI+tnDDs_wz zO*^epI{Hcm)Q z^%&-ABa|mC9skS3%DSXO^#3p;XOPCzW3=H;=dTMp8&$9mW#8B_oH4{9@nAi$$ z6wWZnOFt0*Agb|szXRl*E2*W@4f!%WT|K#_(p7|H_2fLwl|0WR-Y;%udpvWA_iHog zFom4=Yc({VsCmB@L%*t0OEvG;Z0I`7Yu?ZKnALk}Uh{s=$8-`k?^kCvEZ4(57BP8o z;r+}@??)eVGa2+gy`|OPCA*5(%msuJdnBQ>$pxjfVs@k zLDv(>Ettz3o%)!!FV?}Dqf;NV`WFhBqf;OADUK2Oe9Thh@U4@c(jC(YHm zL{C)N??OF&98CFt%g+Q?NyQL&A7@!J_Vr5#B5&V5BpCDEczmdZU3qPoh5ZeoYPf}s zMKwMPdrh7LYp9KBUl9N8DbiC5iyE|-ev3#J9<>DqZOB|=VfhBVTB!xa!txCIU=P)V zD$by}hQ379EG);+Hlk)>5kntcDWh_WnS8x zcN3+RD9z5hk8%r9TAp_+rEIFUM&tADrku;Xw7=RWYps+hV-4?a$|#}?H@v$k2eZG7 zIJ~M`*+=iZyD675Zxi!IEpHX`HWDo`w3vD8h~^u*)rH#MYNCw$@em60RuRp$yqgfM zAev)n&v31woM^<*FXhykx3BL4_NB~Q%Dh>Y_c5ZyL|xe4Of*Kc+vbgHiAISg4V_A~ zfM}PYClSpj+G*%S_AHNRhoQe>-dv(?KK%vr<`9ir-u0L_Le$Nw-FeD~Y@)4}_YI<1 zMBS{~e7@%G`Ip`kYPP%&GH*9gH>)-gO%jEZRqMW*Xctj8t6nLm$MB6sqScmn0`qn# z%31YLLhXbq#9!nSiW4dqXgfk}gvtckkWee3Qh_#Lqb-Dr1^QrD9bYq{m_UD%GhFyo zBcZ533z@5tkj|>tRA|9ELOQE9As44mol$Q^J-$0Bmnv1Fz#OUaEUgmLCc?*)Sv{8d zvO~};~~r=wSjfLoGRnCs9M;0q&9Dv<<9-2r(kz z2G(#w3`e-TxfP)@$i~^(AVLg8U~6COtai%~gtqqi`!4it5z~7`bA;L&HnOk~ozVY4 z7WyD9*}FSVk?nc?=v(^3uo+S3T57{~M}=xbc6FFGoKxGEHmn$zrVXb&q1vG0e`+VE z4J!UPUQ$kNQ1SmBRBD5Yzfm)%#9z&{?24=S$DSpX>8U04u4SZq;xE>8n)rWB$S?kb z^hN1zS29;5w>5In0jrD6)+AQe5c~H#s@P34nkDzggs2%@ysS_tL-Z>4H49zrAHtUU z@$|FSi6%Cqz<*>Hvt|{T+Hcd(FA5d*HdlrTySkb0Qx03Fe?<1sp@@oX0V$f-E(izS<4C~@UqYq_EmGe;+Ioh}f>Wb9XnD2|QmUeqv=-Fx6+#u5WpS8~Ml}%#rw85bk=FLS z+jpr0?HsK)2Z|A_Y|V4de8tM9jW23#e> z=*3Afa$U{)9Z(snKob+m`%ZTPER$qh%c?z>N_w#zGowBfOS+kK(TA9%8<`e;h)TLz z(@u^B0-Zz1_fDOvf}`sA?0@;d;^3 zXWI!gGE_#)e8Sov8;3$kTQ=wKO=YSGDpSD6uiYJ~gN_JQkzFqhQ<3Yg>Ptob8B0@< z>Up9f+=E*ErYoc(epizz7ydHSo(q3qTXhkh3wVfh&jrj>x)Zs|cLH8*=805H>l)tcMjQMseEGdv{(bb-T-&O@8Wcc z#a@jULhvoB-rGa>xhnkasiSUlZx3~1lQRtEYr+4l!$SGL@}e;Q7mL#k4VC8?rtyFD zBg%g@mgb+UF?jRk+)k+^HD6Yf?itI~q?9QAor^?-zKITiFMT5cn9@$O*I!=fBf9-_- zjLC{Q?u-fabR5W>p5l`G5Y5d643hb71gY~Tsh4f-k}Zp^pY$|ntF-m%*1{hDo3ajK z&*E^EDv*bf!)I=DHR%cDMlH_(<{Bk=CnT#hDR+8Q5NBvkc&xyiu+mL!B$?fpsYSqP zFF4unQD1QK^8DxDWT z*&@Zxos{G$>dPR}11UG-nlpo&A@jocnd%ur*=fv2De(@S&_Q^D)T;>lcy@JE)N!c; z!u6hA-Shkam()+(AU<8acktQO?+!`h(v16+OSxk3?{A*QmRFHlV%QU-QTI4WoRas#*_?_1Q?%DtR63>v?fdTs zr!nPxc^){mVt9TtV+8kMUwp+y6%{i0`$6@s7#>opC{USDf2(CvD~2nXmhiDy=;t!+ ztr#j$95bfOh*6=BQ@WeUU{!ejU9-5EEMK5J=CUYIReo3I@~;>MGM9hF@Y$v^G<&=R z)6Kg~OB9bDG)vt}0ny2;2|T4aGECqjq6>=0^$7o!@Vry6*Vs2eu{ zPKu=2;3+R#9gxkTO7d**Fpwx0wZUCLWyspM4gOl+-xvJqi1MRf=V6~7EN%E>mEC^l zVig`5`Mu`w;*&;ALRnJriJe;+hfqR-6L%gqD7WDYed7IYN?+oQ__HndvUwp}Y}zW` zAM5ub<;??~h|@gEvu6cF+$tj8{d_0lphua7YJ4KzK^|O7or|m5L>MVv!8;c>nGhU< zcP{R<7o~RD9rVt{9Zd-C!8;eXhZZys;XSLAry1Q_&bqSD8}v7edFdy-b8+A6NgsFL zy2J7=|Czc5dJFHg%0i;tV(<>Ev=F7+@XoB<$$F#eOuTb(moskx(H3j1ih1*iHXB;Z zym>_3-L(UW<`TsMOvg5qXbw^C8^Z{RMu=8h-kyzhY}ty^tAG81FuOL3P=#>o142D| zACPBO7O`MAp)$#}khzkCN(H))P#2+Mfo8B^C!v@?wanE)C@N4HbF~wqw%bIul(r?XB!*S2EcH1BoF zTx4wUo}yW>fkgz~>C*-6qHhR#yj|87AoOrFuO_A??or#i2zAi6(Xgg4Epd-pRk`MO zagSP62_f03LN2wcd@befe5h6J#atHms8wyqTo(7JRehbU4uEc~P_62#g!I@w51>}{ z3UkqcaenS#E_yHCzkUjk#-OmS-=hSBLA9<%tw1=e)-_F&8P)~O{SUmM!+$Dtp}u1? z{F#B&+*q>;yy&-TE#5m+wH`PPY|Bus&CV2NhN;$NsKz%jt|w2X*>=LI>ziJY)svq! zzLL$OLDee3<}ph0R%s(N>1`(r(VQ7<4q2uB7Slw37rhrQ^%?aUC-vnbCi=6D>NDF& zf3|J<%$DcR_T{9$8XfG<_M&FX@FeAW@~q$De)X53;$8?hl_~C>%li`db*RQC?yc_- zao6%JVIoJV=A|2{ z?ZK2JGw)R9r6;NFHnf6y^BJ!s4UI9c#X(($j%MCm=Iu0eTjtFn+F|H=L?cAo4ecJJ zV`Cgt8#nX~qFKz_X6O>4jE20ke(}Z1GX_N7S-&RcWlZFq^_#`K42!(8erGc;BO~vu z-vpuzj=ZyeQKF2Gyt94>v0jEq-dVpbn3qwKch)b$ysa8Ld1w8S1CfQOhQbV6)-X`WPHnfd-8;QmYZDig$qESOHC0b3iz|hl(RuRoNw2bvu5an71-#=pB za-zAGcPFA{L~{(?m}n`{h@oE%&=D6C%{KJ&xQ;kRG|SNEnKw$b$71MbnYVywx1o11 zZ$8nap|>z^9?>pCFJRtWqMe4GNHmA2Ta6q>G(xo9@{VG?*+k=p4q@IbqHTt*L$pWs zIa9A^TAihQ=qAc&E0OFZnk3q6H7sAG-033fRwMT_ZzoZ=8fjtP4x*T5)aGv>+D^3E z&@)*>Tv3KgXE0+MA&rPe0MW%*QCtFxl%{-!n8^JdL-Q>ej)3sU|r3U zyG#qqzM{rUM{ADIiTwZmiUeonpn$#eTJ+ki*CxF->a|X<)q1VcYlU9R^;)LaQoR=I zHKy07UJLY^uh%@i=IS*^uMxdw>orTSJ>cX5-B(&=aEY-kqD@D%HDla}|8?WLoy?RZ0(PIzviuPoBo&CR-!E<5MTv@o}xnDnDop8QiT}3mwlJ z7Ruetj|<~&)roy^_q|=xxO?^u%H4A5cKbKR5iZVOXmd`zRH*kVRe7(o%SEGPPEFnQ zzm|0GuK%S>%UWM$b*84>T3;uX;|MWqr(sRdM#VgIV%ZltDA640!!S+4?65in;%rwk#;v^ry7f?yOVs&``OK zC<&8m^TfX7x&f;3Sm=mx$#tA2Dc7fdklwo89+m4}tj{mkZ58@Y$@NaWg&fW`RIb5$7F%{n z|LpAxuR$Ta7q>_JdyQY5A2P{_p7iS;%&)(aM*R0+?ygL~2eXal@b1BEE2j)X-$`-| zx|ntkMh;Nuci8aqc0HAZWTbHt-|-h5ZIx&|&VnYQ*)mVd&sZWF@%_&6{m%9M#$0Oo zVYo%oiPR^^(VE`vb7wgkqB$8zB-kT^_h(@>nPqiTpoVh1c9d;>nA8;{k-D|Z;#7A-2tnqPs-f?IJ}co7zBi|WRf zWF=1>nfh*ClQ_J3(H7Jd%{K0QWc^cUW-N*UfN^88-B;s(ZPCe#z>cyyb3WbVu&>Ja?-iVdrXI5B8oP3-DGy9J2_`^7y05JWF?9&KczEZQOy-)L)Jaz@Bc>6CbLsNSzXf_UuIkH4PVOgkDvi}`6@bB}{k+I(}U*WA?D_CM6- zIV1i(uelk!{FAhK*?AtfoeckzUh`oDR=#;3;@24};5Btd$Jiam;d{fP)%9we4XiQbERGiy#9?C{qzm&r5xc}tEl=w zn!c8iH4n_m&d6&tDDh!Z`Y=(}UR1uBm!bWdB{}x?#Eke|y+;g_2x55&%gk^53N?6Z z3)IQ)QA^|}f&SC)50Z~bYaA%CUr*N54YXuK*2;Bl^D%uf;&vmY*LhyA?d_4S+mp51 zv?z??AWcHYiqMptgDdPh0>kP{-_o^x^D7E=mt(uugV_$ zSjk7nz~3#Bb!)QqK-Ds^|LIumb5l2oH4KV19Ge}h9}ufQIy=z!b(5{-=-g-$iHFp1R>jA1Je`97C`i)Ig-3tlUNtS zHO^#i+o5R|@}-1$N1YDxbcNDp$e;YE@!>S6vaqc<$hs<=q*H4TvGi15 zEe`dYH=m_LaeVJvyRjH@{Mu^UMv%ZF;=9vCIH?w#WTfx9=LL~uaj(VWLauNjtX0{} zm??`b?fl)x!*;cv^mR*}HtEeI-YO-+%-Y&4EU41fGV1xk=0tKhin~3WdMSf_CCl1p z$51T)YLSwk9UBW0V8^Q8_;eL|@7n=H9qs>c{t3cGZ92?8~>X6yD94u^s!8F6%oBS#xGw{qp!1x*o7zq1mjWtZd zKRUpuU!fg@?MxU2&xruOya zKDfnh3&|I>Anadv&4@YTs(q1#>m+r!OF*X1R31W3p!K}Bl7r>io0W1jkJ*Sm2-&;<$jh#60l zPqTwA@*Lyu<3Q<)g%CSittfb@SYrln9t8?sOhIdLseVVyLg23Qed-=5mXttRX>7R_ zH?>iSZ26rGY9@lFnML^LvF^|QJZI^^A(RyB{)W5ZA0O*61W~rMp3%pM_Hpp^fnLsZ z))mN2b#YQumy}?45JG)lf_?pa-w0k*!IK9=rm;S-qfk2(l;u@G!L%|AMJ2v!f{$s# zeM}RE_;qQDugR5@z%k(}{&^gm=Ff0YK+_(@M^IPp>Z=}Ar}6t|N2f*v-IBm^Ten%X z`N$&$H3fGG;7;y|%$#F|HEmTT$~^#7_aceL}6I=8D#=%45I+WXGEwp1zO(vl}2G)SkU8KZ0x%V-OBSJ{OEhn$EpYd{jsgnJYD9Ez%BoYn^;e>UP1=_$m7UvSf3s z!-#Kw>5-PQG`}#WTLT{5d3ZTFLdy1Qk~>5z@K17s)itC~!0Tfy-ZD_a6#R?gE|N|f zE+lI3?lieAd!2W%7J(Y3cSZvu3x=+cZ-M%Pq05+-R{9+bC50D<{L-Dq5Kb3>RqX*i zgm+crTA=z!Z+($`DA?SRc#`^8v9=7DLbj*{AGPw<+~M_Ov9CL_X-2$xKbpAf1g{B? zsoor|Q+T&-o7&c~(qHw6_J^Y0LYsDC+mrP$w(j60I* zR4U$sP$_ti%aCR~vjcIF$!KYX+bQS-R%4nLb$iz=asvCIxo2chZy;66Zl+Yx^)A1z z&lXtgL!^h_V*Oz&WHgA#LF?$0pRZzY$zM$L*q$1p<9kg!A0Db3QyXs@>ZZNpd`$F9 zMh?H%*2n1cv^DiMI)dWMg&Y3S=SmLU)x`Z%9fXDu$~GI*c0V?z@3mGPQ!j>-oOryB zNml);O3oTNET|D$jDSf!avyYkT{5lwS*#&DR`W674Ppb-ozThlE=#!)zw`MCwWRwn za}D+Ad%9!kqtg)B3QPi?8_5Uzlj=si%_FF`?=eXc@qx-2SpkJ?O}RBpI(y)DBqCNf z|00U_HGI^*N|)R+yPy!{s%3VDw5;ZgXcn_$W2UCGV11S=y*){v0YF5dp_mx3#Df~f z<1dW4p{OM`^OD^8IziSyn|%7XZ+gXJb>OWSFtSceW*wLik3+^zwR#PlRH2?%J;O!@ z+L<8kC>0-07Jtu8!mITs#P5PGExUB3WGHMVT-2!jqVwEEJzEK&B9PHt!aLF7Nw2ZI zljqrmBqKrAnGymiudZMa+M4ce4_vvo^m3mPXtCtivYP*z?|OTadtlJ$eezNLt6IN7 zDYX8y399uHt^_mmOvR??O zI?*9?0Pnwg)vYH%)&YHdj7p~)Ig}X{a_USXVifjm?}tl zQuCb3Et=7iRqFM{?b)Yf?K_(xl1*tVYZUo_%h++JJJ?G3$l;`I7*Kt5UJC7Xf%JN? z_S(!Yy*WK})VJb}F7y;vYEs43(XZidAl@Ak2md<6*f#HQ#s(Rxv0Z+Y8XMFY8?#@& z?6#8QlKbo5is6aGp^KQUK&2hRc&YfQHw!&6ix2PTdy9jBk)T0*-QhBE)UvHcCAyGl zQS-HnjCUE++|J8JoSm^sI=KdOt1ZDj$30hO@ZaaEkAWR(LHoc zqd7Uy%qc&$nR>68AJ@txCevIRVQXU%R-Je!T{z``+BWjc6&YFb3m(Qmp$JW26 zt~!w%c)IWhx6wwPIC2ubqj%HUMuYO{J0KWMBP!BnJ{5-Q?j6&|adhZ6MmM6cT}OlM z2pvruMuQMgM}xW1jV4Drc=Zdya`YF%xd^{`$EZOWy2AgT!N&s z;Xousg=E}vTAOd<8(aUeZmwWc;v^k#1o!4Tb=OFGW$k;C^a&@8L~Xudkm3$;AW;SwduK@=TksTLG| z=_qIFYg;l#ss1SSD#~3b{oEfN*^kRV5ggg5!@ZHkgo}@B4xjvI1mq98PyV-n>^oR< ziBdiJU#?V7{^w|2XFrF=3x_)PHWq9zl8(-xKuf%N!t2r6f_-3+C@LB-m%9pARdsZ0gSx)B}LOzwO0Q{$P(GpgPRd$9#5N1zGY~aM7Exx!S)LJ zW}8fPo=4gFXju8iQSdV+0+IwMTT#^mD%DBaE zwPR(KJ}qc$a1RGj5S$fkVwb*mVk+#=X&Iq3CU%+7I#DAq^@L{?>pD)Ge|U+rZ*Bfj zoGhb#w@Yts1eJ0|S-fdynCo08I_G99?bciVZe>nXReiHGLxr~O4%Nir8eg)HF!3B~& zN7HF%P9_4PM&wD3NvM&kpDW3OlqwpL^Z&5-HjH844tNGiLu2VjFB=%Xw@xB zs1j<4rKBjql$4g#D5<(5ohqT0Q1sfvFk(rimgy~R6KjLg)Yfb5r9~`5DDr!r_xm~L zem*xhOMQo#@9X>fqv<{G^L)YwIX#|!7->!(AT~`#M@f5f0$4NbbSz#Ue|ZV z^U@vC{vUtiK6*sk*8`k#N zHp`?KBh+wbG|^A42r0&a`W4@{dzNFt+X95rrC@>p`5>!!O5l_RH< zO0>eClXfH^Q;cY>5e_Cw5s$_U%_mAJkJcEvjqaoO=b5;Z34WNPb#(WgRvGO_M2mH$ zGIfemGf@d^RQ)TorcV)y5Gq&bK0<|r$`rbRPywM*g|5FCwaF(`qR?1U2(~_qYt#W)IO-rsO-$jzP zPFJ$INN~u(XWfULrNzYfv6de@dCF zhAOVfJ>|oAr&E#~FS#7VwFHK$G^={er@6uI>w9QgeH)lw_4>a5WT?K^;Mfdrq~=R* zhx#rbC)}PqZ(OEUX8+v!?iQ|Z8P0j}_1z#-eHZz^_o<&z-@$41tz~-E>-*~Cq52MRj#gqWk>7gB?NHylgY^y1RHt?^ zx|wOWwM`Z++>XnhoeT|i+8ys#FWYQh_SQYcN^{mJPixrU*B{1h4Ll(HmOx<THes=*G*Or%o|$3jHw{Sp35&K1oMV9N z_!vn)+-ef)KnOM)NgsmUhqB1oTUl$S@5^;%1jsXz>L9Ah92c+(XoZI*A+iWc-<1gRAjo<1j3rfO0KjqU4gX5Ql@mcWj3!oP=lLrXdHT z^dbk&CP4`HVZIt!NWd;ktC2 zxoAHjinzp4bxfOl$CTt2f#^3O4p)Lg9c6=Cp!m03m5{GCu9K@0f*zJ9eRkTb=^pm& zH#6F|rgfzoI@q_J*VE3)WZ$lrVgmMU%OWA1>TeCd@Ihri>|34e>`<;vkSlu3pVk_5 zB&pQC#S9ujDz$Gl2K@n4&c0O}`Zdk~a`vst(A7xGZuh5$uJ{Lpfj#d}4}F~|JKvuk z`pOusra4)Edgy(mr4;y^!mlMtL+5V_znCa(U9{M0Rz{TO&fgS%1krrRWYnD=I*2HZ zUeui)TF9Ew?nMi%+#J%<^hNUxU6-`kEZ3bL`oRO>Ll#kYdgy)M0OcG?G{;J4AZ;sV zR{RwPw-Zegb*G13K{P?M&HP6d&K{4p5N$QIl(fx6Im6eOJeX(`(S*_dk!YM~i=mqn zZ6MlgXg1M0qD_W=c|Y1#OEhliXJ?_0V?-MaT|n9zqH0i8Y@a4=HBm;hjmeuxTSYWx zw59*T+bW6D+RFVeq^%%YZL}ps%ZXMQx-Zc(qLqdYW*tg_(&TPT!V*F-yK53ECIr*_ z)!$K}B0{Cwo&=!?Az0uS2^A885q_Ld0U_Ao**NbznolUAWnD|EJVG$V(@B*}s6eUC zCRGlhe1-P-+IfgPO&%f?G^jAahoKBHI%0kYAj_|sZiS?dQDA!eqv#HvI5pI2A79lz zzVg5GK7;@4>7hCg!EF@@?Scto7)FTpr-uiE%CHA$U@H8%geduS&1>uDsT5Nqm`J(Vs{V^n|n~J@$mJF3RW$|Jhrr-@y}Z zy^c02lPA1FiV1kajfM!}RDbhId95}Ap3s@9k%V+)>Fm@A+&-k9Fm6h}2dUH(It#T8 zAm<64h59W~Mn8U_u&5QPZ=Nt_g}!$WQ1gV&LcKuLJfX8tvxqVh@?(VkdSVW5b%nHx(Zo-tWb%v zR8C-_#v=J&WuekX5I>v))mQ0ESN#rSX-Z6|8dj%TeDPh%^WX?#*)|>y4Tal!j1U!wBZxZ*QG0ks>D7d&I$W;4m=N_w1mtX{sWC%i+JfT+3XC95JVizF z-#>y_U&n^sjv%@|u@qhU_dC+Nbp5Semr`k`fI|DTL>s90>(J`4OU^`gYRkZ%R`@Q8 zDE-0A*Dfm5^j=82E<%57FHm61z>e|;iU<^RZRDyJ=IZm`->$?Q%zq}o#Wq>rg8y$4 zvc83)HUSFvLB|oj^EMr~3(O*~J8TySZ=RX7f>C#;8k9a-+vTN& z&*Y<$FNS>7d3p*;>SD4NZbNVAnzjq+pD#rRs*h?j8-F*c)JL@%bj~MuP<<4AuYCUj zD(9mTMtCMs_JQ|}M-pW>MAZOk-wh^8E%P37FI32_X~&IrJn%{h5=jQ;)DA-O zzsgUx*DD{}>y>rw^~$aGdSy_1z4D~JUfCe_Aao~LHhrmTQMxaMA?WG$@)HW7e$B$I zxUzWx)3O#XA@{0mFFz5UR67J#?!8;gE^<{c;=OQ#zGa@|a=|maz5E5*Hn+XJLsUTB z@3Bog{@IK+?SSty*|fi_rORm3)|X-eareyKVbh!yX}ek5g1EcMl}W(PuZ|xbY}0 z7$d1WNM+^=mg9C(nfZd{m`Ex!U$7hpe1J-r`GVy*MyLXo<2WfN5Ml3$Tw0Eu@!Ln( zo1=IiVfRI{gXQSxyMOI{ItS1e#H9n%Z9xYO;%!+y)}W0SWYnNFzRjdTXZ+Ba2E8&r zq(LKhg$B6`xMtnxHOO7SRnLt=szL7dt!h%K2IcE1Eh3l4zJ~`@gWSDaXM)OUkh^#5 zNTQ}e?%u7zL`{R-y<2nz5ysB1b^?=J46{I_A(}AS@2^8E3W>HD`T@}b zqRvw$j->n&bGsC%_Ztw<`tyPA?m#5`9!mcId4=%H8fA)K@Pt z5_xc5^N*x$CF;E9=0xr0t|}`bn`nZxm4>dt`nK@YCV0)I*Wy*pgb;7PK!|sC(QD2o z6em@w_SM~l8VHprG@Vc#A;jC)$W=OG4eY`$#M@&?6(beA=ATJbLkM2;KvGo`g4fJ> z8&$OnyWlmq6so|mcN-~(^Cr1kpVd)@xJH?F_;$MUuQAO^BIyIcC6eUaYUrboU*BuW zomCl;8>hrhM>8^hlk{H?~{D*Ua)-wOOK$KNviEydpw{4K`cBK(cuZz28` z;BP+u=HYKH{^sCsHvVSeuZrt0ap#uI&Ff~o?`$*P;xoipOq!=2H$9L@pIx9fbQ(w0 zsU*B}wRU}Qe(u12qIUfJ6Z-HZC^W(<(+B1hJ0XJ}+$y=8yn+s#^@bLQ**GY`C3rYB z)iX(+mVBL!gXo{cd_UE57}BAsoAYauD)OOgGR)li&L zxO$E^lY|&4a4@t?cZGGFb~~zTCD17#nf}qT<#HgDCp_AqT>2=(B{FG|UJvHl_CZC1 z-Ba7wcMtkwGf-&vpg;1Y8MFcDkM^s={qZ@|60^5BWYno2!X-^0* zJ5`kQX}H?QGX~t#muCvN+gdvdxJOAbfg$S({W!}et&6Vo-BzRwIaoK0aa#=3CZGA* zZRn;QC7&GtSFyHavjg(=>DOO(I+~}+<(ysf_ zHxB^ne1zpDMMua-xRs(46{>dfnxX88NV?HV(}_tddSbQmQHh{hT)nPWiwb?+nxIg% zfDv0;8p$?GM~nZv!f~Wjll8ATewAqQImrzgu@{DU?xQ#EW4>3Ko0#@S>~BaruAxUR zAQV)ZQwar)*x`gs70^3_3DHuC0{wyM;(#&RL?CuPI%sp$Hk0zm?9|a+o3r+MeRq4k zzD~@VzGe87Hs#6vI)3fJ>VdGg$9h!ySVlb>mdvC_b)R;oM;l8q0X@1?zvZ%(hxHCd z&*?63xTDpW_U7+Py&@stj++1G<-br{{fguV^y(qW4(QdzuR1A$UQI`?*Q@JMHub6k zC|qWvT!1j8frFZ^5KPAv`S}F z#%~SIrkUvGTZ68o3~yb_w;*mUD3_tLbah-R0#W#|$}4%1R&3dU5Cs*Dh^FT=-<#M* z$q$Ia-I5&;g?o{!tps~+Leh)E1e8TlIOt_BVljQsNaQ)ufE=8Fs)RJyt8Jk3L+14( z_IwBPikPtHJ-_hs^qwzVE8O!B2t}ahZ^Z*_+BL}XJwF*q-}B=@*?G^OyuPaOyi7gc z^ZNJ2OM;SHv1YjbpZ+ye|E*rs2DARJAj{W(Ey-eN3(0*{a=Vh;7WP1<`ukHRdgk2@ z#+!oP?UCMIcq>$B@J)-feGz0^aQppa|)P zg@*qV@AkskU3j;ies44VvUJ_~VRbKixyqEWprEi_Ap4{!T`*WjOBU4%!gefnQH7KR z&6E#6?R%RSw@9f=r{CLfZmLsJRd*5+x$%p_ zckJujsb3VXCM4417lqHlgC;=HgiX$z4nntu*G*FGLt2WFUlbllT1t{%6z)%23X@;d z`SDV1p4-CfCaIPYEfV)BHLJ5aysx{p+{PupdFlz$7Lqn*w2zUtfT)|Kx{9>ma^J^A)5LgEhPMqEN|G8y4CzZV~DB?Rry zB2|)5u|D`|1g%aGf-`KI1g5nRiYQehshSBDDs(%kng|srbQPgEAy|SdGhv ziooEo9JyTDITgRvZpD;xKa{0Lu2z$OM6!eCd(Ze^xV00`I`E;=T7MQZGijb`Q2H<^ zeeQ+=)wSksRhh22Q`>(M0oEYLFChMSi5ZrtldvBLJIhm{eEkebbq|oNrINJ455(#z zd0x`$9!iz`0jAYGK%gEZy}AcT(@dnDdw?`uh)0}zfHX}Y74@29*ds}0?g7#?gb+2F zQ$G=5hMSZsMCVEc*b zsmF24k^@j_9IfG&B{wIe9>*<9t^>$<9Jez0uYs_845y=7biC$N@wIh>*>dG>5u&4T|RHuP%J)(|Z+bQ)=^iAD?^P1-7=g@ztR zw329np?eaoAewLJ?ku;QXr7^cNLxlU*U)b#pv9#`a}0f#XbI75L!T#FOf<{TMr=BY z77=Z;Xk{j8BSc#bok7|{qDe!~BW(fEgrVn*BtNq~)4pw9?8wov1B4!ZYv7$8FgW-gyYA8n`Y92fZn&Y}v6?P5CCIvSmlO z>1;x_>EDMGgFSg6o_gev(UJoOEPDhTB()nx)P(1TwZ zkEEXxsrZvJjDG3Q@|zK2OdlKuN(}>RH8}`HhrIKDbIkXDXJN9vUL`<2r;@*EiGHT?ay=@V;Qnp8LwT463$|uP@Z> z7IAWcS;sArtD1s#fA*y2`gX65(%J5B&r=>?T^2gFjA@PP(elMecWk-qCt1w#m(@;T z`wO~lzZkJ@+K;z}+W)0*f2k_}KA?~`aImqjZb}O*FXyG2Ax#C zovr6;z8jo?rEd#FiOAOyUP4kwLtyF4a!C&*D_3*tkjv5Poh*ytBS)-P6JqR0#$F64 z#Mo6jcyJ9eyEvWM;qhV*R+9fUR+}E=^@(4EdHpIVJg;9b2=n?;WT%$$D<2Q@`da3D zUSEcEh}UBU3h?@5Bt5T3%L@a%-XFQ-bs@_N@;XMh7v%MNp!)f|Zp9#NUPfMv9mo-J zZj)t`RuPU?m4;lI@$K0?7*#tcFO~W7AdVGnT@L1JSuI-D(dEibt$R||MHH4-H6~|# z`%`=Rl@FHnv`B_zVFZbq3I6kMS=4VjMa2EJ7YTj)1QkAvlarb}0ZE)-I#FLPv-Mrx z_Vs(vOPj*CeVwk)dcKL81#V>M=86P~mE1k2Ysk;ccY91(Fh}Wo(>l)^uIfOM6WEp*Y7L5Uv#GrfyX!kh<$GeEBDQ!jXCMGmmAP}8TF^OP$m7OUuJS2k zMYKA-9eKgnQg8Rg)jsr_-M<_Kw=GHQf0OxZF*ghp@5 z86mIJBa%nt%m4ZEzwoBGK>jb3{|l?N`l)N6dnZSK-j=#bS#4PcDQH8xr^rk6sua-+ z_K^P8ehA!dqfM1=61DMn;|wR6GRL&FSSH`RzBp}0_nN#!h2a0oOQ-U3S9kJq@|<5z zUUvWVSC^OCGrN(Ow}s&U%S)&7vj2tM*q2?O`sL)M_wrv|Ub19krn4`8m0rB67{IQh z;N#2EBeQwSd}Jo(R91V0A~3$$5lJ8C@4S6#DBTxX{)CJyBsIdS)pEW#-31v9?r@?E zI~hY-czHuGLbXs<;*ux+mhOqQ`_AYe9~mukz@GlDLgK?YCk1Ozmw+X4+s9{wnabja~pzyTINK~SV#^g52 zd4ypmZgQK^!sL4LeU*P!#3LMm*e!T1`uw$h^!Z@)-!x5aqab>Dokp0rx$yPV0=3CO ziO6hBzSn6^>KT=Re0eD8_0sO)nkx@G-IChO(z$zHptw+Trsh(I8k2A6tSEE(e3Q~g zd1fmVp^>~aNFq}i11wDTQ<};1^4-Oq$^nFG8UQnLmaupS3uM>eiLp}2JYPxZZe#MF zTBB9FUGMC=b)@E^`tk-12j{-GhTg5`FV&MMy0fd>IClGTv@%63BSP!8*|FU(lC+!^ zpt!VxJ)3bXXuSJkM8J)?% znX?sE?x{sn*TD7dTHt^TX0r1YlccZ!W`7N*9HskIlix8uPhQK-D5MukvMe4i$kG)4HLz;ZwDmIBN3 zxFS4Zo@xQs&*TXimM_1M&xkCDtCce4MKTkM*Q>{ndLI?D=eCo2cT(he!6LUWY8FA{_?^yEE6Vrrzt!I!i%dz)G1yFBV?V%*@s}utu7a(>XN1?bxQ>6sokvWIFlwN5}Mp$iUIYRX==qyjHfj+xw$9Hz*Vm}sQyzY*RU!5G}d8jrk zCCf*I%n7ukjSpsQM>14scU4#rpf=N=vaAIn1=0;^Lo**H$=$=voULq?S;^L{@xRff z@vM)hsj|V;ie~718z#_%bbO1zQeb29E17;5HE4qN-EomKwr>7anjY{d zp`Lh4OsgA4mO}rj4b{ZH zqx65BrPZierq7uc!^ImVzW9OMnl^N?aqBxp5VbFuqrqEp+$U03;V>#HcQR{kT+7-* z2KJ2U6Po-1Ma>l}DMh&$^!rlnQn_mtsN7NtBB{<%Iu*MUe)q5xg6~p>2AYLmyU;5wg)|kN}kLqJ2}fV#u76tY{nSGDVOxv-qM&1Ify2N z2RWT&i?^GSv%G@2i1$;(nr9I8?vEtPmH#A5Eaeyq6!aD9ce5gT;rO)mS0~kKd?s9D zvD=fM7A29reSz_u)0=?B9MZ7wod;&k-d_F)ujfQmMmMirC*A6qO4pwHLnm5jGwy?= zgVXg~xGe(>RgyO0s&HRfWj}Rbq}jo%)TgMIZ7u3_sm9q`5spxVCq+hBTolTG)O}Q(XIBAk^ z(c)mAux;-VZiJaIvvBt-h-_6v;>y@fK%pbdCQTOKs1NAiOxP*qiZ<9L+-pu0o{5Az zn`CorVgj^B<>8FuT)bn;8dWXnP)8=pGP)dlgquH%X-!W?(r2&}KX)km4(+xG;Xr?k#RmS10q;X& z(@ySiUwKc@1T4~zqyq-&VWwBbAPt4Sy*=Eu9Zh%%NpFPaNHSoAp4NLIbk;QO%J~_` zqp#eVfEfcmRW*4~bgD7=w`Hik8fT=xW;!Y9RXZen3tzt`Eq5!_k3QDN!B?|#-s%Tr zr>r}>IOmXb*~x#w%T9^D@)l5}W-zBQT`f&1()_D%RCwydlQGP%l>9=?A1Ud89X%9D z<#4{{?t`S)ynUsxfMjlovM8Aw;J2FzMc1xI$aYQDYI&az)Aoe)PbD-sZ5c4F>7SS1 za~!(4!v-lAV-*NH+r*8wYRs%roUMW+^wq`JI#x-KbK!{^sU6G+;7q3FasuN+3eb4l&S8UsG#lE~UL&Z*Bg^GQ< zG+eP!Keu963=MJY6F8x?uH00&9&;cD-+>6pV!4n81WqQ=EgyNJ;3B!0<=IN67U2s= zHVZ2AKk;mp={~nhJA(U5;)HDz;y_pEIg3yFabwjB37C{c|LJgz*xHee63&k}kG?1iw?U{T)nK zNvmtMr0GZt6S^O%y`jc%^1RF=HCzELRSi#Lr_T%Yf+i{-66V@VKLZ~msFeO%Q!2v_ zLjQleZ%8PUNNQCjVCEdb@G0-wG{M`u%H*-uF4I1uNh@mMd^?>kfOu4){9q@2G1qmH z_w=U-5k$&=t9>{S8C`e}e|RrM9TJ=HD1aeMOJKsUwYR{F5M7pOAM|BfqsvlFw-3>F zyQolvOIGFxiP)>47b~=c5F-(K^#z1%)jOh8^Ro~RFa}}p8Y5M4z^l(Bl?5OWu`38g zNR_8$oz4d>0LfM8NP*B}(tAbttx<4Hv-SkF_wG9)84@%xAjbrQ*q`U!^-|F%Eh78M)<`(kOp?Wm%2BJviH5@E&fR@rp2KYzK2O@0#L4Xo=M0A z03vt=ArpX7rJ6v<1OQTa8X*$^NZ|-V1r(DaeeeiYBA-x1p`A&UN2pMt-;*krP=P{g zkt&A}q_FvNX9n|>;={q3R1t&pC4c-N!>0*+^w2Pk=h{F){_~W4H z(Bpcq=l|eDyp9zWCXy7zKX!=Qbc^n~j@e}wo~1C73{jQ=wKFrw@n z|7HF#RKT6#Q)+M9nzTjeIDc$-AEFVW?#ujd_d?AIi56K2?-DH_8Zq>FqN;|{V)tc! zJyBIlLEV@64}AwKscI@{zLhYAv^hlc42_aDo2dITe)i_C90|c5UPr1DLa>RK5-KKC zs_i+4P!S>6#uErd2o)>UL4*nk!9xCtPywNcQti%4VM0T;o`sbicML$ODHS9J_7DLCOVwS0Z2q4y%!h(*B zx>eR8+s17nzmm4>oRslRYtgiWWxxLL*1ogWtIAovSh8F6{UhKj)ng=W`1I9jZs$XA zmX#)=YwvT@?kX`s@3VTn_dd=-j0X|Ck24P^6Vm85Zn`$=YqU?jk24H|NTuG#S%n<{ zIq&1FLVu#>ePUMPl8MmtGLaN1!C8f6e*{`e)LDg>iJJFuR^bVv#iXsYa_=Hq1e8|c z&aYq z>L%Y*6xd{1X=s{e>m3qyD2vV5&TMN_Id_G-fs1k|@24_igJCEg-G)ZU5R?o9iy7a=z`070N1iU1g<}`zBHIG!-gHv-o%p z3grwyJ*mvolqpp;sm#-qDm0Ohc^Vj{GYPfQ`4lVFZs((RNkT;m?N6!%p@>2Q2(=I@ zRA_TT&4i#J>kw)pl&@63k*WrK+sD6mMiNT$29oq`FX6YJ`Hp+OHyO#9_K;!&5}5M9ZFiWBu-y< zAxa+_t+Wz0CQ3`fSTq;abT>qnD{H^n0q>y=VJw;;L<7QD^hH9n9&})j6UwLVLtpP9 zlt&2qdN+0;xf>#(uaih+Mg#ghJ3_Y{giEILTaa4Q9y zBg^Y+UzFuz(JUlG`kL;{eu=r-;3zd+6E_$kvfTMTfS_da+|#Zld-MEs$-ev^FWK%$ z)bF-eB1pD761D9kh_OnxI}i0$QmJI;ttOQe#@}3y2UW7&NvIEi%1O363H1h|CfV*J z)Ja55vfW9j6Y*-d!==q;v5q3GNp`ED`w*pM`)e9^AX-EZmoVD?L@D3?n#LcugVa;R z{WXoth*HY^HI46os7!G_GH&HQL0ZbXzozjq(&n-bbw+y?X({pkB-9B+DfIp%)KiF3 z?)_xz4(Fi0^p}3Vbq~_gW%`p)wE~P5Axg*T=Udleed#;>eCyI}@iw|oKi~Q+ zQF>5+P2(d(wp9{!^R1t51GIu@j?peAT23_E(78m*h-Ml3)cdG!DbY5w z!Pk+tgs3`NRiI0V787-$=NUwch$f771knglx;5GVOtg?_v(au(w1BAdU|X|h`9$MJ zyK-x^IFG3FW8Y${PBfROb7c!jn?tnLN|;SFn`q3?JBVfxb>8fZKjUp}@+Fj54d=}+ zAg!IH>b%(~qIQ;QrIkC3XaXhBn;p!`wh)3h+m=*3MU~!cJwkSbYN_(SeJj)^&Id~r zT0y9R5WLwELUx2Iyjcr247r;dBl_SYq>AxDc(aE|RYM5gY#OQT2vvBqqt9~gD^JTg zODF6(h@UFCK!VI=5PVa90%lAN6McyXIVF`q^+ecy+Ytp>~Jag^DhA`=rkh?RrSYiKfjaiZ$vm(RAshYNIkuG%X(%nrJ$| zK?vU0u zKvzZ)V${H?q(cP?jMVl)(y!7NASntVy0Q%)W^geyrV7%JP$_&eb>^qdwN0Wk8K;ms z8@w?J>v&wlA`RX;Ij$iUx%J>Q&eKt?;DDt078kaW`$IvYodNC_>AtkUMBaADPH}%j zrakx9WZHB8mD6AdE65sf|NYGzt6`-UA*rl}m70&F+MZlxZPQz+nEO7-k}%1-4V=G$ zkaY&E)n$M})@qebJ~duPHBn_#vC$D9S7 zE%|{NxF;o>!x1oU26B~CU|iYgka?eovT5EYvs~>YaBURdtDOXv9gcK}WvStcmoNF` zsY*V1s??gU#rd{KH!02TCqywITiMpQ^+u+mnxnQ_{bqJT3WN`m>qurN8ZWkl3K~ ze@G~3dtM=ALX6IwBM^HYT2P0i=!n>#J4tQE2K{+8p^||8xfoCf`-8nBomrpudaZ)? zw^$%8UnW>lrZ8rk9$Fw_YS#nD4>wNNibHSoT7jtOwH7c{_Z}8$pUh`kwIZVFdZv}> zg_@o&B?h$QddUuG$#~>?E!p?vkd_>S+E7bIvRv&vaCIQ^oa2C^!Pw)8p>O{x2W?MEr>L3wueuxDTnU<>*Y{~S+$^vb3oigZL$ztHwpvhA} zsf}prWW#Vf)Q4B%xedb|Vu+G1dOBULKie;(S}z$VJ>5aA2VbcDpGmFnkzxXBy=$Ei znvh(%kv2bNN~>Ro5P4I2w&VwdWUOQdgrpd`UPwkDSEmZW+Wk=$S-TzI<4x(8C*i%` zl&*>V4tm#(IXz#eNoArj-JGtHj7;4yT}HmX4w}{M8gd3G*pS;!P=xo$i>bHJFU#XVaO+Z7cH1~N0IJCp6#!}@?o70_SH z_kDkDwzA%@hkf@7dPlhL*TX&{Bpu+_!{*{aH`nK8B%T7Hb%S3IyN2MMT|<#GWiSLe$Mj^doH{Q8y#ehqMJm-HgPC>p>Rs ziMknyg+%j+x*3VtM00_1M&fQlIfS4d(+Oo0f{I-8va&gvMW|FI_7XyEm^EQ+e;gld zB~+|b$C4^Zs7Rp$2qg$XXSU>nErbe{DvwmngrGJn`=O;xgrGJ_fv6*S`p|OOMHHA{ ze-61^4{Ju2nkT5sTDQ9w0fV;favssF6K-)j#8q7+K#VCt@gL zPNu=lysNqgQC|AzVNdSmA}00T{wuS4&JyMYBc`~%eBH6iQtjdNV#Z4`fru$fKS#5u z=7isB*T_S{x07FVOsdoJhDcT*7}#HOIhUbvU9V1p#z*fJ$+LTuT|f{XGf!Gkg7uxQ zWqMwpbeZ0HnwM!VP09BkAcD8i%YL-dR}fNf@bsg*t~QeUV>%{Fu((GsFrhHgu=m}r|gGF84U`L-gW>fRLnZf&$ULNsaUznakVg+vpEzDU{v zqAuopmbCdqn~nB1(&iCuGIT1@T%vJ9#}myV+FEp;Y-e)mHp{n+|-Njfj|mTc`|bQseIUqn(vz*R42AAIFBE|}sU5_bGH^xv9zd?wn+u1h^yV5AjUXM0 zb16tQhKJ&uhwPBz*r{ZJTONMHR_3L5RC+thx|sC?cYEV)!6C`nlYKj3g5FxP$x z`8pL8DZWmd8|Ld-%=diVV_2B4!z4ez*Fi{nzV3{q=j-N3dcJOncag8FOI8|RTYCWt z^0fq>^5^pPoUZsP{gWeNsvjrGzbw&gIdt;rZ2NFxZi&A?LulLytByXy8Pawd^`AsT zGM%z4pE}{dC>$-dlMwa%Wb8g6YSuY)>Z!y8S+n(z)SaiE=8p)RdMXkgKKDv$l0b{4 z(R#&))@{7-U}9njiaBUXQ_+-{ACE|hsk=#xQ)w;lrXH~){yXZC`wQ2@ETxE4fiSxz zcuG>>jF`CEv31(@oQj~28h3HnM}7QL=oqy(B!J5Scumm8JUr3c7+BZseZ55X8k0Ms*4_%Njpu0v`XbA3Da!KgtJMdW z{-{mwp#3eE)F18 z&+V8bjddrrTg&tmVqfd99f8%1WQ+9>CdowpfxSH9FJ8V%m0gXX5DDT8bpw(qmsZPkwd5Bm`F)SW#Z^f0tSVDvT(*F+D zOP+6LM5QM^=P8?BU_}`7;ENA|)4wrZFehKUQu6z$(xdL=`I#)JMGLu0;swU{2~8d? zb%gEI?}%lmz9bKs@}AuyHCvdtd^g26xKIykmqXH1-y1KOBB#gqxrnE z@lun=rJ2$vVEn>EI%#spq9LX4u4yrR=zf&vrIeJOM!XT7DtF=G*g06rP?>5lGXRJ@3f}&-TlpdR9{r+wAA5zjIG$?8f2+NwaJ0~ z^HG9I7jNu{#>bz5m+(F?(G`{6CMigM+7)5xPsvc42m9moBIlyfdh>?d2@xz`BMm8J zHTh4vVQ6Bx-d>QY4#DdSGUjVts8n+C#m7Hj0*`!pNS8TS-?%z1`z`&ElVW-f)Bv>* z^C#cvc9M17_Z>}Y=Yevra58zpfq_6-J6CGjvlIMtL4eDirDq?-Gi@D7E%s7dPi??&Zk!qtpr{ zeSCTbN@sjJ62DWECc~MomiN?ZNry?nnIcrTLaTEpvKz8mX$R;;SB7H+>G9kX;!e76 z|Cb%wPd!hyUnqj@e<<93Ww=d6LtQ=D1Tx-w5vl?C{*!-^ zuJ5^d29q#Zlsm^_`D^0zD=2)0n)2Y3-?q zrtf+XJy|7bXvk#A4@k&3B>g_2O{O4-||yRNLc9i`<(O- z$3_1!?Ovo321H|G%C*7U19EG{Zq=tBQ4S6Kw?`{K)5_VMj(*kW+XwVL?kmJfD|aDj zOBnE0=&PP2R7|K`p?e8&m6-cAt|!DLV(!_POsJ3#mgs}!gbD~js?K3OxH8Pq)WM|U zvM^=qAX4S>L5SBjq{<;wpvCti#MNLD_#8MqNuaiTL96P!&Yxq>!Pr7?X>=q zlp<;*yG+wxB$X3b;VRYiyG*OchIxLOY4xMLflR!WW5QAJB(1Fa9es55;urY0ilSNHIS9aCj^Px zkW>~k6e!gOq{<}~B(C+tP&DwAoD{@KS4i3`$YnIpa;GyXkg~@lD-aFTA{ml0A8-EK zqk;4YVC+yt0NU-{#jfn$t`}S0`XF5bho0&rkl#H#4hmHLA|6hys$U{ci%6=?L0^t!zSl7J5Vh>!_wtrqYqpirm&?C%~XZVKN}n%+TaLr<}k})M}&p>^4xTji@r{Sx`9} zQEBK^J893l?;a`)y@j;w3BRN9a-!t8-_bahD4Fih)fj^cxSgmaR_;*J(q2T}j>cVx z(qu&4j>e6N(rQE_R>JB;X*m3j#!ugcEYNoNbBq@grTOsZ7{3~Wv7-fv=2^LaCv6U- zDVl5OJ*3Sh>UK0km`rz4w3JJji9#5!% z5RBk)tVBK`7{T31l}9LF%le~G(c-}X_7@5oVi>^0_R1Pgp|riDSsE|H_^rIfS#TJ> zHzYU16yq=F(RiYN@RX?kE$3>8FAkn!TpXb*77gy!(o^xew)DksYfl6%{p=IGrFYu6 z6Nq5x<0jgHs2Bt@u`|JnNj!W02i#Ddy1FH#QB)b;t z32&r}^?S!Uv1UIV0}6~(VJ45g5z?#Ua@fc{n6FVI4CLxthxQ2ON;Vk}!?-q*em>y) zC7SE!1AeU0vS}EXN)}aumT@7{F8YLZd=gNoZ+yRiY5G-_tU?6mmY>{TnAh2N)Sh#b zRxlvwnt6lp{-8~`OFWTOIxec+W}3AT+aXc6|HO4eG*bg_|B34tEoiOUgoHi#_?D{F zun9C!jmhUhJ z3(=UBJAf!HgSShY5T$YOrpea60l1xgv?4HGI)f~ znw1ctmoLIeWmck8p=qQtD^a4*g@oGZx)B+iPNYb+Q@WLEKiTmd5vqYe*tf#Cca6N<6l$G3M+NJ+TAtT zZ>GfA!FvD$wt?!{wQa~lp+Va)ngX^l;g9SX{LYE;x9a zR5~(@Sy>MPa<-wy&>M-GZKyW%q~MuIUIWLF)@(zi(H=vTwt=zv{)A{47#Zw`I=Vw$ zp@Ex|iY9@P!8(L!4;UG=y$ZFbF`&o!kPs~aBZF56nHhivzI+WVgP8$n;QgdBGXM?z zJE_bJKm-3OQ~?bfAtxIJG_VZ0oM}2+9%k4cQ#l!q;(cT=7|D@*# zmO7>4l1Zn$CzP|z`EhL5l6%@K+9N^9U3j>cT=$Xe5D+2Kbsxz_u7;SZowCtCN=E z>~FzpzbYWne)ec_Gq^*c_TR?NB}%#WC$#>ZXck-Hrjf?-lp;DgKa+F`Y3b+ux3Oms zrK|Jb#*QFLZ|7%{4r6`k@cc~D_N1lH^D{~Ph&I6!`V(4LE=1enMBPl%heR8Qx|yVf zMC*t~jK8yq))Fl=wEjwPGDft(&}pQtA)0UK6w+1`%`g6TXpYhD zPTC5hZYF69qUA)hjCO6JWklP|#`b0%N{Om-R1J9hC2*&NXwuL|qQyiLhCW2Jh$tPD ztp5;=5N$TvDA7WqE?zu`XaUi<(VjI8oXjWcoYa1#%_FLYN9(%}X>*A>SG5sobBM-_ zwinTCqRv|_e-SOtB3f;<58+IrsC`{qW#}Bz+Sj#}hTcn*U)R!GT~COg*3w&DcLiF- z?`k=YEhm+IR9mX;8A-@KsztnbFd_S>7V+X9gzTf*B7JZhLiSN@M4_$uM*FB1-s-0p z&{+GZ7T)Sd-P$}QY9H0YTeS!k-BX^Ha~F;f@&l&FQ3eN0ae0`2EvA$+@t}r}wVJF3 z<$u6i{cpSx>z6*AHSH_dBlbp6tX?zSfv2rX^xzAMd!AFV3cBx{gPr?k6cz=A#xaoT zswpaT7~n&oPeXQUS!h=rU6fiDI)M3pS*QrlyMa06cxxe{C_;wUM^fiFA;Z0qRLRU$ z$^7Qo)R^ZJ`Rx}nhC+@P6QakbEYAZJlI2zUg5nCDK4QqoA6a?V(gHW^OzVWL9b{O2}Eu%sSnLT+gS=kn8z$xI6tw2Hj_{T0s+<0w4IyVL%;JHzzuX+R&s?nvI zoE24OX#0fIjmhhfo07p%IN&Iy;NzJuQ95VzE|ABi&0YqNLVifW_a(&OoD;6Q2oxAr z>hoO5GPwi;pOGi6&mgC_A-@Cn$hx4o`ty3%)=^}JiP2T((zbYa zkV{wY=eY!~tj^jim%x?YXt&=(_Q5kDt}K%i!vkDdfLza&XC>Fo89#;JkZf>ehL8re z_jH^-6yi!}+M7*wWY%7Mp(chVu$eQ%uD((DeqH&Hunk1dd<8xvpawrZt*z8{#8q;5 zhK%ZPlO_|A+v%>pW6zO~Or*04WXpPn9px3>S(M2rJlI1khWH+WMHvMOZ&6O26tXD$ zAva}FhDx^Z*?YCEneQ!1f2O@fSsm$+MOh6+IB%4%EO>iv$f6`FwGQ5*%t0IewERX+guh))muh)(a?#67d*N$ti*N*!4-jxi8 z71(LNc(CYS&(6rCV00aBj(aLy1K%FxG?3DA1Sphkkd&h?a^|p1xp)AQ%40~#9!P3$ zKsq+WvngY_Cez+nW(&DFDF{W|Uy%03^7SVn5f#EzDH0O#8c0IMvW`?#RF1Q5A*7up z59Vr3Z{~yAbMQeIl7z}h37H@y6fH=|nRudugkbyKkfVDpC=!B(u3vz|!ry)6d1-izwVQu@NHK?M8hj()tDklIf-t3B~T*A@Qg$1@43{dBY1 z#{hEn(@ks-AzBXB`g0$5BFb*@=RR&gls)6mef;!sbTm81pZoan1ZY3I$e;T-m$XHE zTheA1pCYZQp}GJ=uOqFhrFsEFuO@8)(Pl%>AZ^^O#)+0%eRn5q1JM#g2avXoXtAMdleU&up-V0RAF7EK82S)ttBB?sI)i8>(L6(=L@S8q8aj#PmJ`h}^jOlC5zRJq zKcb~XvkcvtXbDjlxokwVm}skc7f5Kc*6>ZU3E8YQ{L{63&}OaS zqo$L}X073;&L)-3S{G~aV@PGQ)fJamPapaeNk6cAN0M$}_X@K7Q9-YbQy--c7d~o%B-3_D_S`Z3IuT5JeUk{u|Ftt8 z)8@IK-V0%ydfUu%F+Dg1JFb#4*t`5@8(Ak?;PRVYpmW4RD$|Ikvk0`%-q=vDF=BMMUho4l?`VJ;7mK#jY+);SAcR4{OC#s-X_U#AULc zxmwSKlIzrA=1R@->hLHY)PNJ}a2F^$gluUiXN?|$5G*fqPxu(D2eaV2<9)%F-8#Ux z40fbHC=dd}h-@%c6&CXaupnPOq;112ILybK?_K)}wCRf^J20C&A4$)rSx9=baSzIp zP+bN;50v9Q8cN5spsC1n^A2EE1)vbKyzL0ilLhw>ei8xeBI&G4pV=+zPA1NWZwzuS z@AWX}meheWI#UMDy?IWUbF-PRGcDj;^t%w}Zj$T(=cXd*Id>6~o^xYR7CCnw-{U!V zIPyZA8w_aGI9In%=bV$dm>gkPn>3|OJL^8-a^SQeIYgzq(|*nz;7|L>aDW59uCCI) z(=Dbv6>0*K(g@xA^)wELT9~|;{i~-nXqR?c)}nA(^D~w8To232Q*}($s~?hS_1cgs zn>t0Jr}lFCKU9iT&YI0${;)IT%-hScpkUvRmfy5Pb=nVQW87f3L6Zl9QoFq~d)de) z<2c;lG5@Y}-8pl?{vD;5t`8_u69GTo z58d_?0iQChx*SpZ&(HGKt5DM~N`7GN;GamU)z8=5xk4TA9x>#4-M$)Svwx%b?Q}V& z51&hjgI9WylK_R(TW3qXag;4?o@I(i_=Xc{ARkQtG;FG^^V7BogAc0>uoA@ z%!LM_zCK@`lf#BGzJ1NZ0%zG>gBOr4d=glW6JO<5&O?|}S=ICF3bIsU_m*zWbbejY z);~!PYL_MS9Ty!c??_pMlO&lsvu1s%C(o}tYNrn8*X1t!sXaM-XP#g88vYmSCTDT} zp~LxgW^YsHu*us4r?PdL>Uexvo4#R|cKg7gt$nYFUlt$NJ6W@%R!;N_$5A#WTcon= z=}blym0YSLQ;rHZt!SeoM6?);^d_=Do_j1 zc52aXYoJ_V+q=TH45w#G1kh=WnSP(%t&2>UM#iOdIczPStsOL_w{UWYXNsn@95iK( zZ6pUK{(?j+r54qm{^phmspzFW*4Lcaq zI{oV&XV+>q`H>{K9lOEql0geP9!S1}&H`sR`?W)C-WA`_{`2t4U>x?=cHVXuXr&HE z9lfzV^0ZK6cSEjk?4KmpH8vMTryBb^JgK2O8oLfiLsqt9Lx0yvL(}8Uk}l)}?VNhI zvNqVxuebH>6fVi3xS&9FBbq*zX_e4IO&>p68}3(X_mb>De7O^nKEB)(Nzax(D2qO* zzm#JUKV;yGyR>H5a{#`)i*$%DDen{TJE{9-HzSie1m$VcFlj{-^siGz0;5jG>w}DX zejCRqzuvVs>#S>XbtqFTEFoc+->SdEsjj8bm{F}kDhaOrmoi`6sqJ@j%GE~rCQ-U& zKRYy^sLd%?8tvRu^gV9DvqC%TW)gBjnJX7l2o+<-m1|t*6XH}dS1?W?#Cc?{ViXhN zBr?~y_9j%ovLHT#SP4!aGm6=WRGd4e5N${*P8<(~etmHV+MmO+^0oHw2t-lK)8s-V zRReQ18AnoNOAN|_lbtp~mhM7XYRw=@*CW}9DE)G`fW!LJlABqjC$NgJ6^tsfk;PPrQ;Is>+YLm@b?DtT zsIxY&T>E7EQf;kDZkZ-?kyH~}s>yF-zQHA$UdFUq++s~HW?DxD(l2uUHPd1|s9%pE z?V|ZYCApIj%?A79j+0;=XfrrqxR_L>RJlBTa3ZP9U_j5#Bt(NDx>m%e%vzv}b{8lx z8@nASLS6K4xj*l2RiMf9x?MBmM1I!-eCbSOdazfQZ|-}w)-38s5UDSW#tb^)L>P0m z?`~dy4^m10_zxVjlIT*k?^X6-KTtXQUTNscTb0nQ<3e_lgsh_=Kg&i2EjwiBX;N87 zL5?0I#EzoPzL}8q6{KkjA+zidsPhS#Wsj&FoIx6?lk6fv7LFD6}- zK6p*HA6)Y6TGDdSlAxqb+SE&0te3n?*!I=U5EzxT8iT$(-b-4wK`)X@C9TS!7f7X& zR%y^ZpmLH{Vd$6-1Cr)fIsZah3Y%Z$98Hvl!GFPX7*UFx|AJ>2D&S6tajTqLla_+# z&w}Ygl(Of~g86m^YDV$%XTiKnloIIAf_a`Oh0vb`Q%{s~=+A}6;Wpsm%N9zRT8bVa+lo*v;rvo=^{eq zgkTfr5-KAEn;0*lnIr_8ID=Frgi2J^st6Smf=wJxsE813;>m;}gkTd7BUDHTHgOQ4 z0z$Bf16hfDLa>P&3RS=+ZY&h^mavI!HQHP;eBxW1-gV{@Ht}uAVw6;?HBTI)?F-q& z;AC8TeT4{Wdwn_ns!IR*`?UVEtDIuVgD1dTTnIz1)-&CZcNi14K=``0Ausx9Lhj#f$`k~#%D4XVO3zn-R z8Q8ZUr#q47K>bssL+noleSUl@=ehWA7N&8a7fEMQ2mPi?@0w9(UYARtx2W&P0J!zM!e}78*MhKAFqMDtJxO9CPSAIHT{ko`Z7_| zZ)aMbAZq&UtjlAELqn+F-oRW%TB>+7X5~&GN-g(enp22U(Y=isPL#UtZOk4-sqWEA zD|btxrtuZ(zw%fu)A(|Q`VcaWhmA>I4W^jJ!;3E~4r;szd}H!yQf1Kyz{WgCsEwW% zHs)qRt%TskN56sMlY}7N=aVWy2qJz8p%y~0F~tG}Y|IcO{cP0!Qbjki*$!FW#%zSL zyp735G9={xJzhNB4h^IoN=T=st610$^=wvk-D+iiP{YRe^%~}6df8P<1P|&2dJ!Sj zuv(L^R}Y2KsfNW2`Uk0WEaZIU3_#9OX&MO^^}uVaNl>=KH$u0=@RrXk^g*Btt`cqEUA}uA?pK`J~ zX|R9*8NUc6&@1>klF6i{WAHn{#}K7& z@N*=`5T$$Yb0i}U2G{8!{2a+nq-}=Z@N*;^5N#q_Z1rvb8)_COT4dq`k41JYo z9nnHVpCVdIw7}5W2cc#$qWOkiP1+iwd4^6SZ8gzcLr0UgifE3ZJH3kfRuW}ECAaF4 zwt{Gu(QZw&oM@Zb(mq7Xh_)KKHtSGI)CE=VPQlwsh$f8od7{NcTMVryT12$j(3wOd zL|t?>g=itsxY3?Rw1BAdMCTNNllerQGdhs8c|@H*+K;rkL}OO&CZx?F>bz2KqS-{9 zSNgmPEzTn9yi)zkKy5F1rIq^(X}Oo2Ua5`{HKA=^TZ=xQ(_+d>Ynv=brQLJqIABj0FS$l;ZGlghS`!z-;JRCGgm zs>|H?+({>C zd%vIj6J}%7VWx+YX`{6s?6rF)s@)t6B!A!AxoHMgw}ApWumzEGaTd>xBI za)-a9C8o|i7$y0EG4HAJcwo%CA9DSe_m4>WG4Hl0o8r1Lep>{}VeguR=-er`UtQL% z*apVG>E~`N=fYU#y>|XN(Sx$?<_gY2J%W5)w7Taj_;?T~z*iW7Vf%T$f{!~eU-=64 z-&oQCKK=$tKXo7lGVvcE2}PuSWaYV# zb{gy_WL<{|gz)I52P@(O@bVz%Zd%QA4xH#K6ah}GCk+Tl)EAeAIH7kyaq2f0t(9EI zi94Q$r1}N&$B+lfh6$W4k7h7|K@Rv^3Hx#Wq@Y`kEa^^i2A~$9_V@Dbhh%JtdO>o) zkA7&P-$}F@l3p_2ofP872eR)hz>jAn*YRWebKr-B-c+x9kcV#xz>j-%%UXwN^B_C? zi7k6|!j4szhW2N*PC;&*nA!`B*7rjDeCyXh`+V!)uMD;RqkTfHpD($t_0LNdN6T#e z6HF^N(E1xe8&V2&h{5K2X_((4!FTt!CiUP9s;%+XVEeCV|5581mwJ_|ME7!Spt)Wn z)eM-K_b&0B3N!P;U^LU4>!+D7BPp7hhmm$>7E#7bfv9i!`oi0#gg}Hb3At){pkS9F z*XD>>mf2@mo6&f^J6{5fjesh|*i|}%YST`Pc39TBJwYOUzveynW!(08&6~0rb%*qA zpWh|~)wrs|w$D;2Ca~>u`G&&&)X5Y3UyR-fPJ#{~qyylD1*rvlyFT-ipqmlW0k8|x z+a_vRZi>c*>0j%HU$-&BA3N~^X>9=P!t^H6+5p&v=`qrla5(6~^uG};CK|Jvjw5OV zU>ByBvs@bhyD+_ow1qazv=a6wZ2{3rLpLQY2fz%|*Cxc#FT?b2E&>N~@hrpi_X*_? zg2FTt;-HsGvv44o#1StikDesdhCu`;k8a?Dt%P8TuP0TK5bV)pLJ2}ppcDCE3n3`c zNTH%m<*7~$5(?@RlxSxpsYJVhQuPZ8v>wXxlSdoiZK6DKk?XYLUa~b!4MUT6*T3lT zxji|M5cV;!d2hj&Y8awpu&NTKPQcOT& z_w274O98v?LKQG&ewp@K&7RJiK(MADsXbMqxfe>(911LP2_8-b&P7anOMEcty(QiY z>5wJf0FSs`P7tK^NkvWO=Z>FGaP}I)lt5BEqO6O5R0u(*hEt&CO12mXsyAI-98?{I z>StdR^=F-0%y4X2x`poMOy%_c?tNFr{%(COQ-2?&b~~em{^y;c{ywOm_IK2sZE<^r zvIkR??re*z2&sj36PZ`;fxec$^k-ZAg^*fkH<4Ke$XRGNmw5zHdPzT>Ify9x)gNrJ z9Z~k5KiJ}@3j$r}54QOJPv~p2&`Fz6dWEz_w66(6Um|UUXp5nDlh!PBv!S<>)+}_B zp%;=ipC!Z%J)g9BL>mk}l(e+demb*|C{4AW&fJPsrZe}XY%OWbWH+E}4QYYV^(dPl%{Thx*=UDqQa7FX`7pFY6=~FD z=TWwTG-C8#(l}|Z(d$UdNZoYi4Axspnr*TtQMQCM%jm(R#iVUEy6;X}MA~XJN?J&o zGP*g>79(vj`qNps;{wuVqisWR$N8i#PHLiT9;u6yUZiZ4G-);5PT2^li<7P-%_Vhl zQWxo1%1aQiPOKl>TAy>ZF{dERS2gtMF_#QCX(L z(1&NDX_`4vS*oaI2egY#RAMN5iO41@F`U)#i#Ab-A?+?o*+eBqwM!^v6O}Qoeln$O zqOw5IsYEtWnXhPHez7|6Vv8M#ssb;z*i29$*;p4vKR?tDU*P=E4`;Yh4{_4xDC%Hb zqi6eKh~9FiA?^R4(p2M+SB&9PmA}1Cm3>7|X|~sCzqi+ESBIuI*B_1mG1IFp5HB2x zw=YP?Noajxv+VI`l06=cvV|}yzXe^tf9053>GP!a`KP6-`I@;DBIc#Z|HmTa}pLP4&13TEQJsy^ZmhH%@8FIcH_dUJDxiSZ3 zyU+2KQMtvyTSoDkf`(L$2vGxC^gAk1JHT-SxVC9mVUPL*QEb)BaNdwE?Ki)z!Zo=9cqMan~#tg=_wJvA5Jhy|BX}(J|k@FUyie z@VUv(Ec^NXUAJ~K1hCu<F9n1WGer zKYE9;7x02khY8%+${?Ov@CGnCyQDp#zx9aV`DA`y6cRSj)bR|8{B4PzDNT`e z6biksX*KiXJB|g(oA*uE{tVaojVRCL>K7T!Z+% z4O{Zst7FsrV$F5^?UX0f%H@vM@pt4GYkqlxHUM@&xFqr&AUE~IiB*YzNp0#WZZ$qY z%Bd$#w%@0M4m-|FJbTBY+z7Ajcr`_I@J$C1};E`WCPH!ZremgF5 z>c=L#M_)$%tR7fp5sB)vyI4rfZUuMCdn7MfNkM-y7l(&G~W z++6Fi;hQ@g!!?GRGF5<=A)(z0O`a=7x({gayiN3mR0oPx_(2r)hQ!S^q-Nl|a8!j_ zzJz5B<6>GqgJnOfe=N&!IWFDOkU9`$7k=d_+JlHz$mZW&PAc|hCJ3z^K&fI0D5S1j z{bDYqXoAue*({s=p*t3hcd8E!eqD+o4c6}XAHIY7R#naAw4ZzjTwzc(XUS|9gN1Tc ze!cNE++BH>w?;%8OuNNzvPc!{y{hZ?lV)>f1L-t<+^U*KDeWKV#@|tP{R92DnaKJF zI&#y%VE;f*{z571ALz=7MCKx)E(Z}=7eQkRh|EP6=>2U=WG)hVvjLI0Na)P~UPK-> zBC22f*D-p7<>n$Iik5EdhEC|rt0Dnq7k#<4#u<4+B_GC@y|;T*z8KP#k%ui`f2UJF zV=6zh7is*=M}s59 z?AT{sb~Ka=DrnQ)=WYb8gbErukWx@VLt`l=D(Ig$Yy&AbT$h^QH+Q0UsfhlGLl$M} zEBpfL&yRvE)zL4Yew~yWS?-=VG;IiNrc(M%<~5Y1UiwYuGf1hLev|nHq|{Eo$^1l8 zDyZLNUPwwE^_$FhA&o$p{U-Ard1bkz?uo;il+7V^PaIaKY&NNT;_%UtXooCP_r#&* z4$wB4>XcS*HDB-$Wm`$z6Ndz8inPUKFDGpwbx#~F`y*PinY77dkEU!Bse9rOBW)y2 zn(PjwNmBR3VMEe-(pr;Ug|wE`J#lCqhkL6bO_=PG4RB=%QuoARK4q&()$-I4Bq>`( z>Vm~;%2trZP4?*9ake-pUFc~PEF*#oJ(8%D2rhJAq7tHFJ#UQXEhd5s-HcL2L~x-w zM1@3fp+6sii--{wXkDKZ6%fINzDbl%1Q$A=D31s(^yvXEo{4BZw~7R#0l3dQGJ%YKeS0r&-I_iOP(|IRMoO+fk0|2w<<{4mgB_&wU?n?!W}41MPl(erar z%N!!QeTKlb>%n&vurAo;G)mFoGl?rBqPJ%-d;$?&J(IWtiBx69G+>u|5Yfqxf?aMy zL=Vr9cx$6%3q@UFZU5HvOBB=$K=9YhBl(X!CkG9GGJ%zsa>C{NUek)MtRx zP?t2Sgpn7sUQL0};FG0ZsyIF2F*u%<19mmXQpHT7$2pcZm`<1WU#tE&b#S;r#=hEv^5zz@kXs3b1Za5@{ABt&S;Y+IG)su);Wv) zNX=-SzZgzRqxCLh2rkH0Xq6|d-qk2e)Af#H=|Or~wprGvLhq5%fPFU9KuQ}fk6XQS zNX?APv?XsMGBYk!bmJf363mP-pkGd8W?ZaNC-94A#&8_RQ!1PGU#L=hP%4WE1Nt^Z zZGi!O08wjTK>uhKZZ;Jd(3c(v)DjrbTLc9h#{v}n?9V(D={Oo?=@-X(=TaJ?*0Wrup~Fuok*mXlrZf& zA;!pMD(;mYqOCRqSS`H+ooA=WmtC7;v`)QAUyxwN`e?RT< z-u^gS6KSDcLj!3eY0T&x(j;kt(OIPRq;8>QIcY6vp2?m@T0Iu?_(Y+{J zP3jg}?m^iq(j1drpRyICZrbC$YjAII(kzo*ydP*8X`A`Vg`}mVtw!gPmXM~5K881$ zmlu<^7`>XZMWoF}FC;A_Z8AE6G)C&8q_Lz0q)C(Al{BBU-sm9GJW@B(Y{DyxlDfg> zhd<$tBcutd;oH^F>ba!VMqi?A4yhY;9wyBub)(KLq*`I9nT+Dk4fMqo6D? z)651@(g{Rdq{;N^Kq6bAi706-ud$h5#Hh0krJ9HkB@H056`F{WRw1$#nizGK?u+ZH z=NB>Rv=G%2Vbu8`8?9n1G%@NtDpDL~B05w(ArgT{syCnxhWn??aN`q3oyqv3J}#-z zFJ6kOf1^={Z!-D6GTqT$rz*Rm7g&atQ*Js8p`ea_;eohQj#<*vbNp*Zt9Av4;a{G0 z!!To`Ga-Q-6DoT4DynIC{to>-h{t90W$r()$|(~RbC?_sg22f~M^X<$>3&Ks89>eq^J0FLW2U~9bGrr}} zQakewd#CBz3oEDT+TA$nTkt+P>RRxxa)@yz=R3wtcRf?1T~Ug| z(tzm`Ok$U&VAb~1y)UrcB4OqFAGKTSX&Kw?okXT~E4Z_(cAG8L1ln!byJ$Bk;;k!b zL;0mSSEJ|^@lq7MA|AI_nj)SkM_n_<Ni~< z+N-&vUc9^Efj#v?g0`AF&)X`7=jo7um&4fn*FN4>MaSjWK6zZd9K7CXJgzo|CLANj z15LO)ioOZAN6|Oo4)W!IEw7Eb>Gjq}z0S*FIR0j&UcB2Ph=%-H7m;;k(R{&Jz^=pZ z#Q0PvDW}XY>_JN>FJX|`YXcuWDWjt9a8o8lz5ceY6g5k#2`K8cw^UL6^xnq>PRIOa z>IFo>>Aj|QtsQgnE_Qu_NK--=xK`tfE+tG_Ab1S~t-bvZnw&yeO9@@zT0+@kra~@o zEugHWgbAy6D^g1dUEsPdsilN2aLr-8mJ+(aHMIvc!BWDw)%)=;davb72{~Odmx9a( z8Mxj{#AJ|x>r5hMf}Ae7jEHF8OGx3|BKzstK6ozjRNo z?V2tep$)CmRK?nV2g$E{(Y?X7?yW!eg-IN0&oGvCRDf&!1HO&$1+H}^mc4833wh@f zp)_AF(<+@ygwnjYTbk0mA`$_mxgSSGQFM)r{4HOmB~x*3VSO}Xj#U>xD&trsYpc4N zcB9vopZwF>_n*eOB59H+U2bu>W7DI~$xD9ae(8l1GInjUTAHU**ABW#8%=vD+_hIq zHG!@j@VW?2E7$#6+MQ?Ys_lhIIJY_a7$Wt!ZmRC+AGLOPTsKv>ACY=oH&vGpfA@o)$4$bu+T_T~yP!|aa1XHhL3f z&Eqy1J%_U9aT|@EL0NiSKVkPL%0^jly~*xFS^8Z+VYe}5>3aQyT{bDbub;5{W@p@6 zHtVgndfz3b5B3vw&yvy&`<>DA+R$e7#C~V=-zZCG>?iE5qb&WgpRhZXvd!?)e!{MZ zw28FXu53@zM$#gqyR+UTX`#{eC|ge&Gx`V0){+(&{X8G-P(zw;^q;z9tFk;nnrHM$ z%2ty`jXp}*D$s4o>fRW3FjYcw(f{_;5=M; z-0FRs)TZLfv}xY@7ENPQaixm>K`EPxD^c_yrEDq=Lso*wrs6PcozE}YR2-6m^C)Fg zaTvS~p_EOhcXt)hi+mPG{T$E3Qgk+R5B~1hH#Cc7&FEn@H|pB2^qg8OCXhyt z@%x7QvMDmIX^~bdmPU{&&rTd4*b>-=ErB@GGeh)wLXK>$s*O!6%*Gb0X@y!&N?AHi z`=C(n=Md@0!l?Y;EdS@p|1Gg;1=1+;le(7ioTpV)stVM^rmY^U%#Ka_lT;Yf|E0oM zj{Gkb#&YF4XZ57_?`^-_+J1&swLIH?q_1#!xBZaX71Z{9 zJK8?YpuEcxb13S`A78tz8$*)jkAJz>`{S6J*O`!jKQ7SnaV)ESi|3GRU&;aheCQIF zc#EHDNDaqPKl8Z-irzmD7GdX~f5&<&q~3&nbJ;d}WqAHmqvgdY>j+if%lA=W_3@PX z1>r#!qZXV{{fYdyig!g3@X)^Yy>(_Lu&@37dpq{E_epYFdtbfA{`YHNqy8>`!~LS$ zwS6@WZ_(dF&yi?0wbzpzd&-|XYt7iSm1ENm%8pg`iB*oxcE9MZ69v+r;?u=<;^h>b zce&4z)zY2W z^;*nF)oDRR+B;PWAC?nMnU9d7>vyV%7Iq&~EZEB3LDKGE7v4cqE(ALIfJg*%G=ZX@ zoxklfRavj2m*A+^(KAsyW2g!E8@7U1`Q^yN^z=&4`C}rDlip2K_mjR zibW`jrbtS*KmJxFf@X|BU25e}i~^jk3+J_be-S1;t=yl>1+>S*ju5ktz4sIow{%L@ zWOnxIo#~!pv`7RzMLxbj)7kx>Zd|C=U1I;iHEQsg}q>(O&Qan7PhixZ?M)*?2=$?Z}2GO~=A9v{xKj%o#3 z9>lVk64kIj%4w6^D-oFyMfF=>4T3G05k(Yz`LWZ?TrIvN63|Rh#n+phy%raG44b)cdAPo+wLaI4R)H} z9yL{OTl+0s&HYkMV19e&Cq%Hr;mz3Gn$9m)p0P-4f}?c)ZjuNIQb!rbJv5|toCKs@ z3s3haifGqDk9I-XbuDyhOCsx9=+hQBmwOrko$5oW;((j`ax*A^^&d3r9il=?LAe@< z%s=L*)BB@&MCgB-cfM5z-PDk(X`5@ zcgI19N@D1U51}_u5<|l&B}(FF*oRR{^u$lEuLUVLnwHpi7oLPpr?&X@u!}YUr7!U7 zVP7Jp&iHM>50g@D{5IeR@oIDTyVP!aeHvw{JboMS*`(ATzYX{pQmT;O2D~q69yHQ# z10G5mC3Vy58<9px-SqkZURf@wn_mAqf;-M3b<^u#d;p!zCT%mLe1@`Fq^(A$O+*cC zoNP`Rok`hN(iWprNK>TEMkkTBkTw~e$ZKdOZ8SQPvQ4B(qg#_Uk}{~1jDa*sT5GcH z1983eq;#4Msn1AjNfRdf8fgt_wb57JN9!a=)iTud@1krqsq<~OQMQUSZnEc7wgQwM zZtoIYR-6bf|L7hW1O*&2u^Mh zQH%&qu8F9C2u|(^qI@Daxw{1gV!8Wd;TWTSIJhhD1;#2fa7gomgkIO__@X8RHCo(# zf?iYFz`4BKnye=k#r?my{Z|}vaO3Z#d7^NW=f}m9_2`jlHr;#VFE`XS4|?RoZtx!2 zS&U-8*p7>XDtXR8dMjva^&6ft*KnmNJ3VJaXJ>-1Y=0X$gD| zEoFBK(j7A#*qVsGn4x7ZQ6awwOX)`xBZ8&$#RZqs1vAS0;Ey;X{V%hg7m4V68EZa5 zq$(x43ro3^h;DZjEahq<`dnr`aX|q~new(;ikbr~DE*J`@;@x_l_G?(x5& zrG)dI^M^tOwcEogn7-r^^|JMU2WjJ*Mas6SYB+ySKno za3MhpTqw^j<fXf2NIUc{U^-=Kirx#HOG<0>b06bLX^`b{ zt9L(Av&k~;=X@fw$x=mwh|DHS6m8B6GMj`KSewXf5?)}*`e=?E8grq3aq%0tlWd}x zqGu_UMO2{ZL87+6c$pw-4UCr)i&1?lFkYS~QUNb;GK$^{9El>mKq3D2Uf>{Hm-hlY z$kC9>{%6O_u%}qc=dr4u-Fu22=i^U;K9>voHALIj^aE_OB1D5{bY7cQuYuwa>;OuiASarPt+E`!H0UG1pxYDjrtc z{ktCGI{A1m-RsiFhgI(UJu+(UiKUq|_l2{&(%fNEOh@ZGP zl(HO2{JOvbQVu45;$kb(77Q_d;$jP4Z!>A3o$Z$#oUMs8W;8|GNa`joUL{SE=9}!} zr1hkEM(-r8C5;-bBCR2f7`@^Zv}A%b*XZ$-ttQPeT1?q0Qa5ptPuU96ER+4E2=^8z zW$e|E`aNaKNL$VGezz86OG#5kTS!YtTa3Q@GWD0##b5uRY!Rso!EPcgBy~|(1!;^l zY4x5#T0rUou_H zO4))!1Y#qIY(XJLtF4G^K_Nz~^@-|P7e=eTM7E$1qt(iCMh;IAwa<^%NXs5Rc~P&2 z*+T;k`E`NU9IBE!c-80^XUkCpVx4DZSHx)bfARfgD|$n3XeHpnZIPp9+R7WwQAPK< z9K36_cVGCO_HHmi8#c`)XpEp{Ljt)a6!IRtvmCi4w6Ri-2Xfd$4|Y)zwD4pc^*QXR z^5sAdI|g-A3rF%iGGLEN=#>p&Sw?H>;U*||%3-O4h;eLNrQeU*u7OThD>?i(BoXee zmBJxT^^O@soGBB;o(6~a#iUL#E9(@TkCkcyAky@vh#C_lXra8Pf_;eh=-kD_n! z$58Yw{-pkFgV|4l^{PWci{FZ4mOHT3FN8=Y6KX%ZN)~Jc4Jr5|DnIL7LeHM6$Gx>M zr?!4!r5j)Fl+Mq&y#^tq|1RcB5@{0U0=~KP(X^UGxoGcRB2A)_7CKGE7hMwNLcJ*v zbQ@w_s5g$XmPENw?=Z?1GkHi@z1vgPk|-DI4Is57%7uC>lUfqxLcR8<_4;iRygY98 zzS&nBsGLa@L%laB$P9`T6LToV^ogO~O+?I{I59Deh=~&?Cd!DIHF4(s1R|zP)Y{{D zM&?UY+_6M$3_+p0+whC6MDQ3}Qz}ISuaPS#FfsA{%1*;`)joclXWmjC!oQ0{s_jtW zm!ue&m}nBokbC^khIp`-z$5!*d15D%=c{^#opab{m38B@U?vMz3Y*C;mpC(F-#!2d zakuQ(zvF%27?~h4*bvzmeudT50&EUSc;0iEJoS+3-skN@)dR*`mqp2oh*%L z$89fP2s~@t0Y^E(v@Yu^g~6~d`w-Ex=#H{*MQOv`ulhyxFX@&FyKn2sOM3I>wqyH* zoBM^hYi|GZxg#J1ujF=!ZbhVC$xQ$aPI|B8CVQm^DDfK~=_Udhb?eK8jvfeq)U zf!-u#+xZ{PeTvk)QpytXnOX22=9OBEUQ5|RdN4N)G>Nh?(k7FgNZA6?Mx!GsORwao zfksd^kFxb9+n=&g(psZyQK(CSJu!d@@;R(`g(ki2OkqprV(pIBi{fs*yYM@>?O9HkRlkAMT44@RsXR{3V?wawGA%cHLnLCY2& zZA*Kr)e{eEgr?>LYq|kPeYQApq(*4onl6%~&YI4^--s3y+Cs;&tkELu=|Ge_rHWlH z%lJbV(=8hJ>aHPi34vcho~D~X<(DA`&%>{1wyh#l1*zDS3sYGa9TS@}sj)zQ22vJA zPim4s*!?GdFHNG`OV^QIquH@a*-M1or3dB6|G84mmH#91zqF(7E!?`hBO07o0&m z^=ubhGZ|U*tx7;0F?hTt<-nxKd=$N!H~d4j-mCeYIO^5>dep^fs2fExIH`C(j^VXD zQ1g>fP8&A5no!IgB7Q8x)+W_(QEvGi)kFBNU-$d&nzWw4zPl68)_r%QTHUY6-g%DO zS{ZEPSU34%*b7}FULIzjzQN$)v6;Nk$LgChdZ95=O<<0z`3iU;u_@XA^e;DRi>b-_ z9~6CmL?5(_o=fXim7~t>EL-aP8E$8>l-bYdj(2gmlh^4yHMrR{y|&Ij`5E%wzj|%U z;R7=^-QI_g+rH-W(lSxh}96-cOk`qO{ z5iyPAw8CH_=8!bz^@x~2a*}gpB4&@HphGM1BA7aI_fKs5z=@M@ zNIfPJP;D9VAHd(Lbx@@QzO2J3ROu=dJFC(P{b{)D?GWo|WFMZCpl0^=Ef}x0YD=ic zY_e!)w^Dda9XHVub09%4cZd8+zdWcDfH8yMoAcKdMrH5fqq=JPAb|S#tI0BsnKqQuONp zez`>AS~(0I`!g=dZSsVk?Fy7Of@qNRZ@f&*#eas{g z!rl6%a+B`U`FnMaCfT~qGG zMVLoI=N~On&bb^fhZ$HWRC+H|;GIhj-gA`J>GF_nIk*+L2Py z>3*JUZAiKK&0-ULbC_O+d+JhT^pnMb-uL^wULmCd_-WC;KC>ESJ>HlP&!m zcbr4&=E=UAjl0MuZM8AJfwEboDWlWzMxpXHN!+E?Ta3=4Y%8goCo3mSkv5s^X{0Tr zjYd!AH8hhZjqXL+CQ>&~wk>HRX|2hwPnsmHG1`Z;o-|=}@n>j_ z!38yFodl^1ie^)`nlx^*cTlzpl%Y|af)zyYUHk3;ZHyC@=t+*CR2fmRqR~X9MDSq4 zh)Rgy!G`jT#YFI6Yf`F+s6gvlmcsoO62XI|h+;(WU<-)~h~UBI2?`8b52C2C4?NdH zcWKiw7^ub}9nlhc##wTRgKUi!&qLK|o=b2} zBcg|8Aom6l-7AxYr-|rWnJm-_3RuJ~DEdI|_S;SEC6K!ehkT+?DTf$^!Xipg^>1Pk zot_tSrJVM7c#sc2FP7%(Qq4N$|2Y|x*o#NXeGd+=0sD9#*Baq!#z-}RB)0hi5wzbV z81}KYy`PWS={9X_pZ~9iqkcYS5#Dh`=d^5*({p;K#ZqP`qA%XXVd;zX#hjh<|KBlV ziG-W2Q~sZVHFeo^wdxa3#94#WQ?DHBE!2&nBmI^8Cfv-Hn?ckkUf^MwsVFODLPLN*^SpoqGT9z%6<~?iU!{xH*-w zv{vsWPA8?omdCB$aij$SFA*a$n}wGcPGmM)qHVY-k=ZQ9%}sbUX0sSK*Cfhi_3#p( zeTcTmArdv0U&Kt{HnNE@Zaz(^EFz4XwM1=!aq~u^*1))V;#N8Zu1}33TJ`xNLB++m zc?yc6sp2Jy@wfL9V^Non_z%W4{U%flk_+v28%ejMLQ*E z5l*(Ht8 zxf`Q_%z-1*{gk3uV!0`#uGoH3wx|9W4Wj(Ydwjm~){^viF_p}^>Lr+-2)TGhd(A$y|_SoiA}r(*Em7lX}>F1x;EVw-eN)Gmr9`I@vE4J{ywbjr}NV(`IWpoN@DU`r(j+#VD1@gagI1#6ITc(<ZAf?asseb=KutU0CpY3l(S$bZ-Icg2k z6#TK@9QFM>XonWkLTiVmf5W{slg5m`K-nhJ0;6@LjimWTZzfHW<{7OdttX8dJ(IMS zG-C89(i+lSqlfd#5~MjshfubfG~4L5l&vCl*?vFDR*<%t(|ZB$6e^FCwiX4v*Win-pNL{>gGHD@c(qs=Ijgh*jWe?H< z(pr-pOqx$xV{{$TJko^GwRmMw(rTlhzJ)uEkgDU+>s?fhyT~PVW5;8Z%^{7O>>Z@p zpd3MF5M>cz1mU}l%5{;0j5CN@PN9^pco0;q=RKTAmp=$9QnU||u7wa(sAv?gP8UW9 zLevtWl&+ExRG?C85b2T$K^Q@PY{t#%`Uyc8K|UqY#T0@tg1jz>!$m~vdGmTpW-Qys z7Z^}KjzfM`%q)CSgP0oqV#y|ItZ7lpe{-haUZ-j*V;??M4Oheq(?jcD?vG+VK}WIh zfEvnHy5H%8;qE?&J;gmWz6B3xOhr-ReR&_@e1j=@v91dh|qvh>Hfz0hl z9QB#oG4fqEtu&JL>eHBns@4#eWi+O$ZGv)G)%+vu;MSZs_@JZH)|~W6wHNzW?pqjc zjr9)kt%19rCK7?Wzw#OvhQZ7x;i%7Bk4Dko{Q;<*W;PHnQbMcZ?uX(So`S&8HbXh> z?sZx%c>Deb;NI-w_NfiMe{X zX7JFfv*i%=pk6!oU^yCkWSI7j+tLH@_#F=nyMD*5^g#ECH{Wd()aEGfASu^{9(r$v zyDr?&%P9IDnkz-8pSQf`dKw*cJ0$h~&_7e;Xvh(wfAo3mn93i-R0r)eNCGyMa;|p1V|m@O;yIKmRPZC^wP5 zY^8BKX_!vaR@)AF+74fIsfG)Pwt}F0#8qQoUx~7oY9x&Q@>e~NOEp|T^hT3jV|W@TNouJ^ zh1GC3sihimqj$1iOI^!Uza~@AQrA*NaY`}CU_dmEQp_+I5XFd?UN9gUPQ=`T0nw&J zOe`1>twqGFf`ikVJR?&I21LuQL=&_zP|MTndgB$`e=8CEz(SFtHNX!%i=v z(&>9}$WP;3j=KCb&iN>cwx>@p{wE)Sgr{DfL}a>F0+$Atm&3BUBDlOPmUY$#F7N%9 z(p=svDEdj}S7rTKAXIr8Mep)%6=63N)W{*RpE9Jg^mQNN}E-?I) zqpQ#nE|>jBAHAs89~?0D+uscs{^#hPfDq=_+-9S@iPU+y*_7G3+Kf+$+-9Teh}3zx z*_0_j&Uv{Bl}V(foC#>PtoATcb6zQ_M>bSX^zqNoA!S(7kUEXD zn6$-Y4<{`mZ8o|WX(6flW_2NZ@N6+s7d)&_*#gp}$*x1$d{P%eEN;Xd=aIS);?t?P zizulJA?8vxLYlC8XOrfVx)9=O(j3w%ll?2}%_emr#01J_k;YASEUC?wAcWYR$Yx6r zLTpWBvn4VdHKexUNo=;HSW!Pp*=$LXqP~=}*^)vgT@P# zve^=h8+THwHZZ4h2c>EPb1E|g1?E&vmoIT$M6RCvSk%Fg`A{74b1I`z^m8itkW34h z|Nl9a6+NdC++`G+UwL#3F~-UBGrevG8MWJel9C-BE%@2747-btdqx#ahhGtSLlxr1 zy)pc@2uf;sBqSISN%3Y3bE*Y?N0B{1dHvv@+jTpU+hO7Z2njMpsk=;vYV|Dd%y-uz zC&hK_&Fe_Ybs#u?L?i-<;Nw%$qM}(i>Z76(yc~&I9Y@t2Qy8TXRV}a4GmppNG_~&h z*!`Ndkot8>kbm{e&C;jC_j%-AF5F=-xIiQV`R_aweK7bSia!5+=n`!Of7{ohcHVX+ z{_eQ#X(DPtDeikBj;Gysmoqm{X=t8d3kdW~x>ojpNHC=T267KbN8k7OD-r1acjtwh zWz?RoS^QJhheZe);Meiqfv+JhbWZ*D$?i7GokzczQW}24ou9_ChTo;C0mq>1!sZf1 z`x7x7WIDJXDt3#8;LEq56aztq{_7AGNmEGmqV}>SkBA{46M!$C(%W_K$b>I{n~1?5 zHNJs}ksqgpo{eLuVA#jGu3JQk`T~D`yGXc{@G>0oDdD-OPc0b=P=aD-1z15p>u|zW za927chtoS)QIESJQ!#E9Y?dF|(#?W*E^&FC`YPE)m(14YzG@?BqF`Rvr1ZN@wc+&M z!_^!k)dcdo&x=G*mqqNG)OJp ztjDisS^EY3IF)7X7xZJL)ZQ^Y0N->xL|pS0Xf0!jta;I)yAzq8Lx*lnWPT2vnoDGU z4jtQ%C`NCH&h3j^l+jl@_n(iWC(Y-fb3Zv>uhILc`H<-BqYjo`2mhv@8hP0M)28bw zEo_;BeqT<$2D;d~W<4rKC4~V%$h6=}^DY z;5JCP*$kHzPvq-~IDGki1?N(hJ?r-sj3;I1`h5lak+OgNzJk%X0QXxnE-M~LS@yEu zSFjo>JJ;_kSo$csoMW2bSMVMwhqZE-6*rJZp*`g;E1p9dA$3{teSd*&=aRNrE>}+3 z9MV>!lPQ}`nlgGgWwS_Ij1I(`nA~oIW~19uww0M2YX`;fMfCXN1FhU;x6 ztv9;x5wuPdX|2(@q>ZFCMrV^INfSn|Caou>t7=GHNLov(L$F%<1kxH(=ar7*l_f~y zCc7(Tt3eq??LxsSB6z6&l&T;q(UZK77ZTWF4-Pk9)#EP9CS5Fyw!6=B}DL6 zjpw4#iizN@ZlhEY5xi9uQ6Uk$)rCYcB6zEl1O+D6$D!zlp#AX$2GR%0S($jiLk)qX z#sxKcf5UK1X&&moGb@&mKe(Gfil{`shQdG(pe0*^b_`CQM7O z6(Mx0&l#rRYse6s+FyeAn`=1Z*90F$DfP8Z;r~RWgJ+rc^DZd6pa$B$ay#^xUY0}h zx|E`erMCAWqJQPU{AC@!XoDxT{T-r0cpv5sZ=VHir(0#-P)8~HR0dnO649YDZ}=+_ zy(#mC3yA1S8FWn)M774ad<2RNx{Bq@3`3ytd*I7{Ox_dMm8S74c4g*h9ib=B*ZvEu zQaG*_2hhD5o%xTj8ofKzsS%rMtVjeNw;X(?eDq%<@?MR3jOdO_~7j2q-mp)AeK+x(%VW^pk4y@<@>VD@=LW^pCj zfEy8+#T6@BoyaV%NYQG%ln8AcX8&C&t}ZuV_6z2qA##Wc^ovcD$|e#WZ%ExksVt&A zMb$)YfkCcZP+*Wd@W(WhpMaw@`EmH$PZjKsy1dDcKv8r#J-_8K})On64 zCs4{19*T7!ktsYBYY!q*_^9gIHbkcI5k&(81?HhPl(V^cs9)~aLteT1;6l7|waC#- zOO*c2{I0!DuU%F=;#03slqR4u{d+r_OkTog&E0FvFW>3a2Q}uX!@b71$Iw6Dho0Ar z&pn3z=@hRYZI%SSNhx)dt%ee)9eb!!hUP%ZWqd70XOU7-{EGf^QtFETxs%B_wOf4C zXf+&8S!#@b`n(q@mBv4P-jGP*2Lq(&~ zY0?N)c4c!Z8zHSQ`WR(%NnLJzHDz;1U3z^XX*Q|Gq^hwKNV7;wjBfiau8eNf=h?eb zwiV9Rujn5{nj$T<8rCAUj4x*Ncf8(a$`%-1bPvwfM4E5(CDKOHJfjbjTE-VOdJAbi zWg|wXk=Byt8akR*>AMNq2n?s2amYV?en$>*(5O+# zN9AaSQR24`LF7G=((Lk{NPM>7vl*XF_-w>y5})<>ti@*yJ`?z?#%C2iEASb|XBj?A z@mYe;Vtf|ivk;##d=}s{AD?;njN&tb&s==w;4>SaS@=}#=>2;xL(iL+Y=&5?SL^vj zjk+H;7vHJf85}kb-og!=Ol+SM3C0sptrt&Fb@0zY@4-~-- z*lbin73p*w!_y2X)_9aV=V|UeGqQl+uV7!9*;=Os{GnL07tgyF-_hy*2l@NQ4L>Im zfg67DcxMi{;d^k@+tCfEjyGI|zw!76H+-bLh=>h|`#l|p)9$zP^X`?pNK27#_kN{* zKb%W@xyhdDpSn5j(y!G2_Baa@=@0%XMduIR#v$$TTJ5(-Zr9t;9xPmHOfoyVTQgF1({SKe(>+W!jtckxTBBQeU=;-AJdD`m0x@1@H{-eZ7zK zb`wEc7y8C+subusc-ZD+wQ?z^1Ezcbn8dAh7DoAO`Re5mFiDGC~czQ zZX%tKM*KD zS&N_DD8DkP#m{l8_lsNfrrq=ZGS!16#d`7Xr6Hw?8Ysocne&U!Qi@?S^TAsv#h97- z;FUxSn3)frPsC`M^NS@!43(J=9zw)8nQr)Co{>Q^^>8Fnn+z$UK~cTb4dsi}RCuR> zB0){f)uTBma-!jzgfn9}r*DtZ+ZHvYCcZ95L!jdY%?u7VJJg~zXDlNK61m$ZpAW^_DhBWZ!r zqgZc}G~eiO%GQ(S8685|TGFV|)hJs-8Zp|BvI){$qwmc^>r|8G7=7yq=tC80w$VA1 ztsu=ZI*T+;+GgWSIcXVbtI^4s1^5n0Avtf&vqU>SFjqIYMa zIV|HYRP>H6(5fuAj2lBiBavm?7!7XY7cJw)fN(3N>I197FQim$U{&}9BE@kcqGy|g zq8}Lc#}_y-6v*EkU@$HWK~YB(j0u}UGHp!wPi`vvZ^+AozdsSm(Kls|-sPHbKT7vz zP4?*PRVjlxdhL2{xMd_bNF)Nm#(F6FU}IGjy-uy}UbrqRzm{C5RU^oOQoSo>>KK&j zgF{sJ)0C=nj#|OUBGOZ2L5Ijnn7%Px0*Vi2wz zH&&*0wK6KkYy&*R(ra$VIz|BUa1B9{qQ zvuv&?Q%BB!**4Onwn+1%tGy+_?Z3*hhWjy9h}RF)-tTz%_k5OBVd(8eJ`nz2jiR3> zyA(xlk!PdmE%HPuy4jW^@V8Su^y1+-m0KJN!yE=F>B;m5!C{Z@-Ha@?ERzs*e|clF zMyhf@-=Lf3cUoqfo=Np?mF=A~^!kHVyVf7P)jEru3?bD;804j6Ra3PIV2{ViQ7SIX zG4CDMny|)E_%5s&rZ}8s?HqL0AePmd(OFwc<=G%%Wcgi8M=;7q*LU{nfAV zmY&t~jHyiNl^n`mE$zt{S0G&NwfQ~$ct-QP|BFoKx6ab8%7*rMqSQqNcK1swbzx23bogj;!};Sy-tm*y-tm(y-tm% zy-tm#^TH9nCQ@FNg`=v>?RBcW?RBcG?RBc0?R9N(bN|_gf->9&m)^d)Ip!-%#dG!K zkEzqW_QyjX&ghRfPG$1PQ`Adm42PCHl;)4m-Aq)x<7MAXm)nr+1Meq=FkA4E_Y?c7 zSzw)^vy^H|>0n%@3R1zc4#u#NGL+q53>z8w8Vo{pL!@XUlu|_z1RL3dNVP@~Y-AfE zRUtvJkpV=iPl8}0xwuF-%?}${T8T3jPzpBELX=Mg8+nN+j|g`1s3699u#9FfhAUDoG@2+7gj(%Dee6e#HTB?y@F2= zx5-9`*Ce-#hPg!~=oZj0w~w~Fmxj3vhx`-7gBGZywo|?8M+vIdSg0}M6U2E@O(^Df z`vh_F5{^t=T2QT?>6fYQCX)6Tbi%4WPHi+t{}zNWZ=E#MypLCMH&8uDDGfv1D0M-T z){Zq|H0OrYbV#`{Bw^K^OG<6`s~N|WQsKSH?MF(T_f|I=7vvVx#;x9glr_yS(>wk> zk-AlBZkXQ>mjyK+=J!t`)BIxn;%h{v`9+G7L{ZiS^P4+L8>T!$1oOL>NS(Btu|U5# zm0!#u%2#w5rLu`&e&Z>XMFjKvvmn|UG;9wPRgH4Bj^Dpx3MU%2ISzT#>yNs;>8*ld zTC^R`lveccgiI`8nm2M=MpC*iY?|Q=tcS4yn!R~>ShJ`1^_uO%o%T!3?z|p-0U{5! z{k+K+dqLH8ZzB}w1(BeCr}jL?vO0ID&OI!vbBErX`x3OPjJ*iGsep*fw4gU<6H(Xc zwvQ#EqEm0i<62D1nPu-rDN}Li&0r!^ap=u@L7=FT2*2+2TvGPFf0Ol@IJH|1o3tACqihjts5d&C zlxpCguMH%nCiv%TtC3O}{PVS?lcA^72mgHSJ<>d$t;){!Rsp(klOWH^pH9DI#Ng6SFHEBI*uF(rgYe{pAP9Uuz z%{F=*uPi~DWpr1{R+F~b$hQ+^t4Ldou0`1j(v;DKjkvcsX^YWC7lW3OGMH#cy+m3{ z+GMg1la`RWxZ%Ow(UQfaNt2yM*&k?7>`2t3Q;;9?TUeI)v9{59aa}Vzr*qKGGO)X&>rKEFeIZbj7{PttD3H&vUUK2vZwEd=fSB&|7$OeYe)(e#Lr zzh&MiZ<9*O+obB{x9V%&w-zUss>3Mpe{>HxB+0E%7 zG+HP}omo5wNpBX9qNqVQ?rZAPDw%d)8d}S1A%gEUeyfWcV-NP?H)-|dE)hAW+%?`g zv%{Tk0z~uAW=<;0{=YXv6Clz;4XI1sbrT@rY8KxiK~cx^pmY8pHg4I)$N6gSl0ry! z(JX(nvCz8Dp{QCQjW54;`xk2hEHUlla#(GKz)##>$0k4)>we-k+^?~2o`~VhBXFu< zzuwvA`xQ>{k0KFx47D*XReKA){&QJcuV?uiL9c%xN8K&IhQB-1`DvE*i3|GunVmYh zL-c#5)!N(h*7L$@9kSovXehQdjaf;1{L#!9C#D?A#Fi z<&Jt=X*v9J=W46C$Tnf)(EEP} z$k~6&=rg3HwCNV350IMuHyfQvYWCk`^z<`fie~?fMki60_V0Ipj-o7GfZzQ&lCtyy zJ_{Z|Svmrr1^1^ceSyz{zc?e{4ty5;*$`MUJ%V3l`V?j96#OdFdr0XQ{3_FHN$DE= z1Kx{C=^gwt-if4bNF4lQ-V=BYt)#`)IwL5XB6V5t&XjE-Ei~D+DcejMGrH__+;J0W zfzeM$8%bRj{9zv2AxWBNvX4-;f`}i<3>N-4%eFv%29Y81+$1s)iXRmWch80q8o@Tzb#f&No4tLk)jG# zZ~1MZqT?uK`K<(k@5hPz@by)(TP_>hxPDWW|AIti@1+HUPmg7=}-xwj)`Rs&& zVlG77^A`AxengB*7%qNu5*#0c5=QSI5HTWQ^!_3d!x7GbJVL}+gtKV%vXBctLvrQ6 z@i2puQRuyyy3VWPL3kM?It7rj{B60tOY*SZJxl3+4J!2fg^A%#ANHB+boRh(NT3Jd zwr8@eJ&3lS71g^(JPn6EP0E2d{Ui|&OgN20(a+25kD@n`5vZGvdIV4G_twEkJ-AP7hX>Sr=XVO$)8{HCFQLNs+PO@=CZlsX<(W**Wx?}ZIhS3e znt*e8CJW95hP6qFxeprF=38nrYsT@+px;Fw!m1XstbK?+ zeTHSVLiB0F7U)y8LiFh!IPTg$PtP!es1ykTjp)M2F5{1d%~vzM+`z^Yv$(ifZ>$VXOb=n7)B}S691mnwIJm(H>Iz_^CePtk6-TjFe!V;FZXeJ=8NdKuSuSbHV%)Ef#~tU8wix|F*ML=)XOp@N z;2Fwhk-7|E+I^^@jj?m1)i9H?t)xk#Q%F;!E(4fE+Cu6wfQh_@X3`p~VI*anNE1f4 zCT%2j89;y1B&o{)+KW*pK81-*&*VUP0}&l2$I40~dP@$M z6$4>OHl#sgkE0a*B!|mFB05RNo+F6pAsKsaB?#lZ43!(>Z?Cy)LE6tC{{d%B(_9%F zfAxlo&Wn_F$>rDf7W4ZsVs^FrsTWVWlGya)^;ny%s;YOY73xZtUXG)EemrJX zUUpJ+GijdnFA%~A?}mZ0ji9bN!n-lxAWG>7?*@PkaU*y(ld!tBg_IlNo%dg#w3MTj zvztDo)K+ghi;se)Q(?XRe7YeN)N~dmG>?L&v!&Xy4-lEo!jNttGM$AjRT7!b7U>ty zAiP%XOD z-0=Lxn^QApD)Z_yWhz@f*;S@eCDjBnl|TMV1gCkmJ8PWTs8_jTLHsnq2^*+Q`)Pu` z<)}Gy=-DuqH9>)rZO*bLDA2Ih+aRwF9qQE=$6bN~_4@hdjntz zv=2@b)Kkig1L}1Lkr_us6=w#K83)wtVnI+sQL{67*bD`#b_P!6-St>Vh^l3nlQf_-7}|x^UQGE#h;eUTe`+9`(T9(9rA2>|Y64ocQ1`obtk&G_aHkdi zMWx&3dRLl~uta+zn^NjZTMR9@#i@sXMd?RHP=_)&4Zl?LMN%q>U#j^KDfPrZr26~% z0afu2sV=81wZ%WAI*XJF;~!ETO-h~d52<3LR2Bb_Y6sGMUT>A%*oLHeq|8cXMC6r4 zN#iEldKm7Q{?$LETCyJQBA2qICOe<9Iiw{fzble7EwJv3wNTXK6FNfk98c8EYQ=~~!_mJvU z(t1+&km_;LTGDK*;ZD*T(k!F5_D4%5NZV}4K9921q^(BJp==dt%IKddTS3}lblsbA z7je>NqnlE;jI_zTSThkjrQ?BNDE0_gmM#U zj5J}g6{H2E9E}=MXOQNTR+;RPqeKleEjUtq*L9Ebcvs(h)QF-whpaeYW;965fQVC8?$ zj>HwcWHa<=s!s$_S*v(}?xV6^tYI8`pz2>R8GdwuONN;sZZ8t-cIe9vYpWJ`eOVjd zr@nmnH;X(*B~(Ga8|xGe`tn1LYG+zdn_&&(s=C^z%U_7-{Z6_=ht=`DCC~DAHuf>g}7)tfh-o?4&dvc=8JL!7-)jzq|hSU>< z?%G@I+P7%JwYMO5s9nqTKvJb|ks@=4MlH@jQJcA05>ffasMMIs4=rzgM8Yur(Ng|Q zUnu+R{ynbY0Dip-GKOA#?#mQwP`mZGqB7ic@0^#h z>7KnOQ`2odr>myBMyd%!tph*Rrt=d3Wq)>!;8$XvKopz+IDQRnHZ0C`!|PZgNovXy zSsaJA!570508t3KDSkJ$W>MCnRyVf(^m{#z+jbPUdS4%-*XXvMm1$o+MZ}Pm&zSBf zV!X=dO!u)m%WI1Dixre&q{{ScDy0~vGDAC-QjAeKnRWmX15{>cyAd%uWrjAGh@mMn zwDpJ>m(o}Emoo+?09HZKPXK(fzbdq-tYl`3f9JFrD*CPz0}}v`i6mT1dRF$^jH}^E zfF1ajEe*Z_t!Q7fmX0ZAFU75jjsU~0sxgV<;upiIb&)EPw@toCN z_aHc$fTDH}983|4>gM5Kc9Jg#2D&Kf;`p$gNQ%|yya0M{W0rMZ03PP2KXui8!RNtM z`%e?Y6V*La-(b+y?+yEJ#Co?UF^+Qw2lUULa|60xra2Bmm>qQ66k|l{9NH|k7`>Wz z4jOCdr4A!f=a4eA36OIREk=JwTFUgS+32^~a0BKXnv8xxT1?qSqYv*Ja1K8GeUP&B z4?g{!Mp?QDpZ-pzEWLzJe~+Q8rL+k<+c?V7SNQaIC}rs`{2I;eDNB#x*J!RvSxaf- zR`1s_+y(uHPk-MbrR(rdWuGCX75=QE!j$1WU^Bzn<6bVdNE~N zNMlA1qii#2fzgqqO{Doow_s>rIkIjkb@*9oLgaj4oRR*IP@PYxFhB){y2H zeTA|K(rlx5QMQ^i%jj*Cts-^l@A;IiAZ@kb<^<9>Y0BsUq-CTnM)zaArKB$X-Hfs& zq)jHf25B*AqtWm8q5hI4jeba4Nb1tx_jLJ|ydj%ZJ*^sB9c2qh-S|9*viYP5ldYs| z9;r)z%PAWrtuoo8C>tSlL-c6UT++D74k66}W%`@PO0$Vd^-6z7sVt%rMQx*S`F-#P2zdE}Q3t(z43a+m-4c>IJk)4Cxv08RI`i8M(f>WEZ+o5gC)a6)(%{`T z7BiVVzv~s6z0Vf++e?*I2hApzEzV2N76*$&Ku-WQ(nP zYSpSIjqbr)CFdX}2BwRun#y3V} zuM#m#U|2nuh%o{qvwMjcATTw;w^^5>(@Nzi zZy9|yqEf3vAEM93;>!qS(PtxB);=uI78}B{_F=x3hf3|zsMd#hiq?dPTeA>Vv}_Ob zwDn;`QA!X~BXrhVD2mZYN4-R8>)wP)KT2fXTchZaU-ZnKI_r?`J+6k&vf57Tme+Ek zKB;RzeIe15`NcitGn1E;AADf?x5 z^`r%)E(pApG@sN3fme{`k+xarat>*f)CGaXq!H4T$sWlo%O!0wI*hV8q|HY2D4R{{ zg1~IbW|20U?91h7hc*UPNu%%X2HHwmZ}eHx6sZdWYe`#3YfSduWoXG}(uC1VDceNK zF{2@MDrqCB3j&Kslce-S4XHgz>q+BQ?>3~hpd2^`5Y-Tssy^rPni53tMN4}~U3V$I7$<^fx{Fd}L~u^m5S0?aKTReoA%cI3^Nhtr@K57J zDlkv8KZ+XK!8eUS9UR<;;E)dP@JpMbsI!jnN$WsTd{X*6jm~R#@0R}Gcq^kg*Wg0E zDGbPp#b<^cYk1_NZuZ)*&ORZdU%lo!(WOp)^#}E~8U5<9QcYm0=!*p+IL)sX*=J`} z3hCQ&r}x7^R4>X@!FOuYkyUj8`o5kVwV@Qsz6#444nfnu%g1pYN}=ZSCZnuFDRle| z9Ct%0bo^-|I$jRIwM6u~9D{EpqRVB_bi?XLz%pUp1(`YuGQ1MyQ8}}IXhPH zje5w%bbhw}VF+Q4&W!~ReXG5UVcrb{S5Zob`Gk4vBQAD&=HHlbGNjxv?}mUwNU3e! z4E7+U!g*5|Olmp@bBN+<-0VF}Vr5F1&cP~LhwIh2w}Qej-Xk(SgKa!d#BrVG@i0*y z^%v%GJ5iLVK%4S5UGe4LjhL^fiil%5&EsT#F^6A_s?*`m;c)KGIYbdGOH(VQm~;5n9kE_v+*IIhkUT|b-0)p?@dXQJ$! zC;I&|BC0d{z5E+!hdEF5doiUFT<97)6>PvHcueQptt*x;Kgy45lhIZElar8Sah6Yed{Z6x? zkIqAvX?oFQXz36|&hIoDeUFqK3# zr;)Pj{LKF0r1U|4W`8eIx*Mo>gD`|nrP9RN@<{KSL+CrLV zbPTVznKWv25M`T4BSzOEZ6wV#`os3PvLtDa(M6>7q%Ns@iL{n9%VZxWts!l*!R^5> z(UJ+$R-@A>TTPlWI+e0jq%B5|p=z93Xon z0Jr`srR4z~Bf^#zvH5Vy$W=DIn!^vj zaPGXrT)NmK-S6L9cS42eOfX$cswO=@T{TIgm~b^irJ6vx_~g?fXo~|j*xJQ9P_B(W zw>l(LXy3}IA;#Pn&vaozy`JquIm(qCI_cLZ<0FBcUXa(%c3MEj_UJMDN!dI6n(ZBa zrylCsLNcFGDc+Clf1Vm@izdCgC$DgA5w2!SsV2}Cf1ii8Km$fTb6;xII@U%}%m?kM zcZd_)3bd<6{M>c+)Qk0sw+znD<^R5`p!Km&l5;z=NCd_&(jh1RU~i zU>|%@)B75|kDVZy<_0pXSNvY%?k?9Wy7%AA9E>U)gm2|DY-;QVemc zphKpLs7r$)Lx)Uth|3UF#674AIz-(vrm2i66MPXAXT}#%MO=oU2&N|L78F5Mm?9WN z6>**4dOq)Gt=T!5WTySr_xEk2sqRb&?l!8J- zQAIvqPifxmbe;9(n;@JS+Z5d(Y#DQcXI`~)j(-%o+TM5*DhwI(!W&WH#+V%Z3Kdq2 z`N4@Gd>G3nhk`I+%nx=4;lLO^6#-@Dh1-Wu%ghTm)gkl3m84Ab!c}x$mPa&vmeS#% z;qygTlKgq$%B;zm@yJiG1J~q+fBI9YY~;H6!}IJb!Q;Ujcyome*gO!@EF1?d;>KKrI!i6XS$&FmW>i_kttug^{q8s}M0gDgU= zBHG#CFBBuR+v#=CI%Wf1PA`OdgvQy{L?{uOW?OsfgnaQPJx4VjEpeJ=TN|JyRMTv0 z6xs^TA?N3?2wDO*&9**!S&>c5rrFk0>nKqWwrRHYI9eh%&9<&VOYo-WsLq2Dzv(%u zQ=o;MS*@ShVbB6-jniGB{j#a)XD-HZ4t>xn*N#Nn3$1jz7TO+Yh0~AL*0ps*<7{g- zv!!PUF)mp{-8$LR$gNIo%y?IW*SE_0g6=n_ase+EQq&lXFXS#U;=N z*S-!d7Nt%;4JrbuPCoUb`lS$5YbW1^ssL1D=u(i+qf{r)1o=Fw%2X$Sd>&P4=y;m< zc~pg=T~YZws@zZ&Du1*}iF|92J&F_Ro055Pcw=U^wOUYQY}UtXS|^aq3-nU5S?~Ti zRsp5*E-443@-MnZ{$KlpW?%Hzhj@l6Z{}6FY6y&8TFT{ zB--4o*ap;FYs?!AFNOc(0ov@PCv<2Ypxq9i(r<{{VCal9BlFyuANbzAB%HR-jfVUc z1wwJiN}m6?#ZF`66saSeNcu^>&3_((F*{w<8DDamg{axQ{ARuqn#oL&rp^dLUmAaN zb?*Uo4*wJm2^NL;i_gc1Ps9x#y*~zF9|-5MAiM*+g`0yg4&2FgK-Fq1%yn1b7{4$kXQ#KkF2oO|cl8H4&8)Ax`Qqg3qE{Fxk$hdX zm(6cJr_MHC7hS^KRqcxPm6~V~K7TgelJtj9pOwn*N_xcR@`LQXapo2M!F6c4H|Y_Z z3!&Ve^oY$wD0e9R64og?f%xD}^atb7R^o`FKiC#p0ge7(6to-~{lN-Q_jS=9e71_N zq7-efSHRbxCD0zHv%9Tp8jGRPAKZ!7eO>eix1lXW+vzP#MOy&va60}#okPFMW|})6 zgtiYF{lPeBFSONL_%5^unsd4d=gF zQT)NJpf*sQ1=kgzR*;g%bbB~#a$^pp1abXnAxI~-fR(zv^GKfRuIb|2$)t5+Iv_vkp*D~-6{ zg1la7#9ag;CsM*%{-{VGAyUGQLq#^Egw=p3S)qhgaZD1Vgl!#AW@mRpDF%$df6C78 zpKWPoA$E32bi?1(Ggr*NtM8qc?rO|)he)LQ6_eb-PpUFm{mOYJ+7^}V?8fv~xUX)R ztxLq*wu)4-e#P9j7?c~;7)R4vE7;o`{a$HAJqPl8RcC|j*(Y@S{9b8f-GYjH#ps#_ z^4p~Wb~dO&1%NSj5{PPrO{xWzq0&ej4=M#|r0u~;lz=qSMuVtOjI`Cm8#B3W&7jDv z5q`eBM@tx8f7Sof8sY44h?6%L(Pu~)n$@uAQe-nhBkS_Up>_-iqUxmYrpPt$^z)$~F zuO>gezur5~Pw&EU^3$vR$lBJg_Gy%C#OujVuc_mhpEN|i24dJVM3xTcFmKG4*Z_aE z$Qt(VK$DD~1Tp5raJipjAMiPQS6e`gH4T|*QhX79`h+3U(V!~RKfIsLpBBBf)qF=o z_fO_G8n!-msL^m$XeKinHnwjG&-)VUnak;>*$>+GxHX^rs5PaB<+>dmjLK45m!l1; z^+ro=osPDVDyFs$r=?Ktaau549!hFU3#QBJqvN;TTfK!>m(~5}W~awfx}eRMDK9OU{tzu$FFl@8iI&8dzG_f{ zwupA)JZLFsA=J!@jorU3qbn|e#@Wyvdy4kUET#!jC)z$}xwmi=v=>_D^w&_g=A}+s z9@e#Wqb+e-hqen^?DR*_PH2(S??c_17dqV#+Kx6(h>D?Y(0(tTi$YtWeNI1rNN0ve zZ|rsY^w-o6Eogh3K7qCw+U@i=Xq%v2PV2_21^jyYvs|a5tw-D8+FEEGwB6}$&{}9T z3OjQSHPGl4)RKC(G z)36N4S6WpOK3+<1^p)09d*espFFa%xOuK`EnpJGCKBzaaV0xEcN(-jf>o7f@a=DcA ztpHz~d6+xH0{%Z?;WTfVbg@-JDw{adipqRl(n39-(qVV_wL%*b*>%#YrnF94Vv64f zMP^8J&a$k*kob*WG7r;c%Im^Q%uw3x@Kp?E>kR$wB2CbSty2*gLzIQGN=lwwKO-op( z4VbcA4$4khE_=XQ*OFUIKvO{3Da)aHW31~j`y41?Tyl%qXG^ryb+XSE2y0Z#SjSxv z6&0Py@FF0}Ia8Lmzp7k7EoV*lE&GEE=}8A=pH5U%ai%P@P*K8}98X6@{bqf4Dv09E z`tHdfDmQ-g@PIN?mLKWR#*?zozTuNJ@`4B5RsT;@mNKZ>atb78RN2V|a89sY@i{NcRA#`7J{8y^_%)S%&f!C`j)<~M1XTQ*=gpLuBz`tMo2 z`W3qc*5|4RuiqbISi%3C4%5>R4~4@R{MUsy5(Hy%7Vej-p|r%FlXTE635hH|3gLfe z;*vE&*DcJmN(=KWd9h9^yN)z*Qd)87ckA@tV)4w=V-Gzb3*TN>y?CEptHRgvtX<;6 zAPe7aN4E>b@Qwcc3TPb`v(vR_K?&dV%)<##A~;$2U35Z?1aY$PJE0|x(=!k2pe2-( zg=kVd83VQ-NS@`$vwQFr8rjvz#2rXfqEc`6AM0T?9m!l=PlZBrQE#e$% z{Tz;i7D8*B?h7q|Ry*Ah+AsT)b~Co;9QvS@u3ZgnFSNqx%4mC_?Fwj{pgm4ME6^1;K)ap32Caui3qSiFU0WTL52V+9?Hwj3HQ{90(sps|RqfwmOd;O)LYS3kf| zB1#c`8B`3avrvBwR0OIu^r(LCyRi^dW9S-G1)yp}7l8aR2o=#uAUEfgrm6$EIj=Bu zG|js?FE{i9RQ?!5nW3?${4ofn?9BtpSojg)O&PydtT*7-KK|TZN*4aJyJD_ywWi+= zhk5IM{~O;K`%kd%b7$B+oIAsATb`Alxw4!?Ux@zsJBPpf+3Mv-MbFR^s(O01`m?>m z?ag|IF1zUm?r%5UJVS5ZBiav@4)6?no*#tvyBIS*jpM7s8n`MPM$-`vFVvxxeS2Lao>{?e0TjmH5mpUz2vyI43RA{4Y=y)zDb z1?(%I==Wg4A|0#rPjQ@9UVqQA?F=bSXK)-$08aO|JFEvA>s7aKy5~wV;I~Ik15x|g z2Kq@rL?dojhrx)M+eM8hz+PEm`ne;VP^X?=7~b}pbshZMBS)Em zU6|h8y^c_*z;%F@BJD@Tb z7OVMMQu#edKLYaFcB**p!eTXl|0Csp?nHV*;YBDto}N&65K5<~9|8G&yY9HVuvpD6 zMO%q~iPiiJXazJ@^JAdp&{)m)fw~Lp^?Ef1T8g&E=|<2JXsqVzb7sZRSj`th>n^O* zTbO&BuA&fahtp^J)jI{ySj{gTt)A>xolAeGVTulQ@TN zXsqVDqwRu{5@z*o4ef+Bc)ROCJ4C7GD}vfVb(S&~0kwgY6yE+&7upI^VtC8`KtpBS}>8P4O$`VIbWZV{s;$&3ysLJe(hlA=srH1wlC^IGAJA4{z zDoPUNdIQz`+fv%hEoX0BLx<@Jg=M82kR1M!}2-t>XbDXgLtMkE#8qf6F93O3)`aYs8cFSaf+B6)7*2q6au8*)h^?4u~Pz zY6I`Tr5H5Q{)Z3J9ZEqO^dMcnV<1HhfA{|UJqyNcJ=*&6c=ytGlU{hwx<~aWCapi+ zWZk2B6f@RssH`5vbk(5N^|z^Ft~y7mSdU_^Itl9cq~7|j7DO>(TRSQGoC=OM)tt%~`(t;IA45lpY+-Y)~1hayzds5Jd-5^O%0}yRih7 za@Fqw%H*m`!kaQr99*VXLqZCps6j8K<-23lyakI!(1AJ}G=hfrG5^?)73DA7P2)i( zyW{zZB7dYUOrB_YH$P7-a!ed)+}`7*uuIpiJuDn%yy+2bF;D20j+J;`V%UP?lo&>F zoV@A#Ti8IK_mu6DdVN4*_@Gbs-v^;?<7|)*!V;=KoRq_*Chc z4)XD-TRK%}z%BiUz3Gk%>rMORBZtogAH0))hxR`@-l4Qh|F}fT1>NpVyRJ{Upv%#< zs4N$BI{I08ya8!_uTiR)3))?HG?d$r*7x>?awpRI-gtd<+_=wq3mc%N)6*9H%24t` zTHjj)N@_^!dvCt2p+I&>>w8Z@Nf2p$?;a>QBCYS;d7bJ9X(DaWpNE!Ak+$fkqAkW* zR{K>PhPDVACjz@d3!!l?uobib8m9w`d{<7ZUmhyW2$n!yWbr?;W)f)+WQ26b;5X9QEAc+BbWefr-lBIcr3#9hqgiEj9@Gj zlbW{Z$8csjv_0O!8faUf-A-3Q+YF5}f_LYrA26(Gi{5|Rr~z$HsH1+;*y?Ld3fS1{Qb`z z!tl&4>9yHFo4S(?T5}lr&GfH0U`cP%#2}oK4Dg?NZF~$czz>3KTPy}>=hfD_w#8y} z&H&khObpFty)hQO7@EJ5Fs_T$+sPh=kcx*xIuw-~429-sRMa{Q@P;4?9n+}QKvX#l z@T#;$iNgTD|C+*_`i24i+f{Z=zWv2y{V`NjHVp9ZK$JD6RM!NQF~Aq=(57{AO;dD; z0X`>u1oL<~rqlI_$p9aqrbB2B{yx$d5u*7fc+sIvaNfur{T#1l8aKJmlqHzalKc?QpDiq4w>rP8_Wk;NyQ*@#`E}KGI}X)V zD}`n#DTN{qbK?g!j60c@1O{-s9-iE39=zcr?FHf-J%3=~9^0dW$DwH@+7I;sckk56K1>OxU(Vn)rzlD~7PZoGxw8VU}z@N{~gnhEW zA5XVyjT_$$e!fqjCHRvCeiSY7pDgfIXx-MjjhwEn4%*@LKD4z^YIpeiAJ7_Tn`g=O|CKKmnTd!X`N?^1i??m?BYz~9$l zdMarhy#Wh6N-w1}Ul?AZJ}AvEtxp?NXTOLV`=4Wj=gzRZ#};>Fy!r(|Y}}I&Q32#>ZS9qb8#@)}a4kP-V>J);dh) zazh;k=M%im+O$V~WsQD05XF^M)=&Rr*EDGG>!%Dx?=e&i$SaNy8^+dp_+u4nF@$8F z{ZhkxHjMLq5EXIATdNt%fjYD7`us!tq&2x%5Vw{{)00ZCBj3A3_rc6dEQKqhvNgF_ z2UkL6<|P)vcb_NuQ*vVwyzQHsp}TpBMez4%>D;t4d;^sJO*_LEL7AsC#v*wB#dezU zd+xCa9)-4&bBIN7FK7ic7QxX_<}7I)XnklI+8$5-BcP?wSOn)jNB)P#BKXNgIx{yf zu?Rki*3C6K-C0N5!_~NbyowZ%-*;Qs(O&}!S@2n%*Hgpo9OoMK4(@%Gsr#r}k{?n{mu`j+^|t|C;M7 zJp5tzFF)7^x|88urviP}llg&OwtE~#MD~?ZB&&EqILuhZi_VSXi3Q0Mq@HIL592sR z_Ffz(tLVRNRL_klv;N#vk^xq6t$;G6VR;=Ut2iQ@gC;@YR(<$HHV5c-{RQNKu3PrF z(12U^58A{j3menD@^r(;^p-lUY)oIVYrGlh8yO=cl27b%pSa>Vx(OD+osQmlTtRI< zvBOcjel|$YakM*nP%01Nv_y3?lsHaHRF^^t<+Ma~QL_Sx&P_{H$Dk#k(-PG_P+~eQ zQH_BT)@he^BPfxbmZ(;N65MHtYB4DBopx#GPR)dP+NFJ_OXH(N<1Ia_`6Sw6XmsS) zqAh|}dY_#SEreRdwLyCtv;Z2d`51nos9!E8x%1u8x=$?i7Pf}EPb_h|9@KqeT%uZs z^X;bHBG-QMn6AxzVxiMlp!meJOZylUtJv7@N&a?dJMH#4y#k71Oz!+FD4wyg$F-Bs zR-Y z3Agefh>FD8R_A0T1j-THr&pk&7U43dqoNSuGEYH86=Fhi1gKO+feFc80cBifr4HFb z{ht1xT;{g=h~zTMbU47We6cQb>H=Km!hZ+hj+zeYjGCs4FCe5=$3NB}@2A zv;4RmMq~{(Gp|H5-y6iglntyYkTeioo_L; z#_3FG5wzOr_0U3Sw1h3t0%)acPlxuasHUabQybOmeb92(?uoV+TIO^&v^~&Lr{6-` z4ULv?MQ9ha*tMVkUf0$MEpqztFLVwa&_btAplyd1IDHgt8#G$NtI)PW`#j}ON1KE8 zI{i7?7HE&t9W|_UQ z?Q~s#_P2GW1Xacoo*fjKBz~ISfF(RY%47)-mNHqw?e%FPiU03B9rXWq;dbr}8?axr zEu1^U?j1Xqc^2{Y6+=nuI^Dl;gBqRIKCZ2Q@Gk4~Vs)QX8j*p~cLge67P?wV_sQuXgJYzx8nVf2fMo zzcD#``F0S+kNL_~LIZr)?t>Ti*hL(@N7zTS_QF1*+6YY^dz@{;&aBF};{#XfCeESm z4Cz7C-K*+cvfVvt+t}Ud5t{e!vCEQisPN4GH+!NC?;Xp~W2nq~#~Sn~Dl-nT09_+h zG!C%<9jzZe@{UV8hNqyV@6wLpVNf>?u>kD~b>k2V&^Vny+((QBXe8Q7N^UGb%R${Z z!~*ou-MXc29C|$Q&W5^ihy~~oXesT+0(2YHjYBLzH`{Y&>G!fbyxl2i-8jSobOzc& z+KmNhf3$8KVgVY-?-undK{w{S-A&N;L1O`01KJCX1!xIq4>T5_#W;sQ|lC#VxtXE87X)B#cfnht6QsQ^s{wSg4dCxco+Ro2!?C#&CbAQhlJQMG_nfX1V0 z2B`p*p=tst&Ocf_yNRe+Un;0F%fg@hZa}Qh35Rh_;;$#gte`l5T*|a#c%PI5V*KB2 zO(Ji<@NCuzEJ5Taro456h1f%wbfAw* z3O12?UQt+w<5Uz@;5Ze97x{gldPN+Q@xD7W)IGOru)GjZX0SY}!?cHRj}Akf2zv;> zKT)HWOh#eI(H?1x!f=+*pg|LM2M3pjQ1rve4fUwWNyVC^)-2#oOq@g77`{e)aC`pE z*nf+7Gt&CZ<3Xe%nKl6*uaEa2Z36yQEosFjW{?T`1tObnl0GIQu{)vMaiWf6c~#ddhN4)F@PpvFez?4>KhOFTZ+YKNz*twBR!^qxbFgunN> zgD`S3`+v8w*>5Evf5;4U6$=r&vu?{DE@j`1!-ZhIQi|l@F3{mT2iIaxm1P{<@w}db z^-zveu(82Y}Z4Dot)jF4Ks=Rlz*xl*T^Gzg@gX?q$_nir`m(zCMGN{bKwY%!+ z&+X#1!`J5MwHfLUa${P!c^pbmriGh3q4Zr^xVcR~6&}Bx+3f93MN4$1g_{$h1ZY~g zIS5LOriGhvP{K4V+dHr@g%QZ_yQ(K&$+G-#yMcu(23g z>GVOgMbK!MZ-y2^qhr1lS^$lv`Jm7AY3|@kz1?Hbx`T_pc^{}dxMJ6ifx3e$aypvx zbq81IbQQEXxU`qI7!(ti_VV7kS!afiYwU9m_zV;)m-h1Rh2rMYUf#7(3|-pGyZTu5 zB%ZFZ%iBE-Ew(Q0<(-5UXP5T!c1Mf3OM7{%e5&(pkmXCi!LlCOdT8{`Ux(H~bAAq= z+@uz2q0u*gc#O`s1{!_yV`!_P(Kp`?t%5dqyH`LfMJasEpbC&`-zlJSkZRu%pfZqZ z-{G81DM+>N`>0Als(ss|Dh5?rjrj(uB9Lm|(x5_+YG412>Vg80vg^Gc3;BvqskQY) zP-Qag{W?q;_7=6l!p$9Zu_UVQT_k1l&1XtEAhZ6nD&E`~7S?lTSQ!6%FW7|TnepLI zt%dJj_1L}HZUrsRbcBe{FYbBHe1U#2f8XNS=jXd`G4pF7KnCqwj9T8p#>#$vGv|h8 zGW!;5*!SAzeSh-!8}hB?!GZXKM2xe8erk;mu$EPzWGy%3UCCOO>GkLv6kbb963f5B zYbjKmpPYAca>8Dhd|X z@;FpfD>k@l0?Js+U3G|w8KeJO^eMzP*PE^1TWvUOq2@z~4PG1lqU`0WL)%M6;KKfm z!XvMNZigF(LmnIGj2nG= zVkPG>{=RTR_LCSE*T{m=)Ee(pB3z0gu`;bycw z&=RLp&~`(MolbyuL8G7BAKD2mbnQO0+W{?bx(V8LXurFVjnKA1qn}#>Z7a0bwTq$6 zL3^A&e~o&l1={WOnOgNjGc@|S8_+gEJ6(Gbv;o@TbP}{4+V1o;+O31OIo%6wEwt6? zXlM;I=X8B&HMGU)2xt{F`nj+3X_e4eXI^jB6<0tTyoFZ|(-oJC;^#ULmVxRlDr@UF+A0K98rm6E0jR>zRv>q3DmbN}>@R4H0A+tc zW5v*X#?QTXwG|snol3GF9BP+Kl6@ompE{&s^PrTLb5(2}mhwwK7aXSznYlA;h|HZ~ zqayfG{cHC=_)-09cR2jIul}|BICqBKy16s#Zm|KExAj(lx3lW7KyOF-8@^I4b(Ib8 z>}tYsBhzX^%zm$2X(Cmsa!)XSIoL*o>{rZt_n@*$6_eiGsH{@OjCYY#u~Nm1xBuIU zGOtuI;~j<8D^<*RdqKTY#f&!^>Xj;HysdQtaX%<#yb)-%-)>Pd-lGV+K+1S` zf;vIUc&(rgkTTx+pmvZl-szw=kTTxUpjMDF-cLD+97q{&EUFfeGF~OBW>A^s#dT0M zfl3X{c{BRy5<6TZC^Eaef1PffK*oDD{GZ&YjQ9EhmH^WXwo}S~!;F`=-*YJYJr?Z? z$UF>)veI`Lraa9oCGGk-{c18XpJhaNe5n!S<+IX3cmzUbnfQhQ)U{wz;3i z#M(NJb3cuVH(!qfK;xkxC^8lB-Q0lj@Ujk>Zap3TpSSD()c%SNG8L7uO{xLo;tN?b zCLIi)<-e(O$#(ZyYsT(Q`!{nh_bX1@H*@#%Qr{S}!1F;vB_IV{-K*m;VPW^?PF}a$ zpy0ojW4jGC7G;;{INk=`*(MOFpJ!^%2%j4|*n3lve;_K7KDT%m5E-Al{5?>WQur9% zcl{e%(`-sTX->leV=wgk@PlDxoqcvNG^`N^1HtzGrRgp!6TiZ--DTa3*M6+v zOTqSgUQfX`BOGH9bqlW2q3x5Z`;U7yMwYt1Nv|fWd7|1P@gAlB$I+s$|A{_2F4(C1 zca&;CpyhA9vuzswv{rbyras*E@NkXBTex{si?wq)XlrKBN?Es@&+uLQyI)(!WxICd z>alCn^!-AK^_`B4K#Y#P0&_DWA$1CS|v&WTMASO zsLg|*d)st6>% zaxAD2q%^uer~sr?YQJri@hn>hMaIK!s5g*G*Vaqv@!65#Br+cMD^d=dLg&t~#K}`A zfA6yg{|P%Wd3!L&esOy+B)>!?=s%WCpJf?+C9aGuX!K$qb&Y*JF8C2%RNKEbj`T zT2z!R{Kt4ujdC?+a61qM3o|&Hwy0K^!PQYws&FH#p`uQ))AGT8DFINVFoUxLQoMv` zyPnbi(@%$VN}bH$?K%vhG;p`&pKl0%FoYr0^E-d{UqmYCh=ZypoO=3;NN@J#4XQ4? z(N!PBLDif07m;qiXTYHP{m)HEuL1ywg9bLAoBFIc$w1QJWX7ZvHtQU$Vug%|kAhZs{((3ew zP@*Ln!p)%sOfrPa>V%@nYxWkFLQB}BZJd|SQA`jy$q@dz%Fe%$;7Nw?R6( z7v&uKprx*Tu37!i3yp^G>0Q(hJ27G-puJANg|-#i<8)oLIcT@j&!_6zTA*D{Ki*l_)(q`*`UKi0Xou6^K^vg$ zPOpO2L))BAr`4Axy<*x{3V@%PvB0RLrxpAzNt=a_ba<$*_DTD zmrg4WG109dkyakcJj1NMlMQ6;;f2OX&i&BTT`y$kfQcP~ok5wk{q7;+c&1k(S#pHGaS}#gDZ}$weUX)^T z8~3Enpj*xeDe-UA!*I{9A3A{poYN2aGY5)K30cm&3N0c zc&~Nq_t2|p&3KI3;?{4W|HnyX&IZc5Ad(VG_9JyR!w!LA){HOJ)NAk;GV}U%;v9l` z$ga(wQk-X7z z0KXwh3a6u@L@*+b22mfFzyBCSabW&F7E~om&-{IJ5M_bnuuec4U12UdichCLjL`^L zNyz4-t#%3T|H3YDzV2uA9$_Z`4}K|U^j=~6!9Lcvbb3~@t%t!|Is@zfLPX~noo_Ze zuU{-hr*6VJQs^e?4y?ejMW?!d#P%sV6^-vr^8TXV|DwYbjZf*&226={*Yt;dMA6r` zg;(R&`L+7LeuYyVeTk0aU{GgYyq$gYfKW_NfM;TGTtnEjskgfvKJjD%up&RP4eYsz zbGqenhKxVOQK3#L+j++<8apq|%4eS*gCNbyUmmS4v*~=Bo2k1{*>t|u(Jvp;8_hZ8 z99<}t_d%MBPlOT^X?NyGC}EK%>^MEHqk=#s}FXn9~z)J_m$6_CRz`Te)V2x9W+kHuZ7k^qhGyx8}(!j zG?t;$&{m65ihcsB0;wGB4XOmy+Thp$Q~|0nvry4P75lW-@-#EIUkowOMb#wERNKG#Q_u!{k@% zbprFxkaH(Ad^rgpY7(BeCvyi=Zp+sBh2!saZmJxQo@`?!TRFb_=_i4NHST$K>zW`M zXtypDNp|bvt>UvK8sAgGVb*RPt`D&ZI(F+wUQc#wEUzcKwUb`=>cV!(x{}0A6^-c? zK-3lNRspC+$&|7`cT0_YDhhV%xswzhloQJTv#6*gSb$rCD%!19-eJBcTtm(R<9wlH zw|=R^0pr^in*NzqYoj4HOStcU_io7(S4E@V6Rs)kmfZDBo>A|zt6lqrXw>s}OQwWo zGDdx+6+(AUVTa_{pIbj$7j;@26SlBBVUBdb4v8DdW7hk0?!4`hL1VdB#cp^Pw5UEW zJC=|9D2?SVua+;IXeXuhqfSSE0GSKwaP(lgMzFb{c1O2@%mrEW*%e(O6kSlO)3cy; zRP>zF6QGRNAuiHXmm_FLJOc}uH6{g zuX>ao$lic+=!2HHc5$@5(CC;JLE8f@a_zGxs2{qag--8>c0miAUI*=j_Pc+$W^?sf z2ei-WM6~VDUZ`HT#2?88XePAXbm(vrW2vn(CC;Bf>uEryxslzv`SGN z)0PM;K&mKPpehH+F|CNI3{+$BxB{wDkQ~$76Vx3gpej>64=M)9F?E89K&mdYHdQYa zg5;Q{qbdNESzA*<*>4q}98ktF9i_wMnCjFlj%hc&lpNFe@Ddvxt=9AoQVysnX-@g2 zV+!|RD91E+hTS2)g_7rjN`jm6 z>D?eD!R1hOfs_P4t<&drf|LYb2X%my1fK@AgOmjC2epBe1lvHZASJ;YHd1%xKuUsV zqG|z^+5n#%RGDp#+Mvix8#lY%PLU)yPA{cxj%{?9ri~k^Y4eQj;VGR(!grn(UH`g? zFmHq7Sst;o$jwhk1J?nEUqQ{!A|G5l-(>XCL-R{UJ3KyAGP)r&lSxKfE)j0MuZUmp zQ@e%p7GrM$+Fj=0UlX=~(LYMbHm4gG)K zV(hXyj#I@}8+)G|Wv4dum>Ft8_5>|u&#cJ55rgI;#Ql(!K^gvdokVsn^5UE{7l~oN zt3)k_39n)#6zT=H#vW9dkI;K{0~F(nb8I(20sj6^bc5^$D7s(a zI8*>u%U`o+z2c8ybC2$mB+juF+Bbkm{LG$z4I=9^d!7s;LWwN*Dj%%Ong1JnBq&fYx5&hd?^#J%dy>F#Z&3GVuICuS|Ys6 zSSht@?mxl~Q#`${!xT@q>Su$9r$@s}A&zaBx+s*GOB*6{YVEZA_gm7}Ri1{r$Ex-gI-u^cs+|4?TBcY|Kd^h%dP*Rr z&q6aQ6+4~NrfYMLRpj*J!$jR< z6*~P36pxiQL>`4=v(kphAJ)~i;k43*$aJ)rt>kQf1;uZr4UyxaSgy1oQUk?xr45lE zKrvovLu6AZ-Yad0lyPR*ue2djh!zKyHblOHwpqTcF*@5n9je}Gg67!5LZ{|jg>G?usq`)d%B8*4-5UDhH|XeR_zlqzt5F`pGvLs-OyM>uFRaAf?o&P!)reR@+b&fs|S=4Jb3cKU;@s zdcV*0_Ti+~!}++Bd5LxIgr+a2`Jv+nPxJF8^@}j6Zwqlge2rh= zvn*{kGJbcE-I%O%8##NBbGuNYP3aTGzh?P){d<25sPK0Si*M2&`syNCuqfk)AD|I>!TRcILnX+vQ;T6Yn(-onq( zx{IiBdOX@P>Uwk>JEJXyR=M^EXx&9rI$ayByNC*>UxOCWLUbG-?5}GpgqFFs2kI`O z)af6f{mSy`M_wMVN6scU_CcfLxD0JCw8&ey7;O)<(CM*gyP*Y6e+=z{_Iv%^0on=e zbGjYvc0hZbu8OuD+T(O3v~AFCr*H44erSbuIelXdU0V*?>GVFdEzl09ccX2FwmZE5 zZ4@;fzrULG!Z1_0FCE9i z{Jd3gAA9garM-4rw=W8Ld;VJr`LkVe(~z^>HfwI1eQfk*-N)6>CHD~%)+!RIxRiKS zDPGlXuC@VUs(SB7)|9>j5%bhvSCPt!OH5LaNEM4qOj74vp&;_&5|h+4v|e2LJm984 zYe=;*Nlk!yap`gGF*<>`4G@#mShQYTx?H;n)Qd|@QfolHxOBL738)vBn55p_TUX)5 zrOma^L%q1fB=t%}D|scX@CacOq#B(z>!Vv-s=UFXoRfNpGX?Otg6 z2=jWo^WO*cf|R5-2K9iHq{{f{Zjh4H(x|#XN>csR`p{00lGH1p4v>=66QFjGlGHt* zHjt9kZ$YgfC8=vyR$t{nN>aZJs?37_XgWq`Um{_4UcYF#121CnKUQd#NpG#%6r)j&Zdcmr(>F6z4!e+O`%za?(8cZ zrv=24Y(+QpC>;-RL+87A zxXz*>qfT0gb$CK-$d1bQ{Vz?NukU~Oruq5)joXLv{TGL3GQNN0+vfZ68575QzwoVt zU#w_dY`s=%L;IlcDlwt3ExRoCxI%V}-mCkic-@R+yI+;|?vWf@KkI&u;Mn?EVY+ho zuzBnGx~G5L!%ioz=a*V5FM`P6OaUJTk-k~Hza2#G4k3FD$5qPkV-&U*1Vp^+E?;Di zea+un*dqSl^>u@=d~csLZgRh!@dVo;o6qun-mc6-#LVp7tvj+Y^TQ`o%&1TAl|uJG zeR^X!&TLxU5`GIj6C>y8)f6MY(BZroQCq~wm|xo`>-k4@-rjmmi|*>Zu{s_QBVmU# z8ywAHWxdI|V^8}=RQM5r;WNkrSJvCCttWQN?~tvYh#ivVqt{6!uhHsWbV60#$%iF%|=rgDUNfeLL$i z%0S9-?<~VO1u4z_0aXb|rQ<%W64X?_-7_A;o^xf`!1 zOS1>BCrk4kz3%0LRqZuF)CyL$zXqaEU}=_CLtZ7YG_UTYNJy5ZcPWKImC`Df=Kdhb zSeje(jsfG;W+MMXJJT?PoylJ-=vMMxXm7jt3G?-~eOJ%V+m63(C~tfB@dLc=So_lM zyocha|G@fCR-oN$%T$o9X}38#dr948vjVM-P6C+~u%T;NpjIeafflE`LAkxjHhd4t z9Zsv)>q7CZX}|pQv6=gvY{SQenY*1;* zw&CY!OQDsnJsz!FfeNQPqjf7#?z9|QL<`Y2tPL%Mmb&(9P`3glPCuwrKlCesr^i75 zYEN*bHSK5{{(!a@ZK1dD0NNgCfz!*-c0>EUh&DmHpnXn{g?2)Fo&J<|JD@#IcRW3C+yVEzms(xsOwmH2IZ42IM8(45l? zp!Lvb8_uQOI%u>FN1&~Rl9$8NUeFq7gSWd4v|5xDygsN3q%{03KBp2?YXP-5stS;7 z!&gw1gOrkA+(F$@2CA|*{&{irMJY&$`F2z#AlZhiK*b>0hVwv0pfYRgT-quGl^QxK zs4}b9`{^**hF#PKwqbj{l=jPa2yIbnTCJUtQigQ=@A4$*+!@WGo951F(!Vym!j~ZR zZ=L?F)xS18=FYI;Fn30k{;kx%cAppi4>RQLm|wcAY=mX(d>fHphsa1n)}c1LHD`X` z236KYymxgx=a-)Qd+LWhTQh)L*tv|c=75;_g)#iPU9 zJsj%ABPOBUpKSgFvdc>)!RM33Sl2eN$5OKFGxwK0n`Ih5;~2~?FK0c{RmYTNJ(f% zP$x)9Xj4!JNJ(fdP&-ITXjxDjNJ;3E(K`E9kdn~H1(r)JwUpS!JR205)#*R!)i6N` zOI>&CrSv%Zlrya@v%gA0IW;}N6aH&Gik`nFJ)=mOz`}1qnSdcPWG2X8Z9VQM^L3>A zT{=HUdjIsH9O<`1Gnv)a+q%t>G8b8)BHkN~y_M#E==DP5?)`1!J=U1JugS#o<|0pr zm$P$`2RKf1ky|-VbCIib>?w!2$d#YlNe@_FZ9qk`VXPe$5JRunhTeWU4C5<|wcSvY zgqVYD3nBwC=Dsa7sPJhXGW_7P1;ntJYVC*L9Z{R%3~sS)h)FYRhQHsF=7b;|@@6aT zpSO*5VK(i5dRI*QtVtge6kNLk^FSS1Y$+%Y`OI!uT0i~1UQO$#o2hl2!6^M-H!o+M z`2H``%~Mz|sn-XDrA^hc3#ct&0kzrQyDby2K?|sZ=Fjb_Qp0ya^Va!Y@X_yL7o^$G zkrJu$<-GD8@u>|Rt)R9z8iUFzU$diSxlF5kO^()-DptM*r%OV;^3^+i?|XJ~{ue0H zr01PaG-?@i=^^1+Xc>3uA>kXLUiqrM-AkZe`Kp{YLMy0}l}?X_mP0F??hW1-%s;mr)rtjN^e8k0*!v-X0*-F=r^XIZGuL>vFjwA zLjyGWjs4NqL!;jq3#}8yZ)^^#1=ZOd+l)`I0V(Gfp{fQc?|-(1KDP>_-2Vos5>#bv zJp-x$g;Y1IcP6MDRAJ~wP#H*mqfNg>-dGA!TAPBZ1f97P#^FJc@f$zV8%S+C z>!sv3Ry*C4X|1$O%0Y>3__RNFh6Q(+H0WOo-nla@Si@g))4vvs;jg*rUkkSIfUW+u zV46F_f+zenH~nkD5xz$oE-d^tH~rhIe|z+AxBl(Yzn%KGL;tqx-!}c*s(*9(w?+Rp z>)$5*+n|5z^>3a2t<}FZ`nOvDR_WhL{ac}b%k^)W{w>wNCE?$^mC_2PIF@kp3*Deh zzW`^`W<%ks@7l1+7Q5wci<#bcd!;a|sG&I_9C9Z$EbGJ1jWYx^BoEiGkI%CsJL=8a zA=F?T%j?OGtjFugj*Qal1MJ9GBpF~w-rZcWP#f-FIIR-9jz0&Ku_G^qp9a_LJlK)@ zQQP1N>YSLx!*-gYHnLlJ@Ym_$xZG>>WC4M!ZAmf!h~1 zvmQ|`Zu3I$FvylLTOB?0HX33;cdy8T_W7S7=uYW>reLt6>0ak@0x3TUj`vp3afu<#EpRJry=`;!Zk z8!a6KTIuvQw58Arr#GW5fyTN$1+Arz&_bDOCqONo1X}8Je`q1J#OYXQ0W{X_O`!cD zxI+s?uHA@p=z|tIT>@<{w7}_NXnUY>o#6RR)DPXzKA-dc9@+)%b$SD|6WZhS+P|vL zI-uQ7C!uYJb~!x_Z5y=H>0W4Cp&d?lN1KDTJ6#`b3$)GYdT5)Wtxo5DN7vQ_%{hG? z+5nAp`$=d$G}i6M-qp3$K}n6Xdap)X3vKXr&wx5uxn|EoU5Hg`r#=%D|d#mc;8 z%C2QX?wvTZEkyGIYd8sJ_zLmzMm8+66=J6wQiX_F=PrpNr&oxWX~v-S3en>cwh`1TM9eg+K@G1H9D3B>1J zVy1a(Lw%Z8hz@V}8K_r?m}%~XdWDFY=31y%h?r^4hkAv`dAp}Uy+XuHbJAPNDPAFB zrr8~>SBRKtc0ubEqQTo;4=ojfOw)I~F07yMRi;@4RUb&1=Isrn>IEs&JP+ytDbqYR zM<>_~Ql^=Kstcq{Gab|kQl^;->HsOzoD6CQDbpMdY6B_L>={sIhOl=yflQ_;*Q=~Z zZljmd3}FqmWj3?bGS(Xt?E3y?Gfn<_&c@};y8Kq<8(a0qt}24eOAHt z*N3L1>1~373RG;jcOxB!HL~E(*Wt}%2>f{wi1fgK`0QKr9T35z4>fCKnJg?6TFYUf zP_2c}UgI`fdL6t_nCH$HVx{nKom2KsJaJ9B6N-=>gM!Oebd>8bEe&qug+80PC%`6#y#7&&jE?YT#jX5=Z z{=h-^T5G)2G@002BGs4{x2o0pC3LL_Hapq`mDQLgN1q;}A!s$G!O=2O#TrxZ^utmU z`eZQ8Azp$qg3=t~h1Zn)7({99Zw6YgG1cDg<)mP(V>{w6{xHfineNGSCtt^FPLYNq6*wZCoAQgzbW-zX@BC$0Uh z0HyY%wZG5S)%j9>(%Ro^P%2Pb`+FSPs=Acc{vLTnXO@G;%6=u<7HF*O)6h0UV`V=P zZ4)$B_HB>WnKeLTWgmyOUX;qdC8!Rh%Dx_`7F26Daa}&T2BZYO2&!t3lK9&r^`TWD zRrcpWm7q#%s}ocKsxUMIR1PXPG#yk1Qr?>O7xh&sNV)6epvqMC(}E&X+4oZ$N?=bmg8yEAu!-*WHZ*%OWck3Gf8f|;?dh!n6)$0Si!{(9bKk_)#$Q#N#+;2W^ z!QNqk-&4rnRbFG~`R*zgo)#`|)cuu{yT?xc$~Qv?v{}3!^$WXbyG8lUJUwo}uJQqQ z1mV0V81GoidPe2B)hou;AX_BNIl8LHTG!VrTO6GSvhr-h(9WSjD3<3Yr$<2XfvJ@5 z0p%v8<-l#A+^1B^SJDZ^MZ#KdcX_m4o@<=GQKCCtNnwkn{M8rj{No==sB-PyXuUjF zI=us}m*)zn=b|m8-B`-cM(gFd%(aK2_3~WmvW3a^pVM2>c0+re=Ad2B9;atQJE7f9e@VL? z&@QL@p>2nDI{gvaHfV>_@1SjkwmaPrZ4TPz^s8uFpsh|9McWL`IeqRM>W3z1Eafwy z4bW!SUJtE@#!~(p{Tz5>9kjutiuuAlx%ceoU!QvM985|B#yOi(dMrToT#GRuLtgmyBe z{5-vZQhtV%X*sZ7hpChwE@jB8Up~7SVtR(%!Qr1>%v%WDn9`mLahzY;2d)ZCoI_?A zevWqQ!8Sy)#eKxASlrV-!;IBTq#{u0`Qw)7l<}mCey&J~cF; z1uev6ay!(EKujiAK)nd$yxp^)UIbz?IRWZLASRRJo>d@v5s1lTC$wG!8ob>d(NY9R zCTk<40<`37~e6lF7jVW#$Frb(qXrb@*`k$FR_|rCzetkDOVEt#w{zV_NNS zbu~S}qz&cH{_o5SKB6bh30*vVIKNh7H#{58JEX^tSz~*B zWp~2tfj_51%g)8tp)Wjb_nka`k6uc7yiJF8lhpOo!eQQ&OwXCwdeXSbAB~&br~6g> znXQ`*T29KFg-o2&s=PA%#Vs}H;tszr<*MjAm(+PFS4H1hsEg8iQj@2z*(=%E%dj>$ z`tANgmaFO=-6d7bRdr6UhSrfMYMq_~^;}is^ep|jdHjxUwbMh;dakN+x(l?5b}OB3 z0rgx};dC9S=c;n2%RoI>l{x)zgk4zN)h>1V-X9g=o~ufnK7`hDRk71qXgyaIIlUaM z=c+=dlcD6QR2z;Li^=Txqv~u(;lpK~;j_!w&#?s2sbx<-{S~Jw)+hgi-pMR^%} z_&ulmHHKrip6^n{zCR5kZO~H1eaG4Ovl^e@%=)33%meVZUK51AU$y+#?LOO^G+-Cg z;k-4c#qCc|WcI7xe@w?|zv{^%d%J#0U4!%~y*^;gsVzttks6>k2SsK+bgo`CpHghY zcajdnC=3?n1hpL(t7K!2r+JD6^>kOM2F;6hAM9sXXBxdn*rl=>6n3f9PWaTF>?_fe z7UJ*Nwkuf=Uu`>=w~3SwoR@& zKqyw*2B$kgz1r40-3&?xriGw2p)~_5^M}jYg~a8d8gJn}{StYc8B{xc2yG=T#L7Gi ztykMh*Itg+t8InTOVF0lLb=o9(3V1DWj-3MSKCt8?ugc_ZHd#3pw{v?M|WHI#DX~p$Kb1s?58CYCx*Y6`*R6D)R=Q zDv%Q0w`sl-q{_SmstS-Q^H))ogH)McT3WqO22#@N`GdNk6r{?0C#n*V5?^aTnaX^T z4pZX$wc4OEpQ@KqWjw@+;(7s9dg2@s#qgQ_ z=_Tz>WHbG?lT)UT+2clul<5mRp|shbc;H#Em^Y@NvNfQXG|oh2nLcKWL!^qCzQ-eF z{oOPoJ=4dGu?1Ss^f6S;$2Xt!PAZ3gjP<4TnF@6o|1Sw-o z26cdxF^&%?lQ9m{;k?xz9b%RC3!jS3&zXzbT5XxBYqi4)ozuURm(O48d5G0pi=h0_ z&0oE3Rg?`MxvPKGZf`bn8yi#Pnv1t?`*3j+DRP?}eV||R){01jqsLKM1j}p+-j#M>7(O{NR`vw(R$=oI^7ytMLbtHT@UJ!TkiDh zP>ycaJ+8Jm)atocFg_g)o4(kLc z!JF1T4uBHBDOs*JPUlMqr+m2?TB10ueXI#3kki`7l2Bqft$i%c`4Y})?c;^T^l3zN zTKkvABbp>5EZFOP<{LSw!>@;>!?4jS|2_Gnw6F<)+r zwiz1p<;rNAM9G&uJL$q2Ky?-c?=C7-52`ivXHXqT`SKx9ElBzD5BKT>Ye34ESE8y0 zDPNuossbrro(8G}DPR5sQ~^@H+#6I5Qoh_FpiI6T8%`jz_ED-g;IKB-OUYp^qcWW~d>V17a#wBiv4 z&G6~?tOD!sY&!nnw3v=rmpD?2dFvAUaGain+4mkBZ1bLl8OL!*!F-E+{h()PXz*+p zUd}u!x{O{mFJ5BfyGXCva45FJcjnr!UNCTG>;G|mBWEvnfowFyg8SIrb~XbBQ2yds zT#VQ~tVYy_w}#aSwGbNI{-3!T@g1FAwrejrHFj-!3}qRKROwngC4c;R`dyV~M<3l4 z`#3EFS-{1*MZxRlFMNl`dArbD%Zq(DW?n;X0wX8d2@-9)h+C zZLEr0qxDJ`tKt@Dz0$?1_;s{i>B_y`Wzd$+EAOSMxG(3>2kmo5ycybFXs^?a(e^-l zoGyvB8yaU3?|rH(?t*r?_62AswA1Occd8#cpdC(cMB5IHvxw`^TFMGzr_HsEXf1^W z+Uj&7T1#nx=A7=0wgnoi;&`;p&{!2WK-&b3RdHo#1GK^0T?AS$>N^57S_e{9eEt*l zOD#xMu@h7Ss8|KO~>v?SA^9!rO~NOfIiNy(q-w(gpRR z5R=OtP%jD%-tMipS_d{#6i6=TAfzI&MA3|ja=;SBk*KHzeA8&t3iVz;p|0dI22~$O z$>lqsUXYT@nxGz#lFK*v#BPw1%SRum3%Wo`F0X<*K}s%929!xIGj*7jC}!x8C5mhG zf6F^cF29`-M`f#Jw<+OOC6|ANr`z%uCmv;S!a`yJUO4>qIF<3??eMAZTW4fF+iO2d zo~_A!z}^xmJfrohz9ofcy{k4sW#L)p=+muj+}M^~`u5H;QpNDBap8x5(+KeJtakbm z)Wb76t`~0B!1nNrj%x;556=p3;c{pdL0j&0GStH}Ik#j}r+y$pljC|8N|2^?i2I?$Y08L``As20H6_Ih z(Gsm`9bzJsfKBTVM?#6&v<`9DP3m>RHmyT!iky-$1aER&D?mFG(#dgs_E%kT zJ2dCX>osT_G$zHzp{>xE6d$=!XO@G;qQo3sZ z)f(CpRXwQ2(DtA@kdk50HUOLyqX?%8X11>GlbE9&RRsC$9kF_ z9ZP@<$h?#0gdsCz+Rb-HAFnoFgZ0V}!>t=+uzs+c-_St@>*ml*#$avJ6ome#)h~X> z2A38zH2%)y*cLQ2_ou_4wR@v2r`r}6x3^Afzx}SUIY6*%U=WS zSDsAu^2%$~lYP)$*Pep57uw_WM6^B7Zl}AV?S^(a-3rPB*CTN4VyFau+ zlzRC?P(4WXawl4>1BK)lzU_*t7NmN)0;mS0dRYLf2B}`Y^@jSQ3Z#5B$DSceixx^* zvrtu_Qr3C^RXIrYavG{KP^q0)E~ql~^0c7HtlQV=4P>u_^-`*rhv|)J-F^otzpR%- zJQB`89PS)UQ)%39V35@@GDATV0y-mk-t9LTC!S)H#!3989PS)+}AYPJ!8kn z|KutSc+c1|@}ETO89V3g-UaoH9V7p0sAudL`R71AW5>up3F;ZU!P`9qO2#Jg59YK; z*DN1wi;7&$^1(K!NYpGJtb&Rx%_a-KZPeILXe#pGdsThW2U6tsfO!Y5(UVKY!t1 z)X)nD`A;>psJIRvfjhjCAAvUO_z0xO)Jg4QFj-05LZkH9jgyFxtzOPy{7 z^$09+Iuhy;SnPB;s7GLt)1^5xk3bUOtlrtP6%RyUS|NCGx~_sCOe+Mpp(PHJSgh-4YwK=jzooc|S&NF&It=FZrTC&ZOh{9GlFy+VL124;T*fo;%1++nd5K**Dlb zUjJv#*&q0Gen)MzU+k##1%_!7ss1#1sy!QIbM{!J&bl;SX_}z_9ApmA?yH^sVM2}d zxVl=WyF$JG#9Fl#)ay^IRU@HZf2zEN&t6dUd;O_&`q8hI0KERhTJ<W6-1u2ieuy+r-c2kmj~gJ^r9-A;dx*6UA~(@W8Iqm3T@3}_d$!?nji zJE84PkD^_#KW$FOplwGRJ^E<0ZP1)+S3%nfjkRh7TCYE`R=xGS`k@7FtW~dHtbS;Q zHh8=DqHPkTR$UMBDx_L<38)@btqtajX|4`bV`u`ZT99hhfuI_YYSk{FYEY%U@q3^u zP=%qbXucApw6qec3XoFM2vp@DrKi5<2GpweF0x#fYSk0r)wr7dfRt%=ewz+ct-2$; z@yq82LdRymvyfM}Y8QGvdx3NE{3Y%67N75u_VSyDyE14=`-H9RUWKAFXi2;0|FQSo zfmK!6*Fg}$23TW{J$6u06ctdTp$#CS42Z-YdlVUC4?@Po5XFMv*dAhu1&KO=D1r|W ziDHR5Vk~IvK~O;~QPg~UueJB#zMBM?->Bove19l8>#le1x##S)_CDvmytGO=(mwkF zA+G$Lg=cFt8er~qriVEbv@2}yYYn=SEZyF_PuxM4n!B4sK3Hzdz&|sPuztUJ6T&xhcawOJsF}N)L={mpcQ=X0h?=<< zSiiRurMc52iV4x#xsflrMW?Qiw$6?GDP+;pxsgAaEE+mD@`sW|H_w7ew9bfZC0Mm= zPS#Rt9VXF=P#qzd#IgmLf?7f_iKXK)t{OrxiTT2c6tqvF88-4$(Bwvb5`GRF`5UDf z*~pJZQ!1Ed-g{^mS@7?D%PYQxzmi+{T3OiDRGRYFbdiFa-NVNfJF-QSip|+qX1|eQ z=N_nQ(v)KNmTn?%LOpS=5LdqKvC$hrv0hbmxLLb`Vsou%Sn?0BRIy%9Rp9%G@G$}} zrk(@K73;-RIZ;z=w)OZoqNZ3crf#`OZ|%S2;KkH=Nv9Ka0Oi>-TV?rdThg z_9SYG^qNZ3crqYO-V%u21Ki!CtQL$m;|Bu%p4vIEx{Hw{OZo|gEj9f}L6jL`6 zrFz50|8k-fa4^Zkw~lBy_+)=_DdVv5KbR<$95((t5v7>J#y^AOrJlpazy38mTQyW3 zHvS(Hts2z|J30Fh|;4Uqrxj*ZJuUR)0F0y4)EW zx3_>CcKWxOYT3y%S^ZeO zk7p;(WYsUh9xOX~CVP=w%TAuj?jhH*lV`F7xt5(gljW0Z*~v56MdVs`@=Vr;T+2?L z$+F3{?Btm&gIvo_X*P%J61D79Z~ptui+DE6PD>4akEms*Izy|7*2C>WCVRF7bGDRd zjd5=$w~lDFp%clq>{MlF9=SE-CJh}zw3=w8p+^#}B3f=}clK-9sm#!Hax2MA7`h3$ z~%KrnCeS)>;&Qca1J9wgxWcSIN??f$O-M zEHz&j@k3y_`6jKq3-E12{$9O{_$qSEd|kw663t<`?;;*Z)XX;uZ4{@MgXR*6$}oX}%QkYlP^$+_pbWh_=gZ`>emhDd@S}w%O|};yCxPWk%C^_`CYncebT_m! zQB#r^A)Rn*FJrt2X-lptDbspb{w#FRpZ#VSx{#rl+?z0xQ!^4 z6t>e7MnfhPQ`kmOGyRKI)YrPDik4m5v8!gc6xK7)K)OBh5QyE$}9NS z;yIWHDlBZL-ylknh3)jyM5(i|ot|+uo~;Jz3)|_N$gL)tFrT@CXcbZSuQP}yiMoFc zAX-V({i`d{a-s#+@6JTafYQHq;;<5g@>KQ>&)``n5<(I3%P0(f93d1TZ;@3*2t~-< z_-3NQ0z&<@ugA&CCxjv-K`4(9{Hv5uE+P2WSl%&*5d7;5vIY}^e;q4O#J{r84BP1g z@B(h9cgLkrglvUoC_=Wy-BSGPf9HMlSgCP4OAU3UxIs4h&3;+XRomm^$+$gk-QDex z?~UIejL44pYBY77u)u{^X@Uwn=D(mBcFcp&I~RDUTw=At9rHoBrUuLR#=GKr$`Wge zif)<1-*;c8e>8CPvyHaQvFBgyp1E8lQ2um$3byFxQxM+oE&&M{BHt`BpO9{JJ&#;` zC7w|;gy)e{32Ck6d1L?}&k&wUx)QYv;n`$oqLv{%o3taElbTIFn+0F64B^@2qbpzy zmLWWw%plh?glCiKb%uUB6HjazqSny&iPpo1LN4h91v;lSC7S?n7=RQO_oOkXugFvq?*G%ZPe5X}Ao} zmLOVS{l57WW@jQ$W|IXZjw6I@@+etFgmP68cM>WfgltkmD4!6r$+he&j}WrSX=LRR z67!i?cMPE%LdYiF2n{BLY_cbz{)CWC_F(tfgkUzUg%!yrZG{op($>w;$EDePd8u9s z+2kd;6gixo1!juX{O@Fwh6aZTR=HnoM~I%v z{pwGZcu*QD_p2)|#%SoK+^;Smi&o10>KkOyNA2$)kVO;asre=Nf+hc;ITU&=SxX}d zy_is4M4_h&6jA6Ia<|BS^(b8Be)VAd9QLbwpf3?Gi-E1t`~xX8zDr%iU8;s>Tq^PN z9@Y!ZDkXkyzuiYop4+dxi7aoUbNlnR&_&m2i+5A=p(qV!{_m*`pVCi=E31;HrfK{@ zbY7Lr7^z)h!|Nr(k|$}pJRE<~xs;B!lU#Gx= zCQ3<$t?kQ1YuSTa-3ue|Y&Ap^W=VIGTTRrhZY?NIc=Vx%7~g<_;Tnqh0(2~4rN z)KAp>QI6*tDl|YEDl{M(Dl`BZDs;gcDs+MW^)I!Hl^~Ow-`uA9>Z<=Daoi1GSlFbg zR%|HC+Q?M5RI6>$R7XoU5mVi;mk>*`5Fuwhs^Jj!#Y52y`{EPxG!ce+mJdk_hjCeX~v?nftLpPg`%Jr_dm+PRSmD}1KL*>SV zHm~ktkdQ>QWYpK4N=PfWT!T(IU!N6k{(7qEPe_x9r9^d_VMNt41oeb-G*R^sK@-M3 zg8ize2h&c1@llww7~jZd=8#10h9^nIT9xl%F`K`OV&6- zNH__yiU=X$loBc+goJY`p?pI9wXaLqR~{iGoMXw#C4_|2gHR43B%Hko4JHIT*@{qq zLP$7UO81e3^TWexI3eNubhbV&6V7|M6cWw{aw)R=P0H2S=e++{l1)Q}&M|kuvBdLb z8!5WAu~j?hkcV`ZqYgS}_u!ze%FZCcL0yvjpQY=FGQ7$nxgA+rh9?c$ zkSujjSK^`vp@MvQK0#fHQ`(lenhbI>B| z;WTp1K?@A+N0bgqB_2YE_Q_rDZiMKa+~saYh{nlXZc9RRP405n;!tRr+~qEO08dT7 z@N5kFRYI!@dmP%MwED^KoKRLkEY5kU2Wh(xs$&udn_)6 zU2Yco3cK6`&`jCo{yUWz-{bzwPwHu8#wC$ji;Y^sl3>+}$S%{ljVj{NU4tULG}sX& zD8fsF9rPn-RD{92un%wxFNf zhw!C3!WQ&{)9@4&NZ5itK`u2CDuT&GDU+}TEhS2&1QQzg74Al{1RpwyT2t3{^zkhZYh|5-qTP=Mk+0N+0?=p>jf~ z2qqCKBgBf}R7_xk5GsPp$eKuq6#-e}2%#bvL{<#xjS%Zy*+^+I77dWArr8Stk zie=ht3uel);T_Y|zf`(He*tDq{!(cXHYTg~@G*DCAMT6o{o%s9pu<6ehv(X6rw<|B z7rN8;K1rVw9_~)xg^+r!_y2skX-ZddUL7$$TbgNYUq08 znupgJ`fUPFVIE#<==(&?!)pwEo~U`aCUuRW$BEX%Rf6A79gdk?N;GNQYsjr5T50HL za?Qib4IN5u4Y^)-W)ZC>nlSD@M5~Cp-|xYG&BNXATasHzuKRt%i5PD=(E{uD&ATu= zWkBio3rI94hu=R+)L zzi+6}ndR;;=KV|BVBe>%v>NXpwS=-;wL_kKhps}@{^xHU9MV;HC`fR~Dht*_PS7>M zzAtIe=49!<&&9SGS?Z9kv}Ly=%JaEvE3?;5{{*NxWWvz7BCPZ)K4sU-#G)C_5wkJeaVcd;K{?yyx|u$lwY_R;-sryl3=9L@nYyqrXnnBHlCl zD}xai7V)0Z?QLqF``I&)-< z{;-4FfLsb7?BLpxOAUk_+y@geJCs4l=<|tE31J6UL6l+$CUe;b=z)3&K2uEYQm7>C z;6@OwBbqQj7)G>~sQb*HkH@Un5OtsFL~b=v_nEDTRuL_*e%B_N1WKRzdIAPpNeCJJ zeM04gkkMZxR7MCHeg1J6O@a_I`h8?gB!rB9FInRVA)^5uZ6w?iR`Do8bk_=<9+RGWv>JQZo7yX~r`8zw;!ip+W%58V^VjL14%QIlOfvO2qXP*rwu-(;WStja#ceamG}Rg+!XKSTZ% z{JHGnH|uVh?e7^@g+? z5!1DgU8U&-++N3e0avb=Jn(c>sCFzQxP>7S}1~jmbaD zeV=Ww7GFEG#|b@#^*C|ZoY;PLwI_G+H&RC>eNvKg$0|P9yt;Fi#U=%#e)T(_lz2A> zOE-~8nY*V>N_fj~TRa|;h1O;IH0u%44Wy@(bqA_|v4QlI^8GP@v^?^Z@-d)7OBSA0 zUM6bE!V^m+QA-w{Sneij$-)!Mr8hzHmMlE6{DoXg7M@uCM6M+ZPb~ae@+Du z*OEn=J^r@r*OEoO+2MCLVholnmKyr?0G)(FOBQv8zCf-ei&{hfPSlb`jiGlEwPaCk zXc19M7FC8`NVFcN781*O9K%wgmBu}aT=fQ7p>jhHCs(~f&@w}}B)5iW!q8SktBHDI z`SJ$LLlsd^ET8wsJS2&FVtIz#N}>hU?<{i5fikh&N@5wIJPpE$WF-jYDl~$uiG+|? zE+lIlp~1@POI8t~{t6vTsDMzmLc0>mCxpbZ3;W6=)J0h>$jT+uQK2u#;rVk2Wh(TJ zK#|1qBAVgN!dLp~)G)C;ic2A}{9P_Zwu(2QYbjv=|EE)ARwu91>}D}uIa5okuAC3J zUe_&JIp4KmsGMD39YBH^CM{aq{|PpyX6Vvde4Ta$Gjv^j-WM!2Ll@Otu-pt2)?LY) z2p=;;7uBugni;yNMiVtNbWxp4)XcEJ`aKf^u;22esE#C&PRLzhCqlGA?h3ahL=WVy za6LjaK<*0bOEGM^A9sbH5Tf;QSNL%sxBz{RyTYf*qUmv0IEySg9(RSel101Y!R^Tl zQbcvJFe0CB%|(;D!V~awc;9b0x(~a;!_alguJHG+*5Z4@$5}!pW$Av6J>dysgg zy%5=+tq%kVk?q;~fZidpJymxgOZSAHr{Deuf?Xrqll0;e1VcVgK|D#nLDVAKll0R> zEwVjH&(IHZh0hOplD>&ti)>HQR}k&byLpm6gD8VL?EVH2WqgO-Uss|G@v!^bnJA+? z?Ebdr$QbBh_xHoKcw)wS*!_LmGZOA$_xBRHjQEhGrxRt+2Pc_ClyM)D^ckHaA>7R@Ah2j0XFQpmV{r&!@Obrzp2EX0T zFSh4>j6F3#JFJ(K(Ff;*Hk{j+J9&cp*q|tic9dNJw+B``QIZ!NkiN{)*JQ)0)%*aH(5bpNw5qR)%gy3$|$ui%9yWK;`d<*V&1EGAr5bidPedQ5?yPZu|E+M$v zV1Xj;))UR(ZU^H9bhqx(U*z4Y?Z6D~wgc{#QZ4=WxtsijIGH;6YxVN~nA4p@r&D)X ztpU+f~Rh+>vM zug&nTQyX06{^F+sy%hErUr3Xuk7b%#mUh!w_%|pfzN>hZy9y1Lc<9FW%gm>%j@;IG z%xI22zu`xD(yXLJo2S|juF|Gverkrj zil{}dXV^1|TI70$Jq@?^-%9Wddnmb#-0<$vu0;FuZuJ)B9f&f1!~S8#m56YX2`IQfSKYKzxR1WLxl#x zZ?}ht<<#BV;2=*8B5q8Lb`QBIfSYxu_*)yp?{D%Ql3q1Uy+bl}VRP@0q)RuEcSt60 zED^o(y^o(R)wPAmXLvgzy4#t2A&E(t=k0sYk&JA%-a?Rw@tlvy>&E(t=)5tZGTWaF|sS6}; zCRbHN_a?RuthGvj!Cg+A&pO0s&VZUyO9}=a>g)PU6MCo&d1=erXftWM1 zx_lkhWD+ZBJTSz&$ug_URn`?`nbpA%FDJ{a4u*Ioyan)gCTB9 z$gB>AxE`T=_60*+mwn|Cf+2o#af%@>KrZ|kD8h*?9kbLzsFhZbz1espsLE8HjHU zQ%}N+E<_aMrzYXoiCUO?5}rxa!qk)S6ZjHv->Y~MzJXjuYIs-UGNS!?x1|>7rx9hm zhFwWNq72!vD>;ZLqc-eHb|lKc4ZD)`La7%ODO( zxPoXKK84%DT}0D}Cj8l+#NFzVZh|?CAa^NIH-}+FEseW598J{Hc!BkM1jk#$G=?O+ zEs52Hkc8JG#01V=Nqrs$WZ4@@_!B~vd?AwXYlO-PAqhWC$g($*@T`3>X_mc_gl{El zB43CkJdvz%gph8r2ELb8tGuB>`MMS z&i!JkwhvRSs{LQxi@~$_QzKbbq>EKdi=26}Ug$ zOh}!_{b>{+Pmpd=XA?E&ahDoI)SSn+3f+k2P;u^3n`1z}fpC}Fm|Sxncd5naLJa0S z^`@=Q^mAp!{t+v8si(;`=czO9406qRY7M=KTyvfpL$4>-oTu8*GssQnQ&br`fT%f7 z($KC%&3U|R*_o(0Pq}g15jE#=ms*cwFy~1a_oH(#59T~x!o0r+=E0oDU1~bHbe^zP zm_(H3Q&?dAmJl`nflFP>PR)PdQm2t+{(}x^LhtG&d;HIC22=vr<4M>PUPkn#gB}Aa-y_3k&YTc9G?&SzdjX=+M zUBU7Q^o+MNQHwy&cirn>*3a3t=C($esnsbf^it$EqIA&e*{LT%cm1%G={o- z5>Wkw^2 zRF__(a@lEk;xwWz`st4Vt%u_W-OnZ0a;EEkDpAXs1=jDaM42dKJUgHgr!Pkyf071!%k#h z(ES%XVyKoXk@2d87190pDK74G?e;+!_Og41_Ryw!26R_{DOF01>wL*w1&;H*&Sz`ib<<5iU0%wHHPDG&HVL4rAX zv>&n!oJh^dLw$3y)SNudHzP~UsmNrqY#4$(pVm@f==A%5(wvyRt4PcRkyU#IA=(nN z_uYgBlZ7Ckv^B&7cCEKx>sDD?kAl))Sd{R_8%To})x(CQ?a_xt382tlx5?%&4@AI|wnI(kgCG z$5Szv(kd<{%MvN9;#5MGNRbZ*5VAxHt2m61B~s+WJqTGMMLtX?WQi2{aB~jA5-F_W z>%n+ZOQgt$%QjE3ifUm*^5Gqm^aU*RD{v{~!~4(-`EUZdZj=xIa}VKTneQDQW2tgi zm-$vx;g_pv=N_*U8_j&LE(n=V)2ot>00}1IHF!rtn)%#n_Sp=+q9)>2vo#?#5x1JQ zfZRmfZI*9}Ks6I_!&ykwOvDXm9?=|%C(Xuq*Kr6bGm(0e$!+ACiMZj6AlFQ!&ba53 zYbH`_=+WewiPRW+1i5A+)rM|Gu9--cp_`LyCXzJtt3epAnMkFfZxJ;UDK~TuQ8SS; zL#Gfm6G<34fvA~?8_rFeV1CU++;Gk&mnITwlQYPrj}#VIzum|+E6LZe*prZ1NuEMm z5Hc&tRVba^nU%nBmLH2}H!FeRe61f9D=suEf#JMFmRSi5=S8y2N?*qVbWhRQHco^SEM62N+exKT2Gia!;uM>t> z*Ei!*sIEug#oi z_w*RSsFK|<{9Wva?^<>Y`mM2+n%UrpoTx;+1e0w=`JFg zM%2|ibpp7S!wRh5ndB~|ha&?$NT`kwGSCD<%wE*+EgRsGEOj9RT|ibfUx*BJBB3fm z$UwabS?WRt>O#m;7c$V!gv$9sWT1@*l@Wr5J8%$|x=`{i>6?;)zFJ@P8#2(#xXRt} zowq16WT40858;Rdst4GQWVU?8Uy!FW@R|$TGixtE@wo`2}3% z!=9K3^9#7j2W{{S<`;04r^uQZag`ZljUxnCxkXr!y7n40gRA7D57xC;%8MheG7QX6 z*Zv92{|Z-WsL(lMZ5yj(`}6A>wH%tX~%j#K28gebuh5(aHSx z3@(NGb*@~B=0Eh+C{lYI_iNR#5;KwN^^`WhYW4bQRy<<*%?%Obsbw}u$Vr}BlC2Oj z8XullZX-)`k|&i@uR|1RPV$U05-iV2^%h&hiRRJGJ)`s_%2)|Uvst*cSFg3!!#3nv zPO33<9ij}HP^T_C63frH33ci_L>W4vPMu5Ca#E%BJC!H{C>+f`)Do_l$*1s)GMd~B zq6zEaDsn9+xi*g{w>`O@QF;(ICi=R{(M+aLYJ@Xr9bo#5D#G%_Zut(UoWpQFo1vF`)PxI_=2qPj0QL z<+JY4K{io$jgK1i?JoZebhUA3kZVp*W$1KrJFT;si8FbU=d z$nZ~)Wqy#Wg1wKB`2k$xCPL;1aE%+;m-zu)<6N@L58xW-kY#=V*EpIi^8>iXQDh}( zByf%G$(l$Au8|?Eh-)+)mf{*q(WGm9jGtG!#?Ss%XPG|Vb8_`R+BF&~bf#E?#vNpf zHQ(PdELUB9{_W7XgS4C(9K@q?q>$j>AtFcqWJ?vIaR53}mtmzjP#7#mnY}vkx>lkH z!k-KE#(GG`Gtv&YZqC9Q^Or*q;ItLin2QO~Q+P)DxqcwbztD~~=3KG{LvgGzA0tF7 zVU2kgA^Hew%&~;J^Mx52OqUR%gYZ)brwinD<~efr$d0Ht*dc%Y31dsiUvgUUE1Z-@ zPdqxck?L~vl7e_bX>`U;_g{59T-!As56hnn@!*N!G?0){JTaX5qc3+TB)gHN8O009 zHe-Cz!yEitfaMuwsd;8gqFnk=MSgKG0)nd_-r!&KLnHvgY3FQm83Un;e26H+AXJg# zi82yG6?qj=21CdPXA)&Rger0%(T?F0s>2LY7F74@MKRM1p*9bv>rp5()Cb zFtRL>ARqK1WQhd%;6Or_NRSV9B4mjK`Je+KOC-n#zjRTZ>7NLO5?jasB2{E9t}-9! z*OEt6I9D!3s>mBhX){HIztv}fev3*no&l~|^BS^?)S2>C@Ky3v@Jab9_)7UI_;UFw z_%it__=HSrxf_P51e_@^_MGy3bSS4zf)5NYwdcneKCxbs8blJ>20KLZ*AT z!vOYWx`#XLNtWrpyY{sQS*ClqLu<0iBGuyBWF;ciV(tDZ?(os_6nA(ASLqJZ@N=jZ z@0Vu89Uhby{s+55Lxs*0E5^7}?6c;zA_J{ir-*+N@ucBReiE_IIGM}c=42Pw^ek?* zlRM0#<8_9$D2jKprF0YdB;vjEg}CxO^Ot?C&I&>Ni~RisrT_%+LJ)Le5xlkf*BS81 zMdr0xa@k5ygzdGLp{*q-V)jm6*Af%~dmY+df+AoqBScqXad|23Qb_IkZ3RNolRvujb0?^tew39^x%{-$=dw(j?|>nxt?@Uw z^f*>Z&Hv+pW{>0hl$7di?M=1rZJI7IJ->lGl8tlkTUNo-Kxx zYx%~rMNgt!psi^YU2%^+LU5VADWQB^UQkfoVSg&q?qQcF%oQ=KDS zuip2C`U%v1w(_X*(>-`aR>vG$H))Gg#` zLTV0fArAv`bEvoQzlErogBwW!Q8NcOlCy~BP(ZcT!{HcEp_xOCp@)%c=HN!M8M$T- zZX_F#Yvz!&9zNd#nlN*yH1yNY^;rwe9Lf!yMXs5H8_AR8nmHtldn37K4sIlu6E$;i zBRQQY%^{SX{fW{aLdHIrs98k5itQi{z$^krvI$vc5xL6Rm@Kmh7|EBr_=5lLsWttBJEXeioVG9rwI$Q?wB^bQt-oynqcuo&Ed5M6`CU^_yz4CbYu zc16U~FQgz`!Zw|P1>su)F#yYS#@_u@@1ByM21+G(+&_QlC>5aI$NtP(Qh$AJ^s{;K zWsTQfkn!H!fv3k;n=ZhLU4p)rKo z5Q0TtKq!q6v~=)!7?628^wgUy^L9w83nBA%SoF?>%-bQXoj5e}c4(_%CvS=IxmZJtt7aqNk%7YP~WvY0-~-XJm2`^Mctxn7GM4HA^=+qwM-X?f=Q-tR-5T$E?7?+ik!T-WyofLysQ z@$WxC%$ssu7ZRm%Lm@VgD8(BJu}6uTe)Bcl z?<8dUh05=!#mt(1q4IpPOutb1#blX&q4HzMGW|m3-3Xa}q4GTmnSP=2J=mA&7b$5$Bt5kUvE`>tuez_Fc(M?1%C1d{4Ro+mcbHhR` zUV^n-^LGcB7Mjh~@lDyey_?+I4Zd7LrqSMR<|qxMrq29!k!~V;yGN%B(Mq=sw)2%i zFt&fsD>($>SKE4}gCP7`zEhlq9Rl!GxoU@hh`u|{KwB$0gx;gPu9Y0(ZW7yC$sy=& zK)W!X`K_bI&^UZ+xmR+T3Y|?BJ%(l5U_vw)mTg&t=q^&Wb!MBs!m@1#ftaJpwBL=v zXtW#9K-BW>pE}5s!cFhgx42$=ezlpxtx-L`n#wI64a0jj84bNIZ7Le3Ue#PQq)RuE zXqa4~(GYg$KW*)c8ZyF)ceE=Mfu0T)kflYS=YqRV!wWT))S9uDgJlaG%Dul4&BL;X za&HV#E^{dN3UF&b225JNgURJ$hjQ<5qFnM&?(Io5n|Jd>uo+QHB?;>{jc6BgJrR7q zl|Gp7^gR)L`nFC=VJ5lM^}M=S)0&;n}jyE7`@~pL& zfBz=J-Q-zg=m$h;#6ikWq$7q*o>j)JAlKxXG_;gllV_!&#pIei%MCq=T$86uc^J7J zDa3?vJCkejbSZZt*W~F^Zc8rZ8EU%ao8u{{&`{GYBx)kfSG#|Kkckvho=(U_3Mo%p zfC)5_LdrLgWg>-?$B|_sg_O@G%R~w(4<=+Hg_N@hnMfh!BiWagd64pUWK~9Lx^0CO zk@C-*sj`EV({Pni{t%afls|bRMas|0)!5GMk16AZ3Y`(wb8$&`rKD9xaY@HdUFi7D zR&wPU8ReVC6}`oHS2T~xt^-4BHU!BH|M2n)0g@+IdC-L57$H}q_0|BqSo1RLt!+-! z+o|eVZ*}7JP;YIIc1pdqAt8#L$7CDeF8*d~hCWB#CT{oX+I$O5i4m!@UXq_B4blNv zXFW-X^5<6r-47_G;75(M>Il)*k;+Q@?jwJoMg=Z+AHeD=C%!<9JeS+vRj<&77+BPE zFTTlFDAYfTHpaZ_n;&kSb+2J5)N|c8=a8i(QLUNK*c0$V^;~z%JHT?!tv2E{M7a#1 z__=_nd2Z6U=i=6061ih$k;_RB#m_!O`_miUF}EOUo|~|KTN3R~t~=%z8)1FB5Ov3V zlW0exl)}8a*I$LjndcT*zYmd{0WOQ52T4pP1jj5St34rz;X*=YwGhN`LTO|{6q!RY zK(ksn=0Rkc)xt4%A!Jqy$K05ZSuGrMBaX|g7LNHv2Xt>%o2dc#wm=cboR4O3%%{+# zW0vFR;Fy!78QBHjQ?1jLB8oraE;#OyLz^#q;vTu0{S7>FYnopML5NbV*km(R=J%*5#JW%TZ_GKjx)VimzB5K`77?JvBLtLd=H^HT#*5w9qy9-$SLAah$%N$OK61LBO2^3lUeKCe$)g5qE z7F_C>wfSNyopsFD>p=>XIqR7B0X4F0sb!k0WUvN9m=rHVmsBC1D!r79+VM%4Ad zCeMg=$(8ACbYfU?u1#=1aBDA!+)Vc;*X-EMbX%hRY29w7ZHQ(Q zbu<0CE!Mv~Q8&|fiJBc3nH@hzv?I9%hCWlJlVWE?EPd`EF#|;I0d6OYMojHoOjdic zpr2C-wIKuz4Iq?82xhwFF&MMCFwArhvdo2Hrs;&tg`ual37HGSOj~hW=E5-3_uHiC zsT$3or`c%IOe^qnFw^^_87X}xpxNl`wK);VAFq~YY^YH2G*sx4HdN>mHdN@6HB{&l zHB{)5G*svk{OiAH8n@2#Xq~mPu&dp7tfuOTE4FyQCKY?psS-Pl6#Leh8c|It_HgMY za;p2%T|!)WAhgRm5S}Ww-hy*uLRvsAHE5&fw09gExvm@VCE@sDC4G3U2bKVG#k#Z? z5Y3a>mmaH)nV875{>Pr`zT8TpeAKfliPb25 z4XUK6Ep;ZMo165}p-RHSmx7^!#-fjV1_}&i(RsMM@`xvo*F#zKCteRnJX`ib{N^*X zu+V!5g{z81-Wp9^)eMcr4baq;OxI?6>EAz<`}JDri;8AR^gbcVnI+MSfKp1LfsK8f zWl)b}r4Z8oq!2rVI^K|sH{o|7z-%HZAR$Y{K$5^7%{lF-n?og?01rqj>wWj1P zXJgjY3f<1WZJ`ejD|9cL)eDgBCEdtg0n4p0Y27_RloJ<>Y%)>KT`;n{lCT!DLN~ID z$u%oXSidI`?T^I`M%J5XHc>aS&P2@$-N?2hYF1ca{kA3AkwKHManOdt$|M9M`zQ_J zKoew{^5N4Myg4A^c_vxy`9j3>gM``;f{{%iWDW=;%jt>k%>iL#7m#HR*hR;6A|Z1? z#CLB(=75OtUNWwTk?kgoh>>lHCd-r!@pCY;h6epc232F3-fbzGDY5-WIiZOcD9dPD zwX&qEQ_`B8i+=ZuPDE5m!>zQZjhiPwM(6`S%jkJqBCbgT)GX=(JAXeLeX>4 z34jV|T%mjzMbwn!symygDJf~44kBtwsx)*j45-kQRBq^QB_)je^HT_N zQ_@63-}o8d`C>|P)xAnCl@v}|9w3)u3MVc1l52W`>Iz6SJwbKn5;8sI>g)|6WO{4WSO3zx(&!OJwbJKKjC4mqJZk&AY>HTF`7rnLl!XY)6jb0+lxavf9@rt(@PCEe)P&km+L!q##T<2n8IX^tYEfP!l{f~N87brs`t`1FEI~ECV zNfRz9mEikNKpoUAi-ad}*+0WmrXAc5Xq86l6~aI%5wtfc5g>bc^|EG4ghuc9(3n;| zwOeB-QD-Z>#HThG)b~H=6T;bQOz_`T`UD4edX+47Hn*m~9Uf|gq`mMVu-w_)m&Oyt zBd*-mTt(EJ&3)-I+}aN~64viPat9-=hHBtYqWy`wFYQXyoUO=u=s?t*t-#O~^$>d( zrfc|89ifhd;7gxP$GX$gSPeWwmKhp+X*OBud?9@4cCy+Nf-e;lGDFMOfcXm{Gc@>8 zw;s^~0lw6qEHg9&@}Y#x&=AbK3l#CCy<|)gUs@km=}T$&Ir!4D?=8+*4Sa}ZN)R_L zbQ>ykNq?UMi+Bytl7|%4vXK8`4G=%0_+*DB&nT(~N)R+Uqv-r+4UMMGDDISQB4-r4 zT`$Cyrw>bgs^QiRuaoH)-6h ziJItKpsk7KkXvrt_r8TVOmr^LxBsqVvcJb!m@w{RV zxzt@K9EOl<(t|+%Orl8-0^Of1lU}Y)%JzgzdJyP_giLx6=!$Rfh$cMU|dJyO{WSR6J(Ai`~PZe(`%W4S-v{;~sKrclz6b@HNAHF3Wj!QwHC!_mNIP^f* zBG5nTr^(`iJ+=9wJ(kW+O+w@Fp+^xr`H&X9^{=2b z?X8i@pl^Yc1$dowlgF~4`|7-oX0qz4pf&CvoxJle@W~5j0v{~XXF^rrK2uxnQy5Bs z8DwcykTlJYIXF}WZZG4(a)WYvxr(S6l-tXhM9rWQ*6C@uwO0jhFNcyln6~BivMbU4 zM2oD44n)nM3JhJb6#Az@@mRBtP!}#3?BxwYv?k{Ne@w-)nlHg#rjlj81bcaetaSDT zdnqQ%dQ?>Y%Ak&dr8Bk zU@yzQvKY4fk7i1Y{yR?t;%0IU%|s(}b&9CRQmJuo0Y z0Z3TCyOL{)aP>5Nf!H@ixO!GRjKHQMLUMkcT#6zj=U2!zUF2&>K1ibJ0_u5yEYn4< zvc`~Qx`28vAY{6LdQK!{x`29m6Ea;uJzWS{zJ_`ZUkMWR?q)x%P5GG#h?E;7mev8s^&L2${{~=xPk&Xv}8d79Ghl zn}J*GLzdYL++tm_%w`aS-`8Ol%w`aV9}_a0L9U(BDVlyWbr7?J70IYTM?yvKXlmKhAzkZ{qhFw$p z>%*j*$o~3y{S~m4JLerf(?x}NYApWR5z=H`ZP14IY43RB%O$qrUO<|x_1Sfu>j1fU zTxG8jHSxI6o+4`EaiQHu)Wnmpey{u#foI}zpYL1-JGYZ2NXY0n%N zUjODx+gPp{y+qcd*+dhU-G=R(l-&>AWz8GO?!==s5}K0Tyml$FJLYmB+Lro}k6d$1 z=H++$vcW;Gm&=i4ej~1iWPSmzhGc%&o@%!;07>S@v0p6`5*nsQv8~CyOxp*b-PE#1 zGx<2lsLveTIqZ0H$mH%R<3WNMxu@JbNhcV; zX6lA=K3ST{-A%gSdyDXaB)5{DV7VE&mF!2<%*d@|8=_`LZY5jb*1nf6GBaBCLDY;2 z41I?v&4@X>iV&TMIlF=oZHPJhZbIfkIXYF>6EY8im0Xw5S@6#c!b;90D}!5RSV=Bf z=0UKMBgirjf|Yb6WFCZw+lG*NP^J#z)7`XY4Bz>?qSj+FU9T=dlU7oTpM#Zrq@OW^ zA`o-W$kl&yg&#ML-PSx~*I{{A9oe<-$0NJv@DSOQ#=N>2AR)4=Eo90FX`1!;zyD4I zyGC}>ST_^WH0$v{3Xn&(OWLl{BReG2 z#qU7{4DOInKf42AYVn<~k@5_Q7TZoD zLKfdpL4QIP-%!D!ge<<@!fDC3>}`6mX-S)yRySeSB{#Q@m<9y!vij4hNs$a$vffDhy64rv0(o zd{Q$t6mG!PknV2A)sXH+pm(ObBX-92O+OZw&{rOhYxr1PnYNEcyV0aabKOMAb>o!V z;n&P{FTWF?f&+*86a-;E01_O*g=8uy<_+3Qn`YVrbU;^S%6#w zu9jnong|ls<6%Ti1TL6NqB%^9E|@e7$kU<==BHb9O#bd}f%W^3H=z!b0tE9qi6(_S zjk8C{GAZOLG=(ga0t8b;mPrAExrQv00t9n1StbPtrXL}b0t9miA(H|Gvm2o_Y8!&t zjF9C-2xe2cV?;3DEKvP~qnq!?>s1QoEnEtMc|n?y1ULiDrnVjpBgZw2ENU28&`^;t zWBIK=DiIgZ*Gzp$S-`k}V*8xYOJsIeo%`N+LmxW2$vJG08-Et2_;F!G_IA^5)(H&B zZal7rWH(W+Vh&|*cPYA7rP$ss^?Qqk;&Mu^lkb|8KgcVeoa#H#zJln<`9H}?(6brw z2TjfKqn1#L%|2?}DHf(R=@eC+Wb}=kVy^@3nHqfu{Vmc>pY#PIfd(dEu!WW1=i^=H|nh|U2?nk z*6Wb|VCo4ve~wUpLeTl+gv=nI^8_I?2 zAX#P*2*SO|GJ}B5w-P9#^YzgTI)6*PCCGKY>@{Tuoqs6Jh|XU}vysk!k7Boxve!aU ztI-k<_?WWS>;$9!)wsA%8sOp%JGj?DLPASgtRx9(Li6nP^f*Lr^aSH!LYmM#m~RE- zVVbb+MiaF#^^iW7sD-JA^zlS<5P)Itwhsp639Z2T-Gf{U)_j#tYZ5J35z=duWx35U`0ruN2m>Tg^(Uf zD2)(8I$NMfNcWbzMN-%9xXRSk5tl+pw?kiA%#`UYq@kH&t-nV&NB{n1JhX3RXeVXq z;-URddU?4%;kK{DBm0^^g~)cd{o!RLA+kL{>q~>hEsVk~0Z0vd6-fGi7W#N``gSwJH$%Y_w*%SmVktGy9T#^uSW->q~p zx({)gi)Kn({&sticm%%62-Ia?T?E!(A)Box5P`S97>~fU`-BKgqJw#L7lVWdbR#{L zP;|$9N=fimkJJ8y)LRqQ*P(zs0zFiBC2A4q(b|D1BQUt=ifgg{IS7ex0`~fR1d7EW zT=X>(Ee;W_Q^>M7%vB9OOqRtVqV*cGEDjN^e^ zv}O`&&zMHEZc3;PAw=t10!5;A`3u?%(fVES$_+pbE(I5TM=nJQgD2%`>;&w$i`M90 z5ROOgsOHOpxOXzjRvoz?J|BLh77((4McmCHWC4q~d*&Jl#{w2{cL!M(u!y_cg%ydr%Y+e$yK~T_OXlF`5O;f} zexK6e=sLwEf2-^rkF+P&+#{>7jH`~c{CV+6`{1Y$X>N!EK|-W?;_gmJBhBNn+g}lU z(QVS6gw!KF9=8DGk>(-Uk|-lBxZxLtSX2gEaKkr==Fm^_)#o024v}Q>mZ#98WLdl+ zD#wy#@rI}@A%@WTi*ka2-PJBX0Q3 z+!Qzb1kK=v3(#a#zB|Tu_6dE)8FDG&hO^{q%ng65sEqz4%y@*J^y_-zf@k9q+U>{? zp>BMS3JJmvarWqFM5BHUg$LPK^n|Uw``#dY^AZjL-Skc;OJbIecO2Rluynj52r*iD zHhnm5=U-)r*xH6Hi&Mnbx`ZrF5nJESLFihXBDOvzWO0hvdXDph%)}QLrMO;?U*WGEN54oV^)Fd1 zVkGJMt*#zijn~Cbm#+HqM?Unhq^xrlPl)E#owc1zV58HeS9a2AZR#Ali*yq?U79mQ zh%3*Iw|+*KHf3|umXO+}hi)5umpVewJ@VTEyJ z30W+{Ag`Q_z_VC{L0&k^YJPOSe z7t}1<^QQ_wGd&0$jXRVR7YV& zENXi+gGFtGCM~Kpeh$&~{S1Ae5M4iBs*l_#x_*mYZQPu8ZQh*Xd)PJcrfuO7s*&D)P8l?|SlJ60sRndnkcwK!8A#yL<>Qji1@o2kG zAwF)Fn}{D+_#r;dC(FVQ@o@qn3qQn1PeOwu@o@kl3qQoij)W}yGBvu}6SDBjP^cXT zVd0mq(C1I+bTCeq=6jiz&`Yn#rAVA4(M*XGd1LNZsK(TLmYMfV)rc6qq##~=HOf`1 zah`bf)#8&TtFI-S%Bt)Z|NGJdw$im~s``5JU^_nj*uNV5}evq>u?q zF4oRdwgmZvbQ|k#bs8a!sC-?EL1=qK3NrmPHgo z@#E<_PWu!9e{<)fzvws%Eus*Lv&gcD>Y{^~NtQ(vLUAHlW@re-31nq5h7pPv3M;ZD zI0a3H;qmx6*i|xaqFPf(F9d)XOor6<( z9_uG0NHau5zmY0Xof!nh-XN&uBOq4%;=x8&YKNO>q|uccDsWw03vuuj+ZtmCf@K$B z#q+sJ@S_(&ao0i+JVD4}3_)-oA#*JR!A*oL#t;Mrgv_-N1m_a67)#fHI!6Y9tR|lo z_!BQ%ye0H@VvDPeh!AQIbIxMqz#&lW8^ogo;Od!+x2TwJ+Dc`^m;5FF^_i&5#u$@&O%D9 zX*LETAA1kpv9W$)4MzhskCtq!J0Loi=iz#&X+B~*)HJW7?a_m{ND{K>L0sJSC_=@e z2XXN?vdkS27bD5C=s{duM3zMl;-Vi}7CnfIKapk8gSgm@EQ_9W4dF~-d2FmJmzif0 zdTB+ujxWT<5;Rj{W)>vum{wxn3UtI6V$%KD8V#Waoe8!i-Pc&y*aV5F>{D)e9c^Oe8S z>c#h$lNL0&zZ|=c%xI(i<+Am4o^?&*-3*a#BB%SG94ce&t)mH!lNH*~E0><17GX6RV?Bw5jwzfD+?D(y~T zz;a~83)q1L1y=kjc3?Wkst*B6Ry}ol_kaF_TDIOf@dJg_^QATTw(HqtajEW}8KjCO zxeE+kAuP!_X>x_IBsZOrx+J674ofnE?XV=LupO3UAlfNQ(w$IrNw&gG!>>DTD-2pb zMELXlIwYwAWI0;$#kP1@j`!s9$~qs*vG8;qbyFg2?tBnud`upL&h6z!B%yi_1cCR2Mj8%_1_3~lz38#1Y31^ePE&q?;dSlo-Tf_t-j zTU4xITd*1ns`2`9<(m2$b6dMcUt`{A?Q&Q5n+2EM8&}cCI|UVChW`x4${Fs-cF;-h zQ!(RVhP$#IW_S;2b2?#LTcfGdiP_x%O|645yT6>GWSLHW_v^xYY_UZjAIT*VgVi&b z-C4No6OP%P305P0L?_p$wTbV3{Z-~Qu8Ga6o76;$7VZovfYWZM-hpo+$0ek`$vEmgG`2!;+khW>}IFq=^B_ zk{rhS=u%@ny5pKJ5!PcXP#Q&hSdYkJq2AF{9^q^45F#AY zbuk#2K1|mcZ0q!4y3RZ)Wx9r-8K$c@nqj&QK{HI(UefgG+8#e+88BT9ldx<$eVD5j zxZX_cMkgwKC(^GnOYwL;{iP=3b-*v*HW9DWTH5n9DxJ2IZX%`Ag9i!G;;}U!TumDj z{9VF}6j;O$!*#yH1b>cZnBaHN3={mKG<|}T_!;Jp2`*<_tqBu+o!qDCH~*uv8@{K) zW_NYpQ?UlWzqKiD9Nku2xm}1sOu_QIQl{WzG{Y2pcB0Nmn1UKK!xTI(O`n39_!+T` zDVV~x#xkbh4zwG^SoHbB?=Jr;&mWJjHuIZ|uH`G5imt&env1U4FQi0Qp92wH2%oY$ zbt=Q$-HK+IyW5B9RED`Lm8Q?#DEz!~?k)gTYd1{Y$++Ce${PPVoXuOtYQ0NVzFF^z z&s+8LP0rhlADf!DjI`$FtysE=sB)77FmIWf74q)z$|ggbC!rZ8>eLffPSjxenfU`T z))P&gaLm)eU^bd3oaX2+4)!hnp>Oe0y@l-s8ch`T0{ksQd6g{c6*bw#BdfEE2UTSk z_f7UG&Z_KF+_zkASd(4aKSTZ%{JHGnH|rj(@>#0J)zQf|dZY0_#AYd}=#T1X$hGlq zPLXaRv-IWum?cb0uiJH&!nAairpHf@q3&Dd+Wo$0YT#9Bb4O{?d~|7BWS7VT$pc_Q zmh~;JQ_jXb%4n~VQ#-WB2|b4OIC0n<<~*G`nGKDZHJy#y=QTMS*VH#P8%us}ZZ-x< zH<8(>-4C;ot^+>gwv~_HQGTXL;qmvAPr`Ac@c29F2jg_(fA14U%QJ22Owc6jh zZ{s&fF#&a$fMIhq8swqt<)!u6#cN-j)iG_Hp`({{mn$-LBjweDWLo-GA6cCBq69~> zBZPSkFQ@TN+{M$p{ zQBQk9|Mz4s{T7MR&Yv99Rz@O!Ddwma`d5tF{pX1HDUecz_#=N?NxA~?4 z^EY})|M*Oaj6_O(t7M4n<*6&9!>Y%ylG?>SUus;;tJ~{NorY)RCd*B1j~C0tWqqTM zC|`F`S#pK^*jIvDr)Xqt-{RRlie zO>--K$#wdIe`ckppU#!OP5zCp^i5pp75%x=t+P^By6nZ2m9Cf{R=WRI|ME&7c)v*PdN`j>0gY^8_9R=QY+-_%OKklmu`m0pzYD~(?=&mOgeZ_3TY7P=UJlrg(_ zJWi;JOZBw!$l_#CVITP+8oxE2!~ir9kaEg~^rBffDXX5#&XE+ots?UHdZ8B^CJ`*J)rsuG7S=W$J{g z)7MHCgf>*nX9 zb?&4Zv36UTvh1!|6Gv<&kv1`VbX|*f)6&KyN3H_{Tf8>xVodU)b+SjFJF&&$(9f&r zM~!#lll2W6FOn%=sk^B~3!NB&GuurcRFpmY!$N4GJAcy>Ea!w2!qkHTk(;ezSq}u z>;>4%riU&ZrBA?k2xZQM} zs%zU#Lx7g_?IJhOg}GK2rcdem?Zsi!#gp30aIVcR-QP!9-luev*4ZWY;abW=a>?;$ zr47g~ezi~WYkJ@7)|Drc?`MeIb2qu?q9HQ*_FBo*eM-(P>r-6Yr}*>il3|jh_S>5F zyZz!VnOx+-|9J^f3?rJYyw zrmk|glc0}ex-#57WV(vy!eIK#U^LUM!M&&0y+_9Gy*=-JmEAjM$JBf8nR@SoR^Iy` zG6$$xQKOAoGFZ$dyLe`$x?yoeIsO@6hJQ*E@((QQcKM-^Wo60??{}kw;-Ecc>Do<| zv?#|n_h@(O#|g{44_vKCVY;keyJ=Ym9I{TkG5z%uQ6+%1&cS^|Rk(R+1%^^usAGuL zJU`xtuDW|yt=ko@2XD-jS7Xejy;@0b6u*;OzEXGaWEF~z^R-76QO(GI{=qbUK25HE zw~P2oVS7ecw*DjFZo8`KBt#kVA1_iFC&&d=#zi`Feq~2lz_QX9)fJMj1>q`b@>LkmYVmgA|biCVV zVw8ODW95p?u4}0|5342X_wv*A(n;MOqja|XdwtaQip7rlX2_c9AkBs*h1uOJ+NWeC zc`e;;rv8(5QD1o>02%5Jl2M+NnM*64{rZQ+)sh;D3SZIbDH)HxOL*HBenY)`c8e;> zA3K0ow3c+H^8*){qOV!hAb;LRve@jp)?#mO%QdFZ!guAz)8`c~kblzB#mzUdWteyEPmSi9E?6C@#3Y?+`IXYvQ+Y`*$MfFDkvR~ zuq(y9q9B(2_$M;K#Y80ANHTb~-SpQ&qV_NCtdv1!%AH4SD|gZ#JY#1__f2GM9jVgV zEY@@=iL6vx(Y!t32ZSm|&GKddF`Czl~*=h`mHQxh;27U<%N~K zcDAGg%Y|~s*Z3Ui@_384ma%9Q+k{FBfy}2s-PbK%_vzg)=iTQF_q+Gw-G|!U6C16( z`}(}Q-mWxTHn=m@>YK4(DQr})8hV#Z!ffZs%Vg~O>S9?KShZ}JS~2KcDqGc86h_~842(*OA07Wzt43hsSU5@j-`5Y z8CggDhehPGvh9pK%IsPxQ*m8DUC?YI`oi$+8g6r?UUYF;roqX3kv_plDJvurs)MGRE1UI6D&F$GZD!F8jejBgIyQz z&tgy_VqRV6nW6rwUSH}!oI&8qRx7VelPh%{)=Mc9y;93=;!vWB$2S>8Sx>c_HtZ=W zdi9_zY39>js-vF8&&aorC1ob%@M7hOgRtu4uR*8FyXnXGI7Y`ObuVYCWLQ1V5A3v7 z_La4It$1d(Jg5|Dn)75|iTEon)k*8auSM=tT&lh98I&PEwwE7^3fGta z#|k+KVWbNg!r%S|7ap>>g`8|42y|d$1jTOfqJ6|681SG6rnUbOY1o7-w@t#)HZh#`)yZ`p3lH2GoC6$)RG zp4RRz_wl~j>K;7aYBiKa|HDJz>BEk8SG|$0x^{PZddGuglv4F;X_?UJdg;k^(iY8R zjACNN7!@y>ARd>xFUOi{@%pq8RMof&M?{ zz689^Y3o0o2d#uEHMXv)H3luEEeSoG(hx(mhEhY_s^Jz1y(OATLyqGR)ev(oMbs2S zD~579=!rR~3QB`=-y=m(1ikYA{npz19ZpW7z2Eme&)@Uto3r=3_g?c_d+p(kFKOzT zi}|YCLh7ot&Sx$JmDuR6;pjp?a?wh9>oDk&TX0f{$8;pcc3uhOfb*niEK9g)WJ={) zWvZ>HzO5+UR#ewkRNGcm(^ga+(xmH6-%%QtXCwL>7x^IhGKmlbFL_%=MtRvu=(%I& z?s2LT^__`A)Dn0|CF(;;)S-tdQBOKJg}E(tAZpWwwziVR9HCccSvTID7=+*vKoBWA zS#VPkg+q!;fh5z@NWdVvL&@y4mw?L*u)iy?yWpn+`=kPU)ffeKZ|aL*5|1RX2Lf14 z8^?`J6>b@4xEh%qUo6pn@F`~S9r1+tT{7MdP8GuB_s`Kf_=TyITJanPU-SpKWrq45 z%4y~WEHPS9G>@fcfL76a_i44gkJk@j_o zBoY!Eaf*Sn$H){S?L;^?2b`sgIetdbrQjx|I4X%db*L{wcROOwGBfg#N}-F~kum2c zg;tMJ3ia4GW#suFVRGK@X%tk*Bigxl%xI@av2CSDRWlwH(utZPco*%9%A^a*rF{13 z;Iv*R<>s3__b#&l9R2ctql7PgA5g+WaQ|-RB2hUoZr7RQ=wwjPD?3oi&LdUJ_%8sC zERD)bNUqt~+HWm$Z)GnRNeljqjuW#1GMi1sZ<}uz3Hd?1R}LvFkEFM*FCk&s5%ab_ zMGe8d1tQ*iKzdZSK33)pK2(|4fY2$RTmOC*%=@s_8UnxA2)L3%o72h2H%>5i9Zx9M z2t0J;FLdMw57Cj|-YaF~i#hTnjGVdX9@nhr7{X>g*J{LIY!tR0vK6f)JZZ!sAAUi2 zmYY8zx|sZ$5Q;R=CG;x(Z)77^S8=Mp4amlhO!atP^&xmGdb2rr`crA&E7G+ijjn8) zg7l1Mfb`T~iHPg%CnJ;45npeDP2@P2;0fwp2{tQr*Xuw>n}JqsnKDo&2WtC;d?j%+ z3Xk?dUt**s2TworziFpG9<0#ka`D}7h+lYG=6d1{qwp3;j#?iq9`%yzf8|7qWYQU~ z#szKfqlgm~#1$e>Hw*`~Cd{a97Q#wK;31a7j5ByB3`--h@dcLRStNP`^N_~Rvi{0% ze32Rgr;Hcze@63o8A*eo@1Y(f=W}@a5%1ocK#ch9AVqxY4k^@J@>H*k7ultSX=^}T z_DNyiC&Cr}oX)2cEpEsac{0|t8zNkmr>+Gi{`?7R zfs$uV84Jt5fwk4n$HVNQ5o3DGl*hRP7I5)#E4%o3iVSF0Q9axmFj{$N^~NIz+YnkE z#o|5qKP@BVE{~313PdG#BeKDcHJz?Rem`W#INy zZr~dGCZP>FH)Jj|P}PUIE$7{E0NYV24Bd>{umg~rm zU}WJ4uvQ`{M+^}{O#%CL95GiZZ%HM6w{~NLX&&w4AVYmBB;4$z!!|1I@som33^E`) z62;1~7#5HA-*!a%IluWh@6tX}(9W0%-B&C2kB%_dJK-n=i^eKjA30e-u*ul%rY6!m zC~5;_Kx<8gfYz$-2x%dF#+kD|$sYd`@TYc#g!QrEU7qw&_FKrVnbHp4B$J zcUyLDq+Z;F^P!@bUEz6y|D~R@*NV`l_6$ubYD#5GY|JV9^vQ6xorc(&TLmeU!~;*E z5}raOL!C?LMAO*5AAa>qW0s{5DZqH5$3M|bc2A|D6Ke3r7uY-FQKDTBZ(R9TJtTuY zkd|pN?ifeHF>9?wu$cNj+IrC}LD1M*g)YE!Q79k>WF&J{i98>$M+u}0{hou!)Z%CN z!3A`LJE_Dz>HB}XUh-~zWm`lN>xk^FUVEb^@o$VpKH(<@C}V`qbvszj7>fjqSzIhK zZ*;>O$bc12vuUu?lCL8ULmI5GFH&HIrzRQY(KJ&N!?A%coB7C{c=|)Uo%`~&5nDrW zIP&A0YltT;@q1ZKuM9~qG+$naP(P#jA`8KitApV=18F@8<6GDH?-k|>-d{Xr%1?3OV~kq3OP@G zQeGcIfcM6$R%*Z$fg#dTE}PbdaL>=N{*J$!V*aUg{bxBAVjYMmF6QE;H{4q z4@GWz$oOc%Ai!wgvi(@ghIkLxh2>Ann2@K_!*z~WoFS>O(n^M7V}2S66SHWFF)=O1 z#Na6=2G4B5YfQ|u?_$Fqe!6j^kMcsGn_*0>rLg-dqdC3ZJ(by3^V3H{u=`MvXy0%I zcAEPgNu3ihh+xTDC{KRx3c!FLMYIA&n0h#Uf3lv3IvmD8c-Pz6i_M!a`3(Yejcw5s}KQG@64P&JsOYVfaNss@v@jT$6EaR@)vwuusR z)PvZ)Rg6^!4hx@Zx9Mu0bz+0i7WQKjl_YhCjPx*MzN;iJ0$pe8AFV2EbfgJ6N0z-W z@CKoCvYLB^V?7Svi-5x&pm1z72hzpLfRAC|1HfCn;OG7(5mfLY=#a1d!SVrQbNNkK z>^Qnl2h@T+J)oj9(!m6!$Xm@h00EoUWddnD<7+_G!HmagNe5YaNfhF=r_{i|1d4M% zfhS{v#%zS@i?94p1?hESTBr~)feRq6M;iGd{JL2LjdqQ1WJL4uF7>9Um4i+G-qS(d z(khA&DR|Q_|2l&OsNMkbLk8Ga2Y`Jj_#T^)HA?HTH=;D;C5T@J1_aq*K``L7A1Mhz ztgimvN9!S0>)Qj+0i7R*Rk9M9p82G)u}VdsTS*K~`dYuUFm$+c%OK;+sTa}lS&hH$ z1Wlyuizgi4xp=6?M^)pW+>Kx+obyax%4+%<|6&G-gaUP=dDLgK;n>~r*2H%C)vi7_ zgJ8~4fLL8yFq+A04M)d8abGLiPJ#|FBrJfm;lJ?CKVV+fyfX%Djph&H!&q@V0iFaK zXCv{dR@+*~zzj?yoH{EFTcH#E0U!^&CjDj)$vY*dY4~H_rY^E2u*RR727A5`?9pfl zHT)AB3_?=ACm`X)fw35pVJq zl~gST@{eC?LoyS|Pq!~nzOW9*fP6nIUppknqgvLbUj?mXU3xwKNMi1)A$1aNpERrm z(W;c7D%z8g{g-m|`{OxW!7CbMf3L^y^HGqx`FSwt07xe?9aBqze;6-@4_Su&sA zRq>PISl$z`!xgZ@6@1NPCBE+``nnB5#wVaWnRq^lXJCYiB-ZQ5VQ-8Spg$nc(LCuG zi+V;&KiD48=&=Hm&O_cDuWEHSo_@9ZK*jr}A*xnC81c5)jJms5hBI>^rvz!E9YOhk zyIkw|);F+@Lz7n2jdjci^8;o~omyQqX9(B^BEuF5BVGn)Am|C_jVXX1yV-E0BxeYA zQ%0}`rIt?Re)&IzD%cU1v#ahcYebk&<0Ubigh(yy=%zooQH{wF>I`;2=@Y+5bU@Bxk_Gf0`LD+ovneMzZu*i&{&NJO#gH_rkb}OL2=DXNbA#AX{ z=y2x)e27CZ9rnY&13HTXPS#RPr}Fp}N9l*Hi#Yif3uT)v!Nb2L2^f!5foh{dtFM@1 z{(F5jUFMhjLi`KB9o=EcGX^a&SCz!w6jFH${p%=lr;~IhE|*QoVw|-Mq(GBBNlla?O8^2;!0AQLi`UP zUiwWqT5Er=*WZ?-wT7d^es?*FqJ(ogek(^`Fe8(rFL)dU4TPh3LIlOvZFQ}1RNDW6 zVT7XwLO~B?8>DoY$J`1riskPLh_OQoM=U;c-onBR#P22SoP7yE90=zbfnyYR>IrGG zRo<#b2Q7qkXNzL2pcd~|8LK2y<4I0sb=ZsDLM zJ&KLZ5ea)9zc*DvFXMg#<9SX+`%WbEM}~LpC3LT3KtgYsomN7R{v{}(v-CHlGa#YQ zq8KO@TM7Ldzm0@?=UGHZ{pVR!DswzRjg8LMGD((*#7bUUPqc(1zl$CCQ1c~rtkW=7 zl8f>cXv>U)yUtMcg)6lt|6_70_iclm$~h33+z4%Yi*mM=e~yiYhwwQb8qQ}&`IZx9 zHtU=Q+Ujh!wkaZSoDGxxrrMQQ!%2uo@CGpCgeaKMI;6?<+b3aDDUTImQ)v~qDn=Go z;Nkb&67rU@l(d-1C(bBiKc*ZkiRuG2!w6smn-|JzN7^ z4t$PtIJQ;$UMb~IeZ?NB5z<_Kio7O!ht0tQHTw&+eG3PTRZ6{9{CXBC5UY?1+28F? z$L;nt-#44Ak!d&vTcUmY?#7^wU1G1pK3mBI>x?7p1Z&!6=r}f_-_{y|p715oYx*`R z^ujHOExnF68%KQ1_HuK)Lw>ntd>j#woETqJ1S-ur1^tz94(Cl1ATGW~xz_D{Pd z`1*mNTvUk=)w2$yg`86^Ky`%=uht+i7b z-JyR>0o&15mr%{Iby4=_n0eu8T~Uh-Ym}P<@MdWf4|Mq780mW>3vb|PQv{3cmy0lAD|zV8%eXz?kA?MGaT8#MB-d$C$S;|$BwxaOy zEy^EJ#%WZfdF9U)8C`6%Z3qI8QF~gC;!(2JCyCcQ0mlimS%JWs4%SfG~n{w%e$2lB!k4O$wB#NgvZQkwYpSy5!t zwxTD)Xq@CEoUU~^J`Ih4qL&ss8PF@W@PV;^#s)y{XnPP(q|tVD$F9|}cQ<2yI{*ap zjr~BLH};n|U~I7v;&5}aFlGx*v^!nkeOmyKgK$F*zI*r=`0&5fz_7Ez@W^P3|8oZa zOvV3#6c`5kU^ojfz$kO;4D#0)6BH7?xQs7J#yFTqAKqx~8!s(D!Yc>%Es*mtsoQk? ztZT>5i$!iVb@M!SI+Lckc!H+q;Gz7CD?aaSuK1ig!tgUSc9YpAzKHZGHzZDJz#;EO z=^jkIG6Fnt{)BlJGI_^E=8Qbl5V<}t?R)33USqqr(7#CB!#UtXNOo*W3$LtE-(xe_ z^)U1CNI~kdUR0*UVb`R`qd7Z3z~sa;Q}VP&U_K)*;-Ws z9YY{!kXYfYqdY{?Tci2!rCOu^b-TPXwrA5WKQclve;p5%ls^^oL;EOK-q^2mNqMBv zLk2j;$;maPLAzX5+kstf9P2esPl-F<-9$>XQ;$gkm8!=&U`eFsDbfpFq8F;xV)lqWE+@kZza7E`xJYiD`@lbSjP;{>DX{2{ABfUm4hXDoj z-H_V1y(THIyYx36Wjehmow=1-m*TAS*AhsB9XW9oAE+P-)quH~58CUm{1>z!g~TIVE6O%!`xRxGe7N|~fxk12@aY9E zF>{Ygs04CVLZp6LL!`3M%9adkVu_r|i&g5wqnt(vX}fRMlo+o7|xzR zuxO?H6^*F?h*R8_r$S?k`^zga9yI zYHLa}jp;NZvACG_!Qfy;vt+UGqA;suv2Y`G!Tc1-@pLY}2k1L009M#3Z(gFp4hQU1 z%E|06kis`20h&-UFgGm+YbEE@^E0wGM~I^(qoqWsqqIOPsn^`a1*k^u;u5zs;mku3 z89kD{2&3h%0HfDJkwF%LUMMA!GxxI;p61a+*zpq14(K^qgl=`0#eS^)3oYNwdq+|j<-ywZi8#{{#|WPsdhomj7ZXSyEewbwAM+qK?05xWD% zjXbcCu_lsN-Of;J+Uu$#$rt_maGFOPDWL0(7S-ZzJ;cH_<03!c00d6yyZ{@4`aemR zMl6EbBVKvO^qS%=K`bMSK;<=tiMf7~41$r*0xAcMTB`s1|N3 z1QVU>UbQG%>72?5G~(iF@UbeAH?O^PqBh}tO4`N>UWwx7MmeH(eiv*uWokmIZzA&8 z`5*!-(pts4<~XvIR-7QHq4y9TqLGLyCZ4#6%ZjSGvH8zQ){FVmzT zQH6WAiK1DNZ4_z3<`C7ZwxW@3McHjdL)(gm;3}QAqAcAoCg%cqvGFS~I~mUD3xFW5 z41tk`UFWi>ESjQsVQD>n6Qe9VQOC7k#SRr|u@kVa5{(h;t_Ay?PnTLjb#*bk5!fAc zn1|i({F}F}Y!Y_aPy8QXcaNxtU^gFZbJ~^!u(KBvndC8NskEwoA#IcsPM|ApLmiWm zF*Z5{M@@=w)a2qpn6iM@YFv8?&Z;`FsM9iNQ~60}xn%q!mxnVJ36?{^LkbIdmfo~# zDv12FZiDBnQ#MPR!JiZL5G-E?`t)mD8zqE>0}N5nTF&wQL?dtw2GQA8nI6 zC)%fv7S;+027?4*Zi)$Y1)#5ja3N$6C!(hy#YsAU%oju{jOh`i#WET>M5JmQ@fP}{15Z}>cm%~*<$9Uchs}DdK&Z^) z6rlzUr+2!)yJ?7i#0b$S5jFCiMu_Di!1$5Y2nhhch*-&={{e>1#Fv3)>GF~OxMwKw zOvTMxgX_PmW>-GIwsHS<+b#POi4lW;?ky-x?Cwr@nuyYy(-}p&ciVpS4>zbR1R$z6 zv)45;ERQT6$?0!oVYWOfhvE^bAB(9a{wOco75}ya4|_AKx?x15xa{hkOqJyJ~SELluic_jg2>|==WIFf%L#wt9N7+WhbPWefR@h(yD5u+P8 zw?YQ)WyVGJ1G7ue;M4Ks9%sh|_+Qv%ma>ms#uaWYQDAj9sg{(+yPEgL>3e@8o~1&Y z?Bp^=ilB^o2sFrgeO9l~~sOr?#%-@g{^ znQc4S*J)Lt)67K+NzhH{HE)*oilhUZGD$TTj33>rus>Ker)M|JTyv1KNtBI6wNJbn z2yxWCiSaF_UL(4@$}4?MOB?mw3O+{Z4ViP^)kKh#xtGv3@eMHQKX)MKjxRz?B+1Gq zvlMfFsVsB&i0T9H^n06vH$7N*xD=L1yGniND{8GSLbdNUNokC(ZbdN@0Qu66nI8Eo z8f#*Krp@+C5*A#3R!Mq)MJM+lm_e7rqgvyp^a$&=wU+^6MBdze@z=f6?$eT;}|MY7RJ9m2DET|n>9p28+D*nRj@RyrL9^jm7_F)Fy|z& z7VV`hqBjIb%|*cp=jtk9z{L}!Qy~!UQfDubvfeuBmj`f&zDXP=>j<{+Whqq3TL#E0 z%7A86lL2?qpIFW&oGpPl8E`T?6C%rB(O3qDR0f-f-6>Hp{}gk3u_@|AEd0dUEX(x24HPAC4)RbhByBs zq^ibCpsFpc*U~}yu2h<|E&zd0ggpuPO=3?(=eQY8;U0oc_4T_)FfG{-jS+2Q zw3Gwa4M#(vh7$37kT@d0ZP$CF>*f-OFOkbmc2(>r3&66?GAj3=ajC!T4C!7xR<^z; z4*)oGgHW_qA+x1dXsM>=bcg0BN!ex2xt`J#HM=$?*@qkWw6$jb63+Zeq3dx#0SRqn z&Gf!cd+le!c@e=;1OceYC2|?xYz&n|?<{8F%-dbGqErUVPF@1&E1G*%GZj=6!!qII$TY7GRKq=?N}%{<|Bbyt4>_ zl2@~xSF_O6*sc@KEyP|^5>=>letNcDEIH9PKd445*)C8v8+dn-ILp}Mq>d9|xR!{y(mK)X}hD|t!5D7ETwnv~2WxI*PW8i^TG0n|BRI7)xoId0!ZXz^M#^>bMKLSDG#B)1iavoh|DW@+RzvcB{Z%JCvvik zB@sji@mzZ(b=u>PlHEOT^8V;4F5f>S?>w*;9RL`VwTn^X40^`0mJzHs%gqLV5uI~y zP^~{!)k$ug#274A+n7DflT+kbp(4$5-77ih)5doy4QZD-j$Q`!7rQrY|s zHaaQ)63!{agmaN-PHzr&*+{M|^RP^Od~_<5kI%`RMd6i+gXD?V{~)k9;niO*nNpxhPQ~(;s@b4X|=2T4|=xB2fva>0Fn#SAlrWs;59f{}fuX zA?YZI>vRJ9tbDZmVIQUCX2`K@5-n$bEwub?kfr5yO3PCnrRBW~JzDlXFG$PXp(-0e z%L0K-XqmaF;H7lLJZh$om>~aodlDVW>&DUa#&cYn?(sBedTs5-(zHYAyl-!%=<_+7 zNYSBR2}K{?#!_^iQnVMOmJ&GrS&yQ1gj+;UrE?{0#YRxHo50qYbRK_Qke~yGZ5lyG zo$V5I6=><~|6~e5gW5jCYI_H&e&SwA%!>}+L}GsOr4aKp93W7OUaiD@0YoM-+pxvT zs``b5*+&|k?c|9oUeDQb+IaTM) zHvpM`5Zl=SHM#u}R7v`$DMMZ=j{-V@l17)+#lhddj2bj+2#|omt7NM5C>JzAX&n3hN`4>MV?1# z1M9poPUX_ig*Gh%ENz}u+T=q5*>NRyX<13@LUzLL8`|J09t0za2N6Kd0wCtXIPSp1 zrJc#~kuSoL&)C_zTLEP!#CU0vONRa)eGk@T~T%*jOx(xl_W znSUw5nsB~H?oCO82;#3u(u6G0nN32HPq(xrc}Yn!24X}ku6 zy&*Er^$SF9T0kn@sjT1C^ymaH8n}c-^Ung|^Si6?yowlolPEQOjZo^DEi9#$Dy0TM zs7RfOx=&0fwVVLQ#NO0|RQ+>y=z~T-9DhX?BOv9%j*R9*7C0AF0qeHsJDK=(Xg1vfM%orHhi;$hXE2)+iT5})tFp9pML-5bcdN_|gY^;E9jb6r19oHn= zzu86k^9$lM6=!JD#wh-j)xw{(?l#B|ls{v^H}WU)sK=k5PX&ntSkZLQ0jnD_F#Q4t z?CndEo8YJ9Q6kB<9}wL>Yi*lD_~? zAL(CcQdDMvxkTl%<$y%f+CuZah34-1#33FaD?xo-pZLo!-1aeJf7CBH_D?!?H#7Dx z%YtLq%3$u;i%)ThFmdC@{uyHu@5fWd?!7q%i;cJ*tR>znpAC*ZJUDi)H}-1Kek1Yz z!HoS#%GjIf*qfQLUsx3!yG{mk@qV?y#e1?l_Uv^I6M2!vgOKNmEZmC!Hk6lT;hC!U zu>ySEfG_CIh6@KUZzjn{e0fTW@kxNe?98TdrBtTIl1dAk_o6s&9;=khVaz0OCDo7* z$B4!zV^(FlyzM|q{AHFd=2#h-^Ohwa>4z6>?iZgpM4*U!O58n!I-frQ@l@QTaJm}; zey-qQ%>dTnZ6qN{4umnfAO>(= zKRf*fC@moCy6k8 zPy1CGQ!4l5?vKGE6cxQ?A6sdox6KuwOTy zh;s)&B+g`iOSa(a6H$S0k8r4jGp>`@Z_Hq`F3UHn zSSfr&n;i}h47MKzOP;N%>?$^j<#$&iYQFL*Frzp`m z!NQxQutIvT)Q7&J1bh+IlxrMJr(8>8fc6E7Dc9$r9X>;Ye^GcDCN1scdM%ieD%YaJ z4jSPDbqC0!6@L*!9B$MP@OZy{joD;;th=WaoGdP^Mk$1Xm0{yIoEEwwo79J*uny`GrR;p6OyqbBzn#;YKnW%9-s6?;cnMBQ3<{+n37b$u+f^=nI z0TubTXx_6xU2oM?yx;r5o)5Y@8hRE$A9#<=l-0=vrg%MURzRnV`=;FlKd`nLX&CD+ zYIc2_+_Bqe#ddv5_ewL0UZ2O`&D;5CQ^QI{|H<2alH1uF|LttQ&y(y$jwEA!S!)-& z;PP8q+JY8PVu6Ka9=@YZCmN<=`ob2NZPK=JF3Z%=mKraJwA>C z%beS80pDgXCqnL;2N;(H#eCmPy-0bASwWh{qacE4JhwRm5= zK(h!h+AnAU^rJ!>u5eMhvjz?*v|%qlQXRj&`J=(NMdBmH>i|L^cvl&}=!o~a1yaNGfpn`PL z^vhsVbDd1!BO_P~C`$7gy9SajApsD#S%H$`XfU&--s1Wq?EBZEYhLB$)LcXeUdZ&o zP4>9F2svcHyHDAZdlYk|ufIXRv4QtpzaRTTQ5GH|{x2FBSQ_1ud#BocpM_QCK*cxs z?5tZ4bn5_bNvYGtMOjBSqpm{VuDlL$brEuo(H&$Mx(G15fJ!afTW2Bv(cv9fyCY5b z!BS*OV*P)S$G`#0dS|>miZqLj*&cs8A5QGq?prvDFn0g_{b#~X39SQQgAL5U!gtSa zDwIM!>?sxr5zvHmpp|@dj>KYz5V*80@BHstvU86rOmlTMPVns*?40*@J4v|z0+JXU zO@M47Z1__hMhC6j%oz^+`Fc)^?^xSAnYc-m>igfd4C4M*l!7LF@t=+0Wk8BQKF?4r z7VfQAg2sA$_6!t>nZ|dVn*&s7NAJ7Sw66AApAcxBmZqm^51zgN4sa0kmGOB;K<7I1 zuUAB8mdaz`8a!SuQk}Ul4xM?RAfPkZ(9^)dpH?}N2RnvjHknOV8jR_8}K;?*1rs zdN)(3;r+;3tKaQ-i%*=b25%dIT{JZ0{7Avda*xAN@$u}Vor}<}RhalUws^bzT^-5i z<$oy4@;JScoMtJ|X;5@TmMQt>3wY@qos9E8q8ociJGn6hZQUqJG zG7?&g{u(L3(So(U&w(J|3ORDUN@Fy%7N;%rGU6rge-UW_iN1ne+PP8Am13qd)LglM zNfqWzKu)A+EfZEv=tiwBy5?vtzR_CYzcB_nUI@%1@~uV)F>;{M(0ZBFN0z+* zb)@B2oc!H+1*99jtw#}n>C+Mse^Tz+TXVmze+qAWHcT9k|0JB<0lqW?=13`s>y})? z;Xg|_)C8ge%;3H6x!1a0T=Q{6k8~t@4MI$`v&3xjq37t`Y)WiW6$wpH1E)7&%zT9X zwPELFxslbGizcBv)?b5qp!sE_acrL^0oVbap!g7XS|6afz)P`vxzQtruYsgK)^sm#(XGjJW~haZPs9+6>60}=1FjPYNkt@oP!?M=N=Aoo#EHK8w+YBfi z2=-xH0|hkJBeoDRx*YaNkGJPtvT?7OM~!S+911_;D(JT67b7&ljM5X%QtCG|7{Tlf zzdVK42@F_6U>XG&&gV0lu_CFh=dd;4Bjm#bQc)AVEy@Gb=T~SVfET;~<2<$l5F0gr zZjT8vhHO3gP6)98(ZnStd5i_HFn#o47FOL<-ia-ytO|5a}d=)?y^>B#40h=x@qc2FTlR;M(kZHG4T^ z1~*U46j=vQ&8x-oYQnk8HDM0LV{RPz<{r+!Pw0-DA=o#s3YP?{*YpU}RF?k_S#~8Y z33#0q%~N3D6im9M4s&7j7x*9>Ooe+7gq7+@(R%a&Qlby@m)l1n`tT${U(2xaX`~iL z#+LYX!Jt}#Q_!XdTWg~T^TwHYgFMW<&1P?Rmw`<6;YWk_thW1Yf*8$-7wu*)_=)wu zxt4R`fvcXvB=|mN_hMuIgTI}7kCH4KC!8X5&9_@twfI?;Y=^Cp0Sh_FWV(1kx=1)! zqUZ=evOxn zaMtUscMYA&h~HiSFEX>JA3z1T5)b-kNbN0*ZGkmhkNSItL@1ogwh)xj<7ELk2Ym+k zN01BfntO-=ba^0{$y=~P85zH}l{R%tXVp>rMcXf^?J8Ry)3=ZFjn;11|CzqN8ud$B zyCS856W`uqKTzsosb~2@dX*NpWE80$VEA)8Y1}-_qA|>HH#J=Z(WWj9NisA4W?sRtiQks5N9kGQR() zV6?y;6h|aT#-~AElJVD>9!BTNpuF%3G#X|dRv4*z=wnyfiIsgCl!Us>@OnwRRkwdM zPnA_SjRp1@>TUt3zY?o$+ybCA1H76if;GSG;kKCO0-54$=T)=Xku!L@HX`0qAMDB!QTs!N0eGb5kxmKDMlvRy;5%`laem`-WhaE(V( zmu8G!Iv`pTWSF0ywRhnv>HJ@-ZUC9MwYx;MV3>`5o* zeqP_j#bpW@<-{-br20T&N4eW+3$8F0{~k$atTI(t6l84Be{Y{lirv z-f67L%UIqQ&b*CR*g*C?LpczYf9O2#wTrYOMZE!^I7O<*T9$xrE(ZIMdIu~_If%?M zX6s6}|4Zw-SWOK^O}_j*GS?DZE7+?*PmG934(5raOS>viag?UoKLi7O(X0Y!>nd&i zBY+BaFiSh|Q$sKZphJEomwKhKu0*3NYVr8^c#+Wb5zO*-k!~cFS0~fs39tJ2c$7CY z9gmRmQU(u3qtg0b5nqe#)3xA?5DDTIr9ti0?P+Ck9sbKNZ4A|<$7l{kb6$LB6K1I$ zEsghrD*7#}zeJ|F8g3qr+n{?Iw`C?g;C(ON5p7CM*am0DEMCH?$}`!xRyUFQ)y0xX z_47qvR|=fpzQr@0w;0~O#q9PiNRMDf_l&?xLj+Gq80Np&DtZm+F4r+U)LfRvGShG2FYre!|^xd!0AfVf#QU7hy2vJkn0cjWruJnHbD!U z;YR^Mb8AN7c2Q2|0|*>}jcBPe;h>B&5|P#e5sZ**Dr6s|ZRmRNp`c%2F_pmw!zR76 z=jMmhbsUeU|CHj#GBX|V(F1B*kGeAGIj$Q_JL$$>x9;Sc&3!M?(|SCslHp)`Qk!S7 z5X=?V!LQeXs5Oy1++-c99v{i8N_7pT#Z?)ZW!Dn~*)b_5@;O9GdZGS~TFQJ$t)z}{ zAF1x%SkVgy+=}OC6zyDET%93{NOgPz%o_g-oVWItd`Wv|<7mNrC1Y>w-2}huLE?H0 zz826&L-Tp_RcJZ(!XSIRT#xhpID@-m?bzt~A+*%{1Rl%h6+lL2^sZi@N;nZv$jwCp zZ-hEuFN^0NI@f(qb7UZMmGLHcMc)wn`(J`;cUPE8I8hLsI78w%=${W9G@H>|Ycg;x zwn(#l(YN|XX#p(by^{;+e58$i7nZtS-cLAJm^YI*>sywN*%&i5VC9#=>h6<(^|JZa zJAbbdbo;+lf>vK50jnrZct-@R1@kd>l_GLErt|3u$6=!d)%se^dV#(%xKG%PYNhYq zJGi3wz=iPOe_kL_t^bPZkyHtWmol>?b5ukk+zTpUB~J-7Dc(|PcG8c876|JxsS%-i zlzfq^Bzol8+n)?4@CrGheM@qsA0;rtx-d0PQYhW`x5NHFQ=E?FaCV6cD zt(69znk!P^+1`bxXncBj(6InB3t?+>cl6z0(rw1>XM;9)$7XYx(Unzrl*tsmPWEIn zE#e|E{yX7{$zr=3BUJ5mabY@otwOIApm=$zwnyH2V8qL8*6Gkqw#ZwfmT&ZXV#oWOhkvkh^vDTQy-uJ6ntb_Do z&(~T!H0IomTlr!mmfWjSeGqy#^M|;ryyt=~5K)@hTJo`ITO1Yro(%p1G45@;p@av-=i}wIF=LMH37I(Q=?4wxx zagWi>bXeTOLLU}S4gwa#6blSa_Pfj)0Dx7FM{6mQ`NR`M<^#V3*XOxj118AkXeoKX z&?@qFZB2tEeulRo^3#pZ7kg2Rv5C_eqQS5NWK}rMaSRS9sfuj{{l1qs(+*z zf3uYFcjWlDtC<3!xmKNq<`2V)1ZlpX;cWAnpj3sAQudJOx;unAs{o`*{V@vN8+R#n zvba;uY;eCCKwxYf(q+a>c>0colP5aT&KvP&!Z~wm*HZsB1(y2c^I)m*bxU`hl>u28 zmZKh)11&ndXnzt;uZZ+zmbEB1>e&AakQs2JFob_*^+kML&Z{_^H)jTPP7eM|uJFCR zP9zM$9BvPfVmR^8$S%U#B=5EF8G*~b)U~@9=OJ7bt4<)}XmMlpw(;_{jOjAxOp^AJ z3Ik+9qc&J-C{Yt$6=2_$C@ynOiLw(itg`*;bpKGJ+@UJ*%_X#VhdNb;D%_VI9DO#K zVX9;phNw-dSRQ71s>)67y@tb~#L1^+e27vs&(J{3{>3!=W=ZZazITJdDX`xHs1UmD zgBQ>SdJ~5j4#KZGi^b7NOx+md#0C4d_nVJ{yukIyy^(jpn9@vLg{MCTy;7yF0MbZ) zu7#RYCn;($K=_jCR=qOZYdC|)LVBMQn75lHGyu?gK6jns56o7nESOgZHlWEwd!64! zaU(+v;d%@+VddQ;2x?`~Ik@F;-r0fe(9Dpde|M8>i&#Qz!s~AL>tJSpJ?fp0^*F{N zwBSdpcV|}*XAc={W25{fF!ZGGI6VCnen~0()9p&(*FCET0ZKU41E`^Hl>hjauEK^v zUq%e=qx{+HT1jBslR?NM3$x@=*;^iR!LJ`-$%L8%diXNa=dL1uiu1eSsGj-+B;S2a zUB*S#!=Xy}V^$x83p*rV#9K7DbGpbM(Cb|Mk(}>qZ1m_JNAe@yqK009%%w{P%{ox2 zUg2=5zKdbMW?n}xZ`JF(@ixqZs_bo-1;3vCw*Ib$wBUapKNC&w2C;>9oTNp#Hypp^ z>)B=df+je5&4&jUpy6)Kn9$9hT@)QmGIMVZ%{5@G=G#2D#SeZ7?;1f{K}`qW7iJ|{ zsfTxk1%@2gAiBZ_>aPDMsu(?ZTUeidO}4Oxu|N~+@gRO+?We6NWu!@H4)T1znk+`_ zWyvRC{7oxYt;9S0z$9+p#VrhsOoOn^MN#rdiRR3G)HEM~u6`y)a=k-T{zXSiF%1M4 zO2Trzv1b6+(I$iF#%}Kh0%3NU!i&>U3SQ)+G1!xEBKR!_>%jsXtPe5*Uu8|th{>Fs znI49b5qH=Rs2Tg_Bte4YR57p?wFW>2VM{o>z*0-H#~-yZcU^7F;kr9jS+B+uvFGD> zs26@%wKX(Pwe@3QY+{sZcKl-|Ju$7Sx{d{3X-ZH&C~qoy^2J+h#YIHefYsL_si&i) zbTP{_GUps8Zc7o6ozbBh{kj+W7{#fl+|5BsN-)^SzNgS%>4yX*?8E*6DajGqR_a6R zRYL1gO&|F=tp@Hw;d|)kdlZv1h4_t=U@S!zC)|Y~5Inq6Co5UxG5%Lq+Qg<`Aa*iJ zYdqEA_qk|;wM%EA8ebO!(M9uI zA2Quhko;3!sLP%a2sk2TR||e5J0QRBBO;H3*DTeGUF7PV5|b;qh(aAyqCAA0xQ04e zE93(q)TOposSK^c({J!!RT1hsS4C(7Iz+jd^FGU=t!OK9B96Q)( ztZ%_waFyP1!=(Prpg6Y%U`m{D_Qx;#`fm8U0_3!*KYk9Gha5*zk0OifW$L^zjz^^O zCH(7mguFyJ5h52e5}`Ui!co1+1%te#0akx}TD}(FA*xGm))#(nG5g5yzN8B&h5=Rn z{}Uda4nGG^*pO54P#f~2@~umSu^~nPY|qjKMqJt#Q;P@tV3fx>N|$i7Qoy$`3Avir zkX%c`F|CUkc*R*|!0~{TaogcD6cBU4PwC>xknfDbp+J#;pdGKQr!rbAa3I z;f-5Cect~+*a$4%KS%z6_b{z*TC2a6-SYX$#9y`mNvY^`K*g*3fQo0e2j@@)N74gA$qV166e;}-$m`am1}p+J z0~Y;g!`F$X8HuNPC=y6&56%&8JCeK7XeB zl;)wR7o|gzHSC?epMqkIXFh|ZAfDmFi)R#Ay+MQ2kBaD<WwN=9~$SLs+hxi zL8STtS(vU8AGwAB$mD?<_xf>o2GNH7I<826v@%Pm=+}XhVdpy1fujt-U*9SK|J?<6 zHwE~)r~QN>mm6j$_-5bh>SwLu*S>OLB4q!ZM$US}_^pbo+iNxwNW z`h47%WCSNg8q~|t(=_&|9zxdH8Vs+kqtEcivDk6VXV!K-F&^kAxE;IPc#q;B?1N1!uH^b9Y3+ z*&kk+QAR2_lL$_ZfP)bYop!<;ke81T5&&^y0|3(R-d35}(5O(AyU()74^PyPXOxoX zTs#yWnPkL9^fT}*?tnaRbpt%L@HjdUldeov)|%*GMZKYof%KS@B?*!^B7fGhdR$_=iQhWRgzpoE0e{ zxS-%0;%1DRyhvbj(Z7miZ(^8=Br_KkNy@)?F(F*kU6F{W~T2cG`md9sT2tJkSm zZ)e2Xq&~4Hs|$kX3!z(LfI+Dlt0aEh3<(3t;MXr$~WiJ|~q(L(%iWC`*(VYZ8yoW}YF%L`%{tO^5|jYRa|7 zK@Go^PN z2%i^I(UFA{O^;L#l3y~RO$F2YmesYmu}yMq`Ca_cHX|&Fw(pWZ5N%__dPediiACHG zVQulLh&+x5YE}>FV4$$sXHZrEl#zVWd)-|xdw^HO$w%I`8)IL$!X%Bm?J5QM=t4n7 zyY=7b&;IXPBRzmUwg(A{YgW=igQvDs@>6rAv=yb=BfMcAA`L8I;A4FtP;TU-+(;|C zeQg7}bsI~U1!=oHTuS4BRVW*0<(8Oq*D z2tqJUja5#Uo>aTN>j-~iZq6I_IzW>=S;zE?OjRRr=cHI=79m=^`^!*I;rH{X1pal& zKbbI4-n#7g@f}pk;!{8dFGL%;>sjY~a^3R>2!}V4MXOX=8&X&_Fb$Y${f}1|>j4UM zoVMG|fUz?Kdr6J<#@i*R5(9cW=H2Z=T=-~3KvO9L5jE0kKVB|T?q_&t zRQZ;g?M2t9+5Ykz3@J;-27R0x``uie0})#Qox`J>Odrjp*t`fcZ}L)moK8v0S7@7P zf+k7HWR}D#^$n4&v@?w_{QyXr^AMKEZsp0oN+w?o+zIFB(;$%h7?vdOQP4${mEzlj z#H9Ee*9ZONY9)B6SP9;EemjDH-wJ{UxOcqiD-%z@&t0Q^{dTqXwL9E<3iBR7UnUXf z|Ng_7&A9FsOJXjQZ~xWx#|IpZh$~Pz)2kfVu5yxB*?JTfz)uRLrawm_QiGs&_NnIv z@qZw-f6{1ApzJbJWOgP9sWRK5Xm>SeA3e@HMeq!vG4}0P^oO{L_by2P$0CqrWDA=J z>6(R!J8Ji~zn{Wyl*1{+p@#Jcp`gQ|#&POI$AiDk`=J7ru70*55V!aIiJYJCi%Z3I zLWW>wc;r}+M$ZMBjY|2cq``F_u=^p;HfFF!5NL`5Z2Z31LpNWK6{-kT}6t^(XJ#MsTAiEiP0a7*M)(x5xqzp7xloGPgKV-$i!>y zu|p?V*#)WT7;h7>7qd|Y7jm>YUYIH`q@L3)JP0v7hXx%=0BHI6sJN}DELk8qF%@-r zktJq=@GABPB*)XHnzRL17^8BzbJ+6`7yL+hQ2&?^000!4z$tR-t81$G6H-R&sqR+< zPNM5`V0=+an;Iu-UqFo01ucjQ)qf7SR{iI#v&H(a#zU?DDcvz_Y()1f)am^^Sy{>n zZ!LR%6LY-e+meOBP{zlfoA?DefzbUjyon=@*RuJL;`@2P!;4xQbcT=lwL~j?0o=cG zEBrnOq{Hv|_?>y(C$xPwqCw}Xjn9Lg80#SrPh*{YM7g2)ruHtat-&#shtN??mxf3P zTOmnur#!bJ1eW(b)SKMoMhJxA?#+iegJrNz@_NaQNie{`vI5<~ zwBwt0`nwwJ$Nx;e3LdYc7;g4-ElM~W@LQ7`3o!BmAJJii`0a{#y+b2nrMs7%646Q%_R(yH)l{8JRe<>uGf@~htbnl8WIM7RJZ@lfva zE)AnXZ@Nb-A6c4rVWRA`}?N?9vCYO{Z<_$g5AC;+Zj-j zE5RbAAk-+H6ly@RFRB3{YQ>YnG-RkJUB*Q~4SJwOxPrYvaT4X+8bKN0hBJk+t{IEy zbFAD*LD@u)vi)#f@3BNQH-AF3c=?17ZtegGiDyJihsY~|E60PMUtZkoO2EWXCbCz8 zKj76Ih8pLNLu}-}u{-kqjR>4`oG0=0%jiQ&)w8E7RT~O|GP?P?fQ)YM!LjJjj%9Qx zW91Yn6scFSdlVBY!g4O2epnt?SUv#fNwyo#2*Pr$4DRa7&EL4x+Oq>#Am-Bn3Ze>Z zL&bhxs7o!>m z#+iaO#*7X``U4$17{G~zv6BHO5pXLxB(4q}#l;&?;@G1^^yXfd2ty9O9k~v5Od{sBSDhiyR08WQ^Ux znQ6Tyn+4oKYO1+k1_<0&89^o4>gi``H# zb5Ze|YM{MXFrFFrLBS`n zpcAiBQ67XRENJqd)>^%(vfSrlmF2ozgMo?b7da4K3CI%8ao`{P?#ys$ny_(ytxTOa zZijCw5G?djuHy2<69^6OkSwmQXr&Dek8>!s9fXE;Ve7jghw?c98yZ4$Bs4slQ#IWM zjv`pL7d3SsJQ&YKCmS2CK}LYO{&&p`)Zn4!e6145xljo-5IGvMxI)^Z>)Njo8zwb2 zth2GYe80~GoB-^+CVu+lr*?R-n^+_^xZ zACcO5?OO653nDaPW-n%aa~~)EXAf-j>r#>V+$5N|P_@{!tQmtP z3dS0kMe{HMXVQUKa9XdEa!(FLl4gpv-D7I@l02^fUw$8Yy{d+Wf4=!uA-`&rtzC*H zLmGXbI4mmzmwnWI!f@{tCBSSvl)A%|0RNt<1lTGsg}P6E2?98O;PZs+-#sTu z@0r^7gKppZYTr@QcO7zK0p&W0ecy<_jW`0w+aJdF^nhdVJ{$jNqhZ{r%ByFHtt)d! zJ3vR<(Tq0D*g990zxo2B?GzYoyo^@U$!Kq56pnU@j&{5|+Ce(nlYdvbZOBQ%?MjYT z`#WQ`8WUsAmzf)W%iaGcR;UPO`}sLa>OR0p>;8dte-&$|$pNLsCx1;06_%us|(Nh3eWZDDLlWNq|D zxYwmfC)cjQJrWbH6odOFd~mA46;5%7gv6NvgZs!ss#M9jKp!Ud0RY$c0c&viYq0#P z`D=YX=%sY}>>nHY{D7y=`EO>?t$lAF(OSgsL9N|x?~T%0o6PmAg)a*J z=4n@RHzpx^ImN$&AULuY^>$Dzx;Ca^+gKH@p$@S`9xuP?QDhRM^Ad2$fPS|a2J-+)h;YMbpQ({ zDXlPKEzopxG7h;dOpcHoJaVb;2CAW*&t1R2MB#lHPd~gpxX&auVp{|6+s2zi+XUVf z0-y`;`=7Y*UINzrm$W<9sQv&v{jdyESYnfvc8g97^6}6hEJu5=e6eRou*_ap!>}f@ zxSR$ovam!RmHJ_$7{8GOr!W-{=FVAXW>)&=Am+~Tr(Y5DB%bzz<62l@z#Qmm&Vlfv zNu9Gbn7xlyrn(4RVNgbJUdH}#fR=C`{TIB%JDcGLvg2$U(~mMDK`y`a%T9PP{0TeO z&oUuFj!N`^R{G5+-K~gU`spX#h+*~_B3Z6o4W;W*A94UZm~nt;q!kJ0G0ex>dlH<= z)9(f9^l=!hH8t@mB-&uSf5bzb$vhSR*UwZI{^|vA+8jvSjGa)jx6lr1f|>!(!KIYl z2QW((^ItfYne5GO!4>xyn9A7G5Y{FC@OT=ZlLGm3nAj5XqwxgfH7?}U3VD`+e3lp1 zx{!a+2*|f29nE~xKz_lKoJ5r^3e<=}d;uA9{G|o>07RsWyDV*glm+G) z<-^Wg8SvV1ao}n$4rmcOV9^C`XGofu0ZbY>DqYJo1F4gR*K9McVLI@0CG0R)o(h#K`Uf-a-{#NFk3MnjTUi>bGq zG4X*l4S9&31QJ;{APhhpRbrY(Kq*xwuvQ1&av}SXC8+XfWrOq@Dt9BiQMH1WVyA@Q zE;)B)FP(gE=RPx%s6LIJv@uAUrmb9YxJfeaWA^1tQ=T<+I&gr7y@9 z)+)Ds+*@u@^rRlyJS+1+ua2AVbn|b_>;aYyb2T)EQxB5UHPuRJDY{3CYK4cD`p~a} zD}Jw`9!7XNg~2?6yzY*6sUh z^qssMG>VG&>KxxNP_$WhiVGDj9}>>cgVAaddW_z~mt0=IUyaVWaX%pL8)!IXBVVXi zPe6#s;Ikfz@-+~v%;)4}o8gNn`Vs}nReFlOtMpi~`zwwA;4T0|jpy-j%&}>QL4X6R z$gtJ;;guaBWle$#|7GNi6PbL8W^FB=kRkCZ#!TjmX>(Aa20o+cC;&tdVV+9#eOe*_ zJQ$0mfQymZ z`xm!K^PcJ6W!EMhpP}!X!Sq4b!ST2T2^z1%pV52d-!jq)oGQB)9ki3CFOLyvLY_2@ z<$Rt~NlYU*#cZC$l_6P^57kB5+sx0f;D9dUoS{Z5m5tcmBf$!Q?DeRSQ!(+mL&;;f zmU9*Yk)Y*7N}B?S50(Fpt~`_C)9bjbE$cQ=H*m-oT{RS1fSD_7YnB*GV+)b{G+UM4 zK7h70LkyrUVRb){B|+ON^{R;bqnfsLvf5UyNjMWxOxxN5ctLeKUuc8MIzE`iUkk&0 zfE)*ZL~}qk8dD+_rLv!*H$>6)`88lmUa6pgv}S{c20?ajEPLTCer4!^FwFnu!wyVm@8i>5mG7J4#WGdGBI>g1#?3urDM}XsLw>!~Su}6? z3D|lg+Y0Tjq(f+uI+%oa2R!cXs4SUpVha)(zZ2|++4RNp*){AWvUr9tP`8OhG$pMY zk1&-Y-;iIUg!_TlNz-&`m~aLnRZX2)jQ&cCvoeY}BVwYj=) zSD|zVk)CWo_7eanoZ>(K1W9E{r5eu$7@itDA-%Gzq?+#}(5KieUXyN?v#vav7;&dP zA;t%*%$NFVm`pb(ez``@`=SaEi}1=VEIi^1YRU7N)-W4$bh}g7?qm|#Udd%hIjq4` zK#bnp{Uzft-)ld`VzMr7mgi<8Nz7Tw{&-@RvL|N5>ai}+De|-v)MMR#xU!YWx;T+M z;7z!z8qqf$&iLL%$N-N{y$ISr;)iC$<8{O;Jaoj1b;Q<;z=#L6AMqTF z2+Cp!TE8MBL^+-GHmlOV3GJC$<1LnR?xb)b(+0BvoddnPG~jDQ5EHvbS9H9OKy?P( z=?ZSl1-DSa9cRFOf`h0_R|0JTa9_kw8O<}yXbI<;U)Rg#&O9 zc;C?Xn4u@(>Caxw)REsgUI{gNmz0rjf8C6132*}ziON37obwx=Hj^ikdMOG_X1@1! zv=s_eiW$iplwwA*-BeM8*CXaNA&<8jNQx?txKC_Gv=}8=@y2yykmMHD%A$44c(scV zYVUiG)6roaa!(L=3V&WT()m@eOY{7yt#%2oC7dxes@K<{lhWdO8AUq*)h1V|kBL&L zxPD*YByXg@lxss|dqGpQcpiYNHV2k;NA#U=A84SE+Ur8O3kYK^=DJ&CNwfgXAVazh z?FRsWpAG1^F}bIBWB?w`s|6f@P?$PeJcXAzf9al%l(ESuV`@j$ z{PvG`rR`A25`@y*Yymzsl1RNl54{p`8?p`Df`EYM3gV8mq9!&g8BCTZoD<<*5pQq{ zy7aILJv1MJUuXzr$0lsKR87R>bh_dQ4GNHEw9@vz{AyHjzXhJO0`|e)MB-`?_o_s* z&@+xyLE-uu~%-`8;P!fQ)lNG;`p2l zKLqC4MRT7VN-5l!94Tjc*3z+IRa(d!Jr6M{b4ohJ?G4a&zx ztUpEt{oHJoJQXF}o4x{BVe!5R=aBh+cGiQP&_?n}Br0dB{#dgtS9(=A+F8S z&?3%XucMaFgMbA%K3vM969?J)1yT?9jo0PNW@9T z-1-1wbXz;wjC2FQmoo1=inwnk2l#`Bs9+#x4z;@1=|Zv+&hyLN%=pP$VW-=ZTl%dt zc^d|AF|@a%%Wp*`K;rIKd>iC`LAF1xxoP6C$tUp-hL+0B@1V8fmuWx`9yF2Cktp>a zYYBrhSpJfoKIb2&Og#!uF!d`ecB?tbR;CUfr%Zjq=dVO{{=Ezs0S3-yn{i(vhoWiK zA-}33YvA8;Tt!T>@OLTJJMmT%G#MNz#xoC-PB;)y-5hhNiV1}U?tVbk)qU;vSo90j zQgi0J+Hw1%Uc_6(qIHy17BWWd1oD!L`JAPoM<+c3-s>fI6!il96IUO9he`56Y{ z<$zy~-(qnwJ8e{606giHM5_M0Jta7&0{DV+Y_CLco~Ju3q5Tq`puGcH1-9~D41oM= z+NJ9z0-`!V1loE27(3Pi8)tR>x|)*oc(u@S8gG!|1*U~r7^i|Yw`xr)mH7cC43Kb+ z{%(C+a$iQc=B_1e7^(&;WG1>7WVZma;CB^Xs{kqz&3hLu`QyvmvA{&zayXt4!xlI( z6+`6PXoaKw%9D==UK7w8nR# zeg>k82#pRwhlmK+{Sp8B)zv@zl^_g!Zic^S7=HQ#+mRf8Acn`3 zXe{R1!X>k#tNu2-DDDEbP>OWE%WX$)#ob!r%c(SkW23vO7K<#`;PpD(*oD1EMyCs} z1EFE5L;FtSiLdTB66=6r1A4y;2Q1G@1Xs7 z`?a^F$iF50VDO1_I~w5<*w))++Z?6a$g#?{h3t!SSHyRTRuqF-us!$&SC8ru z7|TWz_^bcTQb4r>3-K+;BvVr$gfy(X)!4DjIoDI8J?mR%z?z7sf3k3cLUsR<3f0-Z zSPoK>aHipaF~Hc?fPsL9ea1$xKh`&XwjLZF@!N2M2|}8nS1zz$+V*~OJB6-_I7l=E z3!ppx*3OkHX4xH;NhGrEeRLm(f?;gY>uxy)3k)^vSL&WB*kG0m3qYs6Z0Uh4#hc&V zNOh#NgG|!Tl>_0wt__l8iXq89DI}SzB)Rzr#W2Sw;6joKi-jaT1!ciXNfI(7dG%8v z$=3&_Cy532ieChsS^|6=|0cAU4tb|2rr^G3Io=?{Hoep{qxm3T!M13G?{3N)arUw+ z3%2qV3}6Aid&y;U8RzStNti~yd~iSbnz?=bzQzUzsP_UtIGeh$k=LW4LFEO{mWOIn zR0H4Pg+&3sB)Sn=m)&9=Pb0EI&_iab%qdfZ0@w_eH38d5p7pt(zmYS#Rk|_gD|)K6G{O;>?K2b|3C8n1b0%Q&~%tfhI z-lTNnyg<`DS6m`yW+I+2Gu_V8-eG}A@0!y@djG`Qn#(-TS_1QYIN`wg&9VUNnlSox zE(r;#q3GK46p&HGl{cvZ^CMr0XMs#oTw~8A?ZO;I{JEqeq{WbB^x+AVH`yMgOi=Eq zP(Ix2dB1%fDBs9nU2{p-!|50J9?PBd7?$V{r1WEjj=M^kk z_(YzfxWMM%dMp?CFGb_67c;_HHjUpGgl{@kXxy>0hsM1L;Wu`9mkmHJ87Qtnv}g>R z;7D-csL9<+6y&zT-K%X-sN6e2#__XEl|dQub6)-vfPBo1If5> zwUFp9rV_KU-{%?3VDo;Yh$|UQ!~zPjokEi42%;n?`CJgYL?O0+KM!I@5MuK%pTxJl z(10Nq^O>S7{RmC@k6JQm#IO_D~N_jhWp`Zy3t<+n@bfoCm!O#=19Wk z`9Bn26eE^|kgj3G5iAF(`Ja=yAl;L3(G>sr<^NK{O;H-NzbaJqSX`}L%LggGmWvY!z3qj>Fh01#r{+co2QH09> ze#dC2hR?x*H&LNsCBgyDPX^mfVfEw0!&%4ISK8p%-E#2)=bYX#qU0%cLA6AAjVJ$Y*waOs9{&5+pjy z8nbL@U4WPx?ai316lnnzX(f5sW;5swjX`DA$7OdOf)d7(`K?*P@oYT7@z51o$vO*} zf9WS2|8Ite%u6vdS3P(qWPZ|PNjXZ%N<_)7jsx(9iv(cJg$(cv8(PFY`~<^aBeK{M6oWPx+2g0uY~51cKp0nYV+qf{2u z?F!B#G;v;>!Y|%L#L*vl>N*SGWmXSB$4Hf)##j%8-H3-+uQLVy<9&s&UwWn? z*`TVj)1HKV1Z|Rhj5kTn)0-sUyi;VJw80xg{V$2fKF&=Yuq_z~pz09m)nedd1%_=w zj8=!b_{mY+^7}}7!$JOFLFsDo5p(o#oNN36zMBfV6=#kf3AlN|| zHAvxNpG~SA!k)w+ZWH79 zmdCVx;q+PSxEjuoI2gtBP&|7&s#7pP@oI^-GntrklNRCk?!YP3h?;?_%1vI@NEM4 zMg{nDqOr2~47e8o?gYSjlgd2%nsnP=s8j}*2Xq9T zptz1YciYAt^|-1S+opqAtMI8Za@~#s84Z4n0-q+}^K9@_1pI@&goUHL;4dcdv}cRK z48u--TRa~?Xb;FR_*nMxEMs)twar=E&WNviXK+lmZ&dFHgq~2n6SW^ET^sOu6kU7x z7N;}Sm9XkjbnSgOL{r!9A-kD;g zy*^m=A}jmTrL2212WgpnP8e5tqA+fBZ;wnCzX-;)@aW#r03TQPMksJectX|p$0W6= zzT?I2+IgK1zpXZ45Y6T zcU4Acf%f%HO4N!a5F>6?3glqsD=14^uptyJgitv&OkL!}3WL=Gk`bWoCd|9P8H8bC zd)p$15G2XPV?;Bnw50{B8$ms$@GX`TTf2h@Dezc#1$1>SqJ@6&`Z5^>Pg*2qx-<^CQ z*%h=y-NSJ{lA{HUu2N9p;NBhNi zEPI|zOK9K{{B3MwbnutL%wug`6ewrPUXG0k6vJGuRrP^b3yb88#Esrp1VA5&2^XidDAY zq|%Wi&Io*Ljhlz5XI?bGWtDkv(PTU_0^ULjLS9WeuFSMHzq6yhrn(S7aD0efAkMD2 zX$ZD-=YO8vV`$*3QpTcN1*QP@qa;<#1Pl!w)o4h+joGb-tb8YEqLO&fh z)`zL=wiM%F^(JQ+7*83-j)dd>Y_xg@C1B>b7w~b@)XC>Foxgbr)(z(|Q&t7f)k$;>O*YYDMcCQP>Lqv|F^k>pzOt zlynG1iILdQAojfp&B&UxKC(vwS{FW*fY!;}@4s!|m%L@rx<_q%T8F5xrgahuTbKSA zLF;`Zt;e3?q2T832`D)H$pjQ!zLI+Lw<$Q0n$gl)1A4@h)^ix9lGbG?Y<2h{f`YKs z8L;sYQ7}y=I9HiY=|>w*A|v4PtwsbKy&Yusg!p(y2tH5oogAaByPUS1p@Mr<2hZX5 z5EvWC;u`K}O@l+Ra}ZVBtV-`zAK%2BOOzo08(cZ$#H(@o*w~=gxae)oGTJiw=!|l? zgRaOws5=;^fBQxY!hJki@Ojq+THt>offl^Jyg{_!R%%9T0r4lE7Wf#Z(t=VHwhs6{ zLJRf{1^=K8b*3erb#wv>Hkp%vg10Se5DNCBW;6w#20h|Yuo1&l6r6y<)*35S(zXmsVKMzg{?N<{zDWzp_fMnA3ZVw1sl&wK*5|P4MM@=s2NScCqa*R6ijBAih|iF zY<;vPf`UACM{_DPY}<$P7w1#nx~bQLk4Qk%l1CHJwA1SiLemYU22F>36Q8CpQehq6 zW}vWj=hqQ5-8XuDJGQ5~D45(S0R?YB0t~U^{9?Q}Djc@hSM-0)nY1cnJzy3%`t@pm##-$dL$t zVo!*DinZ}56Jj!TQ>)faXcj?6H~Yp$AdT29;a?n@fInwHlz=~Pyw)K6$);vBf4&2? z<4O2g3{&xE2?|^7H%0J=J(nV{S|{4abMWUJ=b`RBha{lx*1`nT9sO#9Q1?J;MpHKc zTE(Mo^(zEZQTH+wwia)UpsrW?JD(d@`cK1Zn_K$54Qv@6w}Gdy{mI?HzR{4Mj`i^H zjSdNT*mZgW9?mLh5FU=CW;74q21nxYurtF{Je-Nb*7gk%JTyml{>hW*M2o}i`Fx(r z=W*R@*x9qs$8|qYI-o25OHV-el28J=cY3)&=)U14gYLsVk5Bg(sj$|a3>3ERTpvOA zeIvOCcqy2CPy!0xJS_nQzkIPlC^(av(URK&au`o?Z(x{8ayNl^R=>)Bh=Tnn)!3B5 z75KyS*ssGPHV`=ku+6nJ%OAp zfvhS|E)+5j`uny_z}`BaWuL)t45(9cD6U!Qjtvt?a|m(b8gfv0wW=r4F3R@w57!tg zUuk;o%blsj+etFefLia>rR-HHyB z;B0C}>p?3BUpxxl#4wc}RDpO_{}28l3eLyIX%_`oG*3Xm<8l*FaPE^0LcvkgjHcjw zphr9kc4wH1f={5Zwe!6Q3c8|SN)LeTNEwEZD?sV5NH}FLu^&-{7c^Z#7#9dz2h!L4 zvTRCSud7MnR7fZDlU_!81lv8;bh7=&zR`ze0N~>0_GSsVIp*#J+*~uaLAZH8HKVz? z3%rTP&Cv`~akB!2t?uteaC6^Ka9f6lg0D19K*5fa5>RmZ6AeN^KQ*H%_y*_^kAjCV zOhv&5P}r(2|A#2p#Y@3knk1m$#yb;GaM+v%p6WFZ~sFSTzQy>g3s@l zfPx23OhCc=W;F-}GpQL(!Ph{KcoaN{Y;;2dS=3i{FR&6xoM*xVAkh0oTS%NWir|_WdzsujsKs0h=+o&)bEJDqo!j{0t!xlq(La?r)D$--vB-0 zQScCksVMjW3R~4>5fn7mN-5JvPU4KQYwB#6qKN%mvd+powaR5*9opIVS@DJfL(OO&9ke1ok8Wd_ibvmrJ(h2IB#+#?J$THrx&!);V}jMG z$Jn2C?E2&ICTx93U(B%!sm_U|&l+3G=&(uCy;T2Wj4d*x$T+eRhZS9Gg*a7C= zPpLOQs?CDVEIIbGQGytewxi2W&rQuthHBSc@O7}NAvc>e15c_i^sCfbV^ld;P+jy{qXVv zz5NgvK<`$3)foHnbPvoKX&TBVo=BUt9)jU;06h#_7tuR9SKgdW8}O!QHcd+@^#qkR zd~fa`MqTfySS&|v>LQ+fE8zdjgliX+uGQyiEFrN{qjNsehezlu@2_)gk?N&XZcd=6 zvKpCt=JW8u9-WhBSbTKJhZ|v+F<)>JZSUyi)R4BKYd}5mbkU)nz)+PHeFlZC`qv|^sI3ce_Fmg%WIHi! zD>l%CW|i;LTv)3evCG)Y+vm3gUhSD1ZH|;h-OJnlfhZi=^S!(uh75iTTB7+89p;l% zSdaSJp|EvJX#_v^P3+d%OTk}$NkGA?Zb(4EPo^~p1*cInTB7Sgk9e`$6%12J^v5V{ z^;jH1L31wCdZHW5WSl)3H{^?-(4Il9tBJ9K0iexbbZRqP5YA1&VJo#s*(dQUWnt*6 zIyzjHgvB04Q3L*?;38}tbbvj#Y2&86LF1|v=PZDz_PUwdUc2zKk*Z6|K0=VnX|=&=(|+UCp$Qkd@k z6sLD3$Dk4P?yZOG zV)brR3^+3v*u6^(=jc>{lXG%RD%K8*-k+X(0_TAZ!mW~wm~aYWz$t%i5Bjs~E`c+8 zXH2?f#DFu#fkV2WBca6{1IdPbiENFpMkcFTlt?5%xmyLn!Chh!;+~<=3BLSQn-EG_ z?Vu?UR4umiDHMvXEc?fRI>dpRSe$kwOYe5Q8I$}^o)f)yn_sbeml#eqrcX#cmc0=Z zPQMs%Zr>9)t1c5bH&@4mv*zsR{b}RC*;{TM-8v?>E{y^8v64NY;wznjI;hxZdd%K! z9}>NHC+!KG#oL97M;#qg=7TZdy!W!*pS`7G^Hwpb*ggi-tiKO+Y0H>U=lY}5^vjp* zz9!ay$F>PgZ;Wk6`ow^9n*(QWY1%Ay?^c`@y?4nD)Wp4eUb%}ghsKnci(|l<_2M2- zG3h&@;>Or+>E|<}_vZu$&fZe7rg=;mxibdTH|Fm_?+!-N1?l&~Jai$t)juExobw$x zd)vE{WA|>3FFH-Xc!7GS=a16Nc^G@9X@4{uHI|gTfsCJ=nF$F#f5fSJx&r#5k4j4{ zgsm{nBl2xo5Ys%aJtKNY+HprXB-mT>jR)E>n09##s89TF4}_z8xd_MXwlP)g*TKV$!F_c=>+$YsMLZ3QrnJ8FNp1p4=Wy;ov|S z!)Phl+x|6;-M`|~qf@nNp54E_g}S6^OsXCe1M2mEAL>o9p)ME{y{|i-``dlZhz<4B z7*Oy2`%ph=5|hH^nbG^&?C(QGrf@8685slWL;tlYoY>NhK`sp`(Z+kwh3H!O{b|vA zcg&u^xxy!KuBwb_QK!U!v+~(J=+DkC1kU30n6~ZU7;r8z;fR%y)3fzl#*w(tTl*-| zQ@w_R%P=wOr>Pg%BOWv2Pb9jkLlA?s2r)wMC)M)~PA04K#$}<*xrt1aDF?hVbIMuH z-Yz5V$slhf<|-@Hyvy@^a|X_mbgtd`S-KJpYA_?d&rH;F5P zpqq{&^rDKIBA_K&nFzp2ZBEnIG1-+=(~1u5%&P{t{ps9JZiUY6tpC{CikghO=?8LP ztFeUipUS35*1Z#VAQXz0>G%gnI8@M21xLp$nESJC@o*~GD`vqt+jPNS*P&pGm<7ML z3w}Tazq&0Jj&rx`7N4Plug5HigI83q@1%l-F$@0Z7hP~975q0B^v=iBtp=0qNfFUr z<>OZ;VXZ}2xoZnGC8?#(;#JBxUc8D%@m{!WNm%pQXMkNZAy&7m?Sd~-!Id!!7UN0) zX>lqQoE5X+4|c&zso=Pn1y8{h3ew_iPtwwiH;Z20>LBn^d+nCk2 zlx+Hj+3v7)M=_QZ=rt~M#5u3+^kum#pTK*%MRw3-gGSpTo)KxfXbl|p2>Xr1Txw&xN0sCWq#QNdWn5(qLS-EU z1~u~s&SSf~I=2{rNkuhW(a})K*Rwng;9#poTpCB(w<83II6L_idIbB~jgmOS8wuZZ z#wmXs12Y!gV&YB;qA8a;#V(}$-3& z0Nyefe%lAlu>3RJuknj-2`=!>&7Jf_Qg*A{Npq9jx3CsMa7gM~iqvP+bif)lNKLEe zCjm!wZ1IKQq4mmRtPo=jh0q)w1&+={pcLiO(!vO?7E+&zu`kTz>iyWTYH$^0n5&1} z%3Ljs#?@^e^5>X&puHT{HKmYaEcP<@lEz>Z`6{*^d$mr zGU3Mh{5&NSSkr6f54GQp0Vmy^a6X>_o2A7kgicK4347an8{sKM?xuQKMaKqxMe78 z?f5TWw?4Bzr@TI=tUjl-9%o>qvG=h^3A9`cKOMjn!>=J;6UHv_NU>g=h4-OrEJFs^ zAcj(ID2lKrt8-bKyzxOO<+RAMkP<3v+MelzB2ax4yyb>W+p}fn?%1AXW~rXQ)QZ?T zXWAhO?L#R~&aiue;zVgn^@RR}RMpBeZ2iD%l5}4(Ij>rl*^jJ_B#U+>T+<6f=o}!P zVqM2bu|1|lB+{LECKhsS^gM?mC!+BR+nC)vm&KmBe~q zz_3J#$zUl+4KbGMtSrHDo^*{uHE!`>6tvG!Uw;>C5vuSO!!jF(@1I~C@F8qHbO_x# zQUW4?cy#j!o1$K5$Gnb%u60G41gp-d6j7bZ#;iJR@KaQ$KvX9e@2TZ)E0pR`Rs3#! zHgXhj6D@Fc$no2uD8yzi7Pu7(TqiuCsn^@!?iX-v6u8cx!UXYw@B(h`5CTUuG%phE zU(<{1ltSrIKgviPaU$4ie3|5YNyis!{3E1MqxI>K#CbnBUka<~y$2LPK}O_`(ZxJ` zGo-KFCVf-tFB^F-b3H5vm3@StG87Hs#`M5?dOJZ9u}X>X^*L4bIhFM}%(Oq~1Joa& zO5OcSvEC_iVT!svfoQZ0NJm5uL_?K~Gp~1I3KybN(*b0vvN0bpfTj&xU5~JTe_Vylg1{vXqY?oUfHH&-rJfMt zhhh#PP?uzzHFV`X@(iYEr&u38%)K6^d#!k1$5s=ywxNqv9DxSPhr)dtJCG^bqnohk zT6DQDV;~J6Ln+5hx6LWqNkbtN)RF4sc|@YXgC%%)hv}h|pC0g3m5B00G#ud&K6%KN zAYh#a0U|Jf7`FavM5FV$7>zk?ISb^h@`ze+^eWUX_ooPU*jG)W3nTLoE*H%{BIv_s zT*5nfrF`c&@`O)`wKVr6a_?BEAT5X5V&*3JXrQCSOyiUe)GgZRUr|6*B9DW+-DzkT zN?8=L34+(4rOygxZ3z_8Z5Z?;bx~GTL1CHtwK{hN{vy*32euM_av6U(x19dQKiqms z1^opWDd=R)!D3q&=$Skot)y>RA{hEE15G=8t7UN_!GK_8l?TcTd}}@A1Q>4QLmFC# zQhuIhcLJ}|L?px3*sbbTr%Jm&mFUk}yFZoEAHo`cN`I6YJ{WaL_!&?kb&vnFyLJqz zzbczVWxY3r=8%7?g5XeSmyx9W6SNEtqYe-8PwS}RQ17Z;G6YVeR>fgJDZ zAvkw}$}R+sQ3wp6@l2@Q+dxqIBmK0UVRnefivHW2X)n1a;z6>r@v)R3bd%R*_+3W7 zyUXtq{rhV9U7>K_#_A`MpT6%`$g{|fHgV}sh zFa#en_h*pm2<@|;A;RA&w78uJkA#<`CCv#|sQ1lvLik%fg#UA(5Z*hvaFWJh}xCZ+=xD~V*2Qf z`n#q2s(;UDLIjZLT=a83l^`5Lh3tQwf!Qi)hk1Q(iqq!3pdxA@ghTJ7kq=ZOc9(KS z;A-cF} zGipqonhR>y+%9H-v7XYOTobGJVL{?J4VU=KSm#S4_m|<$mui+0yUrA>1Bu5{#GS;V z%grxCQL96MOo%K}QYW+dip4j|fK+7qV77wlGy+Kh|oc(5-z6KyO+3UwJT4>=yvb}vuAD}L}G zQWzd2Aet?s&Y;#2^fF?|d?hnU+~I`Z#Spf}6Na!49%7r07k%8cL-etZveFDgc;hL= zd7E{&_p=3|9hg)IO1ff;EADe~j%;{W^tLjP6D@>=EfpG^L zAc(Z^K$Uk@S9G&CuGDLn=Emi8{D-co8-;wLxdgP?XJi)9qmguZ> zSq;xZgR~Bt1?rAS*Yk1lOM6S@m8BbbJcI{^qjBG04a#13(6F3VJY%$GR~x%(skB-} zFlxPo;q-3SQXJWVO=E^dh|0C$ zIBp^V*WzW1L|kcl+}n($k|FmbO4?K%4cYPoOdSeNXhxVsy=@ln-Mq9HydX&qH*EXT zeS>)=tCUex>3eM>dnm8i9<6C}=>X0prx+SC(~R6?Q3$WYRtXq7G?)SGXVTA?nZG>L z*2B(%(aZ4_i#S`GVa&LEBqlkR7ek?~4=zxXdaz1ZF*+Tk%Ag44e16(WwbJqV6_~6# znsy?oHU`1?^7=!us;>4R4F`qEieWNLUkI6E&6)zO54q;Vb?3;M0hBv|L^@VRJz4h` zcdTIaIy73YuwUn3pX$cGm%_LG*-2tl;1F}_nzE|gE~9d++Vq1jUOzNA5Jfa^=~4?+NYcDmE@1bf;Z=mqo4-YLdy zoAp@@vZt+-n$dgOx-FqmhZ}NkL(8PFiV`+F3;Ij$v8{^A6^LjDb5tRyqtn(73O%E=b+g?T z`TBH13i45fqIia_&$(JUepb=X_xUG>Dn(^rq@I0pq!j`|W`II2xHqp2!+3X}?o-7K zzgr@wBe^E-owI+QkU%1Dg8nwZ**aaQ87+~sK=gPLxpSl;kvF2S6`m9!k^4rcZ&u?Q zTc?NNR-?ESEKEef?%W%Xk>2y2zFW>SD0tD`@hP~N3hSM|$Dpv4e^&$r9jT3GV@clM zbu!*;^;n)xUaSc<2M-p8+C%2TgJBE#nZ{2n*3Xxi2a4E!{X~pNB=4nCat|$~JdS;k zxCgq?8TQIQ!x)KV`CB5GVFSUT~qSqDBz zVHM0w^Y>eseFDP@`bFO3ZBO3))7{vYj!}_L5G#42=@GGO}Oegv4-(i7?dLO0Oef*K2V!W_6BSd9_V+ z47c58W0)Aua~p^fG+_l#%xc~G0@bVo>9*&iLn<&Ki7vBw2wQcqUlF!Jee-jd#FE(B zjZU(1_tVM^?tCPT@Z7Mbb$~|H6u;6aTj?^Cp3d>{NRSRUcrF|aG6afOC8@G%191tP z9{l8Im7TPcHwmIgb_EbA?}I7yGKPax*+|?2N-prQk@lb-t%j|S$!vqp!C{07K67t# zoF0-R=nJteN6j)6DTjgIT;0^k(U^|1ED7|DbKV)5e~Ew)RRD-4HDs3ZN(N}Ji~om; zIm;AqA1(J|DE1=xsZ=5Ct7Jz*Fo5+O>M3VW0pz%5T!Hc*iTGh_uz;@g=lLq-8(v<| zRfxN&!nPYv&D~3da(Dw1Pt>47NoulkMIDx_)VpSa8x!e55ebykJf}aQ-ilXduac!c zCPAvFk>dnHdE;S=@+MU#&q9KE7@5%W2-#P(-G$Rk((x0o zRU-8#Q(z}C4ugoM7lM^tb>;-M;@bCAeU0{!~O$_QChf=CE2d}U;fFipbT~!D6`m(X6hvQlkozGtGc&SVVvu98!c!s zA_q`8I_askev^zhHI4C$MHw?5DoHfOdXBKjTjfV*nbLZ2O0?x8Q`(~zxI`A1k!VCs z=_8_@D3lA4Hz)N(d4to^awIPT!zvgf(4vx6kos>CY2M+VVL+u4=q(P&$7;tWtByVh zYa+09M~3w%>BzfVUbtTe37+I^V6a8G*SjjYl;mhm3L+&rXd{&5s52uH`X%y#?T7Wm zzqABFM1wI|=gJm$HTwv4hzJ%LFUf03Cv|$_s+}DLUq-{F5Eo0Ss9Jk1!3V|9z|(Mc z(iij~4OnoO`mG#Kr-RqB6gi$y(Bb0Z_Ee@bo6v)tMq^Dkfc(x>LpMSu%2Y$6TMPq7 ztOQwEpCK$vX5wKL*Azbf4wZ2C#vMA;Ilf!*pI9JuYf%^Ej!LaM^BXLvZdHXY`lr?* zZWQMiy0O7qTi4ujsmecr@=)Jeu@@=U)En7Q;3PZ@XTYmfH`(OSF%#8fX|wmpNnBWk zj#iN2TkWgIf(RKvt#r(xvlunqS1&dobJ#i)&}@20pB=3)g^i|v4tMp)VGsFpH)~)$ z6l=6WuyF(ffh*D?sQ(xttEnTL{)(R~@DqlBtN=EUSe@u)gdu>WQV18eF0r8ux`5zN z&mb&rCvYwb$wVf8K3CLMVF0L-D!#R5iJiy+H|`|!O>MTFAuVOX|04%(6iYMG;8h5_fd_B zs4>sXHY=p{0>6=ln2Q$$kzRHlWGNS&EKqnq_dbAxQU;8*mu=B3Su7;1%p-<@tEXk) z$!};0m)>L@iDyXm8k~DFjSk6Wp{8EF2RdQvtot|`z)BTu80dxIM%Ounz8JYTC;j|O zeO_5|z_%diTd>BWKg;l)95=VL>t2-a?<+$ZhLJp$GYsEV!bJQ3RmmFd>3Cwrb1WXR zM$4*zoC&-jq%NT4Zp?xga$UUm`j93`)icT6lk4aGcwy_Q+Fy{xU8>c(%JL>HNKU=?Lbw2sG0#d4m?;)tQ7vLpsF2y{q*$Z~H!BFG=b<@a zUkRE(8zudH3sUo%aC;@flu)~Td=gqEbB)`6B2vAnNi{NGk&4o%qLb=h2HRGG6qM@n z1fF2q8F&cW1`(7{@5P&hRDa|OskjFmI@!xGFQH>LH`^Z!3cf4Y3k3|p<>2c{rruk@ zEQKHqT1@Kh${^~(OPt>!3t{?&H`KCf0HjW^1(9AlXJ_U_vNPE^DYh` z3g#}#1K!9MB!$dw&c|+6KMh);U;KS4eGkBhsu=R|ACy{Fz^yoHS*y!mOXZWx{2(-{ z(KrkLkpp5vp8~HVdoF76wJPje3s8`%ihjPe!C(@aodFj5pX{s3^Q}#; z`2grtfk|~{%ze_eHFOk=!c$i$~Rn!oF3@)XQ{-87z zEaHYj`AKjmL+FTQ$N^=NhVrYZSg43TD3CdFxCt5_Fo#=tIOXz`+e*`D6GupK5CohzFTP{4vPq=7Qd! zy7kC@)QV{+pP=oLDnsjiB+Em1k!7aZ#j4!q`uflaVs(kgdB>aU>%%^pNJ$Ego@SJM z1tsk?`7`Oe)Wf&YDnHQQ!hj|O!gt!Jr^#7rR_<|V7}W(}4}&;ZZ>gB`wNy8xVx z8h=07k%$MMqJBRtzsvA@9{KC+QT&(b>FIGli> zobnyeknF8O`u$QntRg5dC!|wHVdnEi+?auXbfEfzN1GcE(&^7;LSXiZHQmJ_aHBZ~ zX#1}!R$fn?XL+x`3i5sl_gh;We2(A;jIV`uGilE5CE) zcO`z8gHe^)hx1=D`BFuVXG|h50uPkuD^IJT)DOr{4%tt&{m9NTV_Z&Z3tWU?AA(j^ zw=vosvNsrXp|-9WY+aYuk(CQ9tmTK8wm`_jub~09XF~%avXCZC*_h^Y#b8K`VG-3( zG4uEp_%oDJb(xNtr6`5Xs#1|aE94MOy$t7)1EPO)G38gn)+XB4s*0tQQwfmeXWE&q zUskD?x6&;X`emJZc~%iN{RgUeQJaRQ`2?M}*eitlQu|8Y%D)kxp5F|1GH)sUKPkH{ ze^s&Xe^ElsP6hHC<9m?*PZ4>3I(|;(N;ElS=Z@!Gh6c2d^@I>nNLP#F9Z1OVQ}pc> z!Z*}=%UTh#wd69OZ(&9S%_W5y5dB5*9CO>3)+8w?xK{lI1iAtNf8J7hWCDCaek1&q zyOjQ)l%497g!is#>JOLUJ=m7tlOHSnc`FgA6qOM#!|dMx3$)`8a9D%HK#JYl57`ur zO4FzS1vtqSuhZX4xW;ck`)?>q^LJYXy2DI1@~^P=gN51;p!x!oM(99)h!0+uX2H}u zz(3jts19*2;_iqWX^Ky}UN?V`+wlj@5^ac$f&5JFOOYQBI8W6S+8#l&;rcA>#gHIK zod~I#VXKfzh7J|a;Jp4fH-K3J79htI?`%V?X$g4LcSU0>xj(;}aAL5CKH1GnyueLi z65(qJ>d&v8fmD7j<7rFM6F6LhBTr`Rv z!8vTALh5DMn!&a ze=Ar-8I7J5dWn)#iQc&9D$nQ9{`V`3QF(vppJq1lew`xhMinZTVWKfa{2=h zGgyZy8cf()v4EP3)R1-9c~Cvqr1wMkVMx+Q<{p_eOd%-Kwke+)qnLs_9#8`m1-m85 zxI=Gy9Zq?e5^^S}Dvl;>jX$2eqTN`Koeh)9)w*LX*79){TOiFw4n*oy!n?YF+NOw5 zB)9ifurz8j9ZSMg7zDKkLES46wx*&zxaAr|`CCv|ZK@OCwz$_^i7spRr5)YLXidKa ztFFe~9?HM}crpC@kWujOp=+u*`X6+;J#Cl4lV&th#ZrOoHHWYigss<)a?`2)F${OqBSUn*sHPL`uz^tgmI;%yl8Wo92cp1&C5|# zW;}^Xeo(12kh8!;sNm=Y08#3&>{jAGM&6Io$h#wi&Kag$LE8s|6kKAXRZ|28nBhvw zk>x**o@x%WXS$3w*{+edRwH$ePi5({)Zs|#)E9}rDlRJM!~#>sxGApDjAI@vgVA`{ z`i3GiNNSc;DF=4=k48nJb=`RCn9KyufQWn#C8e@TgSnarTG)EAyV7E(FM+d7P!&SQu44k&uIu9u0X4c)?Jv__J{JzsFZTR;$xm9aSKV@6;x9g z%p{9HNHhS7K86)SvPgyi+7ko>ji`PbuOjk*=|gne>UIJ8K6w@OS5L28Z=N$eMjn&Dw~y&QT>f%Mzxg%k-}H6(*^M^)?IlQ3mEo(NMG;2~j38v-8cz5N{t zQ`XNyOESP@GdipZM;jW@6ati2wx2(bBi){aV%}1ENTk~Zf8{Qv|0iWr+^6fEZPxR| zy?v>XfR20FS%ldpL-HXW`UBH8oKL#UAO2PVoN3^B0Mx6{j$!VCO4cAI<`|0mC*nbN zP4|pKUupsIfKlQ=K8)CO?$~*x+|wvhbl1F(L7W~Hn5`K_QaJ{V+L#ohj?7k#xs1XX zio>br!8sg}JH-9rBcP&>IvA+}J$6me2@|z5_qqnjmw+)#Or>o9fC^@cCIStXFILlM zP}}_tBpZh!Hrx$d!kj@n2C*`{PA)CN0YyB+RyM=ng@thbv8XQsM}HYSxa$M_)B-mm z$OW}H5l|Ji|64!?i(J)NDi%FRrNUMd#)0AGaWly^52Eww)QFCQ(p6We{9Rn0f)Tog zPZi|($NEpu2d2f@iAEMP&znnV^(bK^aJ)w5kYK&3}rK^DwY&Y$>@aO%M zUi}|XQLp)@0i8NDQb%<}w&d^OXz(2_U$d5CCyt5&liufrTZuMhNMQOP#FD|R_d(8)UV98OptJ;swky zGG0ik3}k^n!%A`QT=CGruzB%N8;i{aK&@ETDA5&OwnQ7DNjSRF2n_zsN1X_=FAqq7 z>;ovEko^G!wETkXC>?;>>-U=eJt-WgEDaM^TK1wK7`-1nB_#==C0$&_)WE17k_h`u znQLOhp^ARWCk6LDqLWkaBG=hXpof`mAPt#4q0ym@5e_@Za{hdgmVQ}tNbAO_qgdcI z{=;u2_uDeSR$X4}Ly)&9d#R#o41Hhr`9{gxLPI>(aQX*0pj%d5ux)_OWALY*wbCAs zcyJTl`|&;1y5#f-x*&KrC$ED7anLW~a?_}y6tVU69%37>Ofo@StCK}T5=n-lLCYhJ zeZKZieNAQQ$tnQ^;Xq0n4=d?UGH>2nS$7Zd!Z?U;^t%uj*@{PdTaHLJPd(!Qw|djs z>5ar`!KY{XAzOa`nV(%szxlM2WZBL*DPP^ zxBARSfMYiixqq?+=Efph>Zu{SguP#z+gHb9#>kXw4L54*VGN1-xZI-~02U!pncAvC z664DiGV!8MBD8I;wyP+zgbqDnp8ib^6aTd2xRHdMU^ZCb#N7GC)b-p1 ze8F<2?sfcVpNq$`=h&MKoPxit3(}an;4gXr`w`s|1d6GA$INwUmaaW^&Q98u^x~# zQ;6j99d{0Lbit02^uBCc#vq(_bd$z!wKWn8>#+eZy}>ph%#ZeW;h}E>KMH?aBU*ZG zz71)sIPqj|MnYaQ6`5M6_6>%VL(Q z)A-ST$0ElLJ&wPv@}^!pMDEv#hhkep6)G+iLT8S^Uu2-5$wB#@h&rc|d`uIZg?=26Jv-lWJh6_ixbr7eYaO zYCExUuW$BVh}22ARkz3G9h0zu9K@|g3C&;acZnW*c2`xLm{Cp7ykCWhC^-5Jx9}of zl}u7V^_|_>|N8`2Ik7cx2dCfnBNoQ#!zm5a2a*WTz5(g~36_^M{gsunqXw4ssPh3b zp%o^%0mWAG`WPt_#VRg}P5d}I#Y+1opxC2mvmvm*AT%aBw1g>K5Dw{CU)&z9TF(Yk$gi3!(zl6 z8hG7&7~e(MbmWn9_Es1ZQiV{f9(Ffm%~W+`I3uO>gE#`+R`XLaC`RiVS}db>gJK0l z>-aa$4M9Xh-t*~JO);cfTp(QCrVWsPA3E_PCiFG2p&!^F(7k`I$47D0LpBTL>9n77Ncn2S3V(-(-p)kB@sGl5JBbjr$W_- z`9tW{=)!8*Zl0_;FAvunUNHR#Lj@0*&M zH;a(Z$_@Ia3fj|5v;i_Ropw^J_==7tl2E1?XyQNWz&!kkod>)~&L>$E6Z#7>30IT} zjqoF~D^Xpj_H!3XsvibOqvH71YBPo}xB6P{!8G7kjrDcRNKtaSY$Fj~ewT`%mR3Y@ z;mb%Y@VvWFl0k08(=hT&ek2&7-jColq15|A{N#xlLMLqP>Pt&$qf59c{2ul-n#GEp zYb!yDHQ)pcKkdC=5xZa($_jDR%`epNV3DzeT>B^Yhr$1N*p7O0XXUL-CRgzlM)5Z~ zP`u>>akJ*3WG*^iOr1Ylb^ezHoC(tjKP3}phxC3X-cxU1c6y&nzXwxqgDNQ+f06F# zUtl;=so-Ceu_dfrwt+yc^k*K42rFJc4>VOm46M*GN;Hwx<%JjVw_N@E2l)+=;ETk7 z1#9LJ&~rMT|9-|-*6l~I?o-P%Q5*kZ!wD;3&V}?lbx~$JtS%mjoGDgeQAP6_t?=i~XjyXU>f=GQ>f`YG!`W%8MrF`Qd5=7a5(4Pxm6$yIBksub} zoj!av^rux7mT$2r!RZ%3;zT0v@4ApzvFz3ILMpcAOPgjl9*;SnaF4yA&V#Z*&)A*C zEGv^VGTICsg*sOn zVNqqLvr+zV%vnaGPO_rTgOCx(&U!pVc4%t=sPpGbLY;LU>NL_FSJZiJV-)H%)`j9z z=Qh+;)M*Q`v2Hphf;wYicV?W)O6@i1BYQRw+R^t{+hd5W3fOm8j?rHljO!N&XfudYB6*46ld;HxB-_f9%vTM6wwVnN*;k4EQ~Do26RZ5yG50&xq;s}jqL{` ztqYy43!TYtggeKB9mJjR%kI#Q4*mgi-grTn)5~#9+|z3}fE#k41Hx1MiGMK^=w>IP zxFpkdMO^pH^)@FrgK5@)qfO3%ahY0V16l8zyrTswSx~Kj$;7Y-(TILauk-h!Do`s5Ggq>;$Haww!jY5EBrNm5n>iwGsZ8rVoDpW#~|BtCTZ zyBtL(GC)aRxk`BMI)h>5QjkzR(F5x}V5VU`iQqT}EKG&rlNZ)!5wHfBu;_pfZd>*1 ze4}5JV#9j>=V-7B$T7P5^{3EK`o;H5QJ)p8+YeU#3T0_J3A2JC2k$0NjENycc5f!NOaI{)7;vICxp3I~GD%b^!zsbhbC1+oh zSGQm4)FLP{67Tar7KMf!*f@VC_1NeS?@RR{L<~t#y*U!}BayA7^-+uf^by<&W{ky? z9EP9NCy^}s_{V!O2*Lp$ER;4f=NQfO;AYB*AqG0PM4(gC+#Xu>x@;UjX2L-A_szJCcH@*SL#i=ofjw2H86_W9C1omM zhMr2GA-E#pRZ<+co+S-vtGGy`b25IIo4Oou_y;Y(;?LB@nT^5z0B#|u_Ll-=lHgtL z-yg}OxP{rc0o}nqOtPo2hxLa*WR+HLB7~{QMVZMMn)P%wPhAorSs$(LQ@SprL#9cU zW-0eTs=1AtRz1o&Mqu*b%&s<-yo$G4rds`j6rtYMTWFE zb3c}QZ9Jtv=II(KR*Oy?=8Q7V&Vbh#L+(D(U6jETA`0Na-N#!YG)!llJik8~Kp`$5 zV>pGWAdlC0Dnok>Olg%65d%x%xlwQ72t2&Nf<^S!@7m6Ag@7#dhs+6{j3pi70KHY1`=9RLh`PE>-7cGUY!&~pDKO=Q<6`=FPi}L=XdZJE=Va`rNIm`w~ z86KfW+Tb$+oB15fld0jEWOAfijIJw$NU_?ZTgaWS1=rPz(B!Qg7RBrxC$#9^m8q_L zh?!$x3WnHeU)PW*kXSg}n9_=0fjPMM6@OnF@ZHZv@cR@Tgc?|xy4ZJrx0Qj4fR85g zOiE<-OkJFHzd!k7e`o+^B=Olz1TR-0Yu^fZWaNk|CPWRMIWE?|G37S28{aJ~xr{if(oqkKMCe-`VVu`Q+ zLX+Ton(kqfk0?f_!4Fg9fDbV~#jY3Hj-xyG^*N}5p(zM98=SFzImG2*iAUsd+$Jkf zacv-fXf*Z!kg`6a@^Aiu9q)_hP+5(|#TfEn7Y|<>h})of%Mm+c!eIeuU2}5k;v%Ub zTe?EnMq~dz$qpk*@ldUbhfk~Nj;jpih7|(wCGfYbjmAZJU9@jO1`B1 z2avyw_NjOuvdPTdgDGa*1xTArXTtZBg!Km2%e3fM+hQ(7cC4_jdx?=e_) z#9Px`+(+g@0bv3}+HS$-4!RZ-`dyPPEtu^-quT{49m#ldsK$s3QH7GTz9no$3><0b zKt?-2Ljl+Qp-<5)`W>nvZG0QZq7NIg`xd<`Og7D!?3(Mg z=;=HH?j4vd7X2$UX2ncy!{lanlC>q0$&{#Z%Vm~e( zCITD-^V?uj$e)bF{^nC9x|(WtcbysnIZ4yD>=P}8hSHn>Xwj@AG_CHg1`AvtVPq9ErUP29ut}&Igo`G z73J-)MkG1*F)ckPW(}zG4&+QRbq=H2TphFzA39*uZ{)iQrB@a7fN}T9+hY0|lJguw zQbu_)d?)17Ic8E{aIQX815pCJcN^5GL<4MOxCfz7Ew|4T0!yBvye}!SdO2mnSRFf2 z2r!L-DoTW{UQNl*&=d)gJXpk^#qV|^3I*h#hmbn&A#8o|4ZlTRFL0+2H$>9oW{p3z zkiI({8cvZoFVdR!aKl-|Hy@}Rwubkjzui3i5#Ohl;pk6IoUnEK7r)h4WB(AQ!$Vqa zNz4?ZT62rGRo!_KLbT(Iu+pLzp0IK)-YFwA_yDp$EVth2oPsvmG|6mxgO3MRApF$C zNT+Uiy~nWzwK522$9r5&pQ3q>n^i*%>^*M5LJ`8O-5L+9f_otE@hG0=cwo4gjdNy* z+4u}=-lq5Xb*0ODG{R3Wn#zcn4TKM7^Qm+%Du zmKuc|#7@NRs+P7UU~0W=^46~6K`hpyg;o6EL(EL@;xowJXrIBhCyLKF4@A<32;Kmn zK)i2(CwxYKJj7>QDa;@KkTCy`4xl)E#v8zvEJ6ucgtRg^iI>EDGjiI-vZ1axiflu6 z^EXf+sro*%n7uZzc0Dt)1ePaP8Hm$%vV9kiV$b&6w99!5$isS)U{N#r+y`}-iGB9o zfJ!#&NgR&aZ*P{j9HfTyscBqB%=&D6C$qkmdubmF@-|gtvo7OnRx8qenq5+7cd$+W z_Hnl9R0_j7w&`c%NU}iwpTsmpwyP=1VS`RY3l{M=G3X6o!9CloX}uyGd!UJeen<#n4;|8bWwr2 z1A&5sO@xgd$Gk*~4vMvZy$Ow&K=p!hJQD>-{BQq!LOQ1-tPyu2Xde4K9Zgi9#?|Dj zvwHUGXMoCbW^2e{zdE`QvNhzK-<`LhZucHQLLbN}lUrI?M7-1~e<<4KQ&ttWE6&@& z@|FXZkQ}t?Qtw;vom3@@7^J^o-iNBOs&p0Aqemc$s=P6aRfRt*RXIGJRAnRRr0LoB zFLa7kg@_g`;%}lVory33QBmh;oy{BhttdF`Lr|U7Eg}IUMeg0SQ}uPA5{) zNHCL77V#ZGFPRNE;pJHFqI|^}fb>cG^6qxEuywa;$i>?`@sic9CWRH#C_i8jPFnjT zImZu2W}nT~Z!L87exiXiW6Rl@D6LQN)~NiRNvQLLTes#M8L^^x)cfXUTD?_X?l}0b znWpCOOckYE(&ZMczV}n|52f8L&TK}@MXQ(Z2R*j#IuI=K%?D-5h;&`ZEE9jQl$AAK zd9)z*-|)nUQi?WY)I7ud&zssF4x_Q%z~^^Lw{hV^R><1g-i6PSKcnFD$0u%lCRaw{ zb50~aft(p$5&^zHguFuZKA44tKQ_DD9{B~yw==Z8zr>Bv1kS(kQ0O`jMs%;amqM>M zaVX@9lOm9kQ%d!mA#?98-0%l1Jpt17+sH(?W(jwZEm7lTXZ2y&7m@gMbMP_dammw} z2q6k#fnARbebBk=*S>Jq^|sD#?XuhzWaqSBtVgiHFCCC z=_a(r(^u4ted=!QGK-!g4F~88rshEo&DyIUo0W#+P z1I~fsr>F5WW9K!{7R;rm2E=zfeky*-TzUoR&6354ooS=Lw9*+ZQ!BrCTKQC3d8a^H zIpz%RXByW;E7@qJ5DPnWDTrD)3N@I3=5|2)0T_ZzINGL;g2z8x8MP+WgoE2FiR(OSF5)7p{j({RQewe|(k zlQl$o+NCZ+H~t_1veFl+8-&&v@*|`fu+e5J$z=dga}U!|B=G5wNZ@!pO*u}2m4zIi zb+1U^yg{}EmQefK7LXhx!|0mdh`SYpuW0fPK!70TLJ$iWjtJstIy%{2+BTz5J0Xi3 zUig|Vh$9+7++Il5;$~+N_JtEG_h>Sj#^fBApR9DC1iFmIF4~h3$ zN?$L{m%e5Uu=`p?ZT^Mm1c7rEH-+DAfnv>_3=yk15)i0d!#*fe1%2*0nL&)RL8J+_`JLvKOwC-#sr zdR%vjJC2)EUP(yXwf8WHb~cCu1;pbD#FsoHD2bZqP=_OFI|9LshqnDRBJpW^An;Rm z@)aT;+ez-ppC$H}NAbnl_Ser)QS+XOc(m7xDca5pa>qB~A+$YMI{x$&q3wth z+;aONOOPYCmjJ^Aay#*E22pyy2632x$W$Qm_H*R+C+ct{ZFj)+duV%uMkGFMm%MCK zFsmNKb7))aeCdxb)+4)2+Uoo*qHn2b7b-ckxRiAm%Yve#GJQ^Vp-eg9BoLIG@EY_Q zvTNC$?8*EUCK4g`r zF7mC!xv>R4Y^y<{2b(Is8|U;6`X(QJbq}pa=tbuvYYr6}pb^Y4qjgAL4gQDSO%N`t z@J~=7bd5gL#cdyvis3q7h-Zle&#z#LO>np;Jv#{7A=HRkwU->d36rp=rKX{!X_IJ6>q)aEI@uuhsAq(5N^QgGmWWzB? z@r$-(^k>%7^(UqQOtJF*&>~^ep)2H}GJ3W-x4HonG+sJXDVf-T_>JiB44#mQL3oJH z^%goD460(-%7r#t1flXi2eB8 zqRjpJuEa%U#3!96jtY_`O5qybyTY~3po1N*rQ-*OYdqCi{UkA)HiNS8(*bP|1>7h+ zqpbQ~e6kv?rbYjV?>S@WB~WUlP-@h7WzJA3D6-U23NS(G7&KrwqA?c+VX0FcYxn|S z?`t&$+mgFilVVMIyD_$ZD;i~hMp(b|Sw?r4db>LX@weUG916yhCF@?*a_*``J0K=W zQ*uSkBx;wtAE5oI=BKNyKUXmsS@AGS^Vyh(aV{FS=a1#qHfTVtK9*a|k!d2uEL1{BFcvBUG40J4*&P6=l0=2fS6}Bt z4%rK>C%r%v)|2~KPrkrI^kll|Nz=PTPcG~uwv($uPhR~W>j?lWVY@BcC1~j;*7VinJgO`K@VU6~5ItsnDfP7d~&R)6aE3NABDh@S97QCU31G zsSfbj&X|Uj=@&D#Y^YqBW6~6JD&hPKFc3jiaEm9Gf|B~X>(w`TqQ}fzk;1DdL zvN9Cs9l5+WSk(h-GlINZnR57&VM~&bG&K?xkljQNbh-qST{N4fhJ0;!os`Bs_7vfP zG@GV|L63ijzg;IW0~8ONWJfc;jp4?4ldE5{$Na8Ih8pk|(wfc?)KZf~s8@7_`MNM_ zr5*2Yr%CE|LGB)JVWxgp*I=X~?}R|r8))bvt=eYs>!X>HG#3EFU+4Hpc z7r9lP#1WOrt#360p(m@Yzs;?Im`jMxEgzg$3~rtI-rwNX;p7zc5~Q138@K%V_rx2D5pMCVoqn9vy9n)%M(;MQ}ob?dlonp<*3H3b$}=D`)!Q1$}?6s7h~PTrh3>a-89uA#u05QTkv2hU0`Z;$J=t1#uB3Z;ktA z5b&AxGxxZ@IvEJt=z%=>CI*;S=Eq7|oqI>3eR_})p~?9$gGyoA?t!0PLQccBdvAP5 z^E`B>DTggI;qpxKU-haT1sQ`1w1+4!E1k|P#uFVvo@6i!5ilLmp4Agi5GJcHo?Z31 zw*UWHTb*HIt*G2i>r=!B@`3#$zHYfu_eZBcBG`vfrhg&6VR z%jJWc{HX1Ojg>){)4yiwwY5V_8G;jCZn~c7@&rHH{{&hr80(7auTiP z@d7}^xxdzRs*9SxAA#U;xK{=RycUalGs?WoE5DAB+{usj*AtR`Ixv#G3CWR(kbIvG z_OOwRGDfQ<8Kck=GL{?#fwKgGiGn}}LSUF6umG>DHH#BaDd0lDEjM{$xu?uxSD9Ga0+BBx7F{EP+&T)2p7}Qu=u>{QZ$kuniDtY*1KWUR)^Url6>)5N z6rKAGuA5ZK)H#Cn81~)9QnyFHCw0?&Ooa8zU$Oe7MZx;VYZ>dq1?z0Ea@h}p^`&@a zOd6cmGlm9k#NSrkYZ$&N*RNm)DhhmC0oiD}E}Yqnf(Ck8YN6-_?uMh6u6R=P($m`-j#Uf{+hTxIf9_GEs*VK! zed+ID)|SAC%osiIVD!8xOy)n`bJOpK+P5&UxgFl{pT@?e6I$B$nyc=ds27E9;3DUu+$^O83%_2CR-kM*o}A)Dkt?AeHU^&Qi}$v8tzrTgBcsFE#j_@=mmV1Z-cuO7 zuoT&kS#e-A^1?viEZgBDCmoq^h&mYHmvOI>dgJXXjoxod$mil*Mfh88p<}z*Kmr0{`TH9rEI?IYaMjmsoB2V9b z4j#)!@zm_V+wr$m^kQR1rmY&e8ouP(a3=Ct`HCi|pSCu@NKdMxndK}iL0_3pta~Gx zNxy9$$oQt(KG8i`mVW2-raEoxGDe@?yOR5KG4<(R(x+$f%33j>-KN7i<#oWlH0GLc zLI&P2`D6}Q#|>MCvZ;GewoTl!_93la%fu!kY#m)oaS5!HSSOYntR~QPgb<;E5&OaL z*}ZXO3plnl;F9ZZ#J@%8c#Xv2oY_Y&9wOS2jbWBYBI;`c)EWW;l6g199O6dQPez1f z){oQ|qBv^_gs?7^R}B%vWbTKpB`zJ%=YG4&x7ow;Z4;MQCt(M2)<)P4wd8<+kFFSo z*kf7bt6y6!!s;3ZDvy+5ZuuyB z>L#$ zpo~Gk=7FZJQ`1OeDCBYu7JE*P(I_!VN5)^2{i-uZjyNOmvDNGWtZ;IM)#ze>-djCEt76Q_XSc@1u0Zlj>-Lwo<8~m_Fz%(# zo=|fO-O8N*dG_(Vnm@D~Y#bk;Msk6h!m1h#4IR~JNWYEQt$}Dd-5A@G8qzntJPqQ> zO)t@*He#qqbD@4rKw)dmdMvd%=_@2z|0vz>Mfyi{y07Ig2Hm^h0L?^nFPxTu?#VAT z5Zy~(H0a)aLwvdisj$8a>MxMoy0|ie?ohQ1G9jk$ies`MKD8?SunUoey^Px~HA928 zg^b<~>`e$`e5b7q*aQ@kbv$z{?|Zs-}1ac_lrJ@Pxr-CSnKpLC~W1g z{eMgMZXILMy?|0};eu=*wgDO1iRgaDeF^Bka9#t^{YGj?%lnt0Vmx_2jiD-ee-(wT zR-gR8rTer_vFM(L;M7I;tI`tF{r&s|bRYO!1JQlQe+|0-8&r%(_b?UK@_q^mTSaRk z=x(n(!VMU!r`B6lAQ6H<@laxoJ^Kn?2x{P}!dyBWee&47lc%ODCZe*{xXj45a9fRwdAh7dMd9PN0Ug)K=r%=Xl;{2t!p;`z8uo2fY_tYHd5?vWf$c)1YNH zx_l{XN0N-afF4PHAC}&>W_ohWs~=w@1zN+1Ri-KM&{ol1hIQz&2*^KDUN!n;kMB&q ztFv`;5Vx!5=cI^InEj)edACOHrk#J?z>Q5m+xd-O{GZa8g)zs47o6_Vm{)Q4S0ar$ z^sWRN6PnXN8gm9Uq%~&oJMlHBqi_iRS=-D<=P*nq%ga#M z>hN}iEbki%u4&<+;9Ts!j7!0m6BAHy(yRud;K|gCrr`6SN4!zR{tQ!5@Gca#*1h!) zQSi6s9tw^|{(f8vzB?fS1^drz5DM;i)S%$MSH-7bm-aRA`5;D=)ySzInn8=rtn zyJj>9mljbonoHeQ#OG3gVJa^D2?kjgEsx|<{FBcR0%OHgA7Qp;NmH8tL8uGFrxP%|4(y0%ME{_G*^~_WecXK+iF1wbrKUiun_rys}P;h$C zZMcAQ_FHspnIvIwqs}GdonyecW>4VUbfWZU!(%bwEWI##e|Ej;=DQl(*qIoVO&c{N zO+;gTo%nzLKkmK+zRof2J87FXwkBwaQG~Iy))b}GlB#gfjHrfMN-gcQ)*_*nl1dLb zjzcV=_Ka<68?mIKCZvm=SQ|5F>_PEFFwvS3qbA?~e_i+eZ0DS`yzlqE-|zF&Jm%Q)5zt?9V1ut#iM`XZhhTvpd^&?;`$}$)mgH|wZ?OB$^9Z20I`my|WNGv?f_RDKB z{4#=)AD)wW`#Z0ahR^s^*V;$2-)o^XC|f*fQ`d&Qpj|EBbn<&Q96a_g@WDZ3UEQ6X zmJZ!=lIui}!ptGcDRhvHDRv(61ddNZERE24s^6WW{7<(>1~0tdb~)4q0F=mfgdN1l z({Mj+{d{>!K9CjW%b7Z1;G>{ti`GUri;%3?3imO`y~6n`HUru)BH+^WXdu^pQ;dY3 zE^nj!ES2H=l0$2zeuYlABU;JDX7#V+v)bIg?%Wc`RvqqJz$Xs|M&g^oR@R~4gSfe(zX^)Jy`>kWr_ikfp=U2;>sO1+t7n)*CW>x&t-Q&G>)bGS* z7)sW0H_=?DHHn*LK>fJqT*hR!cnAN>ueAg0tzy_{>Q{qw+O#&2T7MtK`~kU?HZA5S zm!&8A-3xq}mqB!85zD_^MbQmyIXix-L@61zoc$T&GbmmWlr3e;*>3*k^2NNH$&P(~ zB6XJGs7lvJ?73}%_NJdB^!bpN9X~~}dLuI`ok`D!_^jVLd8G%ww9O6ilql8&-btZ_CQUBCzt?SPCmm z!995oy72tRJy39|S1@4S{_73_MlZ{`I_gn*Kz!3Q?%>8}!Zfb_hC0#ezw)F3dv%*4 zO*{O4ySXdxUiF$-3b~&Y{@KJfb3Vsz+ZZE!jdjZPy$A1(xc)u(3y!^}otT<2jW5u3n!aeBcwazemo{XFc2x6AlLgcC5sHZR|wH)JUU$3W$&Ui*7G z(%m|M^;=+H?}JC!Y2mFaY=1fb?~s00_}b(gv+d8_zTb~$_&)S{Ck=W)$e{7kw-+-@+b5^0w2k%3{8njOfDh9dAvI%1-eKHM z(;aIbEz2&AMR>&8YNEU1>5rsj^in5<@UcK-roEcs!My>C;S)ZCCh+8wJ=n-C6$4iv zKhcPyNReVm=j}msr*dnpq)6=2Pp(JS&+Y^&&su;x!@K#p)e8Y*rh#!}9j{--(GfSL z3Ms&)O>t@G!^=EaGM7c-njbgc6c9>`eV!UUmX`p_R}kOhByDU-=T&mF%7woM(`gny zzA`89%O;@>ZBfRG=N*@gs?i8DaSxC@pJmGeWv4HT9tLRH%c6%9Xy?Nr6pD*ExE-3eKtxTM893%tBNe?C#rY

eL9zRn0^^D{tF7;xG=efFZI!a~LvX<2>dSxTPTPWy1-E7DK!63IrLDyfWS|mfkg3dQc}lFoS$S!CjjgP~EUsnb(Z z{at>jfUULT?27LW$kAORB>;4h{T8Ld-{d*l)P&mo>k-U?A2Xlo#0zRAit>GPqe%$R z*nmfhJ=Bj)#r3la)r%*|4#*YGIS?GrDky1H6ty z<86N2@XYG4O-~jVqY-k)OPS7;Wzl8m1N1S8M^-1dXZi}oi%0WDhPipE$z!CO?xEAX z=!Zf0tjfSRa4p{9uR+FbO49l9MlqCGBCB<|e8dg)q-K$)5*ukvO-VYzZhhe@G7kQs}kowflV?ck- z`WsM?h8<7H@sXu7&M7C4l-f=0g;<&?ulCWCagu31x?wI7lv-DPLNxT|#6+WjQ&K$- z>O&%u&Ji87Mr4@3b!*3JgonNy{nA=hGb_MwjiHya^hG?YA2TKLF+EZh$K4V!{Qz?u zhecv_dWH)(OvK8oz|7%z*5C<8US5mmXgufPS&U~ro)J9f<5`Ah1D=q4j4R`1Q}ArT z=x91dajn3hT{-}?V z#15#bUc94db%&(L*YuL|^%`(2%Mcs2#z@-56XSLA4H7F@!uC6NA_QCzXC%M4z?53_ zS%2>>rR} zrI}`5@@$)8_TRU1gvJiO<3;FJPMgG`=}^tYs}@G z#WH8WJ>x5!;}AQbRl(SxlcU+VyZCV_ zHKbW#@r}Pw#Tq3AVLCIwXw-M@<>!MXtyr?^m}PY6&Lb$Yb<&kYRPt4wM@1K@m9(X;TY zs+oVYDmM4k_-4G+NJM(O21SyK&>jeyn8)h)CNGY>9}!zN_9e>V5i?e_@NxDsw77S_ zCVBbs%Sbkq3KOrb7+~NApf)+}E+=MO087UIbm04*-d>L2@`gf-C+Z z_AlU$gDefp zLMK(>{>ZZRM!=4W1_er-xsmvlLgmJAJn-!>Z>(Gj0BGNrjZA&R7)LUL$G+8~+7i>G z#QQF)!|wXNHyJ&L9K(Mu%cAqio47tG+j~l@MT*pD>6V*$n`RbkrVP`eihP45mqf9M zub>#69zHw4hSb&9`3ihZIG#7$sg_2o1tadkyjF4Uc*M1xr?PSkpK^Ygz$r&2Xi)Nw zK^>a`wC_I3NNNMSQ{BvmO6uA8Rn^SDDybTA;CqN#BP6L!tgey@+86OHDKvKGRNN97TFE#R7N-XJ>*t|?z#lkEv5u@)3}**g^75lLh!BvI&~ zr25m5ltiTfB~csmm#9S>=x&*?P-ewM5(N~9+XVo@Y_zV0lg?-~3{}CZEB(1m&1Y)N zlfHZB(OSCh{zh$ZiZ(c%4?9ecwkj>;fyOsGQ$Bq-Gng9D)GDSX>hz&5O#57ce2UruE$wi3}+8iXLy%4TdO<@<2k0R)_#l#8n& zkE{=h8jynUN zIJ_U&#KmO57RTynJA_thVg$?ER5UsieH+MLc0HOv(RfrcFj?qHMlNC=H%qP&Oo-6v z2h>r8_#6Lyze4x>GH=xWnq+#7;O-nWQ!5lqI-Q4SXN`}2(}}5+thMyvZ;ZlXQ771k z1(*)eK1ha6cnWGTl8RS1U#pw>z_|8);bc@2W6>Vw#q|N!AE`BJf~kjTY8G*hMB|VthhAMwa=t_~=HpKriT; zXDTc!9wPiMGUOV)TXt6G9#~$E3!6bmGT9aBq>@M(UpJhUJYO_ZdO_{i{G{`B2`DQ2 zh7#ML$H$lz&Vf1sk3J-%WLzNySYAqCagBxIBFkoy8<7e4!B%D(oIgI4MIS0AO&QWn zZp99yVLNapy5jh*GA-O-3P*Fic{VE}FB46Es0V_A(l+9=@UJ9%9h01Y8zR0}Z&=+z z?B^()C3sCbTVElu@Jxw9%`{Tz3mWwzJ$3W>ur4U+Yz}FOzkho=a0}x^g2p&gnisG;P#TFi{F&F-30I;EW}+s+ z86_!Oc{NiLQaj!#eTZuxU>*Ruw~@1$y)t{(+t>qey^Y=S*O9*+(g40IjH|rNl32GN zp`=sZ57@xAAr-c5nrtw4C(^GFDT(&53Tzx6K@Zqa`@Px@{l@6m_le`sl43};W}UPN zG3y+t8`wjA?@#t&Tny|ZUf;K>@>0R$m-2Cl#l>ASkOGA_|!! z6640ZTSJpN-{)A+l?ydn!t0I3xpJWZBz0qvfM|Y@HlwOVE~IvPxfqQKy^Tfkcewm5 zl)nY?SHOW%KXIZ>mrC;uMUBK9h)EI11ydmx+Y)I{ZO#;fDl;!2djZM>v|O1Q+$k!FaU8h$^V`-rn zf1rPCfkwL%F(O6DbVco`2u&M9KQoa~-CT_FSrupcuz8T8hSgw!CyyXD?boMZGuUFo zN`j5nHuFJcxn2EhHMCTfN;*GJLTGt2O@|3U1NQFoS>&M6Av5tUxDTG~Wq>i?J;~0R z5mQ|&F;18_Gee>e6n*=6QG1mFH+3M;0032>I(?Wgd`o+KBA+9OKl;QEz$UXA7>-XM zDV6w$LG4Q*iU}1(89rP&jQc{ZozD{W5x@r?OnnYpwGp!^7XX4bzMzE@$*q?*jAd8Z zlIgSr;T_Z4$O)a^M#jgzjg#bWnf#5&Us|9eVl79+-g+J`HESWRPRMfl;kYeSyBIx~ zqEu7d5I3x0PBT-pDozE8Q;g0h#)?=>7i6M*1jS;}bs`o*3GdsG-eb`vjRZavp@35_e<5Zbx01rD8OpM_gM;$5AxkeP(l$D)<5(dP60HGeEL%ZI}n%>H)-bOBy^)?c?VLGjwaLU zQHnjH>~;W&Qc@2~o)6qjgtJ4CB6ArA^{o;F35wwR3@!fQZwf84xm!jRpjK(2$Y5Ca zlhA^xL0VjYkkDcti^rpU1ZmN7t)CXuHRoTq8CtNk&_ZjQDME(UCiufx^;jst`6yT0 zHK?|0fU%cTghY@$X`BNeo3bBMUwBI}57SoM^$bG;lU*!Jd-ZpY)y)97>s;_H}HTgPK$&r$o zMcHxBNu;OZKCjM;UHKybt~@zZBgxqpUxQkSCE_#RVnyLD%1U8`+cIMs};W z(KGJ7jiZr}8qUGuYi#p896qS{Z+ex#bGHEH-h5v0qJLq-UFQQ#_2K>zMl-3n$3_e8 zbS^&J@0;b}el7bPTPyCKjmqS_1b5iptmpGQ+&2&5{@g!_`&S$&`fwl0@q(qheI4ItEEl5Ah87l1M0mQIT)6K5x-&rV6BfW8RzidzCR4gL=EkE9sp712K~I z9xO-eJ?8R;YsC9?UMoWqd6$Vy5>OF*p^k!pcgWR9SUS<7?266!<*m8%;CHxNXDq6B zE|u_!y5V-^K~#|5p>oUZ_>I{z%DT~lw~&M{XMV>dyZVoKZy&JGEW%eeXQ8JE#0L;K z#&;A;OqB5v*9Sna&>GzeM>44enkt?qu3H4ghzrk~d#gf|3bAN`Leoc9WQ^dL7oAH! zV{C(5Tz@_U(>R<`S6$T&K;q{NN$c1PUdi4$2Eg$lP}3_`j~C}-_M>`RZB^ST#@fG@ zS@hWe*>#an&^pS{Tjx9fK^&?D`GQXF;9eIDYCD@0bpl*goShvB3RtbORHmsew9boV ziGJ5r&UdBwSWhSZi0M|=7hyDGY;-BkZ~AgJ^K$mGIj%PR^u1ecvy{vaz09Ak#&=(h zKg4X2|9s&=bLesX-)x_SDL8DjsjSBo+`L#THUo^uEztPl!L8G(|kZ4|n9xrV|0Zi48?yW59tsLH4S=d`y z&`V8|aB|tFfGdM>0c7Uoq=_fHVFyv!N1HKSdn+HLz&^miaOg3Tj1#DeT?ML|oSTs2 zd~;QpqLV<;CjVI&k`^Q`4P2Zq&XjaYI$seaXci2P9=MW#vH8jC`u?*1SBkEe)FW#? z%nB$w8*3I}5_r~Y!yZEgga5P80@MdLCbRcu-gjI34PohhEz4*O@kAB+n48ka>Dou! zE{PL9CAAQlc@US!AvW^?yqH_VLZZVCva|mt?3B(fm@S>H_jR^(B=`Evo}c$z>Eq*x zyk0Sn4)bdHd03lC?RIHw(b!lIo7svnr+RJaQuB9f@Ae%mqupMB9y=Qg2i*OmoM%P& zSY+p{!yS|fXKoZ{M`Z`p`lD!ki8|R)r10sxnlqr$wZIBG3xRrbJW@{t| z!2_x%o%gQbwwsr`hHLqxGlVd3T!{;w1nri5QcK#H)W5GN$2o*FhCXl_UQa0Ttl%tk zrw008mD-&uox|k}x8NB06KHC@P4A4=y}G}f)A3a@9shwC$`UARZ7Y9@qZ2~R*;@z! z^)JCc-8QRx$59$R{0h9*>GOG@uy)!STH&dN5SP3_MD8HKI%nbgRjLx}8;%B`qP0+EJ{X zm9i9ct$iP_7}bOD_~&k|S&d{)2Vg~$f>6t<+i2AeRK-6Jt70Uy=)M&!s>r@jk(#Me zUcbG|;tA{q6&^~T&%Ft(jZ--L+Xm{-ok|-0jOp z2G1!c#FC(Q0{1heGN^+rV@ZC{G`QP<%e@r31X&n_R#q(+zq9MvUG0Ee+d$%t(e7zoi77F}mC z&~4e$VSXZJYdjf z0?~PXL}eY3U{2>Zr1R#&+d?Ffuqo%lc`}vy?XnWo5|ZD(gQ#AE=NLBs|YziYenrHCbVaB7qkT7w({UYHZU@O#`x%JB)- z7bl@YtZ^d$)|KI}pVVAk)D6T7Q5ai0IQ~Q<7pw%M&CX&&hc{{R&AdyZuA5k>(EOg< zHX9NWbvmsf(o}ykfO$I=#!bn}!gxo9bcs6RgG_l-IA?cqbIKUfbEYH5&ES5H2#yE) z2SXz(DB`Y#n*_rFgB<)855x30>~wWYK3n@@4+tksM)mBLtO}|XvcY!z5BC?}1m?-VCUD;orT4D@7T6w6UpQq$$jS6tT&VnRM|# zK_(j=jDh;Q-+@(hYhj%CVI@Y5+(3tG4?YcO zvS*l16rO!Yo|1u;4(wW&ckjfOL9PhMnHfs0{K@w2)?Y<`u%It~cLwN8;s?CUvlr6V zhex6{86#29AnEKjhjKy(ZV6a#WO4QGLcl8I6mnO``Y*7{ogd09K?#ykpB{uiSr-n* zL_xb4I*;Ph-7o?ch!-fu1Qklx+S0$U9bhturE_Z02H#96>xyd)Qe~*DANj*MMSSsX zU-A~5`CWhEOlP6x%%jSg+t*Xh{HIbBOT^$T5Ej({GU;qbWHA2$gyx|u^Kf-Tl_vuh z`d|AA^pP&~ClvaA270{@`i6uKNb%x=7<7nWNgYw|nw8S^7HAthx41iCBw3$qiQY?T zifcV_TZx@ee10d-MeHd>oPxXDDgQ_Ww*jDRS%OE*rQf6Bs!VUg4q0<2pVjb;&-3eJmAr! zb|$dtI!|a~u>nc)L6ROc(L>~K`wStb&&tkXcm_;sAqy#EPV$|DIGzc^Y*A`lLx}5B zr)54?O%Lg())b;3;yIluMutvD`<sXF8@>sf-o-*wh9gh%3ming00$&Ahoc(wan7 z;y_K;2kwkb*U}Uegr^i|Y^BC`6rTR`8n3GkHs+{?|AB4#Z13Dc=%Gw9HL!~}ZR1%} zbSmlW;}LyJaNoK3+@STG^UZwX7Hg)T#qO^u@~E3651IWAi)dU=>a3%s zOdx0zu$D|Q@94yVFib{{^5$ZV0$^m8)|gS9vGpwJL7$K}CH0`#d^1i4)r9JGn-Pb} zRS}mTPz=f0R=bARq;sw5+D-DLam6O((J9lO*4)1SI%p{~pAu4`xIo!hA)@J|^8_Yq zfV4)0N$1u}Nqybw=ZVDnS0hy>ROHKl2C?-ai=7Wjr%S3rgYtGd=#(1myC7PqM01o* zcgp4mrk?7P`VZtVrr5cC&VhV;`mo5$8Rq6lpAN(njadR!Yw-5_q_qI~{%k6VqVCt` ziX3O3vx555$Lx&pF!x?SpIqJ`Q#H>IWcOn$R!1HKafP7Exb`GLAnjKPwidMaR<`-q z)s6jK&C95SIp9j1{|Zo#@hsp7=XYXn4cLVAJn7snPl*B#`33-Dj2J659h?q(mv=jG4*$EHZ0yL$+X66P<^V$MYT{-l?RA$Uka)@epFY6OxiG^ zDwWv9v&)C)UTN`6Sed$l^45CJl^o2aK|t14rUw%MsK&PtvIIRZX;O3VR6bB@tnk#9G zfuQbdat~#e9)yE#I|N!d%iqHKPW4DEHC~B7um!%gog61J)hf4*S|f?mJwj0S4idNEKLUBX|%blxbcel*Ywiuaz?Q#-ea*Ks<6QRL0 zr#DOB5AHiLMeuX4X)sGSoC(aUmvVZ~9j8yX5oFjL@dg2zLKECSEktXyuYfh8lp4o1 zJm7}2SJFz-IYgdfRJZ(+MCX`ArYhSQ$Z%z&4FjTLz8q>R|4g_5k|UK#hgv@!E?Ypx z3LWYV9hQK-8U65N2$~ilG z$cc=FM=-ByWY|OC!)ffz$Y#Ll-pD3gXLppdqn>cy)_vp+_Q5~L_q*U3xo^&@Zvj-m z0r5HjJGaa^pCvh(&=1%9IL1{Bu4Abpv$s!4S*rFroHg9i~ z)8g)zb8QRk0Ox*^&i9!i|3DN2y)B*qv6H%(4oM8rRSSjX#;^TOrBwxd|8;`N;(VC@ z^t_in@5BewgQTmt9dmQDN*);F-r4B??e7h`a&HR0lCl`>%%rb$5|k_xB_YWXXRl`NjENm<2Q-erx9{qdr=Q|IxdbhJ@%;n zr#F)(oy*Q+l(0A0RjS3&IxgPM2L?C~FEo}5e^fkuMN0E=z)oZv^FS)1p5&E5#+t$o zQYOc-0LR%w?nbc7R6v3dcnVE4u+(Hp<9BG51N@kctV;aW#ndM?5BI3g?#`+_8_5l% z+woi%KwmvGI8de!N|z%PYLm)|Q5*bopvd)2%!*M1*ney)@WKCzXK(1$jBWf>793jg zyYc}<6n&iR>TSXMY|f1zpz91d&d|wr`Dd+MmT#S;<#OA}l(;^*d>T*&+CDDhM0C=5 z=$y4O^)Krw(_8?;caNz&QzmxDoTRJ%rWibhPYX_x2~WA~?7F+Z(3p9=G+DySH#E!g z5?R7a0L7Y(<|!{Lh6-991CIeVLUk#-jf98{F8D8a`0uWh+*JuEQXz1LCyVP1@j#3C z;w$5>73v`w!~m9)fkP|@AQ?IwzCLV;z8OJlE`wtO|Zbpo6{AXVSTm-BIE*4Mjym zuS0Uz>n>!aOC}6Qg4P)@Jb-NQFtn7hc85LH1{a~AXASa&9;6Z&ec}c#?Sl11p=M2I z80GhzGrjU^(+yLK$XapY5_3{>(cckb><+vgK}X&V*HTWZXSZin;z}VFpb0@C5%tRa ze9n&{ln^r+C4J}KdK=4k`SClfx* zlv8U6g#&F`$9#8b0~B8FZ2z#YPlZ8wN9{Pzfm6Vt1BUOdfaX#m$h=r-8+e0%Br2jZ z5!|HnH)$Wxs%Q6PRjem~;<$QK=8%Hwx2~~Reun;bQ!*b*iQ48PrLP(oYKG#xdadDx zS?qiqpXM<_o9owv6(}3-M!@2zUI}i0m6nnYuJ;VJ$oqKH;~20z4`{JW@So)BeL(MW z*%Huqd8YDVxLGz0!-NbPe&ICEGLUaNXHDEQl{I;OdKq5YFN;M$vL=QSGW{DX4eX3; zm-S_2V|5o2{UX!`B8yujDc*Le7w`AzJ4B4}2ksJ-cZLW_W3ggPp+AW&duceJI5pTt z!jUUjhC4Kr81?-9hZA|0yo3CC*ZLwzH`%j>D*}Vj|KxGoafU1G59@mhNZ9rrYoqX6ZGS5eevPq0!Y^Gf1IUsJ2xfS}AbL9~C@UZlq2W5^M%ys@s7-xPyBXCXNS4je*? z>&*J?`01>gAROSdL)vk3)sKGbU@oVIp)cyo@8$g(zjqCLy>`F1&=dp5deA{|O5Esw zm)|4GuHVa23LDrm3K0gqX>p)gNz|BPDSq#fwfeoN0hD5oQe&7#07J2W#WdFMS#Z<7Fjur73CFsX7RhvKKx2f)N#*XVv~N{vzul) zsyQ4jdE=gOnwMeR^T=Ho669MZ_BHN#;19oQ+*1a?01I9P$2}(t7|J~P)Q5zMME*@Y zj~TanqqV&hxUlihC(|EdI$lQJ9RSL?HDT2KtSy1E-<;++?WN#>f81LL4)lm*#bi81 zLK-OxhTd~XOo3=(pHS5Mt;zS)nxGwk?f@b1&mBRepDtM(S@iY6JRtQJ(2TBYmwVia8fKbg7;A$(%#EkJ8men2iUGWTewlNj z>6|pJ!jW_ywu#jxtp%OMj31HjGfX+oGe`M_ghUw*Rgh}imj1XD|H!4vcIhq}KNpRInFI0O-8BV& zQG)w+Dz=y3C^18VQk7SYRO*QEn39f)(01v{-)S8h3cx|#-K1_wPuJX9GY(5jrwjaa zg5VhaHF|4Sd_;1N^GX^o>5i6s^|bMeQ8vYM8^oq*9!-}XKuDo5j#{Z6pc^qPGgZ_ zUh!*^jf2_r^NNZ$TLw*BDop|8CWc(VWxn5N%SZsyiH@Bi9i#G~l&q`|dXSDp*1Ot~ zj8ZZ&fG_aD5}LSKCO?=Z?l4=7B#jlr33Nio3Icy~%`;<#U6++Cr(Nk*p%uWF-bfiP z$3hoHU6O{>VhB;LI3=A+@usoae3O6m1A<~Vpkdx4um~oN&R1$-rYZoonJtCZUbZ>J zu6n_k1zBOO4n)_)wSrtLDJB6sh@tBkJ%~fvFB)geM~@9rx58Ws^cpb?&5wjyDHHi~ z2ODVBB|QaQ&!iPmBgiAf`c?Prapf+U^zSYZI$F0aNO}|cyBV-ui#&*h0nwDuPeioa z;(IP;GJr3(ZF(^vL+x@+XM;44=${Z`kNdGJ^l7zc;5%HQ3C(c|j&N9>>9&0DpHTj4 zEl<;I)4xJ`*SV&!3#0=D0Yq2Tyuu4vxHya<2MDIHzr_R#ZyG{-77{ZN#qFSuF>w5h zUxG3;zvTpeI*55ZV!kN1MzR$saBMvylXf+VZsZ|gUw9!S>lzi9?kW&Uz zV7v^b$T$>%dBD08IouAtg&rs|?t|iiV53o}oz~^$3#q8IF0JW@Ray|agx1xdu#!$< zZS`tVk&B=1XS9z$$kk)l31yn8QH?u+l_oc1VL_2{9pzu92N|&XiYt z1huqH`ivmKy>J01UYx&cbi=?X*sAp*;*~FhLF$sxH)p+sEMVq7!xRLSlFlkn461KAR7?#(=UYHU{G(ipVLORf#OTkMlytWJR9s)XyqoPl zI56LV?m(HbR+~5XC;l`-|KitDyj!7inSfx#Q*uv$>odGfMluB>0ehv+XT(hqAIq1@ z)H03hF_Y|WP10Ieg3!QRn%AhGBVf$s_)Ag;0i+)uJ;0!&i=&TJXy^o+L`go<<`WlY zf}$nuoog5t7&<-if%&Z;Y|52%nlc1(8NwawX+l1Bdv}`czr)A2SZFZ3`RnFmw^1L9 ze$x3Gy$$);83yeCO&|LerX_!kkA05i)A-o?kiO17_CgjeM%O#QL2yrPdj=m{!op!6 zTZBZ9^}F;Km&1NOzLwu=pXNCt~%8Gt{1FB zJu_|LT2j()OE*RbTusfT!w_1dwLDzX<|B%|l`2 zihJwn7SC6&$)yx8n>9zka;Z76ihZ57Hh(Rv*yVH39EYgsR#@ z!`?`bEpe_u=goTATlneh%Jk}`T*WrQLa_}5{E?4;xom_Tdga}qQ#&SJ(Dd{RFVIqI zYPHiZI9nx$(lKL-s4cV-(<&=5*b#@Dlru%&5^N`(bEF6iM4W2}rLB1jX6GN@J2Ss` zW^Qj0C+=|=l}4%%@kv`&#rlY^+p@c^l?zitI=|IkKAk5eU|j$-G|%fB9CTwJO(yh= zZF+-6VtvK^rXLRqEE80Zz~ykS@`|`cKlP6+^zHgZ`n%{QHeX-X z(Ob$uz@QaFHoPF)XR!*zVg=@DXn)-?SNSd0ADDRoF?nL7VZ;z6D|h3?g|rEk2Me#E zBVT+>6=2W1jotWDr%5RVdh9t%67)4ARZQqwg3Z=kClg=iB%Dm%jJkti+d#sH{2nSdPsjUq1>msVua&PGFvU(SVY(OUgN)wRR3!#?g7djA1}@o zCoVclm&}PI=qdTJ+7KzApSPvc&)IvpBCLaUFtAVkoQ2lipui0*Pz!gmOIAwEV9-8T zb74?mSX3Do{TrlN!7;&1^o8ckOoqkYIwA%M|F^p)53FEfwn>E(=s z|CUv=8f`Jds@afT>E|Fv2pGvBZ`Ex0L0C1*0iEgY67m#we}oU1H!)?j zQZhg*E3mdPoh5;5HZo^jMy> zZBSf%1rbKm+eiVEpLfH{I_B?yeZof)TTlz7L8O3VPm~c90{Oi$^bThNrsQqd4{xjKtC4*E>P zP}0^pj4>VhSdE5ozd`hR?G*bQid*RBE|7YG{{9NwEG-ndM{xf_AIJ&K!2>ZkCBw^{ z4sNF6ygR3)&ymXX*kBtXgRv96uwc3KA1#V-zNa8y2Ehdq1Rp8HMl-owmX48L-9{3h zzLp4^mdV#575tJO)9eEm2^-cW9$p9x-Ow-JuYeo=IddF9QpYDDUR51z#8%~$c=+ml zLh-O~C#C2SS*dPk9Lb~-D$4i3tArdh zj45foa(_{aw9eM}=tMarPWW_(uI>gT7ET)<7wpqtJ86BnT9w<5r7Kx4fsF0d3nZ%z?;S?R=jc8HpY{0h26@Xplkdn-UA) zJD4d$X)xk6p;d}84**lLA3lj>4;k~dkozPdcdETMH+uXag!Y3Zfw@InLJD^{V*(7d zV!w4Pe5_0ZxFdKQ$*;o*>wH`%Vn^h_=~vV|CK0IF1RmIP0%+Ik4~>|tQA)7B-|AId zfJ^Chu+;B=^h(*$ifkICy)-nH%}o|xb5A>4g=?XEfpJYbHMjqQ4?Hbp3WnnR%t2>F zHh_Y6y^(EOBkQ%vGNatO3UT(GE23A4RsMhm46cRZXTYIY`8NOvM2ZXI_{nXri4F5L ziMTPV2#+3OFclc^w~xkvYDcj~3INHbSjw5|`S<-|$rbCtP5Wzb1MnJyQX*&W?z?40 z62%c0$0Dkl-*W1t9qeDydFDW1VwV}rcz=-{IuWyS5aK7&;iCbuo5$2MHP z0sC_HAK>O7!{pqFV53_e-y{n&L+4EmU z0R1_M1ae+AB8;hAPo&P^?Q_PH9knf83FkzGWNoP=Th22eO0srL8quBXZ7y;ozvmBgdGyjdej5NkXTx;8_=N`sOfSB`C+hpA@;l^71}Zmh=I;f(weBLIgi~K8 z_O7D7_`1-yQ*RjpkaGN&|3AMR)Z}SxvHbu1k-X`(`du`VE z(s-MXYBG46jRgT6Nm&Vrnii~t96yR%RDyoSCn3kNIPIIu$4RlEgfvw_J3TL!(NXF7rA%7XRjI9gfD4!LmlU66}z%pNCzE|yLtJ}jeT;Tw#`<{ zJ%5|0twWo~XKHiDls41(yfWLaUurtJ&4(r9N zY8Ea@u#u^2d!04JK=jEMFT945&Ntth>JAY(R!!Q$#0_J4&^YB5GBc{41sySwSvU?h zC64n-_&?^rcrovO@kPb*7<$?R@I~1}#TQ+MBxj2c5HHR)5wPvo4kI&J3}SpOnHI}73e$pG&q!w=;w;GDhKO`B$lpp1SE_q9%3NZxmKdD5M7@^C&s^e4EwM?U zL`Ldd`E?rVYy|FRjUzoCyh8QWYxU7L4w_0i^L(j$loc`x2^$WY4+B30jc6o!7;J0K*mv zHKv0zjIcktTP)__d-xc7^nI|HlYR#-B@T=r$@%IXSj=rr+W~cN097&);LJV8oJx?h8;LlLXq{J(bxZ{O2y|-X7A+p|$s-d#`EtW+2JQW%mv-jR(5-7W$mA zdk^oLIZ8ffJu6eLmjoP{=eQlill1c($19pO@))`S(ahRXxUd*W&S|*M*SYIULnAZK zaRhcQ2Ie{3_MDk48urT1RKqJD=K}G0k`-@Q2;mRD7@ugxCnZK^-T!xMZmiwB}gBOtW5AY`g5-I0QPrB*Nbq} zBJU*tJloB+2=3zp7>+ylw55BvmTgArm4M~^-pz3%(tQaib2cBScI&q8c>F+hq4 z;V9cs8C$X>pVr5gn~6Fq=~T!6O|AV<(+ z-CRql(fEX|C4HDuxwdrA!dw^DQGn(A^ttW6OR3W?Pfw{OZqbD}x?y@akU*Ywb3962 zdRYpT)p;A2{NP;S7G8*xKL*T8RRD9Yn?qd6yI1Gsml(Pq1%`OsD`ece3edWp-Q7C8 ztjs{WfY7#abBGl8>8%1hNBMZT2akLloi4D$g1NK&Gee%%g*Y~7z;6QZ)}%cmr_`1> z53?YrYjMATJAxm?jYAUMn{^o;#C!iz^{pJf1n#x@V1R$omt8~&97A`dBO{h0JS;hZ zsa-thDi2G&-*SnQl@80(R;IzS0(@oEk%HwY7fb6Iihyc+x>3)~pBmz|EgbBk_0E;x z%`E1STK@6Sd!GZ3bmO7++4xeSonL{ITvJV>C6g_|8OS^OyB^D@onm(eT3nokc`hzT z02k4w)g1;?S3SR;m7+}<`}wG?-6kI*SMq;58~vae2wlbZ8&fBlO3a6Yk?infkb4 zsE0(A; z?O^|J$!kEbGt~>^p)V;sF>Qa?2Mm0~i-rU&O*+#yK?G=iUya|H+I`kn=WqUUejNP2 zL$nCs<1gp`9jentk8LILSL6j~6sp%(9`6gbv?%ob-qrW}fDFGYYz4Dk<^LUm9cb5I&i^}9 z=V=YrtVdVtXZqV$USHDISKj}SB!0d@W=X7jLM8D>ugq_i#K#fQxm*fSwwP<|M;v8J>;sP17hHN4e7vsZ2 z81E9o_=psYFF7)d@sn$8ipBUo*)K=DY7}F8egs%Aci!Mid0MQ;1h5X+sD78Ep}*0( zNqywyzU7MvLt5lU5lPVAcsO`F{`P36SlBqx3rG=n=8|9g{=#)W^cDV(@7rGN`pPoC zSG(^{72mOa-^ZC^a3BUMu)Kmtvxw6cdDE-h}u9F!0`x`jD zHfl5U3KN!zWC>-kBIE--$m2PpoBC;PE`gV&Tt9#`TcEKApFljOT2B(DAGnSk6L2 zkxw5UkkxseXs6ryO&gprhmKsm=?*#Om%iFM4i3T)_DzHF>O0lr~?6)zUD2! z(H8U3-yP4#H`KYGgOfC7&#e1Byjt>i07{q}5nlSCyVv>M>TWbKwHsF``DSfqL5XWH z@T*EuhmsmA;tdsGGY70y+#p<171y^K*?}!YoIoWow^$}i?gllX6BYoifvz7sq{Zs( z`;+?K0A~-@$RG2T%w1iN?M(Mw%+xq z*YyB0fbp1;yRihOYE!u{N;Hg5Y&4@)N^(B`pnMU$ zjlVx3Lg`5_WgmF}Wx*X3Jrq=T?)x63uU>lFm&sykS#=6&`nOL86&!?qKOLqY9 z=zgjebLl=q-@|l22g#s&iKXA8S}X(IHCO14@%=Q9?1!UT*MohKebpQx`*2WMEz@pF z_Va6$?C<{Ik^K;oQkb1|<`JJh$iCI%mnNEWSkeWfn1U7f5rQDD&UW3s%z)10m=lP8aLx%2?@Aze;mwK7D4Q zd}$<6+F$@mD^#3BS(#*OY<4sRucrJHT-x>t&I?x_V`?@`fP4AVwd!7G;R*LrgNHKl zaAo47_!N8dhoq5W}g&Qa^8&7;+BFl7rQ}E z5V?H?Ig$0T$LZ~VhNW6%m|t zNjE0Fcu`iCtv3RsB%EN0^OzEgcF3d7!J}&{3kq}^1lYlBWNKmTo|Q~SMmD8LQr>q_ zJM3#%JdcCVzb707z!tVQr7B#f0Q8_LF<@g@)Wr1u>;7O75ePW$TgLgcB^$%L$HHw3`{Rx*j}) z+yV;Zo(BNIY_zV0am$ZnlH4|Bk)(L!Uf~4DePla!H=Bq(Z|>bxV2`T1F_T9H>P!@( zM+GKF5+zlPh+z@BuU6AK4^NoZ=kZX}dV<=5qv1Dc6I=f1M((rFBWqo&n78{~12l~9 zEa1(BUi(k1pe(=!sj{NzbDOU2-ERpr&_9^)ZcE-=hzNUDtK}4=6nL3%OhznPPYe=u`hWncKFy|l+cNml5kwYv$?!E+ zHwor9o?y2k@kU9DOPVDcI&!w0HqgfLdMB>FP?76kEu`FhJ{o|`-E3s8Vn1JVXG`%m zq-b$LdpJZgKsm|M7;_^$REKakBIRU*D^+Gk zZ=6ntOkb1ESGQZS&BDG5ACk-7VxK}tRzv8PWo4sSi_%@luQdH9@Bc6vpg`F>yaFL_ z?!y!wFZm=SLwLrBu;kqmP{~jaS3%O*!#nYWm3RRU?IEsnW)DZq)*g;es|juobKD+o zjqNEuRNCGaRG^zN!3J5{ouu>2o{Icl(vq8ejz~UDi#3#wo(qtf_%Fm^cO1FuFiXh+8jdiE{HGq92fQH zP_&MAAm&;Q8B<7i5;FjehK>4yu~8?dR?y=qqQ;1hF>yXdEJfeU-pzFLjjM#&|H4C= zU8UVT;BxKepFqA;v*&iR!0qNpM1yf@Sn#KWF-fKk9nXD}+Gr*T0c@5#0lS5q-2Z-HQyw?HJ=Fz8+24Hd|HvOV^G zT*6$RdkPz&yyzRsUfb$C)Q*|1*sj(9aSWj97)tX=)H$Hq6Fj9pp9RYVeSQWHWibg0 zeLmq*WpS3WxX{>JKaC?4__WaaY+Vf@DA7)Y56Wv7PR*zP%@9L4A-3h|J zMq%&Z!oF8w_cyT5^1*)hW{ynVIQaNCSBa^9l@zFMo({fcxzStYiGqqlWgjE#PE75P%izbJVrDbF5pNM$9BXbBkc};Pq#x=gqBCi1Fr<)@q9#}T z195@L0Cg5&^-adDqS1KlMl>cHG*)w`8=5l__5_ z$@q=qrz~{CBEs<#jiWmzyn3n`KZ(hV`%P{hvTQw$p9lx!kiM!>e(5`;#G?7kh}9L~ zA>$_jg`Q3VfM7OS*TPBXA;~0jZOR-;@y1WLf6xu*@S&xFC3`ei@X!ZZSt9|sn$uX_ z@L=Xhh8nSGkzzQSk3^lk8DF9uITOVgcU>v!Us7)junBx?kQ={;h$O}#?BS1y%ts^U zfdK>jVui2kLb84YLYY+}3Yx0lS>JdS55W?hM!z$qZqlh3Bm*ut_}$00vAGmwu%VO^ zN!%TJ*JtE=rLBHqDvF4qr4O>aL@#sP#cHCihc|(VYQ#fL6tx*%X7z4M9TPt;-+xlxZBK9GF0aR8aV!AonnH&J_JPjbNeJL{;%T6~2Xsz~Td&r&` z3tKggs>U#U2vKtOeLrLv%o=j>+UMyWgt50X>F8NUgx>{~dAiT&DL^3OFm|E5`4%T% zQTjatKf`W*y+S0QgTGt!(ce2X;};*rT}iMfi`v51l1tXJqE zb@UO7Mwo#mBgx0AE_@^;Shc!N%#fFPoMtMQRJSxV0XUx>h@lwO=W5z2H@xr_c$9EV z2D&~HUP{9Y_GcktYfwifS09o13@*aNaH^jBy+X2;R{?D$fT+MIY?^lQNIE;Bjn2sw z8-rVb1~o~cf#Q^OHp(%UyNqO*)69o!xyRt8s+oV)a@$JnywRYAQ-uB*$4P_`vz9xb zZ^>u@EB}`*_Y^>}h|qG^50;-99gy=EjQr=OXSFn)X|yDh}F%) zLoBy|0)y@a00@OI8?EbG(&>^+T5g+?loZc$fAkJ5_W^(^G_bM~oi2Fj1Fd|WE23AW zNYn%~x8cr~m>EUZ&0}Vwu2vpVtsz1%0mUeKXJO<5j6_lsb-n@@5so$X8b~DSiUp24 zv+>wjH1Nb%3_O3hRq%!BS1GL~ls1zZp(zeZrP}yw_(dGs9PW6=-di>E-2{qG--07| z;jyo^f-g&HT6(3d^zhKr)?(>HGXU4kR9ij_PuTJ~71oyPC~VYD=c+B5nB~rK5PfUQ zt@Z4GtsVP*MmhGnRG1FQ`=*2~`Uf;RGK3&>f1LTU>a8?ntci;4*Dni`B_p8eM-2*K z@L)#JXJrE2A4pr95&+#j&<%PuFx~QK-zY}q2;)Tf=FTe+HftE1W4%*}RO zb?xqpasToMM8PJWwXohkiMl7Nemg*qoT|Tv+?K9Z&iSTR>`ODxGQ%az#KZ3rbV;uT zYR??w2|ivzD~K;U1X3qT>g+g{{;rQCcvoyCN<<0R44bi#zK+Wzf0tn`3GZp#p(SiJYli$zea|4#Yem5$xet(mnAIhiGXTB_n z0)AmAzrp0^nEJ(`{92Qbt_XhN_Gg;>K^fXFGx@nDKiqzi$zLx+`}rn+{S5WHfiL^F zL5BKmCVxYdk5~Qz{jW^L8%FS7FH-lB~`n6Z)sp`11bhy>>-F2YTJU&cy!)u0r6QDrxV1^xu~ zNy^+p`8SB(%N>UBC!eoo|I_ot?C*?M4dDkt2oa$c{ZY;SFK6J@97wWjL)}DUlR2p? z?*o>5>)A`IpoKNi@W5suni*`NA%KxfJ>|L@oDV41A28MK?)@5z7v1|Mwg`cpD(#?` zjd=pJYnK`SQBvb~9yK}a4NOX+yw=ouevxZZfSzdo@6dd0=Px93u!UWKqa>k)Y+nnY z5sa>cpgX3v@Oev03mlHrnw?>^r*0pbeJy;&{>T~G8h?IMKP(i|3|_vVU{k%s_y-U%g;IA$Ru&BS>mo(BVAqCq$YIW9QVgldkLmy zL>+CQ1B~kfBrT(GVLe&gVqI%6Gpd>K)FfKz%E9`szb4I`0z3} zJ5&18t(iT1n8{}|gjVQBpcql!TTz~(C@VqTGv&RVBy~sPJryRlZC14k+HXn0<5=ZwOvQ@w9eU zSFQn5i)n7z+l&o8Smc$F2Hi9*%c*CpW!W501eAy2p_XNeT9$WDSIhDNDXEhK#MK6r z^+LR)^Yj&%&)b=E!%CQ>vo|VqK89>2wwPicoQA~DWri{sZp?bsmEGW8tPH!a?!Mqh zurfa)TZQ;=NTX%=!i9V5nW&} zT8`873gS5L3Vaw-Y)Nv@$iki%N|LvGNv!g_Gt>3rh2PwZIl*3BLh!$)7pq#`UPv6u z-P7|ay0PZz0=khx9&4Kxi=K=hev2a8sO=tGDa<`_BG5N;>wOGvgsud8B<5~QP2vl; z&dDB2DfhxRoPX6VmpeX1w<)azJ!f9@A=RY@GW>891L%5$j`MBRt_D$-SV>LZa{?e1 zy@JToSEygDr(dnXpE_pn$!<{_HlCr{aOrf>hA;3?ZD2eJKihh$YD3BCc$GV_qU@`6 zwXi@KQC^Cj(}TrWz;9T)AU)I_KnC5oRK@nYLZF5o$kB))uqCyf42|-hyN5K6xW$xI ziH+_8Qb6T4KG57IVtr&2Et;2RmfQoX#D!P3dVDkp4v$ejZ!E4;&B_|fF$iw?T{vKOjK5{r>iLm9gR}aR1i-jacr5SQ~3mm3L~qhBS4Zfn1TtD zU~p^~2VX81Ev%SkweUtI?ja{DaUa13(TG`}9C`@@+da3mRa%QS@h&}OS^(gAh0uEP+zYSxTF0zYJr12VlnaJ~@b`#^sLURIwcp zyJ{dpqz${ysqX1lfvsl!yRed2;-IgfSXNg#P&9*zq2Ena6ZZ!^$I86BTDWJGwqKs8 zwEgHb&`A8ffawn~aO8TG=gSr7Ms_V)2<+s2cCqWj)!+4j^Ti>YH}T_40~Nq|e}nU# zX9jUzra13ua30YI&Ksx4Im^Xa&kAu+$sM!cctodNpnK%MpZt1cNM~M>&gG9{!Jk5{ z5`_KRNSKx))F**@4eEe~9%TBn3jIOQwE79-90J%FeNh4=oy!obb)6!R z0`MpJ;GdoW{_Z~b2Pu5{vU#2l{+kjDs`)^V_IShux;SC<5yT)6>{eam3wAHUi;gm} zJ}%rswEqye1{aSLMlWr`pEzN3JD{LF%bV-bfZ6J7DqV&Y>$L)1yb)|P9rsPLT`H+` zx0N8d(5V!Ahjo59g2p;`V2k8+0NUjk3#CGvDyf84YN45d>O&g>)ccgi6i~0GMeJD@ zu`sCpHv*^|(}K!*EL|V}kr7ng5NPJ%sVEJaFK&)P=%dy5e`adB-kk&vT?k$-W zFT(hRPASd#rhw#(HRlSu8nfh~D_OAwhi>CzQI6|U^-~6Pkg0Kx8~xO}NoP+aP(NK^ zSJ=4Y45voB_KU=$wrXy;>W`ootGaS*s}7XY)NaMqC?__-w)vTVnt5{*6hV); zW5SK@jD$YT=3P_Nb!~|!%;o`jsM*{AW)U&j&J)#a?pK0W9jlT*VY4~#JebYlVm5V2 zDej+4Xcght1);bRG>NL8^kqP-DtKiXwA@=eIbBk!RN`TfH3oVYGyXU=7ac~)^;Sto zu`rCX+1ikFwnsubq3prN+OE;Qnm_XjF@Mdkk&sR%FYMuFVH1uf!EU0&tn^)-NJt%puI;-f*tQx-;R4wqcyKeW1LOyIOr%vt&a{j0J zOs=RzNtu!vBg@TR5EzZKyyq_aVbsMvRxh0*e18WI<@=7x_dO>l-z&Fq_gJOl``~jB zw(NyQt}R@{?&*#qG+f1nDct*TL;9X zO?Md_g#JK!%lUv{y>S9N?~N$-(oU8hquFzx6H^P9lXOnMA;XAb1TYMr`j@Gaq;n)z zvoI90nCIK63c|b6m&cJvyV~B-GJDflB#*k`X|1hhM$1?R%lq38kPRZ0k_NLh1)xZ+N5zjONsk1#07JG0`z-O$)jIM=`YKcjaN;H@nh+w` z?GKGU;+ablcm_1-)NdjUDhk-yvxa;%=;G`TUTZtwroMWTH1^@37&d>BrZUi=|BfCqz3^y!~}-AAslcK ziEWf(icWwI^Kgfpi(As!f`OOq2lff!wNrNO8uSCmUac5tzmm>RY*&yiW19hFkJqA- z0qVcWqG1UQA3*sS!!}CiWq87}T#tuJ=P4?k*BzzOId-kmdB#+`*KR$2GTiJ)&^d!^ zabz01c0=Lw1zl%pSFC_!F|ahd4=i_bnWhsGhPg?noxz|fXM5Y>rD>a+qD?bTao)3- zr+DS*um_w8KQbS4YW0|ko#zk6-K`4c$Pz&tvQ&mbEtKk$aYh!){Snqdrg^_7zSkBJ7og??%!C3%j63; z1e0tYec?Ryg|oy2G|rSq-E=(so#o7cCyX(XWJZFx`cHoALI?&)o*^mzlW2vmkm%A( zTpy@)8m|Qj@87GJ%1P%o&D01j^Zvb8Pz=%5v7j-cRsRm(?+JjZXzB8Yq@@PJPSokc zI67h479bV6*6nM%tJWr9r0aF){Ceq-mW`Em+<9eNZq$Y`mCO(g2{;RfYLl}m55Dt2oEV%IG`&fU&@&oThu|UbO9g+0-+dZsn{l+M{$EE1^t1?jn!Bz-bz&n6 zYf-@#bL9IizG#>a?m(1`R7<(s&fUeDrmb|bztUDb*p9;{0G`|V6Pqv)+{BekG&DF~ zJ)X5u5q%Y52`JR%T>UVF4+!Szz6^BktM^0WsCSXzAAwn#UHmnu;2(iK5w3Z+)^ukD zY|U=ew5XuPO4bVu8PAZEDunw`O|n`9{DD#(GR{Tsld>NY48s7f3h!g0OwFr~DGwXW z@_k?sw+EmSoSWwx#BC~h?jTMvl|kG;0kK-z$c8RZ_*M2k@i`Jp{MR@Qpxf9^`AfH$ z+`tIwk;i2on>N!ok6pa>b(exaQESuPnQ$`)d5KZ?nX%s46R5%7DCrS(u{#~AF7}j1 zMQ}PO#RtsEFiPqVEX_!$&vloug|{mj8CE?89t+fLnWXb1?IFnNt$N(Ul$2m%iV$4m z++)y7MiTE~(1%E(A6_+*ctX2bJWjhAf7?CcI2}sojZu_!!zSAx_cn@)htt6+IPI1e zC;yS~$p)t{6sLhMPERUMj~}8qoyv{B8hfY1spe!G+SrYj8e&AYPZ!n%?={*UWsKN; z^%%mCLmstZi0mcw-4Ej4xtS)7yyo4YX=fE8=7Ka7wTa zrZ#Wx7NmtYq0oDmjC8k0Y?-A-QRfvz%_G>92J;-6ClhmRXCHq40_J*a>|zB>0RRjh z^I!^6cCJET{(vp^Yk_&vmkg1)56Z){*@Kyi=O5ON=dr}|Vufk(oZ-Pt#qQl_)AG7@`@+(Vz>Wt}a$sYgQJC zC=jGfti(zztFd1UYE+cinE&&<=bU@bEi(zo?sq@G|9)0(=AQPRx4-Wx_viNEoW(wS zq0h>BBuP$w)d&e)Tts|+mpYPsmsW-D=J_xFgvqHBMee&N)w>d*f}QUheJ_=zdrR3@ zASdW77v<>n%*1R9eiMuQOlH`aGgbrfXObtTv_EwZ{$6peN(&g?>6;1Q10n!kbDZ?8 z0ajfIi5Dm{CIuMukSKtK28uC!0H3CE5Tl6&w0-|858##fd&MjfWtb?Xh8{vVO*K@F zr@dDAfs**Shbf7_o1kXSw@w{~eCsJnFa$7+{4q8MAVVU1bq_<4Z=vT&1WxX*ru*?j zZzojx)|Zr>&rJr(u~m~26xApc6@-X=t5jFS){&+%xo1iXnniuUOA>&hbBU-WzW_N? zRmxb#@c}VQ^=hzs1N##D$u%G~V*x8+fJKjIvr^Coi^98&BAQBk)jm zK;?t__B&KjV3VV>QeexIL4oCz9?h&i@GtR$-}1K%;2&jyzm%22;QvL&aKRs;!T)%$ zfWMIo{szK_eXlx1fxq|_*Njo~S!PUPlk$@QzN`a9f#2H?{*X-I=UU+Ri3Wd`)+Cz! zPt@SQq`+T=hr<3w3jDeK75MX>$_oC}a^#&)SK)-=krCn<0#RUv%lNl)rZ#&B22J7) zQ}H0H;vlc0^B}ygmaa7|U6>z;1y<5_f52xK&HbU~Hc*WD?p)9>u$KmRh!z3?-aZ*$ ztUPi@@B6#JkFV?)t8Bo@-f7%63O&~D=&HwO=g4D98)PYlwL3fpW9<$P+uAlr1kGsp z**^dnuGLolk{+}9;P@BL@*VKK_sYfHVwEkqEe?2@)#h?zzN_X-?!(OWhSH?IFG^(Z zd)n{B>{?lGo>Iq$x@^SFdLCWCq(fD`#1&Jldq~zCgIPdg2)8a*O5@HO*k_eYPwqCY zDwM{Xw9yqx_B~wZd;W45C2xucuA4RQb^N7t*G>M7UbfgPW6y%&pQu5z8s6|-F4)2X_3@%a8tGBSs9-}OpB3Fay- zA_e#pmw>Ru=0$E%HLHIerajLkOy z8FLmIX`0G=#Vv>5 zB-E1vG<+;cA~ov%Rh5xyKvU)Mh${D3Rgy`P!QMbWTa^|HdkbHwd(IR)JsA^nNcYLU zbup#AdS46BgG?wrs8(ePUwq@T!iVbJ5E*BRsw|w?4Lkx?mjcC*k>C6re>2gwxEP3} z0w5yaByjPno(hqCAiN}0mcT{4cACES#a&y&IJJvp-OCH}fCsH;xxO$dR1 zovO-$xa4|@ZUJNLYr2IDvxx%XM5|l4O9M{kEDF)NxI)P)=^g8+oRDhq=UasXqyTj< zsX-`#>rAVNEmfnx)h7-*dV{@-y1Hh1HZPA#&u)}|8|2@5`IlNPtyCPkPqHuIc!j>+ zrWU2tLVT#vCMznkz@_YgoPYw!efN-8&(KzNa4(1O^v))?d3xsoI5IxHbJ-9}@0^Dp zM(+q*MBqt8V8!j|629b$5z5>00rwyZR}6|Mc#j1bfuZKXex@3 z^Q{^lD*Ay%eKl@m0~pc)Dd!3xhpdEM$$%u(>H!qju!Lj4We}8z66Un42725&dh@Rn1QA6F>d;>Nv8kYd(LFVpqA9@hcxtyMjPfw!*0 zJG~s!EVIXs@(tmcCtKfaoE0W@1MaOAOa(OkQQ%1{FGyv9T=S>vegY zli(gveM@zoQ!_2J7NfkJYJ7(7OWSMK9e9uwhuyH3j({1D}#2HLm|{GWsI`0(z1 zuUuISWMG$jMI#TE+CHZ2-&AKtkD?BCkA3vRukg-IEQOXfBMLsCw?r|?0VWK1Muh>h z_Ev^;TLu-l6~_u+nmMbfgAl$<;wfi+Q1vy~0TcXQg!jIwehjD4o$6ckAjLn^2U9+$ zde+^%E2X={k8PiAHaH3-R0|7o``j!%zO&Sjs)GSi7`D`yW zo2fHRP!pcf;uvQ1l%%B;8h65sJT&&euYQ3|-T776t!2aUBnBoN=O{SlxNxWgbbZgz zaBP|djzb8??iL)sfh9dSzQM0B9Pdfe#>K~O8jkl47kr%M!m&i*T z8gSe%=`V$kO?4abYf?jYyz1b!+8NhvrM@1YPO#_>AURk=((+JdjBG}HM&y)wqQ2YwB$YRE=p2&33 zaMU5&0*w5Mp9&){C^(+#qcCz#7C0uC0*>q0ua@3Jd~ocAUlAC!8bV3$5CJY1|msoIo1LbeANHc$iA=%dt$@v1*Qe!0L0NtNUJdzo*Go*rKTDtYY1%v4hsQRrAU#AZO~eye zs&Zj_MZtCr>9U?C@8NVnZH+~0Z#r7K(_|w(SmMo z4c#XP3v^q%(7mdl`*)Fo?w0#AWA3>l0G+HRYs_uuGpCzGn$vL>5RYJRqUcNo#Pgt{ zBHuCv#4ruShFO3(5J0pP)wJwV)6%P^bf7x*&M&k-VoMxSDONPvG);=Nk1w2!=zyw zze~rzGi2FrI@sHF63nu#8s$3^S13?=CraB0>3{P+{KdDpzFZa@9QHp3^`;)w0cwpn zjILPpPNA1c$@tO*B%M=)eIprm(DphqGyV2gWg#X5*>Lhk3Y$wqq^vcjBbaz zxWMbeERH5hTh*!Q{5d#xT94~ak9^+x7KZlFBdVBP#F4!C0mGa?j`=_JZH9g~8(wt3 zuZyAawG8#OtA)(c@i%Zi`wr*}IjE{%Jct)MyqcVZHc%fOkHYcw$OId?cgKlWd@5Zh zh7}}AKg9s2UqDL4a`AtJA1UXk&1GAr2gAj{6*}UXhmPpTKJ+gan1w{a!cb2ocnJ5)jIp?={7)i z=tj`(=$+M$xm~L1bKjLKduj;dvd6*#aQyi)y@k!42whakO>W|FM^_wY;YJ2X8|6qYdgkKAB+t0!Bdo4^zZS3d=13<5|-h0 z$S?0cU*s$ob^mS*w?>m+6D5UUEx836*^{05$`ja&&48M9&cbje`=L~c$W+ImFEpLG zT-+-JJ(vkzN%s4=G~zd#B8acE882PYkgljFS(aSj;=L}&eqY?+vR}uCyG^Ot48y(3 zQbp#_aAV!!)+=pZJJ+v@;{d@=8!g=(Md&G6XZY7FGn`sw5V~Gx_{}-~8U86W!?obP z`%Pyq_ic{u{IV0|<7%k&`9ZaQige`m;$UqjdoN-g76iN5JOoc&s3%*ehiuhrBLq7^ zTXl=>g(jH{z&+dd=R$Lf}EYC5v)a;h~V>7HrCN3x8Vt*n6B**D^}4vr}L%XlH>)PNILR>NNc zpI2jnVFK=m7%Lt_lG}C$$K|>K+bwG1u9h=u20TY^EM~4(fLs5evji{r*}IOw z4({DdoW&a@o@tCBE*YHMx$~fd-XF6mK<>$XIq#i_&b}HPcL>UH6I$hlg-jzq!OANJ z^UegEVnbzT+_i8yCoU#JWkt*NF5x@sFaBv+I~8+^CG#$vum>JP3KZ|Chv>t}lh)1j`hy+YrOyMs7%;<)hn@SC8>f|-lYVmc}jhN zqU;q#fb^qlKze}`x>N`mrL|PuCuJzHvo3tbQt;!i{YzVMrGrYyR_uy|>vMY`gPGjq zEqV0#29Nn4Nm}vH3-Gsd+|iwtGDY{~o`oNG#!{OZpR-YLYTNFPsc~|cH}mlAZekgB zp7dYLe*lp#f49Rm7RQJ>0v#U3LYkjr&gcNgEV?=)$Lw30iDS<7O4fyAp1i8#98)So ztp&&2#MOf2CJ)G?$2>d?$MnPB&i18#j>&yp7)C+}n_uh~LGIDHG&28Nf@0eOZs6j^ ze8E#&nQ71gHSzMB<7L&j9eKjwcv9?5q7-7PcSV=>#GkYgwyL1rNt8~DrKl({wKJv< zc#hct&(P2qJceOo$s@I)v9A%j>^t7CUOIigVU)(Fze^8J$moNyc_2|%Jup#zGt5p6 z%+ItFh763q?i{=an2FoLF&vCfF+1=XpGV7#@uA_-_rKVNhah&u@Qh$b#_+ra&fs>@ zOr!RdQMKWjiONprvEZfTc}`}l(@Hx1I1uQ89yO`8w^wl6 zg}#I=&)McmPf~48RkGo}De0!hR@_&)av01{9ayh6UjA6TY$jN5`rvrkG>najme$yy zDNd{NIIVubbDRz8)`$`M(7Axv!gdmOCuZfp$V_F^z)8~+Wi!D^kAahF!AW(BlUjSb zoKz1^!V!F|d)aQx*~dn3(wLTuwF|T7;P}U~NhH>ro=Yc)Yor6SExR#%lmxC6A4QM( z)iE4X^U-ircAl*W@sYvcC}2>87nT>UVwvxHW#Y^dNw{LP)*m`MFG5)5%47Kiz4zwZ zIpXzs!g%B?@%lgyh@bNM#_g`WzG%VQS3rlTLM3GM`Z_9npAE8*HtY(6wCIuRSlJ-0 z4=Ou1i~-Ur7mw1y7p=?X*m5qROM`h={ zOEX|_;>rdpR{x#6Q%;BJk0*!WU&Nn7NX#F*h&`^Q0w$!a>Qh9)GT+`!!6}XyT0ii;w6=D;6^jw5cPWfckR1y~F=-EMbG-kv>2VbZw#= z9a)BY)wS7Bm7d;zjiM^Jv4LIb1!kD56jO{UP>!sGaUr_ybZj@$2kFPTU@-E zHqTQAXO4H^b~K0KYgV0Ng7kn;Nsg}f1Hke#u!h#lh3miSPk&c$+i%;S-U~Yi;KX<) zd;;#gYtNtlvd}Pc27mgrBd9w9EW9rM^yciy==>@mFPlI8*#M5JnRgf}JF_nGF)za) zV>L&uiy!pJ0vnI6AGG3$021Z)DTE)EA2jBV+5Dj01#}{8J@`TYF0qg{vx?B9+8=xEsc^}&_`I2%OGW+NA} zvQYs0qq1}Bc|HZ;*+|^Bsl0lnF6A49@hO9$>f++ZLu;2%7siv~UMsC#ESgZfdU2qY z)-F_U>DBjCf5Ly13*SPzTq%3k!KV^`R(x*U*2$(++g~^X{`H&B!I!a=Mt`g?4rzN1 zz6`BOX0PtCP-;)3(0Gici7`u_QO+Vwx%T3UI2GrFI0H^o8)O!)vFHu6Dr4o4-{$nF%k`E&ob2D<%DfLp4|Po7A^kKH>8I&7 z14s-}I-MSWwOm<|a-2MDRm4U;y-tKC_`paLztxF5SO@&bvPP6OVLWt+u}1Vpb=%U&>lx8G*Q@#(GW@Qb*1qh<#5WHCor(a_ zW9G@2I=&f;%FY{SMN6obN3}mXk%O!8HUP7?wsgV2T6TXIci&$`goe2Lqx%Bfy&t96 z&)pXRvzfWO*Zu~r>md$$Yd;IQvEc@}(dKw2D;w_K4waoN&g>X>pG00s<{f?3{}Ffh z*e$@_^Kh?BR_@+?vv#=q?tKjzeiwHSWjBVqQ$S}n?%qwt)ZBd+Dmy=%9_DVp#eprt zI=R~2{QcgtxaG4;;C6hq9y??U$oOXO{m&6K-3-0k--i*kqWk;Yt7)Wam@#wfWu2-9 z1Hb|G^w)cLwnO1qemfL?rg*(j_%e25DEt}dm5susGNz_*9V$CpoEE0AS^Mkgnq-0T zNoe+8-OF0x4Dt%fW56WX0auEawz(H9oJjO?X$2KZ$I^eW-Ir%k>P4}>(e@~|JR4uh z&Tfg>$%#Csf71-kd^-g=S^*Yr#OO`f&e82e&C9C^5f-dz=D8W({UXW7rvPE@H_8mR zty3KNLsUrjLz1Nbz>Kc}># zDR#uwVR~;wedLPvt$P@9{w`Y(V>gD7&w?!3G{tr@rY7VqsO+pbDXb~7>_+1z1j>~% z4JAx}Q^a^Zt9mtq+%G#8{MSKD#5mELCzhdwrw4{W>oh>5>*M9mg+myG9VzE|H0WRY zoVx`~F66A(MO|BnO+913z=yPxJtl5|1>e;SEt7{%!r#u(f9#xtYsAsReQ@}wi^}Rj zQ%pvd7Uo==_2^1Jgr%ToF(!w=$3M9T%QH=`pG+=-cUw7={U-&L;vRPWLf`_Kuu{j{ z^f!OBj+H;@1@^-C;ZSTgrMMxa$u$;;2G>3-#|!U6dJ*HfJ6DWekG96|sj4y;V@nb_ zW-Z5kV|JDV<=OHmIzyN=#g(-F&#iM_e6K$Z!jyzw=R66(TWJtCck+$Xf2!KW8(!!9 zBT8a{b_k=*;UCmZB8*R!M#+S>jO)Z8G~t?y{~v?Y*c+nY?{ zc9g8~!p~g{K{G_d7w!sl1{X8deuu}-?8exLJ3x?ZHe&TI98=qf3sBivGQ>whpElF9 zISei+NObJp-vzb2rGD<&1IpO9y)JP9`~tLlh$W)QA}L>wVpmJqwC|`dTMSJID;xZ- zW>fV3x~h6edxo|3Xa3~ou|&Ia{vFYR8c$mRL74AO@V)}p(8AL`Av~RPzQWT%+3_^= zzl*0Wvfyd*achgG;lO7dGnfeN!lbGtn>>Q6J^PnFmeKNG`=MC=8`tFJ%wMi7|4sPY zDZ^#miPFc=!wh(`aa#UbN~*T}W#hA*oy^u{y|eapJ$hG5X&SXjksCF*TFLg>{+jvRP&%S# zw-0yxGq4ch#gK}BbS*cJ&>zcXV5BIDAKI#6hSrMs*&sC1Qm3Vl=rbX3Mqe=|!yC2IpHw@}I_ zjCr{@uP0CHkFtqD9QquyDDHPiaRo16!>t;+j+~gq=Q?3t^qZ9P6`OcJufWfmm@lQd zbIT4fTz==(Ie|^o)uL05f>Yl*5KjHX#r!;qcg;*j{HnYUP%qHLp5X9uT})%-t)th#LAOE+pL;fChaun& zMv%PNJyF(5khQDQMGccdw(&J&d~i#gHMg@vjzivC*`~WK1Ce4fL|?jE;|C; z6kjwr{yC4ej2$GtjDsxPHb+sL$qn1x0e8z*3_Ve0A2iT0<_6?M`iJJ?79;K6yf9ob zS{wE4g6FSkv<_-NSfO0jCc*BkT@G ztht?$X&OO0{4PM%9OI(Tr*pMjj8pcbWZY-vq@f_s7-@|lf zI|uo|mJxZJb=kLlDmyZnoL5RrCTBWU7>W^0_)lN%DWhuknvTlOFNcB0+CK;Rwp>ST zFV@`*Gwf;*zs~a3`yNo0gsVtjBah-M6qwVFD2cb?7MN9JjQly}t47968Do~70n537 zTeF-+JE}Xbn7VYHmLI-5uBOfYHR_J5jW}QHmN&z7iE`)`a5xU7$eD!lLOl5!LXYqN zCd!NPEVORk5@istcryT;a}?Mjz9>=pCX~UkJE+`3X;b_ib05}Ihf8XKhKlQr?(Nu@ z9V&pi_sLL$XTpln?zpng#Io6HtJNDvR5bzt8)CH&44w|-18DO2YjeA56LI#j0%*t! zdf^by|6e=oVU&KrVv$96MRCs{1Iz082P2ja0$O)WG@yk7sLOj)Ivt~OHaL}i$%bty ztJci?bor`k!^`baG+rSBkSJdz?C*}0O=>cY!@Gl|H{K4k3cq-?*zJ+G0ksnKyzQqI zzs$koNO9YM5;k-@C2riA=^QOTeB##osYr4A+rfTuGm3)5fPmbI+=AsB*)X>Icc7~W zC3j(KD0w4PN9>c_atR<8FA1qM*Qwh0Ai&2usS@mw*5&3fwt>tZNp0E&C&4r19K>J0 z9%H+@5cH3P-R=cbpBjQ!-n0Yn>HXFRykph@-s%v%@}?blA3Jb;z&p~0H-N|6vXnLX z%b?P=a;Y5OoHOQFP!Jj~!I$XL=+as#73D!s*Hn3ouZ0Cln_Hf+sV{F6 zB?Vz`je|YmhY40k?ek^XDt}ofcsVTOw#)Dp8tC+Tyg+_m0Gwr@S`c~GXUwm^Nt^8g$GRkW` zkH<2My@x$^2j?+7LtoANTQ~{LV_;|=K3YIERsiWjUp!OJ>lPm+HWy!uvXpXeeg6Bj z2{DFr^O$KgBx4$S@m)0`{tCWGB1<(Qs&&HdymGWz(|Gz8;7^r{KzpgwnNu`N5sau1 z6Q2(=KMl=lb)AXmXldz_JeFERxb{U{gC}ayHENWvg5uDid{gr$R=`RnJFUl9Pofl0 zf*=M#eQ^#ykwt1bU}}&U|5-n*LWYOdIv&c~l}k(WaO zw&fc!@tbn~{)=x@zb$G1csW|qR_yCZnyYJhyD-h2V6zbuH@1=5%TPLwjsIc~nB#-* zEIJ4@W)?;3Bly%XjylRL6n#vU%FLd4B={4?n!8vk$G7H;*$)jJbK+3`R5z&0Yp7V_ z2$;oxWVV!pMbWiUM-!AfD%me1k|wvi1c@wZd;ODDaK`(b{>I&Rfj+17E>R1_I5rTt`YPYT+{h#h1o_NFI24E#M4 zIP#smQ6C_hPHtVQRidYZ-ltkfl+F~@poHy{-e6AsVc~-dz(_3i#g6WGvTNDtR;;74 zx(h&5XIo4JlN{!ybV~qM1Hh^eo6CCkaKQ@ppe}J%Fl_Lw9N~e(&jm}-0SDhIDcFXf zmU?tAA0t8TP23T_DNRK7wM=&5%IDU}E;MTZUzL?+#skyzn>~o!c8tIyXk{CL%U*29 z2;45iL>hq&I5WLzB+>}X+9}cqyqd)b4Bj)0Uad`w+c60#L3GO5OxZ%@icw`U{v-3j1k?o4B$n!ZEt=rC6tzZ zxN}Br{`8XQ`Tf|(nx7g+R{F^FLOD5O&X!_#9lOc8)r)@@sGw5J zrxWWfmuW6+!#Ccr2LM)*Ce3g;8-C;XJ*&g+CvS zgV5e)Zz);Q zs#nQaH*p2x$8-z&*LIeSu(J!LrmY*Ti8z^P|I%iBO*A2kSw8aMqv<#`ic|u?5?2Qc z6zcP9;`CicRluCDX=)ua*o2stV+P6dtnbbEq`@R%{4(OcZ9lwfyF^LAnR{in|8TZ3 z$)=#%UR7jKFf$)PV_;I~pgBFdAU(QU8p5*NS)?XjDA)@GR(DIsZsrM9^f{pns{ls7 zkV>F?Z8v07Q%+u2?v7iVUWNdRbs%YN*vR2E5l~($h)|p~np5ENuh0&A!H6T}%O_M3 z^Z;qjR*+38#tmHZnFT~kIHHf zB)wm*G?MGQ{=dggCxFGsp^392w= zaO%_9()w*!Un5rRL?NRaw!8RMu!niw2LMF}mM>pmbFC_si7$fHF?|K#uxicm)f%#P zwEGv2NJi6cnJS8;-Dj#y({4DRsa0qexR0f^^b>5mpHt=cposaTEzRqtldgl`2yhAJaqV?}^9^lnP%<-9IoHOU`HND4rMN`-N7)^>kkpe4teDO9ox4 z|NAI-nc5(y{X#u6AMDMjVYGv>LH`@DUljqn(mAarNkrYJjmUOFSJ|dvC@0c8#_9$0 zb7R(U3?f$MO$s|{ue6%}6Qs2BQN`f1h$Sgl5^>1zWOA@sTMc}l)phB!DflgM z!AVQ8l#a_|rAX&PN2zzvn35o?(Kcu~dIAUsSg`FXonr@+%FnR|LH-gtF|1iNSnVwsWMM zGyj0tTF2(Cs@Hn-3bl)X5TM<*96HyFI1M@)H9BrwvL+pGv_2zQaUfbY;+u%6+B|+X za!q5N{w88)tjfY?7&u3nphtJ2AF6zUtzXAh0}aIST&9ms4q(uf)AcpfRmp+-3y~c7 zZAT^tR!+d~5^Zg??a8`RLwlk&7pZmR46^XXcfQJv_1bjSf zA|;7)h%$I1^!OP!($AK^3-C9y%*l>|8rz~UA-UWuY9Ib!qYS8{fFm;^?sdt7u5T^?Gn=aKR$2NZVefc zHTXPKo*Dg>dTC|r{XJBYp%y^e{>mM!81h&Cg145xGD_MSf8~j-JY7Fr^;&Q1`j21D zs_U0Omr2)eJyUf3aSZ`o|5w-m&iR*ZJzf9j7d&0xp1*Q(gRASm+ZwvQj1vgx`Vuf? zLu7R9i&<~s9f)3*z>Zn}p^747)&;68L(F;=_@`qr>+L;kO;8A!v&O82WXy<|b+B~f zkL*n3gA-$DW#vBq2Xi&mnR7J{WXaV$v$naK=N?szcbF1z82xar=C4Wu++0m3npR(O zZBzXwm|R=Bg{u&0CpDgz!m7GCn@9@lwEItaWJTs{V5vm?@3WgBw?C>oLk2RLjsmf7 zVnNY9<;2BQ(5yEL($9sW-j1+5XhU=5X`;~xb9#^_rdLnz1GgSzNN}CWCi=SKFj$K@kI?wwy7&72xjGFcn{s*}=nb!Q90Rx8no)!%_e~CPa%RF$z!>(B?uq`JC6d&; zMVBZw&@5;ZeJ`l1$Lp4tF_eN+_X_M6_$>xGHAByLi{B^;4ZPqk$T}d3)pIDrDXYwe zg13UPC)HPM1L(-uU=^AUN!;IsqL$p>1!0~_fd%KDL)GEUJv)TFEh+Uv)Ta$p$|uSnYJskSjZTnCbVg@FvrN}oKgJQV5ls?jpQwJ5OpjFI1L1>LGWJ9FU#SAcpgWzGxAOQ)IUqW^r!eL$JeM0 z3TT&dB#YR;w0g`bm^XSzIj3U6`0UZMNJ3K&OaQ8$&~!M7d=zK6VkmRi=WEjDW0Kfj zhiMOve`(nf5Tk1yd(tO7t4p6Oo%HFX_h`Z=aJ08?*49|S*5j!49bOd9K4b6*N}mKM z)xcdH+FaTN=3c(qQc?u*Bqw4nLyAzP4zShgUT*tUC|--ZJF!}~-}bvud5-DPvZ;mu zJ=W$%ir<@fBi$2dzRS||{dc|k+d!+sHe7yAE))sl1@p)2aZYmg7D$>K8r_>$)|TT#F*7exWL zvo@#V1c()?rySW4)xUJ+m=e4}!<554Y)CB{6)_z`2hUMlg|kIP5G{4GvLqhm%zFeY z0Zp(>se$S2am&9OK8GYrM{TbA3@DTiSO!^wYOZKTgNt)S2S7!*Ism|m4xmA3)V-YA zCOV)II)D*_)&ZNhY{aqA&BMT_liNuYz;JKvGvMP)#kK&h)Fux-=yq;3U;eF5q;xFC zdGlE|kB)J0EIP+I{tYk2*-OPZvBZhpxDbJ70iLkkC-%g%C!U3P7UEfiXAu>tFBaNA z7n3oukQ*Mls-R;KXN$@N;=jMX{vf`dq%;s4?-Y~N`83AV8FXn^*>?=ua+Ru||}sVwaL zid8!2LByJVy16^|>&cZH~0Zl=yf^NUxm(F#Dva&_m*A9hu#RDyLLRJye_9=Csl~EM|8;$eGdT7h|n$}#0b1wfXj>PU}SYC ztTR+2>1SOBdbkM{Fp_j6VLa~DmVVA7E@U$->fn&nii`Qef6;)PHU`L`G@@RymH`fH)hX600oThA?yt9@nIFwg|bj|&n8$uv2HC0dL4`#60-l%00oLuPB(~_dj(Pt${8X&6gIGMZ}l6@rz*b( z7hMGyDJ_}Xv4*;wiwkf$&Q0AhLxi0&yb|KumF>D47a zt}Pn{Y|jL?F;g5>jhEHf*jDM(nV@+gJNkM!)v1Jz`(Yo8zwU|mb|L) z84Z+kJO;%UmUtso0W>+ntwvZxoP5A{^Ad8w5ylo}K7w=7$6}{_W>AXKl=GoXSCrJw zLRQQiunIY(?ciTnzjV5KT~=ciZ6j31Xl z(%I+a9o(`X!CL$yDZ;MlyGs29TY&=4ky4<*Kw?~Ngu4@eI;&O-1xA@ua;{%NIr;tG z6O(+-*)M4C30SXsf$5OW@aMY4;<>T-@!bfj&!sz?AQ=ZKEUs%Skyjvn>`G*%$|W~o z%m$+C9`(BszeRip$#2>_Bav~wu_dx?14|-rCy^5%GWwd2zb%P8!Y`4NgdJRo-1nns ziCiNKqMk(VE&zcqGfQMwRYghU;#EMNp3JzN0XjEp`6cp9)OQ{upMW3sC$bek#PO%| z=@0l#-^+LH76dKR0jp+C{V;B{OB7%v#_gSNRB`*bcRCSu4uJQqBu&5=$}(m10)`V4 z>bkT$@__QS_X7H%hqdzpj*v0e$_r?Nw6$tUdkf8tgC4MAZ`!aF0G(}6Z>`c6rYDeW z5zYU>VkTRJ|ASsnhWOyxh~YC2BBFVf3}Sp1l3BqO&m4u2E@qPd32m|8lC{zn`+X0F zjnWp>{Xvtiv8nK{{Q}+wR|ho(WE(sb0}n8O{*x85dlJ?}Hc@s{8<40dAONE8Z$3|s zTsMQJ;CTPW_glU*9PeV7ql?6V337OzG4fVb6hXZD?&?9OQ7&$u4_@$-Z`D!dwHp~6vt3F387AC|Q&?V>7FT0Dsb!U=oH*^*}-I4`QBfZ{z ztcB3VN3&g#ie6iqA-Q1h6jpwhA>OicG86B$RyS$^9KsusxJC}&KR^W151b!F`WZ+e z!A;1D^go3m$i|&nXPSR*=9zx+jW<)^-}1-{UB1nt8Rp_xcStk1K3xo5z{dKwu_#|o zOz&bI3eT9Icv+5&`|=a})4XX@7tT+d$WqDNN98B3vq~qom!BBz zpLiIZ`!qM)n}l+v;mfw|^Fnp$Y5*?VFtGZ+T2}u>9UoZl<(W23Q7PrPn;6i7R@D7Y z*TI0o9mOXd-Qa4ht#rUomMxXGMw>f4GpjuJl{LDbJG5RM$dd`8W& zZn8>~{}2$43b4OOt+ba7P3AtK>12`-f_d-UpkSUVAyjt3e0rseg^YSRo1{iz{gNzL zKgt`=Xhapo+g`|Ny*x2AwKPpmMUmo}Y@XK>dtQ6E<7kZuvLn-#CI51O zjM+iYOV8%{Z!$;wSNsA=V!d_E42a%Z+gO8`b7PG^sVOx8j0PIq^VRQ0{1%1RLw?(_ zMmgWuvBu3mV-_a*AD{$aI{P{SQ@3Ib7IE{lj{bY1lp(v0{tuRc!qI<;4ClofKmL() zZ^{;HyrHV7SYwz2J*X!WlY&sJF$hCAC10W*VvPoQHWB_ETA)YAuF!h)cSQfKKLJB) z6aAlvK|2`z&*hwS^e>0&1f??x|AB&1iT=mQpTX$=)nCP|Plw8z287n2A2bw4@lrv1 zDEhxdUZYkbYxKV#4PmC}f9dC>h%frTrW+_QpOgXxjv~fYw0AfDbbkCoD8T67_>!I_ zQNHJIIFRgl#$G9q@Uaxx5qdZoX~iEnF*65qPsc=}m9n&spnrnaM?P`L~^4rz~NAiuW39kRq(gc69G(ilL zwKT!YU;8w{rrfvdX@YJ%Iss=tmgA)Y<{jnxH3!a1J1U zf)D4*Q#8RAU_s}S&x8+6*1`1|N5N-=*mNil`1ucOsR;&Q&<<*Xn=DQ60i7~W6Lb~Y zi6$5CO944>Z)dYWG$C)(2b03o;K26XE_t`rCBBelqLx^#u z2`1xDXXPhCfoM$tS$}nbyP9Bpim>PL(Kepvkt{8mEB-6lZG3@q&6mHV5m4v|yaa@W zD1@%!a{huv5w?J<#ud2uYw_>Q1=3ZYW?gvNadGB_r%f@tfUm3+6Z|IkEW#`hIS{^h zQ8xXheo;WH2nLYi&OzaPdZ^0aKO(;=)*tEw(Nl_#r1o&6WmOPrN|&ipQ4yC&TiVlR zJDdJGUrT=}rwV`5u2{)acU=`-rkr!750SFRfdHo)d7^T0KcnqAr}>RuU$BbK$`}j&Z!>>wC*Z!M<|dh zGxi|8IzI^MT)xqJTAp}`+R&!Ydz_i3-eJ-kQy|qB$>r@SmjI(p*2~e(n*RU&D@^Ux;!av!R~Tv-msfobHlQ zWKQ>hXinR|*9Yaw2$`iF4uBEx)8-1k(K2_#GeMc#O=hMv=FiA{s}&2M)_b2F=vfY; zjX`f2wO)~oFSDEjqB)zZS-M(p{mR_NIeyCZlNs1L<&qsZ`w-=d*ig?Y7k_7+Q*)XZ zo5`F$!E~I%-VadD*km0UZ;LTq4_Id=GVQ+iHhlLKHRSy+)b^V4+Y@MWB#37U2F9hw z!z3hQOuSAx|B~Zl;s(vZpEWvZ;EyVdrbGQnQlB!~YTLK_*fwCP^_)1ue|SzC`sZ|< zz$kM%o`bhHryZq!XiohV;C7r8xh`QcNXS^Yeo`UPZkuJ5)fbd+Cc}}{R%`cS8@>r7 z?6-KAu8*Mu`)d=6BRPJ_^SA2OztnP{pQ>qUi5@Q?m7vZ8w=R0Ipo$dZ?|>Wl_eZLu|am99&d3zcs@J(PEgVA|_FBCTc`jm6sSxT!2xadvRy$?h;ZWI5+WdV(D z0>I5{ouChS)sd8Tzeq-Sun2o9RZE?*hAt!c!6%{TxoL!UPBg`40CxpCcS)p1 zwy65`~Z zVigZZq;|y>Mi*9N5j?rcBzg3>7mxWj<$^rPL+{7(xU=NGP9PN-0uOANU-&UUF$g<~ zsq!t)9@>fW5OVewGlxtz85gaRn+$6010-R!kR>90ZX6xb-d{XQ)KYslv&mBVNzH|6 zVP}wd??s9 zvo))dq?E|!Cvb!c*;ip4Y>YYz;|rJ6biy_aAX|37;+1#`f>VqtEaMQeBp}C3Mo8@f zG)8Gb%g!>#q0Y^pAWfq-ubLgJDd$%+qsr3eZYxGYs(^Fb#mjS!eFJ*PUgz(?oRwE9 zGaS=LkH2x$_~Y#HTV4tc{_5-2;Kr7M|6ognt8pFaiK{(LRwyOZWbSGyc|YaMqz(^uGqGR0El8}}V8nj}oD(+tGUPlR8q3B1+B7Fc>8U7=CR*-$r zVahofgM*wK;CE}wZ~+{ZvAVFcnZ!O{8ik7nA_CVDVBQPtJInwTx2s@)VH^x;z%&|&q@QpCNv)(b^5^?_8=>nB@Q2DBVZkmkM$p5?4SWNN?4 z=K+uG^LQ0!%$-LYY1bDy`@P1e%&r=LI-e|KGj0oyD5`^f z0O=F7qIe=XZECSMEk9-#f>FI5>B!eIIoEtDem<16373e+gNYVoC?|gRroRG+*Yeq2X18Er#YlWq0Ee?^l`#^BjC*`AVg zr+Z*D*)s&VLz?VcETKecGQ*SNeZcGTPB900-!J$b4>q7glv}E^05jL&m|QzIK=R`Ha zqfi=YttJtMptUM&$F16vQl>DlE?(8<6m}K$MR--`F3IFojm0rpr#z*+s(;I~N#wZ! zUR82wR_o^O~GdH$i?Z}mpb@Zx2+Sc2-f4gG#kiCS?x-D~2 z%WTcdriuCYDdGqanV877d6YMgPWY-P76{V4a zozFqmRh&Yp@Rqc{$|OjuBovlMJH!z1pRpF4A=>>(ihOcud1_yB5jjK4 zcU4)qDZml+E$NkdU#<2G+x=1FS@1k@6qXUS3J92ro6s~+A`N}eOlYV7<1+U@v?Ki= z(@y_imu7^2$By*BWjp=fqWV`_5AtU+3*t{?@RNK9T7;0^LvVZKddRB1E~CY*_QAL; zoJ_jVSKH@xk3o@T85GBOUbnAq%&V)H?IaheqcfJO^rFfLcO9sunAt{3vSfj;XD#3} zz;N1YDey>19heoGPqRY9QX882r$j+R*2x6T(gjR7Iu8p-E? z-TZ!QESF9SW~0|RnBl?NhRb0g`mrm-#)ggxaYG1d-1KCQNrX%tS~X%cSv4?MI^4{r zDy`lKoFM&$|N56UTz)ueH_0!Z)!(s`gfoSDY_}(KfyGYRO2#Tnoo+32YP?m3K-`Nd za**D#Ojg;Jf9-C#Iis0#LV>r`V)}haL)fy!>Jm;(q0gO{WQkdpR?83{w`j9LT>7R2)I^Uuj;p2?^Af+a&fSeW>f?) z>Kjg8CwH-ONf5$WUS)g4i&+^Lu*ftG7{l-~t8O8{Y9gnrZo7g)ZQWWv0@hoJbpr1q zr=ME~g{VVNvAOIrX8+q-kiGXQw)ZGW(%bFEo*CKX3Wl4Fz@M@U;I?`dQ<5W!+)Rk9 zvnj<;E22q15D?*Waq^SdkS6jsPxUTy9+p8D7n!5ySe&BR%^ z(4AZArVJFNoXc?`2kyar6_cON-j^0-VWN~X7F8|(uLP5Cz~t+JMf}J0BvD9@%Vs`d zTf9m+-^=b0@F1(074B4NGo}M*$2aBVPx^^}3YX(HoL7k#W&qhMuc%_f+Nh>jyb~U6 zfS|dBYcAp5Fo^J0=BBS6zdN3;5g!E;g62JE(6IC6yHV)d?>B z3sVndyaY&m8{S)AGE%I)50V8RJO-X|gGOKO=+j162-ud4I8P!ieM;2217}_2;T-IY zwB@1Gyr4Xc1BA9bl%YjX9!_1HMIQdbo6ZCBaNb_7JXFt)kcT&BMae^f7;TN$dn!Am z182!S>#j|>Nq%P5fmSv41R) zw(d7S{Y)2hV6<+Kn`t!{B{o+q4$e(Eca}ta-P^c$;QOfE8({yGGaL<-2@&bIRM>T) zQkQ1Sj$FjX-6CRC%D6|?y}!NtQy`?;{qIf?lWWJ2my!zJHqQg(XTXs6=S#JC>8F%n zRr}bN2x`~b$JU3EiPelQwhpojg(oSOaqU@!J?w1-{wNQ-2(3XNte0AD%sEosW!a(f zGcfy8_|jXtHG&c3TFqgXPUw)Vyx<>ry8O&6D|>n{_$iRtUzms{YvnIAatzB~IQWSS z{=%hCw(BprxlE0f>JTs;QR1#3M$H*qkaFNah)&0ar~#ecc;|mZr{6luuhZ{b)Sgbi z3N3;<{f7Bjboy!XSzW)6Gr7ps>Hh*TYG5OMK2G}aD4iaZAHm>XQMCg;P9H*{TyxP* z|HMso_^q6k_I;ei>c-ku=&hiS^A6m+|95?y(#wITj6RNETT)j1mPlu4unW1p+aKg@TQ#Y!3j_)g|c7NVAGqIp34Yy9i2rV_=Sb3a;erX zrkZ-M6Q+uZsZLL4z|^woU=3r6K{)KsN2(!? z3_GZF(E?fp2#u9^UfD2|EkH#%rwZ3x0Lfa?<+_0hMy_XU(0?&UUh>9f!->VW2Vj& zAdyA=Psf1Sr!n1;9Bs;Nd9Vgw^dTqP&cTugNH=q7w3%QeV$Hz=pz&lE9L_|jI#6B} z;3xdW0stx8vzK|xyeKO6#x<=CF+qaDwSxGySp2*BKo%wlAAdsydEK(^3|{{n-|QLok-h&91~!6YHq8Ri(@vk`K26 znoK*uFE&<2YGR=T`_@TEf#K&{I4A>KbR?SR7X5i_*|Z7usQC7#UMBu@5u#(TsToV2 z0eg5HT@==)Dd!>aAlyLtX^FSwh%WZQnl&X<6Ohl~_EMc8M za9#I^`d@c9%U5VX3JP|zyr)@;8gTr8AsPqwYj!8c_*~yFrhAdAu}q{44qD{8$MVN) z#b!v{QZHg^VtI;XJqNTSq6Pie3DS&aUrPv&P+TIPe)B~3WrJi#GrWUz-6`YaAtD( z*tX|t=@>;^-r!dbxUg9|6K*lCk+w%3HH3ztPAw?l zGP;eIXiJV)@J7`pi`5^b`Dv>>IKvIOGN88rS{F-h-wE%~)?E}u+eVs^3%MXo3(;9B z#7k>el&ipUW@U3O*JLk50l^M<^8mYIh_vy6TPflz zN6V`M{6s?n)yi@Aao;v`i5I0l*XJ0F?#e^4@%X?gO-oDDpb)oF=v_z3)jib{i|ms2 zNJK@^*>1Ba4Zha9?~O;PEkNw9kiVfz;39i7E%X~>g{r0EU#FZM(T9o`V6TZ!`lSqh zUAZdBJv2lRiBIEIly2A#>(_5BwFD#QPKh?R{-26Hfd#g{Lf-bBj%K!#@N+K+ZHXX;{ z+dY^QQK*Z?pz954>fGfyeSZG%{|dnRd%5N9XUsQuIN4eKH50zncLI*0swz z!W*B%p>Q*D^B8JdJaE8IWE@FP2qQhCLr#xt7V?cq{n7=6U`uE21Ax_J+)h)9v7YQP zN=Kq5uB)KS ze@rGrGT)GL^5wN8cI@kiF2`$U^6jXHY~40wV71f#68!1Ba9dVxtbtJa^ivZ=F5*Uh zyiPe2QJHKPXEsLiP4FmrqlGBRMpikKRpNA|F~RP!IJEUK-C}WG32_1{VoQ%sn)G!m zHbz$rsnRqsp+W69(-wC?<)*t@J_{RU!@)x&v20``Q-SIdXvo}ek|OSP;xz zgfCL1n5|tJn&meCsae*0vn2Z5K#8;~0KGs;|6NI0k^H5XmVTMxSP zO7xLkcXmX>Y$}q@eSZ*G39H{<#(sU)=gg1%*5`{6?O2~ZZlSPys^Z?K+O^(l<9#p6T?rktDegO+5Z*kUk58~%dTFurz2u+oZbIHlji%C2Fo#G3tB zdF||Wu(DOskCp0wwu_bXbQNG_)UCkEB6eY6CCJ-B96>%(&d!K-?KR>x3Bmz+QRjV> z|J_?97*b9#hKN*8!LgtQwfsqzE9EqZU!>9xikEJ_NG{$&4zC`yaZep;D02@Ds*}E? zN0F`FMCYP%(H10vwnopXbb}k3a(VDyfWfomk|Xt7L^X3C#6M zYp!&=3?qw{hyI3XEvv_Xjp3jyPOXRnL^;>)i@)sC6Ij96xDzL4b-XSrCdG$rQ8T~t&$I~j&cK- zQ48k^G`%;)xenL=P?AB?>(cJw(hTwZ&p0OG_7mh?0GM*-VX0a?6JH{*3r5fa1$k;0 zFVDy79@UBbSpJj17hxr$N+AZ|*hWU}AS5*ekP>=F%qgspc?5OeY3!9KSqgOGHLwzs z*};SW8mRWh5F`g)DfPlXGf=NSF4|31_Ya$qdfR$fr~atBZRbJ!zkT~cUAg*Sp5-58 z^gXO~BaatAyO-gFyVUiS)Y~ONx&xOuF@PGj7Vme1tHtwJKK4eVw=-&)>ls*j8dbE+ zj5{EwkbZH~-gFVa}*6sH==I@z+Zfk9+p_265SaUP(if z-~JwdYCHCKY85f&c_rN*Y1jUK_768Ec7R{!NFv=*LH^kq93}JKxS>xDGF@8#>qpAD z?2yhmb--K>Vz7;cr$M+U0alb|LD9oNo2gbU)qL@GGH+J&INhVhIl5!x6h@76d-OQ> z_m7y*hm$%qpE{`)n9t?W;~X3{&XpY-XGqjICq|F+`oR(N$?w=WPNk7QH|kI3?H4`H z1ySS7kPgB+D!>O5!sAdm=H)<#Q4fr|NqjE6X`sfyo1xX_O^trj_SSETuPW<@vBu0Q zT|@7Dx!?_5jXetbQ5|IV9J#MqXM45%<6urN15EiMj~}M*~hCaFSZYn7Fb@IDB4DVaM48@|e;M zk9e{R{v8;v%E7~4*=QgXRjet1Y?qkA8h9nGge_Ci?(jf(%{BPq>W7D@FRngu0$pBd zN1<9ZoR*b4XKLU;O^YQoRM~9Cbd9CzQH+7B`pM&YoG8m36n}ew9JZ$aB){Jr zFb|lbjmoW~A0RP9ZsRljTTyTIx3LQmwe?<12rKIWXjKV%^oCDXjmB>`TN7BMc`Ky+!deXGwpf_n;8#6N$%R?s2CCCad4&pXI8fS5|2*Cd}P9&qM>vpjz|Ua=|$ znNO6jvcKZ)+Kj#Yf52vcm0BDtMJ@fD2DcG*!8nqmSsWqY_)DY>r?uJe|>L<^54K5MbD$XpK$f-F|Pq#LpLJ(6`2a09P7`E&4p(izsJqDgHbWhGp3N^*p3PQ%rP ze%z8Wab*E>IPrOHzd#n^vmtV6d{aKzj3<=5gU85t)k-{Ucw|>(73*@Oo$;N9%C?R3 zZ~PKF&Y^RYTUH4#B=bfen3t32(kXUMBSi2V{6H+62GCV9TC(qV2PlpIav^Rn7yzB= z6}_X2-p9v8SL~{a%z$}+l(fo*=yVRMiGa_N`lZv|9?GX{iVSQ-51;bbLBa+3-xv^l z8Bv=hE1ve(-VftN*JjCzYSbQCIgd!{Ua^lg%5^9mnSX74R z#mKkVvsfO{B+2XLlnkw@W<0R)m61PZk_+Mdd#n{bRe(g`8RHYT0Umn zy068I-SI;)qc(uazE|$Am~ro82<#Lwi{2Ev0-hCDa%8u`Al+cipr{6KlaY?{HP}u! zcqOvILu}B)*Wj!D6i9!IY%qomKFzg3TA&+T7}?-RHkjpWFj+S^II_X!Y;e7=!8y9Y zhLH_E!Uv329Pew;S2t*iMPaFy4GMh?y6OfqA{$)C2H)h^lYVDkg{3PZ8yv?5^sY3E z9P)?!Tc_dYQgM7v4^w);T-Zh_92+j&8HKu|>Z*LE3R2o6Nz3Xv$c4<{1`aJ^;4fv~vQaJ#Zc2^gF zj4S*VNQop(6grfilCuedX9IWrp15lMEuBWn-5`lWxDd={A+=B!1)gz+Z{fIR(3Er9 zJo#y$8jPPSCd)d$Yf>&?2XPJflsZE~O--c-oAHGRLyV0dMs7f6rp6Q`{edrqZ&FV0 zDg0ZLA?2LJqN;lNHpiHgt%8kYV4K~xxR%hCigN#cBoSyUcNY^1X9}_=@Lo;J5lf|F zZ}e`a`W47B5(aFk(7MQNtVkzRo-ND(9R7k%EWo~d@VE4e3$c+0@1}!mV?K_%Od(tf z(Dn|DBZdjCnc&W~-+P`QcrX=t1YcJa7zu)!!^f(kf&8IszD!yFllGRx9O4COxG9uC?h7SSUEkqUwU+LdUR2GbYXgQ&-Cbm^yqGBc!$fKoxcV! zm5WQnKgK9IEqUVYPr`RGI;&BY6sDY4aC`Uweok5XB#(c(3WjnHmV~r%OLk;T2fTZ~XNsy*rBE%%|JMzIFeyNvtA{B3X`yx0Pb0KT&dcQ)HgNuYU0a(doR z<_YSe6J$7ohTQOEVK2osRmG%ZLOoEp!_}Na)o{LzPZ{MeJV6!8jN(&pS{)&D&<` zYp(b%tq+)u2O>YyJN#h&zol>O8 zI1FH~sPz@q=%R;MGzCS@^aBylOD;(0_S!@uU-CX(E=D3nY>$!8!vKj%6d70TOsl1jdS|Fs>@{@xybael7z`Qu zbwfQ6+aT{tL+ZVX$^Z(oZB!*Ds)u!nM3O~GYnLSLXRK;Q;aeN~dXCt0ZcDC;OJ zjkPz_xS$7nOdqt%+xzCS_mJ~KQ_x}q-4;~)5#wl~G>3PdNcTWk{Y9 zWfK5fwL+GJly@`s;P76IkVCDc1!t9V;zO8y$Rh-=Y<3(BeFzz zUCPZ219Q2Au8MLSy1-;c)n})=z}yckIlrA7pxnfjGe!6$=Z$PG6@QSQV5RXEv6!+7 z;xwHrL7K{Jd%X4|_VmUQUO2CaKL2MAgF^|Bu91brdwOtx3H&*wgnQy*!rBq0^W!l` zpz;y5j|I}gQwUOamb-^_6j4tlJhRVPPk3xT4jt(D`jd7>^TIG9E-iKSnCYXO~2g12p>8rM;-(IBT_Ed4YH+XLbFtFof|POw zl+zEaDijE($ik#vu}mc8WkS7FT|RXvl7lTf0g;?P=)h^~nT^H=Sz2Vp=yE}ts^Zgj zc~0GMVIm^Y6~>7x9feaFJw98*!Vy9kRe*AbYRZWr#1*C~@qpNBGw$sT*1`l8!l(3O zRbTnl43y)bfFuqicDKmYq{5zS6n5?9@f?X)J*p*=f)a(NJ3kfd4CiPFU_AJ82%n}k zrZA<1#NgndD=z1@2r~gAuQ*WVFmn+!Uowxx15qzGcY*o8Mf0J40%?*>OXYV}%$O}dJEK+0<|H~7>ce?GA<<@92Dz_dc*()(A~ z-#N{4=>bQE!(7}c;Ui~{MhI=_b zI{%QaF8u<)p*Bw7Vt*8$pY-RG$6C-)${A9tUhlLW)g(?ys0(l#;QN1phz-B7Nl4Pv zpK$?<+hTl92ju@0DAdZuF{4dgjpWmKg75-jN{_FQh0DFfAp|x-VLs^xLyU==)QT!~}3BbBLISYi$1PPrMjmpiiH~wpc z7;c*qLxnJGg3m$Zhd5W20IK+UPyA6pAx6zBo;la3q$<^^hdk%pVVR&i0?Ew|!|)Lk zvOXC8+4Tpa!-iqk3@|jGoC$`j&shr?eh|L0@i1ej5FXyfEf7(7I6Wf_bI;9ncY3sb zmtRoY>SD!5&D+LUuoi=6kv0ihM0iA0Cs;?c$-j$$y$sr9(Md#3qy{Vbvpb?I0Uo~_ z?xrC31UL@ZyIDp7>y7VCdQl_+1NKYHPkkcDoPPcg=^@|7W<5yI;v3Hb{k-@q7f{A* zhJHOi<}JL$i&hTA<8b5?kpSV z88*EN>Sr}NM{O)}$yh1p5Bb!joTzu;cPHIskTm%bO(4o;t3{lX6+g0hcQzAR`7=-Z zmRsCfXb>BgO$VwQW6C5C2Bpv!Uio#y=R@7Tf|FOgWf=tC7v-YPK1$dx8=91suIGgI zzD%L1d=1e=EiGueVzPRD=mCZ$fbW!(t84EjwLe!F5(WLar=V{^*rIS`d(C;yrkEEL zG|#O?a_;6Agg6)H#yYHx=Oz`%+kcl)8(+KT|D*0p;H;kB|EFchQZphVF$g6zmKL&1 zG)$Qx5rxQFS@YFUh%yb`uA8w8k!57d5);Zu%e3gWQ3%sQQ?}2TFntq)xc~S2dCvJP zcbVe*{rz6QznA9T`#H<=oM$`FdCqgrM}#iH8V^6urMP-Gph5Ea&3ZYY#nxd8ug#yN z+WEJ( z8L8jqb#1&Q!KRxY-PKKEy@=G$u{ES#Er#ZB0)VcO(=t$U&cfBV$MNl6T`URK1WQ`DaRNRE6w@!ht z7GiQV6;0zJQ8`V3pdsYg9$&~44B$I|l85uMp%qx4IFWV%3dUDw zN&kK<(u^*L60te^6K!?ghaOhFLW_FLB{KP;&H14}@*swVFrC!RldT3iXVZFTrV?7&03&oV`!XCmTfj^}uz&U&r@gJdlISX;gQfgkaO zJ!UK78}dW7`61k*`n`wvIR~*9`m7~JNvnIKv5R$3^uvIMuT9cbI|A4BiV5kNmW(=!)r>y0~dQ6IO)zeXQ61!Ldv`Ec!g+; zrw_6#J9~sG1CdA+e=WpqXdQ(v7SqMuT~1U&uqBEYm61xGgkiWjpMpGnzhJ+8AO}Ff z*3K!|w%?~#DyL`m_xcwRWw*&i^lH;xBzLso^s9%7d`j;cN$n1M_gD>INUn z{}q|(%EgaI;Z+xUJpH>eGrBFYPcAbzx8kf7b&7rcZ%1a1G2MAGb6dMqGIKI>pp4AC z!FJw=e%(tU9~yw%pv=6pzYfHcnY=Sn$xO$&0$Etv{ptYZQ39DZ$1gMg7HgeMW+vmc zE&-YO26zNyX3bTJGIKwd&nh#WDHzFR=Jqp_%M5&0x&V$WkJa16_o#EkPn378iNyh} zHg|0B!bS#^;4-0(vjs%yo?EZke0;^GDH1hX_XBzm=gQm_sH^=wFi7v>icG++2kbiW z3gm_<30P(7ZQM*%N80IO`H}SB(vk5LX@2ld{AhIsKIYsCti!duXl7yno=K)b301NbaF*lu0q_eD{6=7WoU*#vgXN6#4z7*G#Kv z+Dfq6j)!uMLBhHm!jPA<8t_oAzX)jC>UggxJMhTX!Jv?ri1@?v74iE{OF(?f5-n;O zK)gW@Wom1sp68*Q!hX$k9>F$|l*qhw5MOFze1c;x7kv8|pJ5~*2R)Qc^Y~<;Z%q9J zyLb;}p-f+?J(MYk)5LoyuLEgoHsDxAo#!y4+Ns96%Kh4LWHQzK)llRj=PHHt-n7j;Z0Y-^MG~?5ZHk+8)1Cqp^o-?X;R(4`Og6 zSonIQzN5qZ?^mM4!`bTNF ztu6{6-k?5g-NPX6>chQU3?|iwq0Hwt`Y@8yuD7zDhsiWJZ;imIgrGh=B@=G^ytTVb zoT>Gp4p{^7`tS>o4(LPefJA+Gir&5I!x^Wf)Q9j%|HJx_#wCKs*mHRd54VrwQGYY% zpQ4Za`f$0dEB;xe>5xo9NUjghysP>!@`MC^7;B0y)gnJOcOb)ts?yYl)pq>2r!y1@ zE8wCJ8}@EMAD-`n7PdOnlB4j*_HBhCzNT9O;>%3YTrKh=KHqG(UnDkH$qAWkDAM#z z3xl|;54W=4r1~&m8d28yVd#Z|ubm(A06C}+?SN)bA6g3H@%pfBFCvgy9|j>?G+rOR z1=0b1Sc}Ov-j9py$Bt!w=+Zrt#S z$nMKbS;f^C+;f#R=|nzgREg7uxGo|MDp`m95&X-oHp{@R>nL*2Bi0w(x}#zVkwa)s z?Ftr(?u${_2YMCb;}2jal((7bG8~Wk+xE*B1=jM*1H=Nid zAQho47`AhER|tzHm{>nuC4>@y`e!3$)?GDc(S!F7S-p2*#(12>kZV6GA^DM$%j=q^ zIkQ{SS_C(OzvyC#ZQo7N9=$FGF$0_4RgCqM0GL;GS&EIX+?AsGsRMxD?@9$B!_lD- zC%Yw4(2k~X%S1NdP#Sgm$-F5Wl#RdH8mryUS9alUuBI&~g>>^0c@Fk2^mJ!03stZ$i?^&)RvRSGI8IDrwMDecdjUk}$Og5E&q!v2 z(@R-61l(cbg74Z?@(7$ml!ZwEc$XPE1)Qk!$xI6tMM9ffz80``kV9^Z;gdXwte24y3bY(^hwBAI=YxB7H2SDTi6Nc?nS%aTZ^hN&OjcMs^Cfv z_xLY)0Y_`Rzn1&|xSD5Evy2)2zUvFaJeLCG9J&)&Y~I=1cwFl^tx0!|KOX$`AJ6jA zON{+F1|Zn)d4z|+6tm7VH4R*Ji4D4KPa1m5q)m~v((vWr>7sjXb;iS$8bX!Z7$lDR?B=GJXqwNIk5;Sj zF=xESQDZdEleXFT3Zxd|mn?74jR8|T;Vs;Hn84+)NT0=u1GA%n3!ed>duIL;t6gsM zO+BUY5D@sPx9osd~$BgkmkyDLP64oR3JfRW$_ehEfm zGt6&O+{c!;*6K_FM}6FYf&cWYzU0Mx=ZQ)_w;8Bvda{%0G-^2@Nftg~mLy2{@6}t? zU&LLSEHxWRUvQG@umH1guTax=C=q*gn)v*bviNRZMK{`3=Bh4dpt-RH&8Hh(U{V*u zZaO=VsMrz~`ekE&a$T$(U=Hjw&n$5w*LSrZ3M-7s_B6a1LN4}3*NC8pkcq6*#t58j zs{IHkRK?HjjXK%69hQ$&N}3o5eiFqD&jmI;&dGFDriZ7^+bB zg*W4=d(KKb@&w=EC@dW9XzhAKlr!q=4Pv`q#UMbd06)v&sZ2=}#&VdODZ{gYLOEo+ z8!Dk9u8?a^YfNKNVIHFo@mUT!9!?xqUG%ksVl?zfic#`W8q8)rEve%5pcR-4Gr?hj z&mH8x`2e-dawVJc9q)jMLk#T+=Is~JM3a=t2rfR{wB!#u`f-y^6KMfW6O)Eduuhz} zTV<6%_5f3(LTy$OPH^lu1p3bu4oA{I?}Q9{?+)t<+Bqz(+?bf4!EY6IC1W2PcHch zN*9sjg5QR{#koH=P3w!!qiC(?=-(wNW}YIQc7B4uFwWM800x~qL+D@DHO6yhg@FE1 zr-}T8FyP)gkh?+HVm76tzJPz)PYS;+KK<~|Q26^9_-o?e-x`Epw3g@y`~wX9?HJ(B zuaO_%PlU!1qhNNwXVPdn$LK z?u(;p#x8hXK_q?uqg+wM^p9R-rpzHRAIE)>@*Cf~<2;QO)AsgZpY}hw>ozn-2BO?F zA(Yq)vYFI>FmgQHC&$gukB*JEPx1^f4y!V_m*TiG?k7bZRKg9lop3{~q-B~UGtthM zCU0YUc<($DBP^O>Hpm)2TUt5 zR$w*-BPuxu(v=BiwQi@#>D{_WN+}vO8W;B5hdLnLXrgkAR6&%%pe-KD(ejXy39Yod z>E|SUzETJ3#wAY0V_=;Hgerv=tY*BNE2YVTnpK?YO?Q{eGtH1Ngpoy`6`!zP7H4ii z4fkzE!%jhR4_^9iQF;-&?vd;Uf{`4KsB`S;oFZ^ZGtSkAiskllLzgs=%cc1@O7mOL z3=ojid6;w|-`^o!LyD;>e$!-`%D%iXd9gMqVPj%L11F_I%XL~>&eFHZche8=)68?l zB2&b{AU^msBJPVUYZ?})o6p9P**cbj@;rN6mRxmI5SrI31TBj?s}!a%W20b%D>w{u z(p>z}lM-6z&0#E%Yk76NI=_5+xQB8l)(8)DyXvQ9GVoCx4s1{0;L_E#m#TS`(a&IJ zot_+3O0USmgG05(O5*)tYp;eNzXb!aO$5x|1`H~9KMZlJN83TW1IP7Y@v>m-6XH|2 zImH_9pA3%Xg3CIlsj0e5aeQkv8#svN;Czo;@T(#LVQcya@Ug?&UvPsAhs$5Hx1hsV?& zq02NEkqe0k+o1i+zrx$lS!W7};WRnK1jKZ?;oaLVS80Z3SMlDF(Daq^QCcY<5nSRQ zNOF|8U$Iujy>=W#Bz?(YmTIO1gwt=~Qtgi3kv=gL{7^E0>?0xKKvBYC0(Nb{3x{$% zIYRXJ>+Rii0zT3|GcOXXeH&|I zk$1Sa#3IhO#P$lU&Sl1L4VI8jHOC+!B|8q`nQMMga(w(ltMANVHq@5)S*(2KE#n$^NWz>(!)Il zm>hCk{)JxhBLyY-5$!h;87AW|WxKqH+uD=(uAY#8S;sBsESyqgr>k(Z)bKL z;=ER3T#l9sOuNP;OBFR0_F!Y)wETwC2 zF1x_Z<|6D>wT)|8P}@gK75k`j8@e;10}QM*t05$)fgp+-em}>u|HK;9~MXs(k*~GqG3s^`bhDOpaJ;<6` zxZ%bdcaaDSF!9gDqV}@CAxM)pd;a;!fGh5J`Tp?FJLw$4_?NWW6Rpfpv=%bfEYg=9 zAae+Ver8n(6~+p}`0QtskLLUN=-c}28fRY|w}+%lJ00J})ctpo)x zGwM7FpS5TD0nPygu5fR_r_W88`L@EV_)_7$=$ayR(e?topikGm_IQzeEzkVGU2?t( zM)*p8S?-oRh!SVhew4$3=3JTG^cw=Ujtdoz^)JnJ&u<+0z#-2r!x|NL&A!EX$em)Fbe1N$W%%vQ;DZjL^+)9pFLa`RJt7D0IT{r{f|IqVESIBA6tBFF z^LV=LK0<55mTF}cVveK~u%A9~<;H60xCY@UBp=iWmsl?>J{q^byGj@OJKS%q8qjwc zzT(QEXjFOH@V$Ih(0hLPhVt4Q^jRYDw*8uvcydHUkd@$C4#yy=N<@ZtB*+-@!&g@T z3G`i|h-53`=JZc^AkB}t#4O#}&|0*6h}kmr#f|FyH>p)iOiNxlFHtxY3JzCc7O)yW zW|PbkAvrAL7b5Ywbs^)b@GZI&QtD)k-K08RP9eL8Mdr;|uN}cLQmdtCu(XOgH*1wf z)a*z6dn_5n#VV9iy_>0intVb_OgCBDJd4nJ3j`G?bq4yagjMKQM$^y{s!vTl1S*L@ z*Ft=#Y1ozcMmjfNtEze+J1JV2MX6+`Lzhxj73a4OVp*jC`=SHBd&7~pETG7BMepm# za=r+BrMK?)?}S%+3Aufco7Z;`EO?GPB<%tw1EDvC*J`&Da;#c;`Vm6_xfx zMI{E(g0oT55PD+L9A44imH0gcfxyb)XUaEhmL~`Nm&={S?5a^{c8q*FVPaQzMKI@h<^*`iQ*H!=r`$ zmJlQ6fKM1Q)>^#&!58M?v&)HZV3F)5W(XJOMqRUc(LOMn(_2}y>BcgFg- zb$am=I`Sy&_3#to=g57fmP}S}W+|Cg$|odCqzkF*;4qSTfJPjp(w&#~63Y>n=g`1f z|K4?~Oh@C>Kkao>U7Gi~>Qbx#8BG4Qez!$Q*7_X)-P=FN7FUVenMvP>Q$_l=Ie>zc ziT813<%L_4@3JSjBK9%p>fkqH3GN=il0Du28A~9a(M#dVP`~AIrY$^hIXYMg6>ml` z6R6_$mbatBxhO<1p=dq|#cv)bCV-nIh!o&T1GS^`L4#UmQB}EuKjr}u{J1bqy3+}m zfj;qc2XfUi5QE1~fD_8yhDRVu)H(7I&PLqaauids9G9a~ICq=1;I7ZMFky@f(UPJn zV|)cxKhde`EkdI~{3Bo(X*k!c5yKh7hZ@cTW%jC1mD#iUV~~c~FlSNctc8u!YA+91 zfDse6#lpEj0FHx4#~k8-0g0drWxwSUBe!S&`G<)@n+GT3f$_p8kbt0r-wR)}hgI!> zkBex!(`PJN>M<*y3n}|Db;S5t-ggTJ*ptQ_D=hSN{FIcfD4%UR_5_KSG8xU|dnmFk zR@+6ShI<)!ADEGmOu4|dAGr)s6#g|w2N<$&_`o)HA}4SC2>U(q4pkAfdf)C5 zR7m02{Rt56)%&bS`fFNkb12Xu#^DO8dWLdWAzf=Rxdy^uxNtOc9Vixpbm81p=xoW4 z>M{*P1(!Vg9>ZkF(*gOs)}}3p*(a;SuRnGz6K3W?PNqAmY@rMA4H00010=o%641xo z`h36$kNTQMgy>*X1+HZe4fu8i3B$PvAh<8rcKDVTAu#W=LpEnlw%v6BUH&PY6$m(l zbH8pFP9tyEHy)1Js;|c&s>~pIg_igXGllzFMm30fl==o?^U!zaz}6rXsg8d+?bW-X zjRDnh%M_19cVJ>gp1dGjlPOH$ZY&JR{Bu($G5TI+3AqwUU(nKB`ihLCklL2J$~IOK zjEupOYZQnfPP313euu^M2)%%arGdG|0IO1RS(VIH}c)o>i?jNINj zTnM9Buo%okjIsysG+pGpYa1Ic@YQCRSWFtFAbRfx^sXV|;ueX9@T1*@0(N$>adZ%> z5L%$>XpQVZo?XT;4*UwsH}1U3_&Uo|2s|2qyRUAU3(ivFj{A{t)X9u859^O zqGkL471IcDbG4*y7tZp$9`Jw-y*idrLqgvu9BYJ=)yZ~ z@Zwj=ctA~?9%UjSkbN1ZNTa}tq@S1RibXxGVhTB4szUT+SqL0W}hOj-*db-GZKYLJRf?cohxcc~=8?jz_FLRi964nM~Fx zgh%Ngn0JszA~=ayZ1#1Lx>k2Y#(;zsj@GWNGb_5wNK9i{+Tgp@HL)zavQTwx-`xV1 z#hnigjeg%)=ciwm$PMR8rjnRC3l$U$w#kP9dBZ5i9B42!vk4?Nn1h=<1*Sy%gO(CT z(EVN7%trFiC$UkD5F?+4brcCnd*2M-fd%~(nUdA!;g?B3)J?Q%OdqgAm_CX|)u#=& zN7XSp;l#y##jZI<&TTwu1i(%V6+RMTu)1Iz=Bv^9p$H|-?^7{C6&YC8W0tJ+WLF#B z;Ckogi_mH0^wzzKHZ{r%m+Decz@>57gYDfpjfoKi^ov~Bv2ek-p4j>cBVrUDHL+Ky zvRCM%o}rJO$rX)Jdtg~!(SmHYg5Nv5MP5-YBw@X?U|n6Twx$FG@Wpg*t-XndRPd_q zPV(ZT{0`N0RB>rdqe^DlAg41w(ymFb6V?rH0qk1mhrV-eXGcHeheT|C0Pz`tN(Hq* zpdy|_w5xR2)z9|a9Lo$}Yn+OL-Pnz#;H#jAQZPBp-2|qg z;9aQftWF07BUd}VIG9q<3k<+ z#8r=pi?|-im$duE^=RZ${VKnj}>JCz4ya z+DG@}cCvI&4)tMHt}%4q36-78n%!o-XL1Cp2SveO<-ycy0+W5gs52ZQ?zDkZwviQSl>jDeN9tvf!> z86rI0#ZI7(uSd6SCLm&@So7=k0tu8w5%|<;mR(f4{lOeI||od&;Q+eG6v2o zNY``W{Ef2m2I$vN8DFbzX)F8Z29G0s&reG6-Oc`s^vTvfD0f_XatBaU%PuR6wpXiatp3^(UArmyt&;_-+46lBfK}PUB8t1XC{Ko z5c6M=I=Ln9RZfOebs!El3NA{AGp$S6=k^s`xeT!DNWUdfM+pLFlu8^W{FG0edr(Iy zLH3LtqMXi>4P_Hi5S5;&V@TrhYPQt)gcj`;No%VhK_vAKti}R0y}J$cy6y`48E{#r zz+Z!xkvkEdM!>^ZEJp}Y1-qxfIX|2Qu&5n%n2#Msz_Jn#%J^Wkl()yviTv3HH@fr; zQ!YyQle&~2?lzY}3Fn7Dg;5A^7leM(T%FMT{Lr`L(aU_h6rGw#t2s?v9!-MO$Wttz z{ZZdf*b|Rl_PC_Sz#fPaJmm5 zdzKMHfO>!gG8)ko-*-7F13^kA^|$*+;Ij*E^m&U`NY?hRWNqEK0`n+R$dS_IyFBX2 z_o0%J=F{b))e3xY3mlJ5{s`Zl7o&|-yLr_N=P943oY!b^+<5)-W0trH2u=7ME{(Ec zb;7uvP_2X*lUV+c?{|Ov=-WZa6dff!Aze=<8=)!d^XY$SrIrJTRgj#O3@jz$F9(0H zaie6EW8hWdrF73-?4B!=BV{ix6zWFhqt#dVn6pKxdkelhd5eU)i}N}%KBF5CR3yf7 z0)$4=9M*9myf`cB96-sFWnJRh@b%wGIKK$PHLwv4Bh-3p5R3}US`fajyGCG{DTc#VA65;umdm1^ok+GWtcC5bC66 zASe}egu@-F;2ijRYB`b?&nL8)p`fj|W1$FVao0X2>+i0sOxtSotaA3h8ZG!}8Dj!& zaLX4hIEZ=B{%AoOt~lRbwBXt)+ldyeUGiUw7Cgj`Y?LM)QqxeJ>uP~&q6Jl3e~dZD z{VYb&AEj~E+18SH_F*VYW4z_^ya#BdagO|MY=6i(98$h`yx&B)u_bV05qc~boj9|g zO4P~b>-oa82B?iRbo{h4i_9HI;(@xk<5+$^u8`>&=0r1^KVSZtrP)2ljhc%`Q#gI# zMufR?BSJSS)}HUz>AV5?JSf}`(X36)u1zZlZO#oj`JoMF4(W{z7^+nXI-x)7UZc`v zOTr}LpSM*9dA@2KfMMjo5h{eEVQ>OWbV?$p{=rK&7c$Pw2Gc7eu!n^ed#OJSt5EYD zH5cHsS(*!Q4L*@X^%6eb1-P`CH3S;zym-1U*bdIt#1Dw?N)o5t3y?~iFdcOY3Lx2d zJZ-U;Ea)b~wBxpyn{0>d4o!IK#9ZT0?v&c=(P<@H_m(VZ{l14OwPn|Fo)7sms|L%= zkHOjuXkvzV-RI8TEHQ}g%nSh2|1xkC&`F+5K(6!+;P!kDAh!&~kTBd5fG&zE8wtP? zbyOd#2QkIPfHRNR-sS3|3*kpeL4`Zv@40Z2WhaTNL)&ERR8{fJ;IX!x&%ITbUHD?7M z0XfZjOXc)-yh&GlIYWXwNdiw!&)i*iMR!@0L{9Idxk!}L`>+=klv7?t3`z>&hMH3Q zdjZ)bVgqRu-p&=qC6m+7Sz-{q>}&ZheICM)Kyo=9E*I^1a@rI)$I0nWTmO!n9)v`B zi^ENP2P;z$4Nf;u5(9GDW2;~$DiRXx6XbNJRPp5WYbqTis{uLP@{B8|6MhQFX)hSh zfSfk-a^J6%s!`|SV3Xkn9^|wKN}MNu@XM(?BU%3f!w>oh6J2XtI672%C;S!N*UDF; zi(M|6(Pd4ew~*@ALVtCvvS6J1;H%#%a~q88G#+VWU`dZzvcF|-dy`#;w;)ydk?YK+ zn7J!&QGVzrXVL7xV!a~$YzezJmhLr_fLkSVnh4fW=XKnY4v&H;=IcG*x*5?kEJMLY z#As|pjMI&Xj55$&HzKhAzaWo21-5@i&)be`!BOnU7Ft(!WL=9_z!7yVl0)59pc>a= z6e>Gawcw$*0Tf(oCHfX0K_{(mVf{(BRF!X42*npw1f?&(VRt^&y$ZNx$bz7|GMOc!Qj zF~e7E`NOW7giyf5#zicjEEKfA2fRvHi$`edQ?A9grj$Ct=*$F+POKJVYF9pH{q7Ph z8)#NB29?MeOf7g1q?m!IvkPYU3AhixzN`~yf!4!0GHM|p!H(V zI&i0+XaU@MCfBMAon!|sIe7)9NH!SzX%RGnSIDtdA-=OE-aVpab;z)&OB>!wbWx^Q z5zNO?T1(B8y2yVZU032a{sj|1KKj-l70m+9PP}a32)0Ym9DG(e1!m$XU!qvb_aoqzy8R{c&&iXG8Dq@+FG&?z zfPWx8Q(s8II{gac`d`R`X`3Mk+bkF{AhZ_N(uzqX4^!gycP052kjQ9*&2)r(1O-%A zdm=X1lA=^cY_w41x^meQ;u52p%TipqC$hFLi7lbd;A{DA``S85)}pE%5Zl3yDa$Y; zLQPVZ-!p}>MWdXw;g`!JH{w?1(@=f~a-^Sm2Sx|Ux0zSpR3hFI^>W<1-0+ZCv;Wqj zLm13=DoXC^*xG3qp1Zr^?Wkl?JJ1pS84=hK`!UT2$=WD|23{juj^x7{lct2cjx@jY zPsY%Y-N+I=a_6o8OZ02lDyGsZtAAoaRJKL^Fm!PXpt17lhF5+2qW_HgjeOL1ZI6LP zar=As-@Z?lAT+~xI>w0bIUh85|823owhQ$|U!J2DlCS>2P45lv>=~4idY3W=+lTxc zZEw9QKHWO`XqEOFd^+=%mPYvQocx+NnIdP)T2y`|;< zlFW6SvMt`-QjSqww7s`ik&WW+b`{x^OTPl3FGlUb*E+fkdwI z*Aeb7A-It@+P&{eN)o)t5sD z=3Wt@z@CwLVtxLr%iy@c`-%o~v6t(DOp zVcu^bYvw8K%0WiPNgLhWp*I-6Bw@U)8Gl$l4~SO4H!0u2?2^ZE%E6aiG7&#*SiX$- zmr8kiK%B^*vrh?Rm$dwXt-I;&?gMLOKy-Rc@I5}qWZ5#{E*=l#TCFbK;Ew7C#;>^L z8@IW89s3M!?$Y!4Pe%L_R(ie>zlfiK5oaS^E?;&YWW>u(4vaWUO3jF$T4P6?m``&i z$Eusyw^qC3OiwY+BKDLdpT=)XLMg4aspZ;koqM*wT5YRmeXEV@T!nL%_%8F?6SpK^ zH?CQo%sR)fd|X$rVI4kqx0E{k+4G{qwer!b=?k6?55gno$>(=OhmR6uVooxg5LS6MUTy8uA2d?}+ysp4ugeCz$iOPcqeB+qH@Hk&}6XFFz{;|5!d+ z{elnc3I2-j&T*54;B}-;0aN6x7P_8bGvaS&ykwrB;$r5Gr=<_RW#HeBq5D%`tFtLW z)_pYgn3Zos!IQy;?SC;pE`Wxu~UyH=W)W ztL^4!CZ02cWaTx32aMSo>u@_uqJzK+4Ba9oz;`#|#R4$&_{TRcnm7SK&PNNgjK$%X zU6iQyRDFDe*X1pie>$#yV1yZ0{LaGpDDvVc?%D{Hbic=uKbu@Nyw>jJiOXmA%qqt2 z<*6_K1ZJFdqB+QwFmhp*+-@wz56P8GkdMxVgs)oYK{}%J-%>p3qjt+SRh=kL~ z`(WVXE>ceq?912*a|rwy%)^C&>{yMpln}^Tq<$)&P)o#nib_!>&=9QtEu17)sDbm( z@>4R(+H?BBogI)v{A00n@Re?nQ#>iArbsxmO^b**i&0dF@7i%o-B?D52X`$EKNZD9 z!FIY4U>D`S0ZV}?*1LwY0~;9gL0$dTprhG0C%y& z0}+C>H`bh3dmM+mbR{J+fXanH#hL#xo`)7Vy-9Q3Ykme_o!>ta9t`o_T%RSrFZGRU z7kMj30i+(|(6FjV(|K?u5+q!7G+=v1XtjiRCthqpeQ}CWZZ+N7ITtFIs?_#O(A9jE zX~@BGClji|4bAE$X(F1Ui6k_rxq-PuqsiW}(e(3;CZKba+&t@v`<)||+zN8$LvAdm ze9umMbPb^(|E*wb(JVA+%*0HJy=;7o)K0Pu(Dik$YNN80Mt!Bnt-_K7B&4t;ea}uy zR4_6ThB!Fit`M2X^T|Y}$b^`zsPiK_SL?cCuQwTqR5i$6($||XI_aG8te4EQn@Qc- z%0#;$*6B_@G4sFY#G++(lXip;k8qDVB_Fz3!g+is<0E?Zp!B!|KFqZZP%6d_T$0Md zhgx50Bak6(MDDdZV!5itwp9^M6R5Fs>4y#TVgDcPofPr&-||`zG#t<@@-ESP0IHn4 zBu4D%On}?tB|C*4O!fnCOh!HDdN8gExYm1nI&g1;v_H)f%cK3r4bpzIZIG1qZE?I> z6(;KJv2r`KuUp~jz7Xw{_cQ zLlsc~@6Pr3G@7HawN)I{(HT?*2&S0q@Ys!W0C5I5!lIJSd% zy05NwkVq^#!jht$d`FFRK~LA7YX2_h6GV%K?<^;c&7r`tm4*9h8`+_fp)Jt~w!U_3 ziC`2z8@W>tFDGz!LGU#Ai}BUKoTIc5-+=F-16eqS@e^|A}&QD>yU z13LXUqwaMmk6I1CwDv;wW2#)BRcg~%ziSis0SDA zCHa)0Zo^mS!o^~W?9C(bw*I%4sb+yk5z90B>6+>!5*)`@riZv%9TXi5=5?6>v37H7 zZHJ$gB*9`Cw(O7!%NB~yPL{1VENjXdhACe%HzVXPovfwOcAT^&39J1i?8++AAM!s@ zr34j{c{~6Zb!JE(LgL3kUFYXTE{WZ_YzUNZ3Jh8q4BA8{JSX~fCPfsd?mmZnNm47< zAY5VOPQiXuYyCv%05<^SMMh@5Yk2N_0)UXS&`K_iL%CHMGjdnL#$AYt6fEsPwRt&l zH3x3?mgH5gZGc%6=le(~S=;1G2`%(QEfq^}QXMPgmg(aH(gY2qsJW07H%NqW4XF2c zSEV$t#}=@@9UUz=5>)jTEtj+7FxD{1)*xprq` z;M%7}bH!clUD~MOIWsk?Z-SZsDXKP3kmb&}G9^cy>%Rq4lJAwRh3keL^PlCTRf`ft zz0BLy8qujc`GKTiMxC-iZb)$a`_xDs$LvCD4G83q*wpZ5Fj|JzJ|wFtvp0WFk#sK% z>LWj?&FIWp+y&?c>4^=$Pc2h3xPV6{8Kuia{4$YByFdP)om67aevg2F7*!1EsuSYa z!EROsgcpN>CuI0?u#=K6r%w>RTp}N>ZpDY?%g_k;@k^F0a0npK-kU0S~v!tE&HPUa9XC;KHt{xiI^F;lgL~ z(W(v~mJ45n!G#0wZs?zw{Bf4 z#{K`AW(9qiIIrcv2Y#_$i>ZgX!WR{2@7f{%@&xuMDm15zLt5}oEcqG5EVB|yQ-#O4 zLvFFY6$(?W(~;%=d(12zI>Ep?(EbG6@w?H)Z$oU&qRMPo)jIz@&1yrai+R8oU<)hZ zeN-fR9(Wve9^D}CwWFOu)u?kLX1<``bPuuR4cJVK6z53h{x{js_)1}XFX8BuM2FV1 z*J}le%+@!|#caKJw#?QkqeDl@a1%vbX)+Ty0!cxmrB^dKZ!M*OMSIjuwYuONti9!J z7AOa^Xu_9E=)#IGM`y}2;&3Y=C!vzGpL$) z%w1xJi~?i1gN^lbP4oU}4#|_VY(8f7s6CNf`gkUNE_$A1I2z6e9ppgPx6A8d&VpI$ zdYwh)Y52DcU!6bRV>4cOuU>_ZbXe}XzHs}1_K>CmhDkMcVUN|7zDgmXMCNCVG?P-6 z*pS$UGHXX@shlVFDznTyLcf4!pA z(R?rw^z_}nXtmk!m6!5*k`-V%4}GL4x^Z4$B^)o1uo0Ls?6O@|p)OrjSK#_`ivswV znE6d2Yzh3*NIm_N|1f5rU_V8nh#Bw>cscbxHA^+Aw4oEiMCjZ}z z_wiKY%?{WkY^mVzY?T$^9{=YhlIP7|qBV6}T+bvIMhB^qaEDQ6g|o+E ziD$O=7ImsVKAYb3lwac06una+iCP0x?VzGx0F*nKykbeuLDwoXr1cCMj=31*^JM}y<#Q}us|NkQa0;dPrH-RRLs)xsN}A4 z7R}}6u=D;R4MN!+jvGK|Ykd4`I=@y4etTn7DNGH|Hztz_GlKpV9vyQq8+jsRa9PhZwCPawQNhNfkLZ-q>#Aq;9?Ds-mPsF^VD^m^dH zA``GP^54!$WChzjjod}f@V!AGZaHR)vEX;CgKFb1wLv_}o$H9Loi!4D8yNP0WUxmY z1A_9OF#p!W1R{N|NS`|SuBwQ7cm}=c2K!XI$XeI{advEjn`RW&KJ^Co)%VC`m`M-T zn*TXC244bne7=0Tb6q)vAh5ajKR)`QcJzrdWM+{M!79&Ob+eO1;;Ix@9XD0VDRKXH z%r?1T0XE9pp?RdyuXYB3If^=Mi+}FF8CIJiJ)nRKjG<@iowOIo_Vv!Kz|Drh z0R?|Ba@Q;jpHbfQfp58RWvqXzk-# zk8@j#_Y|tXCX~C*-yZAVjCXR^71g)QxGx=cAVi5M7IP6vzkNf~v~bhLc~`E)O9l9z zILr;PYTZlz0(E4&x8@UmBSYmCi4|O{)iB|x0**{t&2)Z)Cz)3BD!)m+XZcO)J;rZR zk9*TvugE^Dy;C047FJ+Ul2&`8ehk)+LDE6(fC>cJ(rWwa!?Pgu$Ptq_xIa~`7ikQ{ zr*C6n=EbOw`(B3NF=gTVTIA%))c|OT-^X9pI88>FLfWNL$4eW_B#!#zk8{v#qA=!A zoOeaY>|v0TIC29;B$$=5#5fLL-6ppsjYis8xp{Q^qp)F-+|k6S#S?Y0jCU&Wt^56d z;u~EFDfsAdTX3)x(0M5jtx;#M=^=mM#T@0qQKUP!y$VdnEF1?S*o>pNH=E}rf3Uk~nh9#A9QW|PQx~&uAUY{f3(}NZmKTW(5)z1O`qvDO zw_h3R_4f!<`6JE&;l5&d=AQOlho`n)z#^qPkG~?Lo8lWCq@fQCN(Br`xt|ky=D7l> zR2rIJa;vZbKVcyr20qMN3cS~?Fi)zhe5ISWvb~^hWn1LFm2HFy*v@#st`6^ln=2%g zWG+(q@nQ%MvX)3Pu!q|2zVNB)WmntBY^r2Oq1kyLNId3-4Ut0Fwy4v08mZ?}{ubP3 zg8j|Hyl^So0_PGl#F2b&A<^Kg2$hGKkBFqns52+x^)(1>{sB7xSF2cBV_wplFD`{G z3l(1~UAn+NhIC%jU7mti$o+s3!SI5^Y9zywIgipt{Yo-0iNy)fSYckQFeg^nEmoKv zD{LPt%!(DZj_F|K6}LqTbM#6|Ihd4DyiS1H;g*}RjUO(<#ZTPy`XI&`xK0X$fXZp7 zndL%-(X9C>)Cx6KI!lM>a7Flq@uInSEng`s@b!GNzEDH6KR&TR`ZzxH#-0a=RHXA? z=JkAUx5mzfyq-@qhM=Ms(T?!I8|0Q54Q|Pj0j`C)3WW*2%Ns9Qi=&>z-;kDeZ*Z(G z19Ne)PI75E>y`v**+?oHIo?<*(vpMKXDCrxe#V>6u zX}RD5kpVT*`q~Dcv}~LzR1j$y@|e`zVQHCQ-bwbOzLV@a{8VWvQ)yYbTFu72dnZWC zl753EWzNzRy_jSs)otm4%~Pw^?PGRt&^a#VZ=xEMzXv>pH6Hl*fPV%eal z9eH~kJWX*XMu1y_@?wKj$s%*1{}i&A*8NjIF=Gi$I!w9PQR;d zXt&ka1`>c_Jq6XR2zQr-i-l95Z;$h71Gh94fzPa23TPHXJnu9Kh|Hk-ll^U4TE+~x zKRPTtd04^B{@F;73&u#$=DixB#YzK9fo}kunrnhEjv|aXgt7J;z?kEQ(Me$pNCjgV zVay4_XaZNdrg0EPN5Gf}2;&H0t{=h&U?2*9-I8JyFA>7rAcV~vMH#b|3@_0EA>gAc z0El%^=HdA!$qrUo@ddA7h0@z&vbcqLmBolQ; z`vHOk%arE|V<};Lf$S6C5RN1xgxO(02{QXdH5V)Yoq|m5Nv1evZz7D5K^R96hWOK6 z2!sB#JCf5B#`URSOj*dbK~}6Hj8;Jy?UfbZd=(E&qndLh0LVD&-T|5@?N!-l}6@zb=#%up?H)1|)r6(kQAlwhSj(H*F)Vbi?d;IFT6b8wO|KO+y+@sW z08CBV9yq4b1MmIvOxjHol>a{@5W}!nL?C=S>7im2nNGgrV&9&j?@96nFM~4PXrF(I zTETROywGM2H#VJX_Sp13@|TOo*z_FvORvBHV5LX;v`dQYGyYtAIvo8B0rd`S>o4+VEy z1KY#`Hxu5 zR49$J>ME&c)i3s_fh96U`xYCP9UIm@HY_VPtaWTyW^5R?9zd$kow^fJk$(mlQ`^@W z$*yTkNL{=ewYR&l`r`2)A)xZ~WAAGeU)A_nG}{7AllAio3yqXx3lM>x{q+Dty7SXx zDDp1)WF*_JV_H)MLbI!6w|4qUd?c=8_*51P&mzE#bxau$E;F|K`qvZJF=b{QQ~rUj zWBT9|v5JxS&~?nNA_krNF4J|)+wI(S47$aeI7o+ZF~K&pj_Fk=tzsH6EJ?iPmGwmj=2oSifSr(wkT3ea{`f(PStz7XPgNAFfEXB zE!bzg6etX2DZC)P$~vYQIt#30T4DU|I;I(Z*maEdhd5wJwC@tfXrIvCUB@i^9>|4@ zg;VZ2rbj&v)>C1E@fgmEQca2-=w1qiZ^ zu@KS~LZ?&^4krXz$9NFVC4_E?5CGsN0FY_j_WuF|1kYDs8JLtxP0)XcE{@lI4!d8i z3o%QiYcK%HbQ|=qs%ruCQ~)=|18|+^Pj{hpupo>{Z%-J7K^RxL%wF($JhQ*NSBB9n z9*XrtrvOMivwIW99zhsa5QeN{ZX^uxTA0f#avq^v_)~UB8?@I}tdMnZ|6$xFx*oa|M1I0#0WF3Pk zN-&=|3~?nmj{>BytS4VhfnzRsuUjdcHqTJUre~r`YDe>VoFoz2e8-ywWac?ATvLN&_(5up#x>pS+1<&&8na8gAD| zxuC(hw@>WQl}g>n-}iOVW+h~$NQkaKLZw5LON00Uu%ohL+{Dhr{?6FSjIqb6$7sp3 z40bG;i=HK&lxj6u%S?ODTgyl(`W`sjy66_#0`y0yZ{m2Uu4F6~UKk@(SX-Sy1tU-* z1P|XRLNHpuPp`&@w~~3_LCQfyK!wdPbHz7`O)o>u*z}3=w?zJqlfTlDQf@EK_jKNU zqExstR=7A;SQ#s<*DdsfHO?B>xzvzOL4NVCgs5So<>0&z6^?t#=aTPYM;EPpHIZ-xAo zj+AEAupB!|vnqrRP!}|-IkXABdKPT|usDvw3-2WtePCmg5poca2oiGBvmPO(6vWy% zQwbS%m(iytkndPz2czncFB8e<8)Me>LcVGNJDmld$ek7;`AQY@TqA2~5VhF!dZAUF z{B`87^q|w_u~Y+3){+a^Z-^tX5(xIQYNgeck#`B=Zy-%0l)_qGd!2_hyw`yAUXu=b zbKU5Z^y!J1Mx92=vaFinLHNIo68N1G;rn&Z6t0$ytXKa5W-YTs}H>#f6`M;X8myadYm0QVBW7-;VsbXh7?DWzKa zfM1DV5Ui`aEDggl)zpi5${h`f>;qLca`&Ugji@Ia=ooAbqh(S39vNewgvfCXIyM)? z;9Oe#r$oBY1!^us^iADyB|g2H;wAWO`CedL+Sw+?VdJP&6`$n3t=Rbz%Uy4pxzLwH_Ep z5BRJgnP442adZ%^%QSZo5uIUqSU-%W(Px$dW=E{-H2PDO)|zl3~JXv z={Rg5@U_Ckm7q&<0*~t|V~~*n;NcADT0A2DLFHi#dm4AU4*;HRtaZ8*5E&MxCZ!$uqXZm5K#x07p*; z-s2Wp0j!E(DPdk)CS8?!wa<5J3vU5ugjd+rEwo+Lf@`KLm#ZV=yYJ%luyt%;3^|?M z(X9=Z9OjkGb4!F&4uVf+XfLtEsCrzo-llt4#N&{ResXrIg4$wsY7fy*oR;`hf{3p( zz!#jBMn0Z;TAB^vp@a^^CuWCx@uAZaE*}M>J6|?Kg==0$a9Zlf;RUCq?-32Ok3ja_ zaFrVuL}Q3{xKt6$1qDO|o1aY^0zvSSU!K37?Nv6OA0`e`<5k8%lh$rz@xPX2_c2MRbZfLHE-iji6Z2mvra^xLe^ZI zQy@*w-}FC}!Vt z00wYy+tiy#S!Eis)SZjEc-Z!1GjPK9(qQ`GCO+h2Psn(u-vq2mrBJ&wL|JzwFfmW! zGAiG=+s%=K;{1bA-gs8RDARqT+;Brfqr7RFf0V0H7o+U@QPNS?{`_adqx|KHl%rg7 zmpe+kJJO8vPiS_%c>B{Czwk4(O0vA9kREIi!jy4YUT2pknu-!L4LyW+pwUzui%*z} zi}9hR;wLo~$G@qj;?dn)Qz2|lI|gDHE+*K9c1Olkk^9W@G8?^`&h-dFk)nYMNQh8z zrg$}_t@&YUg1YMm=-jHvS^ zw)<4CGwy4J9s{~P36{~-?FlrKlI0b4yB=O6FdIIA^tA!r|6fRs5 z(o?Yz^3#alK0vKz{~(Mr2}5>Aw$3GtIer+2p@D9gSQuRt#-NliniEDvhOoenBNs5Z zJ2F`y%=JS!fDmNE#6no5=HagoQjH>=5H3iB008F#08>9aD(#2L5{b6m7i#yYU6_GwBjAMc@&LFELB-U48yyIuY2Evd4xgE$^3ZpP3jHWe!@c|UX zDitWy6EN`62mpeNn1ucVblQY@A2s(**?kd*aAUB0N-G&Lb#^=>&c!kFAS1#GVEVE+ z8hMPkm=JbPgy0OurF=lvWAkn39Ve8E9a>nA*XiN#CgUq}M)=b8h1h#2*0wmT0Tm7(dnYxWyD;f=&6CcN?Z&<&;ov(1hK-a&e%QyH$ zu1k1$hsJ3&Gi6IsogJiFSZesRWZ12Bv7Q<4RAV2Dbn;2mXG4Y0X-ndS*0tdeAWmLV z!yC1IRQTn<7?YoRg+BFl71pliA+Q%>v{M~`K#tp;7yQYnY<{Q~?_14BVw1RN;(LB~ z`|q)uI_^w*#BQ4mOgja0Q3GIFr3SO@4uA>i2B@8X`}@Q-R60=z1Zsv$Rc3^Tk7SW- zO5?lsp$r7&H3{1Xz#{vjWpQj@G*#Jt4?e;6Pw=5^$C3vYu5BxmDCK?o-KXa@d!$&SOq(t zFkeu44Pnyv_6UFi6pV;pNG8WbEo^jtMn6rR0xCSI~oxujZW|hfbT85aJhOko&MZ+MoYPw5DAeEZ)@pu&**DrnX z=?}&YRv|9Li+(tW*-xktTbz2dYnueU%|d{2R$A-=yuyP$P{;HPTcFhzJF-q1sY2TgUgj{QcRR}XHS zR(rk={wJHUUlj1UMj(LzHD8~fpeO7?By(sVqkekP&W$6WZoWR(VQ#HijYzX|)k#8| zN(yy=Ul)r|%CH+={D~Y)Wz<^Ne`?SmC`zQMOvW%0a?W7$JyI$FwZ>6DQEGMcOP(Qb zkaKFtFP*RBLsMZick^v2c7?HNV^1|@jJ=;;g;%&A3q@oj1Q#3DEirjAmMs+f+=(m& z7CHi}5o-i4^5NC$Hr)QWI@?}HGViJYE)^1X*HHyVKm8ovfQp+5AM^t(K8(9AA)|1m z?Sq9EYhezbBC5rYNU8h^sA#j*ngxD?oJSDyhM96=7s|G4|{qVDdWmi zWy+CP3R86OIGIqjIaU)z_s+l*Y}{Lv@UR2j;M=?#ZOm9oCS%EL2QS2e4g3xtY6DBu239_!Ht^uzG;pHb;&v`l5}VWj+fdA@IW9gi8q4|2X5?ns zsP8#_NUP#H8Cv|-=a5Te742?)(kZAJA$TFo9oYKZf~wFD?I-HoE8B?J`po2x9JW2N z)qS*hkp8JVK| z7f6A!ueXkbG^}S16F<acGexccmSwA$L7C%%v3x5-Jo@Ju*Z5UMz>ioBNrPlc)o>rDD1?{2p zTkxSe|F-gE`6T7Z(OZK$Kaqn9>m<~`4GH_=b{f!&Jn`%NkrER|RQzIYaD>d6$5Nq- zsR@z}?;q6p=is!|d`-`VyQ=}6kD)4Hh)Sa6Ls;ocEV+5c*vS}3QGE+4|Lz%M_r|Z9 zdKsHr`%<6shvM@>cf;)I%Q!^Z9l*O;qt7DZM(&r)WVYMFa51@q-+5<1@hBT&Ic^&u zYB;sRSPo@Yd}hVfXNVe#Ns7oc?uH+R5259Vh~)?y46TC3&+-0bE~DVz%>$NdKtz;8 zU#pYbk@a++!LgbTK_quPBXaA^={~^$Biyo+&GhR~;kS}ua012i-boy*8e6fFBXd2I z6On8#cdWY)PCZsmtEpTIGuA&UcYLf{5CxU7ZiJq>W4*tppLg$FDC60T2v~^moaDTF zxhKa1mP8^ntggu)BaAEdsBV%oDKo1PzXbHG8l3a-ptlG>KUtyQk_eqvM@V_J0j=}< zi$g&@UHXO?I$DH;FuC?8345^qcBWMRht)$Ga*y zhGm#cF@{VTJARLWe#v)TRppyr#>VxsR(rY0^zvtQu$S)W#ksvxz`mZ|%C)awUKOyf z9lVl-!IBKGQOVN(Q6=uopIn=ZZn5I$aBw#TkZH)zdSRAp zb4SappnH22h#10h$s=^O&v`-P`UKYRHCJdzP))Tait3v08Pt~P<&`tUVAJSe5yMpm z`qW=I#&WYUySTyY2V`;uqBhsVdvv2Vm(i7!Ej*Getjiz;b;=VE2F;^vc%-uSxE`t5 zRAD7OPHtU*VNBKlD!E3wRlrDV$ld4pW)zPe3)SL&53`#x#8qSwyX%OFd`6EV5>08st7cadY$_jV4I%|0y~Jn zJc2(j+q4uqIXPi*h+?0nsJ@wt!|)Ce8!3!PY7*+p72&gCq!r8f_hn@iA0~+CM5hF5 zV{rZ)S_`qwb8+5Taenq;CD6$R=MvvMS-b}Vle?LKs>lw!$blkC)#Q>v56s$4aNpI# z{YYCVxSN?*&~JfTvQnXct*8F3$ww zavgz(;t;sgMfDzvg>5a0!2c{M^wB=B#iHm28tf+xxFM8mEJ+&FAkVz0-jlE(?~*jA zkOsT$IE4G8!R{#ieZmZxwTdfy-da$(nOA{W0Dq>_umi+o6*1!Rfz&WdzvS0+^S zJAZ_?&vc8i|+WuH!_^Eo!l*cyjYO z;z_*py744*`jDL=&_d?&D^3zO0zYN3{_<6fy05Z!Dqtp0N1_cnFBc1sL~%8qKYeca z0(cLeXTD?a5VcZI8DdB$F{-DYx@aUVu=Y90*XPOT6T*RxJ#`oWR{PaqIARK}gFFJ4 zF2cd@0|fN$0KXwJw-yM~dLYW1OaaEO#oO)}rLeO02+R!G)(4+3L-SyjRMxtxtnG&v z8<7DsaQw@-CKw6sKWa|XiEd2hz7Fn;wHUS$#%<#%cnoGL%Y-f&%=b4H-nx_DU51{) zB6CHP8_cxaE|7L0VkANyH5`oGov8bkNkF%`w8x>ih#W>}xcwQtY1KCi?)pCZ^AN2K znK1;0UVEY)S#f_#5$-nR2Vh@z75$mO5iGCp5iJ}hbxTL^0|$lV!?X~(^;oE3O!zD= zD!8alT1kZ~Pysj!aT>g?z<;L$vFrMl5{m)Mr_`er)1iZF`09gTUxJ6E2Mg_N<}&5~ zZ+Ej`t7U=f4vk$PL)S4QO=bb2mn+e?^GrMI+KOZj*%gwhLBb{%S=UxdjyxMZXi3e0 zK*{l5n-#&5{k)Rt!IIJExV=pZmR#eNj0u)3-^ImkaIoaX`Chow3jICzL8KJl6Krjl z9EE6L3in4L3})~SHyhp6oUglajLboBeVg0wp|<$Ai@I|Zx!?f2Dx>;2*z1&t0$kg#G5G~t+b`g) zxvuR>x^C*)y4gwle~ih1J%vj-i0zo-+viwO(ruRrt$?vQGEFoIfh-2GR}1*vg;f42 zSI@-_Ly0=mNra%m$(x5quzulUCATQYhDzz(^7l>rthrDLD9?6iJg>~Q<8iaTuLiB5 z%9CC)b0P6HvDDFGB4nKBb(SbWC7(q6%aM-^}ravqgjx zNbm;eCK#3lBa^XgyUUyH$zyS)&(vb7$LZZr>$1otYB#S zeWiV5w2p(rX}CQcD(kaI8=#QMfSe2?>imqo4$D`>Wzd~JrD4~uUMU*JSUEs~Rz-md zGxP>m8E8I>3<-vJvG6XE2Bi&-`*Y_+cdpk#pDkG8JAyA9xYGaZ;|QEJiYv(Puzmp1 z`P|+J-sa>L{;Gw_*HUi$p<89YS@{chpP!|ZbB4I_D)|8gdmj}*IvL8}nw+0_74(N; z@lDQ^%Fe&rmmsEa2x~D`0(e&P?xX z=6Kf@^$--~s(k0%_`-Hx;WArDiNU?WXC}gV6mTqTYtL^)Jp(%w?BRT`eWe8zK)z@_`w=9cZD~%B9{q;G9LeQ*cheGtj*eoO}ZA zv!{T8@lHYbDL$3Ce0Ky;<3e+vUu{l1mBq!^_|V10gVfqc=h^q@ z;^M${!O&c&5!@so53s2xcf7UiWh>6QJ!#yQwig)BBcECyGBR4aSO(#4WL|x0(3>d$ zN;Uh++BuijqmI?pdeosRWmKNv&I#;XTIZ!DS_Pb!>+knDFPGtm7ng%1&B~F9`rBvB zL@k7kOQe7LC?!VC61!4G!y;`sl?|DsYa5CQ*46GMOOb_$#Wx6x0iew}+Gb<}ZN@G6 zGgfoCuT2|mliNU>SLUP5QNA|cfjj`WM+0q~d1&*SFkNwbOWS<$bn5Z6WSjSWZSK}K zFE`MpVlmpNa4DR#v`t|HZPpOZKp&iav`vo&+O%ey4!$;Dogy@7-awnvVB>1G(gipC zc|+T*#;Pk7Ps`b6p0CXv+UA7@+N_z2HW6Q&Gqugl4Yc`;aBwlXi`$;srWf0Y$rk02 zJvOy=;srM9C?2J?f8U-52}DRW&Dnh)x_Yk0bnQh&(%PsQ-Ai@nc z5=ys#{I13`N88C9_buMep5uZHukfKE^4Zt(d$C1v1BQ7En;>EKfs>v8V+;&5=~ijaR*u<%|jtkyz@9~!U#rrJX0 z@#EfBhvP+EuL~*>|CP_@qXL?c+J9$uk2o#1;V2X)EKe8bp@rQh(ldQUn}*?i4pZD04>~Jn_JL-oU5}jCK(#=?*+zZbc21@ndy9_!5CGXub{}7i;cN~`uZ=}ZM zV)=7;S7LL{gN;WYyAX9^)LvfW)f};TVSaYd|l3C zXC$G>Kf>a@_DYt9usEnpOi&I)sve1C?n`_2NPz`}>))0Z5Ztmv!A(YwV+0c{Y(e$Z z*ofeMY|_1`NW{oZZM!?yr3+&`4ow2?%BP(Tfjo+sIh(F0nL~^7VT(iHoe3t%#-kr& zCcb&wV&QU`pdzDyr*;(9j>3}Q*u%cq*?C3RKZ6L{3wSq^=qW5Ye1!ay($b>EJy8K@ za)!thJk>nw`({|JBOn61JQjLS57(#t^{Etgmlw!nj2+9~?4cfl5}Nftftdh=7U|O{ zRLU=cm%gBen|3RlH}@nSY=WDePQ>>j1zY>1&;Ks%jsmrG)R$BbC1L^H+v3kak|B8 z`&{z21kHZ1NErld5ZfK=Z+BGkc7ucMMzG!QO?=pH-QPb_Ik=Zw zX7?X+qK)IR`o+Z%cbr0R#h(3&K`p1d% zU{tc=(lv8Vu+EL0$#ID>xHh|)XwdXDe1uB3Arg_`d%62v<=|=eV%AAAliSk@OK;Pe z{4soDCVvedI+J&UIYTUX+Vwh<4?fqO$;(L@8DrRmwRE*Nli#>=+)Ta#ow_smeEcvo zIZ;DbjanN{b5OWc#0c)`5g-sQmI2$Dyx$Xe#+m$PzzECO&_U%sNjrG{emgO-50#PI z(Lv4e{>DYg8}Es22c5~i#_zN7uQHPx)XzxX_y9JRncQn!#l|!Jjdw}jxC0u8=-7B| zzh~RK{B1wjJL!-+qpi;5Y;5$Ro~?8Itsh9<`c$GVGr0%4$0Rgv;&0qHdE?$}EHk;+ zxGx(o5;wpQtX1;H{m?jW%vZ4Ocz@f~t&)!Ua%;>vBkdSyr}k^KnaO9pCDUs;PKS*)ezTd)d!HyXg>Vl-A2@I{ z;YksGT>a{YvtTbjRTK_1RBZS82F^@63$DGoqB~$P)WCbHRZgUK3Hq;TO||#*`e*1+ zFdzZzsL_F_^XaE}<)n8{^-7MxE4@ydMxBes>6~upvS$)}EnS{}Q)Z7W%C04i&gN%y zC0!x{Iczer?b#4o=k1)ASoVOBF53=RNSibq2_FQkllM>I@EG(`RmlD~|u=nH=gYk!-t<0IM(10W;nEmY(a6vgj3l)~XD*i7_gg~FkdD9?{BOkwBt@GVG z`1Bw7xK5|L`FKn`d)^$J?j|4|%AIfe1keqt_J%in40qqc+3JJCREpS#( z+kZxlQfkI~N;G;5n%F_BEb1U5g>LkNHEIUgvXc0 z$(aeB4WPxtS2$r} zp9-0g*YXS6027G~MDV3+(fqt}8%9lYz@TMh4MRVUu>((~Rleb_y!i!mjzv!8_u^GP z0h^O6bKR920CilAX19E2yvqHk^6Bo%ZBUseX^QfG@#>DGy1U?O86@A0Ap?48S5EO( zwqNbYrP}YiYoAGI8w`s!i^H%8RnB);zLYA@cWAyhUgZ+1e73uC4^%eLJ}+L~N{y70?^^B2MC>4vizaO6HH8=EW_6tRaz$~v!l`LB4_KviTytG|Y?Wl(!$EcEZ1 znzXv1-x44Cp00pCnV^#a2&**~wx@5Q-=R%y1=6T{dfr|Xo00!1X{$1aGlx;Pm1oFp z3(W8?Eg-dY9x|repGHz)m;ekpE3OceH5Fe>v6^A15tD@jB*3owd6$dH`uS?xWZ6%$ zb^8WZYd*@^%>JTD3_HxX-bV4Wa6q3K#X0Q#DRFe`Mu#oNaKm1<>{;hx%PV&~Y*98e zZKcBxKSqr1>)v$aVZ;Zcg%P*o3r6%tq)ixsD;bCpfy;yuo5sX4qT>cI;x%|=HX}Yh zC?O-(4&i~A z!&8`DGNAL7c3cjxo=~~ST+Wb{kLM0Sd|$Ej^HcdsyYo<}awQF!4j!kWFW8Hhs`ze0 zC{Eig&9>#?LG2>2f_{8fLb+UVjmV{HEX$=8eu`Y)5V_1AE^-;wCsr=^uZLXdytyW5 z{YU%`JrP7t!s25~EWI%#<~P2bh9$(xRpO}Wf&M%+N+)2N<7+x z5+O8=VM)Jmb^TV)F^hHA-*p!Wjm|HLP;m_>`Z6<}8O|$EGt%AMGjCMdg1$>wmf#DO z9t;i&>y`+bH(x5OYksB8IzjW|uacAK-eSAqDfG^zF~n3I7^B`)lV@soJWsk!KN-RH zUF0GqO~ZqQU?&uXlu1+C5&P`;7&I56y3&E^7<5};O+d`RK=*r1qmmx4(Y*BK2Y7`<;T!luOwWQ)5mT9v_{qgW;*>K*Okghi&5wXWFp;n! zlkvlH$6ve&M#HsU^(cVaQLY*Ip|=?7P}^{%5fVM|H8uJ>!QmW*!&OVM6A5hAI2;BX z#3%rRFB?KD;65>D5d5c~6f0s3-7}G)&#{us2}TCy+mofW9gwKB!W&=cEEBkl%D>Q^ z?G~?aw|JpXi(nP2<&V!wi=vguC*qe5Gl&{;sg7u-@)5Ea4r3#Ckk+UesrN4Q8$NV} z8NQV;Lza?BL#~Re8g5mWQ;@oVQ?E2|aq0>B8HZDy7;hQo5q7XIY52Z9F)P9?*}E86 znzg*z5N|O-vEw2#E;1oz@)HFe&Z9{z1s(2$<+6GI(*gQI3Qg_kWzvnK)-3G(GBjZ! zihAf%ehV}G+-F!c`D!4tNu1g)E{WbrKEt{D&id0di6-kr)5|O|^eFL%axap8a4NoL zKiDJv;4CClXInhV-4~mF$$gPnX-{;In2L$+d2E5C!yd54p6EW=7N&-;C*iJaePQPm zxN|;pa;~8q)jd43+}Dm{%T;}8-{B*c+Ba3IKpk>+#(^s5}H^|?glEL zt<^`Ot1S=@JE+<(f&^pk32-g$r^67Domw-Djpgqc!o*n0HtghSd4sw~NUJz+MrWK*GzUF z3Xk2|J{&j`?&*U2C>!@jFhf)R7wWkBb?nUQiIz<3rOA0hr_f}U)+kHmWp5MMA<7?FxE zM!X<)lZz1B3nRW7B8h@-#y`C#HYv8bmKJfuQexz zfC4?=a#&DvyXSzlhXw4ngqQ`pPSp-sLKX~CcIIGw!Gf71H48ck3)T)67TkP^n+4C7 zF$<)@sP))QP+b~1L>|HPAoniT+3DB*1@~4dchA3L_+qX(2L3^;krZ?2)w`Xd)-~Nx zf@dTR#i1@%7PB8PC9OUHU(;fqDugssgxu#*>aRX$LNwo-=Q$ea@I8ML@!fOffUSCA zMFI1@pjo~6UJm;}*gk|W_&yGaE=s!{UIp zA6Gx-QoSJ<*^1~Ei6rX?iwLKSs!$fEJr1Ftya)QWWAqroIm&Y9rk9OBLy?&R!j<-(w!lk*Mbcuo&@Jety6r-%1`UHI6A&Iq*3>&0G;Ik-In zT|yIb8G*#Z1ouv(S5CpnFt0wtJxXHR#NA=gCK`KYiZjaRd8HF^<|zZgb|r$ZNd(RY zkcvkE(^+nq{GN7l-nzcFws)h{>5bqOQG_LO_%sL&*jQ~|e(l_e;9KlefyliRQ+6`-hNMpF>~Iz(j=38ESrCnx z`^?T;9~KSZ9)?0QVbUurpqy6M@2R+L<0dtS#;Bu-nu+VDAWhylv-v!R-z;WZI4)gT zB0D7U5-KQjI4CA_hLd@U&II{DYEQG+cJ|;wXx+BPXD!Mp@V_3V+t!r5muqLPp-jE> zlt*t#2$Lj zrS>&Ju|DSxYWunXN!EZFN)lsG}m6u^Lh#W$Zq+p+Qc<^wS6wo6FVXOE8oEVy8 z@|t(7W11EjM6r!hWg$kN3AGO+IgDEz0B zj0jDK&9_Gf(h8>v7JmWAmFrju1tqA}V63Ll9v>7Dl=~4VqQC{_Km*JS0#oD$b3K8< zMrRw$6kjkOpsL0uKwt*A!AvJG*eGR#xz`uWL<7toEUr}^;0E)oED_mI9`c3K&499i zpe$@i*x9UE1Sqo0L5p*iFPxugc@J$-FC9;Ca@}ysi71oB>wLjHXMpKQVC3+wjm~xg zgAG+SRU3T43^%}hho!p8&2Z@qs+!Bk7fVxi&< z-9b}1%nheM!BP1q(mXIm^JW+j4kZXjx*=R?KgYIuj=tHMvS}nZ@!SLS?xsf6A1DoH{{jzfc%#)9x@LYQ5bk~grT6vOeBM%%?u<;s7<9va3fjm;q~k|c>; z6Gk$h8q(PrZ3fj;KyS<`qgbJRe~s=_i+pi-n7fd0wiV%kOKD6TiqrV*czJ~=7L8~d z0}b9Bn;rTtJ5)(sblRhSXsny#$BI+~jhWE9O4KDZL_5rr#Ea>SP7HBveTDlDYp@V^ z7XGgK2X_I9h8~GP49%7|d*=2pvsAiw?JLg1(_!0rV8in__I_9XLQLXun$x}~osn_6 zxVav|Ip-rM=N@;?>rT$~?wpxU&JcIb?M_Y)cg`p$=U8{nIZjSPcTOiK=jUcFtm(|U zqNmKA^CuI|ZtFaE&PFHa33twiPR`x#oL8KjvF@Dvot*RBIk!4Fr@C`SI5{odIcGaL zN$#AEPR{0oT|DUezU`H*L=J{&_k!9{O;Ox=LVgt{>dk*YBRU3TomvG`}r`V;UU>LWXgfU~}=Glw+t_1n(biNzh0@U?@8%W?v%;F9uM`J=+ ziS=maIGaFcKKLGvAI_D*`$K%q!2DQtLA&Snl)*c#pFMbk zpHVAo0U32WSTk_GZR4#2Va^FZ&+21l3Z?6}+tGRkl+%KRuZW#tSA>aMR*3&4MQxIc zcgdUPcEbfLQ=bE|RfCXUA(kE+C_t20E6XtcQ5+tsnq-!%zRIuMrT3%UkPo2FN!EMY zv2m(887onz5(43*P+$j`wPQeNG2$Z0;88Hr>_~jxrQ(ZjW+wGHzemF)YdxPo3s_NP z0AO-a5g@oOROs9=jzz;b7qu#k&iy+@2|_Zgh{9G$u45}Q!M*ZW&XpV7YDL^CAY|GB zm2%Ck<7iMEZ>Fp-Lds>7LIiIC!5B<)w$R3!=7{`|Z`TH2Q$6k$^~gD0)T5HnquD%Q z2m^{33h3%K7h7z6xRKGo;0EhLEHzeeXIXHub(U;R%p0IEvk0@ApkOu!U&!VweBL3> zzx$A&_U>td+H$h8K+Q(znYW><5Uw};a^C^}8A4Ypgjx$ici9NNCaf9lQePMR^igK~2NlV+(3hay#Mq*t~u$*>D#7CvOB`-IrF~W~O!j2d7=- zqy@^zkd|4?B!}LjN8e)e@EQ6)$^Tw_P5G}AnsT}elYdqF>S(bFT?Ex3`5td2C&8EZ zToTs-R5^BFpDA0{KbEpfg<2oVewG}QvK{EOMA;mCeJH#ARH5uBKguq9(~q+AlJ*N_ zfB493Qe2reIfwaRQr1#Ywicb!q^w+I_RJ|lS)blw(p@r}`i386xwTvOhs;{}P*xmQ zW|^_tm<5VRX1mdqd?<_J06Qt(6*y8tJmgGw zb*o@0h`I>AKGY5CBGm0T-G{nfvwf*Mao66-F3z|%!AC0(7Txo){-Ic{`~#+fNP81s zleDizaFaU=X)XLn8~LiARu1}Wzfkss&$!ktZhw1Sa!i$Mr6?;$$MT`or|w2vu{LZM<~kPIK_vu8cg|PWoG@cUno1?M;n!f`dE2P;9u zJ&3PK+_xgO%Q^~ie|7aCuJ4P!mOu0Ny^~uU>NwhhQP@S@>G7!>3OReJ`xBOesGEzg z4|Vw+gt}IK)Lrp{FLgt9>>YI(BxYa@T5|1>xM{m4Q0*MA zYepJ}!hpuwMPZIkby4`BPBkg)4a!J(HRxbI6fQkpD7?IjrtrnH915Su!eBfK@B3{p zDLjs3cuI_4S$i*J7$hNz*;Jx!PQ-Asi^e{7vT0m~f;b}bFb|OxBF1mq3z3sL`}DuX z&yj|XkU70qj4%JHiPU!@CXOq_q49Zt8sD~)T{M1gCz~|h0wY2+cEQ&aq@wY!c0%LB zoqTBg=Gg=^F0bAj8V|7dMdh7mbfhm~1PHtP@kMy)L(I!0y!5Mx;8KO&&Xax6I}_+t z(PC72>bzl%W5=*|`-&l*2-BgNQxt~V(5Hdn>0S)qX)6rOQ5fo8K8<+Cs3At=ntU8r z)e@#sm%Hs5v2<`24~N!RH*V8xWeY%iln^A!LRe~n8M%|N)B*}iIgjP#jRVwD6;ql7 zgo(AM3E~f8VkoTLF04&bh(B?Xur?SC(9yaie9KjQsf=9M=D*`$cKE8Y?C`j929LC5 z#o+wGAa6l-cx2=3@YuBMP(^m=XE&iK*0aBW7~B%wcX;0sBkcP@xi26jT^37FnTH@# z5--8#5J6Yr3rVcSWY9%Wmo_4aPfk<>sQ}q7AWM?Kx=>j#d@dq(5XiY$SEB`kA?d*o zFB%}*+%o7E(we7jA(4EnkGEd%NT8W!sf(uNL@g?UuOUOXU!b9hmt@e4DOg3@fG?jac3sJ;LatO zce=Q9`LV*CUB|oo^GPJGz14^zQ1?Ml_r#j8<#C68D1r4|r6!j8x$GA$*b+o%FEMQw zZxIcYknK9i8RxEpCg`J#ThWn;)|c=Ftj}o9R#=_Mp2g?p<+nmiII4KU9#So{p%L1A1y&<;N zn{*m$AqJhMOj8t{i_x1w=Np)hy66mJ&lX{DLVLGNhZ06C95TjNHxpV^bs=8u}JdRtECv|Zk9jGQRx)36pKt4r|(U7Ii)6}lQ=(7^pD z?G;^%^+5u{)K*gbX)7uHt(6o*4?K&(#sKrp!%)prm=m(=3q^P{##$WFat$1Bp`_Y@ zcOFZR?5xR}6zkz1H2L+FY8>jHfej(*N8k(U|He#JsBa?FpO7w6U7BHc(fU$<(IA8R zjWgp=U!LuuelAKX>IboqW2v9@{eGf;gPOBGi!Z2eX;XiQP~Y(=q5jFglup-Q_QRmm zw0_UpyXhfNf2P?B(h+}k_ktUd;!=ZGQAsi492R#hBkuc7Gos$}n>=z$7wFEIek!3s z$3k*22cBTa#LFAgIeP&m>m{wPoOEI+fv5yMUow#i>}d7M(!>T7zS!u}-MW0FICyPB4<)>w#20wIf%&&3{~NVoiaO5x2ftYRNa55aQlsG?Y9CM>K z^#tH0TmFPgH*-84Bakz8ez%13P&EH8Y~+*6Q}`^NYt(VOz0Hek>+}*hW;Og)i&I9V zed5{&FU4@}q7@F;ny*aAwc}JwW3dDPzQad!;T+-GrH2UDZokIOwG)UGeda!DweHGS z4}gta8+YQSk;pFp*2_kUJJjZt)#k0R?>bYq^U~9yF!kf(@_*TU90e9y3pXU-qgU<1 z>gj<%zH0c+k{AXa5p@{&>Bk8fSfRoS`4U$66CYvVdBVV!X~MuW#=04}nP^bQHxW7( z?ZXMk$mBF@!*_pr&n~(Z>BET4fRW#T0q=dS8KCUdK50_ki!qEic)7!fW$23u`rkSg zYq(Wn4YTkOMqDV2I3!gV(e-LKBfcS898LPNv(_Z7M6Z2aew8@3KUp9bENP?LQY{Uen`d*JClsNsd6s`dYpV? zS1=6OmvvG|7rT(2xPg(*2hxQ=ns`?n`4;AJl0 zFS1||%v;rrS{a$b&Q#KYr8wk_(x1%dQ~GqS z@hh#<-PRLdBQm~-L88;rY#is4oG37%tO<_@Pz*Qn40Km8Lhh){TVU>TsI zIBU(h)R1!c_f*j3fHJ40_^+DNrdZ#sH6>i1*3PGKC$_Z>-JI5n;$VXs{cn)q+B=9!EP{f=5KRjV{-SEtf#%gzP< z+(>>j*aIyCqpeL}g4+eldf@Rl>Gg(&qs;H@c8h|q_=XkS?Xh~rA`vuhDigftvmqsL z)m&#oHX!h6pX>gdqM&lMitX7JAdNi8v+*_8^d1pYfBZpW>epAQDWH<@Z_~-tb66vt zC_F2Nh&96+{~#J%GrILS?x7fx2g#6v7|cttO4n$0RQ$<=z$}nm0b>ZyJ}hj8^(Kwf zK`uUWfD$;)(t*1RWkhH_hE$X9Ay|xSy{I)(Mf(DQA!tq8-z|ID(ykNYv{aSh(~|W? zY)jSbvCun_5MT}v9TreH>CY`SJ9j)do)o zQOAa!l!BGMw?9BRf`kt)=fSj6ZhXKuQzPA>3A8stLC1k}Pz12pq8#)NFlSfH{1sLTN>#gJ+Vo=|+kR9zl^0?5Ld@LSBWXAF?x%2OlPe zVBmQIMTfkBL4vRcdVFRQU&6k$uNauNO^JYkpee6ddnMGwKZOD?CTeXP1jgH~L~hnP zw6v|$&d+laxAWye{_T9bLhuSHX zz=%!nO_TPsV5S~JO(0%Fvf`1}?P`R(5y5Ln6~)zvk=lho#_s*3KPD$I{YX6C?bNs8gDAh zNVLky6HX9?xrziyCb&p0;tmumG`Ani5-AGW*PSHr{tiD$xP~)l3jSy`E8gF%<2)^t zsTTUMK+v$a1-D#;Yi~MoiE#lJepX+(fFB>-s1d8h^#DvdNhpmvhC=L@woE!CgaM(B zn_ebS#}j>l^18kCb|zk#kP~cjtd~UQTFwSms2S->y3W;fU&38UlE)AW)KI!=T^wg= z&Zh=1_M**U{%yWQ>(#Bw`M%4ujm$rMsRuLUvb5}YWr7lRT z>h8@=IUbFM&Td?Fv^S?$2bDv|<_eZ|P&STUVXh&hLhq;Z%^!2q@G-3nJ8}HDkz&%B z4Lu&*MJAI5I82&G5bXoL`7pqhy-+t8<_xlme8%??vdlPtQVIW#G6@0um@gNVh~1Y2 zfS!d^WrW)TOG>owf)eG4N{qvlsd8SN5;N&aF?#Ajt`>`0M`6BNS!k9fr;XNZRjX`b zbEwp4qf`VdmmEgqkllh-)W2<#?FlUjb2Uwf3zlV6wl%7&`$db%U`deM)m#$h6_wj@ zR8+HplmoCXyUsAZsZ(EPO=D*2uzB@ysDzRmj}cQOnGw3WQ(dpa^jzJ75hgL%$Bb3v zvvzJ4QtNnCDz7~gmFXhdHSv=-5DArW!ho#GHn9XnuGO}4>Cv$W4bABMyVH(Ew3s` z*XKG9l0>*r)EXuB7~rDTr>o$b-KFuyS=rqP*3z_WD!%5l>=0}TKwSU6T@6^-ZXd<8 z(1ImvqLK_v37K!$x2V5@1@o)vJxIEPCQxXqrB{XjXYCwTm}j!``=vm=tU zsSh@-2V@-#@xA%6HZ2pG%BEe4{^y#N&I48Utn?*{OY^K$F2S~K+5<4El~fmqaZ}o+ z%_eJ0HtkHwq^2C3Mny$JUlV|qP8ns>1Z|ebNf?JKYovD&l-Lrtz#Xbw8>a+6@Ip2X zGf!|LY8`ztN|%_WZJQ>ovTn>Ai`xP2HcBa@bTs*CDmDq-Db{ogHD3_y?ATfx6V|Gw zTKraqy7^uiw8$8{{~x6~7BfH$78xSdw_a_@eM`8bsKHDn-aYiSbAzZWrc6O-lfmN3 zj3sIL)nEjakR&V(VB7{9A5V`(X}p8dujvL#+}-iuJl=FKiuF^IWb9eX?rNck9Q#$;;BTx&f&ou%0+6n0JFWrYkR}677T2Oty$%nenGb%ZG zcAu|a#(ka@)6?g>FZJ|!b#}n(^r{$?^z(;G)v14T7uQ*^RAk6@!MDH)?Gx;R$~_3O0c{Bh<8}AJJxpnoerLCCV{1r+||04w@0UHr+KK z&bna9UQ-xn@8JkgMijOX3Qx5u>>;B2{&%79u03uFUnh)wDg3Rkrm#$W1Utxj`mvf) zb8cL#`DW}DQukf(KLsV3FE3QKDPdHF$ksyue6n#iUlYHb~j zyF_TF@;j`oYruN6sWD*9zz;oBDYQqcJArTIg*@0u_@6J$?A!)a&`@=T3`5kEJyZn> z#j@XpLX|C?0x}BGJvnTER<}hqy^jJb$*9UiNM|1d<5KyxUp6m#)9@s=Git4*qI1lm zdU&G7*qF7(9H%luMIw{uI1Q%BPD)}TR;ZR({V$;s9Qn|AY(i2I>=L^c_xyWzZRJ1e z1aqt0cY}s(YJWqL4d$??0j8D)2ySa&zQU+>d{*uF9y}yjH%j2lp{x-;6SqK^fOrViFW6QUd*+=8?oGz7`QJ3+u}W zYd6M|O^mrmsCz8iwMGk@c?eP1Ys@oh$EVkhPpd_5BCzYM)*~3<3=imok5)*augy9f z&}IReby*0hj)(ZcvvlDj_s1oR(6^kN+n%&@O58bJh(S{4U+$bssY%Jnb?3}Q9d%W+ z#I*X8p_8Hms3@;qnbtkUx__bB*+Vsjf!(R|0=s2(CFbXt5VGgn*^_sN_1_5Q)Bt|X ze^?RflL1f|fMVAv_)%}fAbKuwwimgs#`z{$M*o@k!m{>mtS#%D1Hp$#_ougsWqtB; z{De874pL24@}6;QS}ku>I`=&zb`%eH_%$!Z*quJjdzQ&)KQ|Ft^jDyzBvc*7!pT+_dpH@nN=x2H@Dtvu2Rr=)kE`Dk4p-e3x?5{lQNP8Q;1c{!Tm(;UNrQ7d z=ze>pzu;HCSr1I*?v4fXPHP#mnzbYT@= z>||^aAHc=dO>KK$)q;Xjt9~x1NDdyfL?JMvkWBsmO6YfCk5Hv##Avs z*tP7x!huzYA`u5d_<{qO7;9V{cG7Ju zt4s`=K6}r2O8o0oY^e^>s(6lt2^qe40=6Zv@&Np4wgwn7=AHU)+5KVPoj#Bzqty}u zf-U8ZUq#006)di+O>wklt=8mky9)cgLwINDg2uG|oUZrSFjPzw)vjW}6xeaSFtB#R z#~jw5UTi^Q`ZykSGlk1|K^_1+r0#xIlbUeHrCwE?i$G^&7(v569$9H!(gF;`$}I2p z(a$<;qqQ~;5&{#~@%t1jgeF0=v9B^?JEoCaV&~#vBnEbb13ONEtqbSSHm<|-4dKmv@C$8>dt0Z$3BeTmYYuh_SR?M8dB*yJ^QYalyUu?~s=bSqlM-SkyWjcTzgL zy6mjlybiT_8MS%owRvfF*tq*#K*uHp2dyliwF0~-jgdDtym7DKURXjE(Qn*)?4#Cb zIaHlNd0vz+dnpEG^4)0kwl;fYX9_N<) zb6VjbU2IP3{3L~{3V5}bJp#DueDYe1j*%l;ecd2w(VeuU5b0C1zCn`p>dhi5EIu^g z`_gldV#(3&ifN^JP3TAJ{H%smDGSiKlT@3LlviHp2pCyGFV_sc=>=)Xf}GZyWph|Q zT6PIK8ai3jszPyN^F3Da^yd2_Ld)E>{lp6~8m#1Zue(jr)mX`Olw#TnkRWswqTD~W5Z%ei6qSlrR2e|oub~L^Y&ZXjTp{Zp!(Fk1L(DYKxu7Wur@EN zHm^r*UZ!aoh#_TdFv8OMg~#MP^}J2JSM3FBv;)G)ROY0MiOd1>$wcPB(hq`B$jQXF zgQiMi)(~4B=%&#eU648vLxU8e*2%kRCjdb~K z;yG|Pw=G~#jO`j0Q-$X1@K+R`X^KQ5l}IE~i9{l`gCaE(-yZngL;FxX(lDLGCPQ|B z=A1Vo(x*<{P49<)b@w)OL3>OyPmw`;#RURF6=(EMfWB2!r;FGR1rC(wpj1>BK$PK_yV1p`e%8R!gy z@F6r1!*Psn3A|7cTV7p&!5UVi-8)?)OkLQO@%jSxG!ec}9Kjw|vWb-q2 z{w3fK5OX|{Xwtz_n<==|)i{)nDLBJu+^7m|05?20gq@2@G#Kd%w1$wTLSyyfli9Wc z0DPdPT#>$D5CcF(x`B(YB2oafwG|3T80P$WF1Fg)i-8D~mNy zYN>J*4)?%7W%6;n8~VYbk;hI4DByI+YUYf;p_A;cM6FzPgkyzwTlJ^KWYGLD2NhAP z_kV!7*SadSrkR)@PMGVnUh4$;sCA@)`MYGCIKyL#4~vU=W5WDyF=|YiJ{M8~rWeCv z%rXZE*+Dal>iqDMYZ#0SoTG<9AW*DCgDgQifhMYGub5h*zZlICX(jH18un%qv>vriC7fg(b}=ZnT0PB^Ejq;EmKraf2Wn*H zxmFaT=MuCG-_|Q(zp{;%>$3LH%-zD>iuCGg!t6`lw6O$}2lNZ0VXSyRxkAHo*QP#! znv2{v2b!jPJat(r!yWrA6yu-VlZT)f8&(@VmxXaz@%TA_E-$~j%EzV}W2$;7mhe&* ztOK?X+x;21hpG!@3K>nphKnS^Idxvn4(y#bTd7AW)oT2b%npUcv)F_e2Mf5JNmxqG z;dw3C77vd)%E2pR2+<@d_<;+cmP4qzp5^ikV2A<88Xbh~^6@Z7B_gHCxTV-%vWwYD z;-R!2rL>%FjbTbj*6f9`F}CHNiJjPSIF7yjn4ZVskF6aEOF3NRV)I?Vq#v=a)w7)D zBLNG?fmM$(4i5=X-JFhFDu&bElBRAi$9{5?(-coqdXWM&wx?bqKM^L%GG_?&El1%c zHZ{>Cf=5krJ3Co(qRUXd7>Hg#6&yxNh#CVzBTwe@qgVSJAxTZaGfH8J^ z>xpWcc#QJmk*8RKHAJw4n??$I>A{e@b+Xvp|D-JU7c$To3fvPP(*ioW)Tn+fgnVf; zDp#O6D=u!>6sa}V7dKSy0Gu=M&BV6@zCG~G#5W7ym>EknsmVS<^yh-|ZN=7v5jNp? z38c&(CQxP%Go4V>Qn&eT)b*v!Zqe26T;uD;ZSlufS1nSgrkZlvNyjq^9CKc0JqjlP z9aU*0FwrBqQKy>5{1<634|%7tf5r6#y!Eg4t^cmnx4RNl((4x~%MO`Bm+iQuP@z0@ z_BOuQ5=#k<1ImY=B-w6%#vV14UNEIMD!<6C%;4#Wj&0H6ahK~){=<(`Wk}VGR!ZQd zR2qc3VCF1c+Yj67a2oYo3NY9`9DgGUrMfsvmrmN)@Pt2=J_wkMCm2q2nQPm#d-A}6 z7}iZVPOhEDrTXXFif19bU02b7qTc)|hx6)MN&!mlCcMAg6cYvHZ@z-X8KDMLMy<{_ zZ;O?MDm&xV_|cQ=aiT!WFovQ}hyovW*E{l#qqX&^3her9}DO6 zG!N``1C^JCTQKZA#}c65vC0KGsD)o_K_D4rNuqLtrERh5UsIk4B}mi&Rv2KU*yP&_ z56W)Z(hB9#8Vl5LSQ?g6pbK}5$ASA&t!_xTHT_qbGilkxuh~!6JRq1{PHJ_2{F)r$ ztVo?dq5>;Bgn%%*d!xVkVE4DEz4~ZZyWnjGSyTAKp%r67Ipkz-p_nN4&{l`mqQWVV z1U6=b2eM-%Q_aT?{M**-_?Q>o$TSPqkGk89Uu%e}RjSCn*{R6AE`H5)skyj9b83K7 zl`Kg7n%~~wkxuLS*8I2B6dHH6^zt?>7=qgTDtA$#8|0`#m<$HY9j=_hZ8LLbI=8?; z9+_;w32#qEH1}dh}sZacwjz5RVpU@kAyWWg)l=Foxg}R4C zMilj3D05W-K$n(mw1R7Q)n-SoOCM0MB{>)tc%kLlp>0;bRl8~jL~?Y_AZm%~tg|{G z2d1fL5zm~Umy>WyUUryK%$B>z!i;_YFq47^RDLi#xp2s!{-M>@*L|@)1^X+5z$jR- zG)RzwJ(uP-4;J7Ra-fub#kSh2$|6u$?kq!0sJd}L=)>T&uXDRBAS$vuR*=jvdL%2xndn$8SHB7sg1Qp z%rrh%V%mBY73n>jQi|Bqe6vD4XVd=q^XS<|f7v|BIeBmO=oh?UsP(9G!rH!i^dqW^ z9yN9<*TJzW)N%CaXPn`!hjgk@$*o6AxnlkF2-l3-JbDK8%)X{Q6(2o13M(rPrgzm3 z(-M0&qBVY)jcJ0mUO_ddt&6^?mmc+wY3oW<^wT5ipD>ilMYgpH!$<{^*_P>`E&HVG z*AM)T#*Yz}^(tM75;{B0<+L6~xe|WvcdzZVy6qQWvr#>!1k|})cGHI`%t4fN3u0vW zPkAr_w1_>$E)S*+TwB|R)bk|eU$(o47^XB&_q)&v1$hx5FH(?G2=XE~tNl>$-0+YodL#+O7zbdT6`jaEMLqe zy=yCm2S(hf&H7I@W)T=Y)o2R!6At>fc^$W@rW)UZ zc~;LUF&w0^JZS15ty=RUv|J8e`z;h#EirF-3JcPFPPmke?g#vnw)4&jhV*vcsq~-( zUuKAHQLalHQml9Ld7KYwADr&ck{RjyqQrA)%IQTWEb~YeEqx=2VoLUHb^O4PF|O9bQhodY;P_a*8Gsk-#Y;&YW15TYsLHPmXSG7KDfRUw!NnHhoaKb# zQB7RY3EOXriB*kD3}@3p^@P(tF`QTG3+Ef!m>c4gD}Hp{QeQYT6T|6KUpNC3!j~%mT?zTqtiEva62s}zI0l~%u(Vc;{&Y$V=g&sJ+S3YgV9*7foAgu! zKL+Z$zY19G~nn-bBuQPy^yRf{66kA5`#fB zj?6e-;!{fnzwGoUI6Ju_^eq|k&-!2%2whLZgEz7;<%O%`D{jCu>jHeA3$T0kjsD2f z4|2%$fYUz?z+mL?1_%U5jP4=@)a;oyXX#389_=*9U;pqYonm=+z3KwIaVo+Mw#e${?9ac)XM@ezU#1Aq`f>J=1RxF0 zhI$AKY|fI#YI)H_mPvPXAS(e_!Zfgfrn(y_gg>j71Dd=d6EaP3J*u#IM|>U#!U6S? zHeg@kf&D+7gXMh;H`I3y_9NYpg(;Lh2U~_HG*&GV&cQl&wC4~0v!SQY^_f4Iixu^q zgIz>`^bF#o33>+M-)cv0Rm~utKw)cV?q1Iz_N->7nx_ocK1~9qSFQPHAO7i?LG=42 z{tRLwHD9pIo_0}x1wqPnLtxN8NXLxRx;=n316ra2 zN3h~_YIbNdElfSVp|-Z_1e)2=mTT1Ni>|{H)8VRul1P(0d1}E}ze=%kZi$f)(5wM0 z6}=U^nSn%@R`*5M>drqJah6fQBDA!B;Z;9z&lBW-a*$utUm-uOG`DF`hN)?5V&+UK z*0P%!p=x{RQsW_`L`|JSwf;+d4icXa)2O=n-1_QxeBN=k(5CqOELciYK^LF5-t=GR zGb4YI!UadUY(B3V z!g&u-{BS_1bU+*a~&8Wlkc^-Xazi7{J0;IL)bMQBj z_H^M^wf#q7>+kDgOw|9><7|5dUgY!jIP;rxxZ3eJhrCob-xnTR2j4qo?I*tf0G+q_ zKJ@y;e4kH+b=3bv6t<>a`~S=LS1>z@!}n$$zOR3=Zocw$<@7 z;RjJBUCFbZZf5gue04vDZ(nJ{MPo1Zq2wjoajB1=FY0w#iCQeh;@+7{ba@Xy{@TGL z*MVDyHca0C7`M*2{Xy{!SO3K0+hcv*eB+|Ae4}K(49TDSbI=xX%0G9_cAHBHFgf5j zH<$JelO=9U^tf;D?XA(5im1K4+Q%9O#b1Cyb^oj`o+#$pSzUbYIWijwRu|J+*fzs| zrEkg^J~m_TR~OG9Fxq0w9-}RWf1Ay?O=U6iQP}$W${3456Aqhun4lNayJ@ClDyxl1 z#_mosr(wGCct~S7n)r6bUfELKr=HaqzNU4J9h6}l2ANB{ zl4FqOt6uhT@v7#2g`KGkwR1`KwX9&~iyOp<`#wSizT}*hM3B%* za>hdn8VY`gtRk=??jrSK6i~Eo0GZb5qqLH!i1c3QyIO(ovMG+vze5Yz^lA=Ei?!rV zTUv6xy}eB!??H!%V+cp}9PtT=nRy86R&^3HR=P#?Py}so8ydwB^NCl#FSaTC3&dGD zBSGPmWz>uHJ_B?@QoRzWUa=`f=>ui@_1nVvfP@_$>KF;WbTVd+`xYiSCG#X$KtV&f z(j9<>+IdU}cdFrd$QZy%V99E*gTQ_!ci!c?PXMb7V1?i$EwIojDLNB2xh5&M4JWC? zE0Udr4qBs{`J%CN9g_F?x!O=%u@Y8@J zTILg+oZW>e3z?^S4t*O!li@w|7aiKp*^T8W+_MwdJ?0c0cBGuboZW?Vf<3UiTRoEF zz?r-|lvjf*-fhSRf;G4`ty)ZZy!Pr@-CB;rpnj0f00A>g{c>D1{l6j))yf1{$|1Jc z<0SIX>>>BUqk^zEeX<>2bluF! z6t*6`1Qy&m5JP_1|1{F_PKS7W?|+Ic_meG&oE{`*#NF%jPf za;wUJFGXSN=!^e<`QG=0cznO1Bjp(SKK|jl`M$ns9en?1r~SnD0|=1jdmgx$i0@yX zOsy)u2T|C1ZfFeOc}TNY?CN38#jwH~!p`3~=KP0he{Qr~;T|YHz9=r_G)*Cm3J;>bCpy6X1|6M*LnEU?e^91Z3Dr)0_DbmXG(NPz zPD}-sdVvSkidsY6RXnbrmCwAQ!KgyDao9LI&JEi52^Oa9-W&OZceR(cUvg~Pv=8RT zCpjBaRznPeqXp+H(!JBP29QzII^qoFk9pYk;NF1V>H@ubs({Xl1G#k+r(Ej-GVGE6Zy4trP-28uim8V zv9NL;>GN&@?#bNNk#75QMJKge8wO+&PYqp|*@*9?u4+d9e?cXZ4+I~Tc+Sx*F*osp;SHHzt4#-{axkg z682K@aS$j~`Q0MdXtYJakm6gP-_mp-}m1{~FDnA*M%xG8nYJ@AEQUXj68m z3f3z-^fR4`4dK|xa_gTbh^CMpNN>F#$22vdbK5{`Fk$1|s5KAPQtcO*b-)h$CIi%r zS_>Eu{MM+|31a0c*tdZRlzp3X-VmhI?$N%(`;HKg(LRZGh z+wcWlcjGbvx+i>2FcKLLtof#R6?<888Rmm@xEj~i+4K8d@an+0BImrzEc`i<2@Vv4 zrhLqeL0MHY_Q)|hjVn1~5}w8kRF86sGBqAWb7{%&yk>dzAP8d0GUC0S?UOc4gfLvN=%H$GWq+e(4JOXG? zodz08B^s-mDV1@*0|k`1f911Y^To?BTZcj-r3~Zq+SU9wKgFlxNH426G}XC&Av96l z=y(VICbA02f;piJJNO8MF|<+z2|iAR2&|3gafg@~6Gv5d4d5Q$X?OT_0*Bj6h})4t z$p%jrQ<5Q&KMy5JT>_bfe5h8`YTd#X2>%``zr6yPfn-x4i>Me21foTJ+7U=TOWzbo zu@cA_MhlqO0vQG<5Qu^5j>8C5Q@b)59?3mWV&D8%k~*L7F2H@n4YdFcpg_1I&r7(q zy5+fELe8bcj3?f8CC%n z75sCiMW2ZJ6}1|!r;%sc0!l4-pFT;sCk4Zj5EELws5Dwla6>a|=o6VHzYxp)iW@DZ)PncvBaL!`G%7{8(W4VKN_D7F zg>tWHl#ttmPmWav$(?oDoqjtUGiZ@Rejca5lM#Yh02sin?+0wHBiCOvET0&C0D|*4Zxoug0w}x(_F#B@pZ-qDJqs<+UqW0G+5E^rRN~O-7F=lc z9gc zG6WA8bH?LJ0}svu9>WviL68U!p)J^J8YO6ctt5h?)5@t`{4YA~Z7NNPVNOJGq9e87 zNhb~bkBAH4aOX2%psH~8NH@~2Q?^t}w0v+0E;|gjH$ZZO*_Ar)gReQk= zx{_3Npmi>W78-yF@#M<$(OQ^Mr&$zC|EcnX#xYe#PW>7q8eS7UcWbTsGlD-YD~OJ2 zt~q6fCT}o%Ct`o$zy?C(ctYe%ATku9tANM)uZP8BJ^5&M6)IqUt*WzB=Itso)y!<8 zGOtvbzqK@KrdX5NP`am}=Kw)8*XbVy)ojj_;%t&!EAyAe*j>YmCxfJ9*`@G@fUGJj|&rJe42w%OF;6dHCmMC7v7(4joi=p*SZ)#Jv9#R8(LB)EEzid~v_Lw)IbZOmO$mXv!C5Nr2(E-?34(YYghP|6f6sDtDlg^8eA1td0FNS!!KbP7wLi<@YYe zk#sku(%pJd_j{30Hx6HuI_bLImm--E&G1lnI8k>2O?_N~aZ}gSq3#99%S!%Fsk`IP zy`=6aMcsY(xv6VRhB4CpMVG^JMu+#D?pglwy#Te(4I6* zpKCa}il|q3Vuv6;2nV$5k9Yw69Sqa`vGi3JE#l&O1kZ+Ed*HRn*CzFSCyO);=zZ`W zChl^$rpCFYNuX1(4Mh%zuL9?jUgqJ*oO?yl{>54a%rb1uDDF!r0LD@_Hs*@-n%Uqt zMO%^kmXYhcL9_)W5PuW6su_47z%31*bX@${7+*ApNQ_+O3yS$N-wb?vAl-Or#YNHh z*0??_YE3@Yd0RwYk68hZmWFZ`ntk0^8=V6@dj%F^oWPxBh(q##nCCqI(>ns0M~*lR zpG6O{8uaOjzpdHOfpB0UnruWZgAJJV^E8%+j8TgycoO@V)DiDs^c2~wK$RM2rk`RR za+d8iF~3Px`-L}0E~MwPR0wtuU@rhq=EN`r+m-l)7~Ai$^kxHMcIG||8Tm-My~Qe$ z{$XC^Cga>QbwS7_(FUZ^&lrR z(q}0Cwm!kQ7!JG&2<@q5lCWYBOZb!PS;BD`bb0~?b?ozBlJnd14LQ4d#}F_Lgj^24 zUiUt2Z0bT&p-JotEai@ zgv~vWKp0Q-GMaPotOUK??lrEQ&)Bvt{{Z$j$yzXi9u(7-(p9eFaM!)WUMtF$m{0sk zPp@Vx$ekW06t5`Qt!F~ZU4yz9uyQpL;0w=#{0P=e+}A~2w*vBjvCbnKqo$N8*6cG} zx@X_f8*AekJDd?DP-KVx7ucn`v6GhV7p3g+0%HTAgw0!WxwKlvvGeVFtF?~n1t)ZY z6}Z-v0*bsw1SpYa?_SUmDR?7{asb%oy2w)MN^`w1AnSo5?|8hWI=GN*N3${fIbt$C zi(aHrIMU}X{B0FdNPuz02OM1d9o>cPr!7Pb4?Z#qG4O!`e1rhMk$}G>z;7ntC)vQW z8rwMUou*tt{g4$WYIUJb;?b77dN|tR=4Bjy{4$;S(MV7phhK{}5t@-cM-a*r6^nzs z>{so>3u6Vkc6^80@fohmch_0ZE0<0LrF$LqEOZ&a6?1Y|%+tr}m9%x%NiuQBKt9U2 zhp_3Vn{@9B^xg@ecXXiZRl#A#F!rC{q;($qDFJ7%`~2KG_PV$G8A4)@c0{S~Ox4lpA2f3QMssHxAHJ|zK2RR(1*}d4X zJhYS@s4=EmFkTU|W=@2Gbw4vSfThuPdE`UN^3ZUV+z3w&i%B7VLm)Jg^kE zwkprGbe__Z(OlXCu`z8ye!_)xw2Y0V zT%(4}iw7fmU*Inku=sKs}168~Ko&Nh9 zqh<8pow%Al;aQa{3DZRV_sd56rT_km!07&)d}`wUJBr&>{ddhN=)YaM#r9t{YVUO) z>rPDa?_=XX@$X}Ey2kV|)njgEKL_w=+sbp)X?g&8>0NQ7MUH+o!Zr}nudh+l)UQ^e zU+a)e`n7ot-}9NKReaC)M1rmHP5CEl{0m@|ny+PGXmIRT!DMVL?=QBB+#p!Ab+u*A zZyA@9)vR1QN@x))yi6-5)&=9LldI-B-lbR@%Ee37==Zt*@WR_!9`pk#uAw~EK$X+s z%2QV0B7hb#PB49V8hTb0(!=a#2$51+XARusg+oR|3Ps(=M0} z;$b1r&|qZncW;s!Pg$eZ$4Hl(j#a`tR8Z{4FvuP7%<~#4)^lB;iv`QZsCwdwFvZR1~35q1WnQof-E5%IbJ3wGonlvy4l$=78e{MMl*2He})IpwF%I0Eq`FRpv}CLrPH| z?70N-S1%#7x!UJ+xjQmhY%{q{mRX;}}gWr;LwPexn~d-8U{HGnU8HWnYj^)$itN+ggB0&U!a z0e0B?2wW@EFalVA9Pibz)w@K)o{EUwf zf<4S6{Kt_%INx!cn-FIDsP!P^9O^2aKuCNI`%E?Rlr-|X-AFHK;`*FgCE`|RL$^Hr7#+-%BAjX+nSZf zVv)a--FswlV4%~5wgMih?)&(Hi{tF}&Xo3YRC}-aaq(zsFP`c)Ji%05Xl@p1uBo*W z19Wf=0$0Ru(b(xXpg8y`iN56t6d5#C=S|Cw$`Lr&jUprA23Hc zFyXDk;?1ku93C&{{2jYJb@OKsnbf9U0JH3*$R=wYSayS%Hb}YN6mOLX*rjW1uyDrc?F9-9u``_AmiiU9hDnWT4TbF1 zUg;yPwRW{eW5=*iO<};bj!3Z*HQo3ZisQMch5Gjp44QBQBHdR_;J(Eh1+2@CL+e*y z41`9CYulR!SKj-Np^?1=@*nx(cX)%cVRMDs4^OdvY6CFl{Rxa5PXETk?m)tBzJpy$ zjom3GcBL6!>>BP1b_3klfpaW-Tx=U_zMv6!t)-<1mj2#M9!+R5J?00K(*40a;@;=N zy$ppPsfBRwW0Yoh9vq_nZ6Eml5RA6M)hKP9>HgF^g*xP1fM)zx<4h3H{;%(jidSbxk?st>4B?`3h7_Wl2rGa^GyWd!nfpkB6 zW;?7d3=3dVVIXV_AIVS{uD+RBBpCLI!Eg%7?KOtWkB!B!2QXa0kGn66Wg?H9Z3x8= zM&KDeIv)|Wj@L{)*+lWNR+@<@#MARMVIu4oUH0nUdDUAm>0w3z>c(UiMl;we8y&1ELhIAsU0xUf8RmS$u@0Z+jJ!3 zqHNRDqlGJuWf+OlzP70&5OMd*I&dh4KcI1_As5ZTVdi+lHYCO1umPogad;lA^T7dg z?{ZT)#K&YtbTyFpN{|3fuqb4v4>8fWt)-V0@5MvoSVqIJD9nijSiAyvO0(huFBbRR zXfR`Y3ojPk<6$uie6t4&TPG4=(cZw~Q@Gu9UyjX-W+oQnVz77}<$XnR=-y)SG#pjU zi*vkK%(%he#ZT#8UUZCy#S92SRpt54Ed!H;YsJmuwGQRs!y-e^hp3 zT3OYw2*&_zQK!Ka)=-f}94iBfhf-a}f^Ns@#MPC5eUuFrAR|Gww7~xL^#ppp5&9oS z5?lc2t_^1xx~);ENlDvrksrx)LF(hB?}Ev=RFHlImViZvp~*SXq-$;%L%g3;xi%T| z&y!IpwZjVBb)WLaxCTk7Ll-9kag>1Q1Q^S+8VZ>E00zlGDNsUsRAN1Zxr)=?4Wn+5 zf@8QKhvMhJ7)arF&_3cLNA$i9dmA$7?@*N0(;5wB2?bUZOkReT5}MOG6G60p~tNVpBHyGeK&at#Gm7EE60CSj$Agfftjh1wwD4x5B4 zg@n;#g@l*rn22&Dj!+~}pSlkLE|LoUoljAE`rG9+^r|}5SQYynkyy2kQ^Xoc>t$tB z`)em>0&=WXM?hhnS&`kNV;z5M!eMq4Bf=}}=x^-G{0$gmQtzbrSq1G$f_;0%dl-eDj zRD#ndQE}-2bHICa0RPIQ`lxKEere?dhzQ*!u+nK+s-BM8(36Mok(kr{q9X^c5-kbs6ia5y zuu-K?_baf7|0DFE)M|wO+ZRb~C}}m4f*8ZmB4SH@no*hsMOSInu$K6bM@t~aL)s-j z(u)NsTrnDj-*XCMyi|cCF&>ZnWZbBt5qXs=%|Rsxkw+ zx}(X(R%Iq&CEmSqh0OC}nLvwpCM#9}aKgZRe`?sN92!zM_kIQTP?Yi($oq zRAmGBr&&Qr{CYVOqe!HqzT92DrIf$1g2gF*NOaOjyhTM<>!MyHuJ=P?3RRg#LR@T} z1xEA)4&x~8CQ1_whSTra02_x1vp0bWZBg+QDmYaNdRzYm(u!e01FF!~U;#D%%VkJx z5Kf`pS;IEH#9>UN^kY7Kl z{#$Ul_teP)nk?Ue4(_4JKG^_|NBZWvjBT};tcA= zk!G{_bHtnYEJ`9vjw{9Rx7GCv@)7Bd7_^Gp#R)0dp>@MSwA0Ud<*Gn@WW6}qKq{V%wsMpt68LBKIm2np6_v!xA^#G*zCSTP^?@ccDeI4mT zDy;8=?194Y12N(F|GfY7Yitho<@?J}M;G5Myr)$c-|1v}LcTBkYCrLP5&_bD-wG}! zx`%Thx2pDpm!hzBbi=rOUx6+V44JQ#hh`3k1rFhEjN01l5MKz99g6VXW#Is0ZcFmipn^k6|1Oq(=7S=+2zUcj4!1t01hZclP9rkn_lHcK69UhR@O3pv5aG-_-S z986FewVLArBuJJB$__JmVWzczms@eDDqAn&n6r^tJx z{7LdAolx=~gg;}1jH}f|!Z1ZeeHUUpA^9=@+P1XOI=y^%ZFc0k^Z^B1NW2VBgn01t zB1Dx#;FS=6`#1i?#dC|8eUM-_o>GDY2}MYdBqEQHLV|ZtwQycOwlEip>}J2MWj6w& z*3uwBa!KvjwRLn-q9VH^23NP#vLo#p4CuKbw>dCQC*A$>OG9cwa9=v9f2$=_SR2Qq zQP`T06klG2BClC+0RDULpAA1h-l#N#CTHfT^l_iMt>dY0*^KueAD&-R2jelfsu$yj z6CmAPJ_j2US;sEis_H1uqOkS%o-N){$@Xb*)0>Y+hZ7^{`cgRe1Qw*lD+pXwgMvN1{6=MjlYGUh2o6Y!U6@;#_*;!^| zFFoXcjIHvoEqW5_*}BTd*!T?F>DfSaN!c%|VBd@MNyS0Hs|0uzqroD~)n>(xlO=kb zq@zse{)A>1_{-1})WZ749lrr}S|p(C42A8;8lr|JJ(5aQ^ACT?VkyCDcVkKBt;mBBn-^@<5m5CaeZN9I7!Y3K{9F4z(N{a!q}~;IMDlcZ~&KhJ-~OFT}EL&#fy2L z00+hB+)H(8F;aP$p(A8b>vbx`(`B3Vk}s&lhq%B7;i z)M~R@=fWg#E-9IuVpK(raWH!TV&IytrNk6#{U3~62XlvA2lR3)7^>!=%g2ZoqXC3w z)WZ3mQ$hkk(N^F3I<+wt8R85?e|x=8+_JKYR-Y`Ep(Kj=phewq=_Qh?tUA@i4shh7O?u%*N28 z6w!0d2=)m22LDvHrKceaP2yIy1F+-AxEuL8nO~wA4)_}4VYW{2 z$t}1n3-MvGFrs#GwL}8HD%28e6HrQZD_QnOBf_XYx%3IsGOn8c`Ad;*ldW`fXE8Bu z2~g*pgnW0+VrN)p7d~S$A;9m%fkupU7zT!klcbFyS0!4CY@Qf*R0MN76Sy^jYkF&K z5x4qrYpsMNbXi$i+b-V?4u1T`6UBbQWTu?Ia4gWwg5%91xGfdMU5I8aU)|F&7|lDW z?K$Sa)L4C#?{@yqY39)VKnPmm*W z1JIQ1AO*`zEB&Pvm3qjX2MOA-gp*AbxqJrl5qvE_CQSFg*#G5!LG9JC;h3H_5d zGRJD`rF_F|U+s88662bv6Wi7;tv5i0QF zh%Gva(8cCf$WKEAKkI_c19x2$Hc#Ze%Gj^aHmBofMeUjRcYqyaJRy0wGFyrWw?sJw zP%KQrgFo_9yzBrMsRKvDD^N>tF~(a+6nINWO4ZiL&s_a#kP*qz_yjw};cA(6{<85S z5xu=-Szjn!EW-wGfxn;^O8A3z>#5!3kzEA@Nw+NuOwP6XDP1D>7bq{`5d{J%he5p> z219S|YnkV)cAN2h3-jMWcizM=e>)Ufj9Cdedvnf&p#>jkb_n{l{FLN)k@o9Ccc!Pg z6>R1uXv|iy(7xbRI1m*~6m5~L3o@+6zaT#&5<*MJIR!}h#n=xIId^>Ou2NmwG^1QU zmYcTrattMK4qJOU2m;tQYcB_%Nyz!>leNM}3(R?S?d2#goQI^GE;(m*I!MZ57uj!J zz%{*V@PVsPEc<4_^4@5{%M<7wbM#k*}mP3Gl$j9$pG-_mVDLDew}Af$%Iv<$ZT9A@%y+!Zi?cGH_A-yp%DmUh+&?RGmY2CT zGGT`WFU~us9pjt1oRZ&IQ+VK~9$(^&`Z5xOJ6HlABKoYNUp??Vv4*^GmJb*6H=KlT zn*JjEh8xjaBlA}Lm$)fw?DwzwjnxFUtrFoHW7O{T&{sIRS2$~PnJ*@%oYRn|en;$A z%xDT#ZG}dfurWj}!iWr0_Y1_x?!SBR5Et88#IYpuw|#qf2oTLdWw^a?p&x(M-Q0}7 zXTx{cTsTVx&M)|I#8EEGq!<4M%9ED{{T+Ta52^ObO1`}A`TVYWay5@2j@33&&bw>? zw0`obgAAr3< zRbBi{xR1Owag|}XKDwv~Lkm?6i%NY4@Gt=rHk=LIphek0dQpA6fqkGQ>TyF2NtDRh z_n&k2y^A(jB7H34PpEJfqDlz0BqpX8xqos;VXmg?wCT09L-xV7Ot?@N5wAatg5XOO z|H>bLTe=?_Leykj27?2*?KsSw`y2|!6`{0MTN;A<7zA<3^qGP z0CFz1ET)@ygga5*D%&6MW#A8l7QN(r@)_aP=wN0y zFYhrHSFB;Uc0zINnv9QcE;jy4vc^?^LEqubF|tkxmHc!|>_@uOhkB<;0Z zXbT&v35XmHulTDyTx|TCQ)Zs0ODvKG66W#3YSbui#VW0Q4wq^iFMl~g{)WsiA>k74 zbb!s9FB5}X1a4f=I38{DSp~Bp+x{3SL7n!m>ED=6+<`BD8{$tnefQ;J+`trYzfVn{ zt!hqY6*aF%&GcAF(+%SpY%124?vn<--5r86SH}{`$KsU~(_>rg1+6_BTdRUU$Bi!cW0mBu} zk>a-xZiSx6Vlm3umI&_Nd@*vZL{dPRkiMA9G2RMw6r%Y<{e ze#UpIrUH_V{{w1+`{uYYG6r54wuZ#z+5N~D}Kh4^$B|L|#Y9YIrEXv4P+D3C`g z449w@5uEqFL52V{hO`Q3gz7E9&7rC($P%*HLXx2bTo+kVKB&mDH=ztHTiyN8{~5rns+k@ z;#yejLrEs$+6|U&WJLyGdAMAuZDCIylqJc6xbLMTF`jaG^`178awek9dXCtSxY4g$ z1IyAqCa!u8HfphF+n7!M3>PS4%MrE=v1&;2oqqzGvXPnuln>*rojDU#fDX|aN3u%< z!#u#te1QMK2Y7d}0G?!5^`%)e?p};6qx=sFTbV93PC*SLzrV)-ougiJ$wTA0P0ZQM z&c+Z+E}9Gl7Mptv{`C);0r;_YdJs*>buE`9*lcMKb0j5?ougHD%#4Y#*T+9C z-|SrW`YZZ17qI~1rU2A@{;mGN@4t+kn=FcqfVyf2to?9|v#(T%h3hPEyZ|k!4Pu0+ zVJgzUW0Ez@Rg!d#!@)K)oKnnvT`;?jJQkz+t(=`6D%H{0!JJoQD3h+vXm`WLgfF-XTEo^&Ty{+qe0VQs{hM0K?xEDqp>3&TvZ3gpgrw-> z(#A0@`#EpD%Yw#-ug^&*T#x?iThXMQjkcnT_%D_&lh93ElbpO5mlW!E7j<_LCxJmD1j1mpbOeTR*oTAJ=bXX z>!?itlnMQ;8sU|aOP4C0*tKfJ;4jGj2quBLY=h_Op{Gl%cSi5I1J!zuor)g@MR{SL zQqwPEiADs`CF-XL#jzn#bz6KSh7CSp|KBhAye*P1g^+Rzby9{yA@ZVM-$khC{hdpo zO#VR~aIaWh9xHOVPeidRdY`d$!t*ahMyMzOI5TIolbqZuW^h3ilJc-FaxWgQJ|sd7 zsLSikcGO#s|Fwg78b83#d{X0r^VwBm)a32CDoZ&t3*2X4TKRoujoH&+;Ygwe<}+By zK-Py6z-JZ>OK+j#NUBDz;vm|%7)m+s0}ampFJRuiRgH~5OXMHqxa03e{3KfK#+bVz zFmrI6)JO_TA&LBpvxt(nfE64Q|F=9%A6VmE=)lZFUXbH`@Exk2q zomv`A{=vnv&=75Sv|~an{2E@9XmJ4$2uroy7D70?k-L>iTOdB;HMt(RvMpZy5#A>n zFOQ5U#J*d0JPgIlK$#r&aQ?{kFGm%~I~|HBZY(njEs@{%o8h=Y1#xH96$p;{_Uqvx zCj?rs@fKspFVu+|w-X9FH{ftFioM8U6Q84oD*o(C63D25$VPLwTu91-ZHvsTX$B}U zpgcOm2~};#v87?F=D&=_(p!T%!?QlB9)#AXvh{bKMeAxca(?M$a-#|?^oms6!K=^4 zI4UA`#HO~x8|cI&?F%H7Oo{`!N>@7`#u|};TWVI zTP*Um_&OhTv@Mc`JV2f5{~#tk^PN8jmv7Lg5AsDoa&Yg~dB)9)hs44$`7=9fDDO0m zA`+X+onpVVQkQi-fs8lkHnQkM>>^=aOuz&p7yv9qL%{Gq09bIlVYC6dnJmMVaD&Wl zaN<+C0b$|42KmtEeQH_DwUusycd%m$g;?~*K3LC0f5a=@8?*W7k9mc)OQj>&mnqJ) zh6o@!N%}>!9-|Drm)qe&M=8T7zOcqCdR~A>wHWNDgGf8dKw)Hp@085(;6DJN5z^T{*Tgx zYs*~prPm$!qw~(yJx)J@et-e}gcX8@>DrL~_&}G0HG#gh0ljQZpm&u5bYW<~uzzo$ z|AUTKYgxgT?FxXt2SK0I0?=m}9NhB^K)0wI^$+wx5ip>bXCZsR;hBCw{@vLN4z~&d zvTG2KraJ)0GR`~F1?mIXAapQ*N^1dOkkQwCTq|MwvUir_%IV&2Elgr-ZDYh5m#bhb!pruoz#v+l)^mx_v8 z0~{x0!BKZvZ*W|uJ!Zi1r`&MNT)tj#{J1g`AE931_$rkPA1gIA6CXb;TQ4|n&w^w6 zrM=OnBod-+PA|YliILsZS`9)T-KRmZymR@4K8F` z+3$ZrpU`h9XR_=8kkNMvI@(}Fb2&BCzRWT(3B8l!2A_CYiP17f55&t#?afDS%62xT zmo={}aK(|^ZnV+fx60t!2}UMi)hs4q38K)0U6o<{l*zy-&Jo4r)UIHccS8|PXbI^u zYtkqebneWJ%!N7G$>J?Z0kLgqX3VjKucI^sYOg*y`sdBY%x z9+rw^B!)h&8vq}$r+Emgj51c)2}iX&iI_3Kcx9)$;bnrTe{^DpQ|w zF5#Hm5+EZf@j?HrezUw4Y`}QMLjV)&oi40*@EGQHXuFHO50zxUJAVpOury7}YZR{9 zoo13Vr~Af5emPQMXDU|tJeHJr*Dr~sWx$ak^9Hz5H2h%Lh1=aesu81(w{V+r*GEzw z(0v{^e_)2gZ9UaaPj$P#g-funx(HRVwy8&EVDZpLz_HX9iRYj8e!yekqer0HcdiYM zMiBSU_AF@fCqxMTXKB%^(Pfsh@gcESB4b)3g@-KlIIX!9bv$~>N%`k7s-0b|iSiXj zmI8b$AX0pkmIZ%H4qi%?6%ZB+zmM+O;=|Y5v+l0sGkv`%G-pCe2fX*Aj~C3~j3~@G zwm;;6greeqf~$+3a=F@@9bmNx$dySNvvgX2MKl8zG|`)zEG%9vwtH}1fJH=IWnoct z3FMaGOqg=U4Kk@nl5JN^oBVd^_G`Cpzv7Ghhc9JA-F`LOf6~l8wi#|bvUOo%$x7!7 zdn(ybTt$~w%;ywiJ|P*tj{KcNboXhy)#aKw|Gu@x1N&L05xap~M!FelXAo5K=+EGb zM1H^51DqsqxgO04x8;h4mbn0bz z4&htYhHnlwJl$*f5t2zF|8}?G3a{Z`<|6`-{J~L8hnQ)KRX+f&Hyaz5@V4Cokyw{u z1gr=@Nk4QQM>Zlsjj${pz6Gydtq9LM6+&{JL1M*o2*AYI)mFrIK%BQAt2L6C(HKeK zW!D7W0Zo)YdF0UuZ@H|nZ-`Mb4>0QGe0*rs%PU2?9F`N5a$N#ao$&&?mhI4# z^X7G=<;pt!mhAl@FId`@*eQ6oFi}%&ofEGW(Cz0r@(JT*#bV4>$a!rp=LrHnI-@ys z$^3gj}R&b3P3u<%GmKh?C7Z!Yc=Ip2T4+c&B7#uJx{!ig!&TsW3YW<-kdKqY#lV*6YXRs1tXKHLzG9 zq!Xj5iQtHeP-JoGU`~YCET@)`rQMn*YRxGu7i&06iklm^aN>D+ z%iP`OwlhMH(^P0X+(-6xGDtIJ2RG&qD08QF#WymwjP*JT?Mp}73()3fIJcum;gF2g z?jnFf-zUmzCM6UY8_U%&QZnainQ=#K)Hie-srERM`+f|ehA#I(cPLsMAA81^vIA0x zaXf(RnhEIrfL}FiAk7vZ}JZ?_PlZaQ`52t@)#!^ln{9O+chN)!VHH@Uk zE3GA2;Qg4=nj4!{!_@yE)$Zd$@v;$Tz$0dR9_l@N7bbq@M0*{a(sqSP+RZXLI zZ@aqN^>M$AJ(AF8Lye~8G7bC|_}abdtKQpv{a;?Yx$xx8K4|C-VBDKUnb%Zkb4)iT zG#6o&!~+&VDP?lz>JK7wZJc1%q?zmH^{y2NH)6C8`Pa|L(qloZitArMb zwt%2yyHB%xeE&%#532bqUZTN$Cxjj^ zY42mMp=6@8uzdU?ZQ*roVY$DBkJi*eA{e?OPk1k2TaoX-?k#jjF9yYKiHzkxfolp% zn|SBv^5MMMGwoP(FvO?E)jT!Znh>8FY?6rHQsblu>9z)T^-VYa63=l37f`zC&Dk_% z;7O<*%)`+->LnRXN)(p->CMcyGsL!UUi8W^mlzh zbmD2qqi{E!jVX?6Ecg|CIuv>Lwn<)+Dhcz9CUJudE;5x>3$=vc;8Latao}3fPY;nlYoL55hyDjvJw)@mMIutGo&t? z1rY`#E_G~;Y;5O&3@uAJ8%70w04mNsR7p9z?5KG?&k2OB$b)v$khEDmaDg)ad^0d^ ztOxM&u!P}aF@yYz4@bWEges{MU61Exeqf74xfo;TDhxE21%t-kxI)mkCJ#@BhvcYP z|GTu347gmJP z8Fi|-PDQgdi}DWXSU#y_6?x90s*4yq-A(| zjBFCrFB<|T=$9g^UleNU7w;*!maV`Ek|fJp<*XBtXa~u6%g{QOzM3~iQ386eY?56- zFa@4GM-AXkQZddccAP0uOfqB-t4C8ajg=guN^T%dqH-s7sA?d3tbw#lubFC(Di6KiwaD69V)U# ztfHd8p@aWRlptvaMt%R)>_7ukQxaI5G19YDX->xwR5e_LQSvKPH5@nvsU?K^%;`E^ z0;eCOUJw+B8Zc+>JQUo`IKvn&Piq;d#_0)w|0p(H^ zIbW>OfnRWiU(~xYsMTa2q1nJZ^_bE8kVkUSBJK#kU1~Ry3GIBM@qUC4zY}GyG{76# z6()H?NL5h%l~TI~wd;_r2uL}xJ(%s^{wRBcD0clVLod+!RiAmJrYCe!h};NwN8=4nJbDOL(Q=YFYe$zO;F*<3FMDRfi8zMknofqPbJ?>!TwzTppD^T+r3$-xi^2pdDB`+;dj2K zNqnSXp#aZJ86<~IGkdkZR9b`E z>mx@n6S0`7T1U6npxY@o*6Q}!SjLdy_BwLnTHIcv1{0s_$`h(*+xD$qYmK$Ri= zvlM@JQ}e{b!|`XA{y7qV>ID+v(fG3+so6FdQwetbRkeZ!ObyszQXkppne6n1lASa* znDm6~osEMoDho=k9c2k3Fd_R-xc;7^(J+%Gh+qV@?=ud-)fW*ov%ED|&bX904fh2Gt-uSJg1bkFL9}w4+=`!ae%Mc1 znIg$n4-YqmCKy2Pyk8Vjg%+C3A8)lb-n5jwKw2u(LL_+<;!ID{J#5&ISemNHPN>H> zp{^$}BE4mg?DHmO)N>V7Bi7}2)RMe%!#JV>24-=3qx1%PHAc#LbvCGRx4-2wGoKc} z1BSi~2V*n#|CB&|$7rxLZwGa?6IBRU=iQ5oN23AfzFVowmQ9L%!pE#`O>&f2MkR`$ zeVl6@xv*Q#4l@-7v7Gv`ySqig5WXc-8J=ks_0MfranC#tVb{xAsEfdClvQH_&-u#Y z%IvC*L@!{?VBDzs6%hl!<$5`DdSAKTifnhb?0zMeG$vS4{?v#-wh~E|@hH1*2UO-NOGbIc;PUOT_e_xM5X9nB`Xf5l_ zf~HQv#1i=_eg{8Kzps1u@8WN#&nYrGR0hGo1G3};Y}mKvbTzDLi<%q%_T3`Co9Q}= zz#x-0zKk9vARy(OcqXMg5fNnAVK?PwSe%aU0wF>di!{f@yx=uBHbiWzYY)0uq<2j2 zMndC7&^DqO;^OENO%j)vA4^zSbuqP67CpPy0Ur98YQCd?XMKKB6(j!XKbmvdS=1t~ z(?dEz_9MLa1;0O>BiVC6*3HlcR#E+4pod#jRyN^AWJBb*4#f*i?WeSMJ+fz8U4llR z*fP_pckWWkKi8#ro&oOpy`=XV)UQLfA}i(G&Z$Q`1*h^iLnA9s?xy*_qVYpDu_~52T45Q%4qNpY6fTD+AEkmjUbSQ_W}3GgH~$*ynVxckC$$YX`z0 zuv~;~WU>=~mTZtb_xW5O>=!u4#a1rR>?E>VkS*gw@}nPX_J*=dc8#worteP&sPVPn z(SY%FmdT!KYPZ}j*_IXr)o45{J`vobBNnb}d=XDRCm0-HydV*;OeSWu(@s$@7}w=g z`T$lCi+EOV3(}p8-7yc&wb#3o5tKe%LL`M=jICkaGUWYX|VV;5NaAnJCrOGe6h7lg{wZ5>;(rk0EavvZ;YHL{C$~9igWgyEM+a zTaRwwOVk`b<+lq8Qp4wMG?wvPqkYg1q%vQ+kIv{0NvJPgt#EZKvMG1bl9*B7VkUqt z!Gx<%d=Xtmzzxb)0|GtQ@ENC$ribgiF8GI<0AH!(&2f^Fh}+0NFJ7DfQx?Fgx4~e& zM1Adh9T9FV0RITPb8ECWJ{FDkh5Quv|HRX11M#;r@;K=Wl?wzd!B8RVMz^6+8UX;i zO&-0Qoh!njP0lVg5^YO(#f4t`iK4h2Vz$sBc9y)fbv5S|3h z3m4e?lVWK+d~}zss1I(oep8VuxD;C|)^| zxy$h>P<~oK%7<5iO{JW+GgkMM$GRrP@M`M^#@4?8@;AM?uh7fVeH+Ukj0ustxB$eH z1NqMN*CIW-e2TG5Ev>H;ojxiW&QGUP9#A@+#~d+Lb4Ay^f?QXA{Lj6Vou2$jUR%2jCQ&{OQ`8E?Hbv(v<4h{A~dMoo-)FNNhX z8d}OP=o!IbH^5U)d86=L4U()f9MB+aSBE64K6lho^+=j*ROV1knvEoD&E#oPBa*BY zwE7-tz6nXz40uPA<{*in5i6fuVi+AUSi;DZ_qiGQu7coT&3tT>a=24Fcphol}t~`mOKRS9wU5n~W z-0DnH1c44Nx#rAr?Vb#Ya37jcad0p}IM)TiFAnO&F#pXv&BF4!nR_yBx&UTfk^;Rmfm6<!UI!t(A4HW`hXs)3%4RsvHF$oKvf*E(_U!BE*xvfv{X0BXIM5YY{}<6Y802t>JQZ%?k@&Mjl>~;n zEy^fD$g>bF;A?U2uUvepE8pw-9;7PSTKE!@0yEAX#O0DgO*Ya%cebQ}a$R%``k4^G z9(A={7-i63h*dn~4m?COnQoD|T5mHgtGgvG8~4>z-8gai{qtX>UD++MX17v1py)Ktj{KBnf zeYLkuM4UmxQTHHS#GE)S9T+=6TdYZBh{N)RHU@4FiE#* zDN4JDNg95Hv_)xGW|F39sX0ipl5>hCQQBE~a_)K3Jfxj5z5Dkn>W;0jqE0a=3U;8Q^p{$Kv54a-fJXk(VCQj@7ay zTGnE>OjCuQp}CDS4z>+mZevi^BlmdK)naRnzl@Uw+D*UQuc0hRz+#9bBvs=d>{T*!lTWygKY zO_D^qvd9^)Nu(=_#oaWCbT!4G@b{WTx|(c~3N(pyMIeZ%Z*P?5NmptJ_Uo0deih*8 zo2fH$U_zx#yKSrbdy)_d#&&o*QdH+zsE(8rr6>>lv6@;&puBNzFYWn>U=v9J*($o` ze?uyvwFrnXmZL!;$Iv*8pdpY4+na>PLt4|d(DFT)ZK_{EJc+#t}$D?pgKg;supP-VOQep0`o(!=f8+;gh7#$VX;<{3!t zKG3IqDE=;QFPt}|u80q{s*C)CZwyJQSNv6c3O&N(jVWpzM>$1uYJ(R;F2GJXwzVYD~fbI8qo6n{@3FA?-+rhF;8O2Q|Q4%UfA28joT?8ZFC3!&4iH!=6gIZfY7Ju zlRPCYSjUo4u#UN^gwznMyUSN7UXM#^%+IZk@7cJXX+~+k8ct5 z>cibrJ~<2@=>>6w5t6BKGyv|(#GP@nJORR~YGbJ#G%2i!xu^TbyOMxkU z!TK)FI&Q8gf%tQF3)|Dro`an93Zl_NAD}dei~#l^g_X8$lY1*bzvjEIViVMfw6Wnf z!5)0zg1r`Cuhn3$)x{q0v&UD&hl_x1<zzPHoiVjxIcN8%Vw zD31V?I^!exStg$ZdN@D#kWUU+C}~^yRxFEF)G;+s55`o4>KT&F52EgK_7 zi0Dy6POnK3v+PxpS|Um89`}^M-DgoUDPCTO+o{l6LR--NTtGNYQ8_ZhW!D>(>Ae;6 zK~_RvAhVG3;(?aF&?m;}J1Z}qIB|`&BS?e-Pn5}?xmbE;XOp!0Ta6Gjj?RrP7TcH# zvlr83pW?6WT{QJT^K4YE;e=i3r8gqI2^)-!G$xFRumst-GiHA*3F;z=gCL_ZW5{;5 zJ(qj+=OB|FDg44i_q(rqa5;2c-}ECe3B)o$YT`Q*56Hu{Nkd;Sg+_-pLsqXgMBrMesCg3jUVq$Y_52PZur@o2R=M!Hr9$C2ccQTF&x zrc-zeyG}ZIYL-P2G%=%{k+tz;_kls4>~qli3vA)5r#|=i>M{JS{E0b)j+9T1bv8e5 zluz;}W;^9vEuZAiCVo!Cr%E8j%2xVnph01TmSya`xl_P zZ`lqp8Z@0SnpUF!lsy;$WP?0fXqA=f|xt4)*qN;0kFl-&%R((2;_ZByb>dWs-icm);T{83NsFbx-`W z0FPWDpDvG_FP|=toFbntj~s!|HSx&Jj7#fDbm>VV~h?{2D_Yts5CdGbaOQ$QYN^{B8 zoE8RUL`Vf1qyyZj2tC6^obCGDIE5Bo9Hy<}$~ZsMO$H@l?s_*C6S!&vl;h(5d;MN7 z+zWQ^65Z=!cau*&?DmttJ?uV=Xei%G!uiC`S|c$u7eUcJl6(%ih6!`6B=%f)9t`!) zgF*Jhcrxw0b(#h040jeX+5B?=nyG}01lThG*l+Ef(%S8PJyt{UtAeuRTm4=iSppmX z?#{p@4*fVFSMuf4l`G$U6p$;Q%BPVl!PU^VI=#Ww5Kv1b!7PZYGaHM%?meEZ3x5yx z!*PJl0@xPci)|r`#A8QegvPem+Qy9Am^KqDPRiT#V7-Kn(S)wO5&5&-XI=+y$TcH^ zYCWdkVBB?A>tNTE^V)~R9}$-1=QH?JK@4`sT}1Lpg!#N7{r)Uk-t&g6mmH{-3o1N0 z@P&S_mmC;Q*ftl)U7P46LW;;z@8(|i2A2gab)$jEpOiU3% zlvi2sg-(ygr?rj_k-t4g-B*f|ZiP^X%O{5>g!nz0eTQV@dh~`NSIv|xkKQ~TVo-;zgEIN* z5+O|3f4XKoX}Wx`zcT6LYTqPhdiuMTGQlS)=WO}psC~-hc@O4ngFdo0q8zP|yGG@G z`n_I6DOC8vN{w{z{ z-izNRN?k@jQ$F2A@MQUP8GRx?eF)!AK3O-5(JKc-3PqQ%H>1C^n+(du{m1&fUbt^2 zD{to72r?Bnyk#L5Mz4`iLhfVq4|(5)!kpn9O62c)F+$$;Rm*N0$b(*XyS}HV8H)}3 z5+m|(Kl2IH$-$jgv%Gl_URHD}#TH1hfCoO2AI{N_dxO2h88)@=JPE!({vAygu+sza zz+)C9$Mp^gio0!%bRh{wzQ|+ixZdgxDT>uZvWQ)s1~AfFDIK_plZ5)(n7`yifabkZ z>a{5+oKJ3#)V@=NhE_S(5(fOvIiB~Wdo^M+evXHKjyi*)-4|RknlGRZttFBpiTq3F z^$Eo{=!0A5@o^qL5O?3x-V6@MMKsMY^g`)D&3*Z!_e5t(?3tZs(He{`YQkj4=03nF zk2TEZN1_q`;t*QB{3Pn|^C#cas*FYCd)Ck3>{XGo=tWkn?Lr~k9mk(Cxk2}F{8h7v z|AwjxrR2>lnQ@6oH>>H*w`gQ4zi?3e_<8^%la~(64Aeu0I)f5nlF4 z@RA<|9B)_4Gk@-O#~6$uy_rdk#2aMT8eF#G1#iH-@m4$Ym$(~!V3b9KBGyoXAHrSRz_TD-TC&v8}_ zh(sklFa4e=f$}XVpQ?Srw6mi2U;GQ%OxIn`2L8!CoZ5fmkD5jN7w;&K0EyKslHyhS zXzEGTc%W5k%6p(ygV7-?=XHFKY1A^?R^MkjN#CX^!>jv81%SNtHJUP_dQkKcf}~di z+KPj;VqV9|U=vN;rBL>ZqKjkzg|!Effk=+KJ&!-e3V!sepfb!7u?0jcW+k5LCl-@v zPBUJMJG1XKNsjvHokvk=4S^wcgo@k=$GFIqu?ljfHJyx($2iY~>GuDu6HI5W1*Ya9 zWQib5Y<{e-c_os+0qf2Y5Gpc6zB-E%eyjtA6A<;KNt|_+FX8tH4#47T zV(d%Z0ZIKE0wyu4l|LY??TDU))SHMmWkuZ1ZzIblieE>Wrzw9R(C|>IDaKlR?z9@u zaZ}RtsXiCzoQ=Pp9w#MJPVLcz3QDsD(~wK_ z4Q1yUREx|z797d^(d(^IGa9{6W!3MNxtf*O$`G)Z;ciB&J6pnGFZ4 zrMF*mHHe{BgT%O?6A!Od^^bP@WEIm|KDh;RqnzxOL@dj22&R_o&QZUkGXJMpf z{<2Gb2pHV?I|&zK<(@ypL*(e9{v;Y?-Yj@>9mZ$gzyY^(Y^LuOsl}rW#J-uH z(Z10{rFdS)n=%9Tz2GLV@DrpC%kg;sL_cd-90NWF??Rgk>!c1IYx4rWk4cv+r8Sz; z*R!%d-?J>eX)y0E$TJVC=;Oy|eGpnVM{!=QK&0hvM?e4t!vnU&P#b~yz+r~xN&0aS=DZ_ zmxB-2v=X(a4b!~=Uo3(-sAL{PDnkK-ow-1aQ*^jsN8=O(FGnL5na^Uu5U;}&`0Z?o zl&EDYcluxf&Z?&ri@QmH;N}-KN;P4g>6XE6Ag>abVkPb(W5gvK@G9r9asuJL>s^5+ zjJ{4eI}!6<-gmfjP0v4iX&>+&Ha&dxK88~dl={Y>@9e_nXD;WUOl-kAj}Ze}`a+HY z?R67zkTsym0?8`pvPtOCWT${4Ajt#wA~fg@?+3gTsWe@0=zXX+noT$w3F46_?khm6 zSRz*^W0ec>EFx$XF@xnznKLAmS>8nA>Zva2sV;I!MyS($?fXi;?E=D_lsKbRqg!4* z3}EBwu=0hdoCIN($J#-An4xzs;&|yRDFI~)seMSC1-V>}pFBgQq`KQ3GrfE@+Q#&kSA&bOV&9`WkgaT#Z$9p{(I8ZLJ4Kxs3? zqz99L>eGIWWAQErlPYvc0Dok5#s=Nu0EF>5xd|nTJge zLf@WuqcqlC7w&X^J){!{WMWvf&-i(Rs$qCHyHg(F#>!^K&jYIl%D?$o)MIr{O2z6N zOBdUY=OJK!K*(*EqyI#H*BP$U1<4R@VP^%dvl6JH$r6@4A7_Ko<}w7Sdgm3Ws(diwvt>-aOS4D$zy5krS#q3e3*G#0}-i__8{7 zDmij0Ov}VaLYhPFyJr!X9{dw(YAj3RmaBU@cBc3>2NNM^qsft!x8|C>ctW7zomL1K zi@<`Fj`a?`=u(VYMDFryU^wYv(74{`l+df2%yTE@(kU*~_rTpv9%((<~wd7fC7p z-W7WdQpR}JUim%wdwu_B+>90 zoMH7S>r+-i+43w3m~j?hoX+V73)e(kE#?bXTk~iNGe)yP&e6OumGp{`*?3t2DUKBH zjb{FeHI8PBwT-A0b_4Yr7)5Q}+s#=C{FO?5#q zVTpLb!snsV#26ka+xO z+@@j~f3CZaya1z8k@}2swWo1`xyNVAjCBLqNZ0P-Jf!P?)jMa+y=|YiCTcO@eZWD+LYKFCi>a7K#tC9HG3yBI~#>s*BHyp{1N-@8K^4Qh0YCpCkYXcqRjymHZ2}SY7YE z_k9tjKwrmLf_Y;3%=zm-K70N&P#aVT)MefOSlS4=kQh8heu|IAkG&(P5`Q~=1_`a8 zGRe0~ZXn8G3brA$o#VM`6C#BZuHP~JMt!7>4R=>< zNVaoH=-?MY-yN80<+L zRk%52gERt4F=9vcwCHJqTlO<5j2=`1`hSz?K0BsMjsOs*9ff#_ZFm^H@y&4V3Z{-bcrdUY&g+!2%Ic2gu0#4o?Uh355SuA2`}5~Ml_ z)ZMClKX*yu5!YZDIlH=S9%;j908R{iCuPe9#K zRsaeRn0I_GOH`?a_Azd$Ao#17P);%QvYDT^U82b)Lq!UK4n$QXnb&!b=KW(c$!kSk z8|uL)Q~o`KOFM)M(o)WUDNHS3N5+`BkIOCG->xtG!Fy)`;MoAU9?jKZ2?#%vL~6sX zp=k7j&;87}M%z7jjF3npzEKJHeeZ&p1ieDJhTnhH{5d`eI!%+Bkz{4=m0BwasS1+? z7v{kp@8zDYvy0dvrw+i%)IGK-WtrR7i9ndf?WOd?!3s?8&ptkwo{k zMUtD5*>+j7N|{3Oi?80X_tX$EyMSCHs|YZsq+2TnobX^;{pNM~&< z{L+3xE#QXWwTqjM5o+;A9$9}>BvZ7&BL%ONcQUs}F2tY%SncYwj}$afNUZD0T*Y7E z(}7{v&I=6tVto3B{n{danvfn}Z07B><$|%9K?$v%?ouQIBSA}7+#9O!*L3zx0&M5? z$0$vFx;^`L2%OvX7`AT-o9`^#7pM(5`ow)%W&r@vwSef7Kr5z2d%yZ+p`>>EJxjmW z%lwe3U%1fXFv;oPbFRf9y2SZ!`OF9|`s-UDL>pXW?R28c0lKnoflGzEN{De$1mt)j z=G*!sDP~kZRci2px|Ck^Zqiv_R{m5QZU}$vK7Je2U<>VICHfphK8BNhdAso>+$X)W z&v3f|4#px)NdazG7dQ|AfopSbCDOkc)l6~2bODYGO?*vc&1iRtMlKv~lOul=^BYE} z7TeqH0Pt3@2V}v6Boa|pEx62=eP}1LI;$ul;RG-c9p%SBk)>j~A^^+1=k{HM4tVi5U>12sjSlKdU`eld+Mg$}ji?I~SmWwG9_i^V zbY#p5a@mi z0x@$$tXa^~^_TvaDN?}QL#hNeSAe=ekNI1cAFNt{q;7(~YOl_o^a^VY+EpS}@sVLD zfIXdCl4{r4)j~_GdbwXcKxD+j%Mtm7#+sp(3g;zRjd32;69i)jT?JB?A2lg4_^X@y zgeE2Ozr~MkjZG4?j`|r1Y+zF&k}}0$`qWS0;Rr7WIP8Ff;3@)y%o{m4s64V*TjcxJ z$TqE5#1ZMn;pe)}WQO+q7_+S|!WS?X&TtGnc#G6%OvswXwi0WUHID6fI=0Q+u~q8W zO3m2D>OpOHY*B#Z8ym+&McS@oYG3=9PWi|k(+?PqbIhKZV~TK05L&WB)KV92&X~BG z8O@=pJs>4o3j|g!l*0=R^^b;87z;0qhZo{tF(rcYGM8z2;bgoL8$#ttoebGLev;KO zFVf&t@3Z=g7s^&Jr!Cx$$~gLm@_6+9OS)l%#uT&F`*PwzC%@b%bn+v9lupiO z`NXK#kU%pf1MwC=nbU6$zz3&)uMb^Ry$CEhBlZw}w4PIliV7d9{8-Y> z7)(qV_9>H9m&>5}0csRHC}*j_cuh<_f?~*%{5QgLHYF{+lIO7xZ`pFh5=IV=S$fG9 zrlwm^IkmmxBaT1!Jk`Uy;2FHQkRw}mE8Ih zCoux}hDX>%uK=i-^EL12=@J1sX;uATzn^dE?>2AlxMvrY@H|U=KnK zjbv9`c146F*PHL{>!rV!#aVC7BZ@%iNXZvyz@;EZk^sB8CFxgnX0fJJ+(o-$%+ibd zvn2k;3!k)C;vwVL@CJcgVsG6mNJ)4F;zMGuM8>p63J+Xry&YELLQ?qp5eV1^x`GI? zo?5#iF?>)xC%8k7@+6pgKP~C%t=XDeiIbD#7XsPDcD?N8t#WpG0@fQWH#ZVsAi}$F zKh131Pt%AU^$BtAj$?5cpV53&#e~=^&U8|MsOghIrOUWAn2d~BR<#ixN-yEgc}ECa z4ITC9q|GyFtJ3FlO^1;3U2#Qzvp_MTHL|3=4+e;zzLOH$^_@6oWz|L#qn#y_VxKzq zv6;^&#UPPVPBF-gi$Dw^XP?#5CocSFVP_W*=0Q7?WzTSYC;Z)YdLn=BM0d-&8|)zP z_;-(=*(ta6iPj$%3R45>ZYdU^#YFyywX}Wqy0v{^uC^N@0l0-o025t{S!2lSy`Kkt zV|aUnm9jqke0xaFeum`g=Qe4;u9cMGNxXo|-_Kv%erQcbtjdKDZ^i;}j-PIIB?|Qc zdoT%30KsyT90g^&bw&&Jx{Yjverqng8Fz%y@T{IH5?O4{;=f$mCq%RJ5BP=Ic?f<~ z6O1GWBt}g@0%5$Bhbu|X^ak!siCdmTUogd>XO^0Mua}&@!$D8+lbcoMr<`~3-bQ)@ zq=4kwG9~^BEo?oMGdo9?qR-f(wpEm#b6fG_AFuAFFqLM;83;XW$KN5=Ni^`!NTOD9 z)zWx#1X&pE)jG^Wu%8r3bjeq(b|PA7>bv0XxYpfSOUL9ZeFOP3u;3a3m{r@Vk6;RB zsL8KyAu=jw`@vRyi)67jl0@d21WlLn@_n{`V=94MUgT9Ne~E3uf|y6~r#88BO?iS; zywX0G+n->0{e0v&E;DI1!To|aHaI?PutvkpMd^Dv7@x|5|8GZ8OH8w=fjKs)L3JaR)een|@5?R^!mjQ$FR3~_IOo=Dt+lq`B$2ovqJAR}GuC7bg7 z;UNk%FiRWQ%9aGT2pmILFm}-JNbKm5cx9S9th9W%6pD>U>X9Q&jnRbq%I(!p;+tn< znh-7&cv*H#^m{ zWPeaqz`{_fY64U;s2w<{vEkW}$UF{oGbsWLYqR??o17(YWRb7MCDjizEAk97!dLo> zBMiq=?uXI6h_r#jNcUcw|Nf3`(i6}WNkm3typSbmh|7wXoPNQfHg_a|C4coQsm?73 z7s^X)zwFbl0B+ef*zNvO&j`LelqBVjz&;60tDW(;Jg*>)%6tuS!K{a!Y49`G!;cjD zl;Od$A3|Ux>9fP_JY!g8pbyT$TO^9du}hHynG1$-fFb0xm_bQ9_enbtpW~?6&B@~HvX@R+xK8!-yl@B}je2zvKe2E$5@+USP#BgL8((0vQ z3wN9}gqQk+3OHj}>7s^z<(}`v2~u?VS?dzl#CbN9_wYBs#@O&2!EDu7H11~I$Sk1{ zC~u(<($gF>#*c|FGe%u$`>Gzxsv}TV(*% z(R`=4RIqM+BI~0~N=kviME=p^T$u_AC_)EqLRp#GOx$NS`ArVcG4jd`Nj)#KaOphtqAGT#OIr7-X*H z&*?;7211u_B?zVR$+nEio+;-GaKF!A4X|cl!4%ZkiTt0&X5&?D-!{0_%Yd48q2xE6 zPd5VsRKp0!XK-Q+v|9pNtIBk+0HA$KxPN!DV=@EX-B;^Vc@J2|c+1w=V`P1>>hPRn zMEl$JfP0KCtwLG9bqNUVBR`V~kYgFxfd2OSgZ? z1=beVD-vLZx&i^oV2Sc>jJ+LAgLKCiK=T$^H<$IKCGuxvR#FT1ZcLRG z3vT56vzzs5;riF}_en9~57&=Hhobdm*%em{_aHEi=H6EMCUoJXe_&z6ZJq>hx`=zY&-(IS+tap)r86qX9Qj z7&Jvf7$N3}O3}53hg*)$l+;SMXe;I1^dLq8CI>V5SBoc!tk%`ysLOP<`1z%>S{#H= zT`j&&vQ3Qo2h!P8{9YUfQ0D}xO`6|}&BKbWSJ{sjX`d50>lPRy1yrQys6l+RwuOHl z{k=EpdZY*JfWd-5zAt69R_PjP^7kbKH~*8p*GiKX*v%%8sRRvzhaKgb;hq0NvJv2ARv1e5H`Io-?o74w=&!iP!+_K7q~ zp*8X>+CLUA^@4~y_Hc<9-BKdZ!h+B+tn;SxCP+e(&D4(Lw-630RFr0LQ_wqchme7c zCjzLQ`-h5fq45;3F%tQwd2n}o>w_wx<5acftqlltV$^7)6Q@-Onzsbl z&a=a6q!B4T-YV^QB7?_=_6o;MMBRSc4w0bi2ZN$th>Q`-#I2`F${K=#t8;8G99ocz z@`t!wlnGo~g5L}m?Tbh*<28H*bI$4V_GI#%t=NplUdwE#)mn!6Xol9#;gfH+v-<~9 zBA&WcHvxRN@8cl3#uXy4i(?^?UwCJTj9=|BxAl+YG7-uG zXswj*N$W@oxGRq+cS!K>HmA z&~r1j>AnxgrcT*uK&A6yk>HcpX=U0Bx$K2_2!}BdIfJT8oUK79M*tX5GTL0`9JLY7 zY8C-l5ynSD3hzEmsCQ@lAc~??Nq5FYO1e7|ZirylD%gK%j&QtP37|Zn=GX6_32)h{ zK@UzGcV$iA8t^!n<1YD4RBQlny3BHO&>%%lU=!hmLRbEHk|mLU$}X;GMRP^cS~NL` zb6c%q3CStvI7D+;kv3er#`!QbsWdIH;1v(Xd??a?ReYCN3oW4C(O{KN=6wZxdivZa z^QeX>qVNmElOFg5AVHhD*z%Iaq>MAbI|gKjUo7K2$;X7Nb!(!Z|vS#*RHPD6(0jU|*3iLNFf) z>KbOl?xe+&7Yh}nf#H<%9p=_Ka&UmQ{q*GiRbBFBn<;4SfUDRx!7R} zf)rwcfQ}YMz=?q>1h{e`KijZzC21gD?1-5(A72eP$K;^2t{@Ku^K@#v$I|0(r^-h7f)s0zHKN$vY&7mM510b z+&Cmva3^*lCI>J+0vZ5%L@If??=g3*q>3A_aMsoAF>a2$V_K7twfL{WSJB;0cwE}% zQS(UbOIyiq_j;XND#d_@gs&0f2Dni2`~#B9*+9v50Asa;@W4!YG`R*K%GH1eV2m}3 z_;0AH*jJ^1RS=Ad(4Z8g8F6Ri^-_efAD#Ke?5@r%ZQ7|ECzdwskPE}G0kqziOt zMZadoRI)Wt+o`H+V++^|mNNQklhI(Uk_3X$R0MlrM_d1+YRGKfYarqN*)~30cnavqe z|A^8iC9gvfZ9v#$!o{<%h5@L}akH1ECbd1$)^l7QI2eaiWBM)?u56Q%DW`IPPr@E= zTN54amN^n-Kz4MW88!VQF4BaMoprVd*>hADM$S|r`xWnUP&Ex%kJE0=0M)#(nJH(b zMabDGTB4ji4Zmo(06!{c&(*d&|Ez6~-qQ66NZa*n+aPZO-%S{T#yV=2aMXL?gcdyDMukKG%4g5#j{{;C#a=>M9B9VMeDB%zTBvYTXh?n$&_Y>J&W zge_CM0YrG>jCL#}yeIXrEbB%$-LA)Aq+K}s<+a-HZJf@__mfi+d!bS*zn>IJB6+kM z4#iReBq}~s)DX`6Gb*L&43;Wo2vq0T0#^Q~eXS|ufn?VcYlG?2F+rGs32=uWrcv22 zy@E;}Ob_6)qAZw>7MLs)r2x!{b=8GG%0`Wtdf#wsYl(9J7F|2x8k~=SotHtNvG6z1 z8Q=6&A-ww=ps7nyvTVcEh}Q2C5!vN3=_8s-2RtU;y=vsSJ}z?1s|9OVjtjUcAB1BG$R#&E{+*u-A9rbLCO#JAx%kMW-y$I&8;FZ3`1NGS zj70H;Kko>0fo@;$A{U$~2Zoi92~)wY;6l5};WldLKC9IxZ8a~u)u(c`8f=Fh8h6bu z*z?QsSNrmZVqxIRCkgLiTt5AKXf@SI9pN%^_$QSB@yg2o*5> zFs3n*$lrM@cge(g@Qo`_dWaoQirP+REma1)!rj}>ToXN~?ccm*X8ZoFq+Gk^fNi6< zK3^+_;qeM$Sda~-_edt%ITCZz#*Nu5@xWjh1fq$Els%<-ZLb|O=48_Ld%vd5nhvAP zIp1HslQG}f&=>-Szrhy-u1wJtfd@#ah0*D7uu%$az!YCm&9@kHTQe1*9cgpgC~}u3 zrIy$|?kO*KrflcH_yQhW!p0HFl~odh2b5sqkh7FINYXW}TbG59`yO&#nz4Mqylgs= zc2jyN(tCtOW+-cR=p7T6Jbvk$Xg3!BX&1@y3o}X86v%tq=NHHP!b!4RU1n!Kb0bIf zCeQ4)U>%@4GbZSfCWe2*rg{e$KDSSSos$^+l>8LGiJzyx22({6;~f0$48n2|BWpo0 zSgV*i1f6TO)<_;M;dCMY$JE{-zv}1z5y;z570B}x@-2Ok??%XvO065@%P#00@@IbX zAkRUO0cs>w0K*y5$fp%X z=^DyT-)V|Pc*kpvrzt{@L0X9g-pk2`J6`(yzvDE;F>J=3rbuCS=qm5+G{uh6r#Ve= zI|@7B{*b0U8aPei&Z}?k{@b`~|C5DAPnMtJOYvj5>stKnJi0swjeMdoL5rgJppLD1{{-P`P;W zRjq?H_Rw~s^zfzp6c6da^;nSD z%$N&74oJJ2SQZ4GyFKvi4Csv)g29Jk7!Zy%GxRAea)?)P1u`RHK zt2FQ@kcoLtRCdMt5Q>_v!hdZPTOt7n)qP?EeDN}cwP_RpMd0v2s0`k_eepM3lA$sN zd)h`a>g#2?@Y@$fg_w_;1z;CnpTo*spD>tnjiYIg~Uc;)bhzn5l2pS9enMikjEaN7OHHC_ld2DEt!b}$2|uC{{sqdSu*R{s&uS+ zWjwrcd!$|^+fJJsII@v4pJf)zWN!i7Px->&eigIq5ZF!T5H>VJm?8TOWue+v8prch3_SvSBC1H}!HJ7c2!a_bVsF#T>?5B>D+_DB2#+mw}!! z&)6|%61DzPkrUVS!Am0|wj}sR^Rl?VH$uOp6WwA^Mw61eC!^yg7%73I3{towB0=8#AZ*$((v^Yu6480MC|QE`YqkaLkH@Fk}9Z_|RlX!e?- z=#M(s!da7)tDDxH=&w!dU^_NORon{^?e1GR>qRsxf9F;21TM2YVW z>bx}t8x3-6b;n8AZRpqm6z)=FD`#LL(WKnGA8AY|QgUkVc4@T~ITZQ=NQG`Iq4o_857<$s+G-j5z$3_y#WlW7X{X#*zfCiYs5H2dE~T9)t0%0 z%}XFXeF>PE%v&S;_7xxiOy&|2ND(X=$o+uwG}w%AolYGXaBXVC5Sd(mnh1S(iG~5i z&I_a+5K9C0!ouBk62*&~DmDu_n{VJj?5=S9@%7-aQV0ch?%fqJ*5m9qFEU<VwBqQz5p#m8|1pkz@fS^aJn&~0IwZ5{u^D&z zhhD>N;|#I`DIq!K+_exKg>f-*w6JyXitsLUNdIW-o30I#F~`AzXK;O6^NyE|kx?!@B% zwaH6|IG=xlF^8hv8x+>gM4j{{(HRefs;)qRCIrJ4NYALa{qcYXd)>D(nsYm;9^;Im z5M=%c-F-xx(Qs2y^!x|%(#@I){sWv6)Cu8Tc^w|-s@}CF>t{Fnkdxv;F7JBnQp(BBpmQ0GI1;$l2 zrZFGW2)`F1GSD_t3q-vYVVW@+LP@vG2XRRzc6C3Q6#D{kr?_7-68oM{&GG1toN)bt z&253^vS#Z)peW4NNN(J!Jo7GoMMxloGC~5+f;fuA=1##+tl=d2NL1j*4|~fVNge24 zkg-^>!fHCNr$`-~b$cedi1kBWOw_nYqP87LFrKzKLiFAX_))$077zzcdIkv`K<#Jb zBq{xWi2D-2D66aOK}8Y8#3~9ZI;K>ELWm2BEE1Mrq6tL8=0YKm0iq#^$pl12u_2mi zjHYTT)mEvkmbO;YS}khPpngnTTI2Sax?*eVq(K|4t!QicpXZ!=-({90p#A=|c;~(A zxo5xU-uJ$I{BR>KC97w5JeaZ(hfdaWn7XY@f^sCmH!Qd5B1iK`*LOj8#-Uk z%;8hCK99`^ffn@V%bAaJ-D}Rq{4+1r*_dYb-&ik6+?O-MzxiNyJ}p&U_kix01)ZN( zYeS>Q6`W}7k$Dh)emRr5d5tZcvEhiBD6;MN-5( zp#y($wEikoB1s$N*F-`3x=Zzm$me%cO^3pkKaxIhc)Ff!(%8cGdCOix^le|BS;H=o zC8JdT{lny9B`mH7VP%|9jTGaojEvlUJxZ5IwpPM<6n&DqcIf&ZW;V%}8S`)xiBypR z?w?9V(gIBJzWJOYHu38N6kHXhUoz9Jb89I)bz31CJ8KM91hjlqsaFG>mFyk1*BlOW zYd+?5E&w!*JEBn8_emK*!D^~+b)kDlgt$p^@O@3`So?R+k?CY`Mfnzy0fig4!R+Lw zh6fl`5iJ6pdcevfnDxqH9{t!E`~3d@NH{%$uX#AawDnegrs7?m5Imo;c3p@!R6p}V57zyFE0O@799@Mrx-oi~%l zVX+#N!{Nk=)w?$~;*Y56{~#K5wO3^|h{VR7VwN*^`Vo$Th#cH0h{zF{I1L6=UQS!k z)FkJf@ZmkN3=dTy!9D$=mEXFUe3H8fis|tJrR*WU7XFo{nA=(3H0;F#YQlflGe>Wc zSZ}iKlPnnFrg0CNZWaia=C+Eap}6JAie?@>io*4Ukse$&T@d+aK?Ju>Kb0T(Jg-q^ ziEnP;qe}&mw+nFF)p#@ma2O;SyYQc6m0SY4$czwr&qX-|rgS=~>COeo@NzSd>-gPlLKOG&x=@6Ukz6TAz zq(?~gFP^7wd3C3He9C+(~7`2+U5W``M@AAhp;cpHm>Vbnurn0i+o;y&k&t2 zN*5Xtjy2l-HeXD;?dCHQ0#`!-Yb-sND344ZCdIzDZt2+O!EFFAE_7{xt{u=p&g8Rd z^yW|jH?E^wg)SY?p*y_U+PJRWKqrJ#=pLNG0l6u_sYYWb13c2h^mCyBFE1iDoOcY-+a zPY`js^p>vAy2&8b`>sUVhV_7}d#$PfsW;|EPD8l3{Vm!D2e`xBlKcH7w*XY%F~uim zVsP!G&R_NSO-}b^D2YA&1~rKHEzE_GGO%-xqXQJtNw0oGy=ZLQg&0geO3SAyNw}j8 z!izQ9(Ai)(;_g%62n_kFJj;+Zin~{5D0durgu@+e?DGo(ZA}8#q!fD!9?I5=exWMI zC~fJ6V?F``aIZGHMZ%-Lv{aIkM_kkoLP>1d>lVSHXKjpdk1+i5LO|qT_$_d>4>`d*R`y#G#Jo;pvn^!^5YM zW_|GRQxONl-y{lM4F6*~;SmhaKuPSb*SRvvzlH0uMy zB@GUS|4kIS7`{a)E*SnJN@A1$Hvz-r86?3@LR+FYfb3}O@wr5(&obWvsN=EPVRY{; z2CEk#1y&~kxr)_B#p(r96stonaUN$lEJ_JnpawFh(91=-O~ zt(7_a2%1b!W_yljE>E$TMZUTCuYA5sIu)L}@m0Xp^)ldcKiFm8Dr?`5V{gslMc%HJ zug{j}mhqCb7jXHCmniCknw^Qn%ZGf~tf^i;(hg1--i_5&w7v?J0{BCTHiIpt)K8QW z^WM#$j^IpMSl6j1(|wy&?S-TD@@e)+%RDztJMVcNybmhrWb8eH@1bhfnS@nGzs8JyOw!R~Kl=cq zr)}su01cwDqa=uk){lo)F*s2NH5xlm>52(7ah8uxCdxFlehqBf4`9eT3rHBf$$OLNAHt>Lt(=;0U2MZ^|aY0 zZO{v@kMQAo&QIBj>ttMVsEhknBcb)guo6e7D^NcmxeE2rv*D|rVLEgG*}Yl1L^oJU z8E5=71XNQ3cLhVDjrGdK(bz9%bKK?zowd$K6v9dlt&tB;^>4BIK&cH(Um|tLWXe^7 z4FQ}br0WCHudv}-qqz?I5dcVF!~C~}4TE?QNd&4<1{LH7fXC9L(?4Er>-2&_#* zMzPzbal=gS#|y?G&I`u5ILOteoaIFI!Ud}JJNqkkzm}xW(nn|AK1L?XcvSh{{6x3uD=0ekAWkI zk}4pmplJyu#Ol0#=OFlS*3)Tq*C{vdAS#>2Eiu5nzUhPAj{%>ywUIAvEo6S>d=y3~ z`O;J^TRmv6$D&R)!zMPoLmEb7Q4GPLW87E!8JuA^HNM8(XAM>AZD}$pyK#vj(T((D?=12BqWP7CLL&XzbZDq@mFHb5?US znVwK#AJN!;HoTq$?mLUjaP?I}XW@hV$RFT-{BZ*LfE@9b{EEglh=13jH64zaO_}Zo zM=T!h0{e^4!4Yo}sbE^4NY`+zrg6Du$P<+bwT?67n|Jqb$eqJv1WKtBh@o7Qq+cjA zsca)G)l}ahA|T9ktqhCtnp!-$Lr2RDT8Y$S=}GzMbfWlHgfSXxdQ<46ZE;uRIB6)< zn8Rub^0>ryr;&cIJYIN~%HwS5zopeLk1zhPf2er(NEd{$pCLZFlr#3B{tyn-H165) zI^HWvZLQ;=zNDYyT_)o>3Ucn5@C?%VVr)}=kBWA^8E5zRt!Ov3Xpz@Nc?zV4i*gLw z6$yQS`X6A*5Y*MqjyOn(s1vC=XMe0p>MzC!R2Gdt;4e?pKVdBQweIyeQQ6qyt0L4t zZQFl#Hz+$;8wBQ;C|A)!qD=r1OL?)#mU+3?F{}$&x2|m=Sz(FPAS=b&NtR%0Bt(xA zLOO05GUrSoL@5*WaG?@H>o|nyysLkNj|~;1TeJ2MJLBFkw)BXbMoFw$8wfWS8=okE znN+VH6j?#(T?iF5G(k`7G9tuG7X>Hr+%SG-J5LaXvap%zVs1|{YARO_t5Lp zxw~gVqDJl!ft!y-^=o)*mpkN5L(+@A1mBz+o1H| z*Mt?cExxEXRvHQ`yvS+}D{S(x!W+^h_A!ze%G!Jmhc|EPvxQC6E`UFHThMP#v;6Tl z{DKbsDHDKkFLk!^hcmTYKdj~`-Zf-cb#(PqVJ{Px zp+)OBL*7df?#GZ1ABqtyeZ(?mi<>LDaRtRiWz>`VuaPDfbKb82zkP%m!W`qr*1Rf& z(YDdppe!j8!i;A%YZ=3K(lezyBEHIP6`~0U=a{WI6uzk0iqGtm2#UT<2TXS5sgY z^z_hn(ab?0yjc~Zm;l|&$!pT}6R@qWY>U=$ussdB!T(v@*RYSMn|w~}$xhKhohSsv2CrDNKL)7ijkJbv%YnfT8b z_;zk`*~vJLttU%#k7oQ1tHSEJWVtB^IfmM@nYj_mltk*S^i+$+ZkIaAsK*jQo35U( z6@q)%po!G;MlF6JxoRex#+^A<(eUCeB0p7hY3bsS@h4_5rAcIHL7o0jPqp++Io-Qw zu-Ufla&ryo-KqkXPHA@u{YT?>N})sO3qZ4!gqCR-TE7B7Y~O(Or!7KjCjhe>`k?C- zSxpPMTeEbYT{lx~HRP0F!eSC?ryI~}LYVviUiqM9ANqew;J^SkmeO@?`$XzXktb$V zzY;d1@fXbTFv_*)H2@Ozdp1)0s5W&b}d?`47S7Zg`JgZ}_k}nel)+ndE@3p&%eO ze(A;G49!LOPc`00+9z#83r6hf1a*?&#%x=-B!-}z%_ZE z4xgLknPAYJ;E|@oYf^Ps;s>nG+m8oPAC6X{o|&Sb=B{Dd5u+Z7;fG_U0z7dnIz+;T zJ|_K%Qch!30j{WD^xmcl=!YHu@IX#Hbx7^u!R)=hM|zj2D%Sdw-O)$r=vwXw{*r!< zUWL&`-n!;vO@>*h88H!Kk(zuCV4^Br|Bm_W?9hoQbL{MKh<}Qm#m7&SJ%4htVtw0< z{X@pPaGRp_D?tLVzn9L++i>2#GGocZ7t)XytuM!a4JMcY7$-_z+I8P2x4Q7nV80XV37@|5a}oSwHbI?q z8sesLC!eIWIE_`|uuHDPFk?mV`;Na(Q3p!9u7WY#T0}$CC__7Y91<=)mNFxJpjTY! z>R|OzCKoumMx@HSP;9VmQ2ODsU>a*|qp`ZLOG9x&A7nM_ggW8UZMM7mY)-E6At9Fp z#~wRTC*Lalw@A6zC1LSXMJe<>`Dr2}YPy@>2Xu8Z?ew}|tOTl|*-5VfU9)6#Az@?A zNTt~7@g8b@cNV~p(9IJFN6F!R+^L8>ockoz&U*4{f7}HA$cO=G)hONOH3{nJU)WB3 zk?J2!5nRDDlfykG7X2>?w2|cS|8o=saYO_OLzp8tiNDnE(@)J1rAuf)82T3v>J83sAkORRDLt88KNLgm2=9qp zF&g2xtqrDlnME4ixk!r;p$X(~8ahn)1WSMyVz;rCxUx2wZuVx0shrR!CCDzZr}lWPahnS)=B8@dFSf^>0fU-v$sszlpEh%F0Drso7MznU(ZbJ#*F@ z-vo?rxP}dn)P^0V;RS9bhXU^(k4bN*OiKu_$5hQi)vgDe>~z|F%<)LK2c>5^hUvN< z^>jX6S2<0xO_TQ`0K|L4-&=n~letd4B2(|TsMj^w$*wZl_ry29lg)=Z^_oq+b@BCH zdIt4AaLCbW>dkZOIRyO)t3HXU;v|zUdau1;q{B2k1`WG@;PlsHvIjEzIwxD~84&eh z17=;VI2ARIyw{oM#l*|+BBM|%6;X4b(nIl;?q{V;siZpd7S=G7wW=|~O4_xfZw5RE zfzeYGJARGR3KJj1X$AkyHF_p_Ns9A`&KU)gI`M<2=BU)hQ@}gC!Y@o>x|5@cLrOFD3E=$yXV@*8g`c`x^s}I977;Q1B;=$eHI z_2f2(s!uT7=&UN90h==%b2T-OTj_SGWL5+s{Eh1A0+F#9g0fEXo142+bB8Hbq;O(A zpVBtW(!M1R2ZNC3#Mjh;azP*TiNMM_aK~|P#bp>mpGI=Ki-^iR&LCTVjhuT+V~o>4?;q2qB}qNI^rOzhAN&^DJQ4%l|A8Sqy}dIoGV1GdV5#uLLDZL0vn|zB3x`aU3j)sA6*v1- z^$fwgJzv6}9i|FH3{6NlO6BB?cgqMJFD)sw@6QLcQ88aIJl^gP@^oLHNn|x@0xX?K zB1ZJ;X*YMcI9jS_>{%J__0)%<9CEz~u%#PaG*Uat*6t-i_rJadsELzpV_`+ua?bx7 z%ZpUo*}m=rvAeJHASnN27eV#obqGl?M2MW>%)sU@P;Htm9h=iW-Wi;aa!T$olrDD` z-_*`>d>nP+F^c!wu1>~LmGj6YE!xBpj?>stW4+`8$otqdQolo`UZ#7NJk^|-Qkp09 zpiQ0B8qocW%LW^dR&WL-1!u=xVOj-8zUIn*m0ZmJpX36gv&#`8H{6};amt&<9b$Ss zWgRQW%k6=jmUK~{r}UQuogb(qld%v4WFc~gXs$ArwWbP>Fx~+uC;b`jwR1$XvxRKr zry`wvl`zn_tBz8f-+EOt;L3~t4W;}Vh>Np5W~-)tp@Jz1dVYH<28z_jlml$;>zcbn z>q;TM41lM!4Ogn(mppu80eS1Ua)?0qKpiX4J=$f89k73#_usEf2HPr z4@O(+F$mq1b@lrQ?Ks_Nlc&K1-IeIt17Nn2;wIBiy8@`W4uG#t7XT#}=(vi^ZVImO zGvIe1IbG+HNt_{unIVR8hy=mtDH76Juk*MQI1l}}@|kR4*U@WIPUs~bBX*6^Ti-wr zUNiT3noe=!TGl%cA6JL0PEgaWa zy3@eJvEPyc9l+}||AXS%sOrB_4h4%YbQTOc3Gm5W5gTKf;LALLCB(F9vxIOKPg$td zbuSrQ@Y77$K;t8seUp>jYO({!?!Hp1c9^`KAW8QM&Fe9Foy;rNymZU|%$uTl*(R@* zc_(Y0PCgp@KJ&~HugKJ!`?!;*3zM^k0%ActK1uQzFk;q!_v$q!a(M|>dz*QG64rFE z7lj+~YA4=~ENn=!_~De_T=T*1M-i+IjCwMHTjG9;?$mMB~I1{h$p#4lfIvLwZ7#VtPvymm{nC0EN%jGwU5Gi85;qbH#H?TYN zCeD>CX-vmmL;Rk+Tuf4B%N9!+s&e}_cm3mN7GQ6el3VP{xB60m1^bVpp7a%zpuf2R z@z8m|We8)Vm_d!QaSH2~#omGDwp{fi)bGsoqSx2|TZC%s^1V~M=pgR#?KBDUvt zz-G&93KpVcVm#_|G$ag-@y(37bz1_pgYAq43^zWqPDCk1OWusFx<34&RS zE=3V3^6v^_%W?m@Ra*vh|Ge4s@J>bVlE>E?8;WiZz%wMha1Sc(GqU&NI&5HW z00Q;Q{jQCA^H$=;UJYr&Z{}WkTtStGw;{Km7?5kLy!|!}oZSZA;WmP>6ffoVbDLyG zW1W{nlbHJmzzjhL2G7-9Pm|}I322XvyszuO@YR6LcRFGccXI;2d+C8xv1Mj4;jq+Y z&ApV}-%D9rFJ(JCWt5@uKpXH;y925bGE~^Fv1tCHIxOb*}_!ziz86bXv%;`FxZ^VBP!U9#C9fOCn*P$oa6%M|XG>fXK6v zZXT94SNAzN_I7ToePcocOz%}u?gSLfg!l;`bICxP_gbDX|yI*1i^ErG?Jt)+xcc28jwk52<^A z;CZ?+;>f0YwfFXY_0`@Bkz%*xawPg9@kww25s*no2IqOhH=OS`LJdV@<8c#n9@f#E zKGX-ZX48c5w4XbEfw)oJ^>->ZE^0QibU-@mW0g@n2v>8VBZxbOG^?fDjiA*=_B&iU z!38Gf`DlIKgy#l)AY@b8hTjrax#A>uGj8)jSMb3jE&LI|;La+3h>S>v+MK|zn@t2` zJAsfUaHVZUi4chb`0FJQSQB#^Unx2RYyllh2B3%CRETF;dmKtQ&CKn~jP!%#wC%@0 zmV0FhT++1qojUSn4V>h5@P3lJ_fhg3jTGdWgha`6x{~Lz0ZN{iiF>`DM9A~Kb2&CA z4$Z__NHB(4N=E19ei2@2h1+&e1p=r9YT|1o4vhOj(feSmE%5Xu@a<#ZJ4oRh?ZBru zIE{NTpzw7O^B(v<%O~IDHl%l*p~}2D?co;kas&N}!e#)JgQvX47P2{vRW^*(c$rb- zBFfP*`kk3Y-SgE=msvl7%Ek~}xDnz7=9wcYZ(WfZKX7Y|_m|YUCC8#9w)VT|z`gMm zrZ`br_=(TE(K35=D)b=!&v1!+d!{F^k)R`?j^wTsSn0{#FCuT3b5=GD9Wul9 zn3DII&93S1HR5|*ukG&eb@HsdQkw8}Ac2cb;3}#eD^oYaYfqAD{dmplfyvk3L5Kwy z?H-S*le8$QkN7-@YnwSk`D-S^ewi=^O^%>+n4)wlKs%pH6yx&-Ly}{v1e7 zWvxVQi^AZt2K|Y|S162rsEA3a5{->?=Ro_B)Ub)Uk%i9=f^js#fc%LuvPNTuOv^EB z{_zsA@I-2iznu!>2I6)XV$0I;KD^~*0IRM8)u?5jzd+dl(S8V}7_S5OQuZGl&d^TG)l!;Z z29KV^fs8_Nav#>*m1t_U%|y|H;f40u>@aCiQtU(cxb<6Q%vxSbDd94>VJK=4P`a@O zlw5?Z2brwFi2qWTrFU;cA*TRXF4s{d0ffU87N{V?Vsj6dT$-VJDVdnNJ`4@44-qkl z4GPsU=8Lo9XTne#kfxx&?sQNN)d-I~6CQS#-u;ubhXv{hQm}6D7TAlApCT6gM+at8rExe8*XjDts6Arg*x?cJOWhe+@K89Gwz(z@dxKx@ks7#5;}&3Zzz5WzGb zT%DNPDlkYL`Q$r3?#|7OFk#pd2SfK#(b5(M%zs{|z`*8&f#DiAz&LXStNX(>!RA!! z(5nENBOlh@cqH*sL|_>uawV}qCCazVH-h;7F}x!JAKUR2dU|WkCT_f+S-SV9Sl9z= zTUdf_;@X;yUqPt@C6%`J`QQ4++}6Jd?G)qq){EDNe)UG8(yxasG>`!}hjCw7x)^WY z;$_KNNrv8p#C~PzJNO;@{RMq|1IZKX2*%kL;2|1&MHy|E80ZKkk3VBc;u&6_T?2ug z>K@P;Gh8oTBrZ!M?uJBUHXcBBde#yuG`I=a-UtIZ;2j-i{dK`ueK)6Z zzmWxvnc!oTVl#jcxUtY94o_Vq$^8VD_uga>%y@=U0F+NT- z-1Is+kK;4Lquw>!E|tg=0B8^F?jVA7-w;GHBPtD&CD!`p5pEpPj?5Oxyc?S9g{ZUz zEKEFX_7X*JY7{No&6S1;xsCHmc5Kij{wi1olFgesX0UyIIDqQvx)ISCzps8 z0p7i9egFMG!&ygz8aIN>v93m0FD`WNBTskchtX$&bdFS7-C=OtTiLJC&SFv3>?G!x zmiJ@ksd~Mkml1m_`#535EBZO&v%QSiTUoYfI;^+w`vQ++#z30>Y5m664SNcAb{|A4*o;7t6MP^0jH{B=tL4b}Of1JlNruitVlBr4{EppPoZNB< zsr|aySsxia$2lbW*yK>vi}t3k1|c|3;YVtlBlB*+CaP|xHeIgd!X%7CnmY_X>DPMo z8SnUF040iUz#&bGHtCCg@PovSWnkc)*ohY*%+oY|Sbp73>@1keSw*p)LcVIs-Sjy8 zZehHI|ASy>ql{kAn7h8Quwh2yyc-baYUaBFbBbo*9_J_VRdZeTFWQt>_Z0RZb2lN} z89oFT!vn~7Vy9hqY3ueraOfu=HTUi-*JEPlZEE|<$jn_fD`p+v{?P@HC zm30r*5_eJB|Nl_!vI|mCZE8H#?tZFosvUe*A5>d+;a5bp)7g=w+D|}(-l%qfjB2QM z1uDm0-OvZstRHkah$(^tmC#^rXr|aC3P>|q;z1OV10|#wjdjc3oQZFPf#E5jXgzCo z_=;Ll1f%XO;C|&RZ9{4M6G5z^Vms?}s`84-A~Zp-jq^6|u5I64+vYveSrGY<-2LI7 z4MixyO+!cAdt$)cvHi4qA{!B^;_D?QEOs2F>nXOZ#z=4@x&wqZw;o8_#2lB^{ob>& z5*yL0Vm4^ z83VOPKbads>M3QbONU3jFM?`}>y!QLH?YTj%Uz#*c`SNnsb_qQNAp$A^1F$%{5P`% z4_M#ecfu@ZU+d1&YROa-|M+8}_&$GUGW2jHkN;FDek6X!3Jbm@#l=)@0F-;hFVgzg zZfoys42_enRdzWZ-UzUS^}N13#YMKFu^q&E{DdqgtAu%YBhi-_FF;XZ{!e|0%bw#= zlVrZc{kyP)^!gG9;}lb0zQpQN`>;yy7k@=o=}vZJt|^1?3Am0 z3f8Bo3`JXA9{b9;B-~#vfxeE$zKz<5aUDvP<#2BcGLg~43bI8U@h+Oa5TH}?UF-X* zGG&S)Nek7A?6nU(m--dm#k0P_XkR+qJyc~C_B!p*tHb}zEUVoJZ@dn_>?&8g8SBHC zM^dj4E2d;or@!nJrMFv>p~F9L*A7SHcWmJ~R_S53*j4d=+uIq_?(JJ+W^FNtl&$;@ z2PR?$K_@vh(uoP-cQkg$cRz+n!={6rJKABspT<|P2eg|7q||G;4fQ7G?n=9v2jvjZ zmXBbgNNM`bk7$#zu3|U%1exx2{>{UD9k>Wi z?a7*_`B`6SwVc+Sp6^(*KL`Y0j}!;Gw^x3z@zaVB4i9JY7brlaE?Zr|bP=&fyL zR`GLO0@`f>?OMgnj1>AlJ*ttyO(f^U>CmA_?|1?PaTmLrnTPM`O4$zq2+BIp71;n? z;w1koj4R>G4#j*$#v85zF(qV$udAT^@ncXf0q}YBX%4qOP03nU9=!9$w9smqJ9Td% zN>;e|(o;Fv)&&D}7_qS3>x^sk4S-_@S0;g@EBopdDFWTipD=<37fxJI49)8o@Ld<& z{{o=NncO6H4$<6qIaIR!0!=c7oQ~bscxoD(+E*NMVj&T#iqefko>BIZ8)q>zR&E~* z0Oin zv%kcAM$Q`JxcZfeg8eM6P9Vtbx-)2}kLg5XN4==iSUy{((S~WX3#pp?g8k=VC{H5T z4YeL%)4_T06KbKZJpRECFlSdvf~XUtl}Vr`7fsj~L~SurU!yomZ0?2KFQG&5rau@r z#5;6<@szzy=X>kbiFmsEbH&r9QHcuhW8A1f@XnsqJD#>4nH*0`!m04&u?}zH%|aJb zicMo3HVYCRneW{?)a@(+mfL}4(i3)}ur(3eLjIE{t37CZ#D@+viN-easFq+I45_0L zHub3yFm8I1sHG|g#xe=WP<~($>78U@S24BpJtz{nUgu$2P_-QnDF_}9Nga7-y&MD)( zq!=8uS~cuyNgWL<80`GHHXVO>A_j*Ux_t(5^kDEF(`2AF=|2XifD(OR@WN_f@S!RP zgZ&qzd;{zQwTXf>`yriVwlk47QuNKAY4)VUyl6`lq;si`C}44dG{g&MRlLzhn15rU z&~N0x`#q=wHz^P901w7605BPi4Sr6`=I8r>+RU=+4I8Y)i324FI6fLX+{`2VHEDvm zSrf7j3Zak(9H|r#p@eOKUH}=?E!c?(VB9V76Fa@qLx6OzP4Vc;7Ey?PAKmE6C9V?j z*dtx}SWmjedeUBpQ+3cPX>NNC_F=CUiR%xs?9*N?s_;y!sGkb@o*yecTK5s;T3U&M zezH-^p8NR2-5v#9ZJMmpCLN$hQU(1n-_A_JR}ZZsoOb>>0JIa9gx&a@ZCzD#VA0o( zSK9QXaQH}ch{0q%+n#od$(FF~>bGS*dz&OfA4Kx_-{n2K$>-sBtO4iq1)7uTZPGDD zKY$PXv+Z51HgRPx9RxYu@W9*9?9LXQ|8&Qv<$HnU5MHt+Z@w%k#}SDTEMJTZg;*B) z$cN>Ff27$*4)6&|f*HI)UL{SG-q|VPOq5!I<7Y-PbEo?_p^dQJQ>E}9rto`6&i4?2 zLdDxLKSWcZxZjg{>e5s=O99KV29`&rCBpLeA1Y%0vzxAkvvdGre6TccN)F4J0*mFo zbf5HNrXLo5v^yaJ^%*iTuO6ZzEW>*vP($GMy8Ns?8clJv6eU~Qtxj1oZ0E;z(c;w| z7&_fsQsfoz6liSUq^NrNKY}XDc0$s}p3$=TQw7Bxt`z&wn15GtH1?G3AxR&7R>wOd z33~+%oF^-ssbJZ9XL49dy|DQ3p8?b6xO=VY?!kMiU7r^*pGB30A6{ReGlym168d!N z^zrOm0$%HxOE$PIO&!~N?)2JY=NRX#yL7e}eBotMJ5MVN%$$zf;S0{96WYM%hM`HN^RUn_w`Teg5B5 zQvizke+_H2@bbL`UN+!SE1l zbVCDQx1uK*5;*AXe9(KSXE^grBDWx^fpRbKJd*j4o% zDq`zC^UAiyF^BzJ%l2LD6>J{6^M^bB$<;#@CQCQkdx+jVN!ahuGtiwWOeX0**wbq zys-HA`I~TP4L^Hzl}h`RrTypDOGPt?#3rTkkH-0^e1$y5QF-9e|HjPCCkU=O zAQf1-a2fA&)HbywXXkU4cu-Z;57BxAFE*1#Cx#MXi5MNwm9X^l!E$&CSRPyKfh7m9 zbf#YT!8%1_`3K^@AEbZzx{U~6`q9`v28^W&#txt)29$6I6_EgFT3wFp`w2Kt_gxqO zclKRQcfd$0eU*basH0B@|?yoL{DV{(_VtycqZYnLq75!eWT6bFer zcg9y@HY~4ZV-9#T+1Yam0$H3Q{sq7wJ^B;NV4kt9Th|i^pC(yR__)SNa8C%MQ4Yo^ zgg-{$5IzSEum4!Kf)dsyTwBMVhc<$I^}R_D`&f= zmPCXHWcHt4K2x3{M7f9?Jw0_R&yV^)(9warr?EW{t2%{M>4#wuahM*~P{L+*Ty~qi z97M)><8>-K@(wCTW6xt4_tpEKLhW}S9U^DrbhEgIW}E_9MHGs)+y%ZJjPQc8aw zVlED-;339rfgyKC_x%n8&Ke*m-QnMK&H-oN$&Z+8FS<+M`6J4i|s;N6eedjaqM zewci7De#x2!Y`+l8s3pongDN*+5LkzTZGNTv?5d!CQPQf0+Iv`pt>R!NZU}SN}|)A zyJl@yU+{Oj>Jf9wVw9Y7-nI*`#Xp(1<#*5PUtZb+$miJ&)knS6qWlnwVZ3pG9JfxH zAb!UQFS@&0&xh$)h3_2!U)kmtWPP&BoezHM8xl#*cX0TJmA$#;4Vpz`3r~iW6W4WZ zz-2U+hiA8`kQJ&$O$fC2u2Y`Th$wD+*oikS=Y2W{y5fl(U@dmW6+$(a)*^iI636ILQz2HI~#t5#E|1Fg2_ zJ}>~ynu*0*NS8c)9t69{D}8$Y-qZhz!GRsd*2e6e;zQ1Y!5L3J9;Nb)T_4 zw-vJBdyVlI6c5<}_qF@IzPi5ywIK$6-+saZ2fcl~*8$kRcu*ao7jcOhCJwmRp?Dei zEjYQkC%K35(tKwehl~dQLD7WVU)AoAV#&g}Ms%(3qvBofeJLtl2lqq!wN!jh5#C|E z$fQ(UidJ4KZs?1O=gBa8N5v^4_n3;|c@B0pb^?Y^x!=G4ZoGv66#rjzH)pvkk7s0%0eR@I?mayKsZCja5XIWh}?{Rg^f-G4vezV zQ%LDx5}6d*f!E+jz*&Ny@&wg#Y{pzJMR1V*FML@goe1QJO+$aQny<>rm)B<6Tqq*= z4z3nq*O-G^;&XLi|2*Y582m+6VbY_=nfNH~srN)ZnK}i?yS*TPr`QYfkrue7p}T4w zkPB_D1=&c958^pr7GmqIQw}YPV~-2~ULU1?ew-L4#<$_EeX*E^0s|qVRz#I*2MN6N zss;J$_^7Ju>$rV^__LnB*z~t)@GwY`o{N6iXN(}s^~YQe*VB)!j$P6Eta!cX>Jfqz;$RNt1cb{_)3b--(SzFoj?r1j#ZTM6+9bnm9tywVVHlUfUwGtc zFDT3#!${U76uva+cumwq!YLjKGbS@0Mz0-eH_0_}$i|T&Hk9y%JigUK{^4aDZRieJ zIM0lWfugbPQV;r5a`Cpa%JB|!2{40!RIb9_-v)@dWS6%jAPa|H9kjQ@J#RC_cn_O) zVBbS*kJ;$4dq1|>@PM;!S?;L8y%5f{Ev}fquKT+z4!$9*w3}N~Sn- zZ8?NJP{YJW<7VJuIb0VqSCXO2k=STl8Ggs^8Y=or+UlrN7fhXRgJmm$99ThY{`%iJ zO>zXfUBYLmh}bzVn2F?W0zDe|oT<;7@w}eT!}Pf|&)uXRs99T(WlutWESE>nK;~|e zpxZzYIeF0SUn6YL4ZsQ;P5lO^<@8k@{SXc@tg*8zzC?2PD!zbpzC1c_%TANWr%@^s zIt`D?=;$A}WsUq`cVXnS!bnd+1aDyf(Kyl5KmTaA4cJM&qmCt5oosT`xuVcELO5`2 z$$b;ywLIa+l@hR<`pv0}UHu{c4yX$1d%df4kOb69LGAgE3bmI@GW2pJmfBb1ckGvk z#Z$XKavqcg8^e?$=eavm$oXJh*!4@!+g|p|IYZy7UcGX@1-W}F=OgnW=hvLGmvYW~ z$1u?ZInP3ej-02|8K87eBe&WEX^*!-6*f)&!vjG3IPz!QdC9kC+77L-<$OqZXq6(Z z1wH2+)tRhWP<77Xo|80-+Rh#aI#RQ+&(E*6V?Sa4loSdMw-my(ghI=MqS|a@dd z;0#zVIeI&p3t1&{RRvlFyGU}N0v)Be{TWMe!NMe|K!RiJXl%@J0EK%mc+0g2PDWv5 zS3%^Xg2-RZYy5u-LUiD;0c*V1&8z6lwLqq$ePm9e7uSH`v6rTU>P?}}I3?(sp(T(E zu%LW`VIw4?8OMnmyf#~>?o@(9KvRHjhsey1}xjF26&|DLpc)MtyDvEn0;Z zTxBFTGq)aTX#rq_7Ox*G(jpxlvW>{2MG>2^yUpTKz__%XkHn=w`7TOTc+eFhdLw92 z{O05`pwr5aRC-Q^7qsQf5cvU{&GYa7OcVK8VlZhu(EjN7Uz2#QFSkuzgvDgyeYrcO zUjKZ#3`7sTzTD{&O=R2>y2|n8ZkQlvDEG*h%K^v4?wBf*wfAKA-7I;%B1UqXSh3V&G;@*ab{$L~AprUDrVr6PddeaD%cmfRxc+jpF1XN#bGAN!6n zu2-+fP6q~SEE)#=0F=t0j}A%BKZB<@{A2Lr@#Zkoy^Lo)^Zb{JXH_{;2Sp_C|CUSo zKK5n`(8?RnIzjdvdWmO^lVSEQo;3>Qd=KMUcTV=~vL?-w2VN!1$=&`qWl zPWO+bauXjp%XTKv$0WY3?tfE#V;9U*$~V<-_!D}NcpSIHoTDm-0oOL- z*2@ak&$TD$2M&NE{|a{QBnOlI?yEy(Dxt4I{p!oVvfhxQuisAez@^%exHsB(C0aS! zI3y&L~cbk4cVU%WB*pRSH1^z z>i`nZ20O?GN8)x3h#QclyEE77Gc+>t7_vJ~NX$w>C_BFb1)(2cc$|j-K;`4meZiqJmD?r z1v~V96$dMmo;2=d(5MRN0s+pKb)636kC+iq0I}(-nM>_|WiBO&bGfmXxorMw=Cba; zGMBQ%xqR0@7fKpvQrjb}D(BL;rA32_gBoOL!+Rd4A*Z-J;qSq;K+q2YnJzpfyNIGc z(RS)6=? z(zO{Xa+8TPUU56_^Ur-^{kkUtZn*J(@#%r?gKfiy`HcjO*8O83LRQ_z&Q91T5Ris* zrBeWQ$!Ah^2aFy5!C0z1wER}Wna3j=?F+dU*F zxq2H-6Xfbw5D!88UO)L9yVGu(1wlBq3EU` zX#hYvn)9%Y1fdkSq8!A^awzAMm)-pYDSK8r>SVPkU=uJZESx_8bbYqWG*bdV&U!Ol zw1v8}>UJs|8*$3X8fv>Dw|X0coO&|m*fj8#BJ9_?-^#jfjOE&Jzx$8{mL4~(SGn1xhmbY)P2ErabK{t@7|dJ+xu`$5@7rNm_A?&CHYK5 zB1d27spXHs=-PIdw=YDEabaCi?@)oxED#9CAW}|Wr_{h@+CdbPk_(Z?32W9 zaO0p)&(miqvQ!@N^=eZpuDO){&{O)4I}`Mg z^BD`_^H)&8?Bhp)r&z`)K~^5#m`xh5Xh-KxNJtf|XezFh83y8MGY}Rbp7ZewIo7z! zx2*)er*6fNC~7PUBH0y@1WzONY2+SRkY5OACAT1q_QWziPt?+rfwKfHok^Cn7DVSx zE!#Bkt~{Tmg?aa5Mm06&&WMi8F!W=`)+FqHfEzZEWK9F#KgZWEQ9@p6b!3GBLAVXl z<+llP{CTkdo)0qI!|e&yMGpV>m~*rd==MT0d0B_9KY^l~PzT5v(4m~uKi^>X-Sifd zQ&xO~yj_N}Sjf~r!wAN{d5y(Dm@r=gee(!cB7I3UpxJR6vc+fP{tTnt`2J#i97bLj zn+Iy425#Ku`a)JxaPko0&;xZr$Se-FK-Q1aihSco8?2TSCfKfd*yhZ!IgGI&PC+&h zn*VQ)3QBxb`|58vR-%`vHh^2pus8_RggfQ5%WEZ2?hlfWmG1mJExZgXi0Ve#jmPn2 zaJ3*Qu390bDR6c5U#XnDxVq5h#N%q8zbD7loRR&+)%6l;^5ROrtnA0tzS5nm9Vq)M zg$QV;gQ78qF8NSFiNuI$-$eWlO zli)cRLW1XDAjZ`sc)r68p0}}K$ z(bR9MfUD}^#C#ON#I^{~7-7Z)KUMD6=RKmz7J~YRyX>(DLDsW)^qfLC!+{*147V_E zaACGq<|~l96^<|K)logeKT4&e?u^CD-4!+`UheMuXL7lFJ?O|CXCO8bnpRdLuonJ1 zmV4J?gNT%fS27P}PTW>snGBdzi+zH))}C0NJLdOcd4B)V9$B8>AD3Wxte=FhW z@%u~eXpKWR#(Sb{+dzb6p~k)2(K=p$Lu^BU70WcsKM+eSzb1GK>ecMYE(n$8N=#rQ z*v9vArh3%K#@pQQ2#Zo`<@sZYXy&$=ef=#A7|ciE7AROMT%^(1JFFxu*sNdvMN?6Z zgB!UM^1%9a59m&a)P4zj39=rQr(bbr0cxWAhtOkfFsV>Sf{Q%a2|>dJ7M6B}1@SZ4 zGO-oE&_LoyWTSl{0`Aa~I{uUFTq5Z6I=j}xAZq{kw2eTFQ&)|{P%av9Um?dJ9n5O? zeE5fEVH)4}a!=pg+!AR={}=$aNNzxNfEbu23)2qqLVTh8fw6-|fQ9RxUTH7Vab^0y zyf1PTeFk6rc3+?bH;t#<7ilDFJo_S9@Wp_dURI|kyhYM__eDMwPem*<$ds@zGU6z@ zxHK7GYF}hNkQ)2t(Sq52u1X7uYsAbveR+c}`a{5F$r0 zg-%xqj54QdICx)lDvnfK*wxhAxH(5QU&Bgq@2;be3o0C9W z?}b*Cj-8+-5az~x6xik0yp-@%_QmC{M2{}LQq{U6Ni9+VSiSIDiHge$lTZcjMC}3c zUCZtvbRFutkbNNU%9W@Morv8pxnT50hxrL~n3jZXZXfFS&t65VbXbJKesfKzB?%q6 z5#n{Y#)C9CYox;-&Drv{Oxh@Ak?za!VP4qo9nS5AUN5JJpO<9lUywZh zZ75#6R8n#s4zd0DoiAu$A*(cQJMtp@sN_E8+mhbz;c#CK$IMorptbSTRMaWIVfmaq zPuA^)6FVKOS{8-73m4bPA>vk;#{$#j;ul9|;0{1UJHs9poGu%Plt<^UqB zk9Gn2=~Kg<@d!F1PZ=7BQoxgA7C9?ErxPUDccy$EW}cbiUIO}fgxa~H!2HI_$u}Fv z?&ENqWhrpLsFc^-B(S4z)Ei8I zY7@0HPC;fizoh}OLvzOvQSW_e`-4D&R^kO#!J z1E4kpeYPOz(;6Q;X&fuSb)Zw!iN+%OOy=!x>?C&+8&=2(CAGbb*dGCa-ex1{XPe-3+6iYV;!hd9>Em3zpc zQC{)UAeX#q?^dC?RZiAR@;G~`9JH(P>KU84;qMEX6F1Rp7dC5Yt@#II50)E$bTLI> zMEa+o8^?O)0M%et4eyrbHR=sk&^!8q1%>bYXageS10A+cOe=|kE0L8 zd6*ZaAP&6m3~}k;(==EHS*rAP85fm)Z1_9wM%Wo!c zINdCG@&$%g!IiOmnGgx$o{(>=Xtt;J-i&sdr+wd}4fWLCo6&}Q+V?%$LB859M+5N> z!_#q*ap18^G2wGdh!O?unsjR6exY; zqG2X7Vl)EgZAOqP3Gty_GHKhvz+Qxmo6`w(yU%fPjXB9mRZi% z^m?${&O#&;^J%LAsN_zc+~L7pg0}h-@aEQb=K(G|_4(cQMH$(|=xg(sr1{oT4r zBs`uYzun#sjx=LB+B!iyfpY-m{s(j?oFV9|%}e`x+IVLo=Q(iy$z@5n-?9+KeA;_% zAq89&sm4J2oj54{xQ67gtO5nBcJy+C7cR8P`Zkv936dt1iW0B84UtX8uhJQsO| z#92BNV7otdDW;6(vA;_y1LT1^@CJi&Oes;8&{_2^4=&z^Dd-0-G9r70i)`YeU}y?l zth?HWi&LNQ;o`YZy|^d?oQjJT`zGL`9NYP^#RC-=?@KDUm_)Snii>GpT%6rMTpZD` zSGXu5E^-b}fs6fNAob;U;fvcD^Kb*4cldD8hTAF>7Z>f5fQv!hz(q0n1$^;_q=JiV zqQ&AO(NL;Fo4N%+1|&emxA)}a(;F{;;Z;fy2zB4Muv-XSw*>;w3QM%v>$J)i8&<6D zVY3+k8eHEBKX!BYboteUS3n{>z7~!BfFcs1F=;ohY|iV*;bUDJYT?x(Q^;+&Mc8xF zx6D!Es4Ov;kT(PY+0;4S|VLucrEq z$B*kpQ*Efna&^0~!ee;2_^e@Pm@L;y>*f+1~@c$9M8YS^b)SmXA zzZxYM7nfb6u_#p8wiHyc2UBtBCyofxh#Lpymr_bH0B(F}0NRIJg=A~?n2E`u!0{A1 z3F7uz(wRZ49n`jX>j5{P9irlB-%==pVq|BTo_)up^SuO|>z!}#-y(=$hz?v0sWI>U zIO+l*!XNUnt8*W<)Yp3z!`rVSadJHj53!eRczH0-2AAF4;goaz4wg5bxk@PEv?2bv zuIcYwZ)S|&L)+8;<<8X!@XKT`0Ty(!Dd{@A689OWq-)*^!cE(Qn-<$3PZDRDid;)# z;lh;j&ca=To_UKyH1S~nychL%-uF`%dgeXp^Ca^IYr@9^M%;NP<-Rp|$5GFN2=@&l z_x+HsR>2sck70hUqg-#fd1OBSzn@3)x6ISOf!@5+^lx8p-g5oh-{e_dYZ`ds(edY( z&4Fdyf=DzQ9TZQ$9eMR{gh7vYV)p@kOe=s5OO!-&qWpX=>sYO3VeqUoPV$s<#PKS( zkRs6iV~M)SdEWK{9M+9Ii;On7FpfL2uw1DvM{@9WO5R4mMR?N{P!!0l!e!$(lFo-Y)nz_pja4j10{ivapAtZKeO~VtNAb4-yEku zmku0u;2;73hCA{iauai6WK!gGU1)RYR5Ir-C#S*WTxN6X+7_}#uKNtkM`KM-{bzS~ znaYo+>l;z68$3$YiEP{d6x({B?f+1lWBUK|1qPwj@!WI zczF{Snf-GHdf0vVn|XCl4ahsIyY{cZ+MtUT>G9a9i=S#3QdSsPd7ljwwAgqjO$Dw z*kk;U30H?gh6w1PkPHI|mt7iMv$Aa2O2EG~w7jx96kHJsXO1FIl>}=m$|@^@t3s=m zhN{6!{L9$$h8clOI|L>(tFkmSVM6iTIrFB^1qS*%59O*FK)k9XOCB(n#D4Q<&CQ)N zbL#ZmQArA?&z@C`F}FEDomgtKfWu?&z&`|Fj;*& zVejDDA_d6vOUi38&a~OH3;g|=0yG<+s^F9}Qk9%`YO0bmPET4gFXcEaNih(MQjEl+ z6hqA{m_0RBGbu~aZf@?vIN});&6qlOYSKw5kpck(wJ76(Kv~7=lJc_BU`h3g+Eq}4 zfxydG9oO*dOZUIyyAM6M@2>Xu?wmh6e@0+h{@lQ{3+Cnq<}R4Mm_LdGGiT46V}9o5 zpOZJ&{4Sb}dFIXuXnqNFAuY31@jNku9DEe>54D5+T$D5(us29}nEnT@2fI%H$TNzlkvZPx6bIKWu!}8;_Q~9I3q^2gYta4RVIsRKwgB<=hba@qO^VeeZA(`Q_ zirP@1G_ElN&fUQ|c$ZJ3kG@|_kIcmZsVYJm`F_0Nz z70FZ-z;@IwL)Mxyk|7)dra5|eWmygW12UB^F0WixQqG6UH38H{VfESou?!?jT2?9v zXB`k#jsF@jYHOgu1FOrb!?oyRbtS5cy7t+5>zS;Wd&^qt3o9e;UL<= zE2*xn2ns~O@XAoqjzJPWy9zDFE~~0i-)GqvLY%eisfziRhq`=t*kN!qQ)n%*7!ey&N1z>p@!kGQI zj{NneDHKw*xBjL9%Kr3MOo1{Ld+RSB{;HWqukaN>N7#zJ^*59HrXST)1?Q zXhB>YG$ci`e3Bzsel9d)vV7)geg?!H8Y4to6)Mf3^t+F7qff0^TU05Ui&Oi>^c+Fi zc9Xti(p@G!bcU9nWYXy-z1XC+CcV+5KQU>WN&jHd&rDi>j`lY^SJPQ0Ei(Dj&eQz2 z%<~r}9g(N`lTEtFr0Y!DSNRW2y{)!gzV`P6lP)?}pSPOlw@ke+OukM1{6eA25?7!g zuskp-aCW9wsZR>PKQ1qWjVLJ>7X(iAvXY8mWkvZ~s=->S8|WsO8kMpjwRw%Gl)Y$% z(E@=(XXi+Il1W1*y~(7Hn)E%B9$uvNi%oi~NnbYU@bk62z@#0;`W&BL)kk>-gt)ex z)781dl$B%lFy_Hhu)Q<$epSN^&zh%jyg66XznHYgq@SB~fT=ggq-iES!lWZiI?|*k zo7DCnpPt%B`D>>9?f+8xXVY(dYR8Mux6hFUil>w2Yno@$J3SQS`VNaEc9; z)oo@VtFpQj0ip8DQKL{9O6khM#<>kHXMWJQ5%Bv0>jnn|Tm!#n;T{N1u(OgC1ZF8c zsSBIA7;yvNpo?eCp1U}I*5cyndAWsC(WzM*xV`vwt2ivnOP0YaUmIt_#BZ@hi)WfT zf2FYz!C{-Sm- z#v;hcn_gMVdKGY?u_h^?>9ar?CL<05Sq2FI;L4vE+7|EWz&cdYfyyed?##5B$jpzp zGPV8e;Fx}cP*aI)9}t)w2^4C(G6(D>isa~^)Cy=Ka^xUf=gc)*kQB@i%r3{OwuS*Y z*U!t~0ytEiqy$46;#tXFiBJLI@IdY71yAAeiw!k}P4a7IVa=QwI6LS-;Xa2Z)sF(LwZLf1CQ5ek>O|Ee$(N3OJ+rbrokcI>_aA95*c{U46p`GJz!jBGSvmpZl_!%gc$YM>_(!~Li)ZgBN9LzwL(?S||HbH=yWa5D&z?cy^Xx7r& z<;z3WzzdaMfNCxPwZo-5&1CSRMS(1XuQ-hu$W**@3Y0AfkcrvGcw4cF`Q*al7CGHF9Z zpU?QVrf-5LWy zU-((svXI4OK>mnNW#ry#TPp|p+MhwV3~U}maH6ax%gHAUMp{M(rvMJyV6?S%SopD7 zKgOLhTEXmnE~qtH&5HEv$BvX3^fJa5R2&1h{0lO|S5aCM$8&0Ijrn0!(}9M}4CE4( z3>u@gZm@L7c_EY&s@_w>kZ6$vK60;X!o*3n#?2Tq*6mV8J0C4V zQe|x>kf=2?16Dl-vWx@@P<`RenodBH8gHhO>Cl0RlXYx$FZMh8@-xjjg*bgnsCR*tG`WNYxn$mg%XN6y9V|uwhWQ%N7^sUzi)59Plhy3^i002+q|t zCH5WCELE>Q%jLwN$%^ApgXRF+8homfGz^{Pfdl-=YR(`^U}pGQrkqlZP+8C-P-uIH zHTx%rmV^!zM8BN{dnAWDibd2+Z`#ZSgn@5`(Datzn2En{3gP`2_urAIKmsPbUzAE>={>fYTbLVfAR~#MtQ0U&-I~w3@_C4AQEyn51 z{>4eZz-771r-qdMP4z%BO%R~Bz)m+2R}GqDyREjOP?L2{l9RarUMT4 zkN3)8eLiD|KfSmjaB+3u;*7w>7Y8n`4P*pQ4rKV2fZU`?wFrzW3vfG)oQZkjzkV{F zV>a(fr*p3t;VtgJW?>^2n_P2B)^M+;CNsG|;qR!}CmL8k1v9WmmLdCqt3u(Gl~~3~ zEV$xCIih4D!H9z|$CjdOvS|pM2@aekuNP-0RXYRinw)cMQK*BI1~!%<{l3@aX-baUs;RAcu*v>wH(1CdL@D+8-8EiJ3gsOXHkJt-{+5?QlVGE?BGZDX4i(tR4yO0l=!R(POYvkSz8pY4wfuK zcmr#iKt}Hs81ujhs^BD9&M)r&`5~M`!ZmQC7pV4AuFwiWiTc39!OA0+BxxPp6zxh_eX>+2iN)kW*QBZSLya+|%nhN}T3hQD_c<+Fn3Sdw506WzO zEFiRSE-`q{HgK*taN}ECQ!Fi*+VbWRIg*`i=9y#Kkv#pK-ne|MtwOoJej2>}So&%e zsb~MA;Xw;BM4O{8L#jfKIi%qJF3CcRBN zIR;ZqsjQ}`vIa+=DrKJ(dVG0F^;{VTtf2mD{8wk#Ba!?vpA z^0HNk=^EThp`3`@^JXCN@-b(Z>GqQF6d}kcgda$^+Z@EJK`aZ$4mDItLu=0USqOl2 z3kx>h?eR{WZ{NdiEDjRKhm3hVRu43CZbu#2={!j9MxY_*2&tBoF2KfnjZQ5Ap48n6 zD2Z_BLE14M0Ft8vE8}8ak_9~&Nf^I>-QoQatO()IuEA7-mCJ+PW+kPL(eXefXu*=A zbj;bVJS-@y4iza8CrqGl?0L837nMlwyfWtLIZu~GaHI+#B+Vv&g({YDLpoFq4yU{7 zG{m9Lr5ZOh$6IjRa3SUCz_U*VHIA1lc9$BvJiw@!5rHKm(f!o z8GAq69*$)gIAca79aNru4X(sLz`YWVsVuZB#%MSbaPs^#L~IoX!Fe^{%Q)zBOID;L zn>IG%?A0&SbMtZ?ed}-IFCv{S!y77=hC)^4YsWD3hxei~ z0^S&45N|s<3L|NKPk%-)Q9t?=g9cA6H(><*ORXP7{b{Q?q2*Z=uwvJ~TJZZhoIBrC z4ZOS#=u*QKt_+uyJDRI6IDFk=%BlMmu?wCQTrhjijN-*bxpNkqmn1|%rfx^XOsB}g za+?;iFTk@!(wDTSe~aU{K9R;LZ)e?EiG$&ICrb<#rjNZ09E>Nv>Df6$1i1a)?`}w8 zocDwdp`KV;wt~_YuNe#@^i@r{1^vapF+!!w#&Rm30lu{%*kldY2`6hyIHUcN-97A{ z@+WVJf!|lDNv+|TR_{@HpX}8HGkKC9b*f61mf=)uS*T_d5dM{PLwxt$k;fLffyF&+ z7AUO=`)JT^+sk2rHykSg z4Z)x|h>I6XaJocT67Qd^6!!InX)^Gx$sSZEU5fR*@5++ZFf4l5m*+)Po(jOg#{9#X zE#s?1CDg*Oj~W;fNrbzS>po7H5YMaR^t~8{%@CvuRYCdW7UUM@&YD|HA3f9VK0&c~ z_n%M=FM7qPs0>ky>I_374UGkbuo&VaR3oMX4Feb1dIhd~9N6pT0zLU2At$V=7F6S< zF1+iM46i&~?Ey@fe{Y&`$c*VqL(hOv znZ7)FV`8wjYDIMkPVugA4(oDW5>Hi<*U&!|{0I3?9JV67(+Yg`!=)I@5Hus#@`m7F zLQ8zF4DW@*>%@y_;NhSsAFCVXl>qRJBb5k{%$}8NJqFY7UUnPs3Aod<@h6HMdXRQ5 z1w@^@j~;>mPH1q^TF@jut;Lr_0|wvy?#}XqJD7~^Z=Zbpc&+Ijzu(>Yuuck0D+|{Y zg{sZWGL5`&!lOKD6#GuPs8a_Gcs0-cYD<##u4k~P%OPPi`l)Vu*CTt>oibbo$ZWJe zJjnmY-kSi%Rn-gJH)SzYz=DVs5r+tLTH26wBZN}YB_)9_v1y@{Vme7CO(4m{Owy)^ zS`e|~RuQ!#VnxJ&s1*>4YvrLvK&=~ApHJ(8rln{>l(bRr_xqpa&Y8)*$t0~l-}imD zJ^9VO=lst(_w3s}hc8k$q?KP}{y8np$Hr7LO^-|ZdUEA!T$|2%e<@$zq}JR{HNpPo z{9k;8_C!$BX3E(yJ7?cBulA-X=W-IFQ%l7*ILZ1*m2*eZxu|lksEef>F&U9o?I)W5 zw3>1sx#?S0U5q(?Gx0WNYgD{B`7IBNRN0+Vxy#DrX_E9+15VZNVodt5PANgk9a1pL zm-C}~j}e@g7b=ps(6P|g!r%-QBzvH+pN8H8CDlnuJtbbxh#alFDdO#{ZA{d{>tV%J zsNv3a$Qw(1|Bm5OW05&6urG9vYp0Mu<2< zCX){G@Ye{|i3jz1_+qKLq{fiMryCE_l%E{C{`y$1iL*1UeA&uDBvw~0UuIhWc0f97 zypVM_b^uV?SXr&N#VQZTM@1^$-EqJC#7w*oCn#?h%XVlK#u@Y4utElRQ~=3@mc7Ag z)j%uO<+8+xGUEi1jI`tgk@9fRFQ%B3QIM>0HkKS^#_=0A@(EJ9IHnfSsOh}&a=lP% zS%=KK=)St`?;Zi`l>f5El{y>D$T*|(GDOdy2~+TD#7BxRcL*+cub{u5J>2IeN$Kbe z>rODf6g`Ax-#Z`YW)G4ZgsU~HEz*P2x_QUe`ZrkMcTkr|%LwFBo``Zvf>Q65oNv+0JUy`KB*5 zJuKr^tk%%OZyU|(63TBqXxEvPu^)EpNYJ@xY2fS6HZxVGdSjwtMJ1}nAf~*W8?FSW z-DD@@fbA`iD00GMc;mQGG_Nt$;mlI1)eo)gT!Ax;!!Qb$VA-B|HS9O#o0%A+tT$7I zQZr=fsfq4+GNG@VFlK_seJn3HD(CG~=a5*DdG0(00p)#HbZ(T!4Fh<@U}Gkh7++QW zXo{y;k}e9xD z^$5S_5r4-KUNEFQkv{y;ByUE0!Ze)zkS#4k%8SFYR=2-YG6`}!qj_DO%!`oqOd<$( zLNBDt&EGPzLq6i0)uFE>Z;_L~hczzgK-!1mzhP_@V-ex)mfR+!vmXr!<01Z&m(P|_ zBQn{KTx*nfyog#%cRZ%3iqNh0vL~OgBB%x=du3J>i2SgX3gc~NUNzzDFCxBWGeU|6 zw$3ucveHB_UAk#%cMdatsMDGn|I9RrYwYbNo&7PPG_v{T&SWx&9utb9gzcy{Bsx)2IyEC#t58h|jzm3%U8sHcM1xoi&(h zthB?ZI#@kBx+-n@>@hu=__WbGB!A}V4D&Z8+12Pk%t_lOovElW@tki)Q~hdpY)Gfi zv5QB!pOvFc^I66?s8&^u5BJCre~jK5<)M)H&F*L@=S?^g1kvfPQyR|dvyGJn4I-o2{3 zUA<^h4Y6ldqlWn_qM(+foi(;Ny7V(te5~nbs7=zY9uh7irJteJT?QF02^J)d**cx{Y91Ou&z1OgSE9U)Hi+ zvmmd{jB=U6*~V{}J9&tEMQq~8kO#vt6o@Lt>&zjIqv2Kq*?HozirZ{pT~(vKDv=hM zR6kTl2L8#P(j=6xPHdB1W!Ys}i&)jial~fk3&bFtM=~f?!!X}L2Hz0{Utvns7+bcX zea>7a4T5y%6@@=n%?Ed|D6o+2>DgP#eti?}P5X%>>2G)g+226&eQDGce1EsRyS-f& zWU0^TR@;x~>PlxU>+E1TnECYXf@HTW4x>Eg1G$y0>nrOjD?R^$7yY%fhpMmfZ0q?i z`V%T&^pCrEsM^P~^t>1Sx%DslXC_|s+j7+RxxWCt4{v$VU;IAo%2CJjT=d*`)1MQT z*|!P#(#$ojf7|c6T#AnUE~|py?)PBU+*rQ@6T98Zx-+KlzmC@awDujT@4te6Q|^Y+ ziCCw!XialNcSdmBwiPpM4FxLx>F@p6a($n_tgtyCHj?&AZ^lOqpAI?U#QxA z9#zMY3&E2TsTaoXtd7A^_*-TNn$%m$P>sBXOi>x%+K6%9LrkedI-FSJ%zZL zLJk(D=l@>Ad&{O%^Pa|i)xrxt!jYb^tT*5t)cctrwr7w?!^nj5@Z#cDjyv|_Qn6mO zIA{Qde7h)9c2n3YNJ7`TZoa29?N1#Z*8Lo7hq_DT&~q|Yr5B|-DZV?pWhl}NLS#bC z+8HEWRn?lO>8nbvwoM>uk+?ooL7VNb!*W*HSF}X=!(=;C3$O|7wPYz84c3!3*~Jp| ze4*fcUf0<|>+U+KSX3O_WU0r0l8tdr_>m9sYN=7A_odRCjOZ zzG1xK$a;tIp)d>ix~EILB>i>i>FAERc-{=>uuw*u7|GM4v0il(X<775?}KyO_zy(BF4lulp5@kX{NVUGgW zJD&AU+0cMh2918W)!9}ld#(9d#zEDxHt8?ywXFLyv(so`v(=vwVTaYPQ#&<`6ngsA zZF|h6=-75u1;78(+iyX8i+q@7<}29m!)>0ZFDA%9I>*Wogv@2JpG{Mf?68~pke@v? zRJofpt)|R4?a0;8&luQb+@0#oB|)tv5co)f8Q$Kwd%?W+xSRID$~wnnlpdQt_b2;uKcah=2_oh zJ~#^EKz2Lk3nCpM!RKc?5oeuBq>z0-FOz^a$ph*sRj&O40^k zxR?|F?wAJaEm(-aY#jq>vU3a#P&EW5Bgk^onQTb5s8t)J8Y(Y#nPM#k6Y1?8VQb{X zBWmrQ^yt%4>$4O_t)OE9Uk<=Yw5n~ktJ{@-VLJQ+LPUsis))R!YwZmyv7+pTx(Z_)n0Q2#9X&p1C( zCt8&&&r7Q<%!}0x!(qXJ6qL~V(8bCjXA|n@>ZrQ^vxg??1m(W%3Z@&&%jYe<()q$X zL_atesl1$>>f~(5x5y}M$5)d!9h$z3`t&5dp|`R39`)y=G3=Ww4zv?$|i~tzF`?^q!Hzp;S2;mAt5^B zn#Xv@=*(gMW)1je>2Qt|_Z)*V;uTlJ^EyC-#2+Cg?n_y2FZZ{7W-0F9XK#j~abL|s zn|O`%hPXe@vCIAKJXSx&{o8XNhTLoS)qbNR27hiu;e|J`B0n?yI3U z*)(q0AQ1OS4#DOA4j!5x;{IK^54o4I^>M`FL__Vq%KO8*9b#41qoU=(K2r=H%V>q# zVpV!=jY+l{ZDj6qW6X5irpDyB<>q8hyrt0{;?^;s`f8)FPWhu~DNZIBT;vGLmIkwE zjuinM{UOIIvI8hTW#2t^SzDTDlT8}4^{Ufqzt)xpbVBU1FPrJt$jV_Eq1A<^2|Rtg zq<&Ofl(+kwN2PLrS=^6fLH}oDXY~6I5pdG9@>M%EK{rdbN8zbT1dNyRwLUtWa?`l+ zRPcCIKC8AT<=7A#;=jONH)fa`u!45~&>?~R^$~XC_q&!3_)nltUpC-3pvVTRGaqxv0q$gEwV`vQ0TGw|(b(S4m6ivbXxZLnEr>ROe1%xT zRkVQ5{U}&jBax`5LD|UWTY5OVrJZH9axyiw7kgTCG*jT~6PHPb4J=~i+ud`|Wrt@q zm9dhIq82QkS6jdZ%&wWGrJ@vMF{@V~RsERf<2I z>cdQ(EX&K8dtk93V=){l%Mgw1%p$q5m948K!`anljO$51^6;(miWaj_Db5B5W`Wma zRi|cc0iygrf-&#;)PO%0)r6d@?&to-js&A)0 zm0-=TO+B}k42tc1#XVD4Wr{o<|B)7{Y!Udv)}DBxGE*x$^>nU3Ld8jMk?v&@tK(?! zki68AuC|qzt@Va+Kaf-jbVy~3M^vvmkya^aayerP_KOnbmVWFFW6Fe|vWDVzK4nT{ zO`?;=6*)e#49_I#Am_BCGY{>XX?G99TID+lZ|gr<&?86FkI9QB9PrO!SR-C~cKv`q z7IpH50slp0t$HQ*TgIrqhui~>`VqhN`3_x@>Bi97U_O|Ea0zO+u}~a5q;K9zdA2aw z!R};EbD}tSYNAV@7cn+(c*Q*f{#evxHLL{LJ@E{wAQ zmP0%4>Qaozy*u|;VeYNDur*v5@$%WvTg=I2-5AUIt^eim*G1KfE3?B|R~N&KzS^NU zcO>q}j>~G><}Kxjka;Vrmo1%~HR`8!7GmAi;$F(NwgxITC{lCyeKiH7a^w;m~KzYQlS5T z99uPHj`TRTO8#bydA)q^%_sun|E96r&guZ2L5jjPrKg1%8BycBWchSuvfLM&bH;}Z z=TDRVQ?fHyjzK?;ua|A3Q8f~D`=foD`XYn_-t4$suq=|1GQK`j&PaRA>g$%{*sSyT z@JiYxQ&fM|D{AbPwxVpTAzkdCJDFaZ+#s*&W$Vjk6hXl0k!&>(At9F)ZjK&yDl;-H zDOTEcFW=h9_i=5~jZ}ND@_i;JeRJ2ffwOm1&tE=f(Y^kq64uzjz-EI?Y_!v@S1TN7 ze$&w@^}KwnQ~or=2>QDg zh5{Os)TXjkR1m2P>@%W*)2$L4f(Le)3ytD4-RD<@$zJUZaYO}Rkq* z!p}xIYmA?ygjNX#&-|7|QrV+BKzN9?QnGLpKZ`*zH?nn^*L6eXa+%`9rNHlQQdFAu z{fB7egu@X1On3~@icijjOQVw%l!Nj*WMSvA$`UcVRGt&07(~-AtinjlGxFfNQbTzV znsD>87Wb9?W<^>~@?=F&YpP44#3se5!I%3w`2`2~DxZu0ly#CaW!H#Yah8{nlJT#6 z873>tv@J4^spP6T3`LCx3@dB~QMHrN-WT6^o*NDlSQMVoInESGA{P?Qh$`3Y7k`Wm z^X+>FshXu}b`!v~G{&kMDRA@;Dc(xFXoKRGTp@XMs+tH}$g(O8 z2U^yn6293vI53hUeYIOf=rKy|y{!5n7`)U!vOJf0lSIf?PqieXZG$%GeyLnzhZPYwV_@1;8uGW&ZC22RKiPRJd@Irup964*koP*D7ooE#*2aZyk9*c||rU za{?^$H29WgoPI+JQ7MNr304xL8{W3@K8zKi?J&E0f$NTIuTB9$L)BJ(!`B_wl!|@Z zo^@*<3I=`9mvz>yKlmm@RTx%}iP22LQXTwivxY}iFHVJ$E6G$A`G&XLoOH{Rkq z^iXXwfvVe_vYaomn53l8$u!xm??_5nkF(=tp(DX}Uy+vBwnuKbsB}7{>5%P4ZBD~P zw>u((ShfdKxlW}i35(!uFOfQ2FS}SlQ5})5Lrj@C$XM-!yspi}9Vfi?Lqa-J*JXNC zMJqdK6j9V^O*IjiDer@xXE1@6u|v%h)T*eK7oZ7{9aIvfL(F*jIw$WS*YN(+EAhp1 z8GkKTtMfpwSJIS&hdv1wxP+=`Xo$Wg zFK6?T(7dEIyihBw`^e8vrCLMfwTAYsW1e6t3pKAb!pxV>juH?ZEfKsA*36h5WnOfK znx8#0%Dm|0m|sa`g};E&2{9k>0wQ4FAn?CDjCcX7B`#!{k9YwwZ{Hv=zlf%0lmmgD zW50S9;Xt70nAassNZG74bm&OA!SGq8;FsE(6VV%|Nh43nFg4;8H22ga)$G@+s&wm) z9Z_iT^9hIj_#*gBe2yM3Eiadr?%a5`kZkEqV_UR_u0qVqKB=^w1zFSP4r`@));7${uzYU=$|vC7YZ`(AKS1wwg`=VXe~x_8x|{NV6XnYbj)` zgHNHaRXZ=p#ys`1)FPerfnJd;4pVFBbl1pq@T9lW(n#CLU2r>`QE~Ibe;n|~q8{8k z;J5S-_+Ll<6n-z<_n$wH9zM@MitoYbyt4?55nhJf>cT!R3+yTiam#8JnR$K==Fa+D zjeV)5pDrJ>XC3G!=~8{AWp*OSeD9gB02}bg7$=RkMiw?u?J}pKJ~J++L!IpGiZjl( zu{e=dJ5X{^HQRsC-L}I6cK<8+`qAu{M4g7G7#tyOlAp{5SrG;p$0NLC$Wm|AB6p_h z)912Jz4D;H4E0gek5I?1KIoUD9(>b5|Hr7mpk99cL4O9S7L`VQ0QDg1$Ed%cUjAnE zQMITvY76SKsK-%%L=|lsoBHEh5Blez9(&6{e=`(&p1Wam>Ja9w5?T9Ocs% zde1?>6ZJLJG4DO-cilTS)o{;2zaRDKPapJ~dW{{QIp}`^^?lSJ>g@XoZ&dEReZCPr ztHiwhE!_6`gZ|f1KSLcr9k-n@L0yPifoenDjQTk0OQ?QS%@=q_)DQT*3qFH7_JM=` z`yU*g+KPFrMArTmmOOOO{|;)|7x5cv?Zdc@>iiPnje6UTgZ@h&Ip}{7Rr=+F{_DSz zQ9sDJA8vnw(&@V3U##XfXUYn(-0cWFEkA2vlJBldOIaB%+plKtF_mS@^pXWKpkN1? z7RZ6r$__L5{*bEBl8w&Cgev!0sSHEqOJ|KN zXsodEbr%F5PL`HB(j$Cc9qdO^S2`ODjJI{MF)DkAFq);**uip$oNb$pf93q-;SHKI zG_I1WH?s?C@YQ@;$p@rn(*p7C!2r|9{syEVJIpyqZEu>GT;hXU#sp?1Dsn z17lF$)R-6ZF7{-vT@Fv~PO?9CYdYzzNqB4Oy){kVns#qZr?;ldTeIF8K9cHfA@(f~ zd3Ge-{NJ$aA>JvZZ}uOx-aFrJolVo6r<7mEF{d9Gl>gb?P|xjbmX|j%{E=>^$0sW@ z>7P3LG}-Se^B2%QpxiWFQS}PLcOS>vzYK|G+XD~XN!DuS?k%H3+17C`MaR}t75vV( zP8`iTdvPP`a{Xd|i`lXGN#sW3FYCrw>SuSK194Xky0P{m!H^w0Gk440esX$HY(b)9 zQhQ8&)O}%$5Ab9ICf2{TG;PFWLpNU{ZmdYl@EE(+wH3Fd#4;|`Z!#ONPG)X5nEBJo zO=b7fX|w^>F-EAI-jM2+gMyRmniA}VB@VMEQ>=|1g0`>d$XUqf9IFy|*CX+|46JlE zoToRCQQNzkrM8*x&KMGu6T$2jmWt`?Wb=(yQ+$c{Rx zbH}b|W=vJi6_d{%^)AVYbu63@q^HCu>x0K+QHHElq|i_YF5q^mURH2e->7Zd#T^!E z1met<<0(!gV~_us?$^?6t4}s0#6h)oLiw8DQy*0`9_xG;cVu7pU-7PEe^I^;HZjG! z2OD0Jo}^9hh3Uz;2@RZWt0u(N22zaQnLWnz9%dsP=y^Eel5>Lfc!BR^bh@RnSWOr) z-fe!xro~ESR5df^-QCj43Rl}g_w2IRj6Eu2+7PMjqQ^aLF0oIU&(>SAC#W1Zz!W!O z!?J}`r>y89MR6*SUg*;*tE}s_GinRbgjAuj9?rO7>|_#B2H^v%%{tZyW5&Y3-^!Ps zjhx}Fl+Hw`+c}oX`p-~%13!-a^^Lvk@4+dBdY3z9z$pDVR*uO9QxeRRouu{2WSqdD z2U+x-TD{D;bhj%>bGCt4d4#Ov+*G>;J7{b(xg$$!I;a4o+-}nwrBN!_p?XS3J<{!r zI_GVT7rvkUf7m|vK{Jkt&NlY$HoGYO`}XxKTAG?}&v$fRfx=|IeL&oECT^PasnZ`2X%uwq_ke^}X zb@OGYxEWu~dB57O(iz?D=F5({wnRtuHA`#jW^l-c^XfyauI-x1ejm-%*HqSam9Z;R zqP4CoC3lHxv^o+koz<6JQ+qxqRyh8M2+CksGeW;~#$xh!>jG1v2F9K7&Qkr(D)WZu z&&ts-5tDImmbKi5eQwkR_qM;|QZ#M9q=Mi7%Kn&jXH5Mc{C13YtoO>hUw3fvXKwt% z%ay;6@qXU9xc<0rU3~Ac-b;9LEdTWN3h*dO##bllN9ykd{C(w7&I9w4VxqkxYfDMB zRz-zJ0U`8-PrmHACttn%k>fDG95w&ZmmT`b%5VHi?pLGKN=Mn)f!}g1O>zLRTGOKM z%fL}tyOT+1WUh_eo|d`wy0||IcQ--Vk1S)_{q1>gMx)-5yWYrcHge<86D6^%scyWt zqyMP>ss4(2aql)GCqZQ8+~9gY`tu#RcN@8_Moz+?pXx8eh{5$i9@YnUo^nUr+iv6} z_N;ryIOaZ^BX>XdBG+f+3h9As;{`$7%l)^|pW@iF)5tw(56T_6+@IsUe`LvR{p*Ycvmd5`WX9gm`{}cPLA4%ee6sKY7)u``eI{^crM8 zf?kxqV^0ko&X%6V$@X-MoHeoUL)zhlpHmlcpXOy zlrr@=a`e%p-lJ4KCpFzm&^Zn>FGW|(N$qkBCQgWSSL#puUb4TX_`%kv1;$=0EcNHf z7&seB*=(;f`EjwmaTrm57U$NBA|f@IlrzKChw>I~c`Er#;^!17<%WEB&d8FG;)U$l8)SG=Y!i62`}>-ae)h#$!hu9T$TLq^WUtGIce zYtU#$#g8p_PRE>0uR1?u=a?^|Z`*!i!pV}1+1ijsKj zgCZwwBAufPvg(p=@%#aly~Mo8{RE1fwAuEcBsGm!)PH^m-1gg(+>6|9C~}hGUWO7m zDOv3GQ-0iPZ=jeLx!*&PI|fRc6*)K0{e~yEtLOTUm>0PNP~@a+)9uTGtdi?lo|mKS z)z1%+JDRu?IT_KG(;n;x;BFaZWn4z-XMNO-K$JOaSCl?8e9Q%~!GP=wS1Bvn8L>e~ zho$G8^Qz@ve)Ic2D8Zj~S^cbs+)$s$2V%VG@K=;R?U~?1LK{Y6Q$ZJ15+(d>zb2pXllDdKCH?i$)StQSKuK@8;ppZusW;v7?<{4$ zz^i}~j^ZVW3n|B5tEm561l)3Z4)+rNtDwl~?+?>?r{_&eW?cB&C%q49+cSTo!kwK> zlbw92oK7cI3`dz0o7{Xe@Uy#j-8tn$_hwwszoO+O1VSQ)rxL%m|CvwxKA-C-_mV$G z6Th}y9~Q5+Y!GMiX%E?WJxK)2H4RR;H&F7Egr98>$!9U5ZQWY?({zK%+iW#|K#?k zBwTXy*U64eSL5as=iZJJH1gc$uMVYO;Jw^2mq5SXxnIk@#6zo*6EDBf$erStYeC=5 zm(51bj!Q^c+G*sZO=vF}mvG(79hZ=_qKnc3?^G)UWt{F7=RSA5P1-?SN}s-iV@}3v zv_JI2n~XoVKnWMAle&$Z#I3#FgTDKIx#Mk8U$0k&3sl~+ax&iL%E`E%gy%Nnp5!N; z4-2yT10TzgyTi!!8oA?;>oM-V+Byb5g}xguVqV;P$jFVy%tj+8ZE1VSxS1O+G9D;$ zUo~>l2E9%hE>L5+R_+n>-S^vJktFO zUs3u&c(dJu*brsT+8(8E>{%(>xg7y}bmRT-{S$ouFp~dA(l_s?zkWGdH%Twr&MzIU>>6j< zhMp&N$>XRqQEoXe?TI|c7t{)KjH^rP8){GESZ|MkUR_^^b7lzZ)|g-%b-^W1R= zC5ViBeUY0f&V%jzR^=(Q^{>{}ZCz{h5q>PUH*g0^=RA-4qtw$&)*?K zI%>;Bopz)(b*##B(wmo*B)Qzi6%Vp5$-g%LNIygJl+Djs2Dy>^JDPDGo8~z$ee>iCg zA6u`4htIemZ%FwxJ|r?mF+Qfl#}=r@WBR=%v}}2tJs&X{olA{bK^!IFG!sfV6;QwG ze3(5SQHs7RS7PMm7&*Icj@!e!*grv?QerJ}RR z^Vn_QRT;SzMo#jK4HKPzc);~~RK5D8|I`3+&z8^sUu*wJ7|WI23RaKQ_^2Ik%}qbK zEdohDQa^{KpFGD$Yl9(S?L2u~8u`ZaF*Ik#Lm+<9O5CYa(k z7$-eh{x*up%sezM~z>av&ss z2Yqd8P~s=X&2ahqhv>Wc`$=U!Ge4VgIy-;=6mxF={)v&>10`N#nPKVn|oD>HKcDdnD8 z-=s&;R>)MvNbQp-eZ94%W086HDDyUGqV)e={ZaM)^G)G_r)>E!+VVrcf5xJ*+GE=} z!MZ2i9nX7S(5}z2;cGcue_qTSZPKrt04=lLI-g5PBc+~B+49TIU*(p6I`zv_eM$ZF zC`#HhS^0wd^K^#cSLO;S|5SPu6H-!1`$U&}nRaJJnz=G$dM~Fa;F%%qs)3;k<;ahmOTl5w;mM#i9aVAxueZ` zU6FHx=@mJ0;y;l)-N+qd*6WI#TkgFoM^5}Faxo)!tas4YKFePJ{F)p&@t??@W#nGs z>HYu2JvV;OMBnWviT^|{ZsZER7X$YSGr{Sdog*jy6S=8I?l|vnft*`rOwN%L|A}0Q zksI&*HIN(cxHk>``OdxgPvmAAxtDq`1aj^=rqUca@t??*8M))VzXWo}JNC~)-%X$5 zKarbbS7GE%^qy04R4eNG@V>R<&%WS~@3<&O&e~`BGVef^ z+`aF3>uGQ7Iq^=32iKq0yyXP%&slOm{`TTOuT7QTFZscZcWd7AB=1jIa^E<9@WqzL z-}UTY@wnUWu;wjK_MXj>d#-x!UHund@#t@mbL(?!-cs!=VsFO4dbYtGgIFNKx{|Ws zW(+@&FP%LGIV*zv47Z%I&+{env!%~I)~ow413=^tCjdnLZ~{Q&4<`Vc^tQZX4L(oF zABG2H1En!Lj-afMJREsBN>k+R`ZT)^mS9bGI_vH^UECfqGOTkaQ|6t(YDihHu3IJJ zypw1ZO<=XCUdir`?uJ>V#~p2Z#?JA{diN8tcLKJZ946*GllG4-UuBJj)aOS>r;OWOocoabi1v>Iw0uw11MV>a35T zO=a7s*8f({((2p$d??{#>yg6=pFGDe|{Q_dSy1783rpKF%ln580P=DCu)F;cxSGSophXXf)yPu9y117XG$f zlTY{`=K58Y{&UOIuy{DhiQm!0L+-i+w>=TZPAOlcjUeUAe^NehUN`HfCEzV_KnP+$P+8~_Dd5l zob}=lKUT`K<=IBF?rcBS%60wr^5akb?w`Lb{qsk&OlIG7^C<#L$U50XDA|aX8ZU9a zQ?}z3dayDWwNPn7Y;woBCH(DszE0^K6~u?GKlLoV$VnM|i}kELFxT1ekM_o4RQ;I= z|Ki+NQPNUI=~&NeXeD#aAEm-Wr%ZQbMz2q|`6)boX6%ymc}+ufn@WTyvT@Pg1=SM2s ztb1XU@U!FEdi<7kbY}mH>`^>j{yvT+lAb3ymd)aKp5d1n3`a)Nvy9_@_u7Vg-#+ta zpE-_uX;1w9k9U6P)bBO)Ntj7`R%gb^Z#I*XFW}s8iuW+i;Byk4I%E(mWOzS-+P4*j$`%>S$KEw%xM zJrce;T}i0fD?7X@dF+-O72M1FFNP9c1YB4P9MXva6SUtJ$(+?V*V>*#d( zIWDLC%%1Vh+E1!8VD|d9pn_fQiU{+4*6no_}4`$!b9ZAe*9?ZJu#&bUNU{+4@n!WOw2eWc+ znV8Q!n3WrE9fSGIgIT%%3-e%7dbwqJ?mU>x(@8nC5K1{E^I-P<-0ytnq3@PcGEXOR zRYuOvgNb{#tdU@?MBivL#GDO5e_dxn)e4e3ZVO2Xo7sF!?BbI}hfTIbrfq z`gR`7EqlV`qx9`On6!(ByQ1{%Jec$|hP$Hl?YM`VXT$7?(zo*)QSoc-iqf~^Hc|Fl z`6zwTf7X1RH9uNr`q5f4$~|lENcz^C<$ucjp#2_7w-1M3|NT6kKNID~-6;BhA>Tgc z*Z(`s1{$nDNj+oxf0=SPyM0)Vx#=i-E#!yD)j-|emzqhg?DpXjp15*V+^c#GirnF@ z`#s$K5e|3$O~OmwJNvD95OPWX!S3TD=|g1g_)D&F>EA_-4}2%rF!v$j-<5jGw^sJ5 zSC_?1;d}+R8-sTPIH{R$xPquZigEMp9rf*)qu}i%r=kBT#HLcO6RClNQAlb66xyyNA z_HSZ8z*c5BQryyEs`7Y2(e>8%BxWhL61M%~zFNy*oGmXXkP~zBZ1) zJ`;=VJBpp7$o~su%h}7>vfq4ij-T_(|89I&;HI1ZCH{3>k1qdhipi@_$?6 znp7vUZWwSonXlo2+O zlgp+*P4!6a-Exioss48GSJLhEP~_Tq*)+f1zMnGa{1NlEuV(kHbhOpaDEUquemZ<` zD9W5z;<{tQIbU~FIqqa?>t9>0{D~>rVc_yqeER3MfZaQxJEOC~P|9k-2mlv3HUVPqR0$0+m~y zY3=NEDD{|IU*)z-Z20Bo?AIeVUt6gDO1nwiYlcUnJtOpX*jsI+s|`VI+U`CF#rBBWqVB#BF*Dn_t?8B~qTbWxJ%eJjbuY%D3$FRcup{ z_MiBtke_y*&OX)DedfD?hxO}dIJ3<>aT>=QOpTxx__l)v37_pN2$Bf{}o^9IeBZFgtPqC_DeX5 z$~+O>sH=9QV_A*hkvzXuhpfCuMu{_WFX^o!ht{05^+ZV-E=qon<~%rzXI<7ku`7nE zK)F|#euXjczjjWl916`bsVkPRT(DxYIm&ftXNCiI;v1S<8stnw4sFsx3zjXdMaI=o z->lnHS6vM?nNnUpf7!Cd*%C&hdg+R?D2>wDQ93iGN9oL-8LG1~(jC!>a7eTwToSDa zrxq<uI6f~}B|ljm z@W*bRQoXD5zB1<#Hg2SrXlYO<5{@9|Z9QYqzYBFg>S5GQ)Z?h1pniqwM?H`FJL;&{ z4*KI!C!r>yUW+;hH4QZrCEhJkFV)tPZcB7EG|RbQ3$<@#mxAI%IzCw)8|Ve?Xfa>i zmjpF5eMRRO(wlCRR%bp&AcU#i6c)VTh z0T)+xP4*7kTl)39qP5Dxwe}qn+Ox4#lRi&VkMrs<7Lnjp*a1*ZfMhKVRU>=l=>k;0 z4d(K**7I&SXV8BVRWfPNzYX;_)XMmv{|M?elL!49PY`74d08$EWM^WcoI_Tem z+K;;IvO)i|sFM~C`rW9Xpk^-_^goVzX4#;>yoUUM8ozYV|M}~=U&-_3gZ@`mgsZaJ zLBA2T1tn&lg0o;JigP?$B(H90>1s}Kye5anQc6kgSI4xjr_j;|L^??@Reuekm7V?$ z+Zq#qu79GuB2hmzCNpjvCflh_l?^;IH5Qkt#L1Eni%p#`Ry+P1gSC|Vhi8FFO|oxX zM{}ZG(uSk}ofS+CrV=l;H0`2%%tck)yjqESomU3*; zDI#N6RzAzyzU!~IJ{u-X)H~#5QbI45mq`h~{7f#GS2J&Z_2TLkSLSElZDEZZ4vy`a zSPIGs9lX)y$H?}N7;hZ0?Uq%ZchA~Ee>BR+d~1TT2qkhKsvq<}*Er}eYoMIDc692b zR?0o2MArTm-jg2me~o&1*Pwq1>P@K6qke~aWjEy}>aC~;QGY}&Tc1&{c7Drq)!wBt zZA|vWDEFqNnx?4*fl{C9ryN>LNl0^RF*zpGq?9Y)+BE1Nd&8i=0JRDAHPk`W`8U#r zKz#xAEb8314f+kJkD`vfY0!To>Z!L=cB4LZ^Pqn*YQg3~|0dKoQU63;_|8Fp1L}*Y z=TYa~GU#86x)=2u)T`b_dkFPEsLJ;a`d@y}p#K8=97-~Fcx|ZaV2N;fFEe+i%OZIn zory<~tW_<%A+jQ$(>_;+GIyutR9I8WiL3OF_3_N*lxl6wAAn#kSl*S4oNa11rR zqMfg+B4eAXjIyi||Bq-5W`09_7QJuKuS4B|`Z?+qTL%4F)E3nDP{+NWJb`*2>Sw4~ zw+{LrKs|EXpnu;72K{$^h%|<>X+zlV4{XSy7IBY#;;y_Y^_$;4#al~>l%g&MgH>z^nv3s)D&HIl= zeF^jFJ17r6rsXcUlXB+clntoQd}4H}{gZ>fRU$j{?#%t(y9WK2pk|>OQ13-Og8IEt z63#_g*}5Usv2jsns*QFH`^&R!V0#y*hd0I=Tbej^NbV%Xk*wCsmb~V`b=5c5MXl$J z#X98=wF7;ky(=BlS*kg)o@T7gzA8uJu9uH7vF{I`CeQVfUr^goFQP8Gmp&otNz}{l z8}zS4eFF76)Y+e*?m_+heiU2@AN=f~zZO-rq$RD2z%;FFh6frLo53$(PrWG*4*C_S z)uOl?gXDNfbOGRL~ExUyujmgg9H_LVLcZ%9&* zp;ND3*ALkba}276a;`!3Fvp;j97AkW4|5FaB4LP8^Ek(_3_1=msvhPTben^@-gWhg zYV6>G3JRweZDTbE4&$Q;0S3RaLNrq{4e_s|HN+7|FULaF^~ik{^)Sca<;$uU4slaG zlyMGD^prH#7Bh=u)To-ACKlvY)~#gfVrSG&H$cn?o<4z0597%=$OzWz^m?W#fr4g7 zUbd5;G9v_1(1=@!##BdFtfRA~jX^#Nop^hyeVXngPu97G%swVDygK_g^!-EB^*pmm z^zCoq)%&#i_+H8&R3GYpQ1rnTi9!Kp(75;V5zZ~^3)bCLk*YymMI#xcY0jA(U9maR2yc|`zkoZb$?MES+O^l5 z*N|#!OSLn9R(xJ&ra*cjJZkT5ZH;l-{hYZml8qcdm~3yL&Ix~BRAm-F#A{1i429)BS z1p=8b$yN6GzhfR&+!lAnGXF{qEM4B9bDN2)M7xBn=Pg~fqOS7wE9Wit^xu_BFI&3o zilueTg07fXy|lKDdZE@UN^#DcEchZQO*z;o+cmIGE*WDD6XS+m8>LGW42ZTQ(-+3N z(?*wx8j1W;N1^~4I}V~wpzJ>4KpB~oB#!+CnHRy^5o?zyz@|835D zAvq+LXlO{L)5Ts`_OY7T0|`!6Nl0$|S7ZxfFT}Itd+R0Yui*_8Winfkp|Le{EuEzz zqI9}#dsL-T*UI83a}}}MGfP{OjjbD}b+^+TXlPE<6PvRBnWk^DC)v=QnNQ4=8!A$< zBTsSV8e_6u$#u-SrPlN9Kx=A)PAOQ*oLpC0C6rtv)}NM3r(b(bX`7}%CaHWyXyI4vR+&Grr!kdGt0`c%Ws!M3 zDQ1}oU~GnIPPz_hFYOl5l0!2#*~rA}##_T$$0SjsBvQPUW}_{ckqzmNC`UQEwml^d zS1zBo^peVuZik7Aa0^sjF_rP6cK#%KGNnIHr2JRI>S&}Wjn>1~b z^~dl5pgud2h;;&1Nsda)JG;j_yHyl_Y^_NGOnOa;)^yT4yU{zl8(q*UR6pcbhZn=O ziKw%Sr>ql))9o~5+q;_T^hU$6xwKOB6Zfu%*Wb)mpt*2YoSYBSAXslE2<5hY*YW9KH7Ofzz(OPNd zC1hmcvP)@&1?e{=zm2ZF_#aZ>qUEj)FP&d!skTLsGp#1n{S0wB zvTLbKkM%nS^XloKi%B9F% z7FAargF;<%WR+J(S7%+<+_>(lOpcu$3v7|Tq?(x;PEHqzfn2I7zD%ubqimxzRUZJD z*)1o)_*qob$$DxUX~|gSvPDH+yUb(JgVdk@!?Ak4LYA)(JueS&X}qzdkN$wRM)j~` z)94+vw$`MyHO3#L%D^L&(lKe~Naj*ttMh)OAgchq^sk`~L_zE8$_?T~8&J>eQnN&bu}>dJU}%?+|Ay%39rli9gEA zm67$zUbAR?YOE!-KJdPIXq{S5D$u=zj9bQvTn+6?)VN?)5vPoXm2;F18G|Ft2bk19 zTz~Fx$~kX}ZGbHAZf}>7MQIUKucif3S~{=0E44skcTwZQnU(7+SGKONtW&KJ8w%_x z5Ggbh$UDf#nN zE)Ubz^0SqGloOek=a<+w?3-GLv!pUNN`AHtDaT0@P`TpDe2Fzb^cB?mU10Sc`;0|O zfBH~4>m#LKI#kZ;7cF79xrb>dYM|6cvJ1=gLcCGrVrAcY4+QKB=HhH4T?qNlZ z1FWymcCm6=NzwyMbV*q$^P4%&oD-{DwP5ke+Um#8ajFT{>~#KkGxNjFm^Hio*R zwJ34)>zos-t(v#Iav^gzE0?aQTQaZqGUHv`8`&D=-U|Dj3*CuUnW&xDDuv|6#VX{c zPy*GnTwGqzek#%|AGO#C-Z6?>Z_1=&ms$=|y|j8o^}NN^tE-n@Qg=o5imJLR=2i2_ zR;@N#M3t)Mti_u_^vblnEZ7ddxsjT8WMhHrwp|q6C>n9R-PomCnC)(rFJl1qsZ_9p zWYlL*w`-}y&dV;XTd=rt-qO0-s+B7iGBL*h1^NxDsMe1!$(!ydiBdJ>7)ML^HcUvto|2C4CcA%)STMojN z$kZYXCxu6?nU}1-OPt>84s!3;XS0h5r~C2F0ZyYwT_f1t6UNiV2soe zl@H?@QU>5)wF0+cdKelsSb;DX^K5M=JnE6k*h{Vs0)~8A?P*IxhuAe3~G83z5y+&4dhIHFbuhUC2)<9J{ZLaj8Y+Tz`v|6V+I_s3L zDYsmI$j4+71d>U zf!d46taBn)Higy(KDJ9Lt#qnQ zYgx-v8zjTY`U7z%mQE>S5@f`Xen!R;J+(GQ{Dota+G3nZK?_hmyrb$>vNF0A<7_E9 z7#q(t>HIP}Qy8k>7-Pg*()b0Xr7;;(r=G8w>{V&!ujPd#Bw89<$eZ=u>5cMo63lwt zxXGlR4cXj#8-g-;(UnRuP1(LN2-dVWenscTn4Woz=_s6}$`n@3$XeK-6e{*&SIyC} zITsIH?X8p&iFj2vS9@2<4=*;yI6oKDxU7wiAMcH~d7^y0$JB(nbjSn};qJ-+c_Nl( zt$9mRO9Qo_Dw2w^u{N2+IEa22$GK_ zRk^6DI$DsKZ#;taP1y~i9Vp3CvM~D|aZeT1cFQFj)!|DpC@fuIGj^K){X zAPB23tDQyfn5(6xrXjSmobguhOZB(vN{5X9=k4YU<>pMOFlFALv{YWn#7mj{79HiS zz)kl@9_|mZ^>SId!g4f*1S+k=CAd6ac7WFh3RM%BGwPIP<&xS9>K4_`tXp5XD$%&O zjo5{vZZdQJWQ-}2x2E$t2T&(cY}NTbob?NCpO|MHHj(mdnJ356W{ z^NNc)7GUK@MrjZkWkkkwCo;++B13!P-{O9BVC(Uiko=LA&UHG=8JP<8|M2-&$Iq;4 zIp@+DFPT1lMXF&H$k z@ZRy!z5Z5s2<|wEvxo24>rdqHx?4ZC*Kda9pWN%0y_`MO@8KSP^gT1h( z4}ZY>9^dQlhTnz*u zzu_-nFYJ7Juippf{1JO$Gn_aP`(PRL`uF;);N`Ff-Ve9JaeHwGu7bN^@w|P0A&1D_ zJ%68H26t8N^P6GEqJ91r_-(iyo_@(be;2$S9)SDdgjZv4)jq!hHdgQRJK&e$7C7Nj z7I^cLeg00k5AK0?EybPJ@ZPWl_AlG# zuY$3feSQyI1GmCEI(d&Xh*ubgbKbPi-vn2|ZSZmEy_S9V-;DdPA2!3-TlV>z;U?G% zcfdaQ0_=w+Z^hmidpE*3ydPG?&}J?zkinZg6DpY_k#03kNhms z8(a%F!cA~9+y?&+_gqxqUGN3uD>)kgHpAOtKm0u`Tts?#fcJx^!74ZtHp4A&3%n0* zhdbadIQ~J>0o)8HTtfPRHPxj5FXI183%olY#-7Uxy#M~vK7Zm8!V8wcQ+6N+mp`)4 z-(8FSUnV>*C;q>}`@-YDhJWFuU&s6v*#8aQXBGMOo4ntZoGb8O_y-ol9kBH={J$Fi zeGB(t|F?N>cupVgUPXL-7yIB{kMn+O3cNi}U=E(~J<<rP!Y=(vZL;8WM;htoHxARw|^CnJE{59dajmXnL6*>5ZzY#9iQ(nLl_!O*x6JA8_o#Z>X7CsC&!3zg)AFhWx;e>;P7c7Eu2;)o` zgAc$exEnUZs}B*ruod>gO9y#Bc-G$uFL)E2@B#88EP=hS2KK?8k5OL!gY*nv19!lw za5sDa4!}GAN&MeQe8DZ-@Rv_Mfkki^tbr3gRp8wMOW>v6Gky)c26n&$a0~1yc*fuJ zY3iAyc;1T~+y$2&{fxiu-U9D;$2{Yg+()`T7W43|mptPSz()$7@i%{ld=C5Jq2r$M zo9`!|jpsQmhP|)~ZvQOd^iu4Fx53!wDZgL^+yU3ZeQ@G-^5F^GKTJM_o8a|u8{7%w z-=sW-Rq*l?@h@Btx4JhF0eU|!@Fu+i_uy<;0Z%y<_h2#H z3_lNd|FpmxfCF&-E3yA)$itr9_=P{GT!C@;RagbT4|l@CSK-e+*as&(O+JMs z@Mc&8zYja$q|=`9x5BT(o$yJx2maTqvHuUWQ%*+?z8UsDi@#tWd=VBNDDWn~2KQkn ztb#>n@E))gZiWY7FO0vIczV9Tn*q1MeQ+myTMYfb5MF0uFZ?mw{sQT-i1>l8dmZon zclNl4vU}+BFb*rv;yvK%vw08rE4T%|laX0|0;Hg(34;R7B@EX_)dte{@ zCG3X-u<*~Ecee(4csi_t%V9J87TgSf413{kVIM5K8hLmYEIic{jld_(8Z9-UT0G)K^`u; zmhgf%!Cv?%?1Nq_;RWZy!U4~_9>(F9VHF&J&2V-b@~{i`!UtdBpRDtHfUhL6L|@K3N8u6iT#uo3pd z&9HEgGf`n2c61^SZ-ve9_%!nHm9Q5U!9F+*_QNt*_;>c|fN|IatKc5k4EMv$^1KUq z*a`dKA7DRx9v1$CeA$gW+ytxOKG+OTT#r1Q4twF{un%4b`{A9i@SnsBjKkR*kcaod zW_U&q^6*yJ3y-Oj=LUt zkNO+N;TBj055Z=5#+#9c^Iw;=*`H(yI~dVgUxWxJCTRmVJ|%E7UW?S?1vA) z!eem%UC6^rVHJD`Hp3_3X1E{r!oR~lIPu-c!=5Atw2Y=+muE$}+H z9o_W>9Tm=un9(epmsdr!n+yNKE-LM%B zz?9=H|mhdbZ^+zn5;19?~iCo(>{7?#0ixC);3G34QFxD_sk zyJ0&VfVaS^lS${I4|l;Ga6jA)UvVeq;8}3u%gGn84>rM7j9cCaH#1K7OStn4-t*(s zXRrxYG0t@(+;k@S9&UqQhJ~-AUk>B&_-)t+&w%}~1Qwn}`iF6N7p#Imfz9v$+yWPV zf_wxohr8e=cmTc^PB@$XHY|aw?;`%-TVMx#H{1fh4!6T!z+LkElgPt6;e>O@SFi*g zdpGj12zJ0Va0|R1ZinxMyWlo>06qXGOd`Hu2|V#r$ipeH2fhVvgDf`5dY;PY@BT>WXn4ZZ{R!&_nDWXgM30$X}<7w(1~@RED+H(U<4 z!$;t57{3p9;fLYGDZKAza2IyNRq*$)2OfZ1;i~(IXZRtw2i^s}a|^uVK1+PTQ(zT* z6YPLD!!2+h+yVavcf+echul=sDU88gunPVXHp7LVM-JA&?eHPE8}5VyaMpI@rjegu z1$-Db!{5QpaQPR=@9>+j50*SYIKjEFuo(ZtINSlNVAq4l!#m(+_!#Vke}H}Pu7{9^ zkHf|uN1^eODFC#ylbO_^cH>`q( zU^6`JE6BqR*b8rgeejpCA9`O!eg^Lc3yyz`_kxYE58e#> z;XSah4FAA59RDrC1%3`T!+y9K&iOX-@Galrz2NpM-kcVG@JK;Cr9ysay$j>1^!WjG*tbm_^YvId(fIK`CZiDZHJK=}n z9_T~wBE~0oArHG@1$-M^3t#p_Dz|pAz2iMz{)|_!RQ+bhs7v!X5BoxEt>L8UC%HeE?%{^=|wN z8-Gqb!+U;#9NYzWz+b`LZ~zX#WB(g>=TVNrGI%{)1>XyMVD&GNhqeEMJp47>4KMi> z@^B@bIKROA8Z3iPz*X>qUn37Mfm`9{;STt!J;=jP!vXk3IB@~(9askUz*X=cum`^M zH^{?Da0grncf;jy0PcYk7t&6GWpLGRk%v=%M?ArDxD8gpoudDH@&~;AY2+#?NB%%Q zfd7QO@Qgo_k6;%pyM%avtKb&c1Ao_#eegNB6Z&uue0(4AUq$%^stI2hgKvEvf5Z2{ZSbRTCw%6wlvnT|oN#G@m-rj$45nZWT=F9R zgI|O@;iduJ6ZXTx%ZP`A_zQj>cEGQ}E%3vGge&|M+zn6oJK+l7_7D8CxWIcqtbhmM zTKN1w2`_l1Pk6y~un%^_e)xu?_WP@r6nGzpJ@B(|D}4Hx{eB;O^-K2q6PGgH3(Me+ z6ZiYg@Y`@R{2lCt&%O-vaQuY*em^|zr2T&3vI6gX7>Dyt-tSkzt6?*2c{%d%X4nhw zJOz1pKkSF6z5@9g+Kn&{AAnWxG1v@iPDLL6686HauiWqNf**O+e&2gN_3i2V{Svqx z*1+Xw?DsdpTVnhD?Xd8i{r(7@Psgyp0&SOQy%_xo$%``{+{F}Mw`oq_$Z9Ug$! z%-`?FYH82I3Yb`czhKE_gde;V?to80Zw2qUnD>B}zMk-gt6&eja3%hSwQtz(?}lH2 z18~M#>|aTGf)(&yxE5ZXz+dp!&AbPkc0KO_AA#}9Io;_7?1x2fCw$1zy9u zk%w=Do8XIEkcYp$4SCVuN;s^dT>wkqM_~=T{dUa34R>M=9`$kF=Sso{#^9Z>0v>{U z;C;n!e4d;%8Mah5QQ!%uyk@PQA)9=LcX z_QTci0Brx}et*ka%2l`>-U4^QW#8ew6XX{dgAc$8c-nVyA10pQJz)pzhaZ6@^^}{i z27VEC!2g0<;1A(;_-nWe-m?dPHqfs8E&hjh!&UGB*aH_nO*(=cs1M#uZ26{IR~(>iG24Q=HPU=2`+`(;AYtO z|4?+t@lluc1HjLX=tRT|kxnvOgmf9H*}B%FwJ65=GJ3lT3w zJP~ms;v~X_h$kUVM7oF{PEau$1N-{ z6!@TA;uMCbdER4`YnfohX&;nRj4;c)SasWJfqyc?!=L$}+{_YNS=;r4a-dG0&x&J3 zP#niF$8{{Qg(bEze7k?YKV4pCnP59p?A1*?2Q$Y7EHHY8cxD-%uAYo?6B9ha6vuWK z&*zxqDHeFcnc{gf!*@7;jB;_056VfdVwxM-$nDIt>Z}jSMNVLFhWi8~Ji!>_A@N+q zG@oE2OU!e~=fpF^;GLe27-6KRcur=LzhIh+*~nGQb0dq)GdR<88Y4W+7(Zo_Jsy~T4h(;WYK z@tnmxSF*?*4Bq8>7#7dpGsgbseo(ICAZ9p>O`OCQo?wZYKGtoPeaa|%e!;r4A5-jh z-UsCdj%71bY~>RS{L=Hq7e6Rhb2sB$b^ZtCdN#3vo7v3%Uou{fVcl%|jT!D^6DL*K zPh7|n*D-vz`~H`Wiy0>Py}tVA6gF_y1?Iz*Y~zjnKPZRhxR0@#4}R@~axF`&XYN9A z{0E!a_3P%tZ!mC=>)ilxoXR*?u#Ww{VZ3~nO>AKcyA70=%NeRSUsiMYMdF!f9S<|Z zx@z$}&K7q0rg$D;_+H~1WWLCnCIr4EOGwd^0dtS~WZ)Y%LKEEOB2Xdwz4XJp9_r)`4BO7#EwG?KjSNUH^}GZro{KaWm`K>rLZf;P2Wo z$w1cqo>koQAN}$uQw$w39;QyHJD0JIn;Cl4x#)GY9OLawa??3S%URC9;ApvpTiC{3 zk)!3RW%k#_N6QH&nBu-mkCvO58FjQ=k_qcUu4aaUdT8^$To>z~S>$rIP(Q+dgY(J=559M_T+3sJ%$w)Df3zHW(t5L+M?O&}_BeU8 zoMtr}IhuLSV3Ensd|0kp>3N{rhvfu^F~vBuoWmR&Sm0Kcc#z?z?1wWxEJqn(f+LyY z&ToELZeq_tAC_A>zyIwI%fVIZ#0VEL#zRc9&#({64O}ro9)9^6@lSiMV+&`ojSEH_ z?`l7}UP41_x<$l&P zFjK$W%w`^BE4%(ezkjg*Sj7{p;e{#jyo~ky0ULObdER`N`EUk9>pj=7n%fy?#VqsZ z;$NCSSFwp(*utZ;jhDf@)$MupXO!P&f+LvXR%W@6IY#D~FRx;WV;J6GAKfFKUu1$8 zF~#A`ayD~Z!~z>wV!U4b3%+KQJDA`>ra19l@tnaNhs{+t#u?b?IhR#zWerPg=J~(U zj#o19qW#P&PGt>ev6juO=iqtv8*jc(eYulG9%3-(xr7l`&$mz6<=5)VzcR~H%yCfK z{1|76|7O)o#>E=$`HlU}Hl`U`ATK8{&lHRNh@nlL_i1(E0oHQ#LgVFfHtO#k|Ho!_Um`DS8Q9`}#46s;8ZKikkFuU+Ht^hs#WTWI z&Su~hzrSD=SF?uQmWt;T*7KKa;KOX@Dz-BCi1=phSjAtmh7Yrrt60wx8(5VU&o@}) z2?k%a{~xuETh)batawa+uNlX3=aNev*AM@)LjBmz7ABssU--`kb>HUPKB+xttaJ{T zW0o&IrGGZ9(w?)P*8l6)l{K98jCJb#ni=kGG)``Q);M{P!R^lP@2wBdT4#QImuWur zoN@8zP4+Rr{RegVllvE|_=WZIFw0u@e%^feHXHfr264P^qda;0g%NIk(R_IQCha+! z4Sf1#^XE>sv1hY9fA;*(8gAWgKAiq1^XHKr=Fh2r(Vpx7Px~F_$r`SILwmmUmj2oF zw)X5LemQ~#PAwY$PW$VyIx+qq=a!93bJPds@qf-G z8~Mkh;yS-(iRZS-v&-`4sKxnVHPejq(Er4-N7;JvTWsNYw((aCz3F*_)!fZErw7~0^<2mXE@v~} zI=!vj#*+-~cHX#(A(~Vp|*0A=QF{2 zrg%TIe4IHpvB1MD@r$2pD~I2ahf&_a1m`lvU{CQpz#NC4t^FSNCq_A+2{tpuzcI_h z%(1SQd>na>d|bomU+r5ac!DYR>@ALind2B1xP~R>7%sR^eO^4nVew2c%LUAFJquiR zZd*C|u6gxQKd$~lTe+1r=e3oCd!2tqxP~$AW0K)7ww2Sokd2(r7Cz55Ze{3i?yKh; z2RAXn;a{@8e6PwnarBqPaT(iqfT4Y!Z&=Mx-?nm`i&)17X4u9i_Wp`^PGlSBG4yx8 z$7D56G0s8##B&%koWv%sW(%9y#!ngAZ~hmE=e~$>^C(k1|3dqc6PV``w(&iN{^35& zYJT?X^76~9W11Njnd8U->da{jw0eGEghv_U)^CVokr_Tb(0cK2EV1uJ*7={F&lu%M zCYWT38<^!@=GdcJJQsdbz5|}yS;Zo2IDC+E#MP|lQ8uvm#m*o9$X1?U;63#jES|q$ z4cD-iJ6X^DY+xIk`HgRh=S>V8bRA>%`rc)PMpjP=dy{zuQncT{Gst2_WCIMg2lKxvHd#jnZI6r z7#(js+|BTRobOuwv)e@D;mn^J5AV4}zZ{uV$0O!(tA6?R9s1?WJN3)JFZ9a=Dg81w z%eX(VuD>)-uA8l27VlP9HqNnskJ>-?s2ls=t8U!G3^VuXkLh3QkFm6Ie&~LdF;0&8 zt^PV)Y@BR<$T&IRVfAh^UKY8I!H?We7-9FN;(0aeIG5SZ*O}vC7C7t?^=EU0{?anP9Iq;yH*}PGF8H7Py!tu4nka>cuFJ zFu|U`6VDoEIgUBbVu25{#Mc=8)VX4UtJaF+7G}AFIUZtxJ%2Bb0~!9G`meKI?DCxb z!1I~mAU1V=-6W22mN=E+Q}!pLJj?{Y`UiRWEoQlvIp$g5UY2-*;j+4~7tel7a0pWz z%`7J|$9fhRcwXFTKL5rV9@${LT>FCd+_cfY;zKXW!y9wnB;<&%eE{J@@^|c)0A(&IuoT z!*!M67X7o^TgLMlU%%t}#JWB1BkZ*rUMJL>M?aRI!N5o5CgxdS(`g@hf4lEj zepHUKw#!G}zi$34atVVzH@K1!HZ#UUOtRN!KJxx`pSNQp7cuB_gv*)YE@s)g>qq4h z`!VTrgkzcJ3KqGR37;pN`q_`l^}H%*oE*azPGcLFFx10%Sj{HJxr22qFvAmUV(-(% za|+uyo1wFelhxeGIHPCC%Ny9h>1<|(t;{hHst9aj6x?&iY|HnR7b>c|N! zGR5HM)RhsgWsKXIWGmA=%0`}Ko?Uy0XBC4zD+1Mw@H)mgjY-a8n)BJnXPM_)Eb^ZW zo^4;8C7ut4#B&Xke4S~2%tlW8oOmu^kw@9;^P5L|s^2+2A9=R4m1^c7Z^W@{0^X(JvsWQ&bt6N|Df)gXg$IHI{Q8~w% z1B{EMi$3!AH!1>)tBr?OU#wsDxYRmw)@9b8yT4=oeD1V$m~n7Qjdf$@a^vQT;pWFd zSEy5;iooV8od*t!nIAv>zH#!zwZ_TSqs@=?*Vzv~zq)CRd9mYq^JkB-`s4WwoL3RJ zoXvcId7ndlmrXuj+W!XgEbus~$Bz4rP`zmdVSxEOHlvU#|$9 z{h0alJB)EAlU%?w$1azb)sJg8pdyf1p-!Cqgx6VoQk}SUrG8nz%J{zFI=EVYovt+w zZhlUkI=^mGC-&MP|3LS(jq1dzE%I{QE5^(EX5(e#n?Hs+OKfe05c6@`4{5SLL^Nx1kH19q3D}TT^Z)P2rGRK$xYP|dtOZ+Fp zgDU*q$+%g?1V_9p567{QtC{B~Y-7K@@?7j(G12MYwCAY(^03E0>|Zvu8rNXw|2_MH z+lt1+5&yB?ogQ)SSofjx{4M*wUB5j1iF3-(f1NW<`_wsS?0@pJ`jm4$#Py+Uo;+C5 z?tS*oOPBU?6HlJe?)~-dN8Q`Y!Ebx6IMeG)^=L1*u-94b<*KOhF~%*S_Hv55nPsof zwU=|ex@UX2$V0u_y-!{p&uK5$u0$ZZy;q&6- zYTCf62V+<51MMYqAM!!t`R=?bl)i2v0wLU!jnDx2R{(ao~aL^O##WAbYi<4HH7kfRU zUflJpdR^t~wd%!5&#M=QZBQ?sVhb0)V7%P1(RfF=Prqcm9P~%y<VMi}o?61arB4QjggP6+eqz>SvTg6>z6H`S~q6?r(aGC9P|Ei_nFgc*%E2nt$hsV5cTs^KiRxWVo_2v~<--LPb z6l>XdlYZHEl6i5_&E~}wx0u(po>!9Q#rSRJ#dWuv7cw4GQ=hTb4|6pEhU2k4IkTWkfY%(uKUNx_=>h-$(?E5GAJI%|_ z?z`mYx;Ny%!Txwher|nNeqQ}I`8jx>{5c-a!++)H(z5)Fe5Rw^#QLrs-Y4#PrF%y?G)|sSN4bXU&gm%EG5Yxqe<#cNKCh$P z!l_jq<-m{q9B@HLxtd4%cX;2p{W_qdoMCl!N4c5J-|8s0ao3QJa@BZwFYEC4wAAUl z9p!pfTqS>}Bjo4!AIN{B`j3*I`>&Iqy|0&_iE;9C%8l|*us{TZ}``zAA4&UVGsF@w*7{}h#;eF<=<8wO7jclLWQ7&-peI4ast^4MJj&hWfAMEh= zx#V5kQO+Bn=YC~JIl=fd9pyAPJ=;;vapbxV?>o0o*2_Q9 zeftIZ8GT89E_+#i?tDdl?s-lApZfVbFFzwYLdBt|G4~YEy+JweNW2I^G?ant`*12Sx&D! z?)~P@d)MRT5{Gp=UXI*iUC%gPPO!Ph@p78edmb<6xc2PhHSxnh9)Y`sW+=BwqOqTUzF z&m}|TXYWhoXUnDXbLcSnZ?*qxY0 zlb@;UJP`olchj zHs|>k`5E|`{0vPw?)~fb&#l`3(tc*!uhog6wCn5Cd- zoOZwQa}P_Lx={Qg*9%5D^#SoLGR4V@#IwL02R$gB3t8exh97iY&WPt6Cb*X=p7&ev z+_m_4xtXIMI$mz&DF!m`drQoZlUc(QYuUJyBao=Oc%@NCun+b*&+n0=T`wDq^@(Fcj*9PO{@|DKglxsDs3vz}~jGA?%fL7sL=fA2SCb!DVQLo9H zbwAmrJ$t@x{n*Av?%S?@-2Ny1KkELRx6aJ|+5FjShdM3u{I*+txaV!-X4M|~IODJK zaa%z?_S$QFkIDBp{c!j`^W&7iTQ9EIFCX*&(C>0}Y}KB_{%PKf9xy&`V3yVIsRP%t zz{o-C`ncPT{S(?fzca`0ePaGE*$<3vGEXL7cHL#T&ULW!`#j79 zC!Ev|?_!qom}7s{ww}==aW&^GQp)xaTBxbV2%Sn70>Z3aVf*oJD+#Ov&a9$ zb1_pq$Sf;PiRUFOa6C)Ai{U$*7e={;37%w%-zbacWz2B`3tY$&_b@!eb%#+-3Y;h> zIFl)+ndLI(7&`4lxxfW1aT~*TIu8{m%2DoQg8P}`)JpM8F~?mj@Gwh^brC<)x-iN~ zOz>6Ka~B&p;xi}8&0ND)eyi&VpLel;8R2Ti+2ynHawZ$Ng3bI&P#gy_kn+69DlTLV zH?x*ISkFUj;1^C8&kNbg8V2q%Z&tB|HSE?+JfC7cx3ht7vzZNNoG2H$i@{m0vy8Bv zF^0OIC?~m@Y3^Vn+n8scGsQE@;4kH8gzb#6OAqlJ#57kh&&@1yKZCPfmll*w zntghn@c9?#oGqNdHlBC3^|`wua1Emz&jc4U#rj_6$%*I4$AP`Yv5uiRuHUR?j&Yu3 z9fy7XL^;DbY~pgZu$gV#%g{ZpS7GrS!8oU|j*l?IXW7I*vW0K5jqfv5?>XmO@r*If zS*+s|%&v`wZ9m^%)(#d$uP#Ryk0#y%6|<%LXhH5<8+d5*i) zI(lw9#5$ffRbBYxZTj*2*3KCJd%J$vXS#m)9TxaLYdpuDd58M&i>&7WmKbB$^W9Hb z$M4>0z1TKW-FWve)Qvx!W&8`x|8Dshn4>+v_iOFBlsRr)ATK|6zy3M(0r?g?cWmYk zW|p{rvx(tF=KHYwGut?sp{3fhn$I)E&ps#*2Qd0*Mc@iH@Mmo1GPZIxOUtb%!;gC| z$Y{U9^_U4RV2aC`<=EdEH>b0;^ZN`uq5iC58*A8ovHEcW>p7DR%spgZ^5hb64bI=g z;`j~La2jhlhxKe;YTi7|77oaYd(t>q#q6Wjn|qgO&%Tez!)a`0hOKO3V5R#xtJrn9 zd>qYMPG>zcY~Ttuv-NRxX5S~oJ!L+uVMBxUMYF{`rc)?TqqWCip&6yymas`66@tQb9bw!4e;4c!TF5MtR1& z;&}&Cyq8)2n>k*)S3F;0iGO1Fg^IvMe-qC~nBdb)vBy5~9K;-d$^xgc#61je^!&^y zul~DuZeWUAndOE1#dAChoW>HDF#MwWGs@DSpT- z!~fErm$SerEb$?R|LA#%3Jh!vR zBMde>Cm-sUvp;g(W&d{hxs)XiIOaO|s`JvJ9hWl60@FOjJQp8#Ki=x+(i7&%!6p51 z^-0$e?quz2_TMRS99lLm&Sst~S!5>gaXGZj&x@yhTuz(sQZ}-Md7fgC{VF~#2hDp3 zBaAV|aZGXw)11wO`DPh0pB%H?#vD(w(fF$?KQ6cNYBn41e715g1IE?0%f~*4;r_uI z_GQ#KM=-&kFvZ)L<=xD2+-HoJ-MW5U4!`dH!YD6ef(fR$?6bzf-!acUEV9VpcH;{g zKW8(>9Fr_C&BJWufNmfA+=cZ%L)@S2FGlznV?4n+R(JonoZ&<^aVc9^ai%)3FGG3z zh}E3e)B`#w4FYfoO;Stud_c_MR@oZqMw>on+i(JXzPW53m z&-?tx-DyC$0&CUl9zwJSR7Yh;`Mi|_fX^F5GFXDDNbaDCz<0jm+JRj<6>y9zx#ig zdGE6>%yDt2|8O5+t9cw|!1()o$NV{xHLPVV7qgig88MI3hB-&Po>@*}$UN#<%}tE6 z$9L78gP1mtQEX(IdG2GY@eZz$e~<68iW^zO-AuCk<>L8gHnQt*@tnpYGYtOKeSi^m zxx)B3iAnBcn)}(vQ_S=HE5-9_1`E#3RqD?jOz;rv86IKXS;uD1Wh<93pw1^)#c0gD z*}ytZ_`Y@FMmDkcNbAm_thO#Q8RufAxQ$t!_XF$0IV^BLOB{B!eegHy!zkx5!F^2e zvLA})1m>7!fq_xt*_UDKKb}!;W`aAI;-G7^=NOi_h~dAx&N0d_$F=8=nBqca`3iF^ zvcRfq#q&Cb_q*;g%8g9$O{RG6Xz?7(9Is)4kFdm#8MaR=t`pCROmG@g+{!GAtSPF` z80*CuY~cE_*7e`+J3mryM#hQfh#zamN#pGY&b`sP@DxidO|YJa#n;+L?D-S>h}lWj zlf}u#%h)Z(%Tp|IUsBwE+%JFT+;Hp^d3f?x>(7>{+A}gudoE@8i2cJT*WPAcjMSMI zciwKFa_)5V_`r3XX-=N0KXyymhiqoxsOPG?QV8mV=E6baKQMNiRS{=u-jwexsdhjv0OX{v6*Ap%2^D& z*ZF$`@f`EGcy?PMp3SW10XFcmC&Y6OTe*eaBo;WxDxP8uuWk^}9P7EC4J@&lBc2q` zsSNzfd|Ab}S;M|7#WTiwPGkcYvzeRO%BrWtA96im6^pFl_*LS$iS<0d2JU!TJZG#H z&jtqGS6^1K#2OBNMm*=Sp1aw=o{i!=UuP?)GvK_gWEKC%T8@6!{^wj4xra5*O*<3L zMUOSU&#y7!99+d1A7!%hTy%bIpZ|@)k6br@rya*K#+O;gJTts#t#i#aEU@o7aqXT< zpL0HWfC&z4vfmkJmUYZ=4huZ-2XXfMwCBa~&<5k-gpJyB9&_COqIMmAK4XNZ7-Kl6 zJ^M4w6dSpmd9Guz^Yu-xAI{TAMmd`)u4a}SnBy)MxQ`_c{G+%N>dPo6F~NPC@tndaFMCxyYnkG7W|?J9!V}wT;;~9Su&vTjPy=>${=DCtZ?q~3S zuG2fkb1-B4E|VO|G;7(&#msXJi|qG*;!kl=wJhvzGHqYu*e>J)F)IK zsAiFub$Glym4T+NrE;1T!BRQLLo9Ot=_P+h-|OA9W1sG&a+3KoOXVgOdX&lq&ONK-@8(wq z_Jp+K(w-%MFTXOd>Fkofm#=Q;czr-+pzZUea-1{6rE-d0&MlQ2SjASR`jpC{Z&U_y zU(^qGoG%|&_tg(4e#Q7Wzn}JuTu}1<_)71`E0t?6t_+-H8+-TH&)~|yAXf8cmcCaR zc!r5sWnd#yJkAAW_Q zS*EMo&VFmjLA*~%jf)K>1EcHOW4MB4BcPp=WOHP=I@vn_ppwEVdljiY~nz+@cV4z3k)wbe?~d` zyVjpendT}say|3h$s*ese87IIF&~~{^`gqak1m&=A2GvY!_ALZUtvB=Dg%>Q%NcBa z*nAmSs$Q((+bk|O-YfP0xP8nB7c$LdjIXE+{N*b1;|(L^;j?VwmhYJ#hsVs1w=w#J zb!LJOec!p_N@ls4Ifh3X53gdNp)xRrRcv4l*Rqy5)^q6(i?qa46}TXIsT6Yh9{Um zldQ^B1_s|G4~w%WZ$1Drn&*;mQf$M&1ow=MTzB5UEdH&7n%OR7^b4z95 zO2%I?e%5h0Gu*)@?qLhN++w~JmHwYPdRk1g!^Gx4lvsEhSvHIFdPzEi}rmKiQ(6L+$O-EI}n8iqb&U$B}*#@TWoT~`?8;2Gjs!xV?!DV{T#<9Zgjk0r)uia)(Fu#Hg; z{)KoZnBpona66k>ow7ez&tNyNGs5s))}5Cz$tI@RZMtVz8I`Fv3HOvEn!4c|Ow|%0`Z5p1}p;*^j|<>^r7E?>@#xCYk3v7MWu(Y`qv^ zD`WhWN%p&6JgeEr%a~_^MNVSyTyCrALoS;_J2S; z2QkTEOmiF?IhlD*XOW8-{DSKRBizmy4=~9ki^Q{ujoisRXFVvM)fsW;sSjgJGRb*N zb0Zts>$l>#g+&&Y*gs!%UYFWG%s(QIhnQvu8(EPR$E#W7a)!=#{dm-VXPR+tWgUAj zb56K{Op`8A!jC+&*IsIk*vz~R_#tgr` z#W~~%7Px>Vo?_LP)!|k3;5;U|n`zcm0-)M=|(S>&OWA zF~$;;tUBrSh;zdTZ(xjfFv(?1b0Zu1cV;g1{QF9u z&5?mm$_XxEJu6T9q};&iY~~!c@?Q*o(>NNuAlgS$JB?3!LFlBaXPbH z&1P<8EB7<-E#v*H@o*sH9LYM)W0nnU=4Q6?1cO7w1;ugJ>GCnh6n8Vrqs%eV?UQnW zvsvN^hQICiD`$M-|F3qxWP(>S#T2t#${b59uv>TW?8k7_K4O&XnPB8h@f^-9$1}${ zEN~4=%rkt6_C3V&5+)d9iYaEq6&j%J39Y~o3_a7>kPawbE=)ScBl!Z;`ObsjjUpExdL3pcZk zQ!WtqUHhcJadJOvSrw6wF*b3|*Nl^!8K`mYFO-MTNsYHe|<+BBg}Ffb4;_qRV=ZU;qTjzjI!4-{c|9*oWUIX zepei0EO8>kBdr^wT*(CUOz{Y_>{=t95f(UtCH|D*AK15yax-gr{^j-&uVe$Ku$lAN z%9Zpcs=yb9+lTxbYgloG{lGe=`34)=$~^mCXFn3rBv>e&IBR;?4`JS&FF# zFZ{lGa1c?vCVVuWU$LoHmo}9)UXR*NftQq56vX(1Y&)_KQ#vzPf z?>fRdj$(#6=6Hw&wzI@j43AZxYxK*dtmS&va~B&pIIeyi!B$RW;0ASL6%Vq8Cs@mi zuCmoW5W^&e;bxR!DD z`mwt6DrOjG6YpgU7qX2V42?Ig@#49TaSpywJe!%}ZZ`2CTR3robz_R*8^trq6HG9E zlk>(I%yKDn+{6O&wc^?3C*mi#-!jSznP8kL&SaLUiQ+k*1-7xoRX-JflXJ-^gOkMb zLZ�S#D#Fhge|M&Ei?laIK#g8Rc#!*nP5i{*+nfm}5uMzGL`j_SsKduUO06t=5;L zr&?c5XOSfaCpterx4x`rjEmXGb;HTN*iPg%#lcUVvMn_)dUlr3DuHg06-X4gAbvz>7cxKlhAGQ&kP#dG*C z#52t{Ze?h)`liHlB;%aH7Or3$3k==j=Zd?u<5wByw^+yZ%@v%`u_wbx_d_N) zl__pumY;UM{xi=zzqFnl%LG?2#U^H1VvaSl^~;qk@%Ic*sSLcrD0ef#?stplG-i1h zbG)Agu3(7;hHo{mIpR5l3C5Y?6lOV(IWA^_dsyP+dht{3cSgCG34V01b!Wf1)}1#n z&-E;_nZci{)359sE}3WFa5a-`W}0pHSvQ_L-+J(6miQNjr`gZHwy*gVYq_5F%%tVz z8s_FnpVHw!nC~j0x^!isAdsm&2Lk3>Nq_OWeqCo&Clr_cOupLh&5NET=Qa zIV^A)OWe-z?UjLlGRhB`;QyFn_Xost&LZRHe;+h%o}RJ)rkfX|T)_m-TC7f-!bUbQ z&)qEY{D;)}4$n7?Z~|k@Fv-`L<_R|PYfHrQ+bnVmLo>{m)!ffGPqB{UAGR)>!!|Bw z=uX!OR%?mIdBp2n&N_C<`hLpwm9e`j16MG~(M+@YQTu@-*}^8q zXBi*sIB=Qs&Lo?-nJparnDKE0L%(z#Vl{U#&V#IDpXK6tHJg}a3pcQhtqje!F05v^ z$HjB@3j2;HpHN4J8`P15SmYH9-mM)YY+{T%nPiD+_Igr0=dZMH*kzUHg*n!dRlJfl ztYt0tv6&T5yUw#01NV5YWQwofrw>^KR&TJr?Dv8=4r3i>F~h4jisNLqFvB*kVCdJ*8>{&) zzCx^Q5G27WSw{=!@n`_Kf124 znh6eLiu0M}E|z$N^$XOK@dxDHY<^5K!}r+4s+Y}=Q`p9%3@x%hw`kA4Y~^JPJZRss zij!EwnXKh{)^pw~o~OBj&CIivdl<;LezA%@o5i!5wOr0Lcd(HYUp0TuW{C?J{;hM) zDAzN=0#iJ~Z0FZo<>e{1^4!CAB<3tZ0ItGbHpm1Vh#KKSv*Ixo)g%>schzAwz8Rl ztlxXEibq((t~|g`Kt@1I# zR$k3Oqw656xR^Cu!CLNMJ!k&YI&ul~+{_~L3_h!WM)<@5^W>YXW9&V3;@1wkPVgPJ z^1lqMsSKR+FL^nQF)m?}hnQyIki6`}JeRSJ>lpf-{q?^3GR`=kW*tk+uxHWwZ~$Al zmWj2lPfYP`=6HYw2LA2(#fw@0d+%Rj1Mgrn|H9yNo`)IXHHVFpce0TWGSBx}-Q;}y z$GA9#b)3cwk21%KBl0rD5+^hK2iHwTxt$4~_kr>97G^n@ zEDQbtAGRY-Lz+akh;Z4oiMXbbOsEbG!EnP~sh-ebhUY)jxY$4e)q-Bei z5iKHGMz(CxGPGr6%gA@qqJc!q$QDfYyY8L2o$a^h^!E9@?*;qb|DOB4pFij99Q1na zu=*@u89%~mp3~=e*vK~ihTZID?0c@y%x1;s<0a^|y!*RYXQY~xyXb2nq#-KU;2 zFWklw?q(&Y{?j}$m(9F@9V})quVcpd-ACENMs{*H``F9O9nOn?X^%zh=d;ZEf!F&i z;LDzOyewu_tK(xm|CcTN4?8*g-`ZsUm=Chimyo*)bz-huO!Be)S)6 zonbyt`;Y!v&T7s%YQ8v+ZCuN4HZb-h&tuGHAB%X=F~`RRtYZV4xtAS0dqBUz7aaFa z&#x?C8_W1K`acEa7@qax?3=o6X$M4#r|feb3qThq=6$ zeQaT7o9991b2m%b%_?r0bkz5L?Mt?DfL%Nz?WpfLyI(Wwr{;qN+|4pR$7;?^SD%a7 z%8l&eBkX59uKpv|kp6e&~cJ(9QFNR{mnW$SkF4PaL(!aV<%(3u&&uh z{rA|sPtGD1yyoa&C4a$se&7t_ii_TG>4ea8nbCh@dH!#=n z-Ogs?d5RsJbguc~Ma=kRdh83#Wl^5}!G)}14eQy<7N))asP84a&asboG4oN^0p|1M zeD#^bD&Ea{?qCZ$*~#4V)aQI={>nNtpWk39cd&{lp07S%&K9<^lkqpG&uPpwzi(z4 z_pycpY~<9rM+e)ulHHu~M(g~Td0{rc!y^8YV`%UJH_cP=1^wr#8UD`9-}?L2>hUnknQ@K&Sj0v?$2JyTYdzS;*q-#* zZDo#+2Ux;+?>3*@#5$%eHlN|=?BD|S@;YYx&UJ;k>|+T}evkURopt;rn>lNV`dq{6 z-#bn=@F})3_r2zkx3HfFnbqaF>pI89UCjK0^!lSh z`+J?YH`%w$zgfGyhFO1dTpv=8(>|;`OW4bK%k}fLzkgJ}e1v5@V})_Ejg36{W9F07 zSL)|~?GqOKO~34QoX45*r02ajqKuK_Vbk0=EJ;Q$2zWNGaqCJcd?iI zm|%hT@E&ok~j z%;hyKVI?cMignz?W|-G_|Kk3! z*1WNZ<-CSi|@_^_k5!7P6Zw8T+fhe^z~7 z!6JT~<-C(MyoZhaD%;p{w{i1V%_p_P(>|pu^>%}9?de;1X zK|MbBMaRp9_o>HaZ05|3`r~}|vx!-UjDrR2Vi{-O?|f$k8~7u(@|W!5e)coANqyI; zvslJ!SQRehGTpKF-)ch@@> za0|=W!DALVO^?5N%cps~{Zj0mQif`MO;pgmQGc%8P-MiJk; zyhZ(gIiH!&2U*GszN}1LJ ztT$IO>))OaSilEa##UDII2*WpyY=St-#1^Jy~BLs!bU#IHukfduX)HmJL*2oY)<`=ewoWkev|clk}d3G zC+FQHt;F7 zvX@;W!4MMBNp-2M~s_4XC0qoGjo1szF5UxZeqr9*Ozwl&2=nc=FipV1+3$D z+04W2V8Jf+xsw@#_R}xa=SG%rKP!1thx)8%GdHn=t?cEa%!tKfXZ_M~a}i6qidD>g z)Nyk@Te*x~A!k4DW7ed2?E5U>VU}^`ugn`SU;~%1l}FgijNST8^LOU+rH|>CvsuMU zS4&7ud)awy~4l?4y4?EcSul+ULyNW4$<^ zmE6EO?qW0du!A+fGj4v3nJ30$+nCSYEag+IVlV5N_N3!xE<0JsKGrcaBOcqzeEyrI zJmL51^DZ`U3tRa-yEwheakHD*Cz($cG2;*Jo1DiQE@mTFv5oh#n;q6t+`%%=FFH0@&BximMHeg2r`W}1^OZZ@_=}JE@7Kj+o7l+w zOO6e;@d@_wx=Xd69gp=ems_tm=6f5C|61*H-TRIWwy^jH?Q++$V}r5R*moZ}Hki*P zAJq@{vO2i>nD1%CV>A_Z z!?zn3ci!Q6IlxvvT5DW<&z;BockSY_L(IxC&by8c7P0YD`r)d&V}tcv^l9~&xAxdz zH#0t?pEKjJ{mf_kI>*CJpEYl+zT3FC@N>roJ2|IbKb-t|>w1>`$Pzxh{@7p@H{N4> zT(iMEv-}H=pT+kc8_ay2^Wlruk&m*RH4ToRrC&17%(>6;aO#)!!?cZ#BiB6K?>IPR zlXC25H@AJo_|LX(jpm8Bf7Lv3@dNs2+1K>XYnt>w+jzdNf3Dc9f7X6O|D4&ZU2bO= z4}Q}+pA(Or|1Iru?iTH``rFo-Sz8?^=X}R}auK`O*rMJXt=w&2@bt&*KmMLA{P5$Bo3H$}TlHN&)C9G zJfR%V{H=0ta~?3CEA}YIS-;Z{zt4Jp=t=c>+VAzlE$ri6UFsFvH-B*4C&y#yPgy6v zltrA$a?WQBm$Q)%u#Jb=%^Uvc_+Ju_eS^9D8%sEMuX*6@tYbZ!d6=CXU>{HZljE3T zA2FYwWhwu_Djs1ybDnk_T*pp6%sw7q<|)nt=5yZvs?V!g#k*P07Pjz7cCwFsJh@x_ zsoG~gFJdXTv5M`i=ksjg70;;8o7l&CX1>%qFrSaJl-;c2f_>_9JzMxBJNX>@c*dXA z&$J%Q=SG(D5ms?lkNV7K3zxH#x3iDCn0cz}!e7*91xvY}ReXT;e1WU>|Fl zIZZ!*Ri78JlwGW1KkK=t*LlX+0p|t(J7EZ_!~@ljT@hYdW=R!%>tK4-I^ zi$FE(AIrUk>YSyuVzhEn$WR~ZN z=R?ktf693c`#mpIGRyP8Di-j^%snF>`xSfn2Ufqe_6l=Hn8;d z&NEgq?O)1qE?Zd2PA+3VH!~~W^BfB}_j$*`TUgC4Y~W$GGUwmsf!DF04a_>v^9&1^ z(XT!WSA0K7r1+HJQfx&#{ zu#`8jiZ!g~Lu}yyJ9*lqfx$jr!^}5nm-$@FQns^-lhf2^30qjtPCm&#&P-RozzIaI@Yq8yV=3%Qw9cmxr7;S_WF&vJj4>tJ!N39lB-$Ab~bay zRO9Ay_H#G03$6c4)#D0QaW@-yR;KZ?n!S9SnQw7Eo;omCz*?4bV48Vl^~(nQcUG-8 zyLg!W+%(Rtk>FC>|it3=cvc*Gu7kc%zC?dILm(Grq|gIoSSPuu$s;6Vh2w;+xqgg%qVgH zV=k{`32$a4Z(|+rVKX0O2Y0fUPcY*$*Kg+X-z?$O+3GWwb)3g$ma>C4vX{3qo74WB+0S-!fNymav*z*uXV!bR4CwCl^?E zu6vXE%)HS4yV7&TJjcuOH`^ba{8shY#8&prx6fHnY@QaXcZq$$!z|oWCuJ~Q5BzcQCkvxKqB)#oFu3x9uy`kcWI z7P6PuFvIaxF_-_#5?-;u@vxFztY?k!Z($?%vyB(M)A90h#;$U`VK(=&h=*CusaL4a zY&LQU+xRfMnfWgD7r8Gpn~$=HlS|cS1#9>S8yR2deBxQ`V>vUgwm+E9Ct1pjtE>~x zV?9q^>}31Z`n|?^!EDaEM!&p)<=n?^7GJB}weB0t=7KWw#AWQ@)^{5RYZn`* z@=vpoli%YwIg6F@`K;p-Hggpl-y8RPYUTL)>#Pe8mOGy7ybrk4@vxkwT*WGGU_H08 zg&pkVKK5~dnb*7TzF&Rjvy_*!iWRKqI=1jZcJc-G@#YHk%FW*goFClGHlBHdd3c}K zUCid}8_gG2v7Gx^!@5ex7xE8kkK38G)PA{1IX=P~UV5{3xtrZwxJ>)+cb#B1ultbp z*~4<4dW(8oz(!v7VfFb{c5~Kp`?(?>Yi2HEA9K8{V+&7Rsr&~#_pqC<{kZ;ah{wLg zY`(EtfBZ4aS#+!Z_;WV$ZL8GhBkT_OC)B^ub3L=l>?0QN5X(5gYM!>*b%MEU<$QK= zA^W+ES?~5dzyjXOGHzuxJJ`T(w(=;uIOR6=c^0!4yY8@n3t7gctmbMqa2;E@nO)q$ zes(hJJ=$jhkFty>uTh^lY~WnB@(OlwDf_vaSxdCf0&Zp*A7VB4uz@{n<#Bd#>L=A_ zF0<_W3s}JGSjJjb^Nbq%+5RhF8Lwa?E7;9d?6lA7S!5q=4mo$S)Ve>xdiJuD<+ocm z>)&;Uea^@4wBB6vDdqTlo&8{4Gd`_7E@3%uVGSQ)Blob4xoeGs^BAl2+`()%vWQ1m z&dHxqpNrYZWo%;`yZHoTAGDt9)Mo*U_!*Y-ORV9f&#KSaY~z}G=NV7?ym`FI>jM_? zAZs|~9_J(THfV>NnDrs&JF9u*3)*Amz1rhqX5SL`JtfyG&fDbt;iZkn$x8Z-s(zWzMwYRSpJX@dzTx^=<@x2Cu8VA89ru1)IX<%0b&wBz$GU&S@qO36 z;6p6uwr$FD)Ay|3a{G9P{`hdKJ)|FYvyR0-ay-0=o!riT9%uFn z*Z-Zy$9q`zG2{HP_W3n7@+do)@vw0+hZ!ri%UphoCA|Ho##e2gSju)*@i6N-z!v5| zVjNt|qEEPvvz#~mOuu}Nja=1kewg-i^T@S~t@iq6mvQqxcKna|V=td)r}dus3;Tl? zGxO%S?{OFxdsxQjS?+{0EbepG$- zvY(TGrJns&$TF6*n^lb2R}Zp;yI9EqX4nU(?KZD`3tO!F0(SB)_VFoZTK6fBnK#a7 zCkNQarH^aRdfv-A&iJ)D0e{hCv@&)LUW0m_3b2;lz=8^MQ$rY?)2b;O@8SBEQ+0R4FvY%T1Z2#FukFcCC@3H^5kd3^B z9qeK+_cP-*^Tu4J{YAgLdcX1V!>s3j4j3=reAsdFGG?xEeeSa#xR+%-$ZD4SLw{Vw zHg07%PkYWfebR9=o4;l$r~FfY%w+=?vz6P}#i}EYleaUg#`(npzU^Q7<&~`FFWA7} zv6a95w|-gvAIIr@TF+eWU^#Vbxx?^EXWr7!sJd1{xH+{QX~v6)BN!MT|)_`ag&US`zU|EKDY zH?WkAtYU1M{+RJH$HyXe^VQSU`?UT0@)vwhQF)f}x2)!OU!gxfm}PuyWj`-`rTJK^ z9~N;F%lRAD@TM8+@d0-5ckJckuX@3MAJp#&Sity9{qb?uFm2Wg{(WE1sZ82mh)NGaB{Zw;}vY_#xt!S zi&8df%szH-(Yfkz z6*KA`Kl2&OvtGQCnV(m$!0~e5h5F~NdHUzdHybw>6j~R~eT#P1d%kBb`&h|qE>b@H zoGpBunfEwPij0%%E;ddso^PD&ew%%x{~5*VaRFO+7d!bF`*_AB_NVqPVkfU-U+9M| z+G!6z=e|qr7ryoF)_sHXkOjQDM8Dzhtl@>1SwA+ijcx4aLB_sdpImPJIgLep8_T(n zHN1Evz~jeP>-A6WnH+P8DF#?O4Z|jR`Z4{ ztvf3hns?sEeqL~u@imxV7V#jOJOJJ4LKiZXxS<3p12&Sz?^r&n`}RuYNh7Szk7O7Vtrq zv6I!DcAfTFz*gp7Zynf0Usj22DYw74?tSKsTbC-w*!%Uvv)Ipl%)a02kQ?k1K6Rt= zoby5Dc{#h7d6RZGnLlQ;mnEEev*Y3wA5xEvY~en3GUFEO%UR6)iv7+4?)$KL=YlHx zf_Jl#+u6omcC%@@d1_Sdqt=(3Sju)*v3P}f;1eHHo;e>^{;RI<%;&6X<++~KY-Iyy z-l`vNT4j8k_6hU-fcazrYgx|ux0xqyW%k$HhwrfNO`hl3%k*0F^mX;w#Rm2>`%dj` zcAl~38=jBvGJnm^LuT_%7I6d1xtERK^t{J5&is`1wh!LVYW{!?+{IGsc7#=79qVX) zu40?xU&;pKUBgzkvWrtbtsmpRlr_ATjl7+0+`w*bXUuVRGMiJ@8YgpE$;GVWHa2tF zXUwv;UL=GA;;-tD;f7^`{m=Zu$Uv5jTyW(#BHZCbr?a0QEa z7t6VsjqG3>(>|{rm$Jru*0PZgvyHRX%UQ~p`MrbL+`%FqU^&mbM}4khH|rUDQ2h;# zk88i+__*VX#?QV6{jl;&`eE&t?F(ME(fWVOJhOo7SjHW!W*_UesCU14Uo3(eARyKJf%|ZXSyMs(r?K9XHQlhU3p?E-P5VRjgzKJ00(K_VF+? z9q;@D=9Aa4nXA~rd)dov%=nJ$K681HC7koD<7MoS@o*YjnZqtFW04#jQKq6KgPjoR@pRj}%v69uS=LWX2g9t5`ayKEKNrwy~3a>|^DmQQOS;g3o ztp~F?z#^V}f_i)dYdD{c+`%^Xv74`)tp3BU*UaWd7V$94IlvmuIZ=JiV;gT`H)|RD ziSwD++{Yrmz;aH>P@jct}Td9@z~j?sLukHav7_*p7q?q7Cz2S z?qwg>PF4SBem}r`KEhI7^3vnJ_ZnXB9rwLg*Auq#Np`W9{rpO%d24r^ryd_H;nHcx z2P=6O>-Z-&bM4EH4|cGHy?m4zKX=|Tmm8+5&+oF5|9rV|^Np|2FaN|Y?#QxUyNsXN ze4a(jdZqQ^1+3v`*%L zScl`Ar9K;3#3QF0Hz#L1Zl1+v&SxjDV;>us^-J@~0`6fMW3Msad^H<*4qG{oUA&9^ zjGv+Yqs}K5u!v<`#%iu*1Dn{&g|AhgUuHi`a@7Boep$f7EaQwb)n@@4cspD9D|WH^ zEcLmbS-b5g7VvSF@hGeLir1;nud$V{&sCp0*w5J6>bozV!2&K}8F#XpQ)esBkJ6XV zW6RF5FImS@HnEB)&#^x^lPxS@Cl|4g4>9xCeow`G_Og`mbJgcftmkUBurN=3E@U5X zVP>cGWj_DNQeOFb^;yn(Ze|Nx^3`Y7dFt~lX8y+bna`EytIwxc#rPZ4X9-)lnO%H@ z{XE93Cp;g{wZFK6<=n~|&U~Z&$+c|bBkbl=jQ!UBxWNA892Rjo%eneZ>T?4d*~K>Y zvzu!Q)Zb%%FI1nGvWRUg=LPfZZ!Tmr*Rg|-vX|Y=_?`2bxy*gD^O_H^l68fSn|s*8 zjJKFKp2a?1&deuW$C=OUx9XP#tl?TVvZ_eG+{s>^a$u=u>hoH5@Pq8-YG(Y&_?gQCEMY$@Sy-w* zcVDSKpJqqM*~{Fktn<_6h50OHDL1f+IagaZUci=+vy(N~I6rtFv;Nolb*+B6o|Sx> zb<8N!FBh_OgT}*Bdt~B_BxgMJmY=F z%?DY{oowK;rN$lp&MrR5e)ck}$2`2>xY^4xo>HMcH?xs#Y~%eOFkigl2L1lU^^W<> zyivbApH;k__1wr7=2YsJcd?(JXV!lA0~T-x%lLOz^Eewg|AWTOo}0`UpJ(i^`n%b6 zh(*iH7Z51vkv;)6${wGG9Fd7H~hyIOSvN^DH*7fUUfgT`Xrmmow{c z_A3i`oMr4->H5p}ecXI=H9L4Wd%2MrhrLc_E|0Q=^Qz4^tJuKX*~%x_#aXxNmqpC_ zyU($(fDf^Ze`7TluTr0tY-I<#xQG4R$E-f<^a=HO0n0d_)huNLSF)8&>|zW1`7pEo zVgIp!(^jj`b6L$2Hn5(pe2`syj{PjSP5tNW3l^|}W$b1(2iU-wYt-i|cJT-7=W%BJ zQ~pWyIge#5V>K(-z~yXZJ-fJr{p?}Z5$&*mnKkNjHmkXu4ZNML+{`ZSU_YN?*1xP9 z3pnF{)aOO4<_&D%a<+04yLkES&X?!?oY`E%B0k7+UUP@@H2j>+T+0sbU@zZS>-zF< zzqe;TzsgcBxKqEpfeox-EAL|$x3iz^%<6YNV*xYoGH%XfHA~pQf3l6Q{*>zruVL&z z+GRF>$Rhrk<(ye(zjHntxsGkTkKJr$?5N{lHrrXm!z^d+r`2aQ8~G?Zn6=jRobPAm zG4sZJ?qDh7pD}KhvVmLK#sT)SWS#SDzEzw;x%+4%RUIZ~D;xkHsdfS{R#DojK`MQ%=mN zpLAko`1wr#S9O2y;OyZtfr-nOFo`a6MO57H_v`U z&KZ6>RHm5UTy}79TKK`mQ#0>Md)q0K->Ku_ynnEmf z==`XVze2t!IZu1n$oOmJ3*`C9`OTyKH_4aCqxM(3d~u4rM_wj>ZF2h;-;w@aU4;3K z#}n;OG`_H>a^&^uU!Gjw`lJ;l#u$Da+F797HsvPTr=gu?@<-$?p~8#TiMOvyzayU3 z^kPe)+y>5tA4Siq2oUx z7MuLxgM-_W%cXsLs7T0jr=73Rz7C`CS5-&j9-Bflv{{m|{CRiz7t?l>o=cg`$|r6=w?iTg-c zi*ogMFg|zvdq&nitm&4-N`!e{r=P>hy~m$N%A_SOG@*?x^0Pm3aBy{U9@<#`;%X-L z#UAC>C>M3U9+9t-N3GZN6YY0-)OydAeJ)sQX%>{Jrw1`|1+;JLEHxk3Z?TVYU1cdDL^!M)}+n`A+$3Q?$QV z{%U#D_y*)t4s4`P}68 zKRmk6mc-pp7$DQcUrO0#S znJc2(FP7(}$SdRvQslMrn^NRW^12jxyL@wsyhq-iB9A-4_NB;k!U_1X6vr>0l_IZ@ z7pBN-<%?6~P4em#dAt1H6nT$)dx|`MO3Y_?qK_{}-j^aTmQP(7UB5y;Cq-T>zg%va zM(=ycuYcqh$j3atB|TrZ%jc!Yd*m0%Z%S@I?E@p{PuvBfE=B)2@)arCFP2x!SBz;t zaUzHFuR^{%MP4h<{`kSc*Cf|pGJ5_t$~F91XP?ef*~sQK%W-|+Yk|Hmb=cdRjsKtVmFFg(pYI<% ze=Fqc9{J)FdHm(E*mWuL9QjiD(lO%;@17)H z=M>AEQsfo#{VDQVdG05p+i#NJlp=4JZ%L8&$PcH;(1^Jn@#%(EVSYdwX>K9(j#Cs($xmOqf9{R;W>DcY}#H4jr}c)cy3 zXr9A34jIRT@(=iPd`Z$c!h1jO8J*8X+UZTv&Ro~y?ibssjBaP6c4mEQ;`1(yXSH_9 z<@bg0tQgl${pfglwDW{=E(4?Ua^+|qx9}bE%aZf7;*s^skv}K*7&Tfy>GvDO@}3lV zh5SkRdy?x9zppv;{3D-M7ybTzlRQ&?`!QbBE1xP4 z=k&<+J?ZzCP4a2-iLOgw{o3Ux%U_>dKk4_QJ@OfHr@?6ZNx#30yK%f+?$-jN`NgCA zCr5tF@kQmu@@G=y74l!mUzgne($V&7<&Vpw_IH!KEk)ig-zJZ`zV*nP9e;9kp0;Rb^KHG6 zuM>C6zaf98_lrmNQF_VH8^vLt9Fp%@(>v%t{g9ORq=z2n_|b0Txc~Ov!MOVIjY;FU z?6c|X;&+^o_IzS2iVn?Np%<*XB91GxH`9b%c}MTy)RVRMouu{_B-%@V;iQoU!}!)| zZ@uv0L zv_IX0aHt=(pXbUeQ{;=}74oR_eZ_G5QS-k+UY25f+vUY6`rjijN>Trad`^mdy3LlA zqW!t@=_&F>^2`+Z3i*^2`38B0d|UGRCH+2ryZpWs_4ml{O_3jw&s*C&ccfHNl{*{xQ_diKG?@OGk-^|OrHZPV|JABH9{%W;1PkR$x ze?xl}+B@Sjy@TI4L3@85+g|!5>3R9-^Cso_m3z3*h4%JnFV*@Sk*8Xp>1QR@XQJ^8 zo&WNe8*kL>j79Re9HZB<_azQE9M9ZrulGLJJ9u)sa_8MM`gwpbKYQ}>Z+0-phpyW8 zsqz)d?^)kFSRKmWIIjHOy!;B~Z%!L+e}nQf@9iDjl&1Xlapj-L%m1+Q^~3Fl-pXg!Mc)w!QSfCK?Lmrns(Na9{7>v{3G(4Wq~98l9ezC>Q!$ zp}*`e_xf*T_}`14gGo!gAPxBj`Q(W4%nkMRldt}27m)a?lKL@!=~txZWu|@65uScR zVrJexG&5ly!~J8$=H9_)PEharS~Y@vKU$M`$N}Qt%x4sbM{)e_`yroH*Lw0_CQEXSm$C6PF9~vt573 zTY3lgCHI&1r=bo*zDM5n-QK~!kI4^?f)upTSNwR6&>yv#BeiudPb z2i}$7^La&A``c&oiqiKCEkIb;TJ6l(**mx`tkbW?wR6g(yzI1w#9}BL%7^>M#vk_% z-WbMza9sIYC*>8TJu^~197oP`+Hy)>rk|vJBCja0HnE!@ z&C3qOx>OE7{b^qPr1Zo7a+M$6GbyiSQmH>&F)6Pql=@CuUQ2pc%$uguj zr{z_ZtNBo(zqe1yt4T}$xgu$Q%*(t+f!CxNK`2?Cp4Spj|6!>8!}PrJQ0XUm<)PO` zJA8Hcv3`cz8v6S~Nq?`FH&04b+nK2Ly}Z)&^0=R$ed@^RF?2qK`^T);9T;30_Rk|< z9^F6Tes&t9(W7fx&aa{p^op%coCEb8b&bTwIk6*UzSNz0Y;dfx)l% z^T>V*d-DsU;|Tj^w{l&|MeVCY@~Ly8^C@|rE9KWG_mh_RU|DE?j=WZ0H6~BIj~|X} zitFkgd7D4Sr)(UZhcMO~okxj}yoTCC^H8XK#kmItTSNI-GHmA5ZLo(BC@!T_7LoZ_$76Z$NtwD<3ufz1mAV zZ@9f1{(E~1^8KDt`GVx}C4P-Fw2$Yw4nH72C7dVKW7|tlAAO$Kpq;w&CvGR~gYEK0 z`J0pbS(%uJWq!6nKRe|`?$h!5q<)gGU-1)%E6v(k5_B|OQMB_3{3zdU8^c~^X%xnFc(!rwnEGM*gQ+mP2}7|;4mqvu7q|2^R% zbG^<=ogc+~EHB@+Cy;g-cjc8jbz*71VYoKlIecXZ^RQFD+m{@e@Hr*qd*v3P|=*p%588eRbJO#Jj+d70sq`}Od)9=c9!@FJ)E;|B&GPCnkm=k~WHc1>dc?o{rm&kaQF zo4xYqQ{)5k8P(D2HuH_KSb=<^>simjc-y^iPf+=S~f-SbJc? z_x;0hZq)7_@>hiU`ti7SPabV2{w8Z-e5WRlFX{JtIr2RDwB$VL_fN(0Z22|Gd0OHZ zjA1=0Gwcepxt7qCBkm0vChO|Ij}FOY}b9 zuAMLsQTu$4{OJ_qJRo)v7y3kLK{EI32DVE>=f-x_eS<<^8Yq}h00x>qMar3BKdzi|7w*BpHGZBt|s}i z|3f>wmD`e{okQ{l`G1?A=|!F)Q?xTz-X{N;xg5Dqhj|`;?HGO>=6Oj`EOv^|Jw_eZ zYI(nQRw_HDo#A_S_;F~bsmSM3v=eoGYL{Onk2+s^bflIth+AD?f(%cJ_wk#9@UezE+a6zx~Yccy5+R$k`)`>5k3X&y6|q+vJh!KU_b&mKj<9#K+f%_HTu}CPn>P`7J5(Ci#*S zdAs~_`8$&PPfI*dg!89IzEZwsOrCgyBINO6=ezvMF?r$zP{?!SlYM@1@tAz{^Ml3m zB6-yMRLJMcPfxC&^nK;p;XLZOxk+BFe$@Ed+^Q`?iBs^ z$RCzpkX+yWD%@tmF|`-j|MElr96ylsx+C1v_KjX==e*th)8|Mh8fR!{%Eg}DY}89zORw(RzmCoOzjJNs$-I zGv!h5pD&ST%cIV#)$)b%sO#!Rd6>tj>%va?-SVjG!rtLL>bfu>Z&&}uG4qpnuoyc2 z%VV*Zr1+dqq5MDUSB|Nl_~KuvzeIj`^@3~u}(gJlJoJEN%Q#P=UUhJU2Ed)iJ|jy`U0Oby*v7S zoVoHX@~HD>k-S-c$C%?;GjcpDvd!}k6N$k z@AP{!^(R`durH6epKOxS$AB#%1(_R9CmqvmNq-Ya(*7`?uxjehTC<`q77|M}>3E|gD|N1b;|a+L z{U!3hq^Q4Ie(pWd^S4p{D*3uG>-VXV>&Q;|r&844D_^4Kl!7-my5gpHfkqa593Rd$|e1NCbYNAiE@u}Z_?h#b6;p{ zcA_mm9lCC8Q0{>Z(f5Px^0U4WJ#TyD)8$d~c0^v2qW<)SUXP}zKUe-#iu#M>9VzOs zkk7q0di)#YXUL<*zg>QJiu!xxt5eiJBJYi;AJ%F5RX$%QKY83brM)n;^};d@ty7_L ztzV2jjwSNV@`;Wk^s`z%ts!+kbCj!aoj#)6(Ea;{r2Q3f|K6kB$@fM79`A@eQyz6) zo$f*6_?M!u+jHgp@~HZY)h#@-gc-{DI|g-9I9~=gSkXOUS2R9g7XhC%P_#e6IZM8&e#={EhOc z`YYtOrKrC_ezW|RF~^tqMOx^8yZnbK>hF<%BSrs5Tj3dmZJV1`OWgs*U0`#`hEKm`Hd;s zpMI@#E=Buu~GXkk`mF$6e=M{4Aa#L!Z;^F`mk=3}1ihlEyQ^^(S1frn|nb zY8)=VF?IQH9JSs!KX7yO`v6VyE_u}Tq+Pz?tI^N7J@PB$QLhK$?@r{l#pr%X`us+Y z{6YOkJtr5-_sFAO4^_xJ2?#f~#8|HP3V8)0Q2W@Oe6nbBgO~m3-(qs3mFLlb(aZI96z9uKf`;jt%lN zBJ$AB3jJituL{p)+mrf9&-PLB(SH|suXf&S-J|*$ke?lqhko|z=N0l_g?=7O?#D;f zvq%4ZlH&Jx{r*67KNa%k6nU-u-iSPmqr&yNR{mHR$KR62@r99bg!68la%VRk99)pD z+$mohecvrSV?N+>t{V<-HPN;L_bJC3G z+;QXiR`_1Z=o_P<`~u|{+~jkP;W*zuwtU*(@``+fF)i`04kY&bPW}J8IePqi<$sCD zLw`H<_gi^sn6I11_Lp84=Icje=4;M-z3=+1=>8VSpOHu1_m|1f-ZF9hu+9ryk6$5w z+MnZ}Ng7YuAI6MhyLKK^ZlZodI~%mqW*&!Lw`@vkXWZ+S0qy)vJHJwAi0w8x-)BB`Lh!%8p<6~Zsv>U)p_H}4Zj}{=5x{e{Cg4Fo9Ot%_~yFq9*}?T zMEzYouAR!szQ2?{BY7V+X|JSh;`WBtUw(o7)!H7}CrQuSJ@Plmqh1fimwKQ5r_uFu z@Dm^xrQ3 z!_T7o?~y+#&l*$zWh3?D@AvO-v`5cxj(n$lqUZIY`4RQ+PCmY**9*1s zrRqn$-ffaElCK+6fAoE@c6nPw9`-?Nu2Zz2t5Z{or-@>(i_$}+OFLx`~rre}7 z`*L$qxp3d8@n|*fejV-~pYJ$0cv8CZKN(kk=>9o+e-HDttityme>L$uh5i?~E|ya zw-M9Y5?9txey{S`dxl@f%uXsl!RwxId<#Ahi=F?w=;NE?I-D(kSvc=6N@_36@4*v% z`_Z>5hcE1*y^Y$7?~VR<*>=iLlt*1>!u{i4e>^z&v$%GakL&OBcwSZ77hk-M3|+UU z+~9Kv-O=qG(%wq>fDYsLjBD?oQ^J=u2a?CXM0@l9K5=_tUlx}8eu4aeKga)>)LvT8 z$hg8fR4Dfk(o3nSK+u;yRJVj|8&?FN0Y`8_C@*7eRSlwLisJqzwTwv4qovx<s9epw~xdJsY`C2DDdKF}zQ{IZ3aee-@b}kR=-#)I~ zX5UR7w_b~s|Jv+l2Tu>>|1z%pC;tEP;r_8c@7clY(v?54dF*j*AN#s5?C-Q#J_wFicFOxQ0AZuZ}MD4KY@Azvn+C!grKH}n_oA8(TnhV$x` z-yFM+YySWH?`q{^=5grt^7&)SkAJ;9bo|QiyZG6`KZWDDW^DQN-Qj!Z@fRE@LYK1xOTo7UQZ=H z>#XR|>#1=6nEavPes3CAKI!~kt>3Q8o{ju>EjP;NT^>EIaR11aKN;rXv*Y?%8P1o{ zafRd9qWt6Ucy{nhq5S4?6E z@~|&*mU;h4zWXHWaa&S9FWyI=8hQqOCM-@kt_|9|zuxQu)xn%KY}|J{Y&Jrn}DfzS!SulgcHn zUudsTx#KH`$8~9RxeDc``=0pFI(=~Ba$(+f8~>9L;}7{Ed3!`2=5@Dzw#k2ff_3`T zxPIOl_wQt+-~8eU6xu6X;rHM-Ogvv9Un0Li?$;=z`)~Lkbs0K-*Y}&`mEk=7`MCbx zljtdot3tVjj(O6|O{$J{I#zX7#nsNOl?XP9pd0&ct*2&+MBHto^ONxBA z{G1f|A^9sK^10@1x8pcb{)_46?X5}2k^JwbOgq)Tf|A}i^pA6?6XrYazHsmVqwH+p zo2u^r-=-0tsxr)wVMV~Gh?Sv6Mb;r=RK)6#MMR7aG2+8IhAvaY>QJgftV}UFWF0Dt zh}ijMeagg$1BX=i@#@4dIlNxbLw{{FAm@4w3XbH3+$zUTSe zb8l|hnd_ALNh|3j-pgctP&l`db`iaSb>GkQ@s7cR8ZP-o$?pXCGO6D^CHYnJy#UX} z`T7-o9DVGzo#y%Vpr?!5gR$-}JQovv3jKL^?9Ba5*2yQ9=#Q8EbwMxX3Es$a*Tp-v z_bemu2<`VAwE1yZxo6n`UkX1|<<^>2?8o7E!FA(r3w%D@?zyc|e&&G%_-EW73Mu8$ zoMZXsvzER~Uq1o(0=Qj&5Pw7PMGons@ay5ntL2rKG5BvuAG6Z4{8HjoxL2Nlx03!F zDp%eINx@&z27Qy;_M!-z8}NU36{euID=>S4z8Hpy;Gs&oIX)(RmqH z2QS%ad~eYE>tbEs`y-;OMz@%HGRBE#igoI~BZO`p_M|;{Q;JU6$4H!#H}M?B(&gKg zrIGxau(KL|s@VBZu~RsfHRA1Ez&$o}W6+`2gu~XttEq1n1z6(`5 z%6IMR;8l#1!&Gi{RcWWS%oju9o&4?Hs^nun^SYX6`#b?Y-)JaC`LQ{Pq;y zUuc8h2OqC;<$DRe@Mf!A`Eo1$uIgr<+rvkw>6P~;Yv2<9!&R=l*A})okC_$!3f~2( zhi@hQ9YwtGUHK;XS$FR=zMqu$&+|c{{P2$);@t)x=n(HD^TC0A@$T+F-qrQ&pU~^- zw-)YQps(L*#&r+es9*0hg>hI@zfIU1PWkP|J!zLo_<`_0&_DC>k-pj7w@NX`lQg;o zEa?9^gsT%&%yQ_VPi?ah{*Q|;|Y zej#*0>^v{Ng%zEgEk9w7lcK9fH?!WdH&@Xqeu+-zkLz!-boc3Xt>~8AYUvVsT^8Lc zzC&ch<1cz$731&=3oYFj_B!eJL3I02USobb?Ab!Qu$iBvJTiX_y~kQN9h!s$3ag>fs;2b?veV{wD{Xgg*;!RP9^OF(m&s_+j_y?f1g>hwIW;Eo49M zkiG^!2X42%mwK&Yd|gNUH%h;W701)lGiI!MpGWFd=8wsXtn<6|ioRr?Ns#X(@_m*x z`M6s@BrWAm!BcR%`Am2g{s~-HFTUG&9~FK9+JgPU{pA3B;If_C_me{KDew_$dS%{- z!fWA&t6Z5kViwoU8wvRBq(4$kul(M33ceVw^FIs!l6uj#JKya*e}e1A!z}Yk7H;(a zq*71HxMQ?`>|B5!cI!B)@0xn{qP0V-RC2ZnfFaC{uP~ShQ7E#Y|JO3rWUh)LM=K47`tzZiTRT<2c`emz|0UkV-@`FT<4#U1=(8C z|5h!($9(Q6@d?1kJ+w17tB9K)oDd#@&xh}?a_jp}!lUpAe6Y%`EwbwPn^a1!qaNYP3f}g43(r*F_ zIlqGsqn&$ezus>u1{SyXIQB;VO26N0f%_bI8a@C%P%ZDdg?M`Dkh>kq>xYje{RB0= zHIzs^gYfg=x_C$6iyhK8z*jq@kHfb*q;G+L1^g(#PSu;kxp*z(0czRm*PNf59Pr z1fF$B-vA%pkz?tkvPV@zxKY4`+F*jF;v?g3Q%-UTuZ1 zaNrsEo$#a7^p~6SfcVkMJkbbW#^2sq%Dg1|?!|@qB5)7m5xR#|JDym+K0@$$kLcT5 z6kZ3vvM9Z|fS2|ZgFgqi>(An6l<_soR`9b8JF_3%nX4_z=j^* zkt)BmkiKdu_vqku?V_4Az4-A<_#W|Nq2fp1`q%u)6|ru#qdM&UVAamz@3s?LxiKd8 zY8j^&z~AF<@BKFRT1?;i>?N^R^&5SAXoK&g;S$Fr`DMxP8p&_9lAp(VNXoxUefWRD zb1du}$KUyNyY+ocu@i)!&-u_LDmUBj_xd~*J9X%8N2eQy8sWFXPgU($XSI^P8QzA! zL6s}#4XyAp{IuiZX9n(vQ|v-Hq-~p@=8%6i%ImwAK8en*-o=jqyb-Qje}~{p;kxl4 z3O^=pZ(sb3!N*sspSecwPc`H4WVqqayZ!sqguSDmwBLUk<%iFMZ@{;F zoUC`2gtx&5HtWmN3qQnxS1}L{({Q8zQ=TK?#yWnFQXZ?WO4spq*z^5%XKuLaukxL~ zMvEV>a^<;DGyEvhGfXSxy)9pVt?))T+Z%-!&eJpSF1W5;SKiNaJotDuy*bSr{h}H^ z=qYo4D8&1oeEzlY2KaC_y;8n9i|hPvgnv$Yo&U}7sZZOtFRAZV_%ygKeFnbXfmg;j zFMP&+9b=3i%ommLkIBnh`F!DgMaGc#&5=(02w`UGY9T{psegR2kwV2a^OMu9S%GK|G5Ki zfZwIz5|0Sub|ZYP#AAvQ4|N=Spb(D~_6Drex8p2)I9xXm`5t5*fa~^C0r+4C9)b^q z>)K%yegk}GQTy1IZyz!Eq~F`0uLMXV^T+M*8D8RXohBY{@T(TqH}xbNX$KkXu6j}5 zPAY%Ny2^o9!&f`-TKF0VUI$<6z#HMs8ZPCoW4wL}{-Mlg%QfY$mEZrf4vVaEr?Gqf zEBbPKmou)wuSQ=O*9y};6fnNt_xmd7ou8(duRc8G( zqI(CO-F$A8pYi)WxKaLB{vYMX?)87Nw=3Bg?@D=B zu%ChJ@=KFn8gAql=s&*@_C9;VK0k?9fbn?PW@|jVM6stC&*Ioy-fC}8>Zb+%XSmM) zIQhK{H^$G~`_Iq!E6#WStj{k1|1n&bpO5kNGPn`1CzSj&_0xd8%iq#R=9{PcOIVJ8j@F8&BxDkfWa^UswP28^@j;;K- zqpX*jEUsHGCE;VZSFM|8+Ti!Y$E)_0^;|FfDLBoikiYe#dR6>W)vq}h z*1(6t2dUgTcaw2146lUWs&aGOyIvjl8qm!~ca*BL&LzZ;IQ(k3uAD9Kx8Qc|QT&KA z{wLud^SAduO8u9t+bUNwPIABcBh?S(zDYH_n)}kTinv)};%6=V!}s;;>pJ*99C#yq zn*(o#@6vE-=Q4j};eV6o3J3nKFfOX?e1Y8mv?`G_;dnH^?tX(hibU^mBgY-TM`Ig!RHl`td3RpQhoGZ-5RLf*-jz@tC5?_rU?&voybnOcJA>nz4KOKkf51 z>L0s7__)2Wd!5Ga6JG9z7TfhcO1f?O^9(=yEcoH#NZ)yc^1ME1@#!kJ?z~DpM&R|N zw_Dc;Z-Czlzo;m^*%pMy;lFd>E%1zk{WQE?!zFGqe{{l)`dF@sn@xSxtST$}c$dEY zh2d!pmvul*Q(4(g_~dfx>lG#6bMxQq7*}o$loE$#>{WEw=V#PE_V$C%m-X@ciaoXe zXZQ`glJ&9oH{93gwzn(!`r#MA$MSc+{uw*x;G41jWBk1w{vO!-g_3XInN`WTWfXfA zJ@)NE$`Qie0C-&5@d4}X$FXnn^WG)xxD~tC@6ned1HVbbCEr%^T?jXRr#qm@_nEJc zpTT%p*~MSz^Nqk~X}H8M$hdwLyg}N*WF=p9y>z|V5~My7*n9Cy`}he@!C!LVS@~AZ+Rn0jbKj&e&PX|{8IK2gGr5G6bCHrxE$6C2Ih*h! zwpT_wZY1FkYPk3*^T%?yF&?f}@>BgR84o30O499@G5gWGnshe(sCG4bRNkw!TMtRS z)WI)<>(*0^@Tu_OX!HF{Sr0bD=O3VtM=N}RhD*6*{-}qaaS-v}qbb+32l71u&n@cu z%>Ov&H&vOO)M4JQt4xK_{~2HJha2tp@ZT5ut6Hy0`;B7nv%@ml^+pWd4xg*$=P@s2 zOMX%Es~KkHcVhqfrLlMK;rjf%Ygqrl&nwDrvQa?EPv(ynxKX~d`_C_gy&)s)^Amdk z#__}9hP_Li?TJ2u{wE_X{g0jXM*k=O*N@29uA9VO0(&{QF}kep{}W|pkNPvV z&&S1{%pV`Y_sHK5+Sn_34i?4Usv|SD_iw~r2z&3s4SP>G+w-Gu!QMkhWsLQGzJ2zU z#eBWkcu%JpyXPOBG55hq#jZLYSm%h+U)s=bIwoU&x8hTc{v>bFIh&;OF}{YzWX$!% ze(MYULCwczJ<+(9?sbxV{}#J-*bTysbHC#?c1zCvBwd_zkyA6d3>qbZx!S7Z1}ls%)CF-VP2m$w1Cn-=K%R|LD|H)qUsVpg$hvrZI0V(5p~XL7AF&hPUF z`}Q~fpfOuZ;$Hb%&I9hwg~H0qymclA=M9;R#b zHuVt0k1fmX>p|?w{P7{&SbyB2v0JkKkaW$Y^FPY^g9+Lj*Q6UcXw1EyLj6cOnLi$R zK4b2y-_)eD*;j|3;(Hdqv!4gVZVlt~6u2=T|3hQ9WIi^^PrB(XncR{iDaU{p?CW=r zpZ64t%h61_H9Io78}=pLahi0W?ZbQVg>{=ze$s90&gAx!bRkW;o4=l}ig9`Umzmss zdz0>FO*+rsU)$%#p5}KjD|Tu7x6B_tc(3@gN@Mp&#r<2#(M-AzD|h7%*@tv*Xwoe% zUbh`>uSc8sB(OV~-$Ngd zjeI{<&h=98+3-VEuDo}VgKEln z`}S1QFQgpa=ZWiS_T>=nhtF`}LHJA!m-6@-&%9OPr{N17xc7HFPu6hpJB{BB@T{z-ey#C)_I~p9 z!2G^Z(p52zPrSlv|1FwyCGB6z8^fR0t9EJk(Fyp=a9us7;LpHy^_aEN+pQlZf8RRp ztCC*F1MrOwJOpoX;8FN%4m<|mq~Q|RDC75L`0YngA3HU1?L2bKJIeeo<;q~!w{(~G zIaw=q$HR?raL`NkS82mly?$^gF0y{?cUH{N7bDcO#lg?(Hm?GWFk6P(|?k=6gw{|_xO=s%o?pq9=vkEK8Td6%?6UnGNXftQ58M-i z+qHWck2B17x5JI~|5KW{DC2P$d$XH&X`dU^TYPd+dCtiD+XP=i`r0C1xWAi(uY=q9 zE9Gf}uZIs;(<|}pwfKQ5x9)97`l=V$zc{3?vAAxX6^5@Oy^hzzSHiDU^Y;|)K{vtE zaJDOj_M*Jkkc4l6&r-R^ETB<-_~75}(ysG*;a>PLYI^1SNNowu%`V=NdqB=>KTzsh z-X~map3}>NrO?-7cwr2eX3qCcb4)n6?<1Rt*Yqtss={7J?qUHvt}1Ekm0Uo(6pTvvaM z%p*&&Z`9w>N;yjEFN>WDhkSf5GY&hnlPvl8!&Y2RQ}QW^YZc>d3OhzzXDGUoxHgdA zCUm;E#^Eo(b#ZNhA9JZbu4%ZmdtF?;ukd~zTo>0g<*3B|SJFPhN;yj6T8o`)uwyqK z%RFAqcv}ZI))!I5j(RR?v%ZL9cM16qRom5th5pzAZ*bsg_^lc)^I8jjRX)4RJQx0z z#xLc5X0?}d8*V(m+^Df<^Zc?AyW{_`OZ!};8GgD0Z-q~G;2HS6 zv|HW2z4DLjxro!OGX7uRbAD?+G3I~DbrANA`|dlGa%t|nhq3n+`V~d?%yCY}uX_0W z7xd+Af-i)RP}3{#VJG3Y!x`2Uf7cleL+rP~hrPJVc#cpgPfwor!gs@mtLc^Ts%oRj zb?dDfcsRLBdrlID*AZ{s{9O;f46f_6|VCu03Qb*jy4}xD{eCHgy5SQhx>bvzaHH{>|Cna@t8l{ zAbvE#&xaqaa^=0eBz!tt*FM_dGvK=R(F@Ny*sp5g9WMv_HSn(-?1$kiUSr>)`fvRP zxRkFR{*(i6f^UTD>LCeFz&YkG)PwmNyZQYt_;273sa(eFUzlU3{Ij3`^S(-*zrHJX zo2oO{8`f&Vynj@U?nmf!^GGc`3=gVyl=rjh;0qnnH^S$_Yt;10d;iVwCGdO85%i5u z6?Yp8QHf_O{EJQc^>PNDf!oa^5{FjiiEZ$)*!TKhDXf=_SXB5WBgrT58qcTSu(u;T z1m6y~s~6!>_=oVr`8!_@;22ZtKhnQmG5=t z5%^)MedYI50`N28I{!lO0Gwr3p?se8`EfT2e-FOD%9Zz6WAK;Yx^XiBf7*ek;H%)L zs`i!l2($2{LwesP`lSO8z#oBgT%wfk$$a@j@Ud_1vVFd7)IWR{+-|)kJO;lOZr4tQ zC*TqIEk*guF39YsDfmXXUHqh-XWW;MNx3mXg*@~_4|r|J#H*H(Kw;ztd9GW={w z(AOV5lk$Fq;qx4LJ$yO*5H-DZ1yt-e!Q<0+*q&DjPr^6DN2}@0pYb&OZ-b}cy78zN zK9>BCQqx~<#z5>>5ulSDcn!P;uImS3_-MGU9_!(LhxASGLGZIw|2(G~4oW>H;p5;x zQMuHkb!IL9Eaga}Ye08=(YRTiA2+>kvafz?m-ah?es~*PSB@Zj3tTteMc}W($E$uS z`_u;bR`~lWH|L+%`&y)ww;5gI+s-;EZwlQhf7Y)XvhWFT-Ms8;<(v*aO!de5PNVn{ zfKP=x&8y-^7~LPy*|iU`Q^Pp?4E$sM_MV{3H&Tbn`-E}q%y~y2{}%WxxNbg4Tl_ro zDfCnGev|m=eT#jw#=iLJhcAZTq^39PC;xo{(bb~+E4uk#*IBDpbG;Eocg(xaI`OLs z-2!y;RC^xt2t;@iz8QXw%88vUIfS>tv+zYKw_f%Z-V49zJ$*Z=dYkn*JXDn4e5GB| z*T9!Kqz}Vaz#~QJe_%9eNna2DJ6u<9O%@LqrN1bjJ_#TC{;u4HBK~5Yx4~b4>(-CG z@MgGfo~ZgW=acaM)`dZId(heSZz*R4J}711-=y6%z>k6-q>fMdyDgra6iDneqdVXO zeSNjUeGWVWKh%L&zQejn!^O{P_-Odk{GIPdefP{BHNtNA8AA80gPkaRy$d@{=uX?R zOFO?M;Zxwc`fY=M2d*2pd*LU+4^qox?H?rGRqxVY;o9~OpW%>y7=DgJ{`K%P9P)31 zpWu*x5OG!cI^_E{`#{&#d}*CJ5tUde47K0!0)ZK zKfe?|8sJOd^{Sud{5sDZRm^oeV{ilYf?S1<=hv=f+QoZv_3bZ6*6)EqyvEM*>|I z-5ILR`i77Amx2%Z`>tG0a%8+$NM4gBcT7UPXAd!Z?u2(&-|lg|J=6@NSa#l zGmLK9R{MC1pY`yW@DFwM_gZoNHKX@@qPN!y-w*DlJxDov(GU8x|9JcV%Gnq?yKz*? z5rn7Umsju~eeFg)gRZT}2T<~jqTlN?=lF@P3Ekr^bS>!4+1|gs47!~zbiR+u%I?|W zY)|U92Hm$m*YBId@EhQ|bDDbi`wqMbK6a;ldWlaGz7+lvf9K)#TGAo`!S+qVz#GXk%NJFV{}-$rzi4))a^{==>vHJIOc zfg0=VB>K0y?DG|SZSWNQ7+t&c722hgqp}TqS-rh#cnW@&&cEY}{R^Z2e7D|SJ-i#f zcmSE(mG>tD`l``5r*B3-<$uoOsFXW}?mcuj>B=1`lw0b@%fwez-kw{?-+4b|+`l28 zy*dA(i=uN~e)LN!+O^|GJ$xD5&G;wfYDPbPulC#sui~dV&QyBy4okV(&>y>Rd%yF# z_wSrPp>s2Si5~&?!VlG4!JjX*YgP z$kzVfiuEn%w-0I0t=9GLSV3QfKUwsb4b|6+?;q@|;798G9aw1RQobPia8-NmMP2?+ z6!I5+6#e$Y+FgxD;%^-N)?w}1_t{$DLk|Cclpp==XX@9{zO5z?lXpJ;p2E3H0RA%R zHxzO6+(p`52!7dFJNi90sYkaS-FVfGbuKF9Zi2rDKT+k@^Fzre34e`p->-6W{Qr4h z1C)5D(VZ~7J;(G{D37`x%Ac~Do=Sb}W8Ye!@BRk@kKHuZFj3xcF5IPr;q$InhPYC696*Z;kp# z=Q~>OPZEBphD*J-!AHW~jF(3FKV^S#tUkYL_)rI43m@UY>)@j_T>Nc>kA+|6;Xmx= z!*hzqoh16pj&s*;qb1FFXZz+mEaN#kg>aK7O_EPc&TetAl?IzqFkH=&N64 z9I80Cc%EoNKjc*R>w{MG8^*iSOZo z4^-1z_ly1fTg_JP5x`ldlzGo_c>aT(_$2-LQ44$}{5CZoa~>$VzmY*V|2z8ntNe`n z-|(TToeRyGM9NbQzX@*Fo}@gr@T=hq)$}FnNU;+|w*lQ@s!q9I5QD!ApRID`TrmMJ zt7+HXA4tJ>l75hyUb#1&g@5e8ecPEg;HRqTmHPt$_~&q4y@%lcgX`w?D0~S1AFA4) zUWjuHelXmw-AMcra1Z*AM% zkA~~w=lh)VTDUHL0r->&`uK(5(;eaygkE*uZwR8z8tQLZxsF&To>OMeEn(q_$J`d)Aa2x1^R<(qBxKbfa|8P?r!x=Eq`DD#vje;R47mxJhMmJgw+9pgUhTzt$AySMjSC{Q&Z{YiE*g)h@>2)7$&K=MY3U zc9MQPjKG8Nld+kfN0}GoQh@l;0G|ohjR$df9lSziMB(H`!{X*Oe~=ZzlaDHNEx5uJ~8k#d{0zp(_i#A=faJ9x;HBQ z%;+QLJzdc?p}XPS_S|Xw?Y%?Mk!Rn+SadDumZFpK$$OWglON{b-{k*^U)9~%M5n92 zTKJoAZTpA6|9kGw+Omt&>g7ilzmW;@p&cueYp1? zCH`XTjY9uv#?F-U?EA0y*od8}@ZXA^hfD1IreG(Foyp_$-<$Pi`Q9XU&QksLoNgG9 zxCG#TbKoJk=X`xVM&Z4rw~L3-{^6g)hpG8n_YZ|9;M?Kns@!7^1j18rANlLXfh>F| z{6saqa;}(So)`nag?YuBD2`*rPs}+*@~QbZbNBc3>&!6xPPpCrLekg6AA!$Q{jeIV z@Fw_2@JJCa+@DLrhfUSbS8edK;G@*^R}|VoFZ_J?V=DJNlCS5g-8`Rz>-?{Qx5Lj- z)6-^U$P@p=@F5p)zM^tvU04tQHv9yYEBl}(_$0V)zDdG^@NcN;)%!p2li`C@uIz(* z;iKT+Rk=Ccn*IMj-1CR){HuXq1h-o+NPi5&7sBsX?U$TSOPm_e?L=oct_hFBPnf3X zE%2KhcpARJfqVCqmF@j~d;3xjKm2_7Ctoi|ekUM))}k96(2py1@G7`2o{jJ^a9uo` z;nU$4tA5BBng5j~b9_&s`#HK_mg?>?+rIp>_}hzaH#)mZ-;VX>)X8rB# zvn0A8y5~>YQM_(5b@>@o@~cC)&&fM%+nd;Fgm0prHuHCWzA3p^Q4LCfd%f=qVuSujbzQC4uQ<4{t`>iS=({g;_k2b4QS?pI-P@0&Uv`nZ zb6T;VLjTZ=_S^>k&c{*l-}6)=x33MaF?YYy{b)>rQsV=N1#cmq?i9cx1J)_z++h@`Jqsm_P zcP?}RbZ5-!-(DEqn=W(>=)Qlsv%M;OZ${UKPB)&n!rz9AHXlE0eaEzt6Fb$#m{$| z&@Y_Rp4(Sf&)H&qEBcw&wCA>{eyjHXSnyl?=|x}m!}i>~0UCcUDZYPE{T1hq*Eyeu zh}{sn=g_&mPtbrq9d++_0{xO3+H-YkIhFohF|)XwY4oq%NF2SIa%PMBi!WDJ_VCU9 zkHai@*T^DWUgp|AV7yYmgvx1#_1;&xZ}5=GyOe%uoG z`s%XsvSoL-=U!IhuC}j|dk$gr!|!o-FG2cIBl-uI_TN7f=*Iklb*buyTK}U8^)F*V z8vR>i^y?09d3o7C;JS5(AHIkDHef4XZzbb~_+N|e-g}*O689*&QTMrvqu7n3U$?CP z@ud~rg!|ibFX+aL#|rJ-sDJdE9&FG3M~$OepPv-sD1KCXDBtq_%NIg7>Y?`B@w#?i zRou=S(2su9-8?CNC(x(R(|il{q13-;S7Ck^eHwjymHY9+S5aQJ^*8SH(!PS|KdaWa zuL%6VaJ%*;=^Nl9kK0i^KYI%A)5hV?!FBtr7I+(c5w`N}Q+dxT4WCH+K1JoqKFsSa zFAK-@`)xmbCOo31SAHKW2ww?5ROQO^ya;>+e3Htob2n*MLB{7K{51adri%C5>N!;% zx)i#TMfahi%dfJ{b$yEbK0&98cNV_iV-C-M_A+@$_1D^DNPPw16G*?Jh(BO7Iw?;G zz8;=Xxw+n2)7LV^PCdHdYW@DY34R&e?wmr>C*hCKuJ%{+QO-l#;CI7+uX4|Gh6|Fu z7cTAYp&}m3^Qr;mWrN87aFr|1$!aXFi&GeW7U^|ys)uiY_ZO!)y4uI}acY6jf$QRw zhQIF+2k+kHW!E~y!4DsgeO(-a7T3ig0-sBIT^t(V+u{Aip&4CtjXn;o@TG8F95V1j zDW|SIRPthnj5BuaLB`Q)_-yR|Rc#OIxU1ZwlYS6JU-^W29+@AP%zp4_Uq2AL4d|Ak z+pe>lKV>lY_X+e<*0$%is(RTcDLQH2ZRk8t>c@dz_-Oc0)sA&mEa|KEEid!KYgDeB z_t(HD!l$X+V;(R``Y`-@2mAH#It@4C$GANQz7Sj9Hf6k1_Jop83wB;cr#tUV!&~4{ zwE22a-Y@d9g>C;JSUJZ~yYLFMg|U7Xf${u1g<+Z*xc=g>QxH=BF53{5wdk zFXg?|1bh$awddb(zeD-5@WBq;SLqy|09@jui*E?N9UfHux1NJZ{G;$n^4ERGCI+v6 zS|8s8d@lT0)&3lFL=pQb_yPx>h2II+jg!6uSg*i!sXE8pL(XHrJ{hp&X|?E4NZFI(=w18}jgn-4=4 z*R2Pm@TH{J#V-bz_~_!7uFbC&$b)q^j`0V!uO__-{y`Pc*~eF>rxV0X}8Vf z+lXG*Zd>7Z!VgB9Z};b${Yw1Gz!$(XDwnzR6H_DqEcy7p!TSC={d1oHd@5WQzYx3@ zu4`XWi(jhxp?vo(246z@@2XsRE|q{k4%fAx6#N1BjcR(2x#2VVKRg51`R^OV_zl<1 zZvps6aIuw-vvQ9m1mEJ2J__IDkUj=)aY&zluX9MBfbx_4Xqr(VqhJWJM z@AF&XXC1l2_Pbg}`-guIUMm^)oj*#sCY7{*UwPS2&^@W@Jgf8LPXPWE+-}_~`GnwG z>1Q9S=?mv&Z;2u4|Mln|B+d-S1%H%vpQpFrm)LDaAAP?6^QRQL%7i<+;)j=je~#Ym zz9xYF{@*#D4~xHHbSJIr|Gc~b-D-3fY2r|EX5k!8+Cc*S+rPIzkCF1E;Dgq4zf|{} z;nl)(1M$;4xV$X+g0r8Zt44R+i~Z|D=vKPW)uTHo*}uIwx`i%ut?0VZaZFTbPkqnv zI?c8u@yVjw^pd;wA?5ZTLjAm4@_f+T$Ns#pg^Jx;bc0@D-L8xK7lnEheLec_4ehyA zI{iI`dJ=sz`pBQ$og0h3P3*U{=gJ50AAS8@J>Sjj)#tu3{!|VrFZDtuNpr5 z&GuZk&fkxV{SBl4SIf-~JBgD!TLTI|}FBQjZz*(^AgQ8O5&e zTg-3h-1HyO2hlhDr9Jo0z4;HjIJfSdkF)5b=uiHKyZ3ZNA4mW9t?tgFMV~@H^b_~b z*S$l_%Labx{(aj3`ghWt7wE<-<@t-mJ%awDfA#z<3!;BykNbWbMZf94?(|a6ar9pvW?#?3Tj0AL zcpBaf*R7|$hY{~D^!Mca@a1sbekurWfa})d5%~3R-F~+LJ`b+j@5bRbz;*l07AyY~ zh(*2~{Ky<~BtB{QgQVA;H+hFK4-=nD)bt+n0gj~i!>7QP7xDXz41@>aw_@L}{6_zW zuOj_5>UhDrv*HJZ`A~F?=sq2`qxd~{S)W>aILTh}OQ5SFKV5lK@G%bM&BEU&A6J!=J*wu6~2?(IfgVZymZHj&v@sG5(>eCBF?);eF#;VgHc7r;|jNM(1YTF6}0R z{vJ)e39lT%xg%V6zEBO9eyHoGwN`q&IEno___YrCH^OH)J`t`PXEN{! zaNW5?)7sk~Zxa6;!7sBu+2VM_f z47WRHlYS6p+>XIzAMUME&d1EX$HU@@#GwT{Lwfb^?WEyB_(-)J%6mIrKj#K;-T2{$ z&xPyyMG$^9T=%>p0-pgtLe2lOLL3|5VF&wh_;d%}0-p-k^}95D0$f*5-Xj^m9Jn7o z*dhNQd>~v~es~#NTYh+jgZ()CD~EQ}0{`5Br{P=Ry8OLIm6!b$K3c6Gk1eLs!E$2;&A_(^cx{FsKH4cDEAdXMJ3 z!oj{Dz5*Um%V*txk$xJ4?>uxzF0FD|w|r!_artM_)uDU5YDccQRJW?2ll~k-cP#5A z-8_?k9}lBRX82LyNu!{bqlM ztMhx&*P&l?WQVJJ9-?nT?>V}|^?N9-==Y#^^E^TNb1(WkhS;AgNPnw3j^|9H`tNT+ zbR&;(U#=+n`qA#%lf)s8{_W#BT;ID+p$~t%BllljJ4qMXiImejro8N^Q#$&6f1w)P zQ|R36x5V!-`WfTg_p?Uyvrl!Wm-U%U;Kh_Wl>V6aM`oKhMvv z?;`LchU(+c0RIJin(Bvgk1h`XBU~4U7Wg{WU%EJ?;X_$>>Ehr$zP#)u+G&4rs799~ zA6+?X;U}=3($#kzd?j30&PMnUyx`xoYK!taly8gKBsgT(?iEh3^N~?Styzez@*Dp%E_Qk#3*b3?Bm5ofkAR z?u&inykMOEydaC6HRyEp;tQ}&b>IPbg98u2uXo^4_$>G&wf!jH;fTR+ho7l(#wGdq zi?pi*T>L**v~S-@_(wl{No_Y)`>uG}JhK)*YS8_g z{&;hdog4D=OBg>_qQ*ttKa{)&=_P=(CUxYl)$M04EZ)xq(60z~y+6r07HF z-<#=f+!cKT`Y$eVx9$^t0=@TA_xsy4`V{&D)%KwD6ZM{v*!P{v{jtm3+Yh3@{Ri&% zSyA*a&+5oMtE;c3;`)lCpBU+I{XOgydL9ht#>zlp*B%ZnelF~l1CzNOxedtkdYk7h z)##R^<2bRPQ{t$87r>bR(LceuEuh-{abbN>51;#E{XEnJ|264ZrWf+7I3~ZYOv0aJ zJ;pLt;iL1s4PJ$PyK^)df0E1tD_9r4!r$JIGGBULFrDPzr5yh6&^{@*-8e0Fg77T7 zzw@>_bf1%-ZhmisZ_%t%#gAtAr*K_7TH#&HTe^5;;Boxa#iNz^VJq{Q5sx|gcm!%_ z?+)<@!RuYbqaNK@<~O_bsxkk;zYEuuHwizN=a#ziw!v#1%9~`K7|(M{qrCI=<@JA; z=K~Jq4Z{5{%3FtS3HjNTSK3h{Jb<11`8(eaOYWITToULW(fA|dR|>uYPV+C=QTwTK z4l4G%6KEF>{m>6z2Cqe%_ses3ew`D9zYN!{*COyw;ktEm1AG@;w{DKZ2h8ip`PBTa zZ@x&}jQNA~t^Dm>qST|TB{rH}S#%lfoI-mkQ{y6<-TCfr^mpHB+=rl^=BxR6eqx9u zz5)1j{Be5@5fU5BghyNmr8`aS5~&Q~qyw_NZ3JT{Ad)KA^}@1Mwgj{apeZt8lf zQzsR#ry9^NxTzyoHh{w0%~v~%*Ha1fQ-0Qw>(be8E4H6TUwOOx zc=}FfoJK!IH$R_LJU<7~d+&4~|0w$Di#adUt*4^J>!~>UXMW+XKTG>bp?~3Cck{I9 zy_2wipZk480R8%99j?B!D)uAjx7_c3Js3m(RgCjg64-e@7*Ye&C9Z z+(6y>=*vRa|5XgjuX9@9$H(>SsI=q*w_Cp$|1cVeWp=<_;!QFt1@7H)T5BK7M%i+I5Mdq1TbUHRksdAt_B zlK9&_PnLY@;2HASz~A|C-e#W>L)Sn)IaQ~Wzx26t3;NI+cl&qoBa43N+W!5hI-7IO zC*41{tVO@Pxx@AMo$Aql{!~ZqKHWJ&eet~4jJ`JEex7MVzjB@XI95((KlXd-S2yl{ zvv}OCL4WlN9l1ZKj{;M6X ze_x{){p#1;uY;=3;XLnk_vcVy^!sdb|6H&U{p>f~$3KZa-0J?^A%lMTTkg(rq@Pqx z;eD15ocALV_aM4k(VedwuS&kV9!38!`&hf@Ns@02z6pMfYL9h#>3!iOy3m%6ToY;X z2mlf9YVlR#EpUkuU*{eL4eU%G)0d!w5ANFT2j4soUJ&9ifx>^RmxYJm90L}(GQL)noE!UVX=i_BJ*MmD%I^|NyhG?;`&<9( zrFwMdx4G{h&FI&B%=1{CA0_WswV_}9kB;0;y74tqJib<*$Gn_&H;+ghYtUDI=01*f z=zZHea)Wf^>;H=@KX<>6YDGVAS4Zvw-S}ElJihj#KOyU`-AQ??>EHwZ?QTAi zb`VCt75xVO&bLFG`Mv?&{N3)y;RO1T|8YMrq|p!A)8YDigud^wzx=Yp)$a*PT!QE~ z^t#*6NnE1nhk85veeThO?s|0F)%Yp>wDfy7t>{}h57nJ7X5j1LcIQtru2fE?-#YMW zcuK=14z=*L`0HlfCi&H)U$9rF?YWNFYl6>(pP=jShZXvZ#I+UuyuCXezf&xBv*%L`hHvp{jK|V<}TKaJHg^{rvd$%ft{|;OA_ce4(fD${**>vcW|ex z@5M@deADoMu)Da6K8Swdkj~txx^c%}Jnlr%FFD*@I}!VF^fQOM>j%;fQs@Vb=@zLA~o-+x8F;>b={=de=FM)dKcI&;_Q;utQDV-o$g}Sxg9MkD~{;Ueo4#sx69tUgDXOHi6{oJ)4{fZMibNA}{$<4+6q#6Ae<2qgKucRHc zp|AZ;|LwqgA@32P`$#v=DDTTl90TZ=PH-Q`2>Q7bJ9FRC)vLF-USsHIobA3|ThI@j z>~1`exMb14fc`7~&d2y8cmF+&@~; zCx76sT}nIXMc;IJr{g^?iMxLW&$niGy1FMX`Vji3BAu>&CtLIl=v(G==BDcU$9IbR zM*@BNNABBu8vW9_&f|c@qw-?Tdw$&M`20=$4WL_w?iAg;QL=xEpkFbs)Ae_}W9Xwl zaX&A$pkEbrH~$*_AAR%9&he0PR?XzSv3mF8c`f?SZ|QV>&%Yjh_-CED8M^j;MsfRY zM&Hoju3bqv+t9DLv;X?^Uc&RmpLe>tw`9~m`uTUck4psou)8~R|I|I-YAycGdJO$L z_tB5l_Ep$7<>Yij%9lj9ep#pSyFvMJ+(4)Rx_%BGM!)#gPS^Je8_{ok-M#-w^no`zb5H2Tl~^H;Qr-;u zr~cgO`nbr{E`0Miaxok z|Nfmt7ixDmZb&`(XP5I^XPvI!BMYIQzq>Q{kglE@itDKX{U=|zk7Gjo>2-fTkw!n^ zEBF5UuHalM$39$FPvPQv3ZhT$)#Z9$8byELK3)B;yPMEGh|X>QZbd)vpsw6ay0}M* z$N(9KfW&4=Lcc*Hw^A__5OvlvqtnQ59!KXtc!cFIPOXGn-1&BU8b9- z&MC}O(myijcOTx>@A;tbO6I@eUAe6~Ki(|%BZz+1(OtRAb#bpPj(ZgSvSZ!HC64}u z>Mqy&sTBHm#&o$pck<5R`&{4d%AKk!ufMpw0rcsUx?G)yO57vpn@{QLcb(dZZpOGS z*ZnSue#L~Y+`YQE-&`E`4Eir7b-5m|tFB_440gFb&#FcL#hG2MemBaP|Ikl3yUW$@ zFNwYx{jKM@_oofL|9f4zHM)Aezqnp2ujV}9!miwCT|B>89M2l`4_@5m`uwI2edEk7 z*X#2p^w);FT;GFiML+q{E?3_>lz8@{A9_WX>-AhU4}8}|x^jzk@%%|~Jj3#U_=jD& z{dDpCckz9SM)V)e?Q(t3KZ$A zgf2dn#qp^}zxdX!T(|Cd=*PwJX+}TgcK7|a4Sjr3m#gPz5}(Q+avssp<@&vz8uYvG za_>(a`l)w!<)-T5^PS@OG@+k&UsvuuU3^|Dj!!H4K@W7felFCDK8gNW-T6yX@%c-2 z9plxnx?Ddu3!~rMvZT<+ULE&3Cl zqrAHMN)^{vJ^IY=Sg+~gUvfX88U4vGx^Hi7=y4n4F(S*L?P51TNihkQWlvfx3lJ}~5(O;cn{h;%|Rr8o1cetG1T%WtQp`ZJouH5Om_*56izw$cHF?+jQ-_NN*KRZW% z*Uj%G=ZAIZtGwN=$LA*Wuc3Eazpd!k@7wMA`E)P(1(n^d&cFQh_v-8M{~O(o=h8AR zgwS~hb-S+D2K3d3bi023nn1thTiveDfzs$_4C{7XPrjcp4j$3%`gvCnebbTMuFpH7 z=m(7M&JEYK%l(VnWgPwPG2O1;cS)gNe|)#=a{zCYd;2H5k7odV!}xC3=h_kUTWY#p z?~h~X_c^^gw_Vq--Y?#Vw4mQ`X1D8e)-3uj&hB=-Z}k6^bCO#3@eHAlPwjSnpQi!+ z%hS4D@4FJ{*H3pJ&ouhaXLh@~M=RPx7hLN;p57aI-a5D2_4!Hw{gQdzuGi%e^wrVs+{L>1 z1dHPnLqC0fx9f9<7WBP0F<$B7Q}Vm7S@d__;y#}K`RuE2>vp|w51~J55#z1SpOSTO z1NyCZx{qf9{q0M-UGGcN=(Be-Ug`W%zTalF|C{(8>Mz{KGl>43W!^`0m^auW?+x0nc4E@P* z`mfHPl67PY`mv9@k7pMBb8EX@pO5-)ro2yfyIvQD(64;TeLNe`uYb1N^*LGs{Zr4m zU+1OK&-)$omoA=>;(e*Fp7ZAQ-LCIN2GMW-gZuSc6#cTK`*_CDM_=i7ea@9aAKc)6 z{pP)e@5F8Fc6~oKfPU+%tWTIL^Y;cc_p)U?iJ)Kpn)~%z4E@YE+{d#8y|>lizTxYv232F3`Kl*>He}2Y3 zxy^lfgXkOn?tVQJMIYJ9enIEI@;;5UpE&xrKk0V$yhZdW^be-pm)E71F82TH zeC{B+R&?{f=ytriL zr{+~Sqx|sA4m<=;!^f!UmEX6G!n+-K3|_XRCwH=%-uyhD@qLyAd@x+CBk+72jF3c^da~S4m=9K7d}Dt|E7ZfG5AyPMJo3czU!KR54yW2 zcR>+1KkY8{lY$4~y6#{}S*8@DtVi&F*3NpMu{5*V)g)>)|8R^x=a4zMu1)9j>i^cq4p@ zn%;A!VZiAB@OAJ(Dp!67B??~y*L^oK2KP4V(g;gw7*9mgV(`z z@k_ujgD)+ze^=iB6ucF#9sl6#;TIOApPEnayQ{pc9WK7+#~0=IZ3FPn;g_mh`TgDy zeAH5X`-{Q{Yq*SQF}N3AWMAHE|Gwd(n906 z^gjJO)dn91x0?r~9reO1;cu$;rCt8ftONOHDTn_a`979@J_y2JhU>=Th?QQ)8{n%* zubZ#q@JHays-K?6^Koc_S1+?Kr}&?S4}~A4roX(<&b&*@%Z9^s-{skMTUtd(|_Z{9Hg=u9$D$ffYL$@|pdB zzQ0sra1MMp+Pn>`9Fj*P|0nz<{?~hYaXy~s3*`-Arx#t(`V3!W3m|?(;RiivKVJxs zS?TS@E%C!gxd)NHUHo|S>7w#_(xxAxt3mf6x=%#6u0;1?K^H-{?3X>}_ah%I(QPc0 ztNK39rI+{Eepf~Ou7%HlkK^xr{LIfr8skVEd>(wD%FS)1!5iVT;HRscxZP;Qtr>nh z{0xt;d=p$Z-_^o5!gb?$9lQ;$ z>j#bScDQce(G2f~>&Agrcn+>xH)h~n4!rVyzEcX^+w~ix|HG@`cI{K@yfVhV7(QLKFY{skSHsNt zFo140x=E@|`F?*0-T>F_4^rN;vX$_9(tFQnF6zHV|0n$yaJzmYe)_mK@j3kGoS%9R zE>2%@i#gtjt_?fqG|}Ga-}&||V`9no^SlqRPWp9EE{H6zvsSp`j~_l8ZudJdl206e zE`Zl~@u%s@LV3(@IgXX5yP~VZ&Xte$Y{dVtW2NnYFx^wrrhMu7Ki~Rj$fkGXB7I?XHpZe}})y|9ZVj zdMVd>^W8S_Hvzx-W%iHw;T@#tq^<`U?ik~BJ^B6k751TOd#IRdGzN)t6FmOMo?Mc@ z^YO8QBRmP8xUna2H3^u6#u2>0?Ief!6XYU473@Om~Xn_siy zb@>xtYX>#U*K0o0ojj=mxxD)9w(pKaJzaD?%%hp zY+7IX^5T39`=o!$A-(q@&THXU6t$bn^6kbC|L5kCeX!?FBhJ<0ANkk5*^_%++WUQL z3UTUdqwCBzkJPC5DE2;mwireZo8a+Er9Pxj|FY7k6aLkxw`z3N zpLXYdEB}zMw>A0x){Gx7z>RY3`*lC+NI#h8a&Hu+Z^@@`gnK^i(f)o^Gkh-GZoeL*D0QUB7HD+0f6oBq7I0lo^pZ_zmD&5wg|_}$xkw9ji=;7j0k?MwP+@Brp# z{FD1p-p3y+#HFu)K2hjT(jI)jE-$+jdu!ErP*%?)`Q~7>hbHVMcn)gBAV6_+G@ z;0}vl{B>SWJ`a=6QEEPyn|VmRG{GN(>&Cq#`~kS#`G%Cc22e@!%cy9Sq)gLLhbtWbMEPe&hRgI}{#*kJ4~yrz!k8gnVYvU%WRfex1Lx z;vR3~UW*1)tlH0PrYrg!H2h-$w)3-|T${|RQ6(KdR=j7jSl14dheV#rUK8A#u-_-dqPYqg#ybZ0a-b@07-hMc#^WeKjfN zN}+rFiyrOs$t-*eyc&P=b}EiGI)SA3J;M9g|I?=rz`yYo>nt@c71Q(mH3VP&Wq0m} z*vi}YmzB5pq5Gs+KN3%{+1*XPs6;FY;X{``Vjmh_~|M) zi)XHX;Jpq!1|L@5lMAcqJ>~-#@jn5d3AeLv^#6ldyTXnBzwVL3xF_R;+W)aLphEwg zwdyxK=Z8O8fh5gX_*Kn&1QBR~Om8!pPqkpZGzP z8Sp)D@9u|-%IRr0WJbKx*cr7~Pww6#J9p>H;f>Q@;VX*x19|R;4;s*;ZSO(&V)z9` z>CHm}sjmq91$aXdFFYq`fDhZ-o=Z8sJb<_zzE1ugQBuz4LOENpGjN}h^9zr8&?|N_ z@U!3_GcV-F6=@Uin{xvHYQ)R;80~Z4p4>I^5BYUoBp;6e{H*=-^%jDUgWHX7;zx?| zEQWuDAKoig7S&rtwlF_6Vdt_+&QVo=E5;ZCiE9#`mT_G5(>(Sz%Fza&c7Xo*OE3H# z((CqzRja8N(mz-<&fk|G=WF1xgY@>p@P%-8z=b$gm_Mp6{@26z8`P7#R`uU=Wj@YL z@DN;gUYUeXgX{WF8$1ZtKL3O_!Ots-?_?vsQcv}Vu>U=na|itQrkV=%BdAc!lH7T2eXn-ntbkr50v%8%94C4%(bcH(~OsM#*PUd3POOXknB z8Rs@(?6p>v>`P@`W1U$`IHX(+=&BFX*K-^`8m_D77I+n0SI=qq)qC{i_C7&7BmHQ# zof_q?$bVs2{H#V-gB{)ZZ7uwK2VMuC<={sneD^Tt_=_J2bSGjb#NUPS$^1bq;VJl4 zaJzG2spl+w`Qhfgkxy^d^G>y%>pAGZdN}9F(*DP;D71g6=VO)jzn1$>BlYzYfnN<@ zNZ$GUJWBf~pH1-RI7jtnxE0$s=1M<%%zPKlXrDCPX`^~_A7IA&4@DP^#g84Cl_ zz>n$4{Y!MOmgw03daS!nVB@=P5%lZOe&1^4`m0Cx4)f& z=#Dzp(p_b*6Mxg_(&#=Gd*_wtB4fsStlvxo8~*yJC{@DKYLG%-k>&a!r{=SO7 z@J+!vV}_f*x+?xe(f6X?A^Ojj7wSXeEb%M-eOC1A##s7So%Kk|qRqTt_HWJw`8!|N z(+Y9RBAWW`p4?}W|DqCmADcR{Q^mwEaIAH1bWO2NcpLfrihOkY>t6VyaP9o}Tiz3a zS7Iyg=h<>l%u&w?yRo{X>J%Q)SqF=1&`}We-nK(r? z+IJRx>a?ER0iwU|>v~VltOLd74=x|*-)4(qd5^ECIQ&nUUaCw;`atBNVZzZUHIf<3wa^55RQ6nmoW zFv}wOX3%Zx)BT%OSKm0O=%iiyhL@GCKhtXW|0>oA55RqAS^R^q^ALPqAAj}hJPL2^ zoI*SnH|=mO|wTu8s-Z|}8V)4koN3!~d_dQa|M z(arpt?$th>pN(V!-3RFM<&iqE<{bHF$+sDMvoGq&rTN=CQn6>8(RhqAAE}=x_O^14 za}j^%?Rm@rP)~rG zKl1i1A0&MfJPx0xruUc^X@w`@Ti|x{h>V*xN0gPl4WCp_IoHGr``K`=l>r8(| zUx$8ckEL&P)=U01&vPFktG_22hPT7*{FC(c@PENi=kI*^X;*#sJ(}PHn1Afff5qP_ zDswmKjq-Kg?^r&`FN3{(cH7sdQGVVQ0Nj|KvZ7{mf+2=Hur%!>CZgf0n+ne|-)5@tji|{?2pOi@%k>=iD}DKdwstjo6z2H|zzR?TJ2# zerj3P)DP)jpFuyn+|u{n>lk0LUp0!k#AE5VI_sr;8OnEOMOHiBRIcZ_0o<-V8RaLx zINT_IL;v}OvA52fwLNbTdu`Zz4sO_++`qkM?6vHr_rDeXFAbOcYLDTb!2m12vi|d{ z`UCUu-dWrGRAR3Qdt=~+|1H1hx4v4@Pu$1Sujyaki+cGSBbsBEeKmN4B4S!Ng9pfkYHDhnv`TF~9t?-vC zv$pFZqyCRAD|-fRdF6-oKt6WvUkas$2yY{9)u5r>(6e%>LLez~(=;@|Qz z_o9bnwdb;Fcnog0&X#yZzRmd++=y?DbAFhMRexmTc$ob-Cw|tzyGVbDnqK@gA34gu8h%F5`LSa+&PzTG z@L})+B|)E`=5dLUJ`S&hU!Zd9QnsXTflq*oPxAHSOC z-@I6|5k5)$@hbk<>{}#0Y3yw~+kT&I^ndIn4!7)W;#PUS4$M2o9_5@s>;?XW|HHGk z`x@aP`0q9O36H`*bl@@gf8lofCP|-w`zGso3jS@lu03VphrzGKR=%vtb5~yr^E>66 zRm9B+N%9ZCXT#7gX`L3)Jh*z)0@`;jP@Rb-${DixqSlO2)|lQue>jn zf~Vlx^20Yer1!nbd_O{OKLDTRz(epA4m=9~#DT})qet5B!;JcekAmyspMoC&*Tp9b z{~=r#AKz=d|L>4K0Dshhhu}LLcocs85qke(@SET|{}S-49MY%YPdo4|{67xd_j-BR zX?}hF0r+unU3^3EpE{(E!mn^hAA>*Xz!UHu2m2}bKONF%;l~`Q_usdP`??N10RIDA zS3e>6;|}Sg@D2wagP(Gg-hKjpBwQE&6nrjRH~wVd*Tauj#}D&*oH73R-Y73y1m9of z=CPc?18}jg%RdBP2iL_X3XeOakHIqzJOK|Jt+$_okA&;|%fhdPYsxBS( zE?hT0hu~4Tw*2tfaGifK_*#eb3HWk{^eOmOhxA$a+Yae{Z?Yd7rT0Go_ri7lhv2mi z>7(%R4(Vg?+a1y;;PV{Pr{L=ycotrEjNX4=E8k0V-~sr(@DXbNFqh3n{|LdC!L{pu zcr#qP{)4ZC>)Kz!%3s&MQt(?zuUp?_;hW&P`t!ZTJ;Kp?9)O?C^J!iFA^14b+nuAz z{2hf4CjHrJ{FLVcG2x_VSz1_MDc`qAz>k5SrE<^d#sXaIr{Ld%+pV94XW=s(xbN-q zvdbNK0Di3l55a%pz@zYb2Ofjp;lLB{r4Bp=Uk)Fv#>d)|8RfUq*Qi|Czxw{n_~T$d z0Ds>Y9e4u%7YCk#Z*|~V_znl|WUSYT53duxE5Gzg%wK;e#?0%8Qj$WMtCa6zoGR=$XUX+^%3 z{oXS(N$xCj?&|aSbjf?px#ymH?$6x0GZVIdB>lnJ$n_HZSku10*&;j+kJ3K#1KfKV zk?3iPZi~KD9l#!cEdD{B5CU)R6 zOgsLWCDCsyv#&-u7nnTiy~sfP=!CC^2kI++c#jl_mU|wi8#(8|+UPd!t&B>pToJohMhaa=HD(3v}5#U&z5`s3AwkBbKAQdlxvOfgqS=qcAEE3{iv$s zee4MKJU_wxD9QWBf_l+^yYj7P_^B^(8^+(aKdHxM1fHFxkBjY_=oj#`8JB4DoN*U? zBV2rIw6F2}K{xy*xVBE}gO?O8@f@MPJ@~(~Lw*0#8;ED?X!Bfr5j#g5QVV^LnZ%(2 zzXpDo>8FuD&hJ@|!o%`M{K&FUyBq#@{&s#D^dtIbuU*~tNA9w&+UQdv_v0~g?rAbF z-+L)<^Jnzy(|-6CcvzlEeFouwf@^Ut!=F;Pv{jmk_UG^y#m@r_KkNIaPc`#i`1 zM?0+-`H3O&Yn$@oU-~)bE9ABLtQS5EpNecFZ~XgRqTlcHu=gI&`x1{l{3!TTlN<3W`aGnG!{|E@XtS;{FOw;Va`JYfmG2CnUERN;5RWeje_ zz_^ba`vdob;2Dz}?-5JDcR5^dhm?g&TuaAr-V}W|t`}cuZ3n6E0QTCC2p^Y(55cFw zlcvAMKKd~H2>2qC8~fxV@Ktc_I<mk)`}T_%1Ra(5w%+-n!YFxTTza>`XseFJ}-w1+KMg z8Ga5tY(5kFHFyTD?GLoQ#PdAxu>LCgo$#d!mwFD)jYJm1=kd4m*5YP8{dZ{dv)dkh z*jbI77S92A7OsuUL-18_mQ&64B9@mkZi*kn@IiQW43BOO&R5PKd2jd}eZM6R&%wju zDdi;LH^2kyBpJW_Ycwfd;+8?~LB)>n9J~nE&dn6y&%?ELE5SFzKPCm%^VfSU+sl9W zYw$x&ZoGFo_A=MG$LQ^zfbR?si-Y)|f=`5N=V>$WNpOxeHU0Bm3*h>fgYN~`+PeV% z2wai7>|0N1XgV}J7WJ52x1^>Rh(mw=y+zSb{N@KfO0byo&{xTX9Yyc4dS z6DYtt;97qv!Q0_nZa3p=yqB#CKh$DBwwdc2xE8+zd=8vr@=g2R>w?|(OTp*D)%wE^ zhPRpe-sObX{&1;ZSpG^sE5HwdGc7dBmwq-o*q_VDoq=3f9K}uzelk38z3)9k;y*>< z_1E@4w?w|K*pYnbf?s9f-S98NwRrZySHX8T>tj5}F#!JxTx;(k`1$a&P5r3%LO}6v z7=AZg%hwV3I{1O6KJk>GWt7W%$GxBl?W@Q<7N-Zp{Tp55>_EW8gM&D2KU zYw8>C7aoAWiGIL8e;=|-{QF!aGW8hZ<1o*xUeugts6*>a|4l2GdoNzulm9%G%j&oM zR1yD2urKwKoM?=fXEghJ`(N0Hom(4iVZLtg=!h#II$iMf$JIvfHuWVR@9+!ZcPXa_ zxs{Z|^3Sl-Jm;T<{{$YGKm6-#SvNWy*nEp}X3M(ag)cPgS$}`g0m1#QGWLFoy|BCy zdui-d=ha5H%09xahCO-y>KL9|l>Gq93+kf_-c4qdr3YdI0)8}u8nTl5kKENrx~Z_dxgG38l25jWgn)N z(WCjJ{%Jh1ANwo&pr_VC-zy_!=EQz?Z8Rcr*l5_7Hs9XNn>2PNoEAP$ik)6~48GjV zD~V-qvmHflgz^@iUUR>Dr(M>|E|XqH#R-rDo@xL4pe!?n0OTe)8d*YYpRK>0j= zyto7P-ofx=-gT|3oNIT;O}J{u*2i~f^ov2{SN7E0_uDxmXE)nH;^gnU$Q;l|xfSGg z=I{Fdq#gSCeG|WjtusV#5Izi_P*>t#iC5xe-q*nIYxvvgA5-osFJ2;-M(*IVYwmm8 zoGZr2-P(+6```F(;JNzw!Y+71iJR1;8@>P@ww@3_hVf%DT>6XiKEn^=`bO;Jv9l04 zt^JDdKKRd(ZH`mkfjrT#z~4{5=`y)-zsq@r_Zq{$VDjifHxQy9hcAa~>$)U-1^mo_ zes@E^2mT0L+ds*|2jSW|%{;sY*RFSp@Gj;NZ62+_JK$4I|BU?;=YQ=y?(?vAl<_ow zDsut$-SPRlvzqxHvcDqn?8V;P^TXRi@}h>l^Wbh?oM_k^lNUqSIUTvM`BBOlhA)9L zj2L-wLZe+q;CH~axV3YkdJ|l0w=Q@N9@g#>m!WQ+zl3{nSvYQ7a@c!$v7Uzo_`VnD zd0v7)3fJmeg})8g@+|gu*2hc2=NE}*0{-JO!{=4uDfrFsukv@ZA9@q1@C-bP{VtRH z{ZQJydRinh1@5-{MQ1kSHKyGMu`>xdt=-G;I9!WE4c-k8Yd7(;?N#al*W%O(f62nr z@F^GS*8#ooUEtby)(?-vHU9_U-S7ow9HU-`7XQoe0r=h~_l6^PJywI?Y$?C(AIyhv zZM^A(N0#dL)9@%2`6gYY?U&A&4IJ7?(nHTX4fZdVw2>Rm*M z{kGRQ-->-Lex2|%T&rIiz8JnBV87Wuz3_E#?R-l={1@<-<#)oT!ZrWX@PpvmK1DD5RJio>#yH{kafyFF{3Ht>gdcCQUxt6l zqF;meT6o(VyqDTyzZ3p#_yW^^qyMGhzlUr40KM=>Ec*TMXs@n62!9p*69eVXZOm(B z_%!sx){he38hj(`_^|UNG7h)>llA3K$Bg6N{(!$*=3UoyA@`|!_3PJecnAD5rk~4P zH{Efl4?fqz2jGk0TAmNVSHQ#eo28z^@c)5p`&}dOtKr&yV0(?{<1M@kUbOIT_+|_5 zgGcVu%O8MGfouCsL-1*EZJZj0$Kh9)@%Jx4Bt9eXl@|T>ZNvxO8_@S|7>RxteAr^Y z8-C~p-TyxLZ1{?Rec8SC@@oLT7Owd}1b6P&`7rz(xE8+=_<0uIzMcHD@GkgL3-5+s z0{>~Ce(M|c>x0K0(D?v-t%VQ4XZ}pTE*XX&3_m4MzW0I>xBcP0@WV{*U!MwZ{}=lW zaIOD#!S97@<4iYv2)?Ij-*`VtpRYgH?DxTQ=xclc{(zgU>q;RnOF z2K2oHE8_nMJo?a>^JLL{qkp!)MfBXPDeS$LH=Z!AtN%+2?JvpX~7- z5OrfLYGTJ3;dukf;W6T-+!s9&;c@s4iXT!=KEr#txX%B)>?c2TLi4&+%9`VqC2}R? zHgf&FR||6M4LRBS^uNg?ay8^0=lar>`@SyMem?JM<2uciyFr&rA~(o--<7*cmy7*} z^C7G&FUN;QykyVPkE#4D{`F(;ZRFnKZzmPB7k$l(o5&3z_cZI!2c*6;gL19woBQTj z%3XL#_i2aewwHNl;P}<`tAt!+8TZ}I_V)LnT4#IhAnjR0Zr{G} z@`Sg&&AAQuy<)gtUi2q!#l)XZ_}lQ8Ozy3ZH`WtN>~teH_~qK@e@waPo34oPKKLre zC+#|D0KRm2&HcVY(+_XMM8>4{3)o+R-zxE~QtP^}5}TvFbCmw=Pd7eQ?9E}ImxjA>`TKF!xJY?UBpMmX>i)#xQ!M@@;Y+_7evU`% z_rU+nJSu-T;`Mni=JHz>z74L8b9wkjDgPs;{z6Y*@-coPxkmZR=pW7=W9oap*GD8@ zQpl~l+Kb;Booqc+M3#U_{BJSRB* zW|3P${k8Va!w{am9zr{H_u5UwwNX5iPr19>m~?}yF)Cvr9FGx=M!(QfJ2Hy+!p zkIWM%c;lwXwO>S=_H#~M<{eW`V!W_9?QhBN_MO`3jv}8in~ekF@7-Yc%rU0Q=d2aqNSQacl(s$aia_e@3>M4==d|i9damv+`!n)rmim zU^%S^H|MV;4`Td=>pX^I!;W_lK>X-|@5yys*nW_dlZ8)!2kt*fo&9(5iCM8zK<;ph zof3Tde_^MF+y%%5=6V06#?o%R7jqvGewoz!!>MNeg}m=V{Nmu^8iu%e`SJLU^b`8gxcduY+sX z>3R4a7X2c8HT-z9J&pInRN#-prLQ&e$vEfY>=ccZ;FC=5y=K*Y-%9o}*4c2ky?%Q1 zxbaV8Z^Ezi@_OOBzz;CX^N!iN`PmPTd{>Y6Abg~#$Ghy8uf@9tuc5ESyNwT#y$aX# zJK@7{E#7JPuD1HaC&9IN*S^HK19#(n@=@c)yNJEiqk23l@RQ(LeVkpQktAGek2qZP zwfsrK-?sFR9{9oNf5>ca*Z2{tm(i;97f?eSK|Ts|Md-vELSpMs9~| z_3eb;3D@>L)A03htvz~ueJ$So@L@~&gYcK(VexjyfA~hlKX?59GS3ge-SPhuhd0|J zWc(NTEb^~B?#rJ$zWgBaBfs|LkG0FYU$;_>~-VlVaEn)*GmJbWemP;58m zFXP;L5uS(dZgS%sZ3VvC!kyisk*ndSnfk^)YaIS7_@V$m%Uvf+Jd*HtKdJK`_~$G< z3%?n@mucU4k8>XW9k@1r72#jE*ss8!frqWX#eZjFG%^I=!z}-J?|MUc9DX;v%jCxS zu_XLSxRx(H@R#9X`6BkS@Csb>FAsmp!i(?+;F|vx_uG>;h3Vyy)j>IVgKNYU^qa6HJi+%zAO^bdB{=9`(;nSYh z;~0BSG%^{kwNnD#3D^8j!TT)w8TcAY`8oJ1i~Rz86I{E_F2O(ijDD`A3h#hx^^3Jd zBXi(do+aS3Ecz*UH(blJjBkIuJnKj9W{aIccn&_Eonho&Mov5DGXnpcg}1*q8hOLw zM;Bb|2gU`j-}rCq@%l{N$)oya?CUQ+fCk7G8uu4gav&f4#>*++HjuiZ|+)CuGlppH%yrSNnF5zYPR=BpF zsKLwdLjwC*GaCC@ZF@!|uPxd(`n`aC?_<emZ@5U$m)A6|xQ?KcR282;~o|FuT^%kY~rw6Do8aj}~}HTb>oE|VMU`L=e( zNw~Iu&Ed?*@u6uH@^oVT2E$M-mVD?Bh?8`lL% z_}g%8eC>hHq8{4*UKTEKIKeF6_|9P-z63r$z?<)1EW+=AYy069_)V7bojCgv@K2le zFY_WK@rlD{Q9o@xl7uJVVe4Aa?}6_NKghIiyw5fZ@3Pp>`}&&wB0P?M*!dtSzXBKk zH2<9sv+rZ!ak$)%)5=f6BNqK0c$GZW%Fn`2qCaW&^Y9Zaya=Cb;T8BC3wQQmJ&S*L zo9z?*k(&T+`@>&>YyKtSTP(asIOCIAfA~hYW5xyC&wmS^}z47@GN|- zrTjenW{Z9ievO4!;FnnJJNvOOW8rc5Vhc~g&$I9z_&IPbzq0T*E&6$Q&BBZD^{gwk z_*dWqaJBvSXa2MBIJ_UO{s9s3wJ)wJ`wiU1=c^_p=5Xc1HT6SdjtF@jrCCyegWqncQm=b z7v-*h;StOHo0ak{{^j9sT6hs&gCA&?@4qL@UH`%-Q2yyAkDlD{- zFFbn-&so6V-^#Vp{ajSl_c+||+PA)&CoRt6RZ1_&2C`gt4I;ncQubF{kY8)ab8XwY z*gH4uUY{Yi)0ei5UMg~{#>k!T$%+4Y{F}dQ+vpVjZj|l0?_Qr3;U~evu8-aNOZ_a| zIe_!^@HwV^e=|hm36ygnn*sH9Y`!1sx2+u$yE&5H>;1FD{iij? z+p^B!*I#=7{MGyCarYly-rq45*qSE|P;KpU8?KY`hA40OHQPofJCx^ymiI}@6U#q# zokU04tN*}g574a(pUj$!CKWON;Ug17qAv^_tat-ZIJ~#PqTo;6A;LC5? zHaf&`(B${I4=M=H!T0>Gp2r3FPVgkM4Sj$AO!Bk@PrxrSx$Gx-k0!~lZhULVU1}+( zt&{bdrJPRqHRF^c{tV^$zC3d0QD5f}HXZBjB+qA@<~^Sw_0D2%@-2G5$iv&VztKB=52gIB89Wzu_cr%? z2Myimt&RTF4Zj_(&C7l8wF;Lwjo{zS@Xzjme-{S*Yn|b}Z%+IuV&{ST!s8_4Me+xc z$jlAfMvF4fB!hOM>%0NzV(*{Eo0i0G`zJYl@{0ZQ6$+^p4>+7a&_<>J^kEar! zKKNpI*G@)!-Tm3t={p&DmPhW&joZ}cw2SZ?;M)4Q0$&c-)<@2#xc-8N#aH~y{xA|* zJy;ukpXA}?+&negaThNSMXrF{N}hvyL)!cNF>-(L+FRCBW#s1Z{L5`J9(~b}^Tvul z(&eNj@)82c!#w`Q6#v}(hwlW})(sW-G`QqK!*^rd;2g~Q39iL24xeo)KM6n7QhpD7 zzNP#uJO`J$H2gE356#1`hHKYPMfmMJAGD9Df2Nl}UHq23i?)G3Bl*Agp3U|%^MA>N zj_J{38Rfce?0b)bB%P{QT!LBxkY(@>S~{j*O6dON|C?{^ zm~|2V{YZ=ZZ}fTZpIf}Vepv#W#O^S57yQ09x|8%5)2__Rade|6&<^MM|DMXfv-$6n zI;OX7@+NI;NPmj|i1z@$$oIl!d~Y@UleN!tG;8A&t0$jEe)dbX(F(fGYm=Mx5&0bQ z{umGTo_|7qJM#Y$`De$-e-F0|c^L=NpJtu;NALS*jePdb+x^PRN^c!7jNL^q*GA73 zzgGqA)<5JU_8cxu@B9<*D;2pfjgh<6Tj5Hcl_>Y{r^D|vi=8Tb;-7gRl$pogc-vZE zCyQL$pp8lZnl4heF=EjxG8ZOpu7YB#`DZFj_(sJueIQ%sK^zOyAnGo{&qeZl&hav zaoY#EHUI0sH}~CR&)DKQb2ye-+A8(>tAP;Aus)T$0+?aQBN~>9XyQu zlGk`{L+oE`$WxEj9X(O0Z+;ff%f4P49X8k1V)Lo`s@m&MiJwFwyKbwE{!HRBFKEwy zeT7?Y8o9N|$$0J@9F%L_vsrE*ayM`H?jJiJ4$4Kn%WBtN9=XZ?s=3!6&aPwRzSV4x z%wgOI`R%sg``W0hoSc&O%E3qANAh=L+Iz_od@3O^K{9AjVF zP~se$9gQr62lheS@nN}F31mdB6S?d-a^i0{a(mLd@_82$+7RhVn=>;`*{Vqd5Rse?R=JV0`Ln&p}w{=zIPXg55R44 z5j!d59z-r|9VPx|;CI5mV3s5P`p<65&mz~4+$;Y@c|*v>81KXU7Jr7}r&{=k_ygDc zZBMc<47d3!Ec?oGg4I+*XdnrGVT#$9&LMt^@|_Q^H0bnO?$MPSaa(S-vmE$43~Z@{`A1#{xAH=A=l12P3DP)-;y7* z8{N;%k3r;SAs5&W5xHbj&TW6>&atffM&OI#VeK#a?ME=~!uK=%Iom5kco)3K!n@&O zKWu&x{XY143YWNzu;G6C8{U0i=c$R!d2VsAo<;1)^@mnY1%9x?-S)XJ5}5&)`!~)P z^>PwNa()Vbv~p7Lx0$EHxRg_(oVVa^IXmj*^ke4*@+HiU#BC5R`4+~doX!orXAAC@ zbL(zu+(xkTl48eg|D$w2q?`fD5kK5=J`-M!$Q6;>?3d$wz>sU~ws_-oj`D2vigCbF z>Lv4u^ZQ+!_3CZrgIj;(D)sX2G33USH$r*O`Erf^=F5nkKJ1k1rp_@3Bq_-(vbvJ5{E9+n^C zZw=l7*Veslb2#@54_o(&ekZ&S{w1^gs23FBY4|3%=3g)TX$$X%KLMX++V|&3u|Ehe z!S^@$In8mY41W&3m&xZhc?~Z9ooVu@cQ9P+w;jW}qO3nh)Cu1OuGKFMci>uld*M^y zT73KAC%}2FOtXFci&(e*@H;H!m*HzIyapeDYw>MMaoz;3#kUiFCtQnf8ZQ1V2>5Tj z{|vqrzPrhd=fL{m&%<{$x&M9|xBl?Q;nPj-zpqgGTj$Stz8~)1fBf?<&2b{+{XJsO zIhOPDo5G)mkZ~Z3y)L-)C+7!-y)olS3Om!0)AkwVl}@wapT|z4-$t9?W5~gm!L_&) z;2HQNQ~y{much9J2bnM7?sND18-6P9HRwiu$?vy~enQ5j-QFo*|F(}5Cvi&5<$Cxz zeOyYx`{AdFLSr56bv*H}M0p$Gu78j2+-w)czY*js&-?NZjxV2hi0k4PwvF;yW9~Z} z^7V0cD%Y&hq8l)&&j|hw4eRHN+mGXUNBAj$`gjAa=y$>QeNlg|q8q*+{DY?cDa~=H z&*vwZ+<*V4#A}55EI{AQK8LyB$cH95qNaT)}{Pz5#A@9d`Yh0Ly?Xgu2GK#w)c@cj@#btk8q9m zXXYWkN!m;S7RqcBZKg;an+jMX-qAi|{cTUP5B$H|Lcd?-j(_k8Rehb=4UfW)H`~K_-ntLo3E$J?#yWNY z-l1@rmxti{!n;jvo{=}t|5qd#xV zgU(6J>;KU8K2BeUyZN=B;cv(~%dP)>=B+pMc`Xh<1Kwr&<3BGfeIQSH zeQG3I09Zt z=6=nX19$8BN<^(^8awNe)9Tp^e*~`8vmgEzT&w3Gyb9OqS%$v^XE|Z?_n}6AufbRR z({lZL3jV>v?x#z>biyBppBJ$2Z43%e!zb0o?7uQD%PlP7z3`cEt$zLRkHWS7F$j-a z^vm!);2$;p>uHWhHTYEcqb863q7k3AQ<7{rcfYVqY6C2jMf|+IU=sUyc0(O#h7WxCXxo-eGe8jG*}6*3I=hT-!hDgy-Rh znEIDA`!^@ z+^}7L?@$r`GW?7{oV<+&i9-ec!GG!Ft+RmpZ}32WlbcuQil5o1Ip+ZXIDb348-DuV z`sQbMotMJS!N_UjS_Yo5@Em-K#gEuCk;tsNAK&NWHT8In@uQ5Lqb%jr;5I+o&P4zD znwnRg@VRg;Z_>WL*1vk;bI{lFsvlmUJ+-`P+sOO=;j%yMeD}>}9Nc@H-f3?)|FN?b zIc*#tf&W=4NA%kla-JD}m^5%b)-s6;@3y=@Z-gydVP)S)dc(mxHj&l;3vVu z@?YXndN$(brMthg10Ub2mr>tO`*BBLKWzYe*T1RH<3sSZaLu1#`0a2l9wYEu;1aur zFUI+b_8!JR_yUv5_4Sx>I*D8vxf!OMe|}kf>w&)lKg;A|$DdQ=XYnD2+&=#f_eXdE zJ`Jv|8%yvui+&Y85q`21SdV=)?IxkvkDX0^!4Eb0mzw#WfG@I?pMsxkv7dq8V6mTr zueaDQz}LdX*M|Rod&zGl_|0&wy{qsw7X8>ctgGPfGwu6(DPlhX&sprJ;43XW1788x z#=RVTxxyun3h>L}3rzn)^0AEEJr+M|@O5zQ+(X+JnAa69e)RvIefDQLx5?km@q9$H zkxTwX2ER+Zy0P;Lav$UGhK%=l7?=0K4^_$${Q>xX3Ku`xpNmBHfV+PDmXDe$epIkC zA34nrXA#%s_^HJs4)0dD_>sqtqw4WETK6M^oog)d$iZJ?oY4Fzz@JdK_>o{CbuZkF z$FKOvtrCwKcHTrzi$~kJ>}x7|It{;c#e)M5ys-;~9;2m&n{vLu$ zerS9cF5~Ih_}q+zx3MMl7=dTtVe^&n_Vd^mve@r}pJL(N@RKa%_rV90@})gTUf_H% z{8Rkx{D+TL*V}W<`HLcUzK7f*2NL1S@<-I{XBfGg%{z=Eag|=m%+7lkCWk?7(8&j96hWtFUH|H_+BkW zd|M~GhgKwhN%+_QPmg~Od?S2sGrq=sy)3*8KiK5PbFX>$tMCOTH@-Jrgm;YS}z!1sXvBH({>KQ0U3VA0RRAA*OqpY)UXOOeQr;A{BX zdA{20Co(s#YOY_Z*xBoCecvv&I2!o^JggjP=LGyDxRxg=cprS1K%VT-$de5GoKf9= z4xWZ<{kQ-hfNT3&CHRlv+Wb+4ud(RIE{H~cXwgr=`{9~@Dflq_ra(L2*yu+Y_(_rN zqf5tzo|e-?wGEx<0PL_k@RyLy||aC7dUQFE{Ob z*OW`WEb`VhoyaXjZVyxL_-3A^;qxuL7d{uR#jzj08m_I=2jNe{#plL&Z`^+?!^?1O zys5!AS@hd3WIlkuJCMgaHS)L<{&;kI=>C?pQyN}@YkAlUe;Tf>)BE91!1pohcV;ub zgTB7T%kWL;M@|3z56FpsHTZ_s?P@=7Tgr7KT-)F8gue#A$Mny5UM>yKI@{H8q8ENA zT$?ZZ;dj8b_8au|wfUk9FQUI7;9v9nSq<*&pxbY|i18k-+3$o;g=_ZH@C9&foa}|K zglqZH4_|62e-NI7Yxj@J@L$5i&KF9bNmn9~H{o4T=8Gq{H0KMqueVN@Czm8o+Itxf zcGCM<7yPe$N9SlW&dfRTN&?aEhEL?XIkNxL=%>c_Ci~z|?-*VW@pA+}ccT2G#Lq+C z;b&Lf&mwkaQjXSNEAX9m*{+Vu&c)n!gikg7G{)t)&$V$m3EztTC8oar(O`)~5B$(~ z>Em)1J{=x5E{lF1em3>f;#`EUf(OR!sJC$;`W5(Q{L`)zoJ+Xwf*%v`-+Oth=*QtZ z<6l@l2~WbMe*2pG{<$0BJ@6yoTE1uD2g0@fmWQX{TD}+ISHZ*llRQfPmG{xW-F)Av zqUL+-QqJGJTOZdF@CCc-{W=9-3D?H83_J_h#{C?8Ib0jp3%pA#Ma4ioC@Im;3fPc+#y#%kp z)%wFXP1M^r_9dQ2*(?%!@>*j zIPV$N=G_u}16-STs_>WKT7JfsvA(vHpMc*ESL+Xd7@joi@4uf$;*)__;MzElgFgii zyZ(@VT!8-^-e=nP)~AgpyrrBna+4$4iX1Fo%K+b$>0@Gw8bekXj8_nm6vbs8@1 z72@U|~A&chd)dFDT)>9#+7EnLgvH2hk)=3g)T zD;C}lUkcay*&sXz*ZeEPpM-1v)!_GA%5Pg9jofA7o$#CCnty5d2KZ;q`1y|zyZH|v zhHLXgKYWvg55k|e@G|@f3$MY8aIJs0eTC;e;o3OX2^asaH?OZ+ztOlpOv8_8v$Q{a zCOoYEa-XpF5AL_a&%nO3;t$RBO8p%5@orHPUH3jh5qoF8ce{GttOD3EUE_|UGFYkILF42;DRIxL2^7hbkVPYqC1xNbedH!z1$(vu+cvs*4{s(eDM=mTL zVkZs1>%XwmhupsJ*V|)a2&*Klqh!Z6C4iD)#v-yc2#K zT)PjQhOdT)#oMhv{Cap;ySnvmYm$T)Pe^!*7Onn)UZS&*P34HTd0dZGLFW zdivV+Vki72^!GRI8_!>+;kUyz{a*O@;cETi*ID=={L2cL@w0OqYfbotG9G+wQ?p;x z$Ir8xw9e<{ThEa`jIz& zTwd=XZu=uQPqE{U|M+t#-1UDq!=DiU#afv-`@5uSsuglo@_6@0E;UzXsLdH=O#?RH(UpMbvt|DS;W{SBUiFT;PW{W3oPLO_3ELq7+91pO-l z+&ge5aXdS;1&Ek*wi=fqgLT>!?k`AyN2r~@{ixHj)5;B(;Gyqkj0gKP6{23}$u z)$%U~Pol5Qn+5nR`2J@58uM-mp0emy;YY&5>M!$7W`y^kz}Ftt*Kg@imjqiE*v&wwwj?e#zL>_^=>)_*pewgdvDt0a-{#t&- zuI0KLevTPmEC{3!Tb8y`#X)#$7JAHE(Q zwofkoH@1rL1FntF33wOdlh*%I@D9uPoq=cITK~zxm%_F7Dfs%@I;I4_5`AratHS%? z+V~c`jy!~G{VxF@f@}RR1%KS4pMn1puJym_Xe4qs-0gqgD~;R#+9NHI8uNj>ZvD0) zKc@dxD0j|>^m*I4o^cbd#XSz64cFQ|2|oxv)9g3iwC-MS^uSYat$%0X3*cJZ^YCuC z7WX22k)ki-TC$}j(gSzndfjivjcYIRx5xdse$9{{6W6Y9^1i+g>v8LbZ-;C7-skH} z-)mei80UEh;BTVeXY#1`AdTn@!K?S_^U*N;4Y<~>Bk;C;bpP6K;JgSttleeY9pFYw z4E`*CJ70OC8CT*I{k3<+BYyT^C#(1=b}HCegB^Ju%Q88GLp?sHj=^!Z z^>YpcInAFT>}-a+@%hK&!8jZKWU;gAqq;xN4lR*>xa-gTW9%6Il(4hse)>34h3^5M zP1`p5oAI1ehH_@YKLd8o3YOz9qrLYtA~z2?nTMRu7;^qI4`N>Or~5|E&szNHgP&sY zXM}S4>i+!Uu|WJxf8rB}Pu-vU47oA>R4H#Qa$)n2_#0bIo?3VUz8tPy-=^S8;KxY- z>if*mIgRU^4Ez?jc72e8-wD^QKMU{zT$=|<@cS&~SK(XW+B_8db~N&D_)!7>Kilv> z0iU+NzR!|^pAOgJlY!5JYw^j!SHRW!!>@#^^@m?;v0sG`!PWY&;r=UJtv~!tc-Xiq z`ICab4Zl1PKkva{;TibJ3H`oo4t@z-JLgh>-vYlXVBfp3B=$>i=VRgi$#`9b?*c#B z)R(#HIB$-TpGB_if4I&??%QMKt_{j{A$KQoHB-*p@7r3J6nj0$UDCmN;+=Ah9xDFl zkSigl&DRC^qwp@%j<+0e$D0y-GyEBo`wxh*CT;( zb8*MSFLy+|Jr_}zxH#Y8x@Ni_mpFU|T&s5y9=Grw_#}({EIbC+`c>Z7e~&m^A6NZ% z&P&{i@CoQwO)h!8xt@hyURRNO0=e_PjkN$Z5Cym^V$Z6wKdAF8G9`24$A9`@y@hOkJ*gbk&itq_= zt=<)Qjq)_^+`_y8*V;7>ABJn=Q_|NDi>u^ekI!x6ljK(pxwXt+TE8y9pMYzAl;BUp zwe?38zCZJVmY=cjvkwB-)*lJ@Qn-*fO5+HnoBX!O^p_W=Qk zPXRuF{jheFIG5ljqtE4ZQ(yY=o56XYhTK7X&uF~<-oBRm@RXHhs9g!*9CtP9+vlR{e2!b zo(S)QKY_kBj|{*chmSYj6p@qlLkBh+d1I`Hl5H)KJ>l+n^PBs}9dFw5TxTG!wR!dc!|EsFN&D^5$lmCWmw!p*&PGnl zzv3P(kzTl)e`nn{ZvORSZy0$kE`xAcKWgJ!TWmPTK;tTJS>0Q z@elqH^tCwl!9NBM%Nx-jfOlESAA%nO*XlP6|AeLdk#X#||B!RGKhoQ$3%(Mr)vw#v z*W%X)|AQqD2jIW6dxA73}QtY`gaO5|seD!;#p4L*YX@%lykJ)8%`j@B=_;Geem(G5?)1M!G9-z(GypAQckAEllH@T9_J zyl9WNxc<50#bI}jJ6=?=_Y(HB@iR8aJ|J8hKNIky7+^k`Iz}Vjodxh z(ek?&J`DdkHkE#$)LEA7#KFW;r6y|i($ z3%(tFZGF%UpN77c-+l01Eqnkj{)N?3{2PMT;M#mW4F8Koe+2$VxK_XR`^X2lHlKIF zx5C5bE$N>_A8Coa3U~YG`rF6tpE>Nw`bF!X1^6v+t$&u_+Zlhgcva!A!583LGw+(u z&&M_}-dX0S1bhlyYwr|%4qR*R419*dC0^BiTO!loZoIC$ZQOVbVee_=wRjD~%Wy4T zBk+%YN{?6j{d{j1uH{D;d=gx%Z#VqynL6)-zXIRQY!C0ajJsYKfWH9O>Nf;`5w5lO zF#I`-{So-?jQ5&;`vY9>z%~E6;9s+p-wnUgQhp!&LW}+YJY&%xf_Gc^Fgyj<;x_`H zXVGu}Su`@sqTdBi!l#(+XS^r98$KKU5tI8z4`lr6gU^9$`7;2Y0pH)$_s{#weAJ$3 zaqZv5-_8YVoBhQ*Gx0r{P^6p+b{@6(=?t-7YVk7;FIoId!Z%p_EaIowcm4eH_f=SCy23To$=0hv?XOt}nt*f`|Fx zwm*EH!o^SLLGlp3g1;N{g2c@`x+TB5ekPDxi(H%hP{020&rV4>Dfnu*w%?P1m*B^k z`o?}j4*sS^zX1POmmY@_d;wgGLlu6C!X*x|hqz9JuQ2@!i9;uH&Taa*nTEfe*Uv%p z!uLd9yKmVKPbq#%oCo1Yz_od)49{8otHIkW`fU$${RG#>wN7{hevla_|9t`y$3Y&% z--q(u=Mr|ix!K=|rTIKHe&cpu$e>lK@*5F0>LzZ#60{@j|oOXWc>5rEO3FKz5Z=mHt3O)_4 z2^?j`uAEOD>GKVpe{ti*XQOWYIi1L0afPr+we%Fn>} zv6P>KPqpY5;JaFQ2|hx6w05n+x5G96W52cQC*Y#5*-yb=gNKdN($1w%w?ro4znc#i zels*5B>(!cBmF&a{~(%l+ga?iF~GcBxARHe&M2Y2;J;lgxh> z{Vw?R7TyhC4xbaS?{yNXM<4tS_^~FJe&pZtm!BmbdE}n7lv9Kc!L{{f1-=!YG|TbN zkcc17Q|xojvil)&3FHnyj>qns^N0Amz1i=@-!yVNAEv)Yp%=aou3caE!xvciAbb(y z^yQS*n8*Ch8Y#aFFT%Avt-&9(@V2Mf&x32%lb!IFh=aC1PQ$mtwe@i?{ATQH`||zp zf3klN$baH2O(yLy2ybV+WEySOAKv=$`e^Cp%`kHRgC9RYtQjY7lTYF_0)IEx&00C_ z&v3m5pFFmlU4!K$k$aAE!uBPloF4deOM7PF9dPY>EDxV%;YIi!aBWMx+Ewev1^8tAc$e9p#y(65?!eXcpZHba817#KF6Zp56@Wi2jNRC`ek^(MZX5W$)ex( zJLVIMekc49i+&njvFP{0Ux8m}=5f@!@Rs=Z!@FjW*-vA9lcRgW2jO$!+PqzcFSqa- ze4T~2ZDM@4@J{%ypViAx!w`q?0S2tLV-pYfi( zGJG9;cat0E_-gQ5;B!qL^$v@=`Tu*?8}Rp<+&i}Fu17lIMY#5!y)^s@`0=K`@g31# z_z3)z0RLQL-PI4DanAP9i6-}!Wp4R{@O|J1o7{NMTNyqJzQE+h_p)m674X1*XY|BI z`EAcJ|HHo&(Dz<+FY)PwuOol=HThYty6ayWelNV+!bQvI5@=eq*4#>l^yc z^PH1}e>cF_G7-T_FdZx3ABGi=`>39lSYebFDG!JY4Z zwOQXexz?+k)*tTNF^gx`mvziKyCc&2-e||H^E)EZ&vwjO$bYstt{ZOLOO&(n^Wop^ zk@+Jvhy4k7p1++fMme&Ey~(p9a=pl<=KFF_h0963x?W(v1i8ih-RQ^up-17}@I6l6 zK6-wDdk2uEoMFm23w|wsJC}_q=c=YZ&M_^K$C0~EGs^8lZkJQHkN!;T?QO`(_qo?K%grPAUF2MQyBTs4SHoTj zxoEd=XXK5)+4<&sm84@$?;{~0GXNPnGmMWFw;-sSaIk?Y6KAFy+~ zX-E3YK(N0IA$JP?Xzei!Ps6o!(g^$rxYl3VU*>%n!+--2s-a(g1hy7ak;g=;*axZ=AGW~_z920UxA0+Uvb;t z=O+dH^&Z9&e~S1s^Aj2K29R^GEd4@D=E5*H69hi{WA8y!87T_344jxgY2LFE`sy z#=vL2yq0o?#E-9pj~~K^;cf7+elKzE{#;AsaQH?kXOU4({rR(^R~Fb^Hzxileh2*1W;xz)lMJ|Y+2!hXVkA(ujK(|;k?i(JQ*_Hrdo1IVpJE^K~q z+aJCH{z=n+|4X%Q`@`43e`4}zp^>K}@cphDGd~d@*=H90_P;W&!mkSGdoOX4xOBlc zz<+LXuN{6;&m6JSgWR#%G4D}`excz<7XCl*usjw0Jp2iGk6BLijD~&@zUxwV!__$_d)o%8UU;Fp^I`R9H` zzX*Q=eq?~pZp5bofB#CoeCKcY4?iQIe@a6?4j;Kik53Z*DqQow2fh_P*|hI%x47%# zEc|7-w%?P7KMmLRn~LyFaBbaL@$D}$%a?J>KieQbOB`db@I9jM>)*voz^A~qbw~<+ zj)iC7>)>J67t)_{@GWDx`04NM)%_eq?rr+RC*+6vIK0GdF1H?KcpLek?LXJxd%}-3 z^`l2M+Pm$4IqwJ$-2W0;{wHzjKeZ*Y7~aR<&Z(CM<|pBU@F(Cagdg)x-i!VH$hU5I z!+&FctRFsuIP7Ke`OW$b!aLy~Fu8w@MdH}m&2xe96n{H^xFq0T{aH1U>qah(oV+i} zd1#E>n_hV$7q2p2uN|{rDD5)l{ctJd)=_WmK2VABo`%bFvd-ya$}_Ix`?1qbe6;o( zgm1_1u=Rt)zYMQfcn!YM!rT7N`UtM&M<@JMc-VSS;+2N~9X^l08|^Fc^6yp2&muQ` zT1(^<;_-m2%TMQSXg!zN4{H5UYa<`?*sETx@5dJ5Pg0(iFBNzR{xK=IUWT^~=jOBX zD*Gz%uzZqu#^IYRJPDV0s^dTWHTVH$`Tj~p>}TOo@++)-iIa0iOXM8t&ufHu&ZV~* zCt}(fYwmNE#__Z2`x#b__!0Yu7e|dJ;J>CGTHdAL_gQ!bemh*t>m0nGaEU`~K}+Or zxZAHUxhN2adcT%y;7;UH#OsGUNM0Fob62%q>*RL0YC>yUYsbXX*gihnyNdJjF@xTN z*LvT{cD`ZgN$z^v#Lo!Q9C z`Z?C9=b5xi9=WyO9P|Au|IN9=i|{SXe_Fd$;G5wGBiks)xL@MD?#=IE>l3L@_RN;Z ze9A|R_sK48#$Ebp#q(3-QV2}zCqJlnqa4Xm$E!2Hy7B8pZl@dd{@f2=2oGD2xbcOr zh08v-Sx(g7zw>p3`q&^oN1FXA{s!$${4O-h^Y2&6 zbyOZZSHh1FJHIgO)Z21qv;HDqMt%)>JX_>%d#8MKIq&_r*PDMt-Z`r!awp@%Wg`D| zLq2tFYtFf9hv<)y-_V>N%lO+%y$&(`^{>$+erfD&yw&eV#~St|&%I@%+fMEOWS&7z z%d0N<8*s_NM(m9J&TjataBV&u#*c}4?>?yWyCu!|`}ab{tegMXnT(va{w~6Ifotb+ zD)2UozEfjA1+J|xcxU_Af z9lXmUH+~hkw1akT#M#FD2iMv;4&P+qNx0-w*z-`*em(Flmh!W{zE*x7{-mY+BK!%s z_MB9;UTFOttZ@1|8z;CedEPT1eejdKe!i(@rEW83=YT?emxNif$ z+svQnj~eT*I6OlBhP996ToV3&=$~xr%UEK(S6=cUgIoeT+PSzK{0O+VPAb6X!?k_x z5~+W*aUCS3Ec3;q^-s;Te2PQkU` z?Q>1P5566J?SA3_eAaFHxHkkp5U$-{8HRVmwem;c^DVsnE%v|Q+PbL=z8L!01w-@aN8fg8(hohA^3kNU*p5@|5do;>j?aL;jAkf?QiDmNHAX$ z|HpnG{%G+`!SAv7n}M%|A0LR9x6vl`&B4oXEguW;&6e^@@R#6$>&|HNJa-ko>kssK zJT}5S4cF$`1pF=R2lkPS=U7wlIp}LV1HTEbwO0;)HT*C$KF0G_1^5r)rL=Gz-)UY?jUYF>;LGh3E+_3>q`XJg>G4cn&=MJf^M=8Q^C81d zJ)T>F*AH!@oWESJ$FmbY8-Au4kEnOURs2cAv+%I?72XS9ZsGm#%it#j?0cJ_qCW_~ z6RwTRWq1)Dw$Cd1HTeI*!`er9TckDeH@LQ5?}TrGYxPURUxsVf6TR?>U*A6Zok0Co zH|C9g_@n4+{c{lhd${I*+1J;`*&6&!^tJxo*3ue@{Y1Cl34aTHZ67=hpKa0ag-?fT z`u*_B;8V@`80(5bpC?T&H?8<@X}>aj0DWzIs=;rE-(%|g2in~BkG4h*zB~MVhr&DI z3*b{sedE11Y53`IZM^A)&x338Xg@rqa2Y?^*it$QF4tSm^=u~8_bvQ)P>5UN=P-8C z$Z2sH@%_9|6zVpNbJ*?df~>dbcflWkhqZ(F*$saQ9UVcDb@8ei`>5Vc>8Wm zKW=RFhdg{OT-!G+!ta2G`5|$rz)SEhDX?Bo(4##E%5!#`uq1DrJrQsuftC^`IzfxS%(ymo3>&5=o_Y- zxej^R8v_N4{4nwrK+NWj;^wRtB6zaFlQ>lyfSa4n8G_&E>g*GmQX ze7M$*CHNe;){a&9Jh)bVY$wJmxa4GGoG|t?6Yv+{+Ps{CSK(7leWM>|e6IDQ9Q=fz z>HW9>e-N%+FP7ksS$GxxG+c{MZ0FXXjwGy)w{5AN2X8pa#0Nimt z1CI{r&#C6%9dOOR0=yHht-DITe%Lx*{HwzEL_ds6Kg=v^iA;c>%iqpf+{CWW6;b~X zE5D1K&Rtp~MOPPWUq>H@+{Lf^V_d&%j@Xhs8_E&%vLB zYx7$H{xDoS=T(AlweTu@w@38geA4%gN(3HW4q*g8i1Pr>7gzO-YBqtR30vt+#a z+DU!@`f~YP&D|wuRKL9_~Vz+Y zYwMY`&$V&17k)AN+VyNdd=IwM+x+cZaC{(+ zVej9Hzn68y6Z-ewlJGaNS2g{W_TTJ{b@H>cO9r_i>}YYx!SA#10{m_ZFTvNrKW+Nq zKQ|!dSK%eN)^4#qJg%)n6Y$7y!ux^PPr={7zBYen;1!F1Id}{9wfGd^BNqQlKG*!O z!lzsOkG+rm1-Rya0^SDK;+ujW06)QuzkhhyZGU(VT+7=W{B(s&|1ZGj!%KRr{Q;6crSc4{8(|gK8E?{ zuce;-@Zwl5_55tGKMf)G3UVJZ?HJ#K8ixNJuEl!WyVqB{rzCP6UbeS z9WCA|_&1bt-28_xgKO=PgZEnW3-E;&UV_iF*ssFpz{BPR@h|oPPruEKgYkaz1U!lU zF(&s9b&GxqzQkfb1HS|wSmzke!{*@MgKOexI+!l);HF(wHM_W7j@>KZ! z9k+kxS|V-m5_NWtLhW`N`!`DWPyvNDiak>xwn1v6(2jSX% z)FJo-@WA;d;v-w@5}#rC6Y!6l z-wfCKV*&mme5M({i<;w23BDb^x5>R@8E*Sl;cvpV{uJB0HS#uGi*Euh`WjEc->~ou zylUY&_!fAt>3`IFk%8O(@Pjx0EA%>4cnO|>YwcHs9}3sr`xKkT`~=tHpMWogYx8Fc zei=Mr`tRTCcJm*eg@;{73(xuGYrFtognq`fZ#+j^f)B#Aai$7?0iHDVjdK&R57GW` zwf^w8;9CDm!FPG~U!!N4_M_f{)U7{!E?j#qJ_k?2wfro==fF=5*gvT;4wm36;gd}6 zKRYSqSK*hzwf+~2w?=M)|37o@9$r;(J?_uh=S&hp2p0n)4Hq#g)s$Kq5iu%aRK!%g zq+X*%OwrQRTAM1>Xt_j03>PsfXhg+`w}^-l5F=HLH;jlFZx~TADq^IHDG3_Q_g#DM zoHHjqv*GzYpFe&)kM5K6u358Y&6?|;y-zPQy?1=jZ9m!YIdGf*^5M(jarbeZf~bAP z@a+NV%i(Dat=9dKYWM)S&AxhgD*SlU{%d3XLo@uBaBKMw#=ikP8(s{z%{TIWzSzv) ze<;VTfA|*x>C1g?OJ5D2_)g;dWxUS5BjoZA`5bwUU1oD$_EyXfE$GR3*WQn39K!vo z0G;MVfP%L8}~d?DQCp9Xk!K>jW8l>t2C zm#kahHvi_ppAX;#@K@osb#e*3K7d!iH^FWGse!*6z#HI=aGQTx;Je}0`ag_uFo5U4 zlistZFMy{9@Dg}Gc&-_L#(l;L_z3uDlN--#*1+@Ow)H>*{93qeoNj^7f!pRu8Hcm~ z6_7p$UJbX|R{(z*ex_-^`TkFM8{D=JPyrwMerv}VGyQe3_E`fT3%A+d055>s`p*{l z6nKuQ-*{hEMs`@;0Jn{!Iq)R`ya4_j+%`Uxz^mcb`iH*?w~ezkKDXJ|0N);9Ukg0> z1G{}0zal;74{Ym*9Qar8V@&_~&zDO7TmYAI2gjNGpI-gRINfj$zjF%zbBJ*|o41%7 z<8=5E?>?}|RifvQ+|OQa>XCOv8vAl0SBG3Pavyb-+vMdbUyEJM$Svjm^BPmmdCCi-CEoq*grRXa}Uw`h4+VnM| zZxh_rcTTWADQ7kMc5|O|qiLVy{X(pqVrS01+~47T-g_?3IegSb?qu&d z2k}$cujx;}-reyzpQEwhc!wEK%uDi({ks^O?==fIj%(0= zHTrG);SKPI;fea6e6jC--Y46K`C|(Cx5npB9FMt#I37#p)373m*X=qI*h`0xnapJk ze?G$Zt9*MTeyY&7a6oIvO%e|m8tvKh%YhpE&o%5X`3?6ihO~CvLfTk;&vN5N{8s@# z=RiBJfv*qX4e;SZ@o${|X;J+x@QMJQF@kk2{MNYi<hyGWobyI9n{+Kp!74piLamVBF~YcrxrbPvh03pgzttgH1l!h zy5*33+ToWU+}d%!$z@;gPFF;}b>l7Tx9m$HXREI~`00nVCOjW5`P4nYIT!ebWXdy# z9}Vm5?f-J9ad$(Wr{MZYqV@jn&0C5BvQd+*lGYwt;Z z(2+*$$R}OHnAVQf5zEnJ+${Fw0x9}=>dZFF^I`{=}oBd7jm2jK=k&&EB zfZOcPf`7=qwaxxK`17PsWWUsV-LjDS7QRHr!JCXYp{<20V$b_EBRBaEtsOs;CQ@R^ zIeT1R@U_?fli&FP_B6mVC)(%FE%03UMo}28Z|`85_&eh$`e(Sc|ASw6Nn$SLEr8d< zx0w2+UoqxmB3Fvs4U_gRSB2aWm+oDz9=UD%AlHIiMbX~%WsVA~lmEDPxjf|BklWg| zybaN6bNioSvcfV94cXILGVOeY7LD>Mwhj%Nosn?JHV4n!4)S60a{G zx$M90U9JSV?Z_?ds&7%ezV=5$YSNXh?sHX<%YPdiH>E8-=E=JK3;MoAZj-5RoV**z zd9hQY$mKuAdx!qk+R?!0$YEXdZSW-B_J0ifhgY?Bd}Zo$np^?VQ-PlJzqfX@h@O@a z@pkQq=_y3d^RFk~XB9n-=vj-NfifPhi`Nt0FE(yQc#+nMl2-S8S!8*B$eZfQw{HL2 zj9k(6dzUL&&O8yhky4Ib{Fr;^7%B6=U&ivSL~h#+tsVSa3-iA&a>vBv>X37$wRVI= zZgaexWB9olxkltp6uI^Ba_0H?n&TL6rnh$7Ck5-Y&AHoku(X2)_|zF){2TUuv`u&m zym)5f{Y&wC#_^m(f}e&RQTXm%l^#|UF5!q?cd}h=iK3q_mOr(PU6j<8@To%SBspCe~~Y` z$bIZ)>-Hy=$lY*fYsU_e+tfwQe->Bt)gd=#QESIHV&7UrPRj9#XP@}Jd@T39UTU?z zx1t(86>i&CsE1F1{{~&rxG47Q75&ZdQh1{AQS2;!D&*=H9=Xo2)4Rpaw_g0^oJjwH z9^3tu0{AR=fh35==Y(kdl)%@*&k zXOe#nycT|`$^CN{GSA6*nuhgCtM|T_j}MQv8-IVm>GHmp$Vsfv7c8 z!zTE7q__Dqax&)-NpD-fl2I z%GU%R5>UR#DXb#{%9jNn9-u!DJ{Eqm=^x{KV-fsvc-(miBYw)@vjTV(yb5lufB5ro zTm3e{8{oG3i;Uy`Q9%A#@YL7r`t#s};5Pk5@R0%O%i!bTHvd(@uY@OxPwBU_p5b@U z;D6wABzst_z2jr&_cRi|mv+*Oo;#2m%I9dmg3Nh-J4!p1`5fGKUojiL20p+{Z|Kj5 zuM9|E4Bs4(z8qc;Kf%;*oTIIV?+i#^58n=t>z9rD=FM=2b&*Yf+IXH{h1<%P4Ic!z z`6nNKTtNC__^1G04j%!x*}t)UKzlv;B^7K4ld`a6WJ$zY=UQO4)&uP{}UL;kvoqx zQGa{yuZVhFW5|qZCp63c<**+p2c|2IW^n7D;J&y-<#b<$o$^gxXtf1@Jrx9c1b>s$gQ>HBX$?oh14pz+rCaT z?6%A&%8~zhi!XoZ-sNkNKe^GD?;b2K_Ldj04w_@%cdLf~41WaKX!~}mT;IC!55MV_ zR_pn;X82(C-4?~AkL~NF{XVSjgg+X`AB^hHh9Ag&+^RVKWR&N_SHt7>;hlw1UJM^T zueIahxbzQ1c{zL){OLHpBFd}bSK!Y?ap9I9UI-s(rkBMHe+zGhcb{+fPue+Qb#y@b zZ1_yl+x(Lc@3A1D{O~gP8q+@G{9!pf^H#h5YWOm^&A;{VfeY>Wo8eExZSj+KF7wUX zT08EDv+vfZ|FhvW@GWutohZ+T_xsT9|6=&*6+9nBKM{@J@S)Lt=W_V>v@cuzRl~o9 zA7bWzNvwYB;k)6s^-D866Z>rOlXf2Ke0bdY*!UffYnmVZ9H58Rf2F?>`&{^jsP z0`jkh4-3e@9zHxE|7Lgre30osFc!o%M)Z4RXtobMGJAX2?l?jWN3# zk-PHaR`=X%WM&t+_hWWdVb}0a?Cr7+UIouH?KaL|HNjtnPc*sXy_iz^#mI$>^Pk%9 z8)U%`fZO&(^5FZy_c!(Xb6L?}1Wyg%W$;jd{wny7*l#;;SqJ|H-p|bc%$Wb0;Ge;5 z_C*RgzZRfB3tk_fKM%eh&T-yYzjksg|04L~aGU?i;19uV_Eo``1f;KnFM`|r(*&Ob zxA`Y>5zi|HiO{-g%}D!eEz{U2NdB%X8L;{5oRt={i?-`OV?pPl1qooA~gcl-ZK z*jH)m@_q=%n>Y*4f{)%~e;z3hel*Nfo6K+y$4P3E8x$X-2Z_+xBQbBpMJ3G&w>ww+u}VBJ`{dMoPO_xZKA&j zer16EGWa~W&HgI*0{9DY`fFqTAAH1*cKe&)XTWXtM=s_56Wo@67Cb*7eIESe0A2(i z1OIEB{Zpd$m%-;-xXh=j;OVs2>1KMF zFTmc6BKG^>w(~|64Ix!d`zs@#$aqetb>@Xl;cLCT#GYE@w$l#Z7P%u0IkD;Gm|Pk8 zReZ&BMWl)9^5&FsBtpJ*%a`^J`jA^D=SbSpWBH1{#j$fF4d|QvO>4(JlCaY@XOXK) z>}r8G!P)+gaqk(3V?8Ziewlw{UicmTR9AocXWK-*TR+$}Y?ps-@mj+!sU!c~qFX=6 zy^q{Sq>D`HBKNjeQrAA@=6&zWU65E#+EuOCN4v1?2R6bZ@X=yuryq>_f$i`?a9h8V zIhp$ta9cl|3m+SxzYty+puZGe0k@s!sf5ph4>9fcrtNOOUF&n(ysr^HmGrr0dcVzx z|JwchFEP3CJ3g70@tig3zm2frvze{5VSh0lN=V{+p;(n|P} zfb_NSMhlm5F!%kC8qn^qCr6~k+Dqp+Xsjp2A8D6!-{2>EKbQ?44!6ZqK71V9HVziU zN5XCMwsQCl@DZjz{^GR@v9B7w0B)OiWPcD+i{T$28#$+Yth}^CNuLit>u2Vn!q1E6 z;;&-(qi}cqoo{f9zjFV?IiwDIc?;o>!foX(h3|q(-qH4XS**P6*z+^IRP1d^{h#vG zlD<9M7Jnbgc;8ARd}O4}`ka3|{5ZI6-IY0o=K#rnl4+mgZ3u}!bK$wFEg_eFtac0g z8SrIde}26EPGzi|W$0-~Zm^lp1uJkUrxt+!un|#-$v1T0r^&coN(;E|tLBh6dC>d>7nW z|L|=A=^NmU0qI-d^#SQKuHbxgK>8f`s(|zb@D%~+OW^kfq_2SA6_CCLJ|`f31H3FC zeG9xKAbrMPSuepe%=q(;@4D?f2Ryq;G)d1mxcW z&k9JNaV7J@fb===^nmmQ@D#Xh9#8_`eV~0@s(}9tKiKsDM6dlzf1UAZi06mfI+pM` zGBOg^U;D4ya_gxPJ)4;iOfdEM&((^ac6f;KezL)~cbG;Bg#~na~7sJyTZ*Bd4IXoqRSHqnEUJsY~fK7ihe0Km(yNZ3c z0GY!T^i)K{){B4SmRa;jdD`Jy(ep1;kK?^CPk3et^NfJ>x$uFytz$-9dhfucq%Va3 zD}a~6x53YdOYa?elJu4EK1po}-}fl~tc70;zu!zRez-H{2a#(+?)|;UNq%Yn;5o)Y zcE4xCM1`a<}M0A333mugR62``1)elMdI zely&*er|+U!GDS?Ut6?%?eOW{+v3mr`7Z^QdMy1iq@ICaPro1e5G|c`K%IyG?)ClR z$GmIk*VEgq&$ZQ|XDa+W(X+aXp3`G`%F$DlX|Jzp`0QS7*5}&l;iCi6H^VoP{^mG; zl)3(J*T36&-k0?5eW0TZJ1zHtDv>{r_;Tfcv3L1;aBfhSe^R=@j-tO5{!KvoO8D>l*xPq4d=31@IQ_Br{4~M`?$;Lo zdl8Oz|!U5@X;iEF_=?mc-sSn#as1*J@+&11;!dn8;*TSW~ZRs1~ z1DGe;@^6Qy!ENa?uVddnAbl=;L_qpN_~d}}rSS6t(pSRE1Jc*RZwN@=2wxeHz8zi_ zkUq1NaWf!&E__2k`a<~60qINO-v*?wgdcQ}eH~E??+v%@uQkHYhbP)El>Vad8_sRQ z3*>&n^KG#$e{au9@^R-s$Q2F?mJ@r@ zZeZP4n0VbKJR6=B!1Lk1gy%@conxguG|Hc1M=|_Zc-(z3@r!qqK~j11U*yV=v$fkA z_|@&MifzW{EVcV_&H{ROz~zDEvR@*gb*cb3z*uTlVC0JlE>3$KIQ<~0@Y zx8Sz*a}E4?xb41A1H2Y~jcK3pKC2dZ#zppVBV!ux!GX_$ zuW_NgNlo%8L(c{1vDsM#KL?)3Uy@JOu8{ik@V1WQWuA1sk&oOL9pUu_(%j@oVY#A$2Fbo7CSG-^Y9)er?y$ILVvI^G6rj_g#wM zU%+jCDua(Ys;z_LpRqi`bDx^ z=?p)@c{SQVq>%Q&{pJAXOeNaw$M6cM-IE<)Q%_XlvAHa)ZoI(Wp3`n*Ul^XKJxls*_&j(4pQG);_?_l__o+cO`P}lucb#vaSJlCjsJFO%BFV=;BZkRd`H`E1+?n!4XZewnKc!xZ+d`@W zevQ=2lK;fXI2FT(oJ+l|H|iyKHsdt$kZ63AeyJ9H_3(elcvEEP>s;?IkoEp)X!Yh6 zVu$#*g>=8gZ|nFRInzkzoe5egCWv2Z$^SLv&f;^lJg$tVrxE@mJnnpprz84grRa&= z%HR^w*uS zJi?p3%^_qYpKA2%VqRzKpX%Xh%oA+oXomkl`b7Pc=ueyDrMJyPvf;_-KMdKZAN;wy zq|b-1n94Zj}GAVzW&~(eg2cXVqY_SBYIo489R=^Gg+c1Kj49 zI(QS@=9j#mIp2RN`;ap4DB2M#gXx!lcry zaTU31d#v8Oyw5DMfOCe(O)>Qt&zEGux5E?Fx71@E{M`Uv1h2Djcl^W7mGHA=-m&}3 zn4RIFOc08r@lcJPk1kK#&fNANa@2cpH_l%$^dyLLkuOC4H^qK`QEid;`wJ;&_N`%c z;+2X0AmykQeel1_IDUfL^pv2d^eX#&p~B~h{Oz_c_!QD#gsy0RtA>~=^r!g{9UXsb{4x; zE7a|0%aOkZeYSW`3p=U;?#A=6U&PAZC7v75GaETuf7=4T3vL_7Gj8J?0NgeY$bny3 zVsEzv@JVp%{ug{H{1VeI#<}AP_-F7$^)K;L1AhyCbzFLH15J1X{Lp_SPA~CO5OGvr zINh|0^!PmH$MCE4&z>HUD@E?>tJ^x}ikvd#&ZS+(^2@7W{WaAdXGQQyaM2l!SL6I< z8GJI_Hr`ahH^bxJM<_2lM4gnk4&DsUGxhuT|c z_-44Ro#esSlYg$6-sp$xw4=7d-MHQSSSjZgm^w$yo9vZIRNmr1`qc3Vuw z99NXX?y3LKulSDt3ej6}z1@GM@L6!%e7+LC0Dd64qIMb2b=ATb!fo@yMtC)RqM6=! z?ztV_3{O;UxBeG#P8EJZTzYT9FFY4M;)cZc*TiqNY)l;k=h(E04Ei)y2GeiX${s-U z^-8YaD$u+2Uv|IMz&F9;#x?daq{<}UoNkW#6h1)ayK6s5obOYz9~xg@X^WYs%t*XH zB<0P9Z-CqCD<9qf{~NN=`f_6Pmty!KGwt$ zm)%AGJUekeBKB6nv*EUNWgUDdJkh?Mq;G-`gWK9s9y+!RX=Uclw zt?}ZZ9r-bH+7iCEQ{pMJl712Xk(pm~tni*}lYH}#>v0SFik5uC$H(@g#SbOO4==a( z_Z9Fl@ZXyG`tSdh{A%E5!?&9GnX&m=EI*NNLOwLFtz(a=&-BZe@qWp;hjxy9qWPEj zB?rC+KHb#k)wegv=X)t(WLZ|mRDLhaa)4i2ITf7&O~n&@=F&5*OSQABX{oNz1KqvavvkN zFYQ_MW-aA?>~{s1%Pl{0s~Y>@zpRD+2VVRnc$5Pl?k%)^()l z&xXGPmvTn^?BD;E_FA3csH3rOYASx1^G;009Gfpqb@hqg8j+vz5ck9B4f*FNNiKf-xoNpoSmoao7iuY*%VytlyM-q^iC z43lz{AXofoTgP^h%Q56S$Dl245un~UpZ6f=;vQq)Prm59=iqn~7O|@cJ{4~BYZ-j= z%EaS{TmF8Innrq=*GE=0#PX2%GS-9j=vjxHEk2sz-@JHY_n!Kg{ID{oY*oHqs9;xp6;bhO5q#eaqCcT zx$MrLE8!moq_6eU=a~5$_e&e$TS@=0$(;w>#w+c-@Bl|me!9(jkI5%*#p=?WLtf>@ zt=OCW2=nMw_H}4Jd<9(gyP|Pn%zKOB)o_V{C^z;&%l-7ZCinLdCI4!8J?XDCx#KN4 zq&(RJ9CgTQo^O-*%`(d4_gmp!vH6wQ(2l;0HNoS$91?JO4#{T-3lPKVyIHpaDKUAbksb8RRNr<%#{()Ees&#fQytVfT$pEPnryq?ar zl-Qb6&3&Qg+B&LC|Ap^$gG=-jz{mf)t>X)kMdm;{L<$W$FK0n<6(6s+}4j|!6(BL^@Gyxss=jhV)A$2 z8#2@=N9TN@%X?Nz&^HEsN0T<{ALD*T1-!P|K3}MTe+Dlw(;Mdy8{qqYllWYgl(z-` zE%qL1ruW~pBs^m|=gEi@+dLr$o(8w2FMtmXNM8aU20y{f-3F{97}BiO(-$@hN`De1dwSABpR){2v|_J-P5raAq*Edi46e=s{bNs~ha7 z(z><|c0^U=m-R7O$@869oR_2Tim&baMb+?9c%u2eP_P%YUGw#%}QTAtT#1#OHZRY#eVvPx0%Cp92>? zCFq#~e~HhLC;_`_8YAopEYxi0&#mB?MYsjcHrrkqpcDieEZ;dO9Zc^ctgz-|3lJG>cg z^Lyz*IQ*@)4u0-NMb^9;SElevFP_}`L9Sx6H_wdJ#LGELV)0V^6mkBxz1@|=PlhM5 zSMsTb=fnSH`a}F1-F5c-o0H|JD&*Yz_9No$3D1nRgLd@Y@@3+2QSvKA&yEJaJ%tTD zUhJJDnnW(IhH|~T_xBnUBR2=R3r+hSZ-Oj(n#u2FxU8ci%U+4|x8uD|(p?wSpr_A! zc0V=1`@`e*bHq>Q$KueP{~zqA0_3Jk{hn;(C;JM!y>saPZ3nlXDo1|V`@VgL8}g#t zu&>~0&gmj&tH%;}8$93igXr+KTI5?LG1*RjnICWtTI_rM<(NOjzD=Her+OD}aY-6! z7Y*oN|G9k~(gI%xx7}yTSjD;zUVyG>zva&_q@Hr%W4ClUXCU@p67z2^a-xU)K33avZQZ>KLJ17MDxC9i1y{`_6OD}+Bx`dpJ6=Rz6}byOW(){BwT7;QTDj{G&F zBojSV=vjkYqH$k%9ee}ac0QsB?tIba{*HGv52wbhEJ+_(!#T07iTeTJS@3!A8~Ged zAA8O`4_+9czX-k?F1n)W4L_B^cftFZ+&GtA1#f~U+Q*P~ob^jbWz&zj^Y35R#qzMs zzgy6EVnBH_p5a_WKzVcEi{P_Od!3n4e-^;i$97%alCz@LlLA3KL$1OMH2 zdtBul#{32D#?>h=#{AJGuG-OaF>2_FO>V(K^AUoCt{Ks_|Ve+J}e-P z3gP|Wr^KcAI(hL=Dg4-g^p)`Jfb_NSEdk|ggg3%%o9a;dA*MNqs)n&N_d*o$tlYBJ}J;u9$H=+W&I_JH0!!- zIXCn2zhg3tsXV{yjgX&sW2@wwF`WG#*7u`jUa+={{1LJFT_gF9+sXYH(nRxhyaNWJ zrw~2&!P#a~k=wiI>Fup7#J)1*D!%pCL$}7uIaj*oUDrACOL+^{@g9Kh?BhuZe1CYN zdAFpmfM>%K?Y9W8fsceI+CPzUHNc%?_Qbzut8*;y&qjz`J91NzqeLRHk^ z!PmfT`XkS?u7+P~>X*;_lk{2e@8GHOMduvFyY1u7i}T&qGQ$u@g;B!>QYp>D$Ht|OTauaDUw)s^H{4BU_-H`Dj=l$R# z&3v#$ZcT~)9QXxrTYE2nj|<=>@R9I*Q@?YHTc1+S3iu@W873!x=j6^P@#47_xj6y( zG{UFCk1_RJ?dgzw+TpjsuQR#i;~njnZ@vAw97lbD+`V*Tk#p9@d@uJ`7lvJh;+On7 z=96RW?WY)i0sL%H+*!xQ`xVRK^Wb?VH_q`_!&kx+t*fQoWFN`?UrSpD!ipCaUj2k0q-m!N00 zsYmMJ@lGvXeODvba(rTYB%gZtHh3cc2ycdOhs(Mk>VJPtAUy45)>#2O8~$-X{`v5Y z@Z(JV{xj&JzZl*Ox2-42;aT`;u$kUJe<1#@h93kEY8N7xbCjbR|J&BFT;ibjnpjyS zUhg;R-_OtHugq6C7fgOOf91jt39z>oJDfJwM>0=)gWBzkdFnQNt~WM{y-mpF?(yYb zwacZAa@5s7_;N4W<#Lc)@uM%d&MsGo+>Unk@x{Jpy2w2ln@4878dett)O#L0AO0J& z-i-VBMevK^iTvo6A3Fy9?A<4g{3+fJXP(yvBz~&VGs2=L7oL5zqpm>D$|00zgrTSN zeFJ^chWFwHH{m45yZ*jUw1J5o#iaja(4LMj`5Y-S;>K;$e91qtBj+{le;&7|BSL=| zt} zb6w%Rmeq}q0_0}?DzP4kj}rLb;8RRJ#`Crn@G~rSNctN1aqt0VdgI(p1AG+xOq2W1 z*hu;o_!PKpew0zqex4ce zA%>nV`BfsftusHzkn56P(HpD_0`hA@kCfjn-@2NZKaKpP-m1~lgxqi`aOYTJ+;^yl z@3Q10>6_s@;X};y#(rAbMvvRp-P!Oq(jRN4_wPK2{(N}96BGA)!i(X3;I{Tz4$p=s zT0gnvhfjpt*17fYHE>)1(G1@MPt?9ef7+YOkKjj`<@>W2&oaL(Ki*MolD~|X!=H-P zL4x<=ioQbhjXBAlUnzVz+?HQE`5gy$^V_^~uld!ZZ`R3)^Ar2?$2h74eyG@ghoP^t z4_n8hct$*AZsI=qDfarzgVH_jii^ zTKHoD=^Np9!T%nYf9zatJA5bHW`E{e+}|H(&p#L58*a0|5U$|1{7c~laGQTB;j;qt z*TPHSiQ-56(+DpMNZ$^>Dj|1KbXxu4!vKh^LS(jRP=&wKrzxBm(M0d8xr&3^i!W_sg&o@wuL zKPbSyY`xM#b1qh>#rK*Ub5(sdTxL} z54W|W7Wgi>JO*-ddos(a_7r9#GuE}R# zU&h;e47qUc=*GC%TSk6={GHveRq$PKTR&ST_QGxJnkM+KPPgliyw5oZxGk=-;LpPo z)tlI#=cl*DRS~?F^baE&^ObiF-z`5pZ$jd@5kE#wb<_!PcYpYbM`Jp|yt1~JH=c`J zHgXr9;miFYv7F@BLVo`^GqF9QrvyDe!9S3^k1+H&4blAq(UbcD`|4-e{ZZiB)trEV1^tN?-t)Jdj?~U-!NpJIeJN$~X_gK#vWNrzo?gjSrx$xWIaqD5@Jz<6L zjsRW?FaEu~omRq^z-|7kg)a)=jqrs5yd7R1z%xH&{sp&{FBiTmfEU6qJ}0sL5@(I4 zIqE#P``)W94;gVSKZFsRr&gh->|Fb}SO>ovJ_Mc7_T`U@l22Yf`-X6L9e#_EPnUIS zS|k0hFBjEgti#LEGZ`-PpU5eOo-XUu0`yEp&Q@O@5Ti{}!Z5+?oO8uO-r{h$!eC+MWtr)lb@Vnu*^ab!?=iA#&3A_Ss^G^kQ z9^6`f_+4;o`QeM;Hv3!P>jQYk$IR2=w({k`r(R&UzW{z!055?T!>#oXzXEP8Km1y_ zwfyjF;I@9N1^!t8&-f&)CS173`rgAF_$s)~zXkA5;0K!VW1PDxfp3G4Ho1R>S>me# z-VUE=a^u`p4LrBdzHV-SU)MjN{lllg6OEhFUuJyDz6|>RXyz|_n|_}vU(5Qk@=Qnl z8M!t-M~+z<>w7!*Q+7nB3-0{97`-_c+1H2V@FN0vH9Q+0XP4tG0K{+g@T=g7=B>h; z;Y9)Z)3&j{7QnONg#r2J!Ny9#9-e3)Nb)Iwf4C3%lp@z_l0BbFcp5xWK4NDr{1EtG%=Z2lL>Y;N8vi{#hllugKSL^FtZ@ebU?f5INsbBPQ?Z_yS##-FL^tv zHh1w`WCzcG{K@XOEOs50{L=RxLs2gHvh=xd&m*w3=}*@C_u zaQD5DmmB)bb6j2C8!2{VU+Ad0#e2N>o8}qmqVKHhJWc5B&lMuS>@U85h8gl*{FC)H z^MWhv{>g(cfZO7x2tE&1yd(==c%^;4l?T57ZnM7#J_~Ler^?_rz)R!G?+p|ZA64)z0s8CUNq@8F z-vl2Kz#}{HAKVtdS@1%5qV_NL<-zB|N166}j~Te@o+9{z@as+P{}`eh|8VE3Jsp$c zxOZd1Ek8UDZW~|f;J=33;;RXMU;vN&hxmsdZRT&>$IgNehuiGSgI@`^*;fR=Fd+Xj z`0oOE6?_cbW?vor0=Uh-CU_;>W?$snu(~NA|19`F19%?17;dw#2tEt`ThqVZ_NE&j zW$?vtTl=np&xYrj>HT@V#77;x8onTIU2{uxUDE{5EV0K&ydG|20hopH}g4ihM}i(U&McR7uc(R z^kq)9pIfei4~3s538MGfya}dT|M1h{wsm0>{5-hLuaWOL#}J@D3;u9`{yg|fi++ip zBKW)T>8AZ|?8KhjmvWRN_v?Qq9%n^QHT*F6-t;seH`Ag=@@awJ06)aE=aSewI-`aA z4RBkW=D@Fl+x%GozXNWI(-L^nb@n)|fVW+nIKIRW8Gm%tF1Q<~;RUgn=+Yh=(enfO zB#L+OLp!_$Zu3Ltf4%gH{2+EzV#jvUf5hj=>b+$o%o`m_Liqv!v8+M;Uw(d?I>c z@$GFkN!Ox1*?@d&toaOKh@S9BTwG;0U2j7bwHOL)ygFSv4;F<6hrXK&jJ(9i!UJaiR z$Hzy@nbFEQAh<1Va^UX<K5`?c+v}wm zJ`8TFmvZd@1vpXuT6Z;YIG0 zNm9A-llcSpVP@LPkqh4mxB0tv3jHJ8?WgaY6U(bhKV62NZ_5(vk@8f*cff7?Q+4o^ z8|~?v;7$OK{75;`Z(HAH!CM1(9(-2-FM{ucj}^yu&R?$gT8^}@rawEX7xo>`=g9Rp z$7HCJ&R6@0Tw1ZCh9M`x7kxdJ_Vij{CBq1o=W73 zJMDSPkn3VkQ9Ji51MDe-Umaji@Lv%p(RlN23%KpN z1zrKS%>y!i=KgvB&w<|ux5ZZh{BHQkX8z6z(ebqe{sP=ue)zZW!_D-@dwXi&?Qola z8{j=}vgh9d9|^bJ-_Pg>s~6$9X8y*$eGdE+xb^-wJau-LbBvDnfRMD$68IHx+kKY` z_$;`sern+5@I?Kt+y4FZw(+M0K9%&g@gsv@`wOep}aGo-FthxXoXA@N&4VJru!b z!)^U-)8F`=M!4Jm-_GgR&M~4(|CV+Y?`K8M?f?H~$aU%88pv-Ga<=+ufr}nn`^#`5 zY8TwrKjy#(&9TqZ3gAQFw)R^BKOAn$zXE;%+}6Hp;D3P^oAKdX7VTde;A`Qw`f7nc z44)X6-dk@;`^gAL)ONUSewPDp2+&^uUk|sn-xBz%@Zo0u#&cX1@OK09ukrQU%GUs2 z5s-fid{sdH8Ig#p3&=kQF8Xcx7r>VU3dp|#z7lS0Pc`tz;kNeN0GIk5XZqJU zF&ZB&@J#{fGjv342uPm;-vzggZw2uFx7c|J{5ZJH{tEagxXu0=_(ZtPKMn9gc%tX% zCB9pHesP?Cyc?Zv{3k`!U8J|ow{zgD;nwoQx591r6H4HX0lWgfC4kq!--p}UX9K(r zZi~+r_{sqN8Og*q+}3_`;H%)a_FDj#{B8AH0$&HW_0JW4{N*aS-wf$yg=f& z0WS92;-dvF^`B^blKDr;Klz;y_+xyI^el~y$KIaDy^@pUliMw##+KXdD1?uP+w3TX zkA&OoXvYrG@7nRebyhp-(DQPD9Zm3!0d_=EsjmP#%C6rq^ip1P4&>bL)vbIjey>5U9zC}9(ExurfVaS(58xTy@kap9f!Dxo?W+J@ z1-Hd-3H)KWEq*KDE8w=csexC*ZE=%R>bUy7xcO(ymtEqw9X*H7v+w6-rbX0|aN9mq zF8uU>^o8*A0@9bl{}zzG5`JAk`dWAe+}2Mw!ta8|t<#*m=schuUI$MUj}m8@J?JL_ zcrN_D0A2{67r;y5rEuGRdL?`o+~)sUKmRkNVRWt;oYUO$NqcI9ZzBC!CTC6IjEl7= zk&C29)DOu0uB)6kWs+~*c9)IZkooreaQX1l;5L62!$-qUH1qM_o8h*9_{H$O*-?XB z8FGo%C!(hTz5;%cnU9p)Kf5Sji(ET$U+hDESv?~vZ9(GvBu?_+qu?ir;?8;?Ke=fk zya;|VJj3J@ygCqG20tr+SHVvX;C1lP0lW!59Bz9qHPVZ9G<<|{emQu>g& zk+JE+%JsPPBW5LyOCL2e`FH7Ku1X(uLi!OWqz@aLJ_I@B$EK$!iKSZfj6n~jj{Dcq z5$Zlaq$@(|k&sr3KYPC%(lO6J6_qX}EM>gM`um7p$`5N{c z#uwxCqak&L=DqU&_P_2qhOd`~^p=qNkN;KLy?ylB{nRIYzLWNpI6?dFZI8wYtTT&sC0ItJPD^4dM1>!L#uK}KCgB3%p~=;qyMATHuv+i@O6AYH*#=o zl6oj z`cUf^GgODx)fwvEBz<>=+LEMi%20PEvyl5PS$~qD7N%4p{$6+eLxx(Crtj>lUQeSp zUfn}K*;oDCLvQS>9!V#Y_tN$DzG_KNePciMNl(7`wx_2>|ofWOcqs?U{St|8y1ctuor>@)sd`y=RiAo+QqTG|+1HJ;H$!?yNHw_e(jRnFw>tx0>LwBUWH+@SJn)`wsx>_D=5FeNi2iSiS{>1!rl|Y$fHzXq%Uai_ zs4ZGQmZF|d(s!n)8>M_$_lq&dDRqBH&k3uyLVAy*7CZWLM@(_?q36-fm521d36+pu z9#JKbM^_;%y+hkVet5fvse(H@B-P%|El=5$?uB^L$X@B)tcfEXn z^?G-G*Z%6`?t0e#YC)Rb)lXHW>8<_LJ861DKULX7uj;2(_0SLYQ_rTOY(`K0{r+lE zPrYq_FJ4-D>W})XrM>iP{ne^odQE@zWiMUTU)|qZFX*pk^`X2qef07J)Sf?D@9QA}W zg*P01Ygm2ijCWT5^KU!R2Mg}&g=X<9$X@f13MTe&RP z`ltCJ^;FW3uedyrtl#0XHd(LZ@>a5bl*{&HeFvA0WIcn+m)-PEv^>z=Rl2FWp7BIT zeb9Z_CY0Ttrfa#plBRbq52;OQ!+zwi@*et2F57#Qg-YF`&XAiz z^5-o>^=d9vL-kI+T|e}A`RkU0^mliL)V70mIlJx%sU3&ttz14objSuS^M~nGTwWda zh|_p`NZoX}ewE9T!*vap#}C){ahaa|ne#Zq+YiI_VlK}fp>LGIF2~KQHb>81gq1mi zB(E7q>bAQ>YVnb}iOY&3^(HQ_9I0!$Y&}vx%;mpF>IyDz9+f+d%Uz>%^IajeZd6O? z0j{r(*7Lc1JX-&_n3@``zvMFa82vVvs$=xOxjcJ}evHfJWAvR|zB)$FmBHRc7lGF%jOAsJ(sU0=;d5yoTcyL^2+bsd~ZF+HKzWY3tuANHRm4rN)?8ld*oAG zo^YtzKb_^?{J8IbVOq<@NLRn_RY?ub<_z=Y0JTmk%yH=r%6% z3bhY$FVY`#`RF43 zI+vD<^lC1*T&y49vh-p-pUX2B>mM=cy-E5@E(<2RWq5t^sar8{{bl+A-23`vgXVK- zxvVPmD7;f)Xr-b>lF_X zX4l`WpLviVni4quGMoxZkFr0O3gm^MCWKF-Tv*N?2YcU zXDx5j^~djDjlYUfj6p`LuNh>tdd|@=Y4xu2yX9Iv9oBbgwIrfvX?3GNuSg$BZ+E38 zPFMK4-ES_}w62H$kH5*tV&3p~-9VQX(l1hTAtuap!9Rs3AIzbQke;8XwuVOic%pjL zIr+;I)enw-`$RP-qCd%zY0Yan>h*|zI!84{^!+(9J9+3x)von|BUNRRZqHFqC+Y1u zsybQkJW{=ptlv9QeUq$TJW|a{(N7$y>QnUnC#ug=^xPBG&nbG(SoLZ*J$Iz~s+-<@ zq*|4#t4FFgQ}yj5)vi?i%2*kW@P9$j#Kw$jCkfa1}XjEaq7mt`qtxAWncZ%vFek) z`m1AAYhS(jShb>`UU#f|rJsK2Sar+(`nF?L)&9CYSJ4M=&sG0EKsV&7bpw`1UK*`B z2I(h9tJ?z^|MzJ1)nNVU(dwtc`i-O2twZ!PN2>>i=m(Eh&kWJG z9<6o_(Laq+vkuf>j8bQwC)!b};V5t83DD~w~ z{oYY(+ClpHqg2H~y80;f_(6KnQR;<*blFjA(?KJ@9jTtp(v2h4+gbY6k*aanh#EZo zTTKl=lt=Ut0W(5pv#0V>NH?Ub4~dO*b&sRp@1?$UO6z*5pThdap6ZQ={w`hJs{hG1 zTa)zSp6ZU|-h6&DdCV(4)n_SsMNd`TP4msu-HvVPsivpuPkKsS*7sy2mG8H8KXwH) zO;`3(kM_{Bd#N9Kr15=o`pw>4px2f9WrmuNUdd4E2miOBa|uoY_TwRh=-ICiVfMe= zSv^F(7133hYNq~D{`fihqBk?u_bK|>OjXk@SH9_{zsOWKrD{HJOVt$v)y>`YPnl{< zcU^&ww8`HMRyX$0l>^n|J%;i5s~%5=Um2*D_tsAhRB!ao=c~v2=&b_@oa6Ysct8E$ zf$IDHG@n;w=m!R=>3wziAoWIHy>YN=>#J7}R!{cRD+jBle){gg>Yn}e9fQ@T{WUjD zZtkyt7^I%icPGQIf7p zQ`JfO@ig^gQr_Y;wJ}9QKTXliX=-Q6DSZAauk8?^OMEx@t?+8`IU3-Sz5p zwW0ehq5IO++#b3uU47nzBVSD(9cY5Ct`e*t#- ztrAAdLt8_)rm6K|{Zn`KVfd!dSKZb9`qbL)EUxYg^T#vYj(n%Pnvwde7rLu&Q#IdA zBUrkt`Q0_?mdN7eku?4%^VM@$GR+9-oeY5PGI^EzdA;N_)2}6wlmB{MpzjH(I~Y7d zYGnu?_}{y1iq!6Nakbm)eEkw5Vo2ZUsA-PZIlIHb6$dj(TI9Eg!N=~e)Fopom@0?# zOh>)X&VZvn7y5`{Kq6(SzaPag_M)#Skwl{J#N58uqJB+C*E#C@(8%@to`IiLCdFfi zE~IODHxDavo*Z@Z*M!x-{aTFjbu4}zk=pF!Bjv95P@KuQqtuR2$wNu%mGFeQNiuog zqgAaxK=zvoUKg4jx`}&~Va-YRO1GA&i8CRuhDKI!INj0HM6u>Gi+UopGj~^e2Wy2S zbw~Kh8A+-_>z!Iwac*t&JcsMNP2V@`IyAL8mUkb4cyuvA|OIF*%hpkAK)!bvr zvV^NhRv#pL+4q`Cy{cDA5T;eIE~*fOw@_&DJVE<|l^?w}&U} zNLM#&{dqcT*9kPonxw;COIJ&i^~!Yhb#lp)boD^D#i2RrswGYD?x8wlcYtb0|1H-m zH52v6{OIWWmn)U@JB^%8Vl~a1?tGu_UnNC*#90?=(&EldTJ7oFWRJ`(N`1a7(J?Q=y zhu-U?LE})?)t|xHPbKM!0)6`tDV!9bW<;fE5mcTsmD_E z?iBTu>^M>U!rPMA$lH)SxnZDeW;{Pot?M@7*@0?zs;(NS{@wld(1L+#QIEx;_Dppb ztKv-cSkd0eb5%RP#Vjf4c0MT|e%X zklNt8_lR4R}tw)nh&MigdNk?>Yxd z90a%gUv`%CUMcB>Te_(&k;S1|-PGnJUDi!4WxFPY5z@125FF;`|J$}_)IXwksdr~GZJ48K@suv!jzDX^adx(0F@I6@VO#3*r?O=6l&vl`V z2dmq9>$L}~#@@GwmL05~-fvxK;lXNkU;T5In$~YyXh)V>)_-y6-7Gb8fL@=a>Ia;@ zJWFl;#e}=ERLg;ST9#UOh-d#k_<11HBzAtB(;iGw?}V2+x2C9-$@-^cwN}i<2ZJ_= zz#Y!Vp&ydfGt|Ks$?B$Ly*XLU_a!o)2oZBN&S}rE?-)Mp!6fy(*0&_7jeg&>4_54h z$lmLCACwIILJIStlgXCYv*BikJ+Yn1`k559+b;{<9Rh2e$uCPF>6OW9d8Fj=&S?73 zkETqvU=`i;Y40VePs4}3n54F9{Ya8(_DkINFW{#_S8U;DP{R7*-wAhfZI{(_oHX$g>2F z=5vb}xz5j7a^D9B{ojc6X6RSUeD4gkJBmTewQ?U+_nn%h)H|UP9)n>9#Y=J6{@mxZ zf1w+CH+1TYJVFrGPw=7?KW*PhC}q2L7VqYC^e#u;yzff)!RG%Pk;B};taj#w9_S`B z!TH_PD-r!;idw+H@MVhHk*wcNQEUAEZhuzPZ!wUC^mDwh&C!qWbHeeZJ?#HWX?y+& zZ{Hu9u#2rHslflUkV!N<+4~SMKt!zbgtI@Bap%K`Ub>&!718tdQ_t$7e(0mhk|uo7 zhg%Ephc@?7Z*Nh z*_wnT%a9PoBqXGg#J;{QJP{d#LYr_V6o<^TKt9*=+b@tDuK_j%vglOwPT{e6_Z%hXv_$s$(gD&Ye5<4LZ})Spbv$ry#bxG%^a1cM#-mvcTuC{hhRN8 zRDB{d8Oii8wS8Ba2C@Fgqqd{G#u=-!$fyAGn|>hl!Q~MrF4Uu5~>H^pbm%X(+O&RSc@MM)ROS3 zUni)Ug{rPeP-7zWyaY8MQooa+eu>nyKxJ8!K3+u)h`#yzDr!UYU0+sFKNfyrK@~MF zMo+Gy_Qu>iw2Jzm=v`+kt9`}p+E-bfDXuqGR_kN+QX;YX{mN=~2|cQ^8dtLFiAriv zsTY2#q;{3Anq5iFs-TxtQuA-%SBUCILy>BlSJTXwOm`I<>AXxP#q+`ynx-Lp9AM_T z+!ro`hRAYWObt=(7gj>a%+Q$^A>omVj8IZq-+e!ZU zI_qhu6aE&2aHpcw1h-o^#AAG?^P@(?T!gIvA`y*AzPp*xrAb_VXScifpXx1u*Z&<6 ze+gMM-?CPKE?@;3)HRi=o}kscH1Vd@63<<~(3nDi-c7T)$boLDUF|fV~R`6@JG48CN4h?SysWsa4hH~hUAhim~P*AY~zQTW3 ztbh?xK(PXbtzhw%Pf|y@ZKjc4J&!i8LrIHrYfDNm8vEOfMD)kvj|b{=g;ZLQ-c(4< z3N`0n(y((OGrUaaBhZJ8|2aSp4OK(5-WQ@i3^M2Ig7n!C^?8Une;1<-1=JQrQ~5Lm z=rQAWGAVs4gB$n2jfKcZDk_G`$MZ{ANe`}P<(sQEJ;&5}m zC0wtJQfX1<{8$t{VG8z4S~=vQ86dsItp(|P0xhbcdeLKe8hj{d#1-uA;}_BNcv>5ne#=ZAvTTXPGZ!GP(3O}&5ktZYa{jhG3sOybN+1% z#1@s+A2m?lmep@GP+O{-^HbIJga&HwE#~}7v&4xqoZmuoG15$xOo-BF%c?EK&H1U~ zdT2SdxvV+=xEy>aU?o(*@D{Lu3@M`DsHEO6qIXwRZLmTx`6}_;Hnth8oUweyQ+eVFOW6n>v!P{qq=(UB7rJ7n;ohoF`hezmz zh1DO?=KMztxyAoPOR%EVpb)(`2L4y9UtvcGkoDXiOKX0oBwKeBI zoBo)ojtZCxC$%0Ju7=TKxG;4h*qpyf3%A15GFq?|t|noMuAp^b0WCqnqPM8&imY)` zos%B*t*MM@d7t}k=KW&Ks@m~Rxt+9z#MId*(aimyd#Io>T)>850UIrTIwu7*RH65n z-tSW9DK`%DX*&LE*jJ@V7V{TzGo?rO1X@YtPT?BTkVscO6vGCz68nm`j8n8L(NRvb zl^$oiCv-37G-!;&-2bcZPqO8mqIF4@I#@qC-bo()t~&&z6v@8oijz!Hr_jy1z4HPs z$R29)0`z!GIMgzE))_`?acD)>Uw2Fxu5ph7ZAwxfok@!xk+%v$Lfh(Dw3-Z0GJ0?vt9<0?vib z$mfVqU-WBQooAuXX#tyr)r^O|s%dE!wMbn};dhezkbX?{F+R7OB` zTD1%>qenX52GWFSkRBVXK15H>e!BQC&S0a5CSSwVpy0Ox{+iFXMQfjPXbrGwcOQ&U zpM@==l_{4B>C{N|iK!dcN9d`M>JM`|(bR6Apo%Nfoi3i&Khg3u^8%Ohd5em#&`lcT z-$|nkPCun4)4;kr?La2Mn2Vu!DLYX1b(MFG2Q&seyqse{Pnw zDD|%Sp(Kf3?98P5G%0gdt2FdOY<>Ufb>a6MntxZ{1^nt94pbNO@ugU%2{olK&B}}p z_<}+;6J6@-`Cs|z^iWz}5vGqtt6xozXh66gR9Gzwr={NNifP-tgLY7jh0b?{X~&5e zomxy~#OO)I)ZCb9&f;QfN6{j*j;I*PE-*h|n;(jwqVr6k$SN=Os-GNMy|+nvSF@Zp zw4}tNM|jnHV7JsE+1K?kO_o5<(rTTv#i5ItUcFSSg)~b}3;w*HIkfJN)+5u65$*s9 zMoB96d_t)Mj+siyGKGq!$w~Ddb2`-M7f&La(ps#^j^0Mgi%r-}x#~jh^P1KMyM0d+ z>_@g!{87jI2X{@?fX>5h}XQ5NB(E`p%>01kl`83Y}9fTNz*$bkXh0 z$ZUma*~&NW>cpQkt@GPKwun54qUA@FiyS@Dquw`RBo_AstsPYBJ*E@tb`fcYjkca~ z`=g_wt@wQJ#}u*?TE7*hCI`Ji4@^fNHuQ15z@a*lm4)`!S$~a5g+8nE*n`lf_4D5I zy?RD3qovZK#rNt(ADzAR8d|g}lD=1uR{6rAc`pu&o&T!Sf=?P@cl7XR8lZpOEH}_I zqiMK$LGUUfCc`Z^Ki``likNbyqe$!gC)2)>=E?D%W}nbj-X=*lAYF>SX>N>j^i=nQ z85&hYq!x82{U$j21CN=Ray#^{(yLF*z!RU!6GM#HXj+@<;g-ZQxiQGxpi1|=V^#&3 zseSq}xh2(HQ2-Aj<}R3Pb7QbMdE3#cw6nN59Vbt?)e_}_5%ByyxiQd)(NH0Mn|08f z(%KtWRg8&)G&kG2Z5+wF`EfhW|JCc(O&5`!z7V4SD5;K^95y&S!#l2&S`azLn4-cP zJ&Q`wRK_f_5C=-UxT%!dTatv*OVQ6f^YfMYp=Ea*_?zh)MT${c1U${W)N=Df@e^|s zeUnIKofa`uiF7|yU|yS+n^7{*+yXsiR+zDT=)FlxXn8lTj0W@PZ%q3i_D{V0f0;LW zmHXXYY`4Ng6EVET@jodGen#@bQq0W$L}w1wLsa_0x|-E%Q=GMY8Fvp=tZJdVR59Hc z=M1mj?&VddKf_o@nlUi4nbHR!EmdwIL~ZLeUNdn^W7YJf*KqoGDDL?Xucq(te!$Ze zo}K7?5MWkAj;EHgrzxFN?M(IVMI*2c6=j=V?8o3Bo+hL|;k!Y~4FN6R_%w*VLZq3< zZ?xV<>jkx@S)s$4=1L}+Cevc`v)TMyog0cDOm9Wu%TqT-bSHtn<`Yj^#^FXqei_bu zT}n&;Xnm(E7V?;W!ZcIei~l5X{x>~q-re-oCRcJwR;17JmeBVZ9_Oe-UzWY)y=^O| zsf~zxkhGtyWt1eC*~l+Emz}SI)b;>9Ge}*~n$E`rYMPwR2)v!nX?2tvc}3mH$0<(P z(H@?jn}gc2*qyY9_bX?d_e-sQ3ebzRS)1fO5@}Z2QU{PKUa52Ibt6Qxdv8V3DE%BS zEymvwINft9LZye8vAf+N57YUUQ2iqZ z=gF#}sVmR_cg1L_=~+j;r1!bGoKC5jxbYeB6uGZxn)aqi%)DeZeO?Aqlp4Nf<(3|0 zn%=aoe+J&s%}xF)s{aXg|KC3X@LO668Ww;0{5|VW?teKedV70n%{%V|oYtm}q$W8s zbJU%CsAOk)^i~gj#Kh?zb?0tk^m#E&dCK>CO*9jcKU$#hcL60oGu1pj5@0ILGpOHwa)8-x7>(Iq{(`nw1@tR`y(8Y9TT;MMuYFe<~9b!J&auru-HlIAE*PcfoCj}g!Zrqgr>R%!(VBOrYr1|ZqlnrN znCY2VM136kr!%04`Xap5$--(&p)PbjF7hKU2`nqZ0qD>=+N@&lJSbL8^mNH6uI72q zc<3TCu*>4&YHiS*K)Ohc=()Z)&3A1!cP>XizNff)yGTzuPmg&dx44>GG~1zzKh0p% zlvvhVtNHUZjOsl5dnkPuYCb0NK079i2E^#I`;`GH^TO0d6YAaiK}y_9fyd1V*A=Hk zdt#5@Fvi1;wEd2rM|(nf%DFcqAElc#w6IDxRiL)ZlZ0kFdMka13~Luz`w<$?qObe@ zS}hPY&)i$)iO)0VAJdZ1{cn0kyNz3S=)?7-=z}$A)Rex!Bl}K`XAdn^B0&mTm8ukq zDbCC3+I%(mV}Sa_qv`w)k3L1)rg$~2_M3@x2#(d&l$i^m$D*o|+gPW#jfoe*YLk1L z?xF4`_f=*^O=Dw+(}+fuNd0t=8GmvWRBJ`}Y*F)4Wp5@WIG%wiN>D7Y+)tCT% zPOG&6w3UhRFR~ZyJ+ROzo@cj>h?=C~{@6T=o+1rtkl|dW&#~c6A%i;T{$`ZKRRqx2 zjHkH3XfNnr)IGNxalf&dZHCpZ(f#pbq1{;f4=i$IQfV5Tc*V4K&f?QwzZJ`W;6?N# zr$a7n+U?Pc=wA$Y>$~ye*AqYQ=O=v8gPdD3-KH~*nx2&S^7Cx;Os6NcrlahXpL)4W7cM-ho z)fuz_&tLHGl74z|p%1sC*@yj3PdC8+1g<;#$oxB@<6$1}JWqM@-yP8> zo5PcRS0-O)?$Go{3#6x@a@XwVI_8;WrUEy)0Q2Md#m^Ndk1k66f?pNuYKH&D=(?W= z(x;|+ZlGC}=NA9D&RY)s-(+gmeXiHj2l`<&)=yuo>+@w*dW1eeE7Kxwpbu*!pPOEe zzMC-L>&_{xSCm)l3mz9cQVWLPl@>{uqRYIx_*sWq4v6; zGE??%A^U_|4;40F6Fi|uJIXZBKKPfUVj9zycJDiS6Yc+E9wZaV=C&n$SG>ciL(^Ru zo=6u-p{Z<|eY6^ZrbTJ`ibg_CJG8w6ZQNFy$k(PlHUqsN^Mt>;qJS&W3%b0#fa{Ks6PblU*)W>j z%W>3TH1NYsr=%jOLdWFM+0JHXCoK`DG5b(;-aF8lLu(J^G3=-8EW5HpD{{jNg0oQ1`P;>R%z_7prY%FVa1Flcw$;P3J0ilMafG zm>MZ=|7Hj6d}Z{>xUO4NT9^CEF&!9MvOY*!(SBOJQGVKP;bx(4#lQM(uD$|3+sqw# zrh#P|4?j0VpjEB}g&}6q){}G^$c@y5C-lJ*8xq~6+0}9as8+01~D@y!# zB>cUGAC})M`^op*j=H6y86RKcamG0`g`{?QLJ!e@I5h7|SA0;4`70y&V?UnxRbbka zRj6IsL7#RUUWAtFDgPce)+7JXF8y2EiL&7J+N$)-)scO7RNp+4PaDUsor_eXv5u5F zpU{qMCVSEccy6ALqBT%7%;M4O=#w{;$dWA@(b^#Ap>ZCQ(`i6?qPg)&f$lb;A#8Wu z%6G9e$nq;yFgei^onKUi-dY5S2_3ft5YBtY@s zMl>8KMH+r54TqwKI+tiO2cuzp%$v^8((2t}^u)emua7RRvSVqLiJDe2X=-V8v?P7u z_*<#U6k0QdNZJ-VQU++_%+DQKPB7M^kB8D&2CckP-*}S-hp7nxb=*&KX&moZKT|8>{A>Lntt<#^k!{9-NFpmpj|*34f@+)$Gb`N&gsWx2hO7xrqLKR$y&znzH6Ipy z7oxuor_Fun^m0h!gS7EYD7^%&>!mqOV}7QZAKDO-S~ccpju{+WV}ACUp9|)P0$$8r zOfuHpwsMK{BekBsL^o@&BQZ2Qo?_@Hn#o#OLeGp>8%n%M??me?R>iA>C21Yfic$-l zAL7-or8`nGl+owoX+sQ(x3qHly^3mmIh|fn?R3vm<7gjQ^MQK>J zyE~OMwJ7iRI!)`PMb$i=8cgv~NN*{sHWZ>%8y%sK)7GmIv@}!w5NS4Gr7v-5pVTOw zSxkKrZMI=u8*R>yMbng@T1GpO6;m5yC=M&?$$ z^FtwB;IyQ2^QWWt7BU|ueM+A}dCZ6@tsDBIkQuI2^#r=rxy2ipY`VF01EljR4kSSo4p6=Ye*W&pAl>puznXzlV)Q)XM$-CnEF1Wv|b!y#&9!2 zX!PIgu|Tf|IjS9dBaWShc@}+grvzf(@N1x z+|SP34TiGmpJkc2+Gu`g?$Z@q;Azo`GCHk~rO)_0B`7P2--`8PA9vW_k#dBJxC+J5$YFnN}q9#j8scBou1ZuHhrLCPL~Gi)wJDCAf3{h z;60IQco3b^S25>lpF4BdUYWRP4j`=xDVeJf0%Fke(Z@G73>yI$Fr=lrYp}!S~G13iIRU$Y0FanEKi`|5)8=Qm$#pZ$&noltgZVjYe%>-U@dNYoh56ZSekdbF5BAX1mfG*mg8Ttv zZEi$7MgqMx?N>V!wQfW=B7O2M#{|hUUm9a%XffeotVF-)`z$pm_kg&PR9(>2>O_NN zeiiQQuc_*H=qv*D3`yD z$!(e}aHA{+oK{k*OG{E|BVZ+V`0@xEXJ%wU5n@Y-WRaq>aqBz!#7_OJG6rtVDQppLqdlnbNX>D;`=_ z|EX8+2&AqLRV4KJZEm1?&(sFFw7NV<{TV>b+K;vVgo2_qZLqV=J>RDvqHdTOO`)%G z$&8v%y=#6pm>m~XNNQp!f@N;kzliy6RyLZ9wNX-MOf>r3+eYJd-vY zHaVI)?Jh5D794faLmc%iolxJBrA?GmD$$?w@h59wYs)JXONo|ZJ}{EBBX{p&6>xnkB6(K*d5 zx&S`tFQQ_*{0DXZvnE{%5 zmP=?wD_txM(TBp+(U9(R{&tuV{S{5bq8+FcLz#@09;~L2(Bw6ept{+VpO%c$#-21W zPucl5`llN1W|6c{$7F9LoxA_ZK|X3qrGfSo>K!|JU??@`=#;*gc{fyT^U^5==Ce>* zN=Bz&YxB<}j?>BjGe&HZ*1t0dkCrc-KLX42lQAzj@iA>V|lNv5mj{>zE& z=Ipfj8EIO*w1+fh0`qg&{7}5qY21S0g!D3M ziq<44TAA^uyWaL^+VCCmS(u)uk9rn6I?F@*-kPp7iI=Z)i)+|6(sm|Jh2;Tex$?3A zb=>Qn5n#Uha)m-0n&rFHzM(6cUkPaHc_1i2d0+Ls>b$D>=+`DrJxzZp^oJKJzQSbs zUjpVj^y%Epppw*al@I9L|4h<9X{DpSKyfU-)dcetjfUMl43t3k?PtcaJ)OdHpc?~7k2uy{E4mCXJOZ!6srolx^fvCHeW7d|W>>`&y2@smSNGlL z!{3~PE9-B=5(=@~S;@Px38fwx7p;HRW+NIm;8E_d*Myi1zgN{o^_&xS}*@d+=f_WE&}>v~D%!yM@@vu#c@YtzYg+7c&vkxVOy-nTu029AczsXf)0J4?{!|=b_1ZApN@vJi#kn z>4}{lvk4a2P$-YQk1mGLR)|#10)<=iEYa^fUCARF&!80-v=x*aC|juXt6iz1LQzF4 z$tW~*zSf<*n1o)0sKw(?tw_t?IL53EYxsA;IZr&MSB26+-T!#cR z;p*8$+g3YfGAGxgkI?_RF%dR)ddYloMqdn${Hx2JUuX;Zwttf&pC;et)W4Mm zHYj6k3HHvV9eabkvwt&=nBBkbM3*P8|Or&lVdI{?F(1uKt910dS{-|=Iy#&lM$5P|Hyatlm zTQnYEvdl-wH-*evDr35bqTHYKyziWH1~;QAhK73^nooYeX-FG`m!R_;{hjksV_G;| z)9%?oR?u#x&GygKoNg=&A(NX?3<@o6LVMx-Y4PGpU} zjnsFMRq1?Wv>rnL1tYq~nMSk%*4!OixWOzsR#^I#jsDFT(cn_3NlLGYYSlaxO{%2hYcOE&`e9%SbnL&C-thx~NT_9cTjnKzvopI!O z4_z!RtS`r^i-nC;dJ#Rkgj!w1obN26XAz0{(CGc9xZYes9VuRJc?q-Hgb3|%?S_Z` zrv_zwPxG~!_FMm)h6gE(^59gs(+_Bxi84uD@(4KNM_0j1A3mR7@pWRV$^Kb#j z2K;*B=h?sin}njKpH0p4bEef%=M4SxBdH5bf0xF+X+iNu=T7<(M+{cc{BF3d;oi4W zTfyxXQ}FZscL)-3es&YH7fxblM)QdZeQU#s<*)JLr;$_8NBy-x{j_QewnwDDjr#n& zrr$|vYUlVYsr0?_Q{jf*bJM@Q|BJ73NfEy;#rieZw*9+n;;!)=eH~X)_f^$R-EPXJ zJETn&=|9ImG4M|e{1XHJ#K1o>@J|f<69fOmz&|nYPYnDM1OLRpKQZusAqLXRCb?RB z!L_}}DAwOa_1>Z-%XDPN@U?qEKUu~3y6~%a3Szee^Qzg*GmhQs@|@G`s?U1gH|`Sd|B3sW)(+E=70hl%2)jw)?4}fAS4DzHvzt>GZgIGA?5YavrpDvC61y3d z*^NtJH>)bUDb;bm2D|D;c9Uwcn^POSF}rb1aor5px3ZgY8+a?Y?pyu+C$cZ!Pk`GD zZcDiGL{bBe=NC%Sy2Ct2C-AWrPif5ZC13WHUxsu}FO%eINxPNh;)Zbi%l$;~TyXJn zHu6D4rf)vj3BGkS^O!O0CXDr!%Z1#g;mn(iWVb6^@h3Qz!&Nhl@ArZ`99M0*Ub><#d^yn2nM1BqA&cQvjhMyO`$@VE)=k8pm9?8y}7 zg#`SIZYtjMUwrK92S7@A$?;Kj;~T=QkBl zPe)5nI`o{u^K~b%Ki3P-EKAR9=y?FoPbr|D^Ol}m=&|b`RgUw6aIsfO*<3E{`X&`T z=VpFRC=ilM;iE6i)VnJvG_9Zn$P&^ISRf!hDz9 zr$R2N7GD>i5&wJJj|Lu*e#?)D*c6F>^ke8FKV|CfOzGE10>I74Cw(okzg;eTKl1dZ zQtdyL{!#@?BKHi(v%$2aMxDuXomW)eH!my5dGpng7gyZ7YOnOuYFQ7ZNxzM_X-kaA zbDdW-1M!@f`8$uRjC4Z$UoYNnYVpU-lNV-8lm6onD2+loXJ6p>G3^Zcno#B7+V(q1 z@`-)Jy3R^KzCn6U{I$-l^*(O%i9)}%667Rep8uxA#;zD*b6%J?tKd$nU}EUz_+bVGPGLOa1jL<>N2n|12vJ@l(||p8QKI z6*sof%X4QATPXef8zGpD@J&R&U&1#<#sO@FD7QAYuQRN0rF%k?wwEY&A_IC4;elRa zF9Nv#ZQ{oC4RUa8>lM3U^XpwFAwMNm;rPmeEB5D+b8X7aNS-%IVces)C`36)$2f>- z$C~_|fol;HSIU)K7t}5M)#d&x+b*0S<1Ms0@ZUNz5Z>!OEa9~CQGU-o`@-U-=2X|07{ThpzrEeT9sB)y9K~$XB@$oPUkqCJ&#(wXI+Bq0Q}U$(O?K zoYY~@@&3am$avdrxRD9}6EOZ}{5NS(6W8**xMEl3IzKn*MlL6E|HAh(vZqxY|6vmJ zCgMgS>|++j{p9`E;98y+SL~@==jV$5QlHxKVLz98XPt%zHmPwk{x}%|nG(L@oIWOQ zOdBE_*R~$9`!>JcbzC*rVYqSC`8ufvIIi>4ld|de{U`f9pPhqn6*3V?M+)p{3dT`s z<&r8we;G2aYJ~C}Vt4Z(zo)j`gkve8m2UZIXb$w2$5T;wpQGjf%HJkv$8c>cmw2$b zeJ$xL;rMXq>m{G-7cou7iKTu@hyVRBZfwey`Rgy^$d=*^$Xobtm$v`g*0ud5<=F;v zWqexvk3za#sQ6d?WcJ(4rNjSJjFZdz55l#r zH{&|_%$AqyEacOqnw(#=;7ai84M)m6f%F11;s0#R8<@Ol!jOq;Tfe-g&FyR3|G{k@Jy-F!EmLKF z;;Q{eJSAhk!uW5}r~|J5rWf)yx36vgUpUY)yztk*ESGtatLg@!$LnlX(+M zv81bo|8|*W+5c+IA5Y1>w{Cg{^j5zh^1aRN>m;;qg@652mk$Tm z{r)4F2f7tEGU0zL=7r3=oBUT6*Ydo$_InApUCH;tFa0!ae6er3te5#G>7OMcoa-?k zCF#FO=BGpfT>HJO+xcEj4$u64>z??{GVfK(c$DWzZN%|!kf|TC@?7T;Q_|kc%lw^7 zI*EMq7b|^KXx#eK3iECBk(hfVqW^fI$zS%-#Q$YnL+q+^y?XqrpmkEYMEm8hjvBW` z=K1Pb_p_7!dVf>D=XYcwy!qW1Zp(Ff=Z#k%Onhjk!u+DVzsO%`{+Ivm`{%h98RI6^ zX8W3#`8!XkgZ2aDuh;+F{C#No^DWn|io?98j9zEr`E<;Kny{I_@iH%Jd7e|i@Z}(U z^7vzFK+VjEW8cbrD}9aO9?6i)y`AGn%IA4p%k$#Od&_k}-NX0A7ar3rdA@4J{?xS| z%xL{r`WX8>BhPhSQTx5}-phL~=^^b?8F!KK4H;*++Mh>1SNgBgzmWcr^h>0FAnkN% zFH5^r?2@#zq`f2U4ypg8{*e04uGg=YZ`e<-UM96F_WKW|LWtu@Lu`w z42w&+v%#;11M>mhzTkNt;fdgJSic{up6}O=`5w3)%qO*l zJ07mgGl~DLWS#>4o`AcuE$fr_PsO?h8JCv#%mf#?EL=;t#GhPnb8X5~9Q^fI#@F04 zhv<*$$LY}t>A`ntya&(AwYb-tKazYV;Z1yn_1od?h577y5j-D12X5&|zHS-KuJ|kS z-%HH?Qgl?sJia}jFY+1Ce<+aU>jkm92X3#k9RHnhEzd2J=e#UmIe^_%xbj?ET+4IW zc&@&~@-M?(0yoXWJOkJA+)+Gt;1Y*t_Mhx7zRa%pmx^n7PBr9m*YZ5eO@#aMZ+v~} zcXn5T%X6`KPOin3bQAyNTJ9%a=Q&wVVL#XEI?suJ;!mgR$csOczf>ycFIk@>JSiWZ z4ldym`Al%}UwAgS#GCNke0bCV4v)l_$R~l@dQ$U|&jh!_nGG)ClyaOadT!->5jBv* zA@RDb5%bw`f6beid)eT-EPfRHqQ#Z0pDORGCl);2;)&on7HprC;)EL0w7D)KMJ2Vy}g(bpJdfAD;9! zlL4NX%<&^UZZyl=JOkVgPtHh|m+~R`B}eoizr>AUIq@e2*AidyTq=05GEax7I8*W%!{sKdeK zQ0n1yD2{=knaeN-ZK~%UX@!$qS9oSLU(0*#bnhw^0$2RMdtFmCESj1 zyTR=PcL?0^aA(0?0(TwU9dM7pJr6gq6#R!<8E!qeE#Y>A+YN3XxI^HMhdT@I61eN& z?tps)?s>R@rQtu^%5dw!Z3(v{+-`9Dz#Rg2Jlt7um%v>IcL&@faL>aHggq|?w=&#% za9hId2)7&DK5&P?9S?UFTr2zJdzp=Jh(K;1ws*h6{S&Si?dXs^?P+-?uX_jXw}<-> z+$Z5m`#bM5=3MMt8uI_`x8B+yF5%wCUhMh8i*YyAtXng&M!gr^t6Hzss#i0yZq2$k zFpsO9SgT%Qy~JB=m4CbTk}thHNq)HbClda+m$rZN$Ib5a{UghrT>aNxk69!&MT>zb`MOGX3NqFRf(B^2;NY z)HA+%qEssCA737=CZeA7<%LyZD(z!p9bOtCtULNai<)tv7$x;t-kV;kUHtQ6v=Ii^ zFTV1{)kMEMR%Q6*C6qt=>{TUIZc~5yOI@wkeElu0QkwgdFQekn?(mf_oA=T^H{~Tj zoxWn@+1rN^wxar~s$Oyd6D>l0T#N@XBliN9Zgzi06uz~8s{QSc6xxP2sgeh2Ra zZsump5lRA%ic*~|UK%{b;x)m$TKrb<9v1He{{GDQP`iB`V z&#<@|G&b_H!KFP|4m{K1O~98~JOw<<;zPjKgG)Yn4?G7v&doivmmj#Q%=t~Ynfx>1 zJahwd(NhilC^#jDdvpZ<+2T)tAG7#t;Kwcg4)_U+n}3dA!gJE%E5KD%4yVNDIq+bM zSE7cr(USt6gz%d^e2qO>0y|J1d=mKg;CJGM&wy8qV+}u3Jes2o^$U!iLKTzT>j22V zLfqJ;9M~lZXBOn6E3te8Iw{&F|6d~fj1;G@A?f=|td z?*-op`MVL$C<>U-f3$fsSHlg^lLj7lEA!{Ui&F>2$XBhEpEw?sZ}4 zp9a3Q9`jJd+hOoMw=nMq-hkr6=x=o^^Zw|t4FK=Zm^tle?jGNOUwV>xNpv_P={ck4 zOjG8xt&)3m0Kd?jc`{?#KaAza;(Z%K{$8rUjGi^^Sbjg=_Y?4$9hgT#-b4Ny`Nj7# zZwmc)f}aJCM)=2p2Xtb2;fKMCJ;3|`^i-lnyhi^8@L$012S55C%Rd19OTcqlG;<|o z{y#91^)!E&{pAWzr-Ok~sy}sR}FAXr5^zDrNoXl8l2cK*4+C^FZ zLMzrI`F1aOy*9plcrlhQ){ny@@4GP{9!3KkCOo|%KM~<+2Ojzo>-iet{|bEj%gn1m z{?B}PomkedUSW9-tx`|t!)JmwhdkE;N|i6cdL~+YD)=djm!J$|-m67__E+?b1D|B^ zXetOsJ{Nq)ef(n2fe*ZcLw*C^_Y3g3;F2zHlx96~NOux*k1xQFwYAcVss!V2LOWl6 zFEzmpKXA7%FISHFjAUQ_GkCYVeEG+5EWd7hk{gabj_atx<(W6y!Mqymb0_e)dsvU; z+rkxCzQ+$N|1PUhAAkq%VlMIAG@j)jw)pqpi@_g(o@Xnve9Ugv(+fPP67xaeS>W%2 zx7fq-%fN50%<`AOB|P7PxBrplg?F#Q^0O^|1^hC&=%0|l@=Nxzp04mWkuru!uaf(i zi~QH%Tfvd7)MHgyzG@E3H-eta;N8GQ&jc!HMt|A;EPvJC>dXg%i~QH%4Gyq;edvF@ z2Fv#bm-Un()B!X4QxE#ezXQGuydm^#$%lvB$a>B}K8f;&IR=C8>A?AFv%~y}M3!II zk-3zkR<)Q1bn@j@YBO(szb`lckjxGL1HSw)_{s-;`I@>cf2yZ1A9WM+2cBVW`Z?y9 zT#xz1Zp_6Fr!n^}JElfHaDC4>oQ#uL7L*33LHeg<{yDx7`31Rfi zf83W>r;KEHudcp4yfO3IU3~co@NM`#2k9<$au|5sK$b7(#y+jv%7>o^?*RGKV1A(et*n201nUv~n}Ej__SLfxJQ-Z2hJhhhE&|pNsu{`5N#Bule#J?VhCtUB|Rh=;LM;hONgT!XpflWHBAF9W}t&%tvo`TMB?HF|2+WIfXU9GMUQ z68r(kFAhTdcVaz#2C|;j4)f&unLjp&xuoL^@DbpWE<+w*`S77EFTBTt%r_18LYJ*qv%yyr0HRK2>#Uhwwd68|rEVfigBe8agJd^Y6cpr<4? zz)bwC2Ok378NA(a)-xFVV{p5_d67PJxSnk z@V7H~3b>@#D)2Sn5)Y-QV48f==56-(IP^RPJ_+)Y50`-3?V{ho>y7q}hvrYS{^Q-4 zOFYa5x7(|Kf{%wDiH8=?u%6lA5)Z?{mxI?t__M+7`nO0=)^il{5$mNb}!%e>JEMY@^O$~3ho)p@OGI;3o%rBz7A^r{qPeyw~{Pn!R@<%54`nwkV zm3MsoE%74DuLKu=cY!~Qc8mDip%2S11{Z&`!9Sbi>+k5kEPwYDUw@B+j|CThXZK_I z)oA}jARZ!KVs5vWx`2cOv*eaH*GzzRG%LWU&6* zBz}mSd5~bNQws*a?=_Y`2KlPs`gP`ZJ@_7Y%zLcA1>|o{WqG?kJrCXq@{(SS2e5o^ zaC#m07y^C@yd3y(@QCT`ujJ1*16fa3@H&v63O)gRDR|*GSiar+tY-}Po8bGwB|O`} ze?|Qz>05aa>v?zv>!IT29?yes1#b<$4!rbCmM69D5lIz+vHuz14Zyn*&zoMr>gjxV z?|gVa=-&nX5}yaaFM@Z52QA4kn()~5&fDM}XL0zmAb$Y-6Vy`@KMjYno?;)c`~b+m z2|f{A-uE#0R&Ytj#$=F9cmij$9tr;}@XFwiLx0GdEI$HV^rV2#{gCxYKKuxLGvuWm z@;mrC$V>QJ4rBed&tW~S;qL$2$m0>%knovPfzgX z;9?&>1MdJX_9XZ%*3%7K;<*dBZ67WWH~B5C9ha)zsNY2za4tyefxutvh@E1 zZs-3t<5|xamYzl6tB}v7oQ6*DsfJ-@woz8mf{LlluFXSJDzbC=Bf>X9}kJsL3Jx_kd;d#Pg?wP@S+vm(X zK|US4+Dhi4zxYg+9|A7==YW@8<*Pq&7RwLK^3|UOz7JgVxBh_T8+^g?qJJ;=R&WV_ zx7jS;@JnC)7r@7WAHsWe{gCDRu3`DP;9J4t*D@FT96N{QTZ2nImu*oow8MK@?eGiWt?s(ljo?_0 zW;Jac>lqFG<-ps2#d>lr`Gdqwx-5cxGUQ)e&+-}Y_kHkEUo%gEo{`{li5oqhlN=9s zfmhgYo%PZfe{djA!ExXBJ&XSUUh-~!Uy(lwUdrOXgO>&mplfr4(t{>G<1AhpyrRWx zf+tw~R`BW;?*yJ`ag)D{zjZDC5_o-!j|FdJ@de;X7T*Zo!s0)Jx3ajbmu_ouSudSz zaak|j!Q!%Bx|79ay>w@b%X;Y)i_3cHt`?W|(mlX~IT@9#m+ob8Sufqs;<8>k)#9>V zIt^U%iL95-0FQ&evR*pN;x#CroAk{Ar)cMc6dHcW(tmXwwIwg>qJOrytcyNo@%hky z+~Tqx`-H`1J@!e9H+I8chW;ONe>dC`&ky0fayxLj6aE@;Q{F$je1|JP53hR}{K+fK zS({StY-IT(;AAe`qsk`c=ihAWUf%?M5PX4RJ_EeVH!R=5VJ`YFgJ*+_{t=s5zS=OB zZwNgtzhzGUl-VWAy?kRA_{&kuUxfV7Z1@}K>u<#^%(E@N8oX@~%hwEHMeVn;d^dzg z-ZyF+^U2^h!{0B#e?fRsQ1QI7o#jW@Vg11BGw`j@QxkeBeaG^3>-oy}23NxoPRRcR zp7;=RiRU3ZSWivJH-mhO@0n-6=quk3ylo#}J`a4o#SehD=<6$Ad?)LF*7EmB@Jx%Z z1V0Tf>0X#B5|eMMk6``6yMZ@KV@|K{9+SXdg#44>-d(JxJGitz?*l&temmr+gYUEC z_va&DeYde2e|_gA_51U}i*bqwUryY-m;ApQsrLi+u>Fz$htdM!xr6w%zGI3Tdao-f zc1-H!@)oD)aqU|Li%Y#6Z}HzDUlE+lmwQOPoM3UOm#bS`>g7a>OTApz;!-cyx46{H zjVvzpa+1ZRUT$G=sh3+>TSy6OTC<8ajBQPT3qVo z9u}8+`Du$wz1$02>IJEn`&nG-e8l2XFaKn5sh5vhT z9p8aU{C@$S1upjCwD98nT@Av^|H$Q6{vVL^U+yM;E&Gs@?%zJ_x477c0~QziaM0pn z9}a;_x{G}{YH_g-CoC@ZA=lz!AI@1^?860%i+#9caj_5TZH@;Cr`U%8i;H~-wz$}b zaEpt5h_blYhZu{CeTcQV*oV><7yA%raj_2-EiU#U!Qx^cs#{#_Ln653Pq7d6EiU#U z$>L%kT3KA|Lo&F;zu1QqaN9nlT3qZyhNVaB!whh-506l}Fy*lY{*Tm4D34>o+kJbd zO9q4g0p1i`+6l>fS-U> zcynL}@PDXoL-_9?el0tYg8xq?@gwboM=dUP;4zDf9q3|lu>)PfC4I#X^su-R$E_Pt9#l;R}g4=drnZ?BpWLaG7z zS=tF|BHL}@Vh5Jt|Eh@|u>+rhOFr*N<-+vq<^Qntfd0PV^8e9#fxj#A_`hYs*NQy; zpO^4lkq6IEd=%f$<+n}6b}pEY0L=iuP|26qJ;33tKhw9KYERtQfmv02pAxRm$O7MJoKXK^X-6)i61J;CBq-m6<&%6p>4 zrM%Y%x66By#ihKrvbdD@WQ$9A?*uOSM9O;#cpS=$l=oDNOM5={W8eHN?fDWGm-c)~ zi;LYT4KCpkyAfx}OaG$0#id_R!Q#>{h`0E8l;4Zpx%`gC`_?(g<$6R9=F`ES1F!i6 z^XA~QzYnh=tDR)t z`zd~3d9U&LaOV`ukF?~U27mZd)+6!RG=?RG~!v_tHMQ=-(|_K1fOro-~0#5pSR@Kffs&;<5TqCdx_<1 zf=j+i{nJ1H=rZ#hOV1rw{PW}Bmn`|=)M_#Du))e#OC095d`A!S;ypS1LCF7o!8iA3 zF6&9kd0GBX=odS)9lYIgmQNHt0W5!PDD!ym3Yz(AkQY5afMOPyaIR`@M^&tN1uWpvUuxo zmbcU8g+k18Eq~vSVE%yl0FVyx_h2ORq2R3%&b3j@v%yD!zZcECDdH^x{1SM|=d7QC z;T{P^SpJ!n%te2A4D%)6uR+f-@Vcv5{$ub`#aR9*cuVkB#hKU4V)?S*8^GIw7Y6@2 zmgOG?za9K!3Ffmb`M6Tdms#>_!POV+ujnaLhUHsTcaLMP-mW99I zk{{}qWBw)hQiMM~j`_>0IXv%xN0nzD^Cj~J;1|K$f!7AVC7$I|!S4X?Q<1q^%X(z} z#<$?Jz@J09&#lDrv0t(LtKh*^n2%r2T;gFccqX{KZ*l_5uK<_#ZF~ds-e0pGdEe?) znTKy+E_Nmhyf(P_drLKzZ)?dvR2}-kqY)3^gAW4V2L4J7mhZID*WYc_!7%0hHSl?m zA9*A5>YG?z^7)8F<~iV!&j;6HUillAPlKL8wV5xo^2wcbn9qm&gOIlw*+ql`ETp9{6O$6;6)lR--!Gc0p1II z7x)d}tHA@-u)noLPeayI&*Bf~!#@P?4tYu6Kf(Kf%X=j^V*R7RC7koYGr(^_c>Vz2 z1uprpabwnF^Vh-aq8v%Re>NZ9y$S0{hI}>nyC1y2rKdwvmbdv=;1eJ(?^P>_Q5$*snRu?+1Sx;jc#>Z&O~@flEB3gWtK8!&4LT zwOX)zfA9(5-EU(av&}dBceG^Q65acDjegVG>9sz%! zxC?r|XZ<3tl9^Wqm-rb7-WFWqr{vu%|1@|5=>Hac7P!wzmNGZ;O)U1(!h<;-)tAli+!tkKl6^enZE(~ zat|=y1upHSbKpUHSYFyQCmv+^Wbob4v$HevYCp1k1bB;wm^T2I_>X^>c?WRGKleVu zJQG~PGbe@lkCy&+k1{_2-WL8I1-HxNGmo)+{kat4*M(lB&!F@ z-?N{&`!Wwa<{O@u z`Y}HNd5O0-Y2elP`wDn3_pfSz>lh?BnYbIU-M zPXHHtQvVI+gTO`q{eze<0+;&q!NJVioMQcA|EmmP{v^26k9Q4a-tiZfKZX3zIE}fT z?)pvUEl#t%wD;PAKLZ|t_x%FgPM3R!v7SuG-vxQ^aOUa^>)!-E6MPf+VuW+t2$r|g z<&n3T7yFg7s_|n_VkDq7#Vo#nM z&Aje!%x^*XJC9-h3gSV+xek1s#p{h_c{|*WbP4SbhmOb*tTD<9Ozqe`om! zyl?dh%=dsxd8s#%dBR1Om;8Sjye_!p&u#Cp{9~5<)Je>HTJkSU_OHLu6#sexr#jc1 z&&t~FJO2L_y`P!a`@-TsfH(NgS6=3`8d>~z$R~lzynwNzMt=*7mj-WT@tWXmEl$m6 zS5LCVJArqwI8}qLd?$;OS#^15i&Hjnd5XmsfOoa{M(`dM{~7#gi_3ggFN@23)(aMw z`K*2xm-(#z7MJ;~REx`e)*y?^d{&ypWj-q%+@8;xXmOd(%CNZ1XU(>_%x7hSOFohL ztSs<2%1`Ey`K%m^%RE&0PR^gAN9LiTz$rQ0L*|>JEiUs-g)JUK<;djQIB@A-*C%f3 z$Ci_lUA+m=|6o4+HSnI0?+p1F;O(Zdp5owNfp38PATQsjHjVwg2>Gdye+%5!lL`Jf zS1xQ zOHW%|>{2g_i(Pub;$oNjSzPQ=e~XJ5+=L;5>{CvsclAqO&zIIshbAZJqKL=Y} z@^iSwB|k@5T=H{_#U($-T3qsTX^TsKjNfqTUlK4bF#%HKX(F`d?NL13V0msv(&Sx7MFT9!_p)5>(mK7dz0(;$jDq!6lzuwFBUB$j?{pfW^;K zJ~!>*4Dh3Y{6N|F4UbhR<@>uJ33^((JW8dX=5#L&-V;32;^V<{z@uPLR)XiAVLcw` zIRbvh;t?}Aoa!vg({PP@)B{gD=bH~71|MPZA>bL{iHNxQE{|1F@%+BA2+t14XJ26b zGH!4gJjdddXCj=xvph``yGJ{h$Er-|kAnU_kWaYC@)8fzz^ht(9e5J>dgwm|{fQNQ z!(VI`hbQ=wZ~Qa?54U(X@Hp^(&_B}Uu`1irzXb9V|Mb47dWw7q>q$jIj(0ibt17zDb^S>PEK-z@sUgAqUHp+BmcZ~T;<$KgC$p7l%qX$gMJ;yuAt1(p}PG2Z2|DjoVI z9#%rWUp&i8{y75P-{KMTIXtQ0qQ9QYseD!E@QeP3A%CHwul^z6mn=RXTvcLu$v-=w zKi$%Q8S<%>ef3wShK{LE2U)xwcm{Yc#D5=`$Evs*9R4_@?=;9qC9wXh`5(NP#ZQ69 zfu|wCie;McQ2By>DZfozPXE8JD(e^C4LsB0Bf+!4(-Hn9E~oNU(>MR@g?w^#-}nh! z$nn#`;x)ljz!RXqqsuA$mj2fupH_qQOa7b%KFs2q!85=+N&bia#2bCXUv?3P^FmEu z{Vl;STD&K?x{>8$5uoudr|?_)S3*9v7RyWe9sw_F@raK(JW1eb2!B17Q~W3ThW}y6 zudmJerF;zm-(>Om;5p!FA)FC+fTuQMJz{4rgJ)U1@?s9BYRvK%5YBckr*PKda7sDt z1NjS0eB)sn_+^W)1CMLU@|4Zo;}m#y5_8dC>=T5inQwTSfM00t>u)#k%N8FA9(OCt z_d@zEaXF=LZGNw-_8;=;xB2Q1T*BcQZ}FPo8Q{s#-_hl70YKx{s+%!&0O+H*`*xL85VCz{966u)HbXK>XnR}4Y0WMi!WOID5a*cpMO|f z`o)*PC7hw;k&#z-_=aEl#Q_$t3He})-wGaXabqWp{wRw-0Ul#<=@-XZd@STkTb#_c zt3S@-8^J4D{Ach4i%Y+_y2YhmoM>_B7uU78^o#3TT>8b0EH3@xB#TSGxP`@~U)%~@ z>K*x>I@#jVFYaV<=@+M1T>8a5z$KqZzc>{YB0!@P*(@z^kv|@O1CO^0L0=Vere~vmrkUd{$SM{{;LC@CP4fF5x^2 zUZk6Ecq)Fz{(cTF{&ocK(A`&08hCgQUp=3KF98=l$HDJ>!dFk3&)Hx7By)-9cHr~D z$K$!WJ!NsJrv_SF>Zvy@F7?zPaIrs9 zPo-JBGzGxaFC#22^;EjWrJfpV@lMb)(c)51O|ke(kk7EV)KfDoF7?!Gi%UH<*Wyx7 zWm;V7sl^tTdTN=)rJnlC;!;m#SzPL=H5Qk8YQ4p!p4wz_si(5R?Rsjb#igFgvAEPz zM=dV(R4%yW6RD@v6P!Qekk4iOHqPQw@1%fBewKRYQH!6rPPv%)l>c(^j>V;1OtScI z*U=yRw152}7MJYMdVHS5*Uc0TdM_P2JZ zFTV|Z1$Y|dUjx52jOB-cF9rVwT;y}X?+s^pS)Y7E7W=ysd@%Gp2L4bXmY47ECWG$= ze;xAM!5@h5l`r%K^n;6hOYr^<%gg$`$B7#|oct{3PbrUMz<x3wl0;9%-kY06zr& zC&F2LHHT-vhyCpY-WdEAFY{NCjy=Ga=>J35o5%TFe*gc^#=egsp&{!SON_CPeQgXT zB-!^Ek}X@-F(gSs5)!iSTL>{pLP!W9J81~XmL&b2&)4IAKDYPl`R@Dv%^!Nd?{nsH zo$FlZI@k5w#VyX$;I-1CgZ*}w|F89~Q~!UTcb$FQ^0SMNAEeziMbvH*{%8JL{Yok- zUWj~a311Wu%s+Mc|MIi)fPeS1ijSM0F+RT5)qlzfcM|L9csUY3f5)Fm#pTbl@aK1X z_W7Jnyf4)3ySdz(kIS%+!~RovC8$yes^+k57Z&p}%kA zX9|2+OZjiS=03F>@=7qD0iWpOH{oHeg6->lE1lUs{xQ5z>tOpk@D)DZaKD!)xt#*M zud)FC4-fEg_dC7HH{)NpJgsAQ>pM<*?0*T^=W}Y2Z^oZ>H&R|6PJ!ETRuh+dd6<{D z+40mecyt^2Z{vO+?$4{52cv9!SMXbKs}DEf-G7mNI67h9OFs#I23`){Aw~Ab;4i^fqHp;#1)lqs?5kk^ zCEV}Num2DGyodky_$H3{_jr!+af@e?kK27mV|~1!+pae+c0ZQ?_I!Oyc&=w!1bSrq zitX_28O7~B+l%lOKKn{Xq~A2N?7I@59`LB#;u9=x@WWZf8^dqGxA^SqAC>;;P}#qR z{X6hld4l!t!_(uZjbp$Ml=S{raD{+^dJJ zeDCkQf_*;pO((~3>HFJ_ce$ri%ct{}@fg+B-1KWZIs?(S=Y1Yv-^yoS{e;?`?z4Z} z<$?3YiOSFN=qJN#!Rx`({P@4~JTmFu^Sro^Tb`Hj@ocWXm(LSQX;n)>m>g_?9-h3-*M2v#{_}2tKjX~gJ)Hmf%YW1P$hCKz?9R*&)UMgD2tIdU*ClVOUXo7tnOa$_K8%51DJLCUN6y2`|0Lz?_?i2%bap2+4Uh)# zelGXgZC+P#a}Q?%KkvXpUKEeR{s20s2S}$d{P`==kEx<@vH8;8<=MUcGxuNh!+sq0 zo0dwy8SOrRCnnShSWdz|`e*4k&ZGOy?E1wFcvKvicDpDO9(MIFv-^1$go`^~?P41OMhV`Dy$^c++H! zOEGjpZc0BTzw)p>ycK-=Tgvm5@GbD&g{1!s{3rOG@v^t|CFB-ySRR}Y72)y6q+@aD z4xjjoX1cq*3H)4#SB_AgMAPoW-=sgSsO+s@HE)YIAEUZA5S^9q-Xo-A^Zj>t#-|mB z|BLhQ(&@H908}PfLDIhC}3HM_-}&u%P#+w6^>K-fppe)(0sAHeHlKWv&Prm z<^_JfgI}7ec5Pm#{zE!<+DOOhUK99&rSjkS40uFd^*0m!dgq~ZN`I*FHT{F|SmJ5> z(x!jPeqB@PSo~MQA756SZGNSDB>TJzrEm6?;D5A{PBr|Q4nLGt`DuQp`Aa&98>-mC2m{chu+r8_ys)oW97qu<7#&*ItecK@*%ol@cdc}Z(dIMX7l$deB2<_ zf!*jw{4JgEsfxd?%e`Ih)zw_Ll@AqYHwpVGmo>h2T$B2VbVh|s$J!kL-yNy`+VS-c z`1qaj{|EGQ{v(~R=d^>e{BH#xQCj`7IFE)mUZ-}~(y#sS1p@J zNV~1!9}Wzjr(@xB$lJ2mZ-uv+qj;8p-+@0~rE#AIZ}61b&5EDZ;a|cZZB`r#!LPul zcb5LE@XR673A?N}Dr8HgU%U)IQB8Sb{w#zqYNT<@i%z{%(&_U+;}`~C4c|ROycqEe zbvHa--1g;HoGt!gX~b82ES`XU0z8THLKe60;Cq&lLwrIuK>f17S(-qRMjs1@<_wsqbUy7&g4-2M~{)xr1FMxeJ_>2si*ZbjX zUGC{5II3f<=k9|@1LbVsSq;|pes(s_Y4nSI@bH&qujskQl$oS+@0`ZH1pcpbc|k9p6%|iA zZ*va&8>bXEjhf@MaW8Oq@lSkK_Wkf@n9IHRw^%O!ZN2yoKD?3q9LG2o%_93!>=SIh zd<1WCM)@-m{ZsJ6tS=e`$LW|=IyH-_U7L>!;9>KE=iLE#%dPUq=5>Z_(m9`3o{M+Z*NonWgi+0{yr6zrK70dDdr{ot zpXX`m^s1>$ID*bS_@+|I2a9vXT(Yk|T=iL1&T%fe+>2Xd-|=$(XJlVtf^>?Z|0;Zb zsCYK`$M6ryL*qZeA5K!c2eI$!-f-^4VP-Amo2~oB^N1I#qk8LZ^8!D^;MX@O(`;N0 z!*5j5xVY&T_-W&Q(ALw>8mqXyC+sYSw|PzeJP-fjS=m=xqdd293=0>3rl96aA?$m? zr+p^+f#zZ6~}Q$M2Ru z7vT3gs71SGyjdf7T$1vzEc*T7xm#$3vg4X#@H<(wj%UTbU}3eJ^$*1% z1LJrcUSf&#Ek45`@ypn=W^JWDJI^ey>#q2t|z=i z4vkj>bk@R~J*&7`9+r%hPV7L%c?=!f1fMiW{;#CnhQ(#S>sRG%0r)8Rg0+gXvd(c1 z!f)IU9`{S|5ogse%ZJh>q<=3|^=c9Nn_ce3KbAUg@xP0G{xaHc^h>KhxK>g+8QEt> zpp&JP^11sl#pf+}9hZCKKB2tEU8{!Uw1#iHsrqmAY6bkkH1)JJI(y+I8fqLZZ*x8` z{VRK<^Hn1!Qu)+k0d(5I)0UM#Rv%`-! zpV`>A$tZi9cL(5M;}stp$FQ=}pLR!iwGOdT@QekNw^rYp!zZ6szbrl`_JRkk<{i@?~Z~x=u4c^Cgb-5S+xGeIs8u}l=_Y_rr z+WzEwc>L7hb@?v5&tUm!d6K1^^eewD{gUW6g5OT7c{c_=79NJa`SZE)!m{6t{e8Go zU4GiUC|_RfCQi~gcErA$%LDsBo`>oOe;0oHX~ic!{4;cN-DwmccK#%+g5sa6zT!|7 z`(iHl;#skX`rH30{o(|CTsGNf!~QY6ShC_~^|NqA>D25iuGPfdpTm=uidfxP>2fb0 zs*O}$>0ie=js5zT^2f%dXeH@Ss~(((ec(5~SKZi&pIhK3K3BVz|JUJnnrlAVd8gKu zrC+tD#w9B{i{W(|s@(zb^Y9DVv@S@^aXzl1ewE6n`liuwoF8279mnnSU6*_|M(rjv z)VSMx=>U)K8l2DBs>(j^dG*Ws+ZVo|jr_E@eE`3gO8Qo>Zow<(SKLm~uV&Sxe>GA1 zAHY9!xi?wPePT}K^HBJ2@P3nJuV_0?{@Sw7lq~)b ze_nBUU|;vP;&23>sE5*tL4OFm2Kyz;pA+yGD@p%P>?7+*Cv<^y zOg|AGmtS$)iv1jT{(IX0Sl##qM+4c%tW?~J z(e6l>d-XHHS0@)^eaVSXli;l$s=szTdkMa*fc%U` zzmt1Hz^k`^3|GI7!so(s|E=+|e*FZ$a7X%Mu+Py@I-}+&Vin-g@LsG(*6u4V_wu$? zX6e6<{b=l$^i&*d9<7Bx;{3nG;Q&0jf@Vs8bgIY6pVSqkZ+X}qe(Zw!TM+xT@HGcD zUS@w7-mAX$rCFJ$)f!3vy*$c8%iF>5-0WxcSMK#D_=s?kKhR0vSUNGkE1uTwoAA^5 zm4{{Va~`|_*BLEucf%+2mVE^Fcj1ZbA8OFEv-Txat;U(>FXQ9(LUiSU# zsK5K+^Whu*t{osH(ccbV!tq)d_Lt#P-_iJ*{~2GDex;9s$GtYZaTblQjr(?Z+V#x? z$~NEAHI+^{$0MC+w>A6%*PXk;KZalGs65F9KMgYQTwzM_WvDUlK!+^u>niV{{!%4o1`-moqR21-yn_h{1UtaJZfWb zp09yd{4%(X{Q=K9UG>D`9Qm^Ji`-RzeT?u4j;WyYTip1)tg z)BdJ$v^t-_QmgSR*-f09z^7yrO}C&>Sm*uUCZ z?Iw-XIGR5zT<+~RA}eeE5QY8M*e7zIiK6N_mtF3ygFAWeM?dT{wvm3-y1{j(BmCDZ z>X+$kf=>z!-futMRyw!lY1~_*-xBWMhkOQ~)G2tpvbOX540USx&Q~;axwmfC>J?nC z-h{WvBK{`rE`Wz@mOpkK;R5{9dW~;-^0s|@>F0Vzd6fyBFX7>fgX>;~4zll5Q+2Ed z_C4X}Mk``=9VdH7&6iPgWd8^DyIk(|>*x{Hfd%Ae{Z1OMnZA9?>n``~BXVfG!q7>E zcbcxeN`aT|?B$6Y&oM0nq%iztmwP%}o(qouqJX`7y{T&OzH~eGdp=U#Q0wkD2D?b7 z#WKa&jxPqlJCu??mUO3hUK ztqzZapWdbMvg7g9F8Atrjqfzy$J4K)*hh_5owRmyCP@D?u4@;;ei*!b5$SA&&w%&p zrh49r_3kYE`dN)*dF-?Fl>X2n>Q`-eZFsj2g8g|9?!VvQBK%A)<(tJ}b1&();5@Cx z|1rGMs^Gd;_chr!;65l-3CCFqk6@pl6F&>|mVK?h^0N~>&gFsm$ooGd;e)XsHC2Av zaq&)ggQujUD&bx)eqH(lZYnb7e-wN{xbmmG z^V>IF?#=55fB)xyiVRY_alW{9 zgfAPdxY@iu3x9A^ygFjxgQYVdrz|bsI>8V2)js^&H2Q<4LuB8vkLE=JIzwFUjZ1?E zikqsO7*Y6l-Th=!-e;Shetm8B$%HLoUJnSdFtNbhj{{|j&NZjIOZs_HBvfF-_gE0cRKx|@+k3x zSNZvU&FlykbVpufnujG*NL*_)PYF;H_Nl#b@$b^~;X; z7s9u!P`la4!{^6HXIeAmv$fmQ<(|%*aAmmhsqiUW*S3Aja`;4^f>ae`hfO1g^--?axb4NMk+oX;k&SpdO1EoEPpb+C7mbH>X*f#Bz#&I<$1}p5_%Ut zpoerU4#(hwXQ*yZrrmPmr9anqAJIa1XdTT*^XCRU7th7iM5of*>Q~Fg>Q@51h0DFT zJ!1c3>&Qy@s^uETG1y;)_y0C{eXKJr>`iIr{M3y+dU)yyTG@@$1Ro4GWZSnzLzwpE{>>)x$Lhd2c$;yuw0&BhMfkH{_1w<;4T2{wR3t6` z*TCDgQ@gf*F11)Xp#_y!r^%B|@aA#qudNp$OH^;i<&i(9iCbNld-+zGDi|~)us4m$&Dz{X1H8GFoo#lBGmwW9_EH6LJejhw-i27ygOYUWw zzpZ@dW6QYQ(;3)SI?2qhbuRbT@tplMf6wCoN$g8dx2>KxTP~efPb%LmpGUzrL&RuY-p4nCmvpe`$(;BEP%i0 z+duyaUocbpR)4y!lYZ8nQnu?*Pp=oB{+w1!RSCx#1mD(1_1TVF&%rnQo_DLcK{_d1 zr_ii%oF(uFB~)i@eNTq_@6UPWGwI~osdm?=Qh;{Buh!T2_91SmHp)JKsrUdX46g}~ z+#^qHe22K)+s9UBAFJx*I8U%IGC=#QZM3^-lk^{5mX6J%yYNe#-#dwYrOmS6lvnYz z{r@3&#rBGW)xCnB%f7iIZs+$}!XrLY{%Dpt&QN&cy0W)I5%QK`mY)o}a?M;XYo|-wscHM*j4}{u=yJPDMC|dewHT+RfQX z^U?NQYvJc_*A6Hsd)@m3UGCMluwo)lqkj|o)NQ3>$E_8&Nq^_!x&cdz=XiLN#liD# zFFf^^;x@h|zfikL1DXYNUdI0+F8AhpyH7P!O5@KGxc|BJ$8i7sZ*8|rC%^AGnjP?5 zYc%c_pL9E9e~#x~+tF?#c?paFY z>BaMZDf_EEG`^G2X#-y}OZxiPagM`h3C~z%KNGOO2H&zpI&0t&dllz_q2j&a zOc*S!ePx3A7w`*TNTCE9go8?0cd>hyO zi{j55_?=qnulb(>zx1VMob9hN{UH5}A89`m$Npq9ybH$#mJgke$^NaSs(T;M?oxOs z=8?6V=eX>T)d>tA? zhH8JMUOUdpAEkek_eZJMjYL4?6{L0(% zM^SQ|pWu;~w9~Wu_bUD*{U@ho{|bIihi~-le{!FZ{jf;&YYgK!0iMLVW7lzR!=oq3 z-rk20byhlQ2PpnluUf*p@Z6>KcL2P`>zco+qKE&PjhjS7lT#`V|j9 z-AM}D;N9WjUFDChr)%LAmx|l?o`A=-4enRo^IpCE@1N2x_r|g5HpTg8Ox}do<2`29 z-_)_jXKb6(t440(;OB=Oob)yG7x|wEZbchX-HR zD7@lXDYQAVoSU z&uUy|!AHYOJd(bR*D?60p~`cMvvW;4X;Y-Xg8nvx`=65<3(r-hPM}50?e*|dzV|gX zxi0;+?<#I~eW4Hh4EOPxKRe-h3#x7pqF)7ml}?2&YS-*vgdeyoZu4;v{N(|`_VeJW zxi7aA`sr>+f6a8w$C~i|@K5(E&OP9(;O#zCMV$`Md{a7`udDu8{0GCIuBkk<{I7CL z_UUGdTfaVnukby0a|%9$d6$=V%l{^wtK64p=X3hQbNikzxDRizL-}vV%LQ&r=k^}0 z3uDu(ftm0Ip~@d?cP+fYV8!P)d0ygo>GyA^!oq*o_ z-CRk2M$q4R@RS(M(_SI^Mf6?Sch4g~?R`gy@PP%C4;G)9@M*`SZ}aYJ_#MV&9qnem zC;i#nC#+fTUI&C{uA$?F5~=kE8Sl&fLUHwIBk?HNfG>M3-{lD)fZlGsp1osN`H{^59#=yvo7m$@3`RfZN<&v9EZJs9N&Zc-+Q(Z zp3_mB?Yzn@_`1y+UyEnchw^9YRN4PYzh=RAA6MP5{liswa)RQs4Ewl0rL%dk;?oO0 z3|{Vp=4m+bJO&@ea}!p_{)CVJRQZ_+oqUg^U+6*Y0I_ws9K1^mBbZiyknb_+;0~BE#8LbrY)Xj;ITaCV(V-?{8A?A+i}WA@ETm#%SOA~ z;90}8PT9Kl)DyKE&hg;?^%ow8pEiF-!|zR1oUP8Uhx?z8I1W!}uegP#mqVBSQM*e9 zh}-qSI44!04qWW3$Yf+3H@Vz9E=cRUzIF}!TgBr8!dB1oJtdvlqm+kMpKHVW@Sc!p z;xiS#y{y``dGQ(i*n7%Di`#GTCYKd|tLMc+)b1MIC!<}N<9q>MvRC#AwEGZ#f#=rk zd{Nz0(#iOj*6TvpFK~IN`#p~Ib?pj*ez6?;{gZ;yc_lh(P^4i_MKMCe~ZIvmj|9( z;d|Eous?=<_nB%}|2j_BbkgzHu_f?Z+}Ca6xDlSQkMg7p`sd+mda6!Z-FOVoe_Sov zxU@~Lb}NsTj^)p2c!#Qrzws~O~e42 zj6b4!s8zsm-i2@6BOR-gtKr)l$)7RSF1%wi@#o=HGBPfyRj*3Ili-bKC_bg&d*NNT zs-CZgr_Lmu4u|Bw^>+-sDd$P74%f*n`}z5T^Z65a;$!W53!?92NfkJ5n&Nxj{0*0T z@mW<5;v4tL&)3np2w(H8+BJV1_W>gBzWqd=qp@+1aJi@dg!3n6pFdPQ zG=GDD@|);ah4+h6oHaU*(;c4lp6a2!m*6-&ytC}>yk)8E(l7Ok{GUQTtc1_IqPk(n z^^f6$8%U=o{@iyr44(ftvdhmM@D(}4i#!(`|EQee$=6jk)?z;dUXSv~u zl747D<+H`VGyLQe*;{-j!WR(#F!XoBBkn8Cw!UP1M*7?T(ztZN{#}>b-+}`FS%`hw zY0}YOInHBvC!Tw?b-7q>>2Kt`x_a%t2LQgdqI5EZsFk1Lv$?Jo~J4 zstuN(=1(Jd9QSFPek=H}PRciByW@<2&wSh{pq!2Q@-=+%74_>V?K;U`?{Bv{umc_$Cw=q(nS9dE%z24&=r4pf=RAhx!*%%n!HUn+H2Q;M`IY~> z3aAdZNF|=${Q$5xucK?q|2ybUf&bQA^ViNNoQF^LU8nd9p1+mG*UpdCD_qh&KGaJUA0U>uSqe+%{j2JijaPMe{g0GCmFd?!_=wD^leTW|gAY8WIK*M! zs)+PsKa~HkkZ<3?mv2yiZU1}=J}^Ybk9Pg5X;JB1{Y;TOOTU)DyS^$vE1`cAo;8Ew zQw{sP5z_I$ceEvZ=s@Y1KZD_wC&^DczCHn;a!UQR^L1T|NqjX&UGC}h?yor9PAmKF zC1k&k`>E`{<)2;d*+1B!@wNK~o0Y_$-Ksxt5zi6u66cgZ(eO{<{`)%a!6SK}MgsQF zx)($O{pI~y+2Jq23$ahG4L<_E#d&F~dm+y&p0$oBPn31;dsJNR=@+Q0aZxnf_Y}d4 zj#oUbE?t11IG{LOqTPz6rL%zb(c&}6<=(#NHv6KS*uRH;y>n_Y9R345HbMHGsaJ!_ zNZ)@wJsCb>h~jK<`x$=EcfPt*lyv;>w;2In;d>5c7u^4znM`G+GlTc5N8o=QmwWZ3 z(;KQ(!{L3fA3Ro(x8vCp@FhEx=e94(87=)uoR_fpRDu^;ES+xXPlV^rpz*T(d@?+2 zrSh{F_JztxKO^5w&~F{58$2)fXV$`g9^8N4X(K#8`$mgH@$%B2-ckGN1|bq!4WHXb ze%ku`D}2IA#bFHX7Ox;3|8=fG@I#!REQI|*xc@yoPgj)Amz~wF<#Rpwnv}SJLT%Q~ zY?Wjm!}U}BmE%l>ALKpZrgH{9l=DT#%T<=nmIaEiowu0)A4Y%8{s`QE9d<+&>HK&@ z^Tq71y4=gR527@$Yf>klU|)py|3nd=wlUI~{*roR^75Cvzlxkvg;Of$O&9}eW0na%` z`c=@s3ZKS(J2sCpyC0DD>fUX58SJOSlew;14t@sy&eN)s(eOMqr88)yB6bSi7+!6I z#@*Jn_u&JMY5hvU{=Un-^H;rn=dYU9l7426L#jzSJD2L2cO|Y!@F;w)J8% zeA-F*Z}%ts43AoaQJlEQU|vILO+)2=6jc^}Jwe z=_l2d{+u_0>-KW^&fiquH2RJ+x}NOM-cr6RvYVo4+KT!MtzT_L-wy z?)9tVCPi#6F06NX;JH8FdoWI+(~bANsG7O&b8ex1egWQFk_Vl^F8BQ3?mJI=#N}R| ztnuYZwwGn^e;-tDmwSG0e8Rk-Ums(C=di}t^6(t|@e@^yxA3QUOX)l*pt@9q{Hg77 z&(EZF+Q}rP(jVM````c2?-kjnPpdpBi2f{igN+*BFW{$)7nQxOk7-*;C+sQtZ+Q{{ zciz&vY3HL}hc7;+8J!>hcNp&~eanX%@VFA{*E`s^ZLN0w$5V^ollcya`Ewo~eoJ}S znto+&Bb^lX71@YeQ+Vd_ii7F&hR-ddd7&(IoU!okugU*O=zj_Sw2Q{e`gIlFYJn8i z)9&!L@@IUC@;MQmAK}wDZ*TsTXeawgk<9{@RtLJkD{@}W&M$3+PySi!&RX!@~5u2H_({iR)9?&&0dt#NTbRvP$u7yA+1&un#L0lam6jaOgVt=viak(m_F ze(+iFjeIxFbZ)`pi^!i2*ync-{Jr=z=Dten@5}Jp(V7>Q&%5D$eD8a_3-7cyHlXbO z-@wo4E~;-2ea|)Tb-CB>j4+-5w{FK$`CSNu=l|8nd*f2;9b z4gU@P!CuYZ_VCHwq<=Jbu>Lpj6yN(gB3_lf|GQcp;kU17TrSh!AK-mn(R``HK74F< z`Jebm*1Oz`ga7@LJ$i`8a-XWri@ET$&ud=HM&~U2C%$u32wpxxI>$-3~8xE_i)x&`Ua}&uCoizJlxU zDKV-)TIC%l^J}snx=j7G=amxR1G!#id9n#U*mwW%HF%Tzbpw$pMtq`rYduYTO-E|a zz#F;T8yElg>E4C^(^%(+?fS@f@H*W8tmrvTkJqKMj_=^uIDQJx>AOE??c!`=Z~3`|m5h=5lZUkjrXj*e5nPIq)>Pf)vM`NhZR9G#~A)`suE z-v9otzp=kwNIIvnui++!H(ob<`-@%ILs`Fvk z9~&Wk|M}Z_BgOal?wid%O1yY|=~P3fK70VrkHo-7!l(SDk!lN{2k-rcbh5!ykCy(f z9Ga(AZ$E*D&QhE$&#%H~XHz_Tp_3y~IxQNh4$KPCFDAnMb@CEC*LmetM|ARykxteS z`I!mc5B>??>9BUE!B6g0yOprt39tHC^U>m8-#t+B#&=D;^sS!nbh$TQ`c05OHtyH3 zueMm+{j77~Ct|GDyMDbjL+$vnuFF0BXr3Q8|BH#}!0yED96YwN;<+DQV!U+bhs$37I?jvm zwCfdT^YbmZ|GQ?J;g5XZ*SH4nwo^J*$GX0)cH1Rrylh;)fbT!69ggj*D^8I8-1mcZ zlHmUDtsH=_Xs9?_eZB`@z;`G*5r+!zNWV1qliPWoR`8FDX$Ais`;+j+JXbOcUUZ^# zhA&XNwts66&(HgBt-s&G>-?krfSp%)0zW~2tDxWIUFj$Bz98GTZ*#eq=Q*n@K5Lk# z1t-aVJ@2)!b#|%Cz5FatNb5yE^bcV_x0&{DE6~aCo^+1!9bvm}z6|dFZtw3d_nr@0 z=evI0XtH#+6^#qDIEDRx*7wEVJKGBQ`4jdzf6%&L zh<-&+k-q=A_31A6*001Os*||mEX4lC``XWF6?2?xaR2+>b5E82fIVur9R4(guWF!q zZS{5*d>`kxt&XjN_bQ>4(cagWFirZY<8&U$j-$82V2cDWb-TxB&bUD5A>eR4>h0I_^t43FV?E8E}x z3=iY`o90jGhiZ2M-}AM6=w_-{&TA2%i#0jp6%AH@xSsM@!|E9SAF42;kQ~T z&ZeL36WROU?-U33KaVpLem_a=n$BtXP~J~y$G_&h0x!l`_-2Y0EpO#U-$n~jb|KC5wUGCXW;XQR_ zF^PwFDX#dNKg;0H@I52D&+1qB4EA01(0OHn^ml(7Jim6slirh`Z(x50zKrt^Hea$X zl+JAKbL)hC4E$6H#nbY3I^2IB`xbcoIr(Gjc*G*<`@i!z1fGiTjcOF!`&wP@&9BH| zYIkvn9BQ;!I=!xG|7`oczVLn{wXPjaCHvw_q;rMyaw+tyC%i~u#piYS43~T3<6gm>81I*}I`9(w67M%iqM-C$Ci@3%l;?_)}VK&l*`fk6IVLh3Aa=WB;1V|7{*k#s1MUjn_f!x52-!r(n9JoyLvsqiTW)UWaIUGN#n^552lyYK-mm7lh+sJ2G>(>tqfyoydY_^6v&!R@#* z5q@T<^5GhJn`NzZwr5eh1<@%Ff5`KXcDCUImj|9Zcwfg&y|GWVPCB!A?!)q}8ro0kKgh<)G73DqEly<#>LkCa_iM@M&4I%*4kIj+ptGX#+YhD$Z61TDaVszu}y3G@Ww+dm8(X|J=boVYk*V+t+3P zOggcJ6|v6z&GYcEfy%cm)TNd1v=cRtY~S?{e1E;*{b%e(>HE)bC%L>}NVt>2d8G8T zI~)7KeAnB?z2qk8)ZlxCR(~47=kT6{(&!|>9~IU-wQ-pSubNK#@M_qfhcD=^b;|nN zezV%$oJaYoU77oQ0lX*g-?O=#<#X9b9+!@Nuj);B?h5iJEA1|Z&+ab12!0uUdWqt1 z`nk49KbP-)GOxqyOwc%5{!E7V*(iVPKFrKpb=)+;cb{-kmwS18t*P=&qwF}%UGC-E zlU~Z7w)ok8oA@sy#jS44hc~aTx@yN?UB8gM|2@Wg;NAF6ocaGZyu~>AQ-F4(wo7Nk zPr?121&|4S+ zeXY7z2tF8ovb4tC^k=x-i~q8diu_sZKgZtxzPRFFs@>^JWIr7HAujiHLN*7_$7|T< z&ZGRdy3uT>bY^B$p4j=2oi6u|uTy;A@w|b3cb+$~`Bm^M>D>NJ@i+aI@Q&|j94-H^ z!sFuAu01!=cb9ag9#j5*K)*J@4}PL}Y87yt3SY}UYKQdqWB&pCtESpXT09TB+>1{G z-cMBvduO+FnsR;L)}yv?|Mx(*x!jA-eBXP{i+&@W37iipj{dvwqul>&b?jUCD9%e) z#y;O3>GbivH*7F`4ev>_Ljlv=d$y6SQ- z&inYjo5d$&zuHaq9kN)It!2QpyZ-OWBeS~t@pM!7UIYFzpRew;s2SPPZ?f7LF{P8BOgLy+F^b>sY zc;&hNb)0m^G%h=Ds&3f*lZ9OF<>3k5A8T=Y6~2c1(~K{GpNUX>%+IHeOJ@M@p|bha z9bTZA;@^q>E{D(NIZ)$Y!>92+_89EbpFsa><&VWJ9{$oD>D&2}1@Kbk>IW1aXOK|g zAEo1ekHP2g$%_anlXyn1Hx+}YJtKavoz~MK@W$|D z-}4~z;YBiNd_!0lK0Yg*LluM9oh$H5d}n++`gzaEeqd$kn4d4h3;DihIv$?&4~=hz z)Dnt0FP$q~ueANiNO=5MjaRkwvcCfF#eMQw@h9sA)~^z(B>mtOT<+z6((}rnQt&45 z@zj$G@ILU(yvMsVd@_7uE{)VS=3|MA(r?g9op_gf{%_}bE}N%);r-&JZ|m}L_yXQD@C7;*E~670Jg<+yyDw5DX@mVUS7iUq z2<_k8^b7nffuH8SBem{c2Z3+!Jug}6XXz|yruwhmInL|wU2kdsY5B7dzM1O|7Po9y zrSoMy%_HMQ;GK^vZ>!;dH~8_6inFapW8sUaw>FQyg(scTy7L9|BJvltdu@Vr2BY5| z?!*SqmnHChqm?Ia*$@20rATM!PUUlHbh^XuasR62eD9|;LqNY zPQDJB7si{y7xI2r<3r%}K2&@x|IfhhalPL1lulV1^9loPv{aOJZ_MFy>e&~M( zPrMskH-2}ymp?^ni+4u9;T`FBU#)pD5}oPrX}eyj~>s&)${JrE?m`N${3% z|MMmv!bd!jKNj=v;q6Am1{CbMwpZ^-zbVgUSUgw5yTk_9`Cs9sKhXZx-m7r@zH}PA zrE$0Xc?3`9Ijm9mU*Li4lMXAN%fR1&*W>;KTi4FI+>7&s*4qEyz`pt)(iwbPJQV&A zo{HxPYMzT%KyUH_k;WI|KAFq9wR?({}%G6bi!7OKaWmF`0Z_qTaI-4Me0Yg zpK(JyTAo(?0sKqevs4A#A7H@N@1jo-Q4+pi97s`E=WUKg;R zzgYdU`XBy8`k8O5Uv?Z610TbEAU3``;Inyttswqfhi^`$e${~2_(%GkPAh*Vzz@MQ zu+J|9FY2TY)T>t9hf@^Z0e<*7<-h)QpSOaSpRM`W9Q&2CG zO6}&Ht99Jg!FBK-Ppd_%Ggsh~IPQy}-RDB2bCCCr+P{KFz?0Os z5~-x)@Ldnf|0=1){r43o!NVG=4j(~(Od8oYF0FQdXCM#3W)3G5%i=W`!Uet4_2 z(g`o4@ht}b8$M&c))Bk^q((Z~AO1;s+XMT~@FcE-+xor=eu3{0**F$RFP-ZbG`?NX znFEhqsJPiU-hpQws&;MO6>|?vy!tloq2jYVjf94~+*=>(Y>-Z`5b>-T#kcajq2+%k z_}mZWp`zh9`{8YJh*;hG6YhV%ZqZEA?>69_x>pr89+b zv3N#gfjjE2?Qe&`lR3|3>(^{}1kWv6{13o0^S<}h#6Nvj>0jqLeQUQWycg%GY#;b0 z{0ZN2v*U$*@MA6F1Io6)N|jCeOS>ta7XSM2$WZZK_|q5e|6cI>F89XW;r^vu*zd&t zVQwAo56+-p)Cf%-IA1!&cRy!umwS1Vepzt+T;Xz0e&Bsz9a;Odb)v;ILOL*=;tApcQh0l3T@v-?>^f~Edj8c3oZ|lI9_{Om{Jf7q0D)=)7{u}R= z4TtZCHyOS|a`?`f2s*9DJtlzJ+{|(yy^cbxBcmoX#%)w|pLieW>sLfobr5b2MLU|GW*poA2Zn zV_nWyTPcoH|{${=(ZSj8*ewy=LC5YQ# zcogqjuytVzd_30yZQh-MPq?FeD~3+7l4>`misEU&_kcIljyA6*|$S)$XNI((eu*^cw?s7$kQ?xQ*gxzkd#xsp zQ>2XS5C16pAF+SIuB>pJ1=v?)UABG8ukgOS&(P|8 zM0x4gYpA+m$FtMmCq7Z#v-ftUt04OdyOeKVr`Eu{4IkV`+~Ro|zK-_{OU-ebRFqB) z-+L-n!yC6&oX!6S@H>Tq*M-uR{=H7tcDa{_8FOjBor(OJ3Lo-Ve#Ym}FK$$p{e~kt zF0=1|bgLrX;!Ta09apY|JA7x#>e8?9tK*c1R#yweNT+GE{4b9`E#T)qlD^IB(eM*| zkJ!$S&4<^Rtoay+&Sm%~2gGgt%~4hDUhSrM_Qk$GJjM5(if`aoHfg?uQBQhRlaBwr zom1hlyywL7c`f|OKKY~Fm*e~Z53QsA+W3Z7m;Sg8s@sY9*&g0zz4%%9M0oUM%{!~N z$KaRv9+t(Yat-NE;Qno^4==(quaka7^pC-l9O;jN=cp;25jkZ)()@(isi*Os1pf?v ziSx!5pUd!FTnD%L9$HKKGqWo`FK~X~WB9>N%3EtU8D4<>mArMFO0}i4FTaT8f0a7o z8?(sIkf-G6Ab91NVE?~?XYQ{2G5<5vl}_Aw?Q^s%bDX8{)FTuhyY3lYPxgCjN@qCn zc@=)0>+h4{AHx0L%MPnAoeiZ_uWTH2Im5x{-wbEAT_B z)zcmDF>wF)-!sNa$NwJh7vMd(kHW_BE%+kF*T!)NJa-Z0oB4AEK6A0+mY)1+*--7C z{7UmZJARIWxBN-_1UnzT7ar&PUiRuZ>1^wv{I@!G48CBNxXqW;jbxwR_kR9~@CUE3 z?o-FY8_Rz7Sgk~#;{R-Tx{2!VIsCr|pLnXjl9|$jXT7GthFN0s@ zy`~y{$N3Z9-S^$Y%JI_oKOfx(KAP(?HjW>{bNimtzY0IsQ2v;G*o)F17_I(B;b%$s zsPW1-8?RU39eD0IANE7wStF!x^?WD%m;IVA)v!;~RPFxyyV|w!Ed}?#7b^k2hU2Md zbY{UbE>K>zhM$M~pT~@8rgr`BS?UjO=gXh#@NKnKPwaU7h2}bMaGmo8q>uBa%f0=^ zwm-De_2w79!>c#fyteokd`b3|d5+2U332e0Vahk{UL0o~JeK1-+h1LTKmV=t3lWD( zEu=q+_kNUykA{a|RNU-5;U<@R`^o9gh#$iKH1<~piCf+leOdZZy!XR&>cRcr*_;PY z-BR({iT*YCme({-?L1GNmeTjXw|~FOJwK=MTw85)!d{VmEuK4$hR4F&4V3?7;p5=f z-_w52;`WovJ^j!~)oshqr&~#X#U71IadhI~SJ;o){&of2{~pv7_+8#t)(@RRty8<# zPjfr1a;pNjf;VuvmsbOaX?|I|li|mxhqmq9YX zKY&l-J28t1gHNGfp{?}W@g8`~hpzBW*OWQ^(&`Udx0C(k`oZ&SGyK|i1*>SPRoZH@Lm1YU(1I<@M!LzH2c0Cl@AyAuJ;i1KXkb_ zF1Pr8qRq#j;r{c(r8~)f(kS)oJLIi9lm*#lm#l=A8y;`W8h!}#0({LcmKcac{b1;@$KTkSSpr#Rd9M_R!rbymMj z^BuVVJ*&&%{_j421^37EGW_Hg#o6ji#n;tF@c%fxJMRxqgby4f`$b(ePpiYfgRdSI zye}#;SoZ$+2fhj)QAX|B`IE>YvhU`5zu6G@e9pVtxa@_;Y*pO8z@N-RrPF1;#@EKZ zEZqNHxp?@hk(#GZqcaR%x|YV>>fu^=)Juwk#ku2~YIhCK0X0PDU3i@Dcx@{@1K(S> z`gXzP-hFZFrf7VvzyDw#Jzf18gns8?YBxMi8EExt1-vZxznT6K_~Rc{AFK{I!==-< zZE)W9gs&bdZu`u+@Xc8j2jeO5@FeBi`ZRL%_z3A2>aQ8shy|(tNbyzGrDOiAhi6RG zxY#%zhaYOA{#rfHFiJWzecutN2VcSWI8=okXCl1nIgxe5^9+2p?>s}?Xz7P=Jq7oj z*Ie$cJGcH;U0ujLU4;D;z8|Mq?|#oTQ98ROt4>DKZVEiPNpQb%kCAPcz*+zrqArgZE&UA1x2pI=zx7=!&# zxc~ir2jKPMWN+^ek92&x)<9;=rgmz1^wml3BK=l zoQH>((ag2`!3Ir|PWQZ;FBYFWF8A&?XzDxO$@`w{H~QY2o#1jWo@t*`J@0`(^RX{c zLi5_L<6Oc1!Xw3hGxixKOTS5bjjxS+UAX_d@XO($T*o*6pMGCDCst`awR|fNj|o%V z9?HID5PZ#M#b3Q}oHg)1qh)XT|0~>o-(#jJYWLw!>aU$I?FKJBUEK0&A3UnK@}v`S z$T(Fx`+eV&4Vfmsajfi%V_yTFa#i(8-n!4N!~O50z6@{7b$0!g<3xNQ{T!U{wfM)v zU(PH4v(oPS@HQuu`8F?3!PBNF{wqTC2PLLUfABV~*S5Y7gdcuW`I!a#JMf&mx5wh& z|3m2{M5^7L`12F|sg{b5`I&8o?AP4Ve!C3z<>4!ySN$2tdN&_FEJ^ub^X?`*SMlKW zqT)x=@5c3OJO4Qoo^y`uZTXw$a_|1M2fp*n8Rkf5`v>ZmM$>WLfX^7LIESG#8@?#5 z>ZiSbKL029vrP8#%5iGL3$@U=JVEDU_~|f>i=D4dKUX@XeD!A$yj)l5Se$Ret7Vgp z)qx80q!Z44O;*Q-z*|PjL+jUO__n{}10LG(;{*7y4%&|u!T)yirN52iJ8SoCc)y&g z|27|wz}F?nf4l#o!Kc!x!F>)T&>sUYQc?M1`8fl=xu5*8ejRbScU&+fv1LHP&cpnQ zeO#jYYxSh(0_8(i-}$0hF8A^|J@eX*zt+K5El_=!gP#=^%HH96vE_3jeCPP!ee4Xl z|NXHC;M;xQp?C=2zd`lQ*1Haiw2yk|dtd7mmwWyfX{I>O!p~za_tw)r4V34--~|@T zKB11{oC#hFp0!DEU3v#TFu&^C57_U8ui!lrRu3=0WA-R+c0HoX62-rzFaEE&-1GlV zmf-wsy;Qtjef7)6eKveWCFPsdhacfneEZ3$Wzq>9s`;{n`n&+Xlk=sve*Fw@RZQ(# z9qzweI$JMkA8vW_J>36(?BC)3_ux*syZP3OSFEG?V);J_ z{@{wn-S#tQ;r{o3hHQ{dm4fQ8-B&gde&fFMZJ+-mJhkt>i_p)cQ=_`-Np9BnHZJ#$ z%N)L&7K;B9uwRx>{Z%z^kJI7)_YlTzlztM|3oPGy!DqD7yta9I1b&t86HTVww40Rw z{_h<`!aF3%6Vqwna<6V2EMG66P&b=|j>1go%rs}vR~qRzBP?|fbZ#4TOn%KzNgl1i}b^M@825^Z*xWU+1AZ(;JJTMow0achR@lf zd{(a=Cv>ay{qK!$2lt<^*y{4Yxck&Ts zsMh5?*l%&USKsD8RDb8fzdjeq|0qDge!snq}r}_XO32!&89AVe=E&9tHa4I_xg3Fy6U#s{{lZ$U;TYZ zBV~6;e?uMhw=H}${JYNTm&JJvJe=cS%ZK0LYq(F+*2nD0()T~F@w&^s4BAD+BW@zlSLQ}rw9T_N$!#nUEdy8A-F6sEcquL(cAw=t` zT5;b$3?KNt>ZH~Am%o-yCf@7Vigs7R(|#k*%fWwv`@d6AemDO3-rq6=p1}9cqS09k zPu)Ja-ah?}bo|fTz6MX>eR{UOFL!wun*aHq9oV-l7azb@Cr`mo^BrfKcfQV)q?FR2QPjS|+$#JH`pZ-$3 z7xtUsz3QsM*nZ%;%e~{rINyFX|F>$l_ipKE);mruxc__E6X6SXD-S!;?sxFiA8Y?$ z>v-P%($76ld1dEyr@>F~{p<4R?1De$e45pVS_f2zJEbUZtzUy&?yYy5%MC@*HI-{hbJ3_IINIvE%DQ@NtJ!w{73}x68ft?lAkDD0K3CFa6$^82JxP)+Nw#dsmc}j#`AD`TNs=T9Nx%D^*Yo;3 zzH>g0pFjG1zt8tIuXFC}T<1FHzVCCN1K-I$cow%ckIVjcLFw2yH4R=gMCH~&{}?>A zs`7))uOk1WetpyVZn2HegL)=5R*$yt^@jL7=r0M*ceoqiTW+d-Cs6Kr_*%}58Uz0q ze%^VX+wO$)L+Fn-{}~6*7OM!cbqhy)9@KNv(`pyrT^axW#(n_#Kb&$O{YLiTuj{%l z!aMssxUTWscNc#%u7dAISePl=~$-dZ*$@%X+jXVG7qfosW%AhTr=?%?vaZYG@G!j6-@2~SIaHyt zXJp@GjO;C*pNAjpr+Bu0(I4(Tr1r9P5vSpikE;INxZYf6rGK2~coruWeIAT=*%d3Ajr^sk*a)V^!6e-3;1JB3N` zna(*}JK@#GOSxrM2|fC~^cNhHAKpd(MV|-$Y1KG$zFG}WX1~E$?0~tq z>_yq%oS=Sc?b{K4m;FdfQ0`QCGUozVK3M@D$#d!A*zbVHW>I`vzrF+y+p2onJSzT2 z)h9RKJ(WdgA^gdY)b4lS*Ws>Ct4q>}bJmNl^?81OfBt0WoX73hZ*jiY%kqT;+ zJ`eo4w5t4Ym2wYaKXyar>#Fj*bP|}i*nIT`_^B>xuUY7P3Xhv29rN3tJ`c*xJ5ljm zHIM#a=nd&V=903TegD31&`&t~%hsUx{n(5zyFJS-banvXJFX>0s zl>diwz0GfnFK7LE2kckD-Se&XzPAM1zwANbSuI0+>w5E)~$^+dw5(M#gD~v z^}Cv9#yRU=p7(hW598mL-)vsJ8eX)z`kndVh|h!g99>a)Y%JyG`&&9ScQ(%;4VhQW z^?6`Fe~fx`5((}E_A3~FO~24R=`5VAcBzhjKe)R-d8N+-{dW0fZ}Wt&us`{)#`mJ= zl=?^ZwK)H-A-ti_13%PxOL3*B_Ph!3)fWpcNSOtgk!$}-u<#hg!1rT;jwiT zw_n4%c@JdxA#I>Y0Rn#7~N6+ZX5n8cN6UCuaEp}@%aTjdrNV9F8a66gFJJ- zf##*5=r_(I{nhOEYx;BHcb)O>1bluYMU-7{_6McYpLJ`|=r@FiJL~6{!0)m?%I0Ht z;gwj=Z}l&oSNhkUQ9reHj6HlF`1$6r#EcS;=2XGAus_cJX_u+bhZj!?fiM&2mz^B^w`I;uFd z_e68y3pppK1ogQDclR|NT0lD4o|nGGXFA+{Zjig6><9m(`rG=$cJO~9RG*%dI~nfg zlW*VySdU@z$%hI_KP9{JTN!j(zzZZwzdYmhWq7rX%I7w|KT}vbv45!lmO^J5ynh?% zKLqa;A^QugGq?QtHoPh4rP?_1DZC)>xvc(o;OpWPpJrdJi1bTUiq9x<7Ud3xhZ0vB z#XRpYyxKX{-{#d16_w60)~#85)`T~4*6GE=^S{|RqeSaRL*UzT$PZTk{qSC&%AdB+ z%yY$5uDgzFA$-q%wM#Xw>nc3=4qcJGr!E~Sop8RdFOB_^@MzB0uy$Vqcc0IP7MISY zkt)~x*#f?4vHGL#o;+`+&x7|h(R{}pM!9RSKNl)X%ac{3q(7MVV)k6C4LphUW8vrw zg-_q5d~4&*et2chxsJuY*u&EAUs3iO;BDaRKG6N@#n9xMYlUs=udv(gFPe z@X@+JhHs;1KcD3tfQXG%Bb92*JT+;T#YF!KA@=dQ?XwO zUpzqVXzhCjUiJm~=XLB$meV+uP+k4*Z}>o;2mU$etS8wCzgJsvZgE(=yzJd|K~3Q9 zzHKkS7jS+@H08btkK#OcdCBtzbvVc36${jKx5-a7Em3aZac_6M{4Sq1*@ z&CLC7F#H<(n^}MS+vmYN;b49FCky^hswn+SI~0c&53}GqTPv<|ali9yCFyLLpn6(7 zul0H0=N)5IpWmqepV(LX`PmFoiE;~8mi>mls*mO2Mm`Vj@0L63c~Y@IlOmn-=zj#C z(OLC*9)1(P(BkmpD$+UQtT#RizcpU* zY5q)%!=8P{!l`Eu_<>=nzp{$wt%NUVD`NAs+*PGhH=o7}o7WBZc`&|2upYqj!*1+H zC+be^HswB4O*-xJ$)8rAnm!MnOCK4fjBWFWHrS8 zt9V1~3sqOSIa!}hA zE1vzw^%?)p!Y`gxxi;^rS5x-&Ij^u2<@Sa5zOE~>c$flD`%Uro1or#jvz__mpK$k_ z@lPIAxz*RGK2y-S2G5&Q`gXtYQZ3p4^ke4uSr0E)Uh!k|^O)MQKeSMuv3P3*uX#!} zxA&gs;AKk4{}vBPb)<7HTJs;(*7M$hPnx4Rv3Ae@nCy4*J@waI*Bp3QE!E%V|KGvg zeJUQQE1iSKWN-E9@ADvU>@1u4xzJnKuc)E;k1>D3FD}q^RfJcrC;ct#^BfIt1$W<9 zPJoB=eY)k_Tc*P~O6G^*^`)PWb#6A#*$uzutj8$(xa?ytsa+nXK99q97MJI%!CS-M zWSySH|7Q5eJ!&tT7ySV5npOEk-tfFJ4ODLTXEhJE{NK2t___}jhxY#H0KA7&{{oF< zKjjt0!$;I}IecC@<<;dO`XN_i*?;zg+ROae5i0mZUVp0`32=Ew+p=5o0_*|$)O)QHj_@plN#5o+{N&k3o`fjWAO2pGw1Wz zc6cxTQf&z4nxFb%#VR4tMpogMIw ztd~>o_SeTINI!ar@<1~7U40&mgVUXJfnUQu=O-HP?qGihUa6|ewdV=XH&^`J|5?{% zcw5=P;{$9>i6X(TbDR=;vsm`b;b&1sj(meID44I4^yBp4klh<%KibPs4r? z^TQS)736EZ~WKi!8ji8 zyk{)?oa_g&A8%dia~Hnd`A#sto$MDDSAVp;x&%Il{eq1D2G91E`nAP#NPFp2xukYU zqTD(@5B$?HTJ=8#e--{_Ir;4td?`A4_o+UAX3-BhI!J#?l8HRXa*&{3Pkrgm-~={#5zL=A~QUHCiNQSehUHguDCDR_-MIn(R|;&&O86yE^A< ze+?gSQvKcfOZm>yIm7$V64bLT{5a>2Se(p+hw(j*-M{<@-#N~}c?I#f3O*#uFt6dsm zzZo9stkd}0=Ruq&Kcu))Z}PmD?$RkYNaITp=0(vjig);2<(5G|tcUpJI?XdkFXo?1 z;59y1zxW*cyYQmU_hKb_N+&hH=Fb)T#) zeB6U7w-5Ck;q$;hSC6aR$HCWQ@1A!S(n~t6YN_9q!@eLqE=Kx4!K?W^Xx~&PKX<^s zIQ#9C#eNaIPMYHFU3fZt!+!C;@R;7xA6ZoMkpA$7J`cvba_?(?TOU3J?tVYA4Iaih zZk9j2KGHe!sNyXWoh10~Vw$(7!l%PqIp-FA0FU84j_K#>EBzj^>KFDLpdI`)>&nc2 zIehRh@nEL&FDV`@U!8=XOi^5Y zjecl<*+1P|<6Sbm3cN*C`RBiJ?(-nt-1pZ5upj+)=KGPA@PmidbJZ(7uh7dXH~b^n zTl}QK=Xsg?*DiPn^TW#2^AddFoMsuso}2X>ApM3nRe#Hq3*qkm!&l(${#VrpN@sN+ z#gEN%PQnLm(-qnH6*5Tie8hR4S;OZ+Jf}G8PP_Ts{+3J1_@7bO-)g6RT8ban!Dr0S zb=iH*-|*BN@|#-O^Xk2#atq{AoSX`g&>8pw*5O!umL1IX^8Q_azs|nO_MGZ>c+>}K_d4h|N|XMkY{~;R&-obc_V-q=%HI9H z>>9l8U5$*E52J?3-hHmv!so&IjU&$fFvGF0z;zX%o~Plr-jm;yh5YBG!=+#0Pqnzs zXF9_d@ZCfVIy>MY1C^JI7aSp-Ip3&X8}9>e5wGVwW3xzT7yJ_Mtt`)6gm-^Ner`(K zCch^A?7Sx`Lw%;gSF@k3<+0oFWaqn#1|y|Y^KV6<<&BN-?Ch^@`bT{pjDvB`Jm-N? z(kW0&`PSx39ep0yH*lU$j=?@Dm-^}3)c**4e1%3Cqyzjud<*a8Z5&J-t#V%&ukphA z?*w=g=lhZPF|watQU0`iI}IMixhj@d)5gl)-4ACsy!&XCtKQ^!|G>jI?jvpdhD7Qh!QP-G6o{uX>)LHXJ49~+LBzPlcKlFx&2DqFPXbtBN(o5A^i z{?Gqh@_Fz)WG(OO%kkTT6QtkuhU#AhULJnxn*3mSqX|5XbvV_rzXA{EJTmit)rqQS zXboL&5$yZ;JQy!VtjpZKbK&7j)qm|d(l)qz{@`i2`yKAHuS@@4Q^o(cl)DL@m;D*K z!M}yO=Sjs(lFkihf3~8N#rGFcyxDxC9sK$v~}9$ z{Fr?_Jcj!e>o1+)@61-e=tq6NhF{MmuF=8s^1rQl)H&yS>N-9T;@>^b^d)#X&eyYe zo&b06vp(^8;QvF6}16`y$!9``dJZ4=yPG z%Nw3I)#n-W*pkCC6#ApH5&J2%Re$sCSMbCrW z{_SU!No;=78Qvkk;@R$-K83sAQy2JHItBX4&z5JNhQ};Wxfaip;p=KBepHI*jb0}m zFG)I9?mO_V&UZa~;eB6Myjk3qSTCJpbHuIRrNHApQ(iK^y#rrRRsQcnUh2Le2RG?nStJ-rQRF z??1?I)zHtiSvsFN>*yN5H}l+M4fgYW9^|FYSLDy7_;VNbJ6bA!%>O$-mHxt?RDa8> z`L~F>>kXcQZyKryw0M555}*iKPlgueouHl zXCLx8@Wiw7r|nzyAM~>`K8{5{WQXRfWN@adlPE&lhyXQpOu zmrL;3XH;{`V|8~*zb^4?*Yz5_^`s^lHSAbi6;1tI_G9A}S39ZyH}J#lRPF|Nv2@vQ z;k;?{XS~k?KQD|@yW8`J*RgNqoYT4%K9=XkmT$v$Nq;2woA!NW19+JNif0?A4#K;= zD8D^QKh3{eIyL!@uPXJQ2H)m6QLYT0BaKr8miKE?SiN%{m{`NrR_xE{w&= zVR%dD`SY}c(x1ort4Hy3I(#$Yzw@+}Xiz_Y%u z`rCYIJv@&6`7KV09a7#a>a4SR%IAUp{Q7F~Rn+sE&jbH=%%O5$gBSZ!_O0K{JYGKm z4_%>orae#V2`{rk?PcqNHo;r+9$_B(f5YAV*~%VPx!G8MYxA)lJ`e8eFi}+1@nJA{6t+vliHS=H=b2Kx9==+9trIK_g_<=2Yz0_ z^EAun)8Vlnir9VkpYVG;ceQ#xd{p&0^|k6bnWEaj`1^7K>uCt^PoP< z_>RN+SDs_y?)TJf;O=wI1@MmS7j5;7{8~Df`L2Ho^=S$}K2!B60q+TSpZ_d{zx}W5 z7iQHTlsYc`yCvm^{^+~_@0_ZBWb?6=@EW|AvHtP}{He*xw_l(W`XA|Ei;%vxX-)VE zp8s1Oh&v(s{Jd|?k4`7}xjt&&0`U3pbiO051HS^VRX};t=G)=lNZ)%|87v0-mwaBr zEAB-%);z)Pm*2_Y5nlf~;t|+yL??{rDw?Hx-d}L{eQW8HD))AT<~f6NN@xkZHRsdW z{B1uxg6|W}KX>6C=cAebYkw>Konti)+PbW-;Kw?uUD{Ir+NWfHist}T;V-}!*Ha$* z8vZl z$NZB9zxtNA`DYRQ;y0OfuE5=W9qXNwel_CL^3`E@FV1DF%XQ`YPWA_zDqq=r<~jJ` z`RXs0mnOht-&2HCpx;$FFP)sr6^HT6PsYNpJS-2ZH9cYW0 z%Ko{Z-;2*FtNxxq{U7mpkgs|;&kslXJh;DGI8zZ4i~Tz66W9;d@=}%y(h04uew~bc zd3cUr<+OZt0)B<>tjnQu7v78S&MdFy|3T%t=QNFmAFi3X-M@e*@chT( zJj+GtL=TZ?T4qyv5@7B7ELE(os}+UWuQj;m6=ZYe;7;Jnt{mvwmU*=?Q-UUi3HlQ+Gq2m*(@J z-=#mU{L_X0djR`fE!4i|xAIq|UxxE;EdJZUm+e&jEsqU?Ut-;_#s5`!FV3B5Ks^in zs`^X~QT^@taDAT#{eApo)x1ck{@}T5;x{-q)8cR;Jmk3S?Y()v-(>H;SM6*34YgMc z_1O(C$-H3S#N3A)fHZ-u;Mef>A=tNJfw7pet6<{>7*@FJ0@YD1|PgwJt7*u z6rMg#nR#ap{jlSPbXqr6zq9p41^*B~o-TdsN1@yE`0bw0>t0IrMBYoleo|KDpPbb5 zpwELi*1ma&*rx+VQh><41?N%eV9|7%B;A1n{d!oG8E z#raF<9Duv${6_pG{bB64Z*fu|UU!#9M%$O^Fnn}->CYlRSH3Nss3G!yLCS3pUsO~6 zxB9;hzf~>sIC2a=hv$1%pZGh{uk)DV#GW&J1Yg-(9ymm~v3F(fo-;cVeujM`EkA6B z4`4k;7&;f>MH*$Ue}TWHKPadCFbMlr@VXu3w{{QchYI&(zqp<9)l%&H!%wgt$@0=V z_>_gp57ys*gg4{-yI$zz`$zZ7o1Eu_Py0N`OWl7~eMZq=cEQ^{toX5*{0V;jP4#QL zu7~bRr+u>ewY6hw_`GA8+hq~F!#?#d8wZ>HE1g?Bzq0vKZ=VP8yknf=p&!@vF81?E z$!`|t`{CDrm4fX{)7Q(MalN%3QhjXPxdgw-ejs(w{}+DI*(ax97U|UZS^3ubZ#+D) zlImmamFn}L{_cJEBJ5kulHY7zT0KPio0vaae}5L2FTw0oC43@EHOjD)**ZW-_TX%TK#+Gkj~(I zYOj)%JJ;tyd-eZA@qZltCH7ZKtKZps(kDWtlh4`LXf%9BRkc@DbT+|9{G|A?aVL9D z>C7SD>MA_16TG;c!-dXbp9l5a-AH~Y2Y(=!_*nKmPKDR^dC>0eIXjc#4Vx++9>Kmx zZrN{O9d$H(4SeHLwXgM;`|yi<<)6GR+@m{(i( z`?cUxv9B;#*Q;pvyzk)AymzaBeV)A8Gv1GMch)B)`8@F3oZof5cd?)2^T0m~E35t+ z;K$%AwkRIX!k^41o$Sq&$L7Lc^m(9jjqev;#}5U<#OJcETT$nE1K_{#-K*u#PvN7t zD{d{no%eaLt|Q6$t|v4lamh9=sDFf_;vP|wthMV?w;S8y?}Jw^;cuzZ6D8^55I)F-~Z+>D4oO#na8{O@WoZsFYNi} zTk!gvCsLm4ItqV_`(lgR$U@Se*Io5V!oCsw?h@Z zQ>ut`{$;$de$gL(Y@YgE9M`)C-g>+8jNMP=Eh?Q-4~v`MX2W-~FJCx1$KdY%Ic1AU z$33s7Cwv9_{Fwea_?K_1U*tjmIK1PV>K6^+^&{1fl7Cm8G5$gZ$LRn3&nTY<{p^n<1HZw(2OY6*UmP80|BAuz^oKOVQM7wrz9`w}<-8cn|CQiV*{8+E z*#Yp?&U@0C@I36hSc3W-fwyg__Iejy>0y=Yp3mD5K7CX33`_e?>b%c`=V@!%A1M+Y zFIqaMN~*t9hu89XFfMGrqjnh$e*$~=JKSFI&)HwsBW~CGJjl<}o&0s^Zi1XTp=5^@r=>W2UN}mjCa<8*G&y zp2?vC3Y3=qoaV|W7H|FFgPSSu*}0{A;O_pVdCN#=^FdwjaO&Rx?(V z`Ouz|059OYCtd9Gz;8A4 zs-6SU-;Vt)?yoJb{(@&`pBBsWRVu066y8HwyN~dB#yV|hpOz)q&upxCvw80Ycm>w= zDVup-ugcP2_<}~#tJHIPta#l>-ame{}KC3*l#SVd~W@EcopgV*fnt2O=g#_(|Ne{G)g3B1Pd8qwm=IqvhIo^^*Sp7meP z%UV_X7kR(73j48HXwa$b+kbKZlusxAL)MJFA;f$uxa|Np>uj#GZK`EAK+ zs*k&W@=W-x4vIs|+vnl#zVxm92kAk7x#+a-f8aYh$O9Hv`D(~MDoOp(^y|QnPgOnt zdw&EEdr|W`yB`mKM1CH@_g1grhm!E7iPCAp_?6=Gpq>%rZS(U+cu~$>Eriam@c!GR zQxzUlQ#!R~Do-ZC2f_E36u0Z$1dq6)E46-C@KNcsNK}3>J^;SodG37x?(R=sv6gfO zJ)m+eKXiw;aL#XCX!g!`$0vLq#BF*s?UGd&maDe(t8uPM6|T25Jdx+>AHh$<>tt1Y z)`u6WBc1U#^?YFI1Nxx{d^G#sbi#fIye{A6t%u)%N8*2*|FnNh`aAxX{ygj_`aHO< zW3MX??+_1Xu#cReerN4fpssWhcZ*xQ^np)#RM(Xs{ju=Zqcpy!!WWqi-|1UkI_>k| zzO{#Q|6Zk@$_<^XI5GS7@V-~ozP-?Y6@IOg>Z7dac^~;a$j{e{={Z9L_7|{EXCIX^ z@a*+fZuHU2ar-1ZvYY&7_Z>5R9@PH?&s}k+cL4hv+z;Bgoagbt|Nr|h+UG%kTsB>q zb_^!<;Bg=6y0V1mhiUMgtlzV7_5$49AE{^q>8G=fw+8yp!&kcJ2l+hkTb#2$_6I%> z;wPe#^1u;vuA_5%kNg$~Z_!ZY_8BI7%foBn?mFA^@c0}T{Ck(nvVTyzQXs4#09mi`FXIje`#czT?q`$VmeG!{!`=JY-{7-(k7@a;Tr24$Op|}?ejyp25~F!YuAD0P2Y5s+ z-S6A`<$=$t|BiINd(F{W`cb?Wv+;Tuylp;>3vtvxw2gGyu^&h|uD7JmgX`U$UH-JZ z)Ea)OllrygrLW*07g2v%icZe9((%}D-12;Fc!z%*W>{KY9SYyvTi0vrJ&wU2vD>P@&7VJj zr({w5m`;}V(r?;cac+6L418OX;?Vka5BSp06(^6-UR&VtZ|b`2yZb5~)Q$_CbJbh; zJZQ&A_FuK{mMRZ`YvQCD`wr-8h4o{!j1}_J^^&9oA9hj_5AGSzJ8|-;+-|Q_vp(zxlNM zZ{x)h_{Xdhn2P<^@FofBFShS%Tql(~lXJ1FV?P$|@%+%*eT~n9>rHuBex8Hj?-je%7Yu|t1i@Ij^f2kyu`vK=8)8KeaFaV5LRzWQyom(`~ie6aH# z_KB{tuiHftV*Pp!d@$<-qA7Pbyy$mo$DQy}-K2AWzxun)PvYU{*iWn!_QT+z$5o+No#Mgnn-2Lrh@b4g%U-ie&%1|x zuaD)oW7MC`%-dTyuO z_HcKd^J2JrKk|pqgX?O-_X~FaTcM};vL>4U^hJNM&x868sH=9ge02w&SVr}<{#Z6y z_DesMfAm+L*BQQ!ed8;lzZpI%q$P6K@$M567b47ryo*wQLf68N6RHamy#a!V4`@{*@{Pg?;v)<>!&`Y%fbEhVx{*!=Hoie@gW~3ttG2&Mh6w z^WFgI%qb_{8T&>)59)K}U$x_Scqi;D9aNmycNTxZ>rK;mXX9hhfzl7pC2slrIe392 z#e={SU(0?cIt5;leMg=@TYXaD zX^j=hDiVHJGx%8@8a{Iy*js6d;NibW?|o`M&k^Hg{Uo0Mw}aopzAgR5`dzV9 zm7D!1U9YmY=QV`i?XCE+`_`rKxER@6UfKaKxJo=9w0{s%FX+ZTBIEI zo#ELks~?&E>+pp3s?S5%cTAJc4&GN<{(Rf#f#336R(W@dMf5dR{gP*8A){dRvkMq3O{Jb3Ao$*>x=XvEuNGF7G$NEbrc)Q=_|NPWvI6S_F z>S^ur4cz_iwc=~ikKsPr?tc^DmntP@D3?HgfX{>Wifyhqp8$U!`>7peZ})e9z<=Sq zU5n4EBUSGB_Y`kd{|@jYX}T}oK!W}o9?-W*kCsltV8x-`uML6MVc$;6tM9>gzbkv2za4?6tP!{Cx&c4@rLNc7<+(8`w?;GN zXB)p(z-O{wnbqeMyxnc-SiX%LE1mhgAGEj{4DZuSaafLcJ^}Z3i7R?NZ^bz2TpyzP z*meB@AJA6qYrO7w*{`0Wc(Zx+5%`vOrElkrHlCpPS=m?lB%1p4^m)*a;@7I&#qdwy z$E&H_hP2mtc&ilUVO#g|+C=GWDXntXV80ihhv#E955EXcp01kj#6I?Q>71A*Kihac z6MisS^)$W;?tbrZ3tl5y^%;YH!Aa70^IhqxA-G5s7sxmt7WAA>ycEINu z-_y-#n_>AX_VJUYv*9uI-?!j1d>;6}$@97{i_cHs%YIk<5(|e{K+ZOarZ5G zAD)MGai)J1K6j|%$8-k1A)P!S`nvfox*Ba7)j4Ikp{^YbRW?G&}I zJtx@@Z+AfX-`3AWO_ToN3F2Fc&*5-)J%7pRvQOwDzgfTT1$WOQI1G39%_ucP?RCjh zJ=JQS_l(bj_L{Uracke{9D}!DKOD;&cj2{d9X0hIJySaKK9`P-cit@VVLX2>LY$O_ zyZdtQh7aZZ+??6;2hYxyPAdCaTf3}wyS+81-AzmoCsW&AMpE%6m+)xWBuv%}{MK@k1VQS4t?rgmAyuifvA-0rd}#Y$eGES_Nc;}=XVG!@8|nGB^b?)+%!}cv ztp8kx&a!#3UzVtPTEDvrKQl;qz{Zh6@5tVbhsWR}d7o7g{TF;5?2~rg*(YrX_WKjn zzNY^Te0d4^b2~cs;E~REDD~&7K4YEzI{t;b=cu-LSN86Hcb~x%hO1nQ&tKv0IgEQ2 zNXLC{llMLGWX@eOe|GeFkhdp(r15J!*OiKW_`Awu_256jd$Zr{6nM#n(jUM%!ZuzH zfp>J)_g;rb@ttESbc!#M&MxO%q^IB&xNo)kkB3h^m3f}?6@1uP)!&|n7h5d-6Bks& zzvy3!;R#WSt3lM~n$LqcIq$?t&Lz^xUPa}`U|$iw{59o`?2YIIBt%ey2rP1jFZ(Tt7&F0Bd z;5FxI9%cRUEc}Y|{rgRLmWSm}dyW_Wfy#~kQ|0ES+&K6v&imiD;Mo?b-&s9#E|-q` zytf0qOsLw|?n76@_p%PW0_9$UpW=K>o3B>+Q2O7dDz3_7KN!BZvh=OpH^bLA6}S0P zo)yyRz`hXr)jvNSo@=G@d{g58D16Fw#gBa-QS&3UZwIG+2l_l{$Cw$J^U`wobk0G@ zPyJ8AuYRm{wC6%8E2Xo0iQ?Jv+i3X2T=K&k=-h>;agM5u7dKZ)C)YLAN4?MUhO8FP z&iPi>?uXzvmrMUD`nP=^fjDox0Z5@V}>n}fdLgzj_vQT^m zvFENm*Ghl#hpNBD!zy_48yaV=pYDeD{!snp9PRk@$EyG6aFsiRatHf7Xs_gM$|ob> z&DMz@e^U9ODm)n;^?`T<`tyAr_$O?&#)}5r=YEfUmLF9AaCC;OmwrpmeO9mZ*ImHl zuFBr}#h4AUKN6~$mG$>4@Z`2?FY{0Jjk3S`q`3K~lh1>CmimwUbC~+f!Twk~#o^)* z{ZM6-bS@lGedImQdksGN4YilO|Gnn(Kz~pbwaZKB7yLvzp+yzXHvg{+zsq++7U!Md zMXSrt#$WS!puhGh>91p+wg>ye?DyE7a?5U3xtrNf-ttvl_)TY>SRbDU_g`_ZYDBPn zJ0AOvoD)$4{rzx{@iY?tz^5v=LkG3&TKIGDLQNDW_WX7Oyz=MDNFQN;5q{{p{5A#t z;1=nJaekjY-xv;W_qCq4#9)6M{x|!Go+fUqY}NJdJf^tnhy7xo2mRtc`<$EqkHM=l z&RV&5;9VI%SM^M_yDs*z?SipQ+r-e`M~D%ixRHr=<_|OxPK;V}y79(P0_H z)`fQWdEn=t`2ND`KN()`5!KWD`6E2_Mfr0L`Yk?}&I#V{^ny=-$K+8x?S3{iUH0X8 ze{K3r;j0;6oX+xg7gc&xI8;*E81Vf&Mes)bFaIGaEjL=WjNDTL~Y)`Elm|eEX$yi1~k2@<96o z;w@{+&o)n3>GL2S2K=pZpTYhX_Va3Gj-MI_@dM|1*|<3zelbG%(Aw)FJf@BE>YfL5 zVH3WPPW%v+Yw>viUW#>1mIv}5l6@KH{cN@`#V2i3JuUt#!Z$Eav-*sLk6)ZQFMR+% z#d#$*e(m#l;GYJwm1jb;tNxu1tK6f!Z#Dma2+!^86Y?#*R$@Yiz(jPmeI=a}->E(} z54;VZ&;I-xwf+07BeL)DgsxXlu{`fxcq-o&#u7jK;4vE%pTqHgo1@Zc*E@6n9S85j zxu52@Gw{`8)sB{z?!h}d`CjD$7(zo{`1L5hX)W7UG*gW`e3zQE{e>Z&MN3tKq zb%lH_{nhoK$spDrtHa&*8hzmJaR2)|I#=OK%c@^!6!W~;D|b2k(wV0-YH0pH3?ImTfP<-j_7l?2$2wKB zZwhzUOZ0@dyQh3!7M09ZK z=Nw*(!>;g@S?Y17GX;KXkJ`68`Um0ee(42HN#EV)`N7lT?z){O@G9L@Pn&NH^m&kf zqEZqwN-RwOU5ov-oU*rZ=Lh&)-fNqGDxXog(_*!_2@6}#bZrC~LTsxmA%)S z1Ru-$5gU)bhEFS{dj67C1-JZ8`c1HrSYwc=*|%Jx__6V;wa;x) z4L>qQEn?$!$Yts0Vm@!o4#7Jh<;(JEU!fWf=CKV&7rj(sWkUe-g}d!=M}%_{0I^RWLA?(UC$8{T}i;@{%4+!d93s*AYw z)0g2Lc#mN9{0N>}HM9Mn@C4SER;E4;f02GH-_6y5cZ5&kc~mq!4IW-X{n7k3+vh?5 z-LYHcmcf1-_J`OX-gvdED!1KY^`npJ*ZX{)5hu<%^WU&fC(oEp>0hN&XRiEg{(lnQ znsvE0f0ztU{z~Qc3Q=8cOOyyvH9~}_{G;0w^q-e;rBK& zKcU=&-&F1}_7AbVeH4C&?_sOq&$8ELzoeMzW6zzI!;iEVAA|i5@Q^ZUFY`nG-=#D6 zwEDGOS4+6}ll)`n6zqo2|54Xf0{v_^q%-AZ@i=&O`10<`S0&*~;3u5#JHCh4XTLkE zPyaupe~tSN8<*F^d$iGfY&ZG&ANZGzb-mW#i{F&aF}^=iD|lX0_(1kk?MFSg!2iQJ zT-Lt||0$il>?3XUd>tM`zbK5(BA z=k0-?;(Kbl|N0sJDEo(4J*)mD{k-g3V(~W2=RyA+J6iqsO)9$;`we5{Pa7}(!hT|$ z;>X_al)Wwe`X!}f<8lM|XugB%ivBV9{TRjD?;-jj`3`<~Mc11j`#JF9rJH6Dn~$A^ z@8$c%QrH*2E1jv2XneHw(v#u6rYI706`pqj-eXJV@vhk4(pg+p{e2_)&3zvDts3jq zt*r-QKbv#1%>T>b?zwM2!!N&~>$Ukny?ZLR*7(f*bQJtH_h06pr9Kbpv$KM97E{k3 zv7f(N}M|4KhsS;bF5cpSXG zvk!R^d``ULe-`#j;bliCpR|K}UJfs~-6 zefLKdC(Eu4W)_ zV;}y2bWZRbX&pRAcJXXG6<1Z^ec@Z4&pa1HOl+v^TNYP5 zT*iL3&x3hFY7NaNL*ZXwf8?{w{iSqH`8g&={r3m#8^9Om7T*N#=kp-0*7jAry@EgI z=Mq1|ew*E~{}nzLKifE!C%5d^by0q+kWGK^Df}Y)TUy@u6JCdL#Qc*lk902a-q7af z6XCA@BM;`tcs_rb^Q7$g{9&I5*ERdB=1X^Ss6H3-il1V??kZeY)_mga<|^LgCC_^j z?w+f-7rykQ?DL|NJxn?qs;GTS!)w8hai3^;CLJE>d?$Df{$L&TM;qTu=9hlmh01$& zfAlPT{5HkEec$>wyv|0==hsr7r^2PP@Co@R65h|}K|kH^JpZ4Lz59L8DR?f{&s#nJ zh40Cpx&Fl-Qn^ieeprTb=fmr>zE@H0d3)hEn=3xeKDK~#TDFk~5{cW{J`d{ezK`CD zy}Li;ZTN^8@|!(3XjD-8>GPEzET8v*Z+S@mw0X#6xck2NIDB|a=fl2dQRzR{q)7&`??X4hE3hwOWB#CRG1+h8e1R9x83HfD z^Uq}X0{GPn@`K%1o`%nL=KqBvrQd^iu<<$`?(QeN6F%rSjl5=m9DZq`{FXmN6)Ia? z`WN3Nh z9uL0^@6NuX_S~j)w90L^Q1%7vwOsEpp9lGHXjS#2T<~kyuT55ewD0J< zm6U#0XPxr|co^K`a1DG)nC2}z(a%>(IuYZfKQF6(SOxEXS@*Lx|G5MYuP1vOPn(vO zj=Rq4fX{>LDmPp4_7&yc#Xh~QbnL!9rHpiXaK2jw?B~Phv{H-PbCOH&xrG#mU9rz! zRyvUhnjzRcyaU{Qzq1H_t(od+@vzP3LH$Skt@v4l{x_zxOZB&TX_<1ekH4-sd<6UY zJ`eh1(U(-uDeyFSlPB>fGMF}eeNCe zi1-^k_ps}24xiFp?f6QF3it?K^m68Qxej;taq3c2{@?H1hfei*P@nPdE6@B({lE8l z5LbyC)Q(y3Pw7Wxe_?cHf3}AgS}ktzzXZPKhQ?*N~@3C&s=C=*tO@?Le?{CA8 zvu;XP=Xr}BSNtz5AwTq|KKp$h)Mw>g#B`?Ex7xgLR+5){V27Z^1u1{W9-wz)r0K$ z{3DH|->$6syVdh^c&R4hoha99Ec+&`SF8h%g-_+VfsJd4@NPv_|E1VZg3r7l9u40L z&r(HF-ERkYohMZ8 zg@%fpq1p7qb@;KP;$>9eV0?^l z#>enx>c4T$Il}Qi58}36PW4BB+MMz46L=n;x4cEUAI8hxeVuc!sUOvao!o7p78n1XR5;Ah0o!>te}+(U+{zSjP=JdiPC>`spb`h$lJZ) z8_uboUC@~X@5ui4Ti{#aOGiq-B>X#guj}%sjccQxR=Mte+8@Bru^+7Y;i}JrIG@;3 zah?zTf3aW9x|d$?sx75|;tQ2~0X_kKvZCU=)&u(C3jA6X<=bzufAksYoPSe(uz2VU zA6ZBF&G<&22lY&vrExzBoo}%37NdB!xGmL6`XzZkXgYg*9>o9o?6Mz<&K>OIA6Ace zIlF%N@mc9yPf?tg!oE~%@x1KIog3Z~J|&y{Y5DCEyvBU_&F%-AwUJKPc=6I95?Tj$ z_htPB{ypn9?Rp<>E1g)rJL^Mzn!zVtQ=D77cY%-QJRRd(;O_lV;pe13eY^6&PV^hY zUp=h)-+?cHk95|ZehY8O_or6w!|kMh?yrU!3N}Bl39mqZH$TsXFAP(;7Pp7tCz@q` zP7>Q*`lTu<4rfu%0r1F~>Zkgz=WT}HU_TAJZ@L1HSg!cA=av;ZD6YCzR6pH_es7-# z`M>pM<*QZj)$nUyh?ju>;qzb~xG-At8GFxC?s@5?ua~~A+JA2XUrUjRRPMmjywIRG!mdWK5yoAAY)<2(~ysGIalbW@yI-gp8YJ}z@T zUxn8^A-~N+=Q#Y<+sY^Uuje)EF8${pm%ZuF@OjXV`|r!L3_5GDclYi22mU7K=bBF4 z7p0&4p7blC)6VCCeyeth!|&lsv45(w^1RK@i}sLxfhS~d{u%A_AbuuszT`a9fgf?s z<%#Mkd-uEVc=%k-AGEld0C(SOtoC_O|I|eJzdPj~@_8`NJn76cZ=w@dQ1NDY;NfJ| zXRWheP*ZsJk9ECvzdr*W9U>j;FRS40`Js2=mA+7h)F|(HEniaoJLDF({FChSz@L48 z$s7+m-~)Cl9?EjP5xr#Jp@go;{LmJDGLObnYxg(dP1wg(vjWeH>@A(;8>M5zq03$C*i4Cl?UomZt;H78O%95 zW#H}LQH#}%Hve1>Z&XNmtaf(&!P5THi7c%8*giI4FN@FSd%X(i&w#t%t$YQa{(5L zz7L(n&U@s-uSh?wn%e6!_C4XLrQ{#Yvi$Yl@co<{Zhk%nzsq@2)?Y#f2YD&X+wbfn z+Q8?5|NBo>{Z)$R^@Go19j4tMwZ^~0#85PJj2r7C;kE-&-caF?iF8?&Ogs&?swhb^*JBb`t@5r z58AzE3B}1N>T?qNUQ6RMh}1l<)JW;4g=&5~o%`RAQPN3TBtP5t9W{L(^p|Dq=WO-t z>hmBDnI%`*|U*v=Lhlia|4S$Az3cr>|e)~9^ewaK)I@=0r z{Hl)q26!_2pBIAv0iSeBaWWE~FjhJv*?(TW#`8wN8?o-%#;?!eH=;AoLp~iRoxSVi z|KjMMhELleZu7(JOTy=ceM1^P@j|V$ZNXZ_V5Q@mrexd z2!z8E;Kw-Mryl%c_{?JRv&CDsNy=B3o%csh}Q{MB&23lMZ3eBaDJTmXDU3djpEbt zq~C=8Zu9?f@R`-6V{!EhJhhKTF4I5xYtD>3u(NoB3}u_QG@UB_kv-L~(3>)0+VAazOR8>zeNKATJf-ea&N(`#$zfSqE$Ja0Z^6?=B}` zpJ%$ty<1Y(+aKNxUV4>!?s9k<-2HB77yRb;iq9_C{{mlrN;-DGTzZDeO@2x9#v8Qz z1-N_8Le818k6<0_Nc7vl=Z#SwTZEs#hIeIMf%TVXXGzE1SLdA11AksAqw)76^oz`v zy~jBS7UzB7yEZ7^hG0Jves`<-uk8z3^-bxt{a*I=o#rUGdrtH&c!IMYBV>+r7GIaX zJwJRJ-n5t6QN7Re*26E3R=>+nJx{=EJ)nMV*A?@Y^b^@B>4in@>ItU&;HRs?_Hd_`+GbuAT6&;g?tsVEQ-Vy(i0`Z&1(pw^i<@!F+6CjK))o^Y7tDocrsX^Q1F$mEw66^=az!jB%Oga^>JXuy4dVbBptBaCd*^ z+V3ddYLu1!_vobgJjk~fjwsU>gfD|9@Evgs{3d+#x0;98zM#*}mrkx_>KC?-bPqh~ z6P0@qosf5BpSO(4wY=0EKEI3dkIjol`8=Gz{lEV+8~bJZWN+<$6n?RI=5gmXd}^fH z(KL%KPu++*;mTq@F)0=7V?9l)bk!#M7wZ4 zat-t!g?Hfmg@*7Y@UGp}A8o$zC;X7JpL6NO(qF)Lpq3xn!jFG0zuA0m5qvu9`s{j7 z!W*#O)yCN>OQfIX?6>eNygTR8+I>nIyfgdG**Lo!e(YDpmDTeP`1n1_c=jAMWvR-& zSVi{g1)ewdeQ|fc*^p)8RXE?|G5pyQo|k6cXMG;{AuL9D<`ni(D^%`>QR=_X zhvQd->IH_dAQf;Fnn!)SYt6u9d!f zj@|O@|w#OC!hbecs&x3LE(#wkfo$!6| z(1P;6jf1t<$=*F@wiA2--=o=l<4brn>*6dvZ^Dal9+0(5&Gpj1?3`o!G<-Sdk63uf171vAq-zwr;QweEy^AN0tY^g6CYWn#7}1>Qm_yEva&C z9IOq0xsl2}NPXUbyXQoF0nf(1`qu8};CEh^zU7$*x2W9eH#75k@E&|mWd45_-uaHk z5!1g4-^_Q@Hvh@BRsE>Z@9Ia^zbg1V=tn)?SNzz0(+v3RU!KUgQtKDH;VFDqV)qMm zx8=weM`sL*?g?{=en-h zJv5G=BF+c-JZP7WO`B&ZB!oyPTe^6u0V=mD`VHXAcpq8;z7XD?_eU1bKfW^Yd+xdie*R(I z|0=5eeg5}K$2}*aE4)xK^%tw>R`~P_$}{G-=KJL5&Rf+kmvX2=ANxG;^SU^-ul1uV z@Jj4wXz~2?emz%j*{5xWfZ3<`JkWV`mD=$Uu6G`M@@lpFa`;#90qhrQ`L_H4>8v~= zzeP~bVh6=@l~(<&eVf7i|E)N&?>A?_3msScT0hK7b?omt-}@B%Lgg-~ zt#-Hmm;xWbIvLAj8{vbyX1=ey2v4h}@$NEy$a6^g(-Sh!E1JTGyr8(+S3rO8{g<+j zZ6zIR_u7ZmzT>}Dzp(qzc0LcS3zLNdPt9HqoO@9!7MD`1!6rcL9=cT|GIqPXZg!ieDIS#kO-Th>uj%uEk z#5}D5^=#$ypq`PeCrpP=fludr1dH3#@YG$3A8VI}$K;>;_$M5lK0XihTk~Er20jPw zp1XP!K8XADRoI7rEu9;$sb5%LdJdkelG@$!=PdY^YVz}A=u|l_oz2Y8)oc8Hq~X1} z&o%uO@Z;Y}zj}y-e)f4VzFcancE5yvo&QMx)Lhlm;$a(nOCiPiTiE{tPpGdrF+b-z zA)Th|17Q4dxO*db%SN7&y(=*!pgV$ujfsNhwvWC zbhg6X`DeD1(!b4fuxjX+gU4}>Z8H36cz0+2)%EZx>~~iZ`@-K!|74o{{2BZa&-`o{+|3i9-U{fzwxRv z$$!^F!hdS0@l?Ii^Qv8t{$&@eQuHOIur)}(GjIk!h*v1%)u{4Glk}Zv0nk-|9At8j2 zY)O)R&%R|(k}b<*OOhl>mLXdRNp|A*e9q&3eQuw5e!jo{czfUObG;ttoa9IbvSjr}wDFs{oip6lLFeJ+pI z{A<@i@4*YRugH9K7Q?fK%6<&~DR)ykDZFQH>)S8j!*8d}!@t1&=dc9-EuCXK6h8@+ z`vQDD`Y1f(Dz|leSNL4tdxmr1=kuyQ z*1uW*mCl?&igP@`K@cE)}a_9N$toBlKS z_0JTa7C*7~rQi61{A2S}UwF$C8o&0wO3nwekN;3Q*4|?9pX#cf-KbAnc(CvLi}mnG z-Z!?m{R7@-nBu{B?uROOEZ+;Ob&fL?o}-hl%ZgI&eR$Y(MXdS1=p*U0=e(8b*mrQb z=g$&%<%h6z`orhg&l#)v$kw-~;Y))Q51r6y_E`EMoOfg8-hl5MtGKfJ`4gVV{^URM z^A&Vb;BEMB%i=lxf3gpqC_lGPuOIY-Z{d41TX*e%uj2Y8H~LTEGn&e8HXrqWD*b#p z#BDsLzzdbvc(FWC^qKrtXq0;7A%1(s<=%YSpryvI&1rQT(8-9shv*c=6GH8FPT}6 zn**PANbzs=+yOtgU-`Tpe(soFIw8S|t6cDp;EQ;EWIFrc1J0RI@{!VMT_H9 z&LI6ctoOpuALw!~--i3n=h}~b#*NDVuao~*Wt7en_N%n}73njH*O{Vn?fdq$K~Gm z9sjcGITl_pv-AgDQq70Md%=g!Q2p)u=p*ncE7ZSs-~JK2z){7ywJSP{^aCcP^}}>{ zJ?;})zKX~y`=IaCuE_zaP=#!&fAW_2R4|Wvc7<=7tMNFHMd2=&d*dtqw%WTihko!@ zcJcj9^Xbk9MW%}Q{2|Qt>A^&kIUk-5B&V@ zv^q246L>$z)`8!^>u@fZ<^Q@lRc_=o)xS6OUjko$TI0pW(GhqE`*mC1$QUS{St)7l zE5NUuP@LE~-TmO7GXLU!=QKQKwCpQVpP*dQ|1pQSt@mDpS7yINt7rZo*>~-(c3FQ# z!Y3>hx4iT&yfE)e6sO!xaEJ3}t)BnFo4g?ZKg9m!+$wiaZpF!9_}g&*Ii4%w`#(~C zvw8L)Jcj3bHsAdV_n%`}BUt6e&Q*k1|Bi)cYo+)vMSV8A+#A=)>BM`%?_%Geh{l~= zzbE98{$tJqI?a6a6MVp*%6tEFJsTqXV7~LRc8!E5-IM<9^eQ+ouk8KbIW~o-gv!tI zlH+^=FEv)g`gaZd$$j;2BJKJUUShoLqv2We$q)I$6}NxD8@b%e1BuO)VJuFj!W+CI zZub+8!N)$YdRlvP<(E$R#){kP=$9%W-j(YVi`%yF_zkLm0`~LaCwO1Wt_Kgp|68cM zYW*HqQ2NtaD!;u?e^oA&CH49u`A@Cq^()62;&Lw@Qg{!_;(VFQJwI%moOazF_Z;>k z>VP%4M+d^=f#ihRGi!U0~6sV zi=@pPU%T9Em;d{nW7rqs+^e4GcPS$M`wg`|v3;esyWG>scwKQ)8-M_GRr{Z}e-zzhXa6 zi<3U^E9?&zMZ2nmNymRZH4J`eiN^bTtaIKhF8dJXJIhxS;Pp6Xa18ZX4)4VN40gSc zr-XFg{#fzzl=}37`@c8Y>~gPPPM4AYFQWed`$W#K9|bQ~Qu;;M&tFmJeg^^X;yY(# z8NB>dwRbY@omfgbyFXMOOU|qUR+biDc1(H3-m7^CZ@EKUwRN1A!d3qx*VW!r)U&(G zy>WEzE3Idu&~INxJT6%ApN#zuc>H3G=pgt-_$|Iavb+%+A)Pi6inj>t+rgVIkiOXu zfuH9b3X9t{F8AKMo8Lm70ewM!F=diL_Qr|;3@}g$&ELMM)d+qIiOnJth+rAnp z-eA4v)5XNYJePa@UbVjbmOq1pc3>aC^Xp*r|AJ55Df=_BssDAHq3{Om z8>6UjoXPO(ZI$P3e*Y>8ovVtpB-;BMd{~_7UlyLRqU^&*sGb%No#9dJr(x@{`S7`A zWp8n^7d~OF{5Bi?veD|V{z0mb<=f^i_xiopXNnW+ugNY?eV@}8R~N9~$bF$u^dl=t zr)lZ5`SV@)xOu9N<>!a+_Qle!4|`RXj{iQ-X83`Z6^E8T|8Th%hoKwfho#gfPZjAL zSR_9ehj)SR;X2xMeu97WMESw^3st2ve3$%Y^W#W(NTS+n{5bq}b48k+pZoF)(&_WQ z^4QS~s?aldhEej*H`KFLjO_jSVG!K^enpmQvJXqrI5Pd+@IOW31^ZuF zTy=&Y^L^jZt-9>T%#|N(9L)#dd2@N%VE200$<=%UkV}1LL zMAec`9iB(4)$VzDF89XEEZ=w;V)pq|&(-J`jFV1{57l3GAMzkPH}CygJ+su7edmu< zqO~^`K8F1;JD@)dUX{FL>yt8dq*IgoA*Rz8?%!`@A-v5Nt*h<2_;+{{&TF%ETKG%S zpZ2lrhf|;K@Szvwe~XhJ;Ya2x{u8nP6TbZw^~(r&nYz;V@9)tPzK#27ow1(@U$H>z zy*2P3;4!}E+Lz6~zUs5q%6(bojv?M`eKijr60i1_$)F!pt0((S8I-STqVp*{%=esh zC%olNBxA{^0UCR9i9`vbrcK99miRBunHZM1B zD4oab-){Xr3|?+k+Bn<~pL<;S(Bd$lk#u4^#HW^MIxoR9vJSNR_k_1?r13sEvnrYb z@5=LcyS{7qiu7j`Qbw}#ty178J8Gt$N_%4(%RYqjXlz|H8Xl2L{b=zy4}Nck`mr`T z`{8Rgs$9G7F7vANOY+^lwX3_!y?LrlUBzJ~^3n|Kx6f9;N27lmUjB&Yi$=uNym;wn z$tm73qkhn}iTKzh8eit;aW41D-CkY&z5xBF*q11&@n!kHVN>bk&8~ht!hEq8em+Hh z7>~{~_>?cDZ@fw~<6gavs0Z>xQ}o|;xu-wuy!>qA=r4E= z_V2Q|D%%qK2GX~6!dQ6DH&p-L_-7^jup>WP{V&4rq^RHRx!(9z(r^5_^zA;$ukf+6 z<+n2ES8uI(Dz3uNRMH3D$>mrdl2~9r(h%8rRA2nhDbJ?@#*?+<(6OX83;Jd&p1W2RqBpDd>OvhV&aO zQ~dWJ-U_!B-~Y4XP2O;vaqw-v@752)%fBr@SU!2Zopg?sRs7ibTxZ~OCMz$!Kz*LV zhZR(bx!^CfmrgQquIO@{0q{cXUu4gM%rL!Tg z;>7Y&SNM#HiZ}D~Sa>$pv6lBvz#DZ&pZREF7wNC^J+D~>&&D~7MX1jW_=?)9&sun? zH>K0{3*||xPcN6Jes|3LV()3(#=Z>Kan?tJx=Lr8?>wOC@HX$NUy>+yJA7KKxaF}- z-K4XL@9sNc-yA-=qVkyK+y3wYlNCP^*dH|>s_TM^@N?C(yK$A>DNryDqJPRIsoa!z zwGOoX0gl19G*iB^`?2-9%l>3w+UujU@W`C1XE>$g>mmE?+=u)hzq#C-uTS?=et3xe zQtU5s?tuB{2K=)Sjo+fgL$|l2e=fV~xsr9=xSryL=PQ$#9}dCKzp6ZM{3(1~9_iS3 zeEr^*PT1$tDM>x|!To;g*-Q3)hA0o%dU6gt!IxJb!E2sUx%XKojOZ<$(c3hB?fzt| zKH{C~%HGy*&O74i`2NV+l?0D#uYT!6{U^iy&$Zv}OS!&txR$}Q@SMfQ%YK)8?={`x zJe`8*U%>wMdCfcjv%hOU>Q8)zVE5pK}oV^aG?{q)poK`wDzyQrdhz7XDuj zMp35?3?e z{`b$1!6$JZQ*PS(0RDjY14H3?-}Cy#J%8Evep(Bcd-KSFHL9mQM~EFPe$IDY)&c(Z zAo;Bn`a|HszH@lz!~J=6pUb^C>Enx&``ABSqdXsje&ZpkPg~9>vT-pQe&C_jleS*U zKUDUur%0y zb-*y$?_~c*%QH>k+xgDa`f)70ZLG?*JbVH^fcWn~yE1$r{SwV&KO0^jp8USz*}h9! z4)?Erj==rTbN_L~Oi4XByR4d+(s1@gwm9e4k?FhQhCvQ#_d8TERQ@ zm(FT*9>D$Am5s(~JZ|yjnPD#X`aK`#4YfsQiOaouu4n%%D>vK6%Abz!eX}^1d-k(< zpY2<82EyC=zVnJ5C;P;*>R(&;4uku@_dEx0?z<0=_Y>*FR8BjuwTA~SRXk|b=Z-u0 zMb6i@cC{TZohrWf49COU{3So{pj|)0qrz0Ktt%I{_C0zQ2Dfc8ixW6LYz6WVDLHa{0Dc-DI!{Afcugv27Bz!*4gUmi)qI3ej)3|uT z4+>2ZAJx625nZ=Jy)#Gw`h!)LzS;F;yvnL^Fw!dQ})@m`F#|;XZ^JE z$OU*j*IBmC=`~gL$rvjCJfc1`T<+EX_`}+%Bmuq=o`G|Ct-pSUm%Ju_>gvPY$9S6S zpY(;DEHBAF$hhb5Nxv=k=j}RctY`1W=dBRgXW<9yv0ul1S1b1!+Ge!1RZkai%PYvG3 zu=+QJ-(ueen@^|1>-?+u9E|=KaQ}7U8JBzhFF!`@nvQ+u&s1*UXNp+!e<_!H_UCy1 zJ`nrH*k`+}dBNg*Ej%hp{bl(!`&{W4IUzr&*WCA(UGC|}zAA3}B-F=#uyx}~RyQ#F|+1|(K<8p7j55K6qku`&UkafQ7Z&%Sg z^%R{%mwWbS`Ci8QaXkD=8P#(jal0QL!Sg0DDxI+4N-{U*@;?Gr2<3Wq0Gv~14yiG<4y#_z=h03jj{-^Mr zSEXa)Wh4BcZ$H>Ii>3c@U$x8f`CYjGy}nnM$i5KQLAI`rTPl8kvg&F6SqZP%U)Z?!{I0Z`5Dou^$Z&cu#&aoh|V8zWp2Tx!fCHy_UwOD(s?whAX5W z&iO2x(C-GX*H-?qygd_MV7|s_MeMJ_{riFzUnzZOn8w{z;^#3u>4^NMC~}<6t7PAr z{dKKfm*MH#s$A>$Jga5Dk?*tYzF8c+9`R=RXDj?E?~RyFipxF!%$e0JwM8w`t6_!L zh_}qI@g7He>%t?q$v+kG=R}u#{pEi@`~>#X?@Ol_I=8T|%X@}a&wOiDZa8`AQ|!yQ z+|&2(w=fZY`kee@`Tu)(YhQj2UniYJ?ys63#=@_ss7GwxUkg8aL*vN44+{7~I(_qM z{^~?Mqu@hMNyqZoK)C<=iyZ5vQ`omJ-%Ie;Pc@H+qTd&OjrZzp9kLK!E<5gq4C$~~tzwER=b<<@pH_5SUG{k1}A+xsbe$_&LrRerPq?!S(>0YAq2+{RJh z2G!?sSB;lH0wh%UEAgSdl$V~N-y7b8eWEP?tb^ZbtMT3r`@oITX|z!7eHR`F-^u<$ z7KfAI{{5@3!;kWQU?e(GUrWCR`_YwvC&JIMZ<6KbS@6J4%45s0zX%_;TK=^9+=l!2 zGik9&<%V<4quGA|A3IJf4V$m`!2R!GR^Kcg|G7L#@E~8DPjR`IHe5AL6)+bn$i6Dy-PmZFn~F4>$2-DPGU!f==@k4{_6zr<%`+oi z?)f2@^VWN!KM(sw#T5@9!EeBiEL43e!*lOO|E&C<8{QheJ6T+_u;UDZ5ALr#U~#nq z-jsZ6@pB7)fcJszdL(d<%02(9>T`;Dp&LAb_dnmDK5Ja=t;e?eo;&=BeOBK&?}2-z ze~agmHvh)JCve|DUUi%q@JBl|U)z1}3-AZqYWzLU=M@>?@Y<)5u z9+pFSV<-MecS!aLZ#PPpXdHD zixbLk|Mx#7UGBB_)_z@?j>@9H&V%BTkX>5aGWpESLdf9Ob{H*$n9jNvuVP6ZLz`n|g zYR8!gf7DXtTDw{vl}-b$k8J!7hx^a9Ooj*KmX77myuUCmUeLI(=Ogu9?#07#<~8#} z?PKD%O1_d>b33m&=da?y-zvXZeInr3zLdve7^frQ-yKk13d0X4;M?XY{_XpkSB^`+ zj_>=6WccOB%A8iubMRYhr4!G%i~3F96SeW}YdXy3UVFFleQ`JHv)Sd|`s!RY`6mkg z6ZQ_*Q;F~g@M*sD=5n2o{!R9gu=PwOc;Ua5A8dRj!u{Vvt$;7({3*+~t$vq&>k5i1 zsk!?H!ngb;KU=&_hZiU;ej$Szkn^N;VmN=n{8<6Mko(^GX>S9#|9;eZcwA9MvgwpL zCH+~fqt2i+!sXt$>l3CK{B`(F?2pV>i|qO1X?WYA4N@&_zp1{brC+0|;_W&*`{Bzt z=Sx>xj`J8^!gsEE#2M*~_nlkR81DZLYro6A`tRlb>RrnH8+-rrsi+j`C%>qA_Qrk@ zybbSP*>ksSXJzmIuBVmDy>eroQ~b9j&U?WxX3$8ijsAFa5`6d5J~$_R|G8$#@TzCz zXWOS@=^wJc#Xe3pf8{x^=NC!7=a}_f?v1Z$-z(l$SssA@=er;HJNyRw*4p!?s0-4G zNvHLIU3Y&CAI*31md_u+5AvMU@^jsbp5OlOf302a)zkmI-_5-(hB+Dh)pFgPU z2+Ly~;GadSz2hnBWB8^&)GwXjB`-^-@MHCq)$?WemBGr}YPI96hL2gUabfodp1R!2 zSABfn0loaE^q*u@ycMV1ci=&s52e+ME?hU6Ic9_R2FhA9aPtPL;il z_lfYs%sXa(626mpIhy+1ak=;2*ZQk!X<>NCRh2tDMDvTi|M@oDnJxd@{x+N88(-77 zulb@l&}{vGyRuR{H2!W%77zuSG1 zz3`{eY4cd!>(cp{=iqi-GZ{XY`dFNAfDhQFd~5A}0v~rx@ndfTe7d>JLf&!KjJ-F zsa^A^Pj`6S%W3=l0KCRevbS-R>9%xwZB)67$djYsN&97A5&a+Fmy2q=On^K8N~g$m z>Dc?69pL`wl3QKw#q+|6if65^9Vgu#>Gh?&YQFGJ`G-It7>lXxf_0dfmY78|69KY(qFYr`nG7H(l%!xbln*WMb%uwR(6}(2WiI#T z>$s|_kIjRZu)p$>;>vW2Jyw0T`_5e&3it2pbs8T2wes+0+8g{t^TGqx`BCslmwSHb zI#2$$xcUH|o9_#({^#ITqtsr@GiCmhPEFr;f(h_0Efhc5GOFN0Pi3El{dmhzpC<5y zf2lq;UM|8jB+8$88NV+)lTN+Pij!gi=sQ_c+m(a;kxZu>eCAN~`w!^sfKTB0p!wlH z_&*($$E;ss)1hBqI;E-qIG3lc$GWTjS#s(R$=FwAzqK&z^QV{2(MXLWdmp|Zd|I)z zaWw&c#W$axhmU1{JR8eT;oB>!o;F{EW>C2f?~T7mecHgMO_!g|{v5m|=iTJPJ~X3r z{PTFM%e{5TLf<*OZLn|NNOAr z&lA)3*C+6g4r$!ILBId)axXt8|E&D{KK1Dnz{q+o8!wm7YNcd(;4FM0 z@4;HU#b)+&{_lVBF86e9Wl^4KhsiE@!u+)B$$VL4f8~+JwZ+fd@WVXslbYk~fOo7Y zKUm(&kySd)9!cNgwgtTKW+{}VKKG+2 zYqNI!4lh4RHIK#q4*VqFby_~`8YrE@!K#n(AK~T8$ZxsO3C!iiv-|#GlG4$hdOFw?Q;=$(kKJYr}m6z`tW>Pv_3b#&4veEeI-@czHiD_P&z5YG$Yt`aX)yMU`4E= z%e{XKpIcPi=J#9h6=fAy)-Q2|q+jB1)h7x6bc46%ennaMIC%Q%(kTU>_ndSR5;RWN z!~b@<7Y|1`FD5TMOJVinEuK#?Or07o_x#!GYvl)9kBx!*pX>b%pTvEJH_*@hymac$ zQNJX^-+&+F+!o6-GvV*NqjD`@U4lp4RlivNsaZt&=O3%RwKJ%IGw?cmM`QgPQdIUi zrz$_#`hPzB=%e^l0rTfR__dLWL%U9C7%H7}In^%vzTg{|d*foG?|I*2>~l|7ez5+H zC?=hyoY!ObLps6-^S!yzuRj*b`~v zEvc0BcSmWwTRxu!AN`^HZ1?xRg->`{@nijU3Eq}{+DqfN$kNjPWxvMza(DuKAnV57 z@Qv^d|7g7t1n(0ro%2Q1E{mUC@NF~Y{}R~$1COezc16I;m61;3Rr#S$fc{WCLOhu7 z?yY}6h3{OW_|J~cF8G)0RIbgN*WqW!tDe@6!DXd?eVF`U`QZrM$slgeZC{9#ePiAq zw*2`SJc;WUtLHZOf1KxN{!dpBH&lOn9y z-o`~#W$FLOe*5dunc;G8eeUGd`aBDKC-yzK|7_R4De#RgRR4{_WuBS^pox{wjPO-$!?Z=d3E7vB_$e^;cs0?r*e`}h`@W~R z1aHqiv{kXsUR~v$?j@ab@S5JtL=RNk) z*ypJ!ojOxBj~GvIx!0}@3l#rrS(uJ>d2Z)6^8@5x%pL%We9yc*gSb!xuR8 zGvnnnquIFL4}apDryA6gPCoWUv3d4WxPM=!*Q1c)4C#t>*a)3WbZ#$ z*jQKwzs7qbwx0P8zK{DA zN$A{!ub8I#ya#{oRb97+avyahe38q&@l~j+@`JL0VP=NgTd_t8m) zUw>a2vLyV1%e{P9-gkeaTodVRsHXOg!9EH8!1vzT0(iL358L4bI1eQpowIQNIwW&b z`Tx9czqoLhdw%dgKYa&&h4*6%qdyZqoBKQ#pX=cfBjtx!>@UKL+)-Rve`Rl`a=WlE zmd&$q@Y0;CX#5NKh@=Lo$`#Rn3a^?^`KloKD!7I8xA0z~+1G-foTd1;`Q?4M|Gu2l zQaUyF=*rIaKi>nt!+UOae=ln**>At1_J&f=Soj;IHBO`9bKvdyzVdZ=Kx^p?FRk^4 zUB6d?f6M#KHXrqb2W?V(US<4tcuhLh=PRCzqdx(DdzQxIdiZbfF!p~|l)BG_+el~E z7xKe+>|cQU&+8cizi~==tQ+>L;W>CNY;ls}^4v~g=RqBfxQy68#{O6{)x`3Alh+l` z?GH=;3+#Kk+>7T1)pWgM_aAn_Yx2E-#Z{RE*{5g!99v&qgdh7%?X~whYP=!)Hu=<# zcHOiDUhjbH-=;qI;9Gb-z`I^hzgXN>?xKDP_Vvr#E-&WpC*ZK3Ko%Ok&gEWzZM>(rvVFWWzbRg7g35gn z`#0d_XjcyS0GE5$t;xRY)|D>z`mw=_it|Vk$8qcnR98N+>)deI!%YL@$ z!}BGpp0+=5;~vuS?{nVtE%5=q>y9Px9$c?2Bv5wsl>M{%%BUIzZsBi>N99v})N04M z<#Mmzqe`mZEg$CYCHsZ9YNyuR=8NL+Q)6Xse&`6_GGFV5pNXHUy`|ItC)Htkrc<)7_zT1&AKsI+IDc+{>|@_l&&sQgQx9GXq?MEKUdAHcqm2vJ7E8~khuQWJy#1}`LW1H z*l&S9WuLC>@PZ$x+}W+t=EGOvG3;w$^&bfDxkdWM&%npP%c37MT>5*S^owy6~Qv6+ep@zq{eBeCHkf3-1%6ezZ7waisM9?=#PU zuPLE=uA*I6;2Aq8Ki4BpdXAFLqV8&M682N!RfD8s^-qR}O( z#zIp2fPnZ68mDGO27O{%{z8qcMN=j@4D$G zd{7~c3tN}QOps1&FU6a#J{;!_mwV5NhWoyAnSg!bTItw2|1Xz&c{P6()jw;1Dw<=W z^j8&E{^>~lBjHa^s$3gi@Cih!CNLM-!7rtf8Y!FzR&a%rb=hd3B|e1%WGZk^;f>{<^K`r+{Jz_ z_oK?e3rv$v_W>GrcAu&R-0|(NI34c49z5&vU^M^tKV_y%f9MWf-)$rR?}ImgN#oJR zSKtiU`_DZe4nM~GPL^kO!AtzA@%Rn%T9KL33Fms;{M;2Du|@uwKxGfW3y_CxKDrOz z#5ot=U>`M0`Zw<=-t2khS$O!mmr^Y)PIAtc{o)^$ha2ICkKmPk=aT#Z_n+?*Hb*+G zXRE*TzmBuO@(*S@Fw3I1fV;%YwQH}Es%fdamBl#V*1!q;#fncbi7J6HNexKC9Ae=dMGeO~^#0?#y0_6fggyjYyKfzNHA z`n1JlRgZ_IwSD#dZi!^7LD-z~2C zz;o~&S$XO++vQ%rtold!%JRuJ?ET++1};>&+u0w_#%URN|DP1+Hjj^l`|ta0hbJ#m z&2v+q-{1ke<%ei^wnZw}zn^(o_>PwpY37GT@OeGtNy{@=;WsPGKN09>SuB13bNpKH zk(|$Hd0;GjINzOZM(11j&BCh52KeVoq<>_W+GTN=ZmIaaiyDvi-AZ%#wm+1AET7DU zFRY_>twsMlyeId`e}Ly-hTqQ0KXzZP6+Cdb>SOcoa`*<$eX#4(zg+(R%Ae_$OaD6O zp(j#qNqEAu+Ns3u1HTDh!9J+whf(mIyjNcloz3ve@5v7};J?8`qSdbV$*Vb5s6M^e zC&b2eMR-^RjnhNujDe@{9MIO)d*DxZN#E-ECwv0yE8}4+Rc^+iY4iL{mwV$YA-nwi z2IYQ%{W{)@u=VOW_{QAISM9Mcze@U7w`*RodA1k4vhRDDZ(Z({>)!|REPPcP_4pa| zYpj<3@l~q-N%&Csw(|17#mQ9o&YPBdq)Y_ubHL#Tb|hfkG`h< zI*QIsc%6J&&r}Q0AFi!axmRW>e_H)t{6f6Nck-u=-y!gEoR4N>>I=C4e7!61a%H8H zi~5vVFa1wes-BjYdczxW?tE_S=fW44)%cqr#sS)3$plHX4BYnJMn-|){0mwSGzkxOx6?Ye>e#Q?>Le&skh zHp@QqV8!jY3=)ciPiT=g?~R80&oQa6MLLe}yYG?k!*LqF)~+Am{{7QJwo0cy-$}_! zj`Jq`#fkEd_3wCirOq0^_8jB{{C0xk+{!JsP5MhY=dlugn+e~`{>J9#o$!e7RTJ}P zg>R&@WrNmZcAmm}F1Ozzo%+wG*!#aXTmi32zOw7V9q^DwYHwx4Qs5idr*t@c;da$$ z#&r3)6#O@MJNB)$bztTlvX5IRzga$S4WGt&re;3_9>M#fR?qwJu<07VHoiLUlz#4v zn!l_c|A6o3xu^Lv!!FtT_f0JZe~tYd%(si-b>h^&mIpE>OJ}F=eAqYO7_=g||7SJYd%~<@QP^Um1<}=c)hO z@Is^2-Z=OQ_;L1~w)NHb@GYFDrmGvrDYj4gA$gRStUmqW&-m`u_y)Lt|M^4k^SrlH zminBBhxb$e+VxkJ{VF#oByFBw49~~;vu~nP_&eEG=DVbB@HgNsUs6BX_xRtz16fao zU>|%yI{VjYzPnAoZ-fVJlm9LLvwp9*3alg^gHA1%d-?nt^|5u@7J zN%=fGI@u3OXF2EHTYD4W{_`1^!Y}&nt6YZr$4l%F(of-hSc{(t@CkF3XDm*R!$bbm z2zs7%`_MzuS=B;uQkwejfk)oebwpM8X_tHBG2&x+U->F%? z8UT0rzBm^;yWmGTKf>yt;jr`@aeZX@^CkF#eTp|LcL@CakFwO$H^;dLPq$Bguy~05 zN%}{QDjqcY9Or%bki}}3y~p*n*)Nk$75tg?h;-`s_OGrFANQyHY|ra|fUjAqIDY}1 z0zXTq7yGN*x+NO!KR57w_zKSTvvy@XDxF)b6D&Rhei0wELUCf>Ep~z*=KVd>84It> zcd7D{<9zROFCLC=mjAz@A2S`3{>>7K6RUqom#2P5UsXL4hkYIFC$Mf;R&ktn;Z521 z!1^~Ce&;QX_t!H@sN1iq&)DPY!3OwqqRUgiOP!?o(em(SmwV&===!wz;S7BJUU4h8 z*>TxNc8O0d(5{Q8z=!j^tSs%?1Ru)zo<-ol!u{_(X8le2br-4JFzl1yCub|3yTE6_ z{oilyfcy8g`}lK3J4=sMO zos@l2xJpb$zdzi6Ug1sns!SSRc7LGMDd}9xqw&}YohI;?UexvM0pj6T_<xA8Iy-tw+=)}vGZjC9VImw)tE$N3EYG)VOvjQt*XgD~maxVQ;# z$#=nPv9FjS{afr0pzPr|h0cl}si1NWJUU76 zwmUSgOTs6>nVr&#@G z!h6(98@E|5OQ#6mKbA)SZTQqoD%a-OY48ba)W7D>JMi1<)W1RKeDtUEGwzeU&5z+% z#OuDJ_U6IhOC!m(P!VN0)og z)~rk8IrCbGbMFE`Rz;s%1Xx>s*)q_UBbk8+Se7o!F1J z7`j%suCA1a@Pl}ld+loUvf|2~-%ZE<#E+^^N9=!sKjB<3TdxNEEq(twVJ$ppkn*H` zM_=@o><_aKwvE#U@N93&pEe(T2d`R5@oeq73SYx|z<9=gr0;)U>pghoDH>nq&-rlw z`-H7-OQ%7Y{9yWf;rVzEO-Q*^dpbvWo_LFT z#$%tw_xQ|)pDBM@xqV#jl{-2>^&gx;1+T~cBA%W83>H7DUGC|mzpi!TkJSGc?7PlXdke$wzz6eQZbx{|$I?&c96HNaV_j}J z6Vudx=3`$ZMdhyGkKe+u3 zTU_qdzs7ate|zsG(=+j~K;;>0Z+ZBdo8lFze-HSB6!F~fweWM3RFf<4JWjUMa;xoA zyuAUBhdRgBbZU5AoC2%m@pN)5izs>t>iRes+FFc|CIuAb%uXHJ`pQ8e#KeL&}myMS$@Xm!4=S$I92%pP- z!t#dW%+4&GPJAb8?cD}1&-vr!&`HT6`!l(<9g5l@j{_iV)3Bu1)AAOJ&z_f5Id7Dq`*Zx>3Q>f5bTv6{zPj_$KnLU3VOZ_vZPC?%KKeDv#o- z!5sB(bMnkSmwRz_^DVW@`aLv6_9gDBrD517x!kkA$om-9U!&mx>2)XY3iUh&uj+em zGhbfmtax7jS5|SHhVWjmX?)e;dgmd0SOeAH?mx87C!K(+s{e4xoe9sxeIXk!h4ah) z-WBDy==A!*O8C$hRiBQ`Q&kGc52vqbJa$6Algm9nEG#a2^TT|Xd-qEl@LqHQ?2lkS zAh*^J7AM&YN+;=C#kuL!f=_rwahrh75cpHphlSujz~fj)S$iuNQhf^ezNdT3P)Iqg0=7(9iaq?6*g$e{4PIbWp#SKz~2HdR<*HjV3`HBII(kVC&L3d-&tOAobO!jt#5;T>szO|bS|Dz{q1>KB0Q3FsVv_1!*g)% zo88CDSVB4nIj2mskK@d7dFnc|yfS1T+Vw5=Pb(=BzJhNrDV=xdUt4!IDkWZkee4yD zjx!wIw7zr{Meg^E@LtE$=AUk*rL$?U@{G+36X83blOM`apY<;HuD^CalD+x!5cZks zs>FlX7YmnueS{{JmHsf!fwK3qw!7TRw{3ji4V}XNW+6R4vUqqoQaXiR zS3apoxr5*lJom9YFdIJScdgUx{E=?uq|wp~59|@2#Qle5 z6;%Il&I7XfVxP;s{9Jd1@_!HX|Adc>SESjxsA?4T8KJz?pFFb|p6`(2XFNJr;Qc;N zo8Kx_l+OI=nt$y+&*$*yuVt_3b)5U~V`r7eDiK#zqop&0`0q!#De$G=Y9!io*yu{K z&(=VmA4UDgRQCMio?pOzq{Y!$>vGRO>#wQY*Wgd#r#U~UB)mfv*{|Td_*zyU_<)*< z^HT6kFUUT}80lNw7K0CEeLD>Mb}skgc~zkNY&wIm5BKfcHVYn9QT;e5gM|Kext9-{ zk`Hl%^IQz|8KQWw`REn+-Z1&CJoOm`k6fyGVLkj;_!{4P3ni*a|2Fr%ZGL>{a&LU~ z;ryu>bPC4Geo$H6f0&$EfA|FcAX($W)@jG#E7;$oEIJjdOJ^zf|Me@!X$>FB`NB3I zO@_ZZUw$?}Tyc47KKH%98dO9216C-{n0-C?vd;3S&A;!$qdB+Bo@XsKolc5di-(`# zix-Gno-FX9$~`hlEmGEX+XertkIJ?2I0Zg|^B}t6pWX1?r!*dWFurQllz#2&jZ-b7 zh@VsNob0=0@eo%__J?^+WaDKtJf^bzW9zOT;kmiLU7Y&lh?CBvFy(>V@T&0rZ zK$m;{lIXh*T917f_OGz{?wIj;%43#)s@7Jy+c;O$t}FY&_p+a)qQY?|z*F8+Jxk)Z zTy><=xLaEPzv6Ol-0k*#2Ra)2pO(tro|kQhAMu@g_!~T=mGX)C;iZ>U?)51ekM`aA z7WjdOYOnS0D|KaG{Uz1^Abws5pL1Aw$@ZuH6W(Zm_!QdP;bq#pUh!%BwylD{#{TnG z&(M0Z&l9Y?RGMr1ERWc5fW_Kn~h`L5scWEXg+NR5h8ijDVP@RX;uQ!Q?CiX3{c$ffBs3-l`X~c2(wu!2b z<-_K$N~byB5hr5*HazG%_3z{W{h@EX?E7*~la+f29Z74sh;-yVkf*d-~Fw{{%_-hxZ6Tc>{#72c`K|)ISAgniag_w$QdQ%tGya(ZFTF$cG@Y&RU(0J{XnrozQsoW^ zm%iosF7P4GDPqn3349g%lJ%n8vaO`!f49l%wGO z{Z)Q}-+o^GZu91S_-NKq7H?Z#lm1`-r1kSzcnsg`Ri|AU+Q@!WLB)^Nvl6`Rbj|P6 zu%8Ow_KEDR+;i|@>?dQq_3P5_!}V+^IzPj!vfeZM>+mOhcVqnZD=>$rBZFVsf<+=zch!z;H{{9E3;3J)%-arYGaa_yxP9WG@>i{tc$ z``{UzmBAgwHD8d^U`Iwe_w?Pouog^cm8`X`1UxBN6Sms;mu!E{U>Eq!@lUO zc`7Pec|Hs6z3*}_-`>8j^^(1p`(_vMZJhIB_cIs3w`W$lwr;!yf9iYgANr}8$yA@;i`q#f5A;8z|qep$!1>>>U5YRU{+ojT5k@Wp&DY1c1@ z;nz3FlV+d)E$M{Bt3~FA7B2VJMdygOKKNm<%f0$1-fNypY`ymxI$fG+yxV>_MSDs= zM^(jVe{`C_OR?{V#m@kEr`4+GH`s52`@gF_2~TON`j@~y@NJdr-{0&4JUCc!^&<9> zy=32)@2@TY2lW=O%l8*y*eAH$yFS|B+xL4S_D9>Oy|%AccpvGcun$#xbl!%y^JY)Aa{=j}pC&io1YvFyRznJsRicp^(@bG2oM_d1Y?Q-w_Rp=G@-}3EW z*!%Ctj_W7=VCE@Xj}`APzN(4pZ+@!@pVA>MPk>*2J8ixi0r!7rTKQe+2mP(9q4&N0)p4iE1kUSpUw(J_q~vDk>c3 zEPPFj^7Aj~*B>Z-|GAKpT<*nH;R>q%KJ1rcpRbDg>l5PbnajQUtRLPw)iSTue~|QV zSCOA>+?9jhTBtm50-de!b4ArIUCp`gBfTe`#68NxmaqE3{paWIfX{EH47Mu0D)a!} zopq7rrBZ{{-eUt4w+C{_zKhGfd9x+&jpU|XW8q1x&jaCK!3VP+><0MSA=0V;o${et z?KpSfCwkgIu{t>bdM<)rMk@p!w;h(`nDyx4jevZPg#i(7Dw{yKO{kyLy|5zNh zg8Q$Fe{y*+W&Q7e{xJLh)Khj}ef2Q;Ga;|??IwQoqsu*irZ6w7R&M`(AbudKL8_(Q z$LJ4FV;&Q+It<0X#qTN(cp8zr4(6QwhNanTzd z^GNGG`+jP>*&on&3_~Y)v~*TYNZYR0;b;3w-{#X%@WVf9yjz~U0-s((e$ZbXr|5^$ zujJeBx-~qU`|T~L|6+LCda8e;^r~p|80oakmbRW>!&~znZ(-W?1H3WcF zc3J&vefc4{cxc{85OrOX; zXD#`sH}&iS|N3*SC!0~vS_0J^EP0oVOzvz6&_qpb` zLK9SO)K?lunl&7!2i(6;-8A^vS2Qjx|D1x);C*1zsXtNeJ<9i_5ApM7F8AVU%SE-z z^7b+KcfG`|o{!-{JU6j8sXj?M+pj1u*>zl3c>gz)=k0p=Px!*g>X&NxCw8)Q{QF=m zfCo00y@&odkDe?D>^KJrJ6i-(k3da88tty4a?`y21T!+hT>{R_{= z^Dmp%icXVG^DAnveebyp9{QpBw>;%;g@4~fJ!SJ(=IPSe&G+e+pBumjTvD7{-Z%~4 zP(l8QM*q$X=^PxSei@uqe;7AY+0VEXRqSr8sZOeO-(55ia-Q zDw+2@El!TW&o@&&t^Q+Y%f4qj<$({W{|b249%kd=~pz6{G$iyWGn&aRXG($K=l= z*cT|Qc({;3KWH#dIz^hQy|&Jr;&M-Cdo%eb6#cE(Hx86P6?KktXufpjhpPT%vA+oK zGgtb#;UyO6I(lKGuBZCIUvatDk7YY4&sZMl3m>yMZNJQhSIwpR*qZILh0GNco|?khjjX5zYISASM_f<_z9Q) zzx;3=`vSaguk7lcSGZi|#w^f!#`^aycs8EzTYV|{S^Eh-%XUm z{?cmM&%L9#$_|fMBi<-p zmHWav@r=Ibx$WRvK2?3Jzh=YxlebGy&u#EkL)0%84}HFneytA5pMlsfg!{+W5qR5T znrCgl<>>X&**i!1*>tA4{QuQ2tFa&Wj^fJl;VJm2k5y083Hws|(;g{u-pQtEGp90{V;SK=A#s9$E%uHqZT{pZ6rgHQ6kS2GRXi}Q2M&wE_%^{*45xSfN3#;>J6 zmhUd#C69$|5|6o{cG-QE_V7w$(XzQP8+^cu=zU5BYPvCr$O7N+0|30*r;dgFmyjVZh*d?8((P{go zEqrc2^{PD2hv!LFxs}-$!tRswhc9J*wCj{@ z@c!xLVf!Ai@VC-g$9)@H$JT@g_?~|af}h+g|6Bh~ak+PWn(TW&>Idv^a^8W(dB|>+ zJDhoTFzsp%e~<5~Y<^q@_rL%1H$0Z-Bi1jk?~#7oud1i*L%13q%l86yeRl=!&yykh zq?501d}3jsgJXrO#^}{oG-~si^5_HObFCG8-zd5`O&jD?&`~V)2sD5#;xKjVy<#I1C zExo1sSAm}}`@iG|-JNrs#DgmL-FOQAh3`Ga`|$p&l=rry6aAy=6P6?oAI+dYT!;J5vu=J^_Jg@EAuqY} z6uio2#aqMl(s>B~gY~w(Z`tK1>0IZ#Hp?6H;R|~!-prrjM`V9;w@S48+h4&W(~DPU zeR39lZ=A-L<>y>KODB1$cw79?3f`9Mcbhkd!yDbv$V$fkAp8OE|ESj-r|MDZ7da#5ueMjf5qjVPUDQyuM8iEeI4FAGQWKc&zN7H zv3|S=Z_PPz)-R9Yf#0bg?fcXA$5o#xeDB$ta({K|HN zvL9buag`fh6+UaI+EocY5$=DE zc>=z@xBRvi`*Ht2`#FT1lAr5UR$Lv!zKhE}KR@WMaur36lMKJYb*TB_cewxD!z`zz z)0%Ty&Cku@2Nx;-^rYM|@UP~`4`#m!o{4$W;x_vk=_hgBkqe!Q@S~9$DR%$%Q+P^F z#ceU{H^TkzhnGo_{``s>*S0V8ZFnB`yDo%Ig|o6Ba#-WY?n{qzxi=mg#j9V+VZR#t z%k0Z!@p%>g+N+xPk78f?ob&sF9Aoe zigcdv-juDAhq>I_HzNz@X(I28!`}bAFXXCp5@)F2?S5Auct7UH0SK*tw|`xE;5z)5 zYtoq#uW@R5ukv5wRqIIE&evE1Z@pFRwd;jH;9EJDryKf(u1lv7-#g@lH-{Hlr+zF4 zUjqCafDA)PjSXJ>ii7Ci9PwDC~wChaPx@oW3WjDX+czM}Q}RhN6?y7}jd zpW*aZ*}tW8fc=eay)+Q+KNsvad?)YAS-TG2l1@^uwD~ajAMw{ZiYMWRI&lAYvPa-u z=V=_-{hZ>rrE}GH-g+;1k@M=uHknjFy?`Y&kd2iqR4$;1^$%p z<1C+4yd(XJp^ATNS4Vhz-}}a+;r@Lrv)z@>oJq=i*6;P<^FLR=+x#^ZJ~Bdi%;vib z@GR^fZv9^Ap7j0urL=?}=R0D%53>`#oOMVE`m5x9>BOE;ywzsixX$HXTy;GvKm1Kx zoy5L!r2KgVonjB9Mn!fi= ze|aYT^W3+w^+2$bJ#}6V<6L#SKNbP+yI&(Ef^s{2z(S>nXd=Y61^y zrE$8CJaZc!=sUloe0u5hD5dr)svRdbgLtDg8b?>C&p3Dq&KtG)Wf6SUYwGuC>@UFU z@ZO#EW1Ec9Z#i1=7K;5R@Y6gm_!Pb$-iYrIEzi`;ls&b-@&#*L*t+*^mwW4<_N?=* zzgA-(P&__Wxh~`A2=>|5s{Yw2_b$9wUgfcE2kKcgo9w4{lHbgqP2k5lFS`=uUWRA!oj+9~yL8rP(|EM|U`^l?ODJyt z!q11`EfclQvF}66 zO@m~gk^N`X`;IdJ9-Bc5b|3Fcc#oyZpH}}v@Zn*ypF=&L&n84{(UU(!~N$5 zz7s5+71MM*@*ev0;bZtNbrAepc>6_auleU8{QS>~Tl;RMS{~`&+oFEA=RV)VkNNID zs)fvHuC4R8IA8 z56_!VI)NXmJ{E^n;p^G=tPJ+;;Fnuy+}XS^4IbJ`<=Xia*Wl5-hip3K@~hlzj_NZ8 z{ho0Ddo`QjPhOV3-Ov9W?%(&IaslZ-xTJUsMt{1?z3aFYzWo+9V())nw`M`<^!QT! zaul6+;4vHIH+z5e8<%_IZccrTJ6kVhC?uU^_Ph8Hok)0CevLcpuTk)9yiZ#J`z7!= z&Y80Q+6}MXQ~AX5>Q(s3h2nPo8~vQ>6MR8=$*$Liz@LU`=C$_z8xYho-jF^6)#)tK0??7qN?B8&;Nh7p4GnZ(Z1g~ z-?_e?>uTTg%l-Vb$Q4KmT_#TSnF*`@_6&~=9 z@S5aDcwXXbEVn25ajqLnkY|xES%Q9%Jn*yPrr*{M?r5?6lJ>7xN4aI@qkmCAJvO|xD#{+w8zS`C;R0D`B|Ld3nhLH!Y!;J8h`bWv{ zO~yEq__23}PLaZh|IxIMBEMW0d8Q2ceDX-{s~4SX%u?w%cFQm#byQo4w(zouk!7adZ6>#_J~ZzF~YvZg8Ko#BGz>=*NS@kokXN zK=e}F)LF^rbmHg9v=4rW`uApiHqkzm>pEEcz*chozRi#1ox?F6 z<@&l=edrvi4gEpXk0#g8`Pok1qY-*U{5hflbh`5Ve3`#KAg{{zXT|c0G{P2|g z*f7Mc__L!2bW*whQ^wI~#ZCV^9!3o-*r5UYY2UKE_4ume2_2Vk!(NA^xMu zzg67ykIM`AL9Pq(c|(7wcK@m-xgGZ& zk0IaJ5#v|#uKu;9YdS%+LDi- zgt(RW%Vvx~ykCf9S-` zLl27oJCVE8L!8KS^ReVP+IL~rk*EKJb@E!~&r9U`^SBq}SwHz&YEpyssS|+u*l6dp z_aLu44f#{%uLUw4Wzj+gE>)TtBD9HyAqE9jxcUN#y$eSKyMjdnj(&SKW#DUrxVGpna&npM^9ezd-J%ox@-sYU=#?pBjpr`R9$VkOwx= zB#Ato=N3vlpCZ3E4CA*7?XQ#T=bkm}K>c>OFDlQwCy-wZK>fQ?=Lq?3es@^L*H7d= z@1Wmh{Tvtu{dq$WhqBLV9r<*=rz!njxFhTzeu#PDXXfFNTuz zX~pl9VbmK&9Qm_7(3gD?`6FOoxGel|mhJUc+?-ES_`Ssn6o9I;&Z(J9#l}zj}Yg&Fk*9+P>(eikstQ zqqdLqAa!!N4lGIi`{Z61QP0`r?Yg2qIeXv-IWKo9xwH1XESvn&N{nAwkGXe)P7&@~ zC{6un#m#!Q?Sc93d-5Z+zx5l+btEqlh4!x3-c$Bb+#J8x`QDk#BcsX3^Svh-zfZ_d zEkwV6P5sxqLr4F<>Qu$edY)|$`*hlWLVNvO$JctGo=MvMkOaledfpm`IF$Qox5=|I z5LeZy@7WXfb$&p8ZdwR`Xx9t(1CLe4{XqOxy)UV_sh{vB`cd|MwTuR@e-C^p^;5{V zoJJmNL_Uo?gXaiI{y9bN!}nFk(!OSI=!dOGzYFh3-jeU};jf1A5&7l{7}qPP^P}Qs zJSS`C55FD*|KAHjoIIg@yy9ki4~~aF<^9TE$UD!m&SO1dq3^BfuUFjE@q8aOEKB{% z;Uyz5khmP!xtyi+WY<+ z$&d4WwA<9lN`%hDJ?QsMK_a{ho3Z{JkstaG$ld2+ zyyRm(xibLmiaCnQ3*HWUayMoAjFT*_5oAv2U-h3teCiCoK@?P5a z6!wwtn1Ob+rJo%Jqg?%5!4SnQ&x3d_Ssj)ePkVb_mq~ki0d`l85oTX|is4hr9#Nd4snNqih;&#O+=3F(L5hY5Ku4 z9Xi=Dh)=n1Ihwo=&*4dC{a2B%k3)NJ(-BpNK*x7I;?{xo?aB4`)2EP!Cc!`QKFE2+ z&A2^Z13HKb!zeZs`nH!5&o`()l{}Q^Hp@Eji16>wE?Ku!8wQOLD)Z&>OI?T&}G}K<=NUk?Zfr zEhjJFg2?=k@$(~j$hL5cjuWb5IE;e+k{a+^ck&M83#VcH?q&TCl6&=leH85rj)uDsC z`LF}|A-=aO<0Xy!$yD^O8+G0#Pvw7yyet{lZ<3GUJ`-du z!`MLnF3g<2Sk4^xed=nti_-1B6nSk{1Zi9dNOq8RY$)|S>EIeheKcX+YBR5 zIRL(iI%moC`&W77AJ0U)ByY5zf^sjG!FZ8!%TEQ*WIW5b?y9)CZqJ#A>!2De_f6W@ zS1GRP-!e}Y^eog$CTMgJyH{}K6-8JMqK$Q`Cbf9MeF zerZ9T&GYW+(f$p^&G>144)u}q3768oEYDYzJaC14_m}Wn26a4VpxnL{P_E2V+>Vd zW&Z6!UOoo#Aod%`$8^Lz_$GDo$U{GcJxWpQqFK<-)6Tc?Any?jOAqS2Nxu6K{3iL~ zH}cpih<}N<4zr=Je>Z0o`OFrmPf6;3P2QrKH7_)WemH~mr%cIek}J#^3^;SMf}r$5%i07L!OcSIfu!^cs`pWb@DHU{Zu=QYd7*p z#m)MhEy(y}f6b$PTb{cj{;#l-pf9hboL*->0;Y{9GQ& zEngS~$G#68ec$5-a{au5OXM&3JZJ^)JJneMorCj(EyA+yny9#WAIYeM>xC4ycOC6r zpCR8CBR@iZxD5Io+1@Z7kf(OWxR(0~%|Af7u|CLehAo6@tt2mi_DX&WA-~0a$kM-) z$v-H8o|SS7u7XZ@YxJ*_8>+Y&|JM(Lk74|0(0&}>|BYq499Bcehu>q8Jn$CzHtq+I z@v?zj|87O4HP9)box3=T+@}TVKbYm7A@^T}b%F!)#?ZCU*}~^s@|-Sq9r(~Yh_^b_ znLyr|`(tICo+kG?fc_HyR9FxHjB5cMxj!~padSQjZH;=$x@!}8<#%B3&2kHDfW3as zp)Yw9-)ols9ZJ5kE!tbJ0EC)ugpPhcY8?5miHILJmV1tTYcWKE%*&6+TdhOCx1@co z524>V5qU<=^9d%u#rFh7XDPV{=QWA9+MD3F{hvVJU|e-j-1OTVKF62&Xq?5Km3Zkt z@6vwWNW{Nfw|-0Re++&;%imPr4E+?g7g@+KBFGQ%oJ{nZVGJREKOOqgk8>4wc&Q%p zKUdQ}{3!ZGo-ey?L3{1Gqdq?}J{Ku&ws(asu2|){hT})DKY1E{PGbRm6*uiOdm%qm zAzw=#xdu9Gm>;%mg?-jNaSi!@ ztPLtuWIJ@Ge~9+Vx~P-l=5sVJ?fK(I+TU7_@g@D}umd{d_@4L#wzmiQNah*ICrild z*kdIi`Nwf5bT&4@{Ri2HFoAq~3j8eoIY_>?73_uIATQD!5weZ-sj&OF-|0>JQRHhmE<}H?;(rxamuO%95Jr%!#|rI+eql%SOD6NcEb_-)5huB1sYRZsxat4(g)q{qlYdNpjPHGPCeJ26y%zJk zd`DpOe(1ct8SBz2%vY5Tfa~YH#gW(Ld4|$olgah-XU-{Zj*G+E{(<}lq2FvW{49P8 zCig1~Kd)o`^T?NXMZQ`=?(#8oit)Nq@_#7#x%6~(Z7=4p3z?4uO9yi%FReXyQZ=}%gC#;y^=SI9frPR zVT|jyXIS1Hv0m3(_U^ou>?t@aU=Ys2q`JJ7xpdD|*zS33Cu@(y1@ zzmpCA@EdvfQq-q8?W-Mye)cr@ttojBx&D3dQHq=E-h(x)*S+u4-izObmwtIheruR@ zzAb+Y0Tv?f;jUHOEZ4EVb-8C~fASvUQ{vAl)`I1EFwC4JMH@V+L%(Ji2pWerzGcp8uL*BD^pL{3pKbK&;&XLD8f&FS*{9)G# z`e8B3^`ZSu^0Hi)N`7`f3H#oSF&~NFYJU!1n&%0N|6|Fcs=)seKNHA5;QHL2<*p*{ z&i582o==g73`T!ReO{37eivNk9oJK+&y%@mS3l~HQQVCGtB(-pGG8yHy-Rt-v)u1J zMxOZ^<|(-k^O*b#eqU)K_1k=ba*y+T6?n-oGRX(u#kiP6`--PgALq8H&vEit#m&5N z`UBKo_M2_D*c-;_%B^UL|9naN$Gpyx_0rGez5Am6(q5-C(0A{Mb)!4u>O;j%|J>pG z6ziD>?$CaJ`%p`P;^(Sop;PP_GLnqn1LO_(zNg$bxJ9miN7&;WbjI*|9PVsgJo!m& zyv!rFJAphY{d-?2W5U=Ond$NU%SYAcSC&2b)3yb==&E(|B8;Q;->$17eeGLVY&Ti@8g8_9weVn z?ybECdY4@P&X@O>C^vi!)+Z-RK$x#FhZ^mEmE z(*6nKN7f0m$*c0cY#A4MrwwM`S~*7vE&u5vHnF6Zy%8t%msJl`55)d-N}#pTaVK>$ZdHZn$&Y6 zxqfcmP4Xfu5wWuGwEMRx_i>lDmJ$~*|NKb4^DO+S?&w+msdOFoIgQc35}&Qei?^|k zlM&?l_ijERe|7`ylJW9A`8T}3ExgcoSm&f@>y}1}o8vLn1v+SjVYDSrjz#}2XIxz) zuW%RnP4w+=K&Rd^v{%|SMz{m|3)#squ9KH84B|xpH2WSp!|P+6_D&)EVT0o4{r`L1 zM_EDt)@SEHVipG)2Zch+)IE4i*)L;J7EPw~07#6zPyDEGQ8;uEDC zMyTSZ|EuzRuo&u$B;Ue)P_pj*mfVl$W{;%3^Ihm{ek;&IYLoXTudo2?T?Sm(rQMFS&l*H=bPoUh{eK0(>8>CUt@yvAq}2FB9_N4>QR3HpD!BllD1^oAs|; z7IFBS=sX7R#rOJU{+g}08Ry=Wpp#Ae^R(B`9ew9#)Bex@e4w~l?ql8$7r&Kz0v^SE zTps*sD{^P;I~`pVH{&5hi-)PSpY|j28?vrpTp=IB`!V!iI6s5V`a8(aZsfhm-`I+AG>H5Q^3y?>FJyd``2{+EI=_f~ zmUeD%H}bP~D7P8)Gs*7_^Rp0{FTN1YeZP`VYCcD~74y))VxL4lJp%Kcte-cMAK>!> z>Bk%7`g=yze}&)vv=3i#Gae@STd%hh$!)KpT~g0|3y1-WR3N zUKu0H6*uF`Xo$Q~iSc%l_P4gc50W=L@)fgO-?ci2>$`r`U!u6_&jH23r9S0spg-vh z@*rIABEQJ@hGc&HhFrh?EtwxWr@A6fzCryka{c=bqsUW!!T74fe07Ap zFYhl&ynRKkKgapD0Lo3~{c7p=LIuI|e}Hv@Ty~j{{H0a12KN3-=~q+;d3;p&qMNDo~yQ(I`v9H|85r61JW-8$VV?g zxpJ<>Ci30f7b?#|jMC82zbo2-{OU>gc_hnSL_Y8~@zSjr_`}cS zW!WxyUeKZ(?Aulgwiphkeckflwd#jjxcDuRysrx)S=M7a$iL;j3u%`_1?WuDzB}2A zT>q}hr~MxC ziZ&RD;{O-qzwmn;QXhv((C@tYJ~rJ8mAaVPJqox?L)akD;wKSJjs%iT)*hjri|8Naqp(2sjzJ?>g7ZeAbRY41%Z zD{kh0SFSfCewI^bbsN-k1Izu6ycOSTmUUF~8Yp)j^RVQcVdT!Mpd)$UAo&~oZi3j? zafZ%{OyomZZ?qsUy8`_s_u0CUr|^E@AlCCNxqc2+@tW}G>(AiNakQ_bxEcSp+I=KH z+RtlN_z4?4i zt}9!R=kc63(H~0QmixdZFID!2&Yk|KzvSUz7 zKF=HEC7VG%(7HK z`oW*21L04(j%ca4nK$lS1IOyZFmlPu^Zt^I$G)vu&ohW0`3}NL^5NR|I)5dv%dqD){=Xk!FZJOlXR0 z>o4Sf4MHsym-V4j5bUpigZ3gDsC}X2`gxTL$WQV8FIiU{BhP+;%yy;#{IfV1`hNAH zyqe?GXa~M?IQm7dBf64z;Q1=z|5fCZ--iB8uE)lQKxc9;@}%_pGxC;4(JskLZ?}j2 z;I`<;lZ8>wL80JVwezd*gt<4@h@@c zO%0e85=EEO`3+MYdp0wYnxT$lb z3jCi)L&!d=b#M zOG3E|Ili`$hhIkj`m#PoB<%NBL;qGLFRQp&pTk>F?h5ii+UxJZeL&veIL3>dd)BNI z^v7xE4#kphyn=plrv6;=%REnV6?vu3(3$!X>RFOJg50?>t_#GUd&q5ep}lh7rbHL$ z9OFJ}iRZ55lV@Qa)sOlU$iwsCPuWLQv@3M-_#8^sjnl|edCqnX>g*-2QyKo0ymVP{ zbKP5ByDlr;4cAi{r_rvrsPmrUX8zanLrN6-YmzJcGo1EWiktSU`F&U^_fvBHdBL6T zu)oFc!^-twqaNV*bFog4`=V|=!5t?c54f=00CN5Nn2X8FaNk`L?GKRO;`>(9$?uY{ zZGt=?es0hU?G3Gu_Da9RDQ>nm?+E%`)|rRMAG;&o5T72@IZ57R z6a4>#yh1GOuYYOX-dOTTUMEWZSCjAL_q^PwbAfyw*YgNa`lIK&mas-8E+vt8PG^^?hm7lNhu?E`ZCI|aWgZq~=M8|rhD{t4*|{cOHR zpGJO){MG|x=JDkB#r_cbcLI5(ez?zhsXSJIb;w&OZpK>yd(^WA`9Q_Z`jmCX`tx1# zDdaQVQO{lEUsIMBd~3n%r>?`qzQ=w@-rpZP!o>*+$-syfeQ;D(j_w2zlg=JZA}6!Y~^5N4Y=oyMdB7=8%_;#&{I}Y$vywj*+!FKMIZ+0G&s?KP>*A zPd@!Q{MpSG_U{gay{i|LWn7$7-0b&F>ENB1->N0U-s>m$4N+tmm&xbw{36Ug>b#Ue zu+MA`|J0{{e8~6qK)d8Rv=@2lrYKj|EmO(w^S!Xz)QL%fzE4}kt?-@X_I}oREZ<<* zht>oa{kr51Y?s9U4DyTop6o)Fds1=JKXKEcQ@8;B@EdvhbMRkj-!K*B8mzy>TNZid zP3!snB>D7Aj4%9KUB8fD1v09{nNp}SONdYKFm?%_Ish+oAq3y zxY@4sDD{dIuzyBS_^&Ihp?TzofG^leCEH``@`>`O#`*!kCiktb+ zh3}8pldmM7unO@!oBTHU3x2O$%56U!Ivb~=e=+(D;~IHb55&3Dr}+rjN5!I^vd&B* z*Y9gxBwth!9y`bSlpcvZe~;&=Nd0{jH`{e^2>g~n`xx?j-2d5%VH9d{XC@yqk`4IAoHK0?L_LIqHdZNA3@82qJ*^j54qge1w=&yA^ze~IYlMgM2o)Vp1!g;=y z%rEE2OYwUUqH~9QDaV(rhaEFeuKxXtcgQcdM7iDAu5ZY5`QDiudC9Tny7$ljv{Bsb zmm`&-BmFXoyj3;paglEv?8mslUfR`Kar64fNxMFJOL50P7i%n~PSYp8mcPop_A&Y7 zvh6Hf_Ph3c3+3Ma1@_XG;pB7pex=N(Ps!7H?nHIgA$UA=^ydz9$TPL~IuDayE`t?_ zD|JdwfR1w=#1*_@7=Gj~+Vk``$wzU&vGn@|@>T%>7G?Rqvu7ss$MgHS(%vZY^6w)K zGgzOMEO_ z6_B@OJ$ZusAwmLFy3oXzu^?v zkBLWK5+0+t8PEH*_x)!pZsxt2naIG|)HzO_EPlVho4n*y={?O6SecBc9XY#4f!XXI=9IWa-W7f zxy?-I&*yib>XY{&->;pUJ)V4=w!e1)d0*{2@1x&={&U`k7yrLG3;ccruKP-J9DSy^ zw2@V@{O20&y?sJ0|9=DiG5>7n%)5>8DCfgGQrwKUtY+w6nO|O;10H)4^Kv`MJ>P*aGo0i1w4n_4Dp-lSh4TJ&qjaL8px^u27J* z3}YO5uXgZ*TTBRkVMheJ}o`=y3m-GwmG~u)jK@Un-L~RNU;B@N%f9T-SFYKfD-z zllxth$nQI0W|4kBNUmRBS6B%B^0^pyBUx@|@|4oh5&bOklTol2{r%*nd4H)Pb-q#D zjKd7}Z)fu7w2%EB^OxvUeh>B0^GS2^B8ezBjXEdDcWdv*wOIrm{d|(1$^Q+r(2vQp z5N~~0g?@@#=4;-!lzyB|z9boWK-M{D$R}~1=SS2zvkdyY^IV7Lkw>qD{wiO@?Q!yt$V2&kb6GDXu7Z7QK0lIv-$6dv9Xj#UDYY8*{(N6d z=J96a>&ha|MJI_o<74P-pw1=oNWN!Oo4orP=oSqpppc~EC^ z{rr}X$=7dfYf+GOtn)hPEIf(&OSuEd7afHE#SaD6!+rzLy^%O{Cm+xA$D|*F$@TLp z=aO&d^HZ4@wvjilhxW#?y@fZRT>ZN_)5sn9{9V=?`^e8e!@OCGI@iftaKE?oW6_P! zU*V4N8%6t3iktcT`Ca4z*&j8Z_D7S!MdtwdA>OaUENK`cK7{@uKDUzkEGBQZ7UOyo z%grV~seQMi_9o~weu{n(`(flGJmELtACVX1dw;Ti_=#M9o)xqi`gsp99_79JljK`@ z-iy@#26?2mFQ~*8=+tS3{3h|gi2S1f)Kl(De@{M!=QK)QeMJ6C6|9S7eAWF3*B#;7 zb#$EKW*#fTbG-%gUY=i#RUa*&W zt^aoLjal#~MxSBikq=*rJS^pw+5!6)+Ia#+cY@n+pXys|S4Z+OT!)L_4v-gMzes!S zcR}aQc=U_Zvm<%eD_D<7oJ=Ag>WOhA_Up+@bG<5lj@k|Vdwic-?5~qgUx7R$>#K%) zVBfnV#*y%$s27wphx!KnH~Pwayzi$is5rpDNTZwjVml z7ZEvfp3+<7n|h%>(!V>&pPhw{6LrcTfKE~zRtQ}S;1AK{!Qt@38QPCJ2>aE)wzH5I zxZf2Q^;@deJk{`VSG(~y9s($-b3ko2s--n zmpSAIPouqV)IU#t;}^uOjEjfl^WQ-J6#rEG1o{`(qn^^PrsVp0u+z!M@Oo+&%iTxr z+z924B`(5fBP_BMXZ!hwCd@n=d?S1m#9K@&G$NP#rWft;->^rLa1@w10qu+b7vJ=Qd z+|V!5Un|H1*C7AP^Zj4Rlj^~5a&FbG)6fr|i2CfK{+HzXcLw{Of&Ha^D7QH6=aDbs zJTCk&c~h>FC(`~ma{Kk@FX;=fv(R@=MLl=3zkVcl=Q>B)Tjw0?_m@Wg`H=d9$eVM2 zk@$HAx$QxeJDBzx$RAHb+=~7s@^n7Om+Sgc=TWYghqeD3lP~1Fk5OzGOUO^TTHAj~ z-gmFRr6vhQP@(P@pr2C#^ZPp1^NHf-yx;P3jMGf=Di>ithTl(-`KTp%&PBBMGVPa< zzu-CQvW|L0KGQ%wCI2+~68dNPd|bxwAo4qWE-(GKQE{`LS=xQJ&uD*``^rkPKE*CU ze;(JLGTv{H>+8TGmth|khKNwaV6`Yk>p)Jga2h6b(;Lv9rUln!%gzU^~hI}-^yP{9FEGyd~v)GD%4DI z%k^m|th=NilgOj0!~ZhhttQvM^ZPNm+XjrI!tCGL-$CDLB>Y^Len?i_92d*KM|-7z zGig8PGsOQ|`sZWv<6Otqpicf9(BI*RdP;r>CSTGH<%)me$cyv27;0-6TNJm{=Qix+ zzRDN0ANm68giMzEkh}o*kxCpoe-EA3TM_@$Xy03L)6YpI(T`oY-n&5l!&|6H1Gcw8 z9_%x;{d@h$r@s&X$o_#dZg;hEDRm#_oL*8JEL5w zf8*QGnWOE8@1eNazxy9!yvV#ToA!M_26tz>&XJG0hJ4bLyxWh^FWw$;B6(vudFDdc zOFaBcuCLGQ+=0&US@5UWcOmb|^9qC~khkJFR1)X=$>aFGj9lN{AP?qywf$KCT6a-y z#cb5yfxH*F4bP>N_4aD=&~MQ$58B@%f6V7cy~zvQgP)(ALc3Px#~>pP-YWJ=gYC-0a_~?UDDST?yn1cOvgi;DY;@;^uS4 zgM5FyJoUe${z~3|llig4eUy8zGS*`y8P9R#`uC|nCr{#cYGmD&?*X4zYUhsDRowK? z^ng%HP2~PwCb?@2xafRLzOfR<5u0V?kniNaS*d^JhwzUxzsp&b?QNmB>4yyZ!JfRU z;%0rS@_DNx`B3se?cCj6 z!}?#YUz{GppRMYSvRJ0jK1gx1{;}MLDSjA9{=6&VO6qf&-2FN7;b)A`&wj>z-Rs(Z zl4pvW`n?aMK0h%YWqHSCAbZ)3>y?_?b%zaC*-AN%LfIm`X( z^1fjr`JDyuCsuuiafm$k0_yV>=fO(9LPyX4eaSm#!yc_RjNRmQE}}j$tp5+>xA~px zTI2;^K)(#%`EAqV77+;RG&mbSq?>i4BUrX-H_nLc>-z0yu3-Rnk-u^d~yJZdh zAp7FZk+*G#IF#$hD#mM;Jl3@&T3U}ftrR!oEtuyuNxO!U_j(idHEF+qJmeG1<6?i6 zd<(y4C+pZU`JjJi75pjVC6K&bING&<{WYI_E3ZcevD`c4y)w`)T%{UDf(`WZ3L{^o z(|!~A0G^lIi2Nvdk2Q$TsiIFl?sK&3DY-{}=uhQ-A$Rg%@~n~=r!ww}6@dNrZHO!B zum0qLA&3VVU!RcASb=^VM*SiMp<~B=P_n*#oqYOtXfI|Z!+4L}=LkkbP5Sd8x$P?0 zx1fH1Tj<}&!u%-n&VKTTzOb)giyypJ2==$Qf7^jNZO9wA!Ef@sbq%=}&&f=r{cJnv zG+BXumv!bt#YK~*mj9F~4Ev_q^>TCaTRgv1@<2Ly1oxv#9^Of=pF{N(d2TY=yO@Os z6+yW<>)~PP_qWLJpS2#3+2nQVTKhk!D0C_}L%-wShLJ)(M%zDdntb3+^hG7tWV^7dC}xyN38v@ zo!n20&(g)Aqn{^pn!GFL5t%Q7OTd0-Q|mmxj@&lbdcJr_esmAU-9-AWsy%e(aNd;l z=VbD$Z*ctP#}As7WVzL_t`mPwCSUji>Lc-Rp4@R5>XX27e<9c32Ps+#`uck@k>m?q z&@Xlzzgx)rPeK1qBeyLLot7WMegVr3Chz5lJSp{`L0)_l>M8aAj(qtp=u5ewWuQNP zDC|p8e+c<}ejlwm`G@5CdEho>p%Xq9^^xnHiR7*s;TDD3)LBcOaUJD)lmASfT>|wi zL0+XC=CzCh==Z(!kDub^ymn|Z%B@BFA>{gf+PUNxwfil(3^~*zl&Qa()P`@Af z;}4KG_K`0p*UwSRA^){J`mrDFOI3irQv&=@h1{LI$Rp&Lo^0;~@~(rC$4b%up5o^9 zOKMa2$HfMJaIFaa{@VM1ndAky4w3c43G%>281K^WjVeJWX&1(ke8+RY;%2$67;nY7 zF14@xnq^(umgl@l|JGI9?61hx(3kt43&`#GUFn8w*L89mUhm7e_N@Y);Zso`S4HTC?Ws#Qu1km2S4*CmTHH?Ym_a>wMl5bCwH|KZ2n^CM{ zHI#dH8sZ24R{Lkjz4l;S%%goSc@m#j7A0@&2%W-wjwXH>M82{G^1tMP<>Wqmt}XSy zNuH1&@w1fr4%MOGQrrLhnB0N$k*rUuIl(@G`>fol(}g_hD%vIeJ3(<^G{{SM{Icb$6GhM!$*VBeeN zE>PTZ9Z?DOze2u?d?xpc7AL<&uD?Iks19`O-a@%@uF(PV=KT;SqVqsFue;x+{?oe9 z(Z65WrylqdZC{yPeeijeFs?nQ(@gQd$^%h~oAJ|D`%Zcebqer(AGyw|)&Tmkd_KF5 z`iIEtWLoFdvJGMH#QmK0X+MzMhVL!PytbQM{|-@p7wGu#yFW4>%af;gV4dSg{n_LT z9N}jf*WZ#S6~mR6Tz7;ug8prOCr7TtC-zAo)G*yr7@SZR%rO$U3l6M_#r&bX>@%k?$>u_>^_v zN90L-9+72-AAHdS`Z*s3S%53!@US;{HrEySt6|tT1%Jr%RAX3fBgM`4zhb!$lhc&Z zpZ1G*Kh}}<+sW;{5x24)_>KImwvVy556TT4fc}+r@=PMt}7tuhk6tJNf)V;-@{i6YsCeI(!v*c0a@|N>^gdp<|nedS+0+jpAlKvj-vm z<+}+J$WQ%>{@OzO&D5FIppAvdIMYT{~dZz^3opidgZOx70$lU zPvv#J>?`X*p2_b`OS^WF8$Req8ILx8&@nn;{UiCUhT>+NjN^SsWL?7uru|7b=tv$& zC-2Pf7f3(8OaABsefH*A_Z+o`DZ8gg=A_fsf3_ zxR&*268ZH5@TVhn=8-q8ZavTbNWOySq{Y%cHW>QhqYw|`hco1dzeL8Cb1gjD!QOrW z;#~6WD02P$mL=qw*Q|BQhCnCkDcURNQ>BuJdm!EimfZOQM#>(J(;UUkcwTW2 z^=VA|r?h{32|Sp*N=KBde-|T$eE%ej7ummO6At^TyAW@(PHR9uh5OHYQ-3sh(Pi*M zRo3%@;$}VXdBM*wXx|_L`f=mHL&@XGo%udj4Ebbo{XE`J$hY-`LIUk?k?*gHcoTm% ziA1^1{BE7h`$Ne0PJrLmQRjl$6KAF-5yxnHRiOgRgD{jVfS1q2O(7yD?m|rBG zOLoON?YQ<_HBfPLUbY<$|0K~F@#L}G$0+f(uF}xT$}3 zEAlX+(J+pXU-}JP>RBlY_DSdAe;?|!Cf_>^_EX8nk*8|+VfuDQeUg7hJx zNF#UQ`Oj5o|2BD@p{RLv@!A!F~?UNvKU89}j-V8Ge>=H-S8CIqD=Cp}?$?z`fc*e|j~G#E7;lh=UPIpdkoCDlZg&{*BkP3xiMa3N zs(l~ONpW+$kK+9?@n?|YW_?`SV0=m5n@jtP+~?!LavLN;XHmVj7Sfe`6#4CysHZ#m zF2&9KY}B;gCzC__^Sr-QkM_g+qdwmGFd`&=<|=O1ztsbbpb-V|gO~x}yE(3VjeE_r zbAB0K6ZO1G`|-4&%jZxsKi(&|<36Hj+IzkU{W=>l--$nC$&;o)U)FWA$o2R1*OTk} z6(5lsZLRZ9%M6t3a~<&`>+`h=^EK^*`yf+Q=Q^Rw1nBrJLww3Qb{=_7UCc*Ysk4uKIG@W)zyC@;TKkS( z%}mULr?h!6T5+@fp$pJ2lAk{yPi>BR=F$(($!FF^zsoqPI}ti7;^ChJ+J}+X+72D@ z^JMbpZ=l?=wBJdt@8>T*3Ht6X7++WN;|H1KE}apdv#FCqe&ieY-<~|U|pL4&Q z_;UgI_es|NJgB&tuhI)4pBRN9^g#53P@ihl?>H6ZZd?r=Je4zy+2s2966eVejz)jU za}bYd(DCBAI+73L$aAVApJUV*#!YgcZ5UshSf6Io=?6ZiUO=8sexK(V`jY37_o`v- z=NdDhQ9|@Dikb=gUR&Wew9YU_k@uJf|44pbL#}@>ESJ3OV#Lof zj>q74pg-z$^sn?|26@T>Yd?HNUUM+&gQzo%y0f68@1H+FzL)dM4f@AnHte4qgpTZg z=t-XW5Pn!u5I@*J9=03y-%;lYxhKzYl{`>x4)l|9t;f+ma_3vnm*=+GX#>EHR}`ns;@a@dcbhH>pg{aEsa5ooWBi_7F^)+4_) zq`l+&(Al!eI!`Vkufyvm@!N6o;apcEdl*KU70{X27CJJ&cOxHu4slYwAPR2s0qmFa zeF1522KmZsh<}NPb>weypL`?M|2(-X_uWS!7M7+UEYCc+na?3A-pXL3p{AtL4vFJB z=)_Hgy~INo@{|0&r}WoO#VyYVwegih`?d+l12OsGh;i$ozo{77CHZg*`Jn{F`SZfC zud)I5`unp}6gTs>@e}+h>yvfl1ukM-e8BZUiH*?lT7|qS>tQc)msse$#r~Q>e!oBZ zUB0t$iCn)Anerj@i}C!Z4b<5{-hk(CNZhvA1pA#&;D_F{AE~%`KVd%iGmHHk+V38U zNa#cR_k)TkKm7ThFKHjEy8UqBbdR-pA{$ zog?>%_L&9Xw-^rRjF(;?LFf2% z%oi>!_YK9(dgf}^S=(s;ockrDz0J2m$7N`1i-P3&0ptZ-P@fMOS3Ahd{en0@&T@-w zgU+S;$Uol9hl9w2U$-7#8_6B{yiEN375PD)n<4YQ$9CxJ&v8bP+b+j^B>ve?KI}RA zCA1VOT45)2Y-b|UF0=ll$RC$Ldu4uHMBexW>M!HyBzX$YS8=0GzFp8i_Zj@tkGvUq z)G)-e!+RsRW-z0wW?SuYg?lbqHeRJ|$?Hr_z z!ll66k^8x5MFkeZ$ zEh4|T82*=YAxa*E{goT=!*J@mlBZWiznmjaCV##I@gV(smHg8ZxNenlGd_mC6VG{* ze6@`{sW=p59{G;kW;@2OoR?MO5OkvZBhG)S1_Is;_=&#P?Cum>neT<{7AVksUQqkN zPD00X5!U~?tj`#7*M{hKS?3=mPv<(nB<&xQdmThRk@rE~{2cmao#5xuoM-2q0Q1($wM}wTv-=+ovXdd)F$sqLlICauGWEd&e`#x5l8~TTuTi@-gqi zpU5ie*o`ltU!Lc0*wfxiakIU#TDvBZFX#k+O8xgLZsyP9P8b(*AMX+Ei*H4_ay{Gg z67{wF;ct_l3P26ze(!qnjZMJiIey8@)F})%bQoDH4VwflGx zfhxX z=-)31`;lz#Sn@sGw=8*PBY7P6&y=QpksRnu=egM%$OFmG^St7c{2KkEy>B~@d^h7(?$6uj!aipQ;zaVQAGs&5cWSbpiR8O~#(XOK z&##duEXFwXp?%?R(eLYff`88ddQWjPe)RJhu9MFmZtVxB>#)CD2E04<$B^gpyhQPH zjqhL|tBv1ea!0dM)fX^ZvkVKY$m?g@3xRp1sKLKlZf{c`i1D zd=Bq3h#yXnZ{T&MjIW=`ZL8pZ7yfM+m2ab5?@!RKB$gXUUhFmGZQRXJ&nwB}JYip- z_7BK|mOyzi^T602p+7weT;hK|`SDQ1f73z`T5t#UMk)AhKl4n1yWp|huP%AXja>hJ z?$_iAk1-?5xu6O6pflXfI?rz*&zpdL7r)&nw>^qH_MCsPy$_x3eyC?D`e8ZwB)+F3 zIwc>#{#XV0^BnCvkZ&1>eC|sA7P-EzK1uF9751|3YVZ*HIpg7HH|oTaUyH>!!mkXY z@FQH09MP^v+9+=3lUe*ek<2eg$-S>YLFT*Sk74gq9sY@Dxpm0vtb(7#4_(Pi^Zi80 z+Y88VkA}X)$zJlx%b`i%f`T=MF*sR=_VPGU8>>*soh;fHmpTA>7}Jcn5?8v=0ci{-JkR zhoI2NfN(2I&!~X#4lm1lbO==+$y9A%h1@*M3Pgtmgh!hN|BFAFHL&`Vr=^ybpZ)1? zUcW1{MpnOU^2aa#^3RsWT7>`N&+cx7(GfvW0ntIB(SP!dyGKMo8`C+KKSj6h&`JGI z-O27AmO!H$|CLb_)p?y-M@IYmM*99+wZ=4*%KderZk~Q29n__+S#!NYZcWypHwKjyZ_#=;GOvkpceEfkELa3H(c6 zylm+i14$!9I0lxm-qC-1$`5n2rh6Z$2k?zky5Ro3@ z)-)wCzEAwH#I*S6K7*3e(o=`@Nmt{;{F6t_fB}R0#HduG5<)*fuf%@IgHq%F7(s6C z(QQ<>`i4YDheo@phIHtpni$9TfM^b-iO_(&9r^st+)8cGHOT)Wqa|Vd<6zw&^TM(ArsUo@p_C z7Oa6-~F>6{?|o&rKQC5iBAhi{MU7BZJE!4 z)pXWACNa6SdqB9^KsV2@)IsW(X{`q(r^gRZ|JPmRsR_9KhXPId#iyG!2^ebD*{n*m zo15RDA<1#=HH#r)G+`bGyvxJUm{ z9p68yqiWP4(o!AF&i}r}ZtmuqByh-p0f=xlmLn`<`IY<5%`JUUWMcY&_||He=yCq4 z5#(lepgH=(V$4OATC*W9{N1{EQN}m5pGq;w=~gPrV`gZ0VFbT&1HIE#y~I0~6lH1U z-<5G|s_GUP(?`t&BmPzOUfErq17rHf{~>1PP}J;|6;!WvN=b=N{TIFVuX2m^c=<0} z6A;?2(|~X_Rsz)W`=vqR7VXtO#w=V7OBHaP<4vcS<3W6?VtC+ypub-SZ+aoZBRaq= zS^XzEz;sSyUvu3a_sGwjQ2}qEWf1RxJyD}AGHhUU(O)bo#p15 zrW~zOQ{W&qA6ZxRZ%V1_mbCunaQzQ;+!~ugQSqsRLg2@Lqu1_L(wS$(fI;bQ?uls; zLsWRF^Bu9Ayd{4sA?X2n0^+b!BsKNVwU zh0IhWq5moc@wXl^adAPx=Aa5tt6P;0ZW$(=_JUq%%4Dtl-F{d3 zCykPyzltB+JWY=eN>!KZ|H|+GfqT_#KJY*Ixmw%C{YRc)A~M%8YT=uvni&-KcRFII zy6VAdq}@LZ2+uT?Z~mh;AVe*RKOi8Y$$uQ8Zl0;}1LD>4!Z*zlps3s{#ftaKS1hd) z;`{VZlYsxnzh|hw%J1FX&58QYbdS<4>g`uo-9KsU>JAV6JKwTVwx6Ox%m z-CWK8pNS~x<%Lh8WnMOCrKYBdn!l3M174n@U!`S#vq%o9muG&K@=`V3JbtfFh`Mpd zMS!a3f3b$uTd%yCWKM8g=q0MPK&WC?t$np+fw|Uir;@CUN^^Z6D}=w(HGj2K!|Lee zj(MpM{u{(y{~H%!hz6@x%3AC{UWlnQ_Hx*$ewA7Ck1kf7^2!UwSE#G&fA6aCFOrhF zgtlC|zS7Y9tKa{Pq~!J&zmJIs=zxXND@LA&6>Bv(yfs{B{SR_3P9>n ztN!1YLYAOx^2*n%O)a;W%p(6z8h`0mf5T6I{7Ur>z4J;_@k>8+lOO)ixYhmlq!)nU zZt?8@c-d}$^y>e3+3x=j%l7zxShnXMWxrC8y8Xiu{1-F%@7LF_RIpqFS#F$p%Z)SZ z6wmARzo%!J0o3C6Pc4gxwn|MN+CuC1++^M|@Zv24_vpWMw?L)8e^6(+?D@Yw#p!*k zdBFSMc|hGX`RDWB|F)L6{o|SZe_Kn;3w|}N{)0PN|Jz!k0_^{jmbm}Zmb}`m*wkEO z;U?do7F1kHS?(=b)9^dwbx&wRlF zNzkT>i;ARdYkvK^5s{h51TsN@T1r+`jmIrhU?P`TZmh{0F5YDNF=~mCd9%$j7$MrU zhQ(+f3TwG~XD-&sGfWDgyMzu$L@cjrUVzP@=0;(UGc5;Xey=G9}A{QBnA zf2H#pywZ6MU+KI?uXJ9KxC34v;YY7k;=|`mLF-qtV^NYjmEt&htztiVt#Utlt%5&# zRg%9zX0J#3Q#eOb9|TzIOo})XO>puWkSsZmBGCZi*U}b~o!uFAi)k4-*l*&~X3GPq z2J8!O;MIN(1EXXt8poZiO`?z@!J0?*^8F#Vf#u4Ba26X)yWS}3iKmgDY3wlx{TXYF zJP#*TuDvR=l7bwrpYlmUQQ`HyLsYovtFv4uNWJa}hSD=nuy{XEMPx89pw zp7@pC?DE6`_-2UdITpAai_Uc-S1kyD>e!vQ?HVNgj`D9carSW{nE7fkO;=?& zMEroVkGSd=o*;ut>#S)=71o?X5o;eNIg^g4C$dLU3w_LF8tj#MvtB`?g)0iEn@z!W zA!gGG+0$|?x)4|8OjDhGmrBM}q7MWVmsfsVN!dUX5BO8Oz3lUaVSSaZzhqRT&rXV( znI(nUxYpSShG*XtCFgt5cQ)gU>pf{J2r_8{KV0r9HhafwvmZBW5UK5%=6asO2~yU( zA+lH{X!mR9YejucFP}HUt4#>i^KIdcms+mGd3m`n^-780zUV6@F#Dpfl#uI-zEXmz zFZxOelkzJ~aH%S+W*Dtu?MD7RQ@T;>eNjP*RmuY;JC9Yd$JVHtwZ(B&6>;voCHsHK z$&ToEGXAK2xuS)1wkNp-t4^Z0Gp>9;WyfMJDarE;^j1@jmt$C7r9Gfj*H77Mf|~Gm z57f(nyKgv-VLLj>I7wl_TV3zxCxgJyRaK3TAH6q5f0gYVU0OsDL@jA^BC%Ef_=Ly& zeHXl2)^(%Q7U@)aqK_qMO-!iXC@_*sF5-uF$pyB|@dXQY7T-pjg5NW(egC~cN16Nm z=M1goW`0Di=SSfOZBkGqq7bYtK`6)HR%d3;u^4aSF+2Dig%U5jf}@l1%R!nyiHe`2 zFydv;;5mv^UUmiIInZ1iwjj!y=LrSuqc~YyJ4dXb9xQ(@VW^rCKuG3&3!I95lZ{#A zS4AM!_l|5NP`NZ$51nvmIhXT#yZzBnZ})-I!$IXoH6CCs@P4rrzYHd3%~l2B+pSah zZGOqt)QxYmy~_T$hgOR^>W6GbUpK*UayQUQx}*uw29XsY{cN6SoH6?>bA%T47}`y0 za9(6uVi3Q&X^GKXKYwwkNvw%CBL7kY2b~~8{W|jVJd&bI_)8l&#blKd#XmA{rAS{? zm?d5JsIy=*t|Xp>gG@EutZO)l18n4VfEDGd@u&GMpzd*&g2u&$He^IUJB_gXHaDMA5O=}|2S(r8&mhWF00$^DnX?qN4Y%jKHQ zBkfl?0FT=myY@Qo9)%aswY76Cuer*0_h=W04tx`u2(?_ZztsD-*e&*tpUX7_63O}U z&c^Y#2HjqzXD!XNj?`_U&^7sE13L5XwfpU|Z;ic-pEu+69Ig7te%!ITAHQ>U@B`9yv5}Zj=i>W%e1m^bkIWVa+K4{s(+2bHjmgnUUQc|hmpp#@ zabfzgGkvs_zW5A==ZP!n)^y5`pJVkF$3=FpB~NtYpE8L%EYCvph|B>se1EZ{cGiz- zVA=h$-F!EFK#xgdP?M<&vovxts__ua(%ng;J~7_W4O@vn3JW7nF{2-U09tL3=stdw z!ECX++n}Sk>F9p^Sh{t6>UG4mc&E!tTPuM0lLJt}kqv@1-^*;e6 z_vy-?-B&|`O-uu|gBCL!@$C{5s3UAj~K$G z+9L)i@cR)X7(QoT$dQuPskC`|acd7>rDu*2!uHrjE_m#C7ItWIGWL{?V;~dXv_9%~FH+vX|=Nf?{D+>Mu0LdEd89Lsk! zvICAB!H@qbj&$UJM^M?(Z*qz3$YER>J93Z$i5)pgPGNy?@KpdSb=^doir93Wcrb*` z%SGfW?;}OI%Efi8!*2+uwtq$B0+(Wuf1mGtY&ubZ`QvVPrLa~v7&(lG3smN&Yef5A zYv2ugd3pUy!s!WgjSp|(tDUVS*w->z`4y&YNyZx4vKIV!2CvmL1`(6isxh^OoqxJ~(gvst6-CF9GR zg%st&?CD}b4XPV4JEV13sHJvn@?>Cw-&G>qcE>X#1z29yqT$n63o4ZCgIxZUp z4R0dxiL~2Eg6LJc#H%4>>Dt#92v>q4o70jC0G5cUz52#kBF6_96^g+PluDc*gZDJo z;9l4D6nEA?NnjC?&l4o6QLd9o;KJrTVt#yqo4JO(33O2ltmch>qAp|j5BhsVe@897 zqfgH9c1Yl{Y;TWMy*{~*_n7^+-(l&y#}1{%jtM?XI$9kWZO`bCPrn(*S|f*4KoiQd zhNH{CE&n8g|?@}_q* z&^P&5Ug9m~=8)c|qfsMBCXP);541Qdd5KOgg; z_e|m%Cn~Pt$yxF{fM4X*A!pswzg*I?kAM+5!NjhA;TYj=4OZ|oJaV+$-vD9WMEqJa zIw)B%bWl(d9R^kBDMeS{8URfP*(lDic4BP_{hOm{UIuh;wbAW81m zU+z(SlPCmY-_z;jP)0@n6X@dfqc0yY^)!nc@#_al?h9r zovB|XE-SmRi5}7hC<&@V1n)C9o3gEC2s}0KT0>JF?7{Uk*`}srKTbGUZ#$o~;*f+0 znoms+B?luq& z?yh68fi+seNG(}{C2P)~TIm{sz|;_DqD8A*z#iK#?DIX&_-o)5_RJ=zM~|D#!5#4% zrGMU@_~-M|yAraO|Ga$(&FJZOhO|r*RcWzy9WAVJ^H%==0R58ntkqT!qbm!b|BC3Z zf#;nhp)$Z^mo3pu;K|{!6r$T2;#Aq1-W|h`L+gNCh%h?1XGvvwNtqlWj_^QDosbUy$#%;#iwarjS zpCOBZN{GArhr0|O6X~4#F{IkeZcLYrmI&Yx$CDf5VMJ>SI?+NR#Ni)6$Mw4h?u@?0HH#c8 zZe&=KDQ&Q9FTJ~4K9C1k{wOo)abUBE(T6j%zg zX6GWXVE-~K?8$>vmd<9 z*FqF0w+vLKg9;3UOy624r;G?GXWPBS%yj~Dc)*sNerx!d-)<)G`J;F5>^YNBNG(1+ zQzGl{BczPfMV0uXq}vX@ORfZCCwZC8jv0<89{}H%a1+?}s{lTa8>Fr-e=cfx{`Vh2 z5B^C#14ZZ~^uMt7A=Xzf&vlG1F@qxxGBmAcJj&23{fBvXzx(=Bs=8~n$%SRDgSED% zhOTWxD3_HMt1R-v;eq}(UC%bFB%Mxm$6fK}rC;FObH3fgr500>*X2hDR2(G4lL>7u z(CU1FcC@D{(iUoAh+N;1FEhSLROfQ>d-(y7N5n7Tx+sg{BUuDk{rX*wiOS<1BjS;m zW5TM~dGE^nvg0||RVMAZczwT&CmFSZ71&SZRnT3xorq*vi|-eA42b=XP141e)^=Fg6fF?KGmj<&_`EY|Mtx5* zmojmbhV>GjOB*H)_GyM=dJp<#85vek_c04FZ}by`pwZ`gXXx0U<*h~}OJ&__?$kr& zb~j^Heei1g3FSRSV2Hierbkhvu3DgbStN5zcJ`H3R=$$ypj9s=*WFzI48$k1d?h=l zOJpHej_cmlt#_ePH!&9~@nJ2~2i({F&*^{tm%`=e{rmMUolBQ5rNWZ)s6W|me$Uo` zP483ci1fe{*1vb%L+9Q9&9)o&f#~13(e2l4d52r(qaL+7y2*a*FE?oZgNr>b8JX}i z?nmA0?8_=!@88`omgq>V9_(QnH|b=V>5p$^fVTSg2{L?BdcSEVhh4QN(8XmKPx*d0 zle#pXzG>1o9qy=_-!Z2Ro>wq4I(a$CQM#k@&QIx&@%e49(;p66BiuQ>`XBO^9iFLv z#5zNKo~1`XKX%rhcMvfo4(-X?90-w7dLLY}}^pP>(a7ItB1+?^F6P$tb5`WJZzh7o@Q9 zB5sgbZ=$@uVmU#L7F+6T0=ZSrmD>tQ;&K5iz|GmVGJ zJ-bIQi<}O*>-AB?XcyYigP04=b9da)W5xeiAts!D$+V|PVG=hjXmobJT0OXiLDYg@ zgq3%C7vJXivEVX_MzivFc{l&11Z_SHr%$@mwB&WH7vO;5CYM^{w|s zzOVP~GUFrGUbqJ}!1%RZz??7XPzBDf^>tx=^Zg*}*BT5#oeK%HAK?93qt#&k+T&Dm zf2~pKvVX0?;(zR>U$a$OV1GD<2cLgCKTobte~mw#B=7$FCcdU^&^(o#x4ZJd&DC$G zNUIA!*XHNq&%b@DdP-h5{(KW(y+1jPs~+v}fTw8x5Pq*CQ`&8Gg`ZvXLO*4ziM|1^ zoGU1GUW6P8>Vk}w0zSK0{FvWG$@u~WT1b2$D=A7wSLt^d6;K+N+d)czsW10iqGfBd z>QBaswtDUtd!qTk>Hq2EKgsoPm+{r<`N{RQd$jduTa432g&U+EH(w#l|Fhhr2oPxc z^rwJ!-aYIyZdUPYy88?7hO^&Yrtm`l z5u;g+xUjunYPZW@(i5kgT+f&`?>Pq)xod~uW8c#CewZY)Y@aTcs8gfC_XOvXY_dUm z8bxcy=Zh%T>|8aZ^!fA*jDF8FFtX2P)cgdsrsZu1TM&3n#xoe5bVGTqHxhRZlTVvj z0)N66RQlpI1f=mf(%sIod3wLx%kO6VOLvZ5oM0cbXEEVjY6a$O59q$%+I+P~viXnO zBj`2 zhEKCBkjdqCvC5KdM#O_6ZlolF`sys0m+c`DAlotDEAmzsPOTz~Cp}PW_Ve~nf6f(W zeI=ChMv2^a)+q4(;~p0k?H}IgXY+vuXL zpghBHO(ghVYuS+&XHn;VjhF^H#Ldt(5LxLZd{`5gV7ncKrHI5PtY?4K%dJXZ?SoX| zzY@Egz2FY3SNR}o$V~8P=`eZ?VEoY7hk&dN_I-2q+Ag@Q{tkB0_#@=0#CVdZ58L@2 z6{cj$FsFQaL~W95Zt5Aq0;l`ogY%?^A7LVZqI(lu6}Npz=D6aFyIlH3fX^7i#3mNY z4>MAmXw@008}JQbfBmqf)Dxeck1^kd$R z9syNvf6bd>EQ*)j6!T*1B>K4vAmMAQ#xF%6KEg#uVdIf_>FMOV;~IKLNSZc5d;~GP z6iRpq<%$J<$RWQ2jF62(3857xz)8pkI0^ew_*Z`4Fop~IQZzWSPVVomGGQeraFB16 z*N$GHd1NDD8z81i+9(nd5uUL^+tg{_fo`^c=oQWHmG9r*QiCE&wWNmMrSy78P0vpR z{(02;hJ>j3!@o9*8CkDg{sAcsCILi+u+KR<&v#-*5w#;yJ{@n0MADa-evcp0oI}FYSx+J3 zqg7))XZCu?>p}nhw!FIjCAt29Ir9aA=ej8|HR8w})vt#-7C(?q#jW8g&cEHU&i^dC z%i!BvPZ!zFM+Drq@cU`Nhzd&9y$(&a1Yx&`^#%d!yttWx!Ae z8SbmZ5#yWWKgc8pv&*&3pFdjD!OaKGH*#pw2p5GXrx4iP-o(HDQsEnu#o!|JQp}I| z@9hM6d($QEiTX>PID9^zknN_gqE06FC@0(RWH0hok5OlxeHYW381<>$GTngDtDHjG zE%RFD^EZ00kKO|k0s{A=w(AfM{Qt0pPDs5Ly$%O`Wo4Xy~IYw=e^P3VX@OarC zBf#L~thZ}eFsCkxMFLF8?_I#PWQ2VrSPRP$mQ|_$BDKi7{wxq3cLdk9)5@*XN+X95 ze0eJh8&SuU`^DY}+m!o|Tz}%_vN3n5a6Bx~sw*wMIRS@nw3N~~3rpIWxJU3;WkLpl zqn|T+%?4|S4V7Ho9>YY{wqKEyM+BTQ+xnjEB-y2rayIwbe3LSH3mhLjT zS7j|Ga_}VPc?^+Fqu-%UjI-_G8u&{Ysz}>QCfS$8`fpox4+>MZ>LtRaP!g)9igFX= z5{wmj+e#$zH%pgTx800Z|h~j066;N>ciOZY0>H?uRvHt%C z1BbJ;pceo#8Crq%XW0+zUN`w0OVvzQValU;FWW-#N^c(YYJa}jeowcvB;6(Z`#ZFV z`cU62g5z)BQ{OtfLzfJE&{z8Nb-=Yg=*Gm62&|1iAW*+=M|X>CntfmFGBD$Mx8L4R z_X+v}>D5rHDJ*83j6ZOW2O&IO;omT?R)Q46Jke6g{d(~SY;W5Ac(oFo=j3b;6N#zG z-WtMrA^W`x68Tn)Eh^_?6I4{~NGl>F+m-fozD2@CACJOCjyv%&=%{)dp4gxGC}iX; z`4M>VMOR$lk(bIn0bzl0si2dR+Eul~$l}}FFHe9RT?f9bQJg)wpQC;36DP#PB-H=1 z?lzXJ_q%MD?9f98J%9uj#UY0i5ezh*k*e+y>Llv=Iv->}vaB37RCO`~9L^fO1hqFX zfAODK5J9!Yc18*7BJH*L8-O1M;8j%TbK4Zf)Sr0vJatbt5iv}K!^v^vz42VLvh(Y& zw0heSXQWkL^jkjrF6SBk)D5v1aOX}z2{h(9{0R74_KFoD@3T7vaT}+03U+ZNW4hg= z3GCbRkX`3FDeXZ5^Xkhz40xa|UNQB)NbVNjHv93V*6JQ@t)lghfW74dcfmc9g%10G zYh>Y|E9fQtLH;$g3b`zBy(fFK-?0Ca?)kNk_RTNY#i(z?;Y&`-ud3+Jf#7drc|NCX zFIoNVm96WQrC2h1WhWWDu-ZeGJ7)*VH`}1TmfLPqHBWz=QNAJ?X2JkR;TB3}P_EY9 zKcLo5z&RO$Sqd9HMXT5IRV%*G>cVXw>x-&T4-k}2kD=0I-5nV(jglL3At!WYI1l-u z!I+)_jW@Rb%y^U!G_P-QYAL|E!uO)TmwIC!lB9Wk{e!$-Aixzv0k zR#*$GRChOtj(1E=s{`wFIlelMTS7t>2>WKb?0i8BX1+>gx-_U0;ssYYB6s3KNjqm& zZ)EE`*!mqxk12@+$qnHM>E9e%udfa=96u@No=*3Y(t<;2Bad=jR|oKmZtQ2u+<^01 zXKplcUjKYa4A;663_i}I-Pb?Uvf;qKpg%`Cuz#kde&e<3g&ys~{#lpo*fuZJ6$Zv` zSnmkJ&moVux6N^wpfU;M;G}YS{rvtGvQWv~(;kqhd$(EOLhG%zO0j=WnjaH_OR957 z)H3hi0Mnb&A+No0+~I`numS3oP%QDljXPs)Q7LoO-3SHJ*tjPrv9d1Q>~51yL!LKNj@X z_kuvIoo#P+!WJ`y?)&9E`N^|PV%%BqiIVGY?_nQ()xBkn5O$mw<<-9_?jT2mMDQsJ z$A!VIM?p|r%^#&0BDgdnJ!FA_;p8eZ$0TBO0*s0-v^?<$)u z(lu_bf%w_(-rR{=Nk9l*`4XSr$nk0tHVdwmrlmc=udrShuE$I2k$VA;;N(Vkg2{~l zlW$0!G$5>2ciex|T&P~FpKsAo^W6D{(#WTq{L7g#9G`&>KWLK07Z=0tf%WETd&|Wd zogTGp`-z<%T^)NrwYQt1C1;9R0$V^YkGL zSQK2JacDi)EPrm3*gX4Sb@@>eaGpG3jWj%4%DM;V5Bi6Y$Bp;_*jD{)3L>icHZHH%$$viprG5mIO2>1;;?Y^z#$Rm@CStQe=w! zAmC0)Y`We{S_1N#o4qHL8FWPi+Tmsw3H&9i49=AQ0PO2mKpc0)?#Y(3X+?{SW_#^W@yKg3#-Jo8v9I!)F>gA&D<#ur70}PZNmgoAWf{Wae)>B64 zjXIYTZ_B&$q9<9(UM`w}<@vp-(*wHFvEg!~v`|b~!nXk2bVc9Wjcc;yxVd|K3#^Fi zl_7=pgS^79o@v8dhRi?JI)IlEoumjQ@G|@f0;JwzO9HS|Rketyhre7@iQq)`hfYn( z(`8Y9_QyS)Dx`YJ3F0Vm2OKY$%kP>2N^_z(D92T5_?niova zH-eo;qnHl@jRF{p0d*n6hn+g*6rZluces?|Q(o|!@)vjzkjf{wI%(+Kai3CuO z`S;|_alN*5zWQ9=ke6g-4(V6ckZWr9){vJc|E8$DvL3wJJBH$hbas2c+t+p&C-PELiD(?%5MWt^mJ6wzbT;JM`r%Tcm z?L^(EQwts-L(#If8@#Lp81#)NPioM$pT?kj(m5F;lez`M)FfjQsW-ZNn;4Z>a89sQ zNy#uUim1*F7xw7OW&X1hdo#ZNfXC=x)Iw01pSio@&+KSLDkNm$HIOQf1@uVSQf*Z{ zWdNC6(@!E-s;B%yhLCQmambZhR--S90h&5xkDczH2I}iNSf6BJKCkJJyrw<+3t{4e z7DX;U~MBgUpFvOd7awP#X=hH|u@qX;brsWjy}MQG%% zyt~I`K2!r-r*P7*!@7z4>eo?vX2W9!A(U~f<2VhQ9RucE0dWKAxDAde`}YIn32+Z# z9rgj6q~m6tkHg8u7Puley-6<~N}AJA2}{8!f&rb+1MobyRee@_4R}H)Ai5M^!E7c0 zu|BiafQ@xou6oO!4K>y@zx*bb15rw*mehHI5&ufvBf>GKvhpgEh7R-oZ0RE|kNuCK zmRGnAUER*P5qhI6yoQ;1O-(0iP$oEX2JWlI9HfRzW zMn4iAe59LSW?1#ED84=LE+nci7puiSrieq2Lu*Jt2i3H$dEqzPECax!_THmQ?8N>P z^_0#3`4RUwA6jxWn5Jv~GP(Y;^3T|EhB2F^M|dvzXlzkgj! zzrJ5&%h?TGR)XmxZrH{i;fiJv{yqLJ?L~k_dUv#c`m1LT>vXl4qD{wr*1y8N8`&1y zsxPPN(p!4}rkC<&E6T7op3fov{PDLXW!NNeHsgPT3wVZi)4M=3QPTgE-ccgjm1d1d zt?hiV+v}ypD>7M$u$+5b&aH{j@BF*c_HWBD$+u-_lV^-gLA@s|6YQuWYU&A%-p{ja zx}5Ftf7$%*rk7GE`JC?}?It~G>Wdp%=s%Q_hIVsgWCD%vpY%T_%guyEMv9AWQYAbL zWhCd(;9ItZSh>!=P}Sx&f-(jV^@dsOJ&wny;_ z`;Crf?8zD{ZeNI`(G#qTU>uO zzb)yiB02k3GFHbvT@KOeY@hO#Lm&3`PJ?`8cvd|KWwLy z?sPtCchYV&utc8q+^ptvtD4U(YCbnfCZk?EnoOtjs5MVJlgK~6Rn6xXHJ_V+ohI{M zZ!(#ut@*UwZHL}l@3}?I@g~VAOIwp@H0ccHlWw=u^S^gi^SM>c=N2`e!+G?&>7>)? zcRQWVyf+$#=2!1IoLjB&aBj7p13eGhgI;GkpSPy%b~K!a=2!1I&~vTvK+m?f;lTmBdo3@98 z;h;6i`awRb^&I%9)^p&aTF((34Aa3ho6M%Y?kMfrri7zc>pcfLtu-F#wAOQzBpr?V z?R1pQz)Q2iJSfNOJ-4bk-lFDn*uP$@HJxVd4wOxIHVn$4de341YK@2etMwf4L2J+% z46|7l%}3K|KRCa7&#h{X2OLrBy^~}($OfHJ8=|t`%FFKU|JHksa88}^22Po`e3V^&I#k z>r8s{!DycKMxA~ys6XmG2mYuv9{8iybKsBJESeA6-Fdekb<<(k4yg4U_@mZy;E!6* zLI0-Nd^(ESt!b~HwFli0f7E*p`nT42(7&~w!~V58-Cl3r>bLs6Zo54R&9B~b*uPri zVgG792l+CY4LaRnFCFze{mC>a|LQ#l`BG~<$d_8rfq#en&U6;_NBvQj4d&C({?&U9 z{99{0@Ncc>Fh4+p*>u*P4JH5zqrmy%y|tdhduu&6N#@aX2#hdGClEBCtkAyHdu~;8 zyhY9DfJ>rLZ#W;!CMoO}2!r#Hv~`U7&K)^m^>rRQei=XZUJt`mGPS?o_!bjH7(!y&8d{C#m9^WPXUzgv7+XS18lZ)^E!%wPEtI_s!^ zuO7VFT=Q4QycZ9_FLdEFpZ-naCE2e~+LDP1{8@4S>BkG-HxDE^t|8I7c&K6+t;G?apjBb0nT;A_0p6a@*if7>g zqg^`BaFO+PznPP0xts@3*NBZ#I}P zXE6XH4><)2a%ub#l0Z@yB)_-#_1?F|Zm~y-!bi%Da>n{?=@|)aKvhmjV5F<2LuEgv z+1-Ajx{Ba_8`@$e;xlTz8c^BcXEAmHU9j| zHMUoTcb?yJy-%mV-)vJDmhOr!DNBZukMd-dX5a0t?)Mo<{$^j3SGFjlgcD@2;2u(W zAh$W$rS8mC@(b1!CBrlN{x+L&eagkP)G$0^V5*3y9@&0r<9TEFv&gLeQA4>SIVwGB zPq(-o@z-=cTY`QTmm}B`i}iey>@R8O`PkZRPHD@jXM4hHN=i<6FS%OovUnjzuZ%j z8z-ZZWK5cmDwO`@!&2SS=j$gQmP)#xVOX@|dyZj|!}c7*_MT_he)X^-f++YXriDl8^v1naiT1=S^MU{FJnuSm8}q9s{Pk35^Ys3 z<8nEHaw7-UFaHt=(xS_n^uVX!EPmiy9FdAi!7utVBmbIwgJ#s3f1e$tslceH#!H5u zH{&(5RWiQDj?3CH8IcOPB5SNuk{C@>FEHlQ45n`-I(o$G`7GN_;rS!*IbPin z`hWja&#mWHI(HFKMzH$iy9ltY*d0?e~Z=^tJDjuST zda2~|(ilwDo%*W}lWlouA|(vH*chV<%WV(DM9pRw_xrp1Jx(@DSO4B}Re=8?ViF4EEaxs`7|0zrlm=T23OqJ@5;bZFmer{6U~3ThM*)oJ;RJ>_6hn zZ}q29F~s9$;YbCP)I`bnBiv#5ukH@{r&b&nHI8cB!}F!nFdSN&>dM-x%(zke>VCbZ z3JQ{$ji}mXYBRkcB_27Q(0K0a+pBMlCeKohB}p)~ zpwRN`EFknRViV26lOcT5r2iIBkwZ>oSZ130XR;YMkZFYEyqs}LE-FPv)apAAk zUkAIXY;6}M-3wF^4X|7EzcFAr1aLG))MUYq(ydQ;S@^{>04m?y0W2w%BT4G$aDkqu zW^eOf0r0oV^9l@W;hkKN)c&>yq8ud%bDObEEuA0~{%>yN=~i>a*Ag@naKcAZBZ z)}QC7VZGVBpT!HP8q0vi*(j|G`uK$Jo}fJT2g+;7dW*W3+s!oF?M^ocHvNG6h4j?> z`}LG@^!sn_SoBK+nd#mfR*Z{F<*d#6J?bNR`pJ>o#oaHa^;mC=(LhiCYR^&8zFeDk zLwuEi$;<2kDRZ7jm2Q0cEh(SIAw~OAa|kQCmzY56Q8Um(RZ?@vrKEU(c@ok(~Ya=aWz4Q#`kT9!@xMA<5PVui77={&&0ohwj^O@&5fa zW!s&+JGWS&-QRD-H9?&ZF18dOy+-%fj4Fq(PTC2D1*xbw>cX(JemPyTaD$RYl{pDL z)%F##nGCeg_sbmRsraUFgjBz){s-8$Yuw2`#7SH2 zn$TA18p({)eYD#ovC5KdM&H0S63fN(L5B0Tg>RuHJpF$}^1R&m@Cs;poCnqpaQTK9#W)#`>SH47O$7TB+H6PGF2rNFwU|sIMF+hhmVl2D}UE1_l zH3iaAoK6_L2DN@VW1C*1_Ac9>rTdh-WsH#=`i%)A_iUSaTk~~>k0So=_5B1xfh{m6 znkjXg;Por+k#-#UB06!bn^9bT+-qN4)Mh$XYvFB(2)C&Zx@4($PPSj-Sht6uX=$Q% z$P`Xa^hV*{aVb1nY_?ed4t@=y8ljvCoX_OLpCFD7ZG54cGl4^LxqzjiGiXag1T-Dc z&M_T_Xty`(t89w2i!I3(^LqxC`9ORgc{`q{v(CQjUcxj_m)G)+{lu{41rXV{W*NdG z$P6J*5=;`Ncw%pgZ(N=9BNmfo_ysJI!!Mx_UFI1LcmC>O3=5NKzJN%>F&*VKs!`bDuS{ua!y? z)0g?6!rP4gaGm68l2A@cvIeCPbJOBV^wz&%$2ulAm}QvA=3$II2B%yaAYJ~Fw(1n$ zbw0t)NWWwvS)(38TUVRSp0eDwYvk+d?1|yoVs{7k=vM!L&=Mwkzus)o{Ue*FVq27=-eX3@Es~>lAbcB+81o0zb@K; z3y--865?3xz2^vCL|@EVL#Ppl+#N8ImP_d~0x-B^lMGb-#m&UB!i| zmY>5x2eAdr)Jq^)Bj6#9NG6JaCo!mnqLF~=xG%PMUsGuZVuvizOw>anC9w15tw@AjNN_@<8nfRsaf>woMLJwt!^|j*d1-FbRL6x_SwW;4VjA z?!)Lo?&G_4`ec1DDL^J5g*kIXE!;&SY#nDQnnK zO`-;$0I(OjpVb~4g_G8V-cf|Z$`nKUCZ*Kg~^0e6gG^(3#tb+ku~0~ z<(fUJHf1y;I$GKSQ`K0H6i(<56e4FD1i>KYi6>}nm(vxNlkZs3ZiPZpx0I~(Cbq@u zI^R&QJ~j;CH-l>cqI$;Z+01}&h8F;}(YKEAx-!Nq;;?|A0poQTHeUHxe&ZFxJ<52+ z33}j8yU$E{c2gJb&@iQgB?+688o5*OLFI|@p~=y?2Z(=ZwPO(~_oB1jKmp|n(uFgy z%Ya2BauK8(I`B&AYK){6z2-usU<0!#p&50RB^)m^>Hs)KaYdyq>_3#K)$~-%iY({C z2)+d&Z-xBInhhufnjg|E9&;o1aXiMxUYVPA#`>lm+}}z+lMDg4a&Ouh=Qr(q#AD7) zJG4H~?XPJ3?;xBJyjg5&GGed})`dB_bv-n;>56g7$FNaWVAb6AHJgNcIrQ;anc7Ubm`>5g7FePY5)d#{B`C#yhKq<9zASRY}Tg;XN82EZ` za7Hr~hFx$h3M~^!t+5={8eVOYgY<@%i#s%zU1wl}3w%SVh5~-g?as1}(>qvb4OucE z;eY@(hBOcsmc`1Hx;F^4Y0XZ~NLde*r)`*GV+m*X(IXOFG{+$FqIq_Uw6vH$2T2dK z4VU|R2y0D9%BV#u9D^lU8xEz8m*BG!X7&q85_Z-fd@-j78p={-mLz17)<&kK#{6`Q z<=_?Cy~=5&dXu1`V7pUhuO$=7k{SaIvKtHjR)7GAF&E~2xH=hC;5YwbeXGL)^FN{m z_!B%^sW5UCZ|{rCoHT^x=!;rnIDDq0WI=#Av+3M;=e@gelpqAPp|D#`x9 zKppZpfm8wmSxyobuSBzQZR9cDc3AJUpB5E3IK_3chhRz=rO0CgSd;2UQdge(1 zvYNE^u;9qXxfDFCMvHsFTgMdv4C!+R7kORu>TP#0`TS@pyf#{t4RNt=@FgZ_ zJf-*B&sEttEa+(5kV~7C0^WhY`48S%GH1N6D6D3MUgJ2Z_N(_C|XE#~9(i?=Yr!d-5EO=btzD0sqo| zHf4co@PetbzJ}hy)vjcD!|6|FcsYe8qaSb@T4#gXNi-{m2qJxVC5YR|FAg8D#3w=nF2AB*7ik|kuU@jp4YjuBE08^IHFslDmbPi=lGk(p zSdF0>N@!-|2s0)Ke=r<7T)c|T@#ib}YDi7FLR+ZHWfQvpN*syS#G_g_cj^#AOtv^$ zQEM}Tx0}(orqvooZHYZ?{;{X#30hl(SrdA&X--XKLYRRBLOt-&ua1N$J#&ngt-GTp z_gbd1dml3{>k`nkU@EoUT5D)TkLW@)pujA-^mE4^JC^e_V+mN8HCTVTStI^CE-MuhmRH$bhF=;Z#U_3dw|rB8mUsvK z$h@Z%0SO!!cy*sHmdM6n1AasURgyp zMNQ3ork4x}!h#q_2Zfv)W-u`EWwu_YOlqa*9`@BZmCF)7{@_hPr4KDV4RenzK9aS3 zNF+^jFR3lJ$gz`K9)4evSuWTCs2T~$9={Ut4MXVSQ4Gzk+XP857G>x#Jf&mv$W5Ac zFxTg43=vC?M!jMs9ATCY0SLv{uJb`On8p#8;AexUh$U9(k1;j(qP0b*UpENKQ#h2J zUj1TD5AEfcq6s1>|MLZT0@x({h2$w#sPYRc*V1*JhTS5HE~=ngA7Jf$x{W6$A*Q6; zWI}Gv7iU+LSzpM9RG+4!5;D~i&(4cd5)6_{&qCobyxJyC4td}+y@zK1wDE(Tv(`pm zMIzHxHXl+XlzsGC`&3o{kO-w!x9x&97k9qycK8cq;#p&8S!#=+X{>s;_Frki#-f`4W1@M%qrxs4qrSUKZEg{l2&( zyDmWsj`b#CM=y#>|L_0(<$V0^G->~{{m-6)0alD%6F}U70X+V|Y8P5BayZJ?Rsnm9 z(-+u?QU+DQ5;7){{2;$AJYzmI591RvX6}lzqfNx`J9v2^lbxerrZxK9>nns_7@}ez zz5nuc4@ILoz;a*A%~if1G9+i5jWp2B+!3KEe*4+us-TU2ncENw&zksNd;2if07(=EtK<> z&P^jS(KDtW>_74=`2@n$JjS1c{fmM%&!DFOip~xp5t8G$902pmY-Cczy2c&$q}fP$ zp0GL*_y9luc7C3m0&w0W*QdY6pH9rKdt6BBYdr&gMaHSDBGIsglukl0I=+I-%7U;} zcHehgXb-HN?fA8pJzDu7xB{l)nAk@@3X)tZ5Aq>63qiZTzguPrpdN<-$$-_k2^yZ` zXcC}=RUx>ZK}diQ8Rl6^)2}IPAXm#a)-(E8&pD}*@nXIuwqQx4KiKs<9VjVIRJuMM{u|Aswj_~~78eMVoueoxq? zps6j*Zl9$vyGa*`A}o$Fvtac<2uqWJOBXW8r?}1q>dBDiY#-p&(F=W1ag-BuZiXu6!grv7!2jM!YN9d1NP()BAJI zqSg^own5G{mcONRu@$@+l*k45p&Bsv6k&Dsy z5J3FLeY#A(a-EUwkgJfJg|s^2C=j;xg%!3_y!OyH3A>ASvIjHs*w#EjSjf89#$ z86bOsY6XmJHQrBMSQGU(>-Q*9TAJU4Jfh{ORj+A2Rt0^63~e|=#t9XI>xo;!DT*d2 z4V!*FMN@VzgDT0O9##w_Oh-lEw-2cq0&I{F>A*k}PMO@p(%SDtg$oal%>A{vySCTq zj{)Y4bj3U*Scs~u4(8bBUgI~2^euouYR_W!7CfTAuJI9|#TK#>c+Pg{zC8AHi~ zPLgxXPIma+_~P6%eQ_?y3xl*s)91*F$pIsyT7)qb|JVn)YG;-M$_%I=0eCnWu5`$3 zs)!;3g^yUUaxot_?PRfP5luj&QDH|>;TR30xxZ4)$wPV+kX=b1DbekKrcmI+aTfGW zNm*!@0a0>M7W<8`T)}n86^+d;fkXfr&ZunREJ>}p}RW5C@DyS5|55V3d zU4>CTU{mk~S0xg!XhP4KMn17Ww?Dzp`d6Aa@PWho7MB`R70*<>o=3!R#gW|NC$!W= z(Yvm6WSmEuk@3P&i2mm()*f-TBJnGO9jycv2u1A0iS9B^W5mmOkO<5S05O)?d=K}9 zHy175GlYV4iVg4`h?9hT8YMGkePw`8~E zg-|+~0dgeo{KLxB%0?Y>3IMq|kc-37Z?-xVS@_eg`m@E38a9xUw?HFnNPLt_Ee*Uq z8qi2u`-F5P!ArgowZOgDLOfeV#rf-jSmDq!oS{W9)~gy8fUoFyxveC0ISFb@^eMSp zl6t&fa0S_ID11(J49>{ImWg&XfR%)~%2vq3JY19QW?g#c>xtWG)TA_omj3e3%GKCV z%F-LTs=)*9aJEChy8#9Ql+0$#LHq@q+c{E>vgCn|IWYg^XVwZ`BgMfGf%caK-e=4S-bRqaf$5crJ zQoTY%_tLhc-5sGL@#Oc4BM^XAg?%Nf*I2hDcEZwgVL(7lM?p1_)}}|GUJtY{fC?)I zM@t?D^^2>tVDi(R|2&m+7R=((^jY%@+iQPX^p} z;$(nR;nr{8C}U*7XJcRF0XK&k1v?)gUoet(wynW%IYAe+1?T9L9B&ZGR_6gMA+NBy zg0Dr#8lF;eJMyg{;w*JH)w6tj4tzs(&G&Z)|C4-of1uR+N~;bHF&o zEe8FXlYyQnV7p)lGdE};L-Lgr4ho{ffvY4+uvT%=TFHpkXqbbdyDsw3wzkYIW^?vD z&2w~mH?%boAzUq1F(XSGBY_>$l7nOgM@`wd6pOQ~3pbPu^M}sxdI<_KGsF@%Wsl8* zZ?kZurfWi$6v~~nL1MRASY&z<4_H|81VT7O#Hr}!f`+z#B|lpdfiC=1s=Ncc$_G7j!kNxhmUy7h?Hg)}J(Oq3O>yI4$;!}=wp0TWw# zU!h)HLz|a5rq9Y5O4OF=o zj9ePId5bHQfb@0Uan#cleLE!Yqe>A;K~X1(90 zwl4Wodulmev^aObc)P7S3|jrHDHBfG|B*WOCNaeSSnPI4%*aaTq-Y#Y7tZrSbFAM^ zZ;FXtA&*&KwIr}T1attF_x5n!hP7mTRiiLRXb`izvFxZth(%tH(`WCC<$Y3xP*R75 zB8_`hZ$Kc;5=Mv{lhU(%H;P^bUugwPNjqG3jNNsD^2)#+nNrHKXMxQLwJ1s%VJxmT z-8oq{voIN^S4uns2J4@v|NB7wOmy5+BcQ^r9<-=MwHw#D7(qlUme$2ycugOftlb81 zHtfwht=?oX8+Jyce#Zir=CRQP-ap?Z^u%D+Tg8J^-Z!Najq=40_8&;E+_=SWY#^WK zQ)*FdQAWK=vqM&iiJMaUHWN2x%dM_!fow)})>Ezp>Stuuz%uMp`U6fz5N;Hq@<3m+ zI|j+#Buuc_NM+2P^pz;WiIyx^&EVZty8C^Mc4I_YaB}W`cZ-UpeYsR6P->VVmO{Fw z_7Ql!jp#Hh3Ew>06~-}(QuA>89xCNqXbooEkq4TM$dFnHnW*ZJn=%4p;w~36)L~#j zCcSE#76uk&(#4)z62~x5b{tD z@zdb@66&xxrn0EiN}Rcs92|SjT4lTTwY$-VNkL{}o|YUVrdqt{MmXFOAnKA&0STmg)eV$-nU0AwxSb*gnTj3- zj9R4kQaj!uWk-r95@M1A?BU}I63mKX zp`qnSlqG|TO;3yPS|PeV0NiG)QzjnoEk3X?V*McB*WE!aV|=@$_`O8=Q5(F!-k~QQ z^@^k%VFaMqqC>(REZFr|l0==|*UkMB2^DusxiUg5JQSX@sy(^kJDyc}cjQp)h!O#``px38<4n415=6t2m!}6|1U*U&68*jI$ zyY%>rb&RQ?r|Y@orHbC$oAK0baF?sRLwUAj**gXAaCY--hSDpEij0=&1ERlZt4WZ9 zoZ&1rrH>ZWSq~X2Xv`laC)C4D8YzH0y=Ce2b=ns*K{2nWkQ+dj7HAQi+snXfLj!Pi zC>4SjN@Jv*ncL>WTnlw7t&?FuU83&>M2O+ita;PF#+-|exQGuP7Ybu>(FnVF zz-R`cX#5m7ZE8>An|O>yYN6)%wpbj_mnr9Ik{l}mQFeJ*>8>QCYS0WSxO)WBeKW%$ zYT#a`8|_yxr&Y=>%yTPXl~lKL1}{1JxlS^l78A|WaJ4If_acDsc{45hnN^8+_*fLu zCQPAQ+>Gz~yNezTR39H=NR$b^a~U$Hy03AuT_Tev*jzVnw>ZvFp>cD03eMZ9_u>oo zQ$#J%&b7K@6-dk5Adc+6>IQMea9_T3E_Kxh|2*bM1h9+SN<~Eb)Dw&k!c#eck8u;p z!S2fk?Ez?%ZlU$^P+Bj`n;ehNsMl&ur&+r*>2$iYVauJ7zL-QMwGt__JI%5~P*%^$ zEbRX3sMK*2Y&11_;AZ&uqmH_M;bL-&p6oQ96|um-oD!8n&K7LmhTee=_1(6F406Q9 zX=5p;0M~L9z|%oM;U0@~ODzMKb)$B%XxLh4b!bNUb;wD~vctBKhm_LBh16J96d^&4 zuA1Nvtj*E+t=>?ElH+8|YGrCzTL{Dx0?>|CW9ztg&}hwOP_T23>?q|cU&tEA#K|tm z(XOI@t0ifFv7>xXar0t3wJIn&ZpcY0Hk_78#T)SC@ci>2?ol#%~zAkoHY*O^Hb` ziM>p!OZF{;zc@~>k<0ge7Q+N-9PiNI~S@vq4;Vb0?MNNSC1V1x9SAda~) zIVe_WK+}tLI~5VTrQ8DCq^g{l!RrL~{XRIn%XQq_Z|+l=1=n4(swukf>6?PAuv}~x z16aKpy<}xRRZ_g%Bq9buUa&8e44dJG z>*5zAS*YXm_yVDSAVd5OK2ZChAOJypy+hbk*#1UJSowB=`g{fIB}{C2ChPg~Y4Mh( z&T9o@e81$q7d9arX-)8jvbL-=3S^B@*A(_QvPn-V6(}riHAhI&_|Aw9@Hm7^#|Rdvy&xMlDdW?wmI0 zKSjk~t*|oReMDs-%0-`dXL5+frZxZwtC4#CLah;_mTtLz zamPZ9Qbz5FFvPOAKNc5Dn_MYP=vIopht7eG96Hxrgun*FSfUT*A26a0D>I-g52M1Z z$hj8Z9H7O{aBq`cqdbihgSfaP2t2I`b3ClI9eq+zgys{5&CYM-lk(?<5%5p@4?hpO zDP^j9XN`TcPF4r}tatiI(=C3`?+QzEU%RnN{2eg*i^3PZxOnBIMd&Hv*M=ID`|40D zM8Hq0?V-jTQ=A+IwQpsl?Q|uc*DnYk4+<-*OfAi=g_L^cSh~CN8Xy}@%AAIBd26Av zCom^FO$t8d$lqFY3#K~?=qWRmkKYdKX(XiXUaV;;M7;@WcD4`6T;D$)sGIE~IAME^ zN=IHg>o6h7nU$i!I5=%IDOJ-}3S;^;Tcth8MmCy_?T%t}`;ar6prbL-EGxm{HSP4% zc7;v}YR0B43;2*iwgW$*NCQ}RJDvaKcxED-tXF@oh< z)?CS2BD0T(sO#R&OxV;y1R_{4hzjd>-p|H)b4B)Z_O{5bfLD2kWsbS;ti~7Q(>1ebTDb zwG36&b)c)XVyda9;4nTe7E!gQHHnsqwV3E6q@qE8xXq8hOiy{T)FonNy9tsl$CFAI z>UXgMP${g`$@F@;$?u%8fuHdu;`ng776k!F;WL~k{x%4NPokj}prMwJ6N#WaZdjpy zYD!~E7pw0}xeiqa&$tzm#qqVG!Iq}0BmDu0It1ET2Pg}$;C#-piPFphMk4Abn&0M) z3l$Hsuqc8G?O@b_Jc+-pIvgMG8+gLN z#J&m;{hNQ!&ayj|vb-wng<3EjA6K?o|CS0RMcu_38oJ!k@a)JYXri^MT#dZH(cz8N zd3{8}qcB2+&zuj+^%TkR8of#;auBrz>-fS<{ z%Lj(Zx(jhJ^tW2AF5iD6r;ozFxt`W!TTS~;B7h=vw=B_w0Hs>hAsIo|#q1kBm)dZm zl5&J*n8Ius3gWTpMor!F3br?M;tX4j8qGisHP$;kRSP~ey9dib6P?468dDnM3mxL< z3&kR?sYeU0A3oH+Yp8-^lrqQ)+<=R^_2i*RFJt7+LObs`RLNu5s$Re2n3@Zr5a>?V zRol572RjR45}y)qSwdW=>pgH~fN_<(SD{T+6$CDfjjyH#%nC8J>FT5`#a-#DH-`vU zwX@jQcEYbx4H+r0hR%;@i9y+QS4Cr=no)lMW;v7lTot?WT@_ci2*e2w9K5WeQ@*UC zPnT67)tyZ_0sa@z!54Y8W-b)qOD|lMTAN7;!{|Q+<^$;(WCbYYb`I-tag2&*ORb7g zs7@lDr@;u6+XeQF)tSYm7RWE&_~$2XTu4euIX;piq+#(fM5&vp3DK&x1c_Pln30Pe zGeg;gbv2P4?Q}160ntiF(^uJ5DaJJ~+>+t;9t})M1aJp4;TZp(s|G)Yu|sxS(*-$?kv|+&EGRxV;Tp+WO3Q2 zbB?>6m%8tRPYH{CUdRCvbH1QjeF2tyg&JCTjHajs%MF<~xXd15P;d$5XTla#@~#@L zW9Jmja2To-);xj8rQNOLAW{w4z}-O*?7^!lNyfgQM8*8f0L_TM zr(0Y=ns-S0NZlU9SLDrYC#TUKZIKM!6yrY&-+c(;=SC&jzzTBHp6hIG?)KYnv$pUp9q=b39NfnPWK5$u}!PR=cNsG^mq&t&4H73MPNqgTooV9E!e5*Qn^Xf@I|e zvbs)YI99q~O=Ulpn?FydDcPLN!yGyDkdv5pff#IcJ61txg;sgeiR$d8PJ>oqa_bZ= z9HVsV%8sq&f(NhGJfuo7^u`Nkk-2Q-j-pUy_~iXDb4fxgDMVxqZ+e7oSMm_*OI;<$ z+zR5emOLGiaEw;Qh9PI7{c+;&}3e)qQT`Px*3`(R7%kdf16FxC6Y3;$t5tI zuLz0kqoj1vmO?%|w#=aIQrz3BK(@TfdX=69=ANJf{R0xiBsb&eY_Z^kNsw(qhjQ(Wk7-Uw77kF;qEliv@ zyK*X|_}mf=rLB-5pa7ln@54reP}`FrW9_J(^C2S~F&~zyjN)8GwREGz`8X{WrEe$^ zjO~^~bp^C0@O}k>o5{Dq4U`xvNSj4R8~?yZ3ZGK$J9VmoR8*abEElL=n|vhExcm|U z%_gKYKBW(njMkD4NGO05Q{ zeir~v9x_BXE(rCY%$q@QMm!R9St7&4VmBcM>8fUix^e9#7}zo~RELE%$q6c|rCMF{ zjSa5PR4yxw)TbsAYE8)!xo1eaw;DGP>lY0z>}{UWDgHbpFz9CF;55lBF2t3|F{NQo zO;2m3<)p86DO*k!4F}YWu9skW&Wur+zy;d($@j88^F*GE?!XV0`lx*Av3kgUfl`+4 zTUE^a*zxr~6l8nBe_`DuDqO2wMNGsx#3y1tzeu#8V*&@~RXGM9$o^Wp>>vhNbve(j z{JeM5LW6rBe(Vn0_?l$~nVHf9KNl=zQRz6hShrIT9hLyt3KIC9I3QtmNMVIx+Y#k? zSQo}#%;yLri{w#KIJ(mY<|bc+12CVKlwSSq&L`f^@#b(Hj$)v+8lx2)reMA31unM zm&Qp6P>POHbYf`W{*T=qk^Q_B8plfvl;X~{#2A(;%7G%Dw0{v0by`Qc@}*L5G$QV& z6j8LIYTp!~wRY0f@kE)Hak#{WmJB;XfFoU8v=uCCw?XKh1UMJC5A`zL zrmGCw^zuIX8GKQ)SF+`^h>!YkP$rn`qCx*Q7+ z;X}FEQU@rhc@KLA4H9nP0JQhP3B^S|iw{>lcuLx9Fe(wJGSWmQ7BiqBC8_?zl8OQ? z>WMYqjdLQmSRgT_g~0f+BI~7aaSNbw*;{9cU!sk9`;{SI^wRVOd5t{3cpw z@tZ4;vgX`y;$^@N8Rway5_a7Q?m@kTbX0e&6FKkLVJmXfiVcMll~*inWIWP8%rve7 zVj1r8T@gQ(ReZrIq2k&?)HZ3`KYRB{J`6n;`fd3|_Tc7c{9ym#Z|VIm8h&oFQXY9M z$xO#EL21m6LJ73Zx=CgI7JRwaXNWAU1+EFA$Xl`D-e|mrikw3hE4xOn^91FH=JMC! zBLr<#&YKGeT5h$xr_0M=e|fq%!!*$QF01EfyCf#gtMO`bA#e-S|=Ev~c|G zvh9A1%!n~p*us}hKf~SNabr{d-h@n6b)IGEhAFzrprX@*>#@<&#a5rLpF%cVaWdaS z_kOuak+x-kp>{Z%@ zOf2_Nlb4wrLe?jZY9EcQ*!;Sl)>hCxMZu=yX<#)@? zgk)fs>M3yGpKlU9j9h>zAfa#_=xsdxc6n=v6a;*SF3{s?Y|=&`*snfH7ZV!cFk)ng zWt6q8)7@=@zYo(bh35`)9xo&WR|{c$Y=o!QlgPs-LbUgvNYfP+Fh0q|w>&`X7t+)k z$9IkcQUf~DO>|4%db3YSqE<*`qS(9_mNxH03FW{6ntp5}SHdcsekxkmiuZU`3a=t6 zTzE&vf&YGU`okOC9e9Rd62eEvZ_qTUY1$ zH`Dkbux~gOzj~v{9e248(=BZ~#$tY=pXq=b(=Mpme?5AQ+tDRJs_=l3?su%R(_t4qPOKxi@VkTYxz12^^^Vbq&;6?BXBd_cK~#xZ7{J=E}7v zEwTgM$2d!%HS0#+nySTU5nIRLXZxQ<>&S=ZEBN7v$3lacw-ko8UxA+sfB0Kizt4k_ z`{%J)+H4?EB+#0Z6lw2h^EB&1L?858wv%R#$K%l|EbrJJnSsLj#RF$7_1KrUUcZF7TR2=k%lp#b5R!Lrs+~aB z!UKsb=PS;HyE?f^D7#ew2xX>L1A%b7X$K*N+mWyw%pLoODKD6pl0d}#jm2nTy<*f-Uc@Ro$s)kp3g;?cUSY;kAv>W<2C zu>df9Nf*=cR~S5gBxty<3LVqIS<=HX=Lib>jG;3!hLF-goKQA~imA8diU*{%6VWs- zcyPSR+JAw~=9U zmn!KhYwdl|Z@a(yvQ1~%yUqQ2Hok?pHdnTRI1W@}YBBC{%9wkq7MBtMZb%LD-e}BQA>c_mJ3f$e~mw#2=eui=2R!+j#tz% z2wq~;pzarYw1|6z%ZJIc2VnB`SX3!g!PMuW3e|HavPu)eQlZ2GIv#9jyYK_Q8{Z0R zK7PV8FP+F3MOI2X_o$-Wb{rNm6WQ3OW6m9a6gBb7dWaLRTS*@dbek*M>EBjLGwD9= z%d80;F;QK0pXGTpd2K8(+((NIk^vz6oWK5?Md2L z*%-wBJI0{Zv#>-?Jx~yN1L3Uh7Fx5>G36&iP$8YU_ zmLCiK*1W}x;QcN>wEyt8ux6h}CbtX_!KaJkl}I<2x?5pe%i|Ii3N4Arb*Ydltk%JX zLorfJtdQ4NC_HVqRO36<3ixD4u^@ws6@EEsS5yvx#&X4IXQI};gp+jGMQ+0s$Fj>Y zw7MlCW7FPPKGqEtB8-&xgd~yarPUY5VqS-)i((<5^3;IR1)fL53vz)Jl1CwN#8RRx zQ8==|3sHL6%JeaJKO*x4UWU@)X|$P>BX}CY1G-g?e|2 zgJN$5k%mt!F{s5`CwWgn0$VC-N!NiMSgh%m+g%1>H`(k6+K{*d@j~h<`@05Q)j4q@ zZERU|Af#!3K?IO|V*l+92c1KDn?J-%OA;!#HV;c2zzPsVdE4?Jrn%%MULmix*@jet zBzxgdi=Ktp-0MlyDW~`3rjkDZsLdh}y@FYfuGMtX3(RON&Ka@OhN+kdGez(F*9Gp? zF&kNQYGKRr)LdaB3Z6B;C$ePf9q@^2iXzfFK(a!P1)_A1lSZ+~)FoE@%N9q)RNXOB z73w$%R5_qXC_B2Y?7wzjih}44(9g&|zuac?#gFrB{bipY0Q3oNQZq!JHzKhD#~hNi zEZFAhe+?7uJ39MQ-3y`?6jMO+x8=7O+|q;*>z!9^W^HotUbZF!BnW*pmU1o&#V{K0 zkhrpF+b-+Q^;*&6kMG+=ht~&EslwB8^d^lDV*ruolETR)r<-7f06vs5r5w>I(!N}w zFz3=DE0V+v%s%+`0BVwgwLY^`x}|uvy~7+myKX}{&Lt_?h->})4Pwz0y0Sqm(Mu`o%JSM( z_K+wLTQIo9EJ0_AyPYm0HgcXL%?QGGD% z)#QYKJrUcL%y1ck}e{l`(g2DA@EKS{{w6>h0%tCL6h+6R? zu!vUbR6&-_B+JmOs1Wh26Xiru68i?J2~d7nV@&wRs_Nl-dc8_&^&kxeHcX- z+*eln5q)w2_m_g7manZq&!NgNzLNlgE>!#Hm2vjwusuUfa!|TXyMb;{Xl$a}ABVTo zw{x6~>Dgz%J^XIZ#xn1wSMrSTKZ-6^W-6IL|{1W6Tss%xTRNO`@5Pr;h5Z@F6GCbqbYemMG*_dt|nFWE%f5NXg^*l zFgwf;0==h_7-JS$b5e|rg<-OV!;$41r6>DfHUvM|f8=5F75iK6S2Qga_Oie=x~e-F z%YAyqMiEFEbs9w|*Kl8=pfy~>CDdX&;o$u!2w%)vTyCZSUCR&51Y2=GN_t4m!w+3JAV^$ojne7~Jgu_iziyr@P=+r$84t&LF0en>{SgG#wlP zi(s=4sK6%9Je@3-@TT@pmkWf9!Aqohbg>|&)<4Up=>s7;aToWfLT-oW zkYA#-bgsSVyCSW~zfIA#E1((lX8@73xn{)D7}Syxt(^cH`B!QW5Y{5+II8UNF$Mwh z;BqT`#7~m3Lf?adj?Ym6$%DvK=twTTAH{s9-+q(_sALO&=mGiZ6hHL=Z167(i>K7E z^3gQ`6MWs)vpN_vR91_%R`ZygpV>ab=61#dNq*XYUFd_-J4jRtlF&|SQDc8Y0e_sj z$%IgkSrG`GQqx098j>mK1>}|?xrm>mmee#>_NUc&YvgGcXaiyE_zXD0J1i9jmy1W8 zv**}W)K!c1R4qIqxRKq^@=M2{wDD6f2U2^v>>#}{u%pCsN{Z+#u`|wwNx=$yIq~YD zidTab4&?@UFus9P6)4I)V*r+XB3~*0UH)x(gz~rWN#PHFi%7HRgRvn^!5u|3rHu+G zCG4p$@7B2Vig<_XO9n{fp@0^vXl|Oa&Di=THy^sh;u-+Nm-d;2cqvZAx0)jv9{*ip z$YKx}-!ps0*QF80Z{`4f73?jbp+Y;oUm0lAd0u7Wx$sBOv4SsirRrzH*1-R zZ?7EZ4NpL3NTdVya#qy;LihB-6tLIa5LoI#LxKYj3ix z9%_Z=?amuo^B4zHPmJB&bi3dt6JvB{W!uIV2y@w!`Ysz5%?%#TzQ4S!ux3c{x+#`^ zuWi0|teGo=ll=zmW^II~uC{}Z0XfE0wL*Hvav+y)BrvGM|5B8~05_m9m-L%q6%OVp z*5Ql5Fm*b%tTX-&mxD^Vt%9r=J5@4NHA=&8t%1m?t3SbMl@e5J;;G8YGKPzd0+@de zSEp-&rA0NX>18jyrgK(NvX>z^j1?k7lkTjdciHMj(>Xb|#u z!pn~O0* zQDffdpk-<6Toi)Yc}pkY{3+E6A|v@5%z^IjBrL4CxVt@&=7;lWNNpe1OI%7!wgn}q zWu|wBQ3v`5zW4np^b{O)N>80YPjxLlbrMXO10xiD;P0tqNG{wcI`D3d2&`urle`6x zEbxvA4mr8wwM?Y3SM9+>Agb&j<@WDruURhfwE*=94TA!l zzyO(>JGvExI-{$G4d9&;7Pb{_dJRmiO2tQ{vg!)Cdgrc!rYze|^%84bbpsyOI73?l z2e*-2pq;}m(4tg;(67!Mu)Vu#5h zoinM%c>4wCA*sg5QTuXnmyz`Ob+h>$91hQ7+v!4}e}8d@-;y{Z<)$M@FYRuzHqZEu z8Hw9!*&=AbOwO#tn&7ofaQOUF2mcGN4DJB}j8UJ#EsUSw(&ax`D}K-l-WEy+FKlg4 z##g$v6@2HcOEabJna zoH89Z2o*2#pETZqKc!~hva?k|1YTEEmQ8rm;gEuk7GOUyEe=KKk4P}&4Gc+sAnBH+ z1)Y~gs>W<7nf7x398(K&?1~}T(h$V;77>%9SNz3dnAp||KGD{SW5vib=5PHKJq0{# zpBSiaKsVqxnKdKsMoG@!q7>>A6(SLw)Eld~yoIOg!_1U?z&nN@7SUV1i}LcyiE?eW zx6FxD_;~{#I%;hh zYPv-%B?=?f^ZK7W${Mr-?IM5U2m6oxA-LK+#-D3iE0TLD`md4Vf$lWqcxP0kotXhh z8PSyjSJ@7|+MHNHb!oH9azqc7J`QHjz%vw4>krk^^>XE=&3L7Q%h}qgfh`kWK2X09 zVtD;!M+)FTv~=*D2CiWy1MN^94d;pvFW9?9X?G||K+`NVd?vGoveop#gydmy#j;jw z#b)XD?1MCF)?`2J9fBxQZ@>```}fQ#8-C-KAYBBWA(X+#c3)s12uV;81P6qq(tQ0r z$2~m4W64B9rRtgPYMC0sk{KD{>+uc!YXKjjNNu}7%Yi#|43Xh!+lw1vn@j^a5oL}8 z5%ZiagC?{i)phvGn1v$cg|BG%;XAm7*_!dY4#h$TUhT{Ke|suBw@kJzv=N@XOFntD zJW5UzsemmAAYUnpD_v?Th)|UUJgA~qcT!x9%&OOi@2{^otVL87vNU8+%R6wIS7leP zmMz6pwLxo~IyF$Go5n|aj`{Ny=P#&s8Ii8+c!+he-ML%_K+VC<-3~Kx{A9NOP3O=( z7K>Xh0F^2axh52O*~{wc&R4ydk--)(_Q=6o$$-Rw5@KryRL45Bj!88xc8`C#vr<0X zJ$i_JAjJ>NXbD+OG!%EooQ?bY3&VwQQKna457HvDn+{jY`-`j3vU;V;PwVyLf>wpt z#AOy3Bn>=6xPsv_zkOUhZowJ&3mFq~UV42_%Y7G8#lj)%s1#y2UNEO*=7IP0YE1lq z4fXiDRA~J+zY};?Rr4f&qP~_5;-qx+Y>0~-(KrqEF4Vpzoit!|c7!T(CokKRZFtu4 z`uhX}L-yb9P#_nI6Y${q(BQ&&#NfhvN&V)dJN*97h8XaBia$>1+%Lr7SvfJ8?cq^K zf3S+PQ5a#$Nt)#92Hj^x?=TA4v!xx|GuNmYLNqfFI=`Bh=~1Sv2}$jU37=H+Goyal z_leUSH>_*l%Ep>0O4dUK|1tXq5y< zzamd3Y8D$oRO8p7dJkEynyDHiIDOqT{*wMsS#M;IT;;hRPA7 z4(+CE^V_1ZZT?M=4a}fAi_JF$=cYUJtjEOcJ=$TuUhSwE9h4^PAUb%0ibZ5uf2Z0_ zfM#R3<><+m?fTgrl=_QX@9*ar#e8yz*bo9sf{$L!BdcJK^0{C*#2|MSC48xY<3c85 zO{kzQpDa(rOHt9wuObl>$N>E4M`4D)-zC#$zFU z+j+2{<^B85HZow*y`CnjG#-OhQD?wH@_YIy1XmM$2c&+i9;?MyBvsuUFxdKziYLrM zlf>c!R6pE~%M zA*j3pB|CM+E%vK9kw-u%=aA4kSK_z|wudkPflXl_ z!n857O0!b2Jrgkv2bWyXBQ|r2oDr*S!r{f-qu9<2yHJ5Yk;?KM9b`k?KLSB_Ha^^# zwsVsu7csc1kp;=9E`fDARz8Z}9fn**D3uoq>n>))yCYSdTtoJ~?E0e$xnyk5>OTi& z&1L=Q7@6uH?-#dlpVu3dY@xyT=w$MGh3a=x)eyhFhhsebtk@*!h9ee9z@};xo)9~N zu~4`v?F=34M9k6Q>$hku+>xd8v^z^jK5BP(#N~Ep>7aP)4O%<00@4~iYLzT3KQ1V% zoH=)$9=#g<*$o?<;82+AslrrvpNm~?m#+Lk+3*yZ9Q3RMPs52+5n48?FwaTeS3ha- z--Pm_9z1!yX5R+-Bw3bLdg7B`MO4i*ncoEBkoN&S5eUOCZG=jHB-<4jI)2&G^K5XONc|4G1rq@Y?@Vzf%|!{tNng;Me?@{YB!>Pra@crSB-NUf_HSfxPSbzSrD93 z(QvD1Lr~FKp{ONfKt#;U9^93<5Uz9JGQH?ciAR;{!ecp!%gu|sA=Dl7)Z;h8m0J&W z@EqChXu5kp|Bm2ELg>es?Xr`2-it^W5^%Gnl36U#u zFTQE5!zofP-uI4axbV~dG!yK%^Am@rn{ewF7<6lNwnN-^(?UvBHFOk@pJ}Js!lZ&= zE@xdeLw9qv{<=UFjA2&nvZM*uG6VI3`9~D6@CdBoI;j7}R<~S#a(yiDC z#LU(+sQDS1Dx$}5)V?~Y4|OcxA5mC*r&(8{BZ!2_X0zVB{j$12o>2MyzC=`r{X+q7 zX(}5r7Gggc6l0ZoinE+=F_rXAf@yZg&c_i`JG$*SDgh8)Uh%Hj1`~50$qPtt;aoJt z_vEEyMb!|mVY(Z8fhck~s;U-9@+uwX%P#tmWNH!g4tw2=(X3YKNU9VNOveMg?U(Wa z! z2nF`-;_nM2y>d9q75kt+Lg9xOi`y5=yTu8ruQ0gLWxu9;)g%MMoRc7)hiHq`Vd@9^ zv~?$J*Z5h(VsPdH&%4v&@WzGv%}=vCe)RefYpt-VCbLIJNW!^8D#ddq$Hk?AC(OSt zBM5t8lTreSUB9Q=9G^6L>-@T5xLWJP9g_l|z;v7ckXpU9!uEu=(A%&H%%@F#({L%!Ra#ru>=nb}gTLJQC9v z)dc9!nw)(hIH@||NXKdx39Eu*M;EKh`q`M}m~C!gu^5>8<$ejNHbuEAypuR*Yt(P9 zA=hqLA%g-5aFRT5{hyshd_2Ef%z_n2cD92g|2tEGVbyKYw+yp_H}j#OG$dgBMBqD| z6|1or_(eOT(NxM-v~*QqjZ?d!OH!6gqf0|rie@I~pA&)!F;*voLWP`qbBmj`&2N9b zJYYJ!%9ch~-F9dKwn}eNyvPLyAPwMTLlZ?&v^dl~44laLVuoqvJ0?bn*w zr=q7_Jr{?++h)d#=lM0V1V$r5W@Dbsp{8YJa()(3>DvVa|48t@aHq0Z1=}MapH@D{ z7*(pHgOE{@!(50^ zkL85It{?`XtV~Lv0A*)^N)?u3kpfh%U~+I?7Iappbh!b30&l^W_8L?3kqS zV{O=q1~Ym}C@z`LwupaZAcjCEEkOhgJem&aYhulRV2WIU(ZcCvX){R_%i4s=;&!tN%a0D>=KU`2aBs z`@Y{okwSw$e4l36^mI19AeTjm`k*<7OF(MG6+uunO8q4Choh+E!KNBV#N88AE#A6& z$ON28;@-s-$pANsWXVIR;AZL2g=Ms=j&QrS2ZbulKzU@F$}wcCe*A}zjHCP-Y@PUc zXc6Sm$Ibd%0(=|7mnh6W($}$QQ59b(BUcnTn0q3N_v6~aT-x9s<+sU1{5f5`Govu? zvww*vNoJrXJ0Z6Z^cEOB&HOM&6O|3m(OGD|Wq%<_lD;5(%rj1KBjamCFJp~XMQz#F zd17Kbb^;6HaW#Mm*m?SqA_IRelmTlr`_p@6JaU!4SMU{_S*9@uRfmPjE;*aur0FLV zpF1qH%(>#|Y0N9itub79e1QqZ{OB~uJFE#`MU{(y)>ohPcOz=S*Gm~i98OByXC4yS zF=mjs@|bj#JI{tUWyb&2EAI&tUr!ww*tzsII*}xUE00Tbg=*k$@ct1A$0U~XJo~ej zV>M-kL+zp=|9HL$Kt6c!6|b2EQ22t9rd5rn!lSwz-m1Y! zu(UHn$$Sg5lziOQDVXN23X}gFEKZwzUMCdF1v8>%gzQJ=HD0y;|et4_++)aDAr;zv91!7{_jAgytUt zDb>uY^0`yIk99J_i?}$I1Wnju#Bs-HsIa`Bg;J|1He8-hJ5&w@i@P6$hIfH6M)^Si z%y851NFBNA=?IBGIguoCT}zfFfb3H4RXb6ji~1_f__w|j|JIN6 zp8!7WYgkgn3P0bJ8~_$~+ta&@;pnFs0r>cRaQRO#%YX&oB;uluEEU4KZZiZ%jV>xF zMVDna>qRN$c+c|_56h$nk0ZXe_w8s3ZjF2;591c+-6cQ`q(jb{mhl#H;@0mBH{;vL zT!V8bc`f*VEI~>g@XqJ=f7gFvN%#O?lhGJ_0bdipMq)wy8*g&{1wc`|h+OvlKkz1o zQrqwGFpjY`iaCavK}2J5>&sJo7|Tx7r|z{`deqgAI^s>tx(w7nb`e|Y{Feu`*tlI> zb5=Dlk7YP7B(KPm?L>zc>joL%U`w%>0dS+HvG^?Jclu3;T}zBoM05kkW#@Z z$vHq=T-QoY0d2EFd{>MeDYdvCu55OLzi-6Id&-Qkyu_9}{7zq4vP-~VAR)8#{-Uf< zoXmLoPdLWFQg4_>aru=YS9*Qv1C|9iyVG>hi1Uu$J^HMnF!11Kg8|_8>FXs?1KHzb1bV7?BF0$#N2 zC?VoNg6?@0ojh@nPYrB?WUOg_>baD?3)w5=KRQOiZhNFgo1Llg>?tSA=5Bu0Y9<9)jg*8L2JInPnHD{6Lp=91#S`E@5Fv zua>CJcBV8U2+B70UqQ0joZYa>3=#^DgByje_oWw=wx8c&b~%nHvXc5p@- znKsoeBWQ*2D}(92nRtH}Y!O-g6(dhjS*a0}!67hFe8VK6BsYTz&3&!`T@}nBhhj(I zt4SIlrer;_?( zqY8;PTjs!SgSR3^2RwS(k=GQ1WfUQrf&SY{WBN|~+rNpO!~611gV^40Pd}_TQb2`6 zZzYHsv2~q$F#gd|YO|22_hv!={~moZL1Uq~$(&M_NFfqG|NVNyDQ}W+5jGp;1HrHf zqe2u5Nh--@Q3KT(oslwGtqZWwOd)A&Z^plnACELN!FR5Ie~UgzU6>qSeBcrz5=8-% z`_$%+j$1(u>N1G%?$JfUW3e78CE6qA8)6_S1F$DE7tT#PQM=%tQ5{#Mm5s%yvhL%_9qJB*V;GI$2r)BFEFD^Yoeld)7rvCc2)kpC z%8;~?V*#PC-(Vf1fwADjWRtVi?2qYVocgEhKe5gtV7bgZVpfz8VG%0JdZ;@F0-m5s zs>ut0X0*`Hc%d?6Y7;e>*paXGh2!pCF`?hfI3E}E2u#BvJJgnuL$YwxqS?KPBTdpM z%D@at(ts8k7{rD>u6sd|3qpFxr+rDx+r`U^IYPj?LUjriWy)^HzktUWEmS5^Conb2?AtDabg29zV zjz)1@W#!<}eeUbX!3#EcgPK{7KVb=Nhj!$}q4|m2+)Q}d2b0@U&HIA1(Fs%q(?g%! z-(Jr)T!Y~2k}*nOFwFasO13f=W*ES}=RHK+ zNBQnVceLKP^!UEM@QNXR6yNmk;I;k4m=SM8sX>l;)Y8S{o}R(~#x_fTx%iQ0Tx2py zoQX)rKHs9DHp8wBSDQ_e0Kq33lx(Z)#PtvxN9kcVUN{eX&k)PG##la=+@;mZ0rzcY zToIcM#S0w{dY#tAlE++zI6-4(`Pu9-G=mdm6QoU9UU|+8S(H|yaY_p*OU09c?M%E8 zu}jl>!|6e>Q9eOJsht|`Pp$?LdC&r+eg>-h>Mduqh?X$-P z!q{A$m#Vl-)EC?(XJlSs#SJ$N3+}N!*==5$Oqd`WfY5*dj&v?f7eW&|S)k~M8^+#8 zR@4=pm{AxF%7jvhg_)I+^O}p~M)$mRS}6urH~@RaQ12EWwyX7HuJ8oSA02!{$>qhp zRK5uG$`j_S4|GQLDPd9BW~rF1obxhIj59{T);x-M5nuB?9zzZOx>-tP71t5mVyk~C zhItMz2p1~z#W~2mHw_yJqZbhbg0@d>U%Rn_OFknD2 zgI$snn2tWkXU*sdY~&@VNq!9gyH0r_)KLb?3@jQ95(#xd=Be!VZUtXUeu#+Vz*s4H z-b#C+j;grjDC?KS!$`^nXAD7%f$!mp$}AAl%!^)KJpp`UqCz>_(|R(lDQI#kL*?ztfW05l>VJW_6sxEBrgQmQWi=dZH)JkjK`H^Jb`4?Iz;n&v*rmSAUxKNZ$q9Qji8&K zp@5%l$JErto*qn#SP2X2Pz&|A)sRVBUc$XSY{&po5y~fEBLsK~sd*Mmp>3a=ZcW=A zX$Hp{x$83B+=Wg)04eAE)P6vu~RFNvZvpc4tIml|X@0<>qrR$)w4)99)rpvS}+C{ z&|5589uHzM+09!?-qZWZ0|6op&DA|p)kw^ z+cQr%oeJf~qle{UzWBC$T&TWb!t)dn)??{Ad2xZ3rZ5{p0P>Rgr_|438$Epnad)x*VFH%dGa*@deIRij1wl|9e?ot)A$-M{2%##7k#vhlU7+6skCx?BtctK z)k;^+rTz?S{YvI=+z2#P0$y0RCnaqiz1t-eKosJb63<6_+ghH00uCc(U%;wQAySCk zP%g?o`!fPA!O`)=8cn;_?ln#tsse{319X~xaO+^){ysZYPjt^WRhpFPh z;!gwBO-rVG0Ro2g44&~XK8XZork;aZ$1LX!=A<@27hW({sU>II42rieUPLK_7xAO` zrhf;o^`BzI^%oL_C{Ri}93B30FIdh7xbEV%aNh#Wt65EtGCT8>VpOO$h;Fsyvbn@R*UMWPs7La`Bus`D9kH#P$)Y5wLKsE14i`uo#t9R396(di zN-|lSIc$VGb-aetT@d$KiW07Jq-{=cvmrfJkv}smA?LhE$T^4K->S#t&}b|Q&)4XF zqDuW#sW8{x#N}($;nAI))(+Ke8WvlQg*2Y>qUl`{n4Z3;7Ed$wKIym$=w!f8 zi)aM;M}Xy4i+nj@rYksV^-aMa0ZZ1auRVm_%OW+&A6s93;4uv&h$N{T=Tt(p^_9Zp zLN76ag-w9JhBO|m^E?hfMj+;o)&#KnNh(ISWKmE1w)dHnD{t<8YuZ~Qu*N5+~uaJ>&C-pe+wm&@J=Ano#!TMtxX7!Kt`ghwt3ye$g+Lb1bjHZ{! zBoXC>>z`;^3bWcZTg;1P=$LhvyEX6hn*&CT9uX!iQ4Adsz&2hb_PNsWl!t0 zM1nByaO?JVHN)h9QbPNIxIaY=YVfx^fFd?@>`C^rl~m$HhY}ByDbd(5)Bk_RVT$lM zIrmW##hE*p6PY8JC{OcH(=cdA!JcC{KNn#JVty4N96$Y-rGQV7D;&N}8SV%^A{RRjWGJ6mGayjf}QI2QCsfELscU9hXXGZH5k~FWB1CHz=}>Lx(L7 zcb;`mEAhEw*{TQ_W$D$@RQ|b6YeU?9*%`(Y0sm)x&JF5W@|hPLPtMvptAKMz}gkfBGIy+7rcr;Kmb) zScini`AFWIodCGS@tDeaXaqcQNXL;MQVYBw)Kb`3t&HlQ0|p(&=3Gwz1|7NPTu)l8 zf~A#3RWDM0wlHZHJ?&}{c--IC1s4h-LhQ4Xn%H3KYqqA7j6rBqcM!$Cby+`nzknSp zqb@UK&<=;XDO1LwZ$!ZZ8M+yiVQ^VgNLNEBB%L(0ENRAOs+&XBn5r$T_j`67Y4+1Z0$d-*^xURK0+$JH7p0mf8 z33c~9j^xSCQDa@!nW{L>4ztSfaUYCgz9!aR!Dl@cG7cBbL#k$)cSKP_yfs(n>*^`ZL| zQ?ZYnALi6{x{{tdqMmCfI?-1}_lUx=iyALW#e_MOL?ot65V%wgl+!sD4Qxo;3j{d|3)&S(osx~N79XTF zAAdaZ^-oscac!uCoTmHLh51ORISje%04^#Cq{zzbgpm4zm?!KQuoTZe%LPLU_YRR z09tZAEq>DIG0FKEr?bbW-?xj$C`kG31*3`9VQ}LA!0jBh$3y3O3r2Han-l|( z|8m-8FqAc$eQ6cm&S*|^`w?c^Cl z5SDYy7pN^kw;{x2=D$y8U;aQ^JZnTLjqOZyO6chH?U%bdxr0^ph>z-?9@m>aXmn?{ zw1%4fcNzp5$o9#xh76jto7ppJ4}eoVWs%<`9@2rMIAhSC-WPxdDYI2D3jpLT;%6h6^>@`0+pf&BmQQmfG20%}RUTmJ()*{o#}M^~DIE1wfkybOL)c2)HjT;6{?JTK z7n{cb-s`CaPZ)RQ}5Y1ikZI zoF*Rxho9)^#ST}n8pYAyk5gFNWq|q+*_rFM(AfOoH|7KuttPzPt$6Ts6CgwQ+AT#^1q^2y#ku;EBFf zElqz?OAZN2yu?n>#*^lgnQd0MJB@0w;4)GA7%@oj@WahqRweZ=l?v zZ7mNem?wv`M>N^mBH{Gua{GAk`t$gFBJ4Cey#BOVe|z_JvH5U^p}(+japs5keY6k8 z&4f_-Q{LINBl3ewK!V*ftm*~hcoL;nDRX4^6xg&!mm^KFzKQyur?3chjhPIJm~R>^8RRp}T_$HVZv!4Hh`Y zdCu|})|I54>^i*|ur5%+=mI8ln+nQ$;?aSQ-XfF_=?rei2A4@KHuoR}N>equY=3yz z9Ri$Jmin39g1m-DHAO4ls5GcS2ebFcQBy4{vZ%^u3qNjZh51)bvPtf|`3$>3zG6ZE z#DY1++Qou$Lh?g;XN%!mL2`MIpHz<{QPOBf{0mE#Ip!`1!rEa({1FSxBL14Vqq#~d zhIX?k_w+;*qbqY9ooqMX|GtoRMmn1=;_Bj0QVTM914nNOFx046kRh+V0U)4?;UF|4 zw}5r3Ck;=@rH`z6>}~N|7Ux%dkuISUtFLeyUwn-kbW6gDO#?5F|Htk zq%j6P4D2@c_WpM9$22t0`0eq5jhFDzKkzmFOZp21CJ=`dnXifm)vhC0H8cD?({x}W zVl}C4qc)HKTa6sNqhBcg8Nca&9={oXHSlX)7l}WQ7p!lAcZxsqD{NzBkICG*Wc;9r z@q)rESe($6i~s&IyPIy;?7cH%{P%c{QH-pKa~Vu9${Uj-N(CYP)T(mh<2}lay<>(| zayrVzt9=5$N+ZqT0B0Z;Y2QfVG9}<=o|;;QxCPUB^TIxf!a2t=n+a=_d5oZ3eP@zI zGXF6IRBIt(dbm(69J!H{EB54=&?iZJ*E@=565lO1#>|v)YDrJPZgSm{@=_ ztMX{@Fd|)&B}p(l;^yG`L}ZjhBckqK01zGx=Sp=RRX z{dz1^^Z7;x@Dabi!R(*ScNj6{qfqQ$PcdTjDA7W3a1mJsXoA4EfEn~j}HXrxV2pugi8 zUhFy_NYsoLRl-78pS_dLCQN6zn|;RwS9Beubf86fjKqj-=s|*GY!-jjqyj@>a;`la z5bU{F(Q=4c#R&rW%U2IcUG>!7ygfar0<{tAb!oiAHVP4tiH@6 zD?`2%znOWHI$A6tVDJaen?gzM;ng{**u`L6vO;T4YId`B(H$G|46vobt+P@xGudT~(U)P`3SMcADukphFkzaw7@McE;(-R~~JuEinOq;tfHqJWMrcuC?Fz-jk z(KtYf`}{7%d`XiPH?^5Y$g|C5+;?5KzOcWI3;g=M-1^xrHj+c$OaZYjFu0sk?_oPu znwS}5@BfZzj|#qWIbmYmur_a|m%BzuhRpv7uJ&dc%6&t-ul~zJI^Ig8wwW#tZ*Pe$^s05w}rvWTKVI1#h$(-RTqHdQSX$-V0%ec@kC)5{v$I z+k2>*BT?_koX2py2Rd;<`T{8IDy6}=6UHZO8B9QiaZ*#=ZPRY_#$!VB+P~2 zAy+0b=Hh)sqmYl-#z^bAl^e1v1$7DBCGjtt-&$$%PUUJXHO+}FYASi5JUJ1DG&A^9 zal9cTj!T93I4i+8^%RLg>``z*$!!)Bs`H5MQP8na51If*Y3S%L?@5g#-avkG&rkr! z%g^{dc3w&&6>{Oex>K7(4$0Hx1wsrPc(QzCk7uR4K<7>D%Wu9j`Jup)$!`vWC4$in zO^H1r*%)~;+57-}#lboKSsT(5bU@Zd>?~G~$gr*uylsqkBcKj}4rd|;Qv1{6xAcuW z;(s1T8y_;Wbva+6&Tso^eS10EV8lD-%fb=O=MA=d6O0d*_jl+JcLmULxq*mS-hJ6D zq}v+LUH&+OA6&(NmKmT&06(Q1Q5)r5+`#(n%Onu!G><&2Dxs(}(vz1yk`8@3?m_c4 zOnj#PcV?s>&oQkkh&{Mx1#r{Ivl!N8Dkyt{P{__Tz%n|xTYn50^`dr0uh$>nBiM^x z<=tfrSEplllK|H^ z3LLEvY>9wop$nkh0aotOj|+*Lh{itu^>3J2{kQ4=yGFmp^Jo@;StAx741qA2I-#Fe z3hDWhvq^Zb4FBpkt9(lAk~tXqjeJnSj_`Tp1Y6}Qgc2wr^Voufd=i~+ZH`1!U_!AV% zy9YZfk6}VB03&G%4hyaSZ0~AF9aD3+G7U)EThgaXLWs%p*e=;I|F;?Vg`F1~Yt*;{ zF*9wbp~x-Pl^IF?NGG9>0hVdD6MhU6DOol6d693FQDJbmi-B-E8wVcQwCdrhgItIO zx3jVkkMURJS|320P=APA-H}{h5bGNqzPNQM3}(QN&c$yFRZ;ErQuv<9F?KB9veQu*dc~P{= z@oC~m_2IqqW-=Rhj6d-J*k2NMFpmLi>vt}&Qz`0`7KqY{|Gij)huW7#qkE5{!}`aPMFmuayP%6I3QsKVbN4%$*o4uvHxQ9*dK~ zb}UY~LT5*}D6`&2hp*T3*&PB)*No@L7C6P+)swe&p7!gZo_DM8)~Z{-331KKwS&ULm0GdRAXMs(+p6r|&s^rrpLj>{`55xDAw)JmLm z;7DhJOX3=#6d9ILvS{O(pGejqxekWLY`aEU82N)Pm7s}x^q|YpIs;DM;=cBJa+^fI zgPt94!aLw?onF#ykteGQF7@dUovsS4rtf!wAcg*s5y*$XEiqG2hGl=oFgU{PF zS(Oqe=kgZM=KUGaGkx|)?3w;OwrB_s?yAb1pc7bEx=bT0sIxaER>{o>bE}Y<(rp4) z3+JP>9}-mDcq%=_@rf4FplT(J6Z>@|2{m#eq%+{co7wkBhv9{d7T1*#mu^Q+o0bQERg}En=BvN}KXXy!v z+E5xaMNLH#Qt#kO3vE_UWJ_skiuT4gj4er+Yn+C+Y`UC@8hwclu1JF&wb|0<3}D6e zUI1%w5rVcUF$rJLho`Db2%xExn&v9=z(RRulQT5+xS!LM%EBBtS=!*i24R0W>uRk* z);!|L)|{GzS+wb-an!6ibWMShs&rXmiCiJJa{e75SiH1)`BvOV->afU;^EQiKwhh) zl=B|kA!mtJpqou(m znav@otzFTUadR9OGiu&#k>({{{cre^cMDui(EQ zU*m=UBft7V>GLBlR+LW;D#_q|EkZFxS8LF`4_7Ly2A}LebA!NYV2!a|KC{;J#L0HK zk~_Uc4*U9%lZ9c!!*HTF0xgfH)0G4vWaLr|LX>jRYM8-+TbARdpIlGDHvA{ig{c&Z zIWMH&Pba~5+MIlbVM%C591nf9`usWA_u1G#P=`4j&!?!vpz>4@wmzNA_fQK5u_m&% zWj?7CKAAmIB&W@GCYSjbjf2XD3l^v9KY#m(?&+Wi{Dn$F5vTeAC!$!z zc_8j)L;*w%p5Nl$!MaJh&9I0dd_xcy87qO+ArTuCL01u*LU=S$3FPe@_Rp55x?ioox|W2OmtQGpaX96P9)!+PBvsf!KwT$s zlL|w~PN`v07iSXx8ILZ$5Yg#QLNg-=XF<|z@zYCv7-LZHs*1cMo`eMtq$B-aNs#XG zSfgW?`>VfVt1;ILH_WDQkCqnvpoo95$K_r(ver*b`{=s*WC`Ot#u$wO8K*} zKZHP;q(wla$QTgELi~evk$yC}rY@t?JkQ+)`EGw*F}mAWGbV;%o`4ws(miiGEOO7C zmCj;2Ak~y3Sc2#sBIALu9EIk`W(XF!nV@#j%EV&$O=-%Tl9)R5t{82GAyrILZ?_1T zXa=|%2B)IUfc>`KU|Nk>pxubsZr$NU>5c*~RWten{GI=%))FhIj0TdqqfVNgq0Q#)!Rg`Y+2VFF`fxsR!L;lVidnX?bt(9Y-#t0hp;q;I!6-`S#r<7wE85d}nAVJNW~y?>(9*gi3`1)5O&+870xr=rE+DDExPfS!nmO z9INRHHyQn#1YczaUGn|8Z87 zb+vn>eGnFO${{L9(wf*IoZu^oMu+ITAg!j6jJ3E8F#?jNgAt03D^Y59Ov8$>lX6>G zBOW%q6H$Wf3&WFzcLvsz<1ycXys>g;R%O=aKD{4<+;5s&Fo{zCBRnFr(&0)|@+2Sd zJWd26HS}n79!?PPK+a-?qTo50yzzP^bJ*bZ13?M7aNO3aO)dsTGp~0@PxjOxxk7f^ zV;c%RA58;$-=x3S_E==Fp(Ngvmp$SKLX<71IEVO}UOICJdYd+vVTKO9D6wFDi2CpN zlz3qe8tk6yqQ~Z(Z*bbHYF%K543eFil`LbO1`o(%5ez$NU5Zq)izRu;ZWOTdK;^i z1I5$kIw~=j(*_n~iO))qf}>U74<%Y>*}k!-tygo>U^VQOlg7oy2#Lf6-O|Hen{gWb zDvnA-y+}d1cqom_dK6Dmn`|&IGc`Mg@LER$X3I&Efz=y%>GPLVGgJ}RGmW^~0ZJiVBX{&vW%lAz)Bmxnvx=uALmnFji$U@ygvi+E15 zsc8pme8jT^2oz5NwH&#j+iV3pxb81?M{9@e6);j)UrG#|rZkK3!~#a@28&HNXF$e( zK;9v^_sw*(U{h31hMT}Z8J#YXXZ&%4-l*bd%#i1CBgh@-z?tgiRO}j&WRT1t)4WK= znU~o&l($|!#wdsQATgkmeP?vK_~QX7xLPYR!+g7sRDmu{oZ7{EEeCF}i=w}#n5NNC zsvsHWU)F#giER#%oMkI!bbTVVg_=|-nUbx5WT7jp%nes>cLs<^S2K$pEc+omQRLT` z#7s@tU19!_FbdxD%2><=L)?n9!dEkGTiY>Mt+6biMb|lUmtsN~7MO957sLaU@T<)D zp?ScCmy*#}FsnIRn6UMmijeBpc9i1~gr`VxokRtc(R3*@D2pu2HkV&a$r0$%BH%Iziep zCP7TzNvJFsfG#uEe1uQ}0RIq<2>0PY?TIS+U(C-6wEQclf|+$?)@zXgc*L%$!JN$9 z1~oC;segwdgHfN7NfU;b(*>dp7Ftw{*`(}Ov`1m#86W}RtjvY91jt~~5{#=u{Qq6+7T)(`H9&@DQNNzm|)qyPcLq7YD4UD5@+Rg=m` zlJaS7e5A4{-glria@wD`KyJ>ll`ga9u-~k~g<>q&Uc^-C@xdF>I(dyH#s{o7i{P$3 zDyD7`GFVS+HwLySbx7p^Io^!8>KK?RxLaFt@*h||{&n?PpjN!*d+5LvUNL&C-+dt+ zKQWjOzvg$wu-@boNwC2ybf89p7_bT;iGgQn!QW#Cqmz(FdKsB(!l6>XRKK@`_Kq!J}X40Q-V8r_fDCUK9T zt@_e;bLQ#-F30^`8YS>);2>sBi%O$jn$c5UDPmtGryIxIaa}GF)16-%u*~bZbaO!V_elA1HZJ4$D z8D&A+3rSO-_8VvovepJBCc`!{XFEq_le4C&>_F#MGet(B{E;rReEgJTwKJGbI8+n4 z?HXuuzRp#Pb`5hWY;znZ6jZCI+;E(rc<57~Y|z>qxoKz-wE+4tM>ZmaR~D^khCgGI zDE4y0c{ocZXs}_SKvng4U>--S{3()mrvHyB{ok+q(JuVQH9nT6rbBeXc9fMIT4ZH- zSqaf;m(a1>k?{@FN-|~u=oFTx)KJLD;Ocrw5`Ed@YBG7q+Afws-MnJ08McL6r3dJ0 zQX+FW0`K<-dRbESlWL<*xK$y%(V=MhSd+_O6w~~CyaN%_@L@}_AI z>9Pmo!CMh_XvuO&2Z;Bg!ht;M$dybIRb=UFG>>0w{sZ7Ig!^4(bvC`+QaC4_U8c6x*tBAJnjy0SVzM)fAy315VnVHv`hh4q%h14YLsHFpDAaDm!WP@oxWmCEAfN{dO5*|si&vk(1+ zzl%S`n+g%=ckCmqqVkKeHP)1}a2l$-Z`+b0a8LG9;OJZckZ2F|4sY&DM{^Np_*30I zMS?@}En4x^m;V;3nE!2*@Uhpt|+B{|lP12Dies{Wc{%*l#CQO9T@5jYt% z$>OO-?TOy7Xa7>?9I))p#H;gFFPxalttR zY`-5VibCid!WG^XXSrONJShE&yyF1Yn?MogQVz=s zf;%9)iA%_ao}>+x#Z>cq!XB1unoKy*myS-5!?CZLTarlu+$p3_PSa?4t{|mh=b|Ts zqk`Na5dIe3?Dbx;XCnusBHnj_0!nTvigpbz?rPyRBCLSfCx|_-(gpe4PKH?BU3=J2 zldBxt^|HUo94~Hke}l+X3<*lzx9ks}MTJ+Wm2g1K!q@_h3SZ50%ga2aIF2+_a8c^3 zoeaSaoP}Fu{Tm7o@~^aXfGi**(dE)#bJ2KnZ2HON`a zl)iy*bzefwwhswgZ5!4=aLvz*_AZ$Z+#K^X!{KILkb2N)-t+r{$m1=N2<6B|zLKnf z7v&);iELHnLWNE>V0aiksf6Z=cVej94TVhTn%HBA5n8gryjYC0v3jDwY1RjRP>5?c$2e5G0?`}RLHI0&X zc#K59?2}?eQfEOD18uTMBh#ehl=9NduK*=B#^a)H0@?+ib<8bQ z3B9~m=OL5O^$5$byCqM-__QYgfn?ldhA$HlUd^{?)q&u)&e(F6ruq{yRZB7qB=~@s zr#EG*fVE`Nh3RGt><)t3Qf6DqFH96oRG+3&OXVQhm&vrG%{t2vk1b|@qQ5L>rd{@5 z*JEam0IoR%6i0IOAqR(ZVL)z{*Ha883xg6P(+s@Oew9P!AE?xlNth9gb@=5TnFoj|-%eR;@R_3C^?xYFgoB8pj)wIp80vJphQ_9*H=FjeE&yu) zXT8G&OcSoH2g^4(q}H@Zc;Bqd1};)$29Azi+`jv=efUDhXfa!v3za*u`vk~GBPggB z%RAI3BtQ2@2b03YH-+FDMnI_V7y(8r#>J{=S3iQgp2cG*JkKHdxVANbM|KxG zvrgj=4@$eGG@eJ2&f?@5PAU|l@c~?0iz5v|u_!696<@W+$TlLs)i~VADnSR{4vIXK zlUkPEI+Wl#_-f~fphMOQQ^*fYHGoYABB~~~QECikBG5_p2ZBLd61>@Z45c*#jVZ5= z(MkM~xmX^?7>&^`e8zO8to7pny9oi%qy7ZMBv7k_oDuO0b~e}15(-`@eRb${vn;S@ zQK@4I(t{Px&l7iBnE_88%!@_5#*C%?5N&dara|wUv>UJ`P=DIejv@Rkp&+Wm!iEeF zdvt?5y-Uof50e^E4z&^+79zcw&sQ5@*>rj+x0kBmz7n0iEF`7loKLZAlEk>X<%0Vu z7$7xXuvq#;`V(5)y)w6`D9OSuWuhQdwM%Lnx7{N@Kc|LP#y@Kw`1H&D^1r_z^9oMG zN`Y6t#Ev&CSE|4pqNPR+j@DElwSmdRo49tgG&~K{WKxT%lY~2#WcoQ!a^|=oJrI5W zq8sE^8x18a2zSiSGZQd{ym6QXSK5r_@%JK>z>&oRI{-RUA9acterwFG?BUzCoS)u| zj^;Ou)A@(R{B$%n{PlbVSOk4Cmw%ir*IyBU2yJ_J>|Gn%n`Gl20*_*$!B_3c{263j zG#Xc?3#$Dhr6m}THL|K>jiga<$6epE51sCKT$EM+{ z#cIBKs1&+`U{e+dd|m}CnxCT8q|{SFwm=94@e)eI$!29{3Ino_y5EG;4AZ`P`E9`a+BZ2ZqX~7HDLX|+ON6Q~7B!CX(Dq?;N_zPrUecmnr^g$J$ zcGWB6(}>yP3>>H=BE{V$56q=w3jhZuYB?`I#JiVj2bh~5#Vr%D8Zvz+xnL?6u$zy)2FwVbUvX{S`hROK zR(Dgl76o5r$~-pE9-M~h>h3iaD6)HBAHKi7LSXPtKmpwF!vju%O@|n1Kw~_NYbTUKE7}qYeE4D}) z1(w1+Ym6NxT1vLzITmJ}`9b(7v`-uzXwrFoEok5TS`}}(Q*s#!HGy}P#L3*2LQdnc z4CzN5=F?m=j1O$4PYai=Z`|Z8ILOBXI4crHWjsk^HYTdo6(oY&SG)r;P+dge>IPFO zLJz{y7xs4-g|+VGt)>xVb0~QhSQE(w_RvAcc z3WSagt*h=9GOz~Al2b!VcK0o5B&j&hZO^RB!n;b5Qcc55j?EAy16DZcpT)=RuK3;& zSddR4n?I=0)$g~Ie}U9D(bZUh`ze=Wo>*U|WJy8Rd|q5s0~A?&V%NpLf~|5mPe zDSzXAECp{~%M1Ckn6vt0|FeI{H>9>5ce5qPf)2sb?r!*4-@tWu)wvtQ*9A$EdG(Ko zjrh;qat0E{V>_g_(htR%X%m?tK4|E{0CttErjY+Ty^|@o!L-Ya>8MP7uPg6iu7DFK z=mklrW^72F9&2C{%LRFY$L_N=rQ{_cGq;?@o9x~!v`zsWCZap#b{a4mZDDQqk06V& zWZqI68MG7~PGx^aI_*3S zkY&eX?nnsXE;_Xmb-a^kP?;ghJdBP#;e-5h4rsCkxf#EbZ+56y^Cix-xpmW#Ag~jH zt=klAy1n4>v&|hT1TXl(FhgL7*0L| zn(;kW_U;G-Tg+`&BsdaqZ_N#Li4QQJzT4a`(dj!zmv%LX4u}mpz_Y_~NFH@20PNs@ zuydO0j9pc!{mI7HGT}qov+*W`5NYt}^Ltjco<*Z0Y&&Nf+|9mA4m~y@3kVt3*O_TV z;eSx)&EWLgDMq!KF-)BHmpTM52R&YhHSKV6I+86BdUZ1(jKL!9WC4a_A{%uRqasg6 zLGUAx^)*``g}fi;Y$JOwPsmHf+b|Khr=t+lmGJt~h6Nb+%qOFx4bb!1t-ws%9E3;emZ?2_E#P^F?Xm;SHLf7F2RK&6kt+=Rn9&Q^_XeoHRb2jyia;6a?J{ASGFlEq_?l6 zV;9nkThVFN@a^vAPIJqxz>eAYHD+l?MNM@rfAD4nUFi{z4+Pdk5N-Bxf$sV;kmQzi zb6&#Y_iwM`GzRi~-j*a;U?1o@2t>~1IsKY>!$V_U7_`RAU`wAe2Kr{P{j?^)1brm+ zBa=5s#eV^Y`#SjzB8;qihAQ3%L;$z{Tx=ef>w6Yp@jnoViT{E)1Fd(#TTIqH?7@!> zasTIfc}vJxBNh_D%A>0mLv@C8B_<+ZoQjjlPBkWn+Z;b%+T#eFOU$zRuJEIHjZMH4LZwPmA1_$EonaTiG2;Lt5^VA8!4Cfu_#qRxqPw-78!jA z{LUHQ_@Oucjvo=lT7(oJ9$xiG_<{Smz+G6SK1uOHA0s}DekZ;ezpU@;KT`m*LUyB1 z%;PU}SJ=Z9|KXz(4J>6G8w$rwW#^Az%J~~I==3TgkHL%KST%SSzQ!_F%n0}}n=e8f z(7M}v&7x|7v1~5Ae)n8zBq*|7#LD%|DK@tCpfTw-?xW_HcN%`@MF(4PVzj*vukX$` zZ$GVEVBrmXF;#H5Xd|Ls#+TNLs_bOs?2*%8jv!mhz`Tz19oifJw+EteUXjkHHZ5o_ zBv2;PAr&!l_uVN|J71V(5FtI6C*U@3PuMcF3p#&A5vk@c#)wPmk z$t&?>npMR7RVvzl&r8Nk^N``kGXR5_egZ(UB>mfIrFn8ej@A z?#%e;jo1nfk{W2{=_)s9MVRgWK#b~GbLe|8D&L?jnpNF)BPcRhF$@?PVipfG+^&Oe zPai|srR9_}&S?a$hwfP`83=J;dOCBy5n?oVl%76zOB0P7W{R+zZ~Jv&kpqQ(WFI1&ZvHk`x; z*>E18e@CIyaxOwzU}u4=jMTaWF`IqJNN~p3(NT8vuw2X+-9d9{D z2Ls5Bgq^IJ)VX#)jQ_I(vNjeTxD!GfVR^M>!35lkNC~qyS6Fa*$1u zdc(rY(>@c-h#uGDK4F**D4Q2b36i_{O%jCEo{QIuFFG&0Yed&eg*X=!!zv>JLn3aLfTiEjmyaDH1qM1sf@8pWQ7nCg~sR_3zlVAehX{kC&|Ex}h+j zBafxva`8qddS!fLz#Vs%(w!cQzq1dI#?==aa=b)t!XgyaSF;XGHrJhNXkaCPMC1Y7aUS9bx_8Yz0Q{IEnRnT#~=aMei< z*Z&OSX3U?VUiJk*M!`b!t2ZM2qjS|T!$bU$GWB5xO&^GmS}l9yHW%qNaBaYm1WjEj zfxxA)U?J8PVM)>GgKZE}%qS|IG)Z=zqk_{ZG}C5fO> ze`(xQ-MSC7Y&SEAHjc_;CzVyf@NfU73&&^g>*M{@FWVj!F7Xg^6Mn=IU5@?CO;42c zM40S3)Dv+A)PEvW7J9`}l00r@4j)+-{OWKCq9@9Cd|#zuVqrs78!^iB<>N2+Hw?5S z(w?4Rie%>?N&3XNiRfG5333F>P&#^PwHb3!rfW?A)Vh`YC`Tp7`E%OD1z$F4BYUw@$B&e9b`oSs|MQL z&pEdWct3*Z1S(v=1onrF&GfBnBgDFW$-3nw2NHrS7wliw7 zYpZouldc|S+of7~&m=;*8J$U}GW!ThhAV%R;-b7y;{*g|(mG{-IHu`HjdtQ>Pq+QB z!C+b|9+hv~J!? z4ixN+@|HpDOm_ws)r<$cev5>W4win}&C>Ewo27BN-7I}PNAk%=g`SdNthPSCc>s91 z_%J^ojSuF>CyVjvkvS5bVW;3{ff!w2kdF$>Yz|7y2O?6Kvu+{^$FkvcE4u*~ODKk^ z11L-Md+UsxP*6BiWi-0ckuMw~E5K9etw7cXBD_oJI5L260bDdhTL-saVOU>SCRF zK=d^DUX^=^I_F?&W|2``AXunK&x`Hj|C5!jB@8Et=W}$4Qvkgj)gWp@Eu2H@z zUmJ!gg0K_4)bAcW2Na#u_vNck5l+`Kr_4Jr*s3AE4Nd_2*Ki~xWn$#Nu9^%kk@Tq5 zki2ukst`=+%|jEAv3i`z0+S=iw)n{L)T)j+Ffq&OYl8I_&EAdJgW@kCWLlNZD|FHc zYThK(=qNe0l`)J5OK4s@lI%*9<&s3u6|JF_*1BQ}y!oWJVcvcU!39$&)YlvRlk;N@ zs?YF*B_6vQHo%HgmDhV=6$6dRkfs`A2aPoAU~$!zW7t8jkpwLj4>oDaA`{Smz0=JX zM;Vu>VA8OundKd!<>1T|b;l7bJ?F6I<W@g>5x9~BMFPi!gBKazs(gH0Q!}H&r$w6p*&4>C$%X2ibEHHx ztnqddZ*Vc#s;iJU$jL#S-e`(`vIahZ>q@^qkJjbK6%I?ybOAsbKtGrZt!0q29dk^K zsd~&Vy0)X~+w`OB>11?hsP%M<@^lXmR3wZ?O-2HpD=W3~c&xtm?T4nBas`cx^${?NFSQ(;IUBv|QQQNV`*p~QD zeWCB@)`?Hu+Ogg$yqwP4u@Z=~)T|*jl5>``3txnS;1#M%-b^3BJ7yNt0m&{`(5_sM6K$jT1A*ksCQhQ6@cyV9pP-G_ ze;#dJ7*!?AduXh7#gy){j|2Rf(kRieWl3RZZJOH>Y*^xxwMU02jA7eYOcKWwC)=FP zDhldROFaY-#q%Nj1x1ot7sbZHL@D=L91u%QKM`8eP3a1FoXY zRk%V%DS67x5sP5Fqg3{E#gkf$pSv7EXlwKuv!80l-giz%7xi!wN0%z>(u7Jo2M|hV zGq{;yXn_X{+tc9)d!Rqzb{&<0E1sy~6x0fR%={rk8*IQTx2_20UB6G}&k?{wUznLN zFJhwjArjCOk5MZVMq*9~0Xi$MbNT8kyFe^$T*&AvGRrq4rFc!x(xmH~qy ziS7xGz7xWxB00BSr$1SAO@>- zuw!W1t?g9G8i#?l;U6q6{;luCzx5;ir*`Dn>&yDXy?!EJZdoJLgYIE1!C&mC-gdsY z;!jV$zyh&t(a|Z%6RZ~!)#PxSV<$MR4tA^%Y_EtNPd zA}Xj~G|@}9m9iua7=}!sR4gQgm*i#Y%ddm!YJ4t#-T-My*WJhT*e&HX8+0rT#q z;cE$$*y9FDw5YbUFX^sKBdCr;0GAO&~WjI%Q$CNrSPk2zuu%VH!{2gkw1Z0Yl^WHBB7ligic^ zDGWX&69WwcYVL|21OV}%Riw|Kj>uywunVxT5VJPttD}%zi1{M;C6wtcm;}^3pcUyM&f$?V9s05LtI2gDQih=---B-iB;LOOHeVMK-77Sv$2;O6I7fQ11k)pb#>h z>+*AA4Ro&feVRf&4>)wP=f1-rKY2a-pYP0Qc!qtZ$;rJ(Mziidx~EdXuQ%`R@4id? z)siCQh}u9_nTNYFxl`NOWzZsKBH;FUdP6C*tkaRD(Pr@z$>L~tXlP)(Ijx+{t>=@_J2LqpgzlK-dwf`6^wuivTP_us+m;!j4S9)!cTMid@iQgV{~ zGp0OGvm`x1fp7arC-aPu>9=57R;cAn4D04LMUSZu#bG+wzfIp8(ylhQqcz;_uo2ta z=@yTV+{m-6cmU?f6`3&`iY9jUp$dX`64ZUfTO&u5piuAIks;3CqFC-trV$bh=vAJ=1=6G_lm^eMDh*99Rm$ZZ{J7&bL3iuD7l@Md56FLLlJ&v>- z5)DS)ID^~#JZ+cwmTTt_&hDyYB5#dOo_(5aM5jwS_y*xz=p0KZgUQW4DB}GoC|F0j zRaC`xN1mxXyo5){SEtN@YkS#2`oFpX-ndv??Ciwq^Fqb+>GJ#(A-Yg^2dEO%#w73?JNi!?_tBN!!5E%YT&O9 zLlV@5{oi8A!Pw3PsPMZJN{9jZmVQ5+q4R&axlUFYR~LJ_UT34j$^DlVD){b2PzjrW zsT7&g_6nDfm64>i9{pzaxL}PD{P!zSD4loC0RmvA?GzdqO-ZX_EzacrlW(EgBQ(!3s+VI;NO9GK3f8Vo8k$0PiB|>l2 zd!`q0t5Gq#n*A|-T>j4@Mw9$gn~-W|@yml(q6@3_LW`!vFxY2g3AH`YOl6ep#w(ne z(ULu8OsT}xzwrnaY9YaBlfE>*9e9&e0@8tSi8=^}J#|SRg3QM7v-F(7C9 zsH5*8hggh8l9YOY^4S)&MSmHVnQaGjUPTmUlT_!|mB!ci6v2hIgKeD_sc!JSyi4A7 zv7CfE!NuM41FBV3du1~!yt!=88mLr0vZZ)_47K@bsFtwT15k|KK#6GwqIYnS_5G)H;(KBcubI$SYw zYH4}g74}@Dl0ne)nj<-I+bdXh2&0NhZxT<}Q@7UJk}00Z_&S~_UaR*bhw685_fI-E zI@mSMjEa*dkBsP%^Q02RC8nZj-ZA>V-hG$SQ=@=%Vyzz5wFGXS5k+Q%nO@#8ozsHx zo>QY;`F?x)VZC9j`$9&;!oR>AgAJN|;xIRh517J^x$$(vCr6TL8CIL@Xbj&CY4qMk z>vlDUBa(DI)ct7X)#mO;N<2Bwvw9W(imGEzGq(HoKCKsfE(VB9we$*0ifKUrCgGzs zuY?n0OgdZ(4{2vmR}e6ac}X`V7b^edtht-JvBt{o1Er3q|CDwW0p zy;_&GGVHy78)5QZVri$Kb%vkcK^a&Y9(Zda$!xcq^@G^t2+7oTco3E4&C&spxg&AI z7u(@)?;gY?R>RRvmEDdvGUg6ReyKoVSo$IG;ET^!KmwFB zKdn&>%Z$4zxAf%sVm|xMDJp?+>4jf#qKf(|zkNjT2xJf1T9mo;uK7gf)eTe~7r(#XJjjU7rqpUQ|mQO4~v(q=IeZNf=03o6RYZhjX zLUq|@>10-8>h3hG7P~RUl<0EBa8cc#T(Cn4oWl!i(j)+MQQf|CIxM8facuuTd3X@E z)<`o06M4lwk;4+N1zXi-YRO;N`zyrA;Mmu2uzKd)mxy3u2W?2$?}naT@tLjJ=K;Kn6s*@# z>Vlj}=VIhzggz4xfLR{%kVMfaK)j>$Q{*`$aD1$ao_^9GlC~L4bynT6Q%$o=Pg6a& zE|H5DOEPVA`40}fvV^%8ook5xNY`5WYjkj32>XY{YGRflW9EEDDeC{crE|5qr|_Wi(UFmUN;SN&|p$%=U&)1-Od@#%-WY%dQ+=H zG|yORfWCzVNv!i4{Jt+}#&`>`<#xJ4$DPm8r7-y&MWu(heA07?W3!T&#lKwO^s^X8 zq|q2;bob6QgfG9A2+~!e*wNVAs)qHDP^%-vVHZp*$B)VuKjTQkkV%@fan;fWuD4&J zq*3gh%{H6acjkm0F9BVFHM7OQQ-XhuF+e0gXCUrvX?NmBjALKTzDZ*m^Z}4=MWJ69 z!?|&x`+6eysS_WuuR%dVMk;y3T$VZuzVkIp(d&NxdY5^EO(!n#$qoM-FNE=oW1zTjSy&j7@3?&&LL8yZU#tBn}0*S)med zzN3HlXZ@MfuDxEa7`U0RWek2PmMujlm1%6`QWJgkgw9hj(rs;Ju6rWdU{17|8e=VS z(p*b#Y-GvI=jimmyk!I9Go*C!6-SL?X~Fvu-F8HuD_oyfx{i(I8e*IIo)+QSM87xB zX_mRF=;E%;NLG6Uw_Si z*?+2!;~&a@8eiju|0CZwX7^7VfG^`la{KP${9^^8HQ&$8)WC5ur$(yzBXqcvB#As~ zByU$9V<4ms0R!U~@zH}YyON~IZ z1jSc-#4obYZdX+2BwA8z+pV5}vi7O;N5_f0{>u=M$#r?v*G%ft6x)#yN-D4Cn?JNGrIq@i%4%xDRc-GtI05!2g6 z<-=%%sE0MXP__0@lmo^YRzQkZ?5_w!+=82zT_HJAt*f(rU15&8m3^ z@x=89x0yN3sp>dKI{a!o6h)}RX>h(VKliVkLDbkIHNcCQLD)qj_dkxZN%2I;qMd5F$f9@Jzk z4tv3G6XBHfLb5HL0b2ZUz)|YJSBLn2Slux2!HnTO>_vFR1P;8!*I&rrKq>K>ze7R^ zf5(}R`VHykhwna}zJDvHxv#EmJ7o;&>!E!`^^OIz<|Wb_LrV3yOW^r>^iKCdP>Z>sGN1 zS!De_`v7uFEC7WJfy%H4Aj-uZa}e3_w)@=mlt^0uan0cwsbMNQQoJG55P7q}e1FOqvZzyxNUWe}wPw5llYq^= zRePBk5tX={T00|FWbExCV0;Ti!wxi5V_RIPTNvrS${gJUQ25_ zD=-)#Y}xVvQdDv_l6)0c5BkMgg~d?~Mn%c7IYlF!ExJi!llUJi2VwSv-zR#K>Il(} zuF?W+yln|iu!ZWwmY+zGm6cy)rY&uB)`gomfCC`z5`Kl3ICcDsFEIpwY3H2|Y@4WZ z_JHIGL7v_86KL2QWq6%aAzhdF1^WnVtn~99T3;^nL(8)Ta7jZK<|&*z=$uAw{E$L` zF(*QkhL`u4d9-DT)qi7LG$tSsTavPN?-u=vNdx~_+yO;=9LbFKcQ>D5d0PX}FucX` zB()--nk1`l`zbt9;vYJfy#3|w>tuQ~eeuiN9^us!L9rurvO~zLM(i?Ktf6}eNyX8w z#B*GO&4@cV8_+^Jf&n*$8rD-TB@gI*o*W|Y_u?gu&#TWS?*gB8OqcBlFqwk|VsKhV z2-4-%o=Mztx&2NvYTh*tW6zT^)}Z+X(g5ofyK%V|#u0{`!jhE_LCs zP(M6CG`_=i&BaJ@2FKC0hQ;1>1sAFwfIi46X;$xGZ8%pU^&biB&67K4?-6MQ=Jo;& zKg7xr58&`pTjYj7In->~qa?&RKpv{Jq%bjxl#Xau9!@{Z;_2tH{h8sY6OkCSVy{A< z_i*kRZfhZawiY5oG_%0FkzB-z&77`Hsrqb4-BG#37w%2r$s#>1w}EzEBIpUdsJnE! zv42yQium;BJ{;*7BU3f@2@p!S(* zA%`GanRM{2zZv%epCnAtAjzPTGp`s*8yXb0l8Wzm!gS0@B$BD+;5CtGODv;BE;EN~5BAn5ddN>7Z1@8Q4D#=!5pA29E)I zaCjVi%T&PZ0lBEVy+N2CP?F2;ps=%G74x5>ASMm=4WilIXbkuds8WYEl7Q-X`FKS9 zpbDd#rKdX-`=OmZPUqv})58yov)TA?adiG+WDM=66F8y*R`_wV{x;FHT&!WAUVy&4 zRiqBdtqTFHoiyU;bM&tnJ;TORrZ+WX?In(2J03kO7xTrpwj7I52f%=+cYSJT7t-QlqID;Xu zQ6@_bd(tSJbfB=ejA8;v_nDIZT{NE^?L>i;uPyJKqD%CDD`UBLu-r;;g*ChC1A8#mqN^}jIUfm$%nx56<2H-g>ge(J<%6mLtfU0!y=!{vpiR?5T>K-dYZzhj z;CV=A2I;jFD1H@@O1fvJVeu;tx81Y@j(&;SD-IJZ?1PDTgpWeTj|}DXbc5V@C#T9qW`4%#TGDz$=bh zPvx)JGwfq9o#Ei71VNX$;k|uInXFAcTvPuC7wmuyo#a!x7Bb7P_2WC?l!$ANQH~Ah zG=mOXW{^Oc08Xa2kLxKM?AyDAO16lg?C8Ve9ep)940{N60q(j-BaD5pV?t97J9e8N zEi&?Tqw1V*m!XDshh0#gsat)Xl%8yvGx&;Ufzjv&T~g+s1hf*Iq`Z?f1w}$JbAKW? zXG*NYL3ttrRY-mT<0~KX7^66#BPU%br^|(=A<2$`m<|spv zm7#m+z&=FCESaLKP+w>ts6z_vhsVvx`^@|?YIEo&V|OR3It-wm(Kj*5;dLo&CG#aS zTd8={1u;PKm96BCZ1HimxDR71$0Kq5o_$)(f7gJuOpsDJ&}Z;=BksZW2q(wNGHem# zvPS_zVllV|^17wHxSejv5@~DWkQg?$2M*cyNRgTM8kFE749T`gYp?K$A_~JW=~46m z215GCjQfEhVae&ko{7MA#43U@Qt@C!bab-5e*pyNE@Gu(+op^hvufkbQFXw8gy?U@ zE3eVhe-cLBV`111Zz6gP+`&;+S>ZUP#R8BL$8az|V%jkB!PlD^YTqzGM9>0pZD|36B>s?4rE3B?~=9OJ18{e?QK?Z{B zRWcA)PUqRfqBe8~aw{@t5Jt86F+OBjLg+B^96gB88}5F-Ts$HyF4E0`ZrpIQf3U{1 zm|(n=tx9Ym*xaCBLMRB(*MLxvRmWlIla_zY&0dy&C`ZY*{YVCYRS!H0J>{ zgkmCzv%rioah~?0F6p=L^ryW(#Az`8+lMixD#NB zh}yXPvxJOg4Vscb!C4{{YNV8a{lwi8D8<(_yF$gQ)(t9J?oMAHfCPs+yX|aw7ivY& z2Ob{y+NyU8!}-zBFP9bAKk&Q8ZV$lE3jvB(*O(B=}+1}g9y-N=|Q zaDMYJJ)g~Pj}K-?qYp>34@buzOv4YChM9H{xd*Ch2^^P%kZ2)k2;*#I-DEk7#DkyS zt#3$}IxGP)=Q?(*MMTRmoqEj;v&@U)T1tEAUA)FW{U5oGJ*mf&gYl4OFIsp#Bxc6E zE6pT2R&+TSSA!50Y=+;&Se_T|-pm%&-Akr8Moq908^jwxnWM1jmKshR%fPd+ux9F7 z5T;qm6}KhJWeclnxeVsGw!xEKD5Ju9%@I~%(W4VJCQ`7|?ijbKK;DMKM|KP6z^b3n z6`;VWbz2UOGJEJMQ(8OwTM_rLQ&ep77^&r7;(M2$FK_r1KOc}Vg{`~nQ5WgA)mgYj zJF?o(PCov@Ql$bmG8)!N7TIL=?l=|4Fv9L(+uxXXTv>(mc8k`+^~AQZUPfiXxyS-y z+5!fItVOTi_Dhv&8^&594l-kPBNV3@-eMd;eVhvhVOSyccK| zhFbTOjfX-d{HHmBnoFCs_TEt-*u*T0LC#EUh6juG@a>noyV=d%La5w4i0*EXg)Au3 zi$+K9|37(e+TF&HWDUO+A0w~-~t4O!cvR$l% z=8MDm$@R&>^7?48IJr7>hk2Gskotme8W3hMP_WLQ9jnXOG|{EMklO9&jCy)Mf7mWD zl}LjAk)A6?#G~g{TD!)+SI&uEH3`=Pd9@^4U-Mr(msh}U0i;#P0`6XgOhI)va3i=+ zgPq`pK=sLkam{i&SjeNgYmwEt1P$E)TE-8aCH~fT;&1&(|J3##@=j|Jjc36NSx@}Y zxprMv-n5yuveN=!NJ-?+J6i;`sX+Fk^Ra0r$`RqWYCEU%f*py6j30F!A5W!6>R0wU z*k4z_7%%ESs?Oh9@nA+SMu zm>H1U8R`%meYo9NW}99Rjk#oNr0hUtQjSkRr?t(5H`{rE;DRqE3zom9)gxTlbU~Pr zDj4P(`_CF=xjh<_naP*W>jg`22crL@(nuDuY4~Ng!>9nIXZ5^0gKwV2YXKu6&6dY1 zdK7N;NpP!iZBrLfQ3TFDeewNnzFsYAAs~RkQ7s)<+L@q2R$Os3B%&UOV65=hb! zUH^KHp^IXeVjGW&f?|B{Yymll z!XwnKCSu65Mdl3~WG^TFRIe3odc=~C=iqW}|E)Sp*S)mEw827haZ@bH!h*C8IPTYi zfSntMN2%!?q>|{I6g!|xBpaORwsys3SWD9G{{1+uJlIJKdlM@Nyim3&jqr(<3VCN+q1pTU; zOYfFhf*~F-DPO03e~Ah7YarMna1|D04&_HlzsM4Mm;s2LeY#shczTxVq+DlraCMv! zZzgrE8=}!g&Ufg@Al|a5gRaQPB^+Bx#u!G<5@G_oj>LBEl+EDeV~)gvof~9O&?T>+ z;{n0S+5*tfZ?-(gMUiF~zyG4u^c<^!uQp&?6eC+;-WhZikqmp2BFXJ3M~qV zDlt(f0>ldf_V{vjH-Gp(yEcsZ&CO+2mb;sD46tImD}obu>Ibq!(@GC27t*`$ zPIT{C&bJrRsSI@=hPLm@{-e=q`+R=4xmzuO2I{69JZsKJ{e~r;UWr>@*zXo`Q{?VQ zt%m(?AkHGx;(f}s)@0wgQH|IFZW|V_{>BUcQ@p8x1wFt%>U_XKaGk^cbd;>rpcCyV zuHlI)a&NDN-^jK+kh|&-wk%hJ3x$SB74~75J67M0o~vxpsN~a*V~V649SO=OR`g4l zSQDiX3!~Y`r~6y@!yGUEdVMfKfomHTESWdZ1C8|d0)lEPHi>ouNoq*+U5`s&!v+}l zgf~HP_KuMoz7!p-=Dl?pFrAzcFQNC-b)l{ZatOw%Umks_#TWLjP$>f&J_RL0*y7(d z1jVDz(L5to_U|m6e#NC_HIJBNDIVNR5@dvD+!evrC&3>8Dau z*@`O`Orll{33r&0-znT+=>FS)Ue;zmrs6_HFq?!?!4;eX`#t_{we`mSP` z0b^lXcEI^F4kpJWqSiFgP#7HR?10@d`8?}(-rPRnk-#Q#xB4ti?11EcNz${?IRi&1 z?uAo>l%`|@b8}Vn{)=8_#8E$;7 zQHf`hC=lp;bdd4}NCO|Dh&c#3&|2Q~f2^)uhPIjN9ev4wDx}gODniAL7drA9WLK@n z9v+k_fv$Y}rHJIwfx0?XeqCtW=hyi(WyiZ#0FJ2Qq3!SN9wFQZm0e;vcVx!jLWDdIv}c5g&zGO0SCCC&S-vh^Apc0QW|D*woUwI##WlB8(o!n#sn9oRkqyj6sIVjhIx zh$Ccz-GrOd5hCjW6GI{_aj|%Ndvql$?66W`t$onlsv;cMxHdt;*Qs z1Pt2c0*MsTl~~S6UuLu;F{-1b9DcCBo3%9jjqTzgxm?gZwh6$U@WF-&M%xK57;Q^R zyG^YzITF{XVuXP{>bx1)ft^8gwU0xWX;EXG=cFI_q}8I#Na0a5bPFms^H$o1Xs2Xn z0yDM?ouZ9Mw8aQ+71xNA&Sk0Gff(Kn%@yLK2rA(3o6R3M3;u!9X*~6H*a%)(fUsLH zo1_;r;gxwlA+JwS2J5aZ%TRLyM|*iaf4Y5~p{V>5O48^@$#**Y+AzA+mDjHt+jz5w zMC4XC8bP?h0a+JF=T1`yXNblS4&uNNX_m~{K5VXtRmL;D0Ey4U`c{}5wz6HZ3!Caa zK5E!eAAaHdr;E_@GLK_t$jVc!qk#C#F$)RaQyRCsGK;u2#*lnQ_l?{_V6#Cb7zJ}nP#BgR8z@nDgQY^_Ox@%0{(ffxDdVg#~ zV!xjb$bFEWWm|B&dx+sV0qUhYgtyvJK2rjV9npsn(2Jp4S1K!ZX&B=T-u~2+G z11pSgp#AYE)(Zag{Sj5J>l=w>=o5&I7j{VYr?_cYSxG#aStr|Sv9$tb8;-H(u*|R2 zzpkW5Sq&yVNmfFnS81sq+w-#|_RVs=c@V&kEg%~=7558*+1m;;N@?vgR?%<8VPi-H zC@xHfpwg9nAk8|LEDs4*A{y!gOE2u|T^~@3s%B|F`y<#!OtY3dNl}q3=$k_tyDXn> z!-t==@r*rYPn_$6FTddg;+rSL)@e$K<)+IJsNm=lFv$0q@_H)}K#r4ItH$x`ghjWY z&jLd#;m7{KI8-SXX35d?^$JPk#qDXB&jReCHnoSv{F9gpRCf^uC{s$KnkvH8*6Iw= z!N6^zszkS2_cNGJhnQcsw;!iO>wl}{bMLh1xesUK%n&LNV3Wc^7TSx$u`&;+#{J;Z z!8*YF3CeoF7}+B2g^nQx_B1m3?qS|JBNbq{cMjk)l&!J3Q9mRzn+R%zSh zYaR&)go4;4`xrTcP^jfZ^_}H)0S|VgvZ?mu?v*cRwAIpbL zLo4Pg5%Q~-Uh}QX!x9iFDo;eVP?wZUm-`p~XlUZ_<4yr;E#LQ__IyPS!;(}iBZDZ- zeS&=0V*ZaI+=tXeQel9Z>9Tiv(iPI{?apHQC1 z?%3}TMQUeX=u9(N^wOCDXeza@86Xd#tE+c5#9eCLcoHy-#8}_1lE^`liOBsLN4<>g zt0_!xs-YGe@?qcucrtO)x34r300(Yu);quqoIRk$K{RW8#`OernzW1JS_@B#`PYpV zvVf9XvcD96*ika8cC>r+W9easnj!2^>O>~`7O1Q^tJC^b6=qJiNR{ZINp`VmcWQ)) znZ)h&4|mB49SmKlYb!b!aoWWEda<~=x;#0%x*T1N;=7 za(^G)m?SAPzhzPd?_4<4VhCe#IRSggI#Y-yjY4KvI#dc&Mh9<~+sEbATY|3=&NmgS z;Bq}f%=Ta{ws3)=`MA=;L}{?Nd>EafQ`O>+>?1_6=mKTY5DRkAe$^3P&dfe%d|GT- z=l4{724lZnQES1&r1hqSd_#Jfx2*!0;BeTg>v7}~+uFq9Tyboz^;YiKhP#pRx(SQa z1%*i)UG_)Ix{fhet8f^!*9fp}8i?{ErWbfHTv0 z%_G^x87PPoQus4e=v}+W(mmTP@(rO?T&6JmP9b=TmR>%$7o_><7+#*W4ZcFTM;+3~ zdF=qqc~MW>Zp}Xh${OVeEW`t?%FTy0EXo-$QHyHmL19dqkOtb>lw zcL5-&f)D2{>p}Br;Z0p@g`r{p%N8J^ei;i6s(-|q2Mw9mHJdn;EHA2O>(VZS(AD%a z!I^_hn^q#5)b^K9G_lsURljslQEAg5jw#i0uUBjCBpx+_PKQW$$UiR#i$BeU%fw`H zd_1O*ruAX^jvntnt-|H!vmA{mMyuiHZ*T3vV1*kwrgw9CVSEZ1HBXY{yQ z69zitnJ@-Ao~TyUbxlgzCBJ5Iy>;=D8pGjH&WoWHtB74-V}e0-{T6cK;&g zyPG5(Vo=YHx?3BBBu5=fejl1nuyx9&k^aDbX4ad(sQ=lp&tW^@~E9}6*AbB$r=P0jgfe}WEK<5o$bja#s($lxlfb>fjYBu!St>MH+lBO zv?zRmEqL||9e1gcC^cEaNN(X1lC zTHR1*xxIo5+v3qY`2rCj$q}zH=aEFAyFFRG6p@IHUQ9O)~;qx^dRaq}C-Np7_lG442EMvNVN|BDn0#ClYbf4Eo8`iRUBZw7!n z11Cp)fs?YX;sxp|p2x<|MO{U!f*mah)CL(;SyAZ;%4ks_jo7+TLz$ka)ImjQDFry3 z=8CIG0!(-QL{aOw9UA(0++ft7Mu3ys$$+vWidagApFx250fpFpff+Y%3@{o%p>X(k zc7y*y-h{7WWSG=O@>}llliy7)aUWPVLkj8I35^iCi1JM(Ui{N!T{(h>g zqUy*OxMVf(8iKppH5_`%4y1_2zL-r}I#cGi3pVT^{XB82>;z6wmW#jRi^y*U2l@l_ zbv)AlSs&K*Y5aP;Q1iQZ)Bnh~WF;1BY%yKLI2G75cVBjld>}=jpc@d*iNJs`!$Zfo zdTe`4N3oZAGatq9wQ9%zydnzUDqgz?$G}W#H<8QGrt5_QPR=vpVlF_|xjRL^e7b|J zvV1`KNAE0+t{VGfVyfnMW_nX<`V#0|p)!CeLCnO6p+TY^C*fgt`q+}(t%8|Y0YT56 z9bYn2L{HUQ7V$Y{95n+`d9x=-1;{(k{sNr-A?-BE~UO_|X9Xjh+W*+}y zIr~iDL9{qNXv{TgWma6Ufl>2JoQ^tMhv7PP=rR+obP|G%nlh(&Z#<4Z!iV|wQvCQ| zA6K_-BiHX=e!7Pyc_>FU)zMnV*+rmR+ba+&951V@} zCu>+ZJgo57>&d!k#gRAmgLl>}t&Y9cN%rQQ(*AGNi%%l!F%Wn+>;KUMV$ucsxIE$SC;_Y}RMy;nh)|VMd%1BCp^4n+- zN5yD0NwBh$YecWMjkNvwYp96bEIGy-9YMGR(^pWU(wfzUNpJ8BEfbmq7N03Fcv)Zo z3NciNbdJ&nw*;M2@q4(s&h#oW`Mhh z*WLrn5U9-rc7ynekE%a$3zbxq9jJt&H!Cc<37e|Iy~M_GbmiXZw7bqns$wn@b8Cg? zP_Bbmyc8jDNgKDVMCYT^KIeQMbG3zQ9ll`3K+WX!-IUrAysb>$48I~g7JR+VFj#9H z88SwB8u{uK+ow%l;eQChM40lc7xy2r5EmbQnoaqdrBToqtZTw7r&*{+|9yMU=HU3~ z7aYdFBv?aTU~Ol0;W9&yP!e&RF3Qt@f*zm^{)8 zvB{7$;Ym%!h}(qS?-1xmS27ZS&s)~&sAd;4(N=FjbPe{u$`zmeEvgEAYBpe_-% zK&pxGSaxSaxY+Fl_c8wH`|@Y+#_Jcl&VoK0Yi3uGa)v(x42;rSR705OATetsG$uEx`i_XX53Qjiwl3=@gBzpWlWvs^w# z12ya$+ue!Me`y_!UkbfC#yvw};#&AmE6xLJ>FuwtU!w%?*Eh2d z&;LGo^GqI7m!m|C1zcAXDuz|&Eg|7T4@`@ucq-`slTcYZn{R^+K-W834O21F@kUG) zg>ovKtljIinpwrC)O3^Pvje#_n;@7uMqe*~lI{)&g8oj=WF=zeI!H~a`HduS1YCj; z4+uPN_nXz77N0J@eABnZm!93vR}UQ5B`s+uXkfzE9ra!a%p5i>Ts%E?7lxRcbqEI2 z!XjJk85>CvspQF!FUa+o>&(J9?7aCGuI9o2?Atz}@g4 zeAxFGh%Q(XE8%`{d~jkjL2%W~uoR0J_ac@mP6R~-_%ChXAkw_m;j@hRP6~+%U|qzq zJb71_aU7vC+x^Bh@n-aLv7Y{l9SN0`?=2OTJ2S6U{D_vq6-)OFR=bh!FT>iEbEOel z7l&YmSQ6*`On=9^83luU#d}ac6;d%(5LNm<;MeTNiuEvS=txC$mo?;ck9ogk=qcNI zQ)d>BB_+!=gK}fd6ZbPgU=b!HWZ;|({v>2P8nFq+i{%x11R`rH6kl}D7VE7->yTyp;;u&h!v{lQ|zI|vwr|$Q^o+6Gu)%5Zdb6NLnS$70*!=b>!{ow-LIC5<=53V;QOU=0?8t4R(Bz` z%7>p38NlO~`Uhu7UERt!AbNPve$p;?%2lT8IV?lSyFb#B_cR)fThVqk7-x%b^VuhM z@tw^tG2;8b|NHsxzd!qFIvf4%Fo^#AWWw(?Od6~ctE-HJ4jDuwyE{n-oQq6l1kr-V z(0#_b&KR9#DxlEKIFE#vEOkO0_)GUG5yw2cR2PWY9UYjjc(d}H zIw;<3kiqt$8Lp%#21Y?-{l?L50GVYYK_vo~aa}q`MmOHlQjl& z2Pz4h-pae+Ua_dn4R(~#wLPu@$d&lzbWs>1KnYVE~m4r#GF@$V%x;0B|Hbx<)FtxIstftZh<+!xjdxrV-^e+oU~FF9*D*8i*q099epqDb zFieu_&|aXj(Mc@24ebnKe&m2t;FL|%06k@|BGE;oX)p2v;YHe$*Dbzl!*)vxLNYoq zABXt(f0ZLds9Vz!;sOt3$01hKZe4)IRCSQAaD%nY8wUvojjf(~Q96?vwm55}gP&lA z#Nn!~&0*Oa&I8~)c>k9LMuRS0$eV;PO!v-!ir{5z@?rkH~c zdP_z>$=7#!ueYo(KMdLFe`Mipz41vjF`T@*b4|lKoX^gV|}QgT^Z1*Z@A_G(z?mBcF%D%!ny7&6}-*g`^vyvm!Yh<5D&2 zR7+d>XT58vD=uq|%`mp|Isnd%?@}$^%sLCH2RnjE~KU3KQ(lsrBb?f z1-B+rrAssF_hO`+y-tqChX=<;rze+}N2f<8*YWBJ+|^a4SthaVX?vObQ+9)cEV#NF~?#=}+^0jZ` zw7B*oEd2%Z8@Bibf}Vsw>{Q47kS|?L(92Os2nFBd6tgjYy4_q-VO#d#%iE7}*vo&- zT!`rbA@cclSp=C--l}KcQAC;N8c&g(qWKuDN!;7$+0*0Z1unu42XFyovz_oVP(_;A zw{LS|iZSRugN-uIF9PmHe9!#^oEVflB$RH-a0x{bKmNG6f4%&&yv>{5kB=;I^m_B@ z6Cfupe`G-%smJ*RGq5Q9@vLtCH&`IW`f-_12z)tNknj_u!adO~2^3SRI{(0xBeuir zGpj?bK<-69#D%v)U~*yVHF-Zh0d<0K{SXJxF5wLztWF4r@l>RY$|@enmn<6SA1m*v z8&gb{q{g70e|BtnLY`)z~K24|4cBmwR0b-HahW>a>6pO=BQBrf< zG}^G_9hoSSO2sG{%aO_~7n-vOo>_Ut7NHz_l zZ$%3^wE4wN&}vOAIa@b9BDM^+kp5UavVDtSUZ&f86l=|yO&OGEIntLS>fOYp zd~8hYBw1=eF@o#1oUdO3MzY<4)--m=$GN(F|3xFzqw#z8K_E)u?egp7L)^e3(bl25 zjSLK}CRXtUh$2SRYPHt%8mQJZ?iKCU!fC*Xw3_YN(U4(E;@X~~M?XtTzDih=qfV#S zZ#R$f7bY+`&9SG|o}fBD{pbvLocbN0Ie{H^Heap8mtgPX4LX(n!)<{hE6>i+$x<04 zw#^jR*hF>UrM;sJd7I6e4?xsOqo_$GwBJkYPU4c}9gidqD&BOtR^tyZg7=_EjRy2k zBs`3|JAkiqEgw0eOA~@1I3?oCw5B+GV`D7wTiPkB^>TgrbUj7A1E0*(qfn_etct|M zqjp;lRcU%$m#3T5x@sWp9D(@8{9N^-CguVnZ+Dv`Qg}HC-?aD;VLma`-6|# zez3q6K5StD3I^#W6PBn38EY{GTZuD`hqM-gylov8_zX$8MaUSD9~u^Rs8|J3Va)0! z8v3s1=vaZ{y@@VnJ1l-JErB)*mV7;;?WZuJEwup8Lf>QS3aNFvSlxG!@IkbtptNl< z3GH17?hf04+)`Ega#R+WUfyXjG^5M2+12uKzPhdbdDjrt0!F)W4HQYZUggyPnImGc zL~hLYpd!4(e$S7qT?0oF^A$T2HcU!~e0K#G(s2{khO2|gYlQtyfM6G!6T4S7&}JvS zs@OV164*d4GjK;E4qRQ|V~*Ymb}YXAKbw{IXi>`~`}XMg?Yr5F>4)bR(>K$%&)$AC z=j9ZFNhXmYP!?pn>@*Ce(2O}122vg$YX|9@$=NiF;kZh<%36p9$cE9V7f#VDJj@!% z9nth|riwHVRMn}A7zjpgvga&M92yjjY4=J_;Mv2cC)#$~XQ-^+z?L-xKweIr;Xe%s zNmQFgIWu^DiXpTu3KY^!F_%>#-_r@3qg=$aGyw5TRCWpvY2M)!9d zR+P~xVy`13i;G{Zan}G5AYSGAkCqAZJi(r{n1-l83)<+de_;3c={kH zO%;q2;hDtr#&Rxs)l72$EJ@$LgXt5_+Sz5mWUAOtxC^A7%H{&3@MMr(PMrN_?i8e8 zs(BE1$`6Xkn+6Pvo{VX{lj$mlojtF3qakPT(+tRHu1u^NabT<3%u&>z$O)j#=MWR$ zBe7>)FoLAWdcC!xn=Byf6Q?kQ(;?{_me(Pk(wo8~<(mw`1;+ zt>j3Y4&Bf30r*p#NB#TV^)3R^q7r~?D%tTU%5o6CBHHLXo$yjf!1-;y4xZNYSc zBAhD`Ofzum92!y&LxR)MfEbdDfGs()fv!d$wR`Azp?ZvtQfJaz-5Uq%5J;wHQe}%~ zP(B=K#>W}nvn0T*JT3PxOg%eWGZK+iwL4?SXI^)S<$w1uZk3$P0}zYJ$u&ByVMw)R za1fNPmNYIwv9^-b^zyl3I)iAlCXZ%M2$x1H#E4b}rp;K-GX+gXCUL5r&X~*b69K(0g6?q?!rB1DgLH z4JoEfQM8j3nX$!AwpYuamk3_YQE*FSFxt-);IYy83N4<0L!+tK6_;Wr;V0Zh>p&T9 zqs^ZMgu^WR1_~xG(mDyS@b?gjLUJ-a`%Khnw9&Hmo(I<(Mv$al`GS@!;W>={Ss9$O zW-rugD_T}WRoxpCWpb?+TdEX?#YYvH5uYNrG*9MRQQc8+?^ZHWeFXc#X&5RJ|EIpL ze-}|3{WJcqkB{%*h5wPSfC$>UDi;x0zhuo=(+nFd;f%I8XK{OrGWb_duWD5>0Jpn^j8d&!Kk0*)evzxK%AIxBq+uj z@BxIEN|gz$3Rn@n^(MQyB;!JJ0l3l}JO@!Q|f z=;v>!A^!Glc8|ub8_bS@l|TD(z}MXE>vUKrhWD{ffq(-bm*FiZMlR6u3&Biwx|UkL(5f0ZcD##I<9#3DFozEf3BPaYHD4^ZPq&ZI zYpb-A-qY>@1@E*joemWYk6R?%StBSyIbz{>h#!(?f? zWw?_F)Io!{CJX~26otz$_0eHodcv016f9M+$f6pNtUGcxxRu!Uz-Ca0n5;Gxk7q42 z@ggh>;~?;EI`lgfd)$5)4Fg$eN!Sk;5k)ek(jz)V3r$J zPyK2~{UynP2r^=4Mybdy(Ud|7FY0bL3kh?8sdrbTMq&oP+1k1sHGHbWhF^#Ma{2p4 z-a}8-0ZY11;kM}h=CXqJqOl}WnI_AQk}OkO7U(){G5sUf20U_axfD64gs@|C(gZ7g z)&-n@){UH(kKRA5*6f!kkih#5vMKDTgVUYP{%+4PdwiI$9=Cx1XisMKlHI&i+U6FD zU3k9=?`zl$9zl&3g(`@#F_KnNE-C5&|9Sx(GsA{otVEaKh44QBsviJgMFZgP6Wp-d z8wM-TDmh9`oVs#Rq(aL!bC|ml#ybUi%rRAFf}hQ|MZR}{tz=?vFWHv7i%L8~GN(_S zI81MLeMJryu~&5JH73l4RGnO{wwteaAz3xFt#TbM5t9s?l(-GepV1n4O&B6JZeGwqkg4HSa+7+Ugvlkt2SQv+Y zbxaFtMNU@D)7c3fa)wxp4d7JiZQO3a$hp9WD|rt1k@bW#KUqnxsvw9@rhm8#!6563 z`Gw%$^6KU4c6owKEjmZ!+Do!WFCR8*i<@cLWa$CQn6)Z7TqU2o8@NCzaOJbil>}h} zRd+T)7hUCBY!om|4pSZ)oQ_`n1Qx#=e1I=h+*lPYGEL9k^)yO=MSy~zLtM8 zEN}7V4p67$uHh#tl4o_jT0X3AC!c9-csF|I2qWiGs4WX?l#f^2vv8R*d)5<=nJ-Le zRlY07vfv+{I@&0mv3x?P2xqulG1MuFS+Of!C0$8{%mUT$3|Zy&Q;5I8CDS07xkXz}2Y11k2WeN-p1dAGQE`Q2LAU;<_= z+c7Ej>_KN&N@vOKyITeq&9q2pTvNyv(mxg?0~BHgbI5ys23|aQwk6bZdYkHw+S8DN z`T5KWg|WltWGB%EKKru=P5GK`?2Fz8$;+uJEOMti=njkf*w$u+5`qSI@AMLMTiJVI zh&w;s8XmR0dqzPJ3vnw-wTKX$2v)p^3yjmGU6+(jz2Y~7z{H+WaJfS3ksy(vjAC>N z+7dX9`R(j+Gey*iI2+4}YYZ6c3c>aceGJW$uUKG==xnh^MvgdEQ%pi(2B671&2`be zq_hEczejtJpb+Up9-40&BAS7U873;`w_>S!Oyx6!xubHjVJioby_J@D%1vfmv*KNP z6g(!akU!EnxNij@%;waNA-ZeBCv6vRqeWk zxO_gzYqN%% zaZ<;}le2~4Q$=d?u;jg;-eWGp5&~GTwR(V3UKIk_)%3-4pwEF4fWeaRJEVydckdZ{ zm%tbUMt4jXoBFYg@?aFT4A7saFS z;b0hEA%PJc?Z)$oWPRC>71yVnAW2`gkfd*7l`90nZgrTdtxfU$;A8&&3CK$5U;F|teUg%9aWYx4~mOU4c-wqra6WGl4wa`kO_ zC8#`390Rn;Y87&8fXDV@0QgO(e0eWTp&23 zfhvG(VEzOB!S~tQ)bOHBLRHG|zt0Z;c4S+HL>HPR5u*Z0^kB~;;waxM5jT+(B_^~M zX=i70o8IS7b(wiE6Y-I4I7zu29jbKa!X-s&rgCfZd~LMsJGx-RBAqfB#fn}Pq3yI( zo@D~Wn!`ndFmkfB3w0J}v)A6-cg&;;B_UlU1O0+Ebbv=sFQqV+Lrb zW|o18{#303LY#9fNuWgwNwCPyd(RXP4!V&7uB2VgokbVg<41I!OamBtTt#z_sPsEs zMG%KCBp8oDOg6!obYgi>tr_r|h&lF<0@V*o)u8WI#i8iE9)ZA>wsAaNgniYY_v3{; zr+J%7M4(6{riDZ5lOxRVta-VClZyN-1Npibdy<8voP!|b9zqlfAfyE(EaZ2olZb1= z<^($~+Sw5u{6mG|Ahv(&Zde-bh90#=4x&@T7Ge|@*5L8w1DglPGVRsh85rBTfph5b zWF|)gw`GWZ+@Poug#qNsNT>%stM)FSVUgMCVHgG&+BDG4=Es)OT-=rk&jL_vh+>#P z(8TCe_zlUIFC!qNW{cZ7@&IfJ1ciIOnUqZnWopOh=;f6+Rqatw_8VZOXt#tO+p$q} zHR}WWgUP^h%wmqd5`lo@7?JMA-oT|O7t{K2O1a+>GsTPLEPv!9a^_yPSFjQfuv#cS z|4G1PH{AF|jOsfYOrsh7pZm2V1ePaCrpfurl>2wg#V6| zu6gLVhI+Y*n?1orlq!+62zc4bagv14QKoPEyND8mxJTdUj*KcuS9UYN>>IQbo zM{QsyPPZG_X`TsDIjx1Z@c$32wvisiQH1o>xiPRD3@WQUsx_nd)|gF}U=blK8eH7CTo1QymS{eaX={$LR+ zKT0;@oGFAi^Y538{+78pWQxK(+HPMTj6eV}(?dPUBJo~@B^k-Wp3)o-F^LaT{2g@n zd7Nz`enF{ev=JIpdBL>csVp`W%}0(%^szk7Cd(ZFXaOZFzorxOrkw}a*YE;ua6jrW zxM7=PU#;5+x9r{If-1L7JnyGa+Vck1(sJVZE@_d`O#bA`1 zw`C|A?Rv5UMiXgHl3vS)XAjG}IrKloEu4rfprUqF{6f)#x`E7273bB;Gi6_|4c_d= z>DHZNS~5XyGTvib!{^|)(MZs5=<3CsB8!QR103%DUiCP3)STSdXC2FPqA{XG(L64U zZLA(x@Et8s6Z|EOE0a0*wM~4TR*wBOe>v-Dd&d-Lm@5_5DCjRj$;-N6z>_l^P%*Mh=z z)TPMWV;@_AYw_lK?bw=nlfdxOLSOseDr^d&;t%kz`z4bcFyOzJ{8VI=B< zc$!TX0y9t+*68+uR0-qga3@vn04O6MqtbjBOu1R0`}&4LS7tAeF|+2w2qA{O>+L#> zIl8IoFirwA-@j}Q9xm6+3)VtrCsr>{B%YwaQc5k6Mm($1h^;|zpaw^vSX9zSuAQUF z6qdEC8nLPo^h0Pw8O5SOr;T=)_LcI9n7>X#KPaA(IfOZzT;ZV(WCXV$JIv;qZ2ST&`~5;$2KJc8c*7& z)=nnMSmXEvOD!LY`FKTC-|o=}94!{f zaxOrLzZ?LD6>w()|B~88$<pf$g9;dlM*m3kru4>MJt{Fn4D$83stmb-h)hk^76JjI_O|qGB{>Q+w)| zlWMByPNUjWx_>>8e2i+a0^ZFi5>-KcsIL%YZ2`YYy2j^fDNBnA9WG66f;8ivor*q@ zzJFxAmZuK3!haqnR%kX_LR6FjLSaX)fC|E+wM4=(wo&aJd|Jjjd_Z^I7te(RNFzO> z0`APxvtiy}m!%Ka&te`yL0bjJO;Y!b3JkB73wA`*V^FgWCSaf+x6s24HH_slAGpYB z9)BhH4$AwB8HyHbavO@Ba#j&Guu(*JP5Ia+VCrX3~cT4vRZm1DKSn1PH!eJSY!qSv@r8RIj zi*p1=WAZKZZx{8Y%in?tlCHw^3IC)s6ey(A4X@UnKo zi$=Rd@@Y4x*+-6`rdgy$Y$`bLk9DO#(1idG=SGo5z1gA_ASqQ;xl;Toy4 zK1*7;(+n1O()h$ATO|`}YYnTF{WwFcwTc$82?m=xI-SM8>GF8tE8W+Ff6SBU*X4JM z{J@|wKg!4P>p1L5h!UNpLDy57AV1MBF=iD$4{5V%YqY4q!p4+L!;!bWkj{ zNw>~666Nj3+sn3I0)(T3x2Tm^UQryvoItVF-96wDU%(rq@%?6n2A2=dF#-6oTOsTW z(fOqh+vzrgpX#3yplfz{C{;ySG8q&@7UvJzZ#20Ttat3E4Z8yMCoEK#%ApuNZ}~JL z9MP^(4xIoW*~tMlA7@Y9M|Nsk6j87oG?5}=NUm8`l*~dto=JOlUY=NLt(#*D;=w;=@W}iEM6gFL%oz=lVUcaRQP_i{ z9GoV@8w{KFa`T{IKh>co-?EiI7lVj^*&h#6M{XCP@R!INu2PA+2kWMQa>1}eT?|0a z-^|cJo#e^AY)AayY5@HN0TA0fBxM!Cu%gg#L$N%0odp!~ln3JQumEmQr@+N(pi8}6 zJD4@_Q*@0UmdwJ-g_RikDm+|Rrcx)kiS#`5bVGxsOpHenV#1@;6#o5qu#$#-)Y?TT zf;`$0`h6g#Dwenl_!Kh;GAMs$N*O9_FH6N72AYm;i7Xzlqltu&epoR7^znUtfsfo` z;C0j$xa{~u3&t@0{VrCM{q``wN7D7hK{SMmP-vG=DYI;_;vM<@AU|3TK9)XEW*Bj= zZj0$)N+{tyvx~KiLePm;9tx6ze|d$XAIU3Zd;yDD5L!Pnu8jQBi5d*8$RM&AIQZYV zU`bo!>lU6t*Gw5k&x|t!_ai}B`d{pn0Qz|?M+lR+RV?MRilhfCJra$y-+U(1ED&uU zMb$-LVvmv=z(=MRAS9V(wcGm-Gp^|U^QC$Jc%lInC7o@$`VsDEvo$mX?ZFYg&ch|e zegw>T%&qRQCyhUz&!DBb$66QLpm2m!Ldn|Hm1jhYCL3KU#FH{j5lZ_bL@#C$Y5H@J ziLIE%@y`#Nr~AO8bf4){Ohf4eW!l&S|3iojcj+X*REz(DX%0P3X#Ne+6<)-da8u>L zMJR2_-1X?t2(Ybsn-VT)!;2jsJ-bO9S6IT9f}}fme!GG^(lL=4Xvy0VI}_8rLCJMz zv?tkFQ2k(6EX_Vi)L<1_9CJLqn%-DSWp)}2K5kqiiiv!sxRw6i(1}09j@=N&k&nbU zCQSW(fQltl_R;1%4xs(4%y%OFO_&&jO#1M56a+;3 zvrXee3RXxXAi|yEKGG_|4;Uph*~7QkUSOG3bOm$K zGh#=%F^GVxpLv6lawSsM5Gb)YSxyKw5(rQ1!xkEp(k)Zs3T+wGnYRjvpc7F(oXZrS zWqIDUq14dPIFMI7WxZrnH^M(Q=$ZmdMj*#piNZB~clu&^$<#E95Q zS4RP`BLbPv;9Ytm;bnco`uOr`b(@rVX3=IwDz2O?T*SmECNcejE#eQQ$s7MT#7pF| zZU6$7xA`7Q`tdGb5h0_;zLal>eT|=Qw-Cf%)AY17zQP^t2+~??#B0Ey(|lY+FA^u}onPM1=I7@p zR^6!b$Wefj8fp0a*8M#-F4@gvIt>njgrd{&1nVkEm$P#wp{zh+e*ajR+s^I z3WL&EOYM{!!S;W)oW5;1TlpQLEwOYy>@A)tn@>C%&$mfYLz=-n@p?7TM;=}nWkA1J zUluM=!c$IB3J)ycmL}Up1Wr~UaIly9IJ@EBS?hkk@kVYovK3x7*r1!!Ly$c2d%<@u zhJ+{=1J0?c_eUH}Zj5XWD6Gz2oyr_1OC=9WSF^|yNo%I9FUs_^3}I$|n&uB;$oUZF zSJ@C|`Ab~(u;WF9q|1st-i=P#RfVWkzZdXV595Mji}MC7)s6=j#Ve6@T7zO87;=k<$|fgl%qYSqC6t0wGROBmR5lQ<~O@2yy zkoX4Wa_a7a6&O|v(rE;}|A=X3rR`mQpU!};*`TQ!|IHm?ms;sf+Gpd=^B$gKIVPID}!=0Mo5SlM6o{Eq~VLCTh88Y zrgv~lC7Y>nC%52O)wJT|^ofg2VOhopEvHt5^!?*!)`rj4PZ$D;0dPQ+{80_G$0>r| z!CGc0vNHVVLLjv{hu-S@*>kpx>X`OHrN-mM{O(s>?T?$}X{*v~7=)rcjfk^`yAWHJ zc8rBJyDGY{0Xg;(o3L{#pkztW#El3ZDNdc@G}yZL4K0Na+IGh;@4rae6LLP>_2HTg z^qX#gDFrRcuzcPce2L38q`UeB6o5yhNeS1VSbowXPcxrUL+Vo;(<@Q49RHxH1d82YnQPV7rQ;oJ;Nfkd8$!wM7vAvZ~;b zQpl4*1_n?Ll}ftof1JoBJqhuHl~#A3q){x!7CxW~bIxw^Qer_~+YxKDvMk6qyGLiwktDRZ(pju4OTY1|5mXfhS2*r8rb;)eTfUuH+1>siVIT^!?21VY^bi@K0w4r`@M6H}th*<$fFHWuKkj1q{ zC}s6=2HYinvRj1P@NJ5g=CrrS8h=TlK+17>x4?YB81x@r zTZ=6koiN9{LS5}YIJ^s_pq)9r&ptZP5$$hLMDCjr7)ca1j3hq%_r+3!W^m=L7E$AK z73Fdk0(GQV$Eu4 zorjeOGh@zNCMq`@eAw8G1_&+#$pzt-!zC;z;H?WXaj0m@=5FBqqC(Udw%rYM47zZ{ zBNUOkf#%-JPcu$ZVB7@{3>Lyf1xRr?(3xoL_CdskNV1F(X`BQK>?BuU>f-<3kvM&A zu46~frAE{@B(3;BP-D;-a1qoe@$u&-iXQxQO=c1&37etoWAix?d~iB1Z}1mPokKNo zR9bIS2qXtcVeNOzL>L4X3PI1JHv;-jGiV#Q1c`BlC+!v8StWv)Jg;sSh}Sk_6*Ud- ziYUf9hbI3-0Fh}KDxlqtqKM5-M^S@TKBU#}%-C|8DM$khR{(4=_!DBw67h%%o?qZq zOkDpOKA%sG?7sO7;Rd?YA2n6DuWqCW!z28-@BaUCW*pzcFMC8;(pKUbxTO%0QdNT; z+cD?e%tBa=$VDZG0pCpHToL{y#U;y}juM;T3)!39TsRL!uOw}8>hlSQE}tO5;XI!( zgw*;Y4!zr^d#i*f0=4B#>#Bf?Tujbm+p`i3Sv(>{P4OrsuY|r>NV4un`0Uua$q&V% zkRx&ay#I=s`lTNuQs>285{&LiY)mZpg{#)QXCsx-0er6jfF-jVCkk#0baIGqXW%E$ zq}aJ+KLgH6gr6A6AIl?{848)#XAfO)L>9h2c8M`ZfYUZ4}}Ugn;_1 zF97Y+68C+Y0EI;@Z1Mq)Mrop3h?eHOaER#vB?QZNNqYd@StI-rM_w_R^BV%3S`#Z1 zEU}zfLY@yt_t8=WLMVBDK6>-@MeS9CGTAuw1T)Fni!N>x*g__Mf`O1_W_fB6EBfK>{G z)2Z)PP<*@{M%jdYj+9l^q`Mub+lhZzy!w``Ji?V#7>!Gjf0l9VuBwp1v3dNgA5dy( zHYG8o^L9A^H;Rfm_BM)ZAap!Bd#24AU<-g1kn;WXU9?Tx#tePI@-s>e5w^o;V4K67 z0pO(Y4>?=mzyp11)Gp`n3=bAC^_&Uj8BO1L?6~N< z=KR7RgR{5l`};C&*eS~j;-S=XzvwdDafFM(L}7S{uCr5(lmKLzD0asXy)5Cap$fxx z)(eP4E$#|;i}RbjEIgp7_UlaK!3!Yz?ocYa_}*9A*9;#b2zR9YU}C(mXk%SVd@s8S z8zTX%v6>~n4SfWx!8K&&^nK zGfE|ymzM-Kav{fX-)_GHsuL)kI`ioc_6f^yX1!);$kAX+T#En!dKy?7HZSBA;s6Q- z2{-AAag1b+VHjZuGuJE+R#DvX-61m67&UKDHlD7g7wl<*;0L4ch^3skU8ER#_w~*K ztx&qVeU=V>U%3G&b^8@|eiYQ*@MTh7BLp-`lclx2s}`$A78uqo zpd4{n2)aJ5C|WjRF%wqJGOmWH)_xzEKn&XMCWg<;-N+zr954szV5%}`kJ#=C%Wpa& z8ZkJZ-Np{!Cz?9J=w`8%GkZxjpcax%QA>>zhrH6DSVnc)fH+aiYd2p=WYgfy%=^gmGsL=T)egiPaE5$dl5)!?2{ciPed|=7*K1qJ2qUJ z{fG#^1tNHK!UUDrbBccJSOGy5*pEW$>V`c z7^@4VhFlTBd6Z_>w9x|u7mu3|p=AVzf!Rc1M+=--C>qk8GMLrmh)PJ!I>OWG3Xe`?O^MgZK|`-=`XhWlaHArVjdsacN&a9xOc}U*s%hF|))su+pylP~ zCA#-r$vCSffy)Brt{_frMxlg7$hIBL3$(|Y77ydFBLQ~WO*9-5;BsIKLkS^|)|eMA z>?E5@CQ6nlA3c(vt#NHkj55FE44vBMXzczy__R1jqQA3iqzqnj8m1(SoTFS6Bhg$m z6%ewO79Y!3jgb&2fy4d;p@q_XtZ6iYOU*8F*Ym|P+-!WvKEX^H@YxXSky_3m2q()8 z&t%EtG$#L*;uP0j1#7%bpE(6)ooplqz~3?EPDetzZZzHeG8$iKwfvRz z<`dHZrcYKMhiIG4MnE7j^Hdzl3=jo$LD^i*fL{KzoYAwPpZXS9hB3l)%j-F&)9Z&< z@~M5)Xk;cIAwC%&X2zzvkK3tvo&kf_(?&F0Z0)<i995upeyIrlA3Cuxb`bsT)ImckfnDN=IFh+I|{iE+^K(45%2O&LnL&? zaR+*?j$M#7DN$;N5v6txl-iL)shxx48>j)?psJ_nSfF%F;*My@k6Z%Ex+7%{3%8gW zAPR%onjGupduDt0dS@3eoF*d5rfUwaLRec8A7Yo`IiO-2N#S)@q8A`l(!54Hu_=M~ z$2L_;+KvU%ALe@)t>Z?TXtP3bQ-KyXuDqvE0Jo1B0%@HT%Oz#v2VRU+#3_jAD=lUOJNQ*k9(iua|e99zRR`8*J-4vP~wp z@7XEqIL<*%PVQ%Bs1&)<-(R8WiowL`j>k!e!feNMMQ6wG+7f8u3I({~K*UX)YKW1v zdi#D4j@R=)mI#9_9#;1(M?=-5cE<~=EJ=*OKjdZp3gB1un_2ni<>+ia zKb|j6=Lc8kN8QiYTB&h|Als9hrx;Hfv#nJjj?Eg3bLV zehOmNKZ#RxGd{;de>YkiLjZO5fRp6dZybfA2kBbjyzW6#5Ce4vk}B??8=pH4hdAU{ zE)}y#r&#ys6=9Rv90A7F!9ATKkju(2R9m?tbW*yKZDwJ{uXa~d_(w}c0%Y!Zt?8{c zQR=$@_rZaG)ZU})NwmpmO)mooi;!69_Jb1R-AB63n{^d2a|9WoCVk|uFJ_J#?w7x* z)HYt;P%D86;i9b`f4bdV@;NmPiYNS-Fp1U)E2N|XK|n@U9ysp3NPESL9)?2NkS90+ zqh4$_k1@`uO@%aiNLGbfJibKRmWS`N>!&*@zMZy#8?Z<&BP^L4I5Q8ScCT6+XG2DC z9)4Vx&*GuHB(?o?qrObr|9~=4-w9UV!%|T24@-7=WXTbs|7k=RDVY_Ji{(~Avc+a( zea`fLk1rUoVXqEcgG-82gl~P0zLoBeH^oknc0rQGjGYm8DhKA7JTg~)96D=Z_4s8* zhir|ER@j*p<1YgZyt}?;hgqYmn&WV$oZ+M&yP9zRxAUA@I~(J1dYn5NdmVoKo9cY& zM|*um4#ujt49W&*7ybyP$nbh=-KGBr+S^i#!)wah+t&FSxA~@_zOwKg|HQO9?zdU} z*Ts4$Pm&kJR|3C_{Ca6j{h~&w*C}96>GCL+=`trVh|3a(9j(G-)VlQYpY3d9tD|w6 zb|bhPhDgzy=QFupZgG>P0F%5Bm8?CLnJcb;TQ=okj6yG|PbMBG_KFm7zdKI=Gg-Q$ z;vxoGXd=g;(+Y^o=tSz0-)PV${@=6rqUVAOLF!TXnY)ITG z+a)U04ki*ZNsmwWx62vg^=q^>pZ<<4S8Sqat^I?xV5e-clX1aRHm%^Pbg zYJcEp+r583m!dsl@#I)irYh+Q8n$2L} zGTn*AtqfUlX*(MK9IsHok1a{Kz_tj7&q?CL|5!+Zjc5meYzY+4O(MGECg#&bjVK6+GQ}8-( zDK02>K!~eycCl8jv>e+4{cU-}EL?>%#DJAWbI5^C1$6MDH7)T*SEo&-&uy7KDdsDX zy`%9}*-L!redrz7p4T>FuLVKT^exuX6{m&_;n-=9(=>wLi*@9M?`lB+)U2H8xK1ktUDU z+A8^O-cys;ynbhv&v9qZDF}j&?7!Dn^WTEwML=ZB9b6p7v+mWurQ3W z2^$ro1Q|D6J=xxR3!q7}Ei$B8S<`aIDV@tWlukw?$b1%42yV@zNL}RFf;y?Dz(;;~ zGs3|gMOhv?Z4O4V=ObRYk?FDKU7*eR_NVWU%WZH!xO`w)jT%`ihHrcBOxun(12)s) z%FvO&D*+O?KV#)$yDh|xCiUWaV8tp|uSfteCmzCTA@(nmI{~0UB4>>t=iQ^0ye8Lj zw@>@(B8EdXYO1Y5LMcaq$rp>gl0jXG4aZu2mgB&lJs2hOW(F6=db$8U_K1$YD|A+x z-ES~#;Srss15{pT*t^jMFezjGjSx$;Alrhzj@5HZ?FSUz)qYXWTYp^`Lg`a_*+u1` z=VC(@_{A~axepw4m%k0Qd2qE9<%+^g=*qLuJpl_5g1eCfz(rNDUESc{-Cf=EY3J>* zt{7P(1?9VFGM1q zdz^oIw#}QH^)&~R0&$Z8lwHnF>TZRO0?LT86w{HTkQd++61+BGGcl6-9ha#$j{Z|= z9rJys+jedZke6V!W5kb{>R$OxA`ypm$(!ILBXD#K1OC$;YT&lO_{@=Gc)dQG@c)d? zI`g-yHJ3RrZE_4n##o*E`RZZXQLYO!_pm|p;L5C7nLdh?90$>Bo+*qB*q$sY*?gbP zpD;3x@kQLymA*H9&mJb|Aq;ca_r@Vb^)z)4kC7%&9U|}9n@#* zjEnSV_82z_YSa-Nnwg9J-JD)&@vGXOEb+o3_A)Q)$NNr-695lseR^|K|5n(BH93^QNJUDi}{cC14(fBksCJ4Pw-xXy+ z(OM{+=5^Ni!7Z{gWlG(#$7p2_A+V%Z20}+ezL)fmTqrEJd=Se3Ie?T=dpDJeoS0_k z3TQh1adI{d=vXk-#V^w3#st<@B-)Yq3#!&nSKH?sK7_012Zbv3re+TAD#C&;oPID-@z*uadz}OAi7Lj zQ5yA%4TxpOJ)3LZ5Di0wg1`nPKI#p}GXe{xH7st*48I^EVcbs9DCHaAG*g4q%fQpj z`WcPH{6U6>h#FQ$I(z6ns9cPlc*!50FmPQM~zb>4>%Kqq5?IgcW<4NwbPHut_D)@@pN0?D zRW}Fe*-k%r=I^0X!5Zt`w}$Y_J31=JC!Z|HX;A z#w{8stOIWm1qVJ}h2MmCxWfMPn$ zW=YClqP2s1s%`ZKWjO`XM_;TnnJ!+h4PS_xt%xl#W;W~eWWJSlG$wSSPtUutNCPk} z#F25Z?-f%9ENS@tbS z(#dWODL72c@^zhnNsL;=V(abdygj*sZ9&gz!jv9ZK(_cpFQU)Tc^&FvYY6gZBeqO+ zP;QT&Jw0xo-)^?cmsfZSB9Lt}OKph7N&q1Zvrz=-IJ7RL6t9sRFAK)_Y<7pJj>@qN zbe^fMsHjq}h+qdp*6obQoyPeP&tZ1ZGD6n-5&!x4fLeIeD+iTrS8h#;2BmMYHvgh7 z*v%3;ZcX1Ux@I3*9iPl~3_mPdeAHWm9X4?h?F-1nCJsjoug-okeNpPd+6v`!FeC<7&KXUHu*G>WcQMK>xi4$Bg6C5 zIE%Rzxqrz@BB#0tR)Rt{(O6lO*};tYRS_+0wTk>b)Ki@Sj^{{fP|w;pJ&uh*rns(n zs3BdeTu=gVJK846C4r4xOsqg>^f0mFIck9qT`lnQo{1HVd?5ObdaaLGTwB`4p8mk5 zHU&i6wyzhNlQxxNAiDD#CS8bIbX>;-d`q@@%AR$Kk$w*M$ zFN&ZZe<#scC(S0~4(D>AE=I;eR>-zCB-oZ-lE&e z-aCu(Are7+;ZEV93@T(O@5(4Ub}~8_tlJ}J;^J=O!?H>dDmmF6HT}q(_JB z{e}>xxc{P z&vd*bS_5U*aom%;1U{PIYv6Y`h6@v$kcGgb6gE*;yre5!(j6`N=h2$6{i=J&VaUcG ziC^@AA(8XnInOP$9RT}G8To+R1nWgo04Z9M1#8}w$77Nd`Rw&_y}19LIu?(Pg8q@n zDg*)Hfvn9<>Hv&OPF5CHnlvJf_YgQN&q)~Q%uw%83XS}2O3KD)KWV2_W`|>Wa?(}T z)w8SxA}P`_SPZ=`_i}{JBbAdW!6=-q7ZIq5z2%SV>0mkV*XVlK!l+v&;o=Znz%+1K}dt01$>>kQr_1| ze2w!&Yztq%g?i|Sh5ppd-SSa87K+n##zGB^9n*QtKK=lnvgiSblSu6Px)q-WXC#nP zSmAb?JL^f&WE2ljdGXudPzn4u1Sil#=Y08Xv6O}n+|)lm^H~AA64xW+V67Ok5-le% zyCF^oq)Znq&k*wN46Z03M%(@OaHwyi9br?X`*w`Io2-6FX;^?=A0UJV`2ZHs+uedF zK^#{Y1vrIIB`34Uo!it3GZ5HwSV}G%6pFQn*hZzr8LbG2mLl-!_@V|hX_E`XYSGde zXvaot6fcH~K|RhL4Z#t9{F`-b*nisd6*;UWUHM!C;-b4NNaaNJ;GYm@$EC$HE+eD# zXJo$2oB8)k)cn)jBa@pHQ5pSuGe^^TcwjMJ5pEg!afAM!-yZ3$PupKRM^lj%3Zga- zXRzz|YAN`cLu&!*@dlI0ueV<&GfK}3h;45b#QAht?FgI!9YNJp$);QSqKE4VVM#D< zI^vQSRbgPPCfd_hYwJJgyrU+P(CjtiQS7i;SYdlg7>mGnqTi><&SyuOps&-KP>o4# z6l%&#V7*ub)Yh752m!;UJJ*_zuE2h{4C958W>PRph|;I9Gf*PY^sp9PzW8k4NQN@- zE;jD9p*op6$JGp);}Vpx6y1WUHV==iRdDK95L+?%AWtg*rwZPK4o@zhJtI+4YtM+~f zpi?y>69FDJUZ>T0N*L{84qz>E(SX>l?imsUP)p!IWVk6pIPncQCC4+v#e&U>h;dPq zkLE>$Nt-MTVF!W3zQ62sy!{?@SoG~+(eA}oP1n*e$?F&b=;#RAUoG`{gW#DRNt5tP zh6ZAD{g19gxB$F^c!8~f<)tWxlWFCVi`&?LB{))0FP1FSt5}JxWQeO0+xv}lXw$-# zq_R9VEwh2y-vM_!bk(ke2Ea&2|DNcAe{*nxRAexyxSZiyi(xNng?U>R<% zJ=_2T5&HG0U%z5M8u_gwZJxAOf-7ySk$b~_DY`2%dVeJKL$Jjlo}cbMX)|7k`G-f$ zsNdYp?pI$nkHB;~7xQ>F+uU!F3?&9_#v)-U&LUDw&2x>!=PF}g%G*nIz^5rx$1|vo z7m*OdULD?UKCwOGnAR6F2$+y_I9rJzf4%wiVfkf=hA!VH2$M$*$sOA5>zFBCO7!rqbFV1an{+ouF?G zdse^y!mZ(;SAkQ?927{tyU9Ath&QhyAn1s=|L_@(0vqDr&cDB%uYt>;vV~0}N5*YUCa)PKOcREi7N{Cm%W(U$PPu z=6s3;$B1`%M{MA$-J)KlH%GnX~R z!QuD@RGOQxz?^{#bT6(pATyesr)>bc46;)d`|aCQg--+_Tw#`eq<@MST`(2i1pGgY zF92_~v1f+6LMB0-Mys^5u!`F~*ogMT*f~o}2?0C<+Ev=k+^U)8Ha)6xbGkA)eDe74 z{bzWNXaR4ruVZm;Od`mcqy|U)dLQ8}M3>1y&W3E8)wviGjS-i*vuzSA@W*?t;gyrYxN-Akk?Z&UP%q2mPM-8b~6#@N5mfZL0X_-L@=Q2)YG{8UqS z6|^hYa)<)*Cg;Fs#nq}btVt9kT7y-o2ICpjzxFW~chOAJlwci=rl^=(A@u$a#PEZ? zftx?NqP3B4Ag+ta3c>Ak*%`kOb_%SQQl1MaIQn^c((7l zSjPj6JzTe;pjD5_AUeR<7kuICa&hINYEG-*onsCq>!2u^MOxmnx^96dIYuHIE ziszqDV4Qt>8UguZT@59aV{HuqPJkRan0=ff503a{VB5^8cm^#YHsuNvHTbfc&~f`U%dni2Qbe>@B7wwr;)~{y$R{_52sCmM3bR>`uk#ie;V|oX zkLr$mP~gez)ezVsCbyEE5Tc#F!VS{I0TaUPrDT-YLl{3?n7byyjF>_my-iH)J()q% zQWMJfpu_zk+@u*QB!S&lCe64?#~a44s}R(!K<=R!g&pN{1kopN`AOP;!=9W>d}?g> z9fm+mh_yySiZ6ts`kq1qIo!SmhP=O1kv&f~q{7Tt=fV}pC-h%BU$FTF^_u{hKyD(L zDtbl?M$2a?&Zw#r|X;|ZL(d$uG!K?wM>!b2G`Qtl$LxXac;1F zc*8ckb>1+5MM7WB9de1cGU{l+4ZAG$-sW**0?t-w3;7&Fi>Fr?x4dDC`pE&!nPDwW zs;1v74ZB>Fc4DtNCMYM*NwzCy)E~d(AX%9K;9OcwZxWEK0z2BZ&HnvyveVgic6oVz zaCN*GpPina9$YR@!5Pk_ti_2yw|tpUJE7Jds^X%L1AfX^FL57Sbd zQLdf55F`fy9J(9qye2s~pOijfQW`+cEGd12%$(X=!N>9rK#XlFfZ2CFC-S^10+tQL z{*`%!sK=raI7`mAljOlTHHVJRM!1WuP?x%f7v>dpNk4`kxfGPg6Lr@PHmt7I8f-f$+rfE3xR1uz=}W; zfd^sBnT@4{Em`Y7sBZ>qUNES5`2ZXxAu5m&&j8_A5P2|#trXr%HicCVgCtz?8ec4H zXfuQqrTQ;eF02$ffj=%kJBjyul4;VUp-3^yKlmE0+=k)wK6xObFz%3bi##<%;KM?P zk0B1I1u_bO|BJI5{@l=S);|*bbP5AR;w20R1hsAcvh75H54^7n+XM+{3R&uM^D%>2`0Feu&ZhvT& zw!^&Uid7y}BN(WXH+P|egH;LT-dzDHH>Dcb3-ht6c=QPpbx_yz5TW_7w?T)ROv^*up}|jj z9PD-!@#4q3t@j2WR1&dd7b>`A@(H?sKSQD)s7U-4k5{KN>;dzuqk7MD0h7*IW@tA0nLy zYprFoUZ>=wkUq^YAf<{f8bk}pJNqeS(kY+2Yu&`4-Ay|@NeAJD_q9G)5BrM`#yaAD zqSUqx2Inb7%y);jy>!zyTQs=%S51cCotHdeBj~LFJijRKF_zGLm!%(Xp(w6 z{*^Q@Ns3l*EhI2Un`u>P++;)JD>))?9r^yt)wdSua24R0YQM*dJz>qKt=8Pj*)c|3jD9y~DA|eYbHg$guztV}Kx$gxil` z5jMqy<7hmd*p{C8WT8D!LR#FpD41Ftj4B31f@#zus_1D*avxz!qwmLXAA}5oa>sau zaId}uVt9rIcH#RsOmUzN>F=>{ z2mKA6meEpfhAx9G`SJ4|yy{?QjX8D>5%8B+Av-p3hMsj z*}2za`v44haf4u&yt|VEjGe(E@EEzp+0)3wx1_ko6R2>51Fz8XWPdI6{|VL!>U!DG3g4MJJjKjdMkcuc$6T2<%YxrrSPauL*~!< zPAv@MB7cH%iHq-9kQaJFE6zGO2dN~=3oFK$!tVePoWl1buu)d$`DP8^!BYA$;nT@5 zzQK{kH#wMdF|pv;`-Nm{(!i_Il_4pQ)A)6~@TVZuPO=(`iixg+@g)&&XhAf};wxPT5+Va4pSpD=?k z@4!htmy2y<%+4E+QZXh?hEWST1E5-7EEep58OeF2D4ah6w*eq+P0NAZ8?e@}c3g?X zAnW{Sr*+OT^`x0D^DnjA(vS>7d8QABt-$C&+cm|9uRR1)K@au*9W} z2}9IUL3q%6Gq$n}3HIEO`;M@TsRaM$VLpp5p`KMwIX;@+MTAFg-5w<0D=Y}yh(D=^ z*!dKomIqEgi{Vr4CicQzwUWnei!G{3Ri0i|>O1xO{ur-F^|c&tA{=5p$`oC)D00s) z?`Kz|^W(GY)2qw*@fb6v6gx;YG_cb;_Q??7HUF=h3|_@X28Km6dO#6TEiCvX*PFC= zS^_uvjrE%PwZ>~*Vtv!a+H6@1E2Wc5N3PYfZ>tRIw{^o4^(UzFrwa_2TFhjFXjRQ> zQ3$Squco|?ajqW_lA@fS+tQ;ejxQMXi}lTo-H(sVIEngV1~@z^P|a2ELF`fwKjdB` zE3G}Dbq+_Nk#I`Wi`cT$zc1(a;%r!{?YV&Akj4}|Xl-~&yAiq%;zFE-Y6Hx9i-{$) z7rPgQ@pQL&Kr2Jc4qoG(8|*~pA405$v}v%35MGNdtFTJ34d{({K;~NANQsZkgOXPN zOn;@-C36(|Gvf@~E2|ihX*Q}iETomW;n~bJ@9j!e#op@PS6>ZeV(>A43W4X}Dde9V z-_51=GjEROy@gt;(<>IoF4bY|33Yt7No?IRL>Y$c+d# zCsJ6;!MKoI+X#aK4n^kC;!`tmw)i%mL1=$lJ*GzQ}b0OPnwZ!O||Di$7qWOWM&dO<)Bh$j2G25&hp2-x(7Cd zk#y8JlYlk~3?}d8T0=3*dfyoi09l<3mmD6gs1Tzp!_z0LPg|2@Wn)RxpJ18;A!8Rt z-Oeg22Vf9d03HjpGai53+`mQ(wcGa(8&>BA4?<R^LA?;;sL?K97$V^zpNIxkf`Hgm)sUgogXraQfmr9jBjY>0V z>fdxWv@$@8p3Mkp2V$iCl=iHN&VJ=gJUi6P^6*3}WlEQm-DSR`fg+wXIhfT_R%*t< zN$M5z@8Gqqn=Mh{Yz)FoMUZiJCo~rs>kx~kuT}Lf+dKvy^CXR`zhDPRmgd>rcWa{I zv?UfiYllIYhjpimtGd%GieV^E)ib4KJT`8_P%AZMV{IFQdyN2NIx6Iw#<)Mu&5$zt zskR0qw;J;6&>_EkL)st}GH)8C+dHPKi!p=bZ!(B93{v#tLg4mji&iVTV5R~Z-kptB zyiBHq8>z@j({P^&Mlc$|biwuJsHXg`u({g5-$^94FaHPfk8`?VCUj?5Atl38d#x6U zCutVKHeCMX2Nk&S^bi5r!S|Uv3e?-x)jJuL@!RV0GsfC7r*^VR4R~g^+TR>49uM?D z>DR}YKtYdZFj`kv+-Q8}bQln6<3a*;WcZv>i6mBrsV(_A71XkW< z3WUrM^;4i_Pulw0|BjY#|6yI9#;-@d^Cyq5@xuSew~USONeqE?=)VfQQ97YWRmXf5ccnZ!cz_qe|nkhfpi8ntrEgp4j+ zTq(bx`dSyRbIF2YfyP#4C@sJoZDmVRhqZDiM2s!XkPL~&6XFaQz~kz2bqo3Q{PS}0 z$MRuxxc$6&y1jyazeNaMz<`HMG$8!POPlingFMXnAQxHy=48fNSE-SoNjOidU?I8W z1JNI;gUB#Yt2P+~W73ha7@?ktAaP8oLB${by~q7zl3__?Jn>mRgaj|Q*<(k z(E*6LEC3nzo?z0S^m|)gX#xzUid9!TiH{YvC}bvQa2}dhymK-agwy}UFh6YFo7uxsaNqN% zZxh5-cehaJ?ME|3wa1H(LmC6d$a#ojttV$3hQMBQFp@5Qu_RY*f`Ei`va!(twUkh? zpug)+qx8TFe`N6*fBGN!R*OlzVA(mjjzZ#c`Dx_}O%7jP`DpWKqD}GVtUz=mRfbc= z2qato2}T4m8gq7}F$pz9vgm5ntLs;>{#4(o-}m40tFEu*_{Q2>tFzIVSyoH1imf^j zTVNR`&L}9Rwjai+?MyHoxvA}Ft=yAf+IJQ8(fz{2<*8Q%9~H;@Ka1o2Ir|Um`m{bn zeF?l%{K&T&+hzW}h;KI6jR==4yhQt6Itf|Z{4uP<6d6NO?2FjQXKy#tyK4+mNzIgo z6L2m(;cIyiDkC)c}7d(q(n zUlxTY%r5Y@peK&o*La2Ii zdy0l`(l!^G(E1opEVhz28W?5x4G{IakcBJyIc2vR@3aGZG3<`gkg!Ti*O_732Yq!- zD)+FYDc*^fF5LsSDd3m9MTb9L*`R)spkwrg zVL3PI*35t(6%!6e2dnLG7*ECOCMA9{T)8YLSvTP%{Fp&(o1rum!0jGTaPklnL=!OEs(#<*$c$X7P>}8J z>6z!lR)fVtEt#>$jR<5_f)A1#DLhDkSOa$$XYj-6?{y4TyA2c&D~k2+z4 z&y1&rDT_*<)y)d9E*bG)<{j@%Ch1m>jWCiay8(s7C)S!mBEeR+EV9iS2{eofp)owV zdw;AC78u7&f=B(pi#aV6FRL_)Z{!3W2-sve7pQYnBi$>}$A9&>{#pkKmyz$>lIxXS3T+Atj@YYP;MTcszXr3zZSFY&4*F znB4{#3j84h@N?-*65Cf$#9dF?SpHYg{rEy`x0C@7AYt52B@hB`2*3q1+eHH=l58$7 zuq5^{MQ%2mcZ(~Pb3ct>7Sp3ooBOW{amj?iL@c?J_nYh0-TXFePmeg@)0OE1(MRjs zH_X&Qh`c%c@bQxFjKm?JWW<$uA0W$I+OxN-JAn{m5OZkprVmB?Pz6(rykrKawDcKl zaOMmE-#-KQBeHpUg#il7*lQpoi|8xixrc)kyju=q-g2>lMS=isuKC1`Q{f^zt=1ty z^M=7ui0B8Wr9@g3sH$kXIN?M}Y_(O2tyF3u*SfUyR#8#TKey*4;x8qaQ^SlBt}RI} zgC@0ZX77P#ZvfqRMWWNuv+wSj<7n>RGFv0z?O|)&sipcJMkRi0IRllqtawmM=0%(Y zh#TQ)iVHY?dAnNPZTDBR-}kJ;7RVBOj*c>&7mquFRN`pp#dxynLiPnj2=u=Rm^Gp7@EZh3C zCh7(%JAHLK-{$VuXktK(fFX}+c#yoQWsKjkuD^;&+>$Iosp;_7I0P|uxCTqmtmUp5 z<7moLn;M@9ppSXG(a|%peMka_e*bPFsGs!atQ8Z*qK1OnBlP-bG;&9mIkU_QKvNSC zhbYY1?lFYF>d1@ z-0asQZ6Vq8-Tt!iXiba{z4Hdne`yl_Nh zuIzIri6`NDekl#P(MWN@&Q2x5J}dL*RCHO~7D?=#IdhRAe?`uG zKtlvUApf_{X4=&z8S0mV)!PrBsPu zRtydb1U7rs;JTDQkU&L?7RX2B(yv#jdy1t~c3ZSM(NHZ!Mg;Ki@-S3iGscXVeNY}) zQCvS_N=So2`dZi~ypfhAr##q)?PUA(aJxJ|e~)-NTrZoG{b36n-orTscoO?GhCyOP z3plq@Km^vXjq}MmT1;8+4$@r;s4|a86h)SF=u&qW_SkN3>&U9;ZHu&&#F2I-h^6QC zsUrCar?{PegKvt+B|%Q~mM6>g1B+>+YKt*HEPuXE!Oj#(uG>@j93b1Qb^4q2!4xUI zb|z2F$kc(P^n=+Ra9*eV2x7CBX_Pf#q zSR(BP6_jyDx!M4xj|&vs&Y$SI$>joLw zEbv~a&n9p1VbA)T-spyB?MW6l%lX0b>R`M)#j75VqoVYq#mxlHLq3!Q$C&2Mf$oU3 z$W*o>R-`c|yQVbU36hA$^5_Juvt^uI>@?s_f#~d)C5=HI5kJEa1@I^z=pVR3C{#E>=?~e{bU-6A?c$xo z_1b`DQP!|3=Ljg}z%;3U&q=gQU&86;MC9@4^8S8X9UhHu??1((vPh#h_n$tX9vhf} zZ^F}c$Fo8lby)Lgt%)atuBRn`!XNrBYRP|B+OKJiK!kQ$Be=bl(I|rii%KDQ-4Jf> znsXMTPgpProxZ|VlOwoo6>`w~k6~**pvN8X(Us{x?zf`_iuyGZF}!IO z6KBD{*rP6J_Jx@fjHv$T1_%B*mLAGHIdKeEkM)UZ^8wuQ(flZT^Yj5DNMbCP3QCVo zpd&sKloO0DlnLq|M!&2!ORMPqvc<+j>^**^HEsl;X$qD9!M~M6j;hU&GV_5FA%#{V zAUF^wP?A!+8co}Z{0SKag{4)HLPbyh1vlug#X&v4IB35b-{4L$%3-hEqVCC>5dhiQwy&d5@KkEpvKqp?T2SfJ991A+LbYI&P8Fq9RA#l|o}!A+_|^Xi znYGrKv@j4HKRIXjK?@0x1Y$C(4%v|m-HS-iBWYTx3IdPPqN^x5vQ`Zxq!-^b$0?a@ zNhw>*8c!+^-P|4wu`qSE3ZF@)H(M^;KYoY8b4fp4e$V~*oFC+p^aEU48sO0eF$=xaJS}q2uTnLIkAS=9WFq{BLMGY`Ou-^X+xy5J6bvN#5h6J(I z7l_+-gXHk_WTTj!SHkRNtRE?#bh*BNUS=Kp7{0|l0%v3s{w(1rsSs1eKS5h)W+|hY zh7}^K2b&W}PNvvM=8v!9fW$~-1Dfu2H#6V2?OwKEh}IA_MmVB3%(*9B{5L8qWeqYG zJw{oGd|-feS~!OXAfs?nV~+$LsgxeuzcZPH2nriEdy|h(Sou`15z8FnPo<97&hqF~ z-H`=7wR?%^KUdN*a7umLe+!?BA2}bdUb(}3@!d~tWomkp_y+h;+}0oY&PO=C0b)VC zax!jeY~@-(42wjgLQl;!_+iEyNW(1e=1#puEyxzp%Z3^>1HCNnv@4cn9$4gtPK@~p zEErxZi5NO>Wa~}?O;@y9X50psijGlX9qmqNB9Vdwab~XJ9+tW*b*c;ZopyDlIPDJj z$)DO?DR8-A!9Xn(M>~)tS_cvCU(`FIi>;Q&uMvi|ntL zF?na$iAhMAkn2^)O(S{ZHYbP=7_LMjWS8zl8OY3{$in$!f5<7uH~R}6<7IzCZ6Djb zWEqS);EylI#q}w1Zjg(9fg%S%#t?d)-7as?Vg~FQfv2e)lX4^O(4pGhVV_{PSVp*r z9*N-^ObKlpdH>MSUE+V4R1gH-_0qs>Gjo$HJ|l$1>bM?I4hi_|?fiEGA}^FI!!9&B zV6%`y@OTOqr+h@@$cB{T4MqT@#tyK);n6Q-9D)9ZBS!(7}Pm{jZ4Gb8rMl-j}nM}nk zI_&ifkEz>j&+GjM+qG;ii{y(H#S+{7M6q9{P=+cI3}-^uoYkk#+x0y_%@lUJkzM_p z%^cO~NQKU;C(h&T8qhfiur_qA2bO&_{Su7ua{tzj`k%s4QjAW7R@KOnT-dBvOC}QyKQoeA}KoU~ilW$`CKeFhOvf84-1SJKWOXPgrex*AZZg zlU>XBjz!Nj$lIu{%Q^&PD4M*VHBJ0Si&2-Kh&v3-l;V414sKbYZT!pmHiW)AV!w*ZK{}4U_6e6PS}kMes_pLfGtsm zkf$}ts&$wWx9wszNVS9oLFWMQy1RiCi9XcuGHmNM@{$Zl}k^j%SzJYqSK# zw)GFK8yJjy6)gLJz<5_&ygMw;zqF&`LxSSiV~cbRk`+pJ%DIk~0#U`|`X~F`*nrV&#~;07p4 zy+q~{Lan@(ai)vVf&h}&loApXD0%8uKJ+jWD1lWv!-4GyKwY61qW>JMFDz-?=fQB| zUgGGHNhJ3_EQI_hpOO92(I_Mh*l@DO6;_#mP3c`T20}&`&R&+$4U&9ha_a7B zjg=I3p5n90$th8tqHS~Iele{~daX8mp(B^*5#ds)^(Uyy1xP?d7TvXY3uIbEcN0BV7h_{OCTWVo>zmS*0wRQpwQ%UuyRaEClLJ13+ z<_jpo(u{W*v8(AsU8n|q`QrgGn=J=Jpd8Mw9~uAk|Pd6|r@k_mYS`=sc3jZvId#A3RN9S(Vw%Wrsf!$;?X=>z}!j;zoMp(87AQ@KgCGn-5t zvwLubR?5MO!kjfqL6O;*Sf2I(DTOJ66s}RRdXM=FQEU65?zT6B1f=S#R(Vx5rc_ag zfvjNlpQC^6?}*TxhpzUL?jD&oq}($B&Ns|#Is1cx<&I|Ei8FjP*Fnsd*xGv80lqNf3(8F zw5%$1EzLEsDviQD2yGapz3uf~#xJckU~eeGd9yw|#&s`We4Ndk*zx)7karS(93OA* zVG;-M;QP(X&-2X()Yyq8L*GH2=hbd1nRW4s#W>wTIc#_tecvgHy`fuibwz5{b4cBq ze<8{z5#!`X6bLQ0EE5u;dA^;p$Tcy3g(!S+GJ&{5EaT(uPHE976sg1o&7BPdkYE%f z`=|<2nUBH7WvO_x9I~!u-nG!GcA)Jwz)_4IqyJ#r68@@xiU;Gj@~@caz>8(7q+Z7( zBi5nonCZB-dAyB(x2?S!I_17#$>x3zTH&&D>Od z6_cdMGxnh+oAL~KrYPfP=?C31{j699zll3f_80M&ieK~x-Sv$myf)eE-Fx3Uz5+g^ z-s8o+{uTTOqPzGo)o^=`$Z*=B+mk{>ISvjJ)4<7631`$s5f&Cp)3)5kqs`OZ%lUTk znK>RaFHwn2k#l_!WFd*99*jm}zX27>MT=H1Ee(b^307F&Uvuh&54h0@5~(Uei6xF3tk;vS1B=VWP0 zx@Fk1Rr;f@{egz>E4-dqu?1eQ_B8Nv$t2T+OcZlbva}82XsBmVjnT)KJzjS9}DK3s{L_TGBY1mUNg; zOBz4G_}%_-MZ=PZQ;iE;y6^39kblv{S|(wh~);Fz1C#%Gr)b53A*3 z`E~WU#LVOn?wX++tTo)al!(`dzt7GYNoHWc>wou<$1}9~Tz$GjBa^GA8-xH+Xz29p zUI7mbxakOZ1bKEMny6~CO@hoPwY8=j2T1;wJbn3EV%(W}YTLh~!%KRD9H;SWb-N7y zal!H-WldghhD#X?>kF6yP@=7RD4N<5?L?!pH)Avsyj|TbS<`<12+R+gbf~0>p_SS* z7-@ulFAr-E(GD(j?AXiNP6hOFv}0$zw9w#U4Xv025nyzk4mC{*2Y_K;x;mzUSA4p{ zO0Lla88={k@$>xlVH>)OIWjMXBkj0xt^lEgz?nW?mIrhg9Rq=F?!TR*-MaEx&{0F! z2PT6wrfe=d>=FKFVZo4E`a@L7{y&VV=K`_)3`ppC?(8H({lQ9lrqinX!D-@O-Ia|ja4ZI#jCIsw(Js>>#YQI^=tl(m9Ijyf z#iHZpI(7ztLm=1umA}5>ODLo^AyRaFNxCR|ke@Ey6oi)%UgsVh`@FpFv zd`pQHNZJWJoFs=O&dF$8w@h@Z&710GA4DLWa61 zrGaY?!pMN_ELW(kAVD3zU2Z?$U;C`qAWw8mC>My-jKl9TL#+Fi=W*lfUJ2sA0HLr` zF5rBpsXBNox0fwT*e!u~*zsw%AzfQGeBnS?xF~Z1TS;D!;86Tbmmo^Qf}6-tb|soZ zDWR@g$BK=|F_isbezOz@`{(WImX_`FdVTTg8J<%NV&xDN6Bv!KLq0ewwe${lgah)J z!8QS?BEWp=j(L1|zF}8r(zj)%HR{Aw6X0B}|er{s)HnL9CHHe1msQhMBt$JJdKkeoz2l z7vHw%^50|5`p5xR-~=AGv`!%Fm>PyF%{Jx4E5Y=F$Qg6)omgQ+wTYJY%QB4ya>1rn zo6B4yuJ0BZo2kMMSHlN?0Z~LzGWN_bTL?eP@Yt|^6 zu;O)`T*TU-gF|O63K`J~9gC0*zBH&ogfUSt_Z~UG1^i~5e)1Y z)VQuu>A?7g#5f)TLgBSj7Ikbhy2is2d(&e?lwvpuB$D;Lk{xYz8UIOrh-XxbW>JAi zvWy|HIEc*U%zJYOwxRO}DeNetuv|X^EwjR4hipIb9W=yi^hEY7BVS59BR&fFp`WM|UBW~hRviYJG!ot`PDuK6O$mge0Cbk9Lv;ix~TM8C;|zA0g=X?_0? z!*}G-`t=;YPql>(C1iuV95KeSLbobgtGYIS_dAMXmwI%82eDL@ zC(D)IeXZQShDLG2O0rMrPTl|KH`BwVwef{G`OyeNNyV7982 z7%h!7f^f{ka=zvK=B9(x{ierMuZ})x^T@Fl5)s<~KkH??C?a9FL!SP0asTj*Zw5I~ zmvgbA$J?1ha42o%q;Lhu33DRjxKtAd%)vdE+F$_jr0$~K3m8et5f3Jg1ws zd-@UM;(VY+3jw?+{$lSPg|1V|dj@LFdXTtwXSS#l32$F-GHZiW)#e zz3^vGcPr#+XGn@7ysw4s%{7>mYv90(h7KxVj8#E`OK_XkIHNs=1!++)7TT^HRBzcE zB)0byYhka}nH`Me`Iq}t7TB8&00>6s5LJCQ?s}v#^+I4F=Cq&;ZEOqr6bn>LLHrWg znBGT@*Bzc>GAv)CwQ;n{LvbMLMOdgqy42T<)gEXJeZ9Q8nM|&(ZsrF!i*Z)$5l>^= z%f)hhc)hqDU!PnZ94yYREC!O9@Oh0uY)A$CjJ$g$vt5#MRE<|Kl~@_DMmW1jQp~b2 zHT%-9c~f%L$VYEic-jfaRS(2}@xlLy)H5pck}gnLmZ1x&7faCHG!t~M!RlO-5Ca{L zIk8n_WY$dTm>@6Y?nQGF4$vs5h}5yT5bL%QKQIOzae`F=5hSkU3kdT5jmj zvWv63#eld^NhpzG@Ie@C_a@`jJeOf}a;b#crC`HqXJ6LS(3HqW9y1)|=uI%fqX4rc zbOLw5f0+y;1Ep2h#)jo0hnyt7iZ_j-A72daXFyhROoF>RRXc7*o_EHci@>axYXHnr zpl3HXXTcXG5DVW*>!%N5cv<{e5g_zi^tgd_gJh1NhMYkyj_-qY2u8s6&NK1Rrr zdK-lUfO6kg{T)Xn7!H1gFqAZ3ygQM)gADML)^-2MF~j55zWyGSg>T-K>@y zjOCWjO2^?j!==cQ#gK~Paq}o&28+%U8kKdGX@_caoLrBQ3b(}!RwQ9AqFaCM72qoF z?QF`t(lne5zHk*sk~74MDkHk~EZL-;s_cdoJ;I9w+d%<%I&>?RsAzrDZK zNrf_~ko3bpbdE8UKehX};BvdWnoB3o8#J_)4$$muejI7l@77)$g4g+jdqT-r!fJ6z z7qFm?frRK#wZvRkeDQ!Km4QR z5z*B-!;sah(b?7E$<5W#(c#2gol%XqwiXjPHen)_oS_k+N`BVwva-zJk>5ern285MN96n?%qr(Q4 zk&d#^Wt78n9tB&M_cS|u(&@552YeBA8{nTq7spB5)_a>V)94>=KI*pDM{SboXtF`) z3-Uouqy;Bqtx0;mc1fF*h5k;jpAAYGl2k8_djd@k_Rt-UMggG{8EcI`vkU)%&UDr# zvXpq2FHZKI;>}H}FEiP*9>M3lhlh;z&UgEm5o#cx?$&^Jo+Q6iTxe+BJ1c4$vE zgp?Ul&sAk4rp6f*toaB0p7YOcCNE3-mDNE!_|PKjJ_(JD7Wcv=^Z*&-rt9T`i_hW2 zPoDq`=ee`POXQb;#!naRd_Uv5BiSRQ^2tbHhd#Ou@^D-jplOfFG^bs#h6&_grc-E% zy9Jv%CD?z%^gerWdy4@gTh^}*ytD@ON7HFE+tKVp95cN@nXNO=Fi9r_CxRBv65Ip! z*IBZ~Zn$4tbSBb2!y9%*hA_Wx7v6AKh{^>TMA1i=B8{zG(?AsM-whxq&nnEb`30BuQ-#1 zjl!>WM_Be%Yb;E*1I7y>#t`CmN_#X2s~A1MVF3**;c`Juvn4{QIYehg84@aQg%q4z z(@0*Y)N<9N^2TuhpyQJ|zz2(n1l=8_ckkgtk!hZdmv$-SD_jyS_d2XQ#{T_;|G^3` z=iqUNd~!26G?Zs?JD^?EzvzB;@$6l06Z3}Ofu~2uY&#?jD6@(;OG$I$uTwbSGcXA{ zXI;=uwC51-SVltxuOu#okMsmoP=GUntoMO4N~Rc4rCj&GEYc!)tn$+XqxEPwOhgFU zX1|8pK20hJi^+P;=r(0aqN_IUsDB7p63O0VK7?PG6~&5mbGu}NYF8T@)Nm^s1)`es zLG=`$B*_{*L^Lp|sS+g(+3Q3J$SVA}gT3-a&vR!tFA>ZoFN_9$MNTuZ1vzF~fehG; z3-$!s1Y1YigDd#Q`wukw#pQZvF+Ij8H<(!G$VID!d;Vy~oe@dtd-~8i;tb|lS;Kcc ze9qaliF!9E?x^|iNI!c29irj!D_Y>10a!ke8E}$h!Ocj4P8|dvPG_N^1QPHDY114f z&K|DNlyHgX2r=rL7Oqs*dU0#ohQF1TgmI20BrFw?3*CHm1G24kpHR4<(zsYt(GHIF zqTvGq#xD=hGc{vb86+`F91J3mW$UyeQZzK?tDS03 zfr{GB(T!IPdEBrM89|A88hNb zxl~$zK1;ICA(v%x;V+?>(FAfhw0qDLN6W4QZJ91G!*iEi40_DVDR2#@k4L9EY>mWs zJOB26!^sRrzwk~ZOd(H#_r63uG;bU<=$Ve&oPS!L-7UZBFLV}0!5>y(Z(f>Zhbv0X z!sv~5P7u+tXH1ZmM^|Xye1RubBMzC3=~|*y;qRFZ7jaimI~0+PSq=TYl<}P;@=RP> z^gBvMQu-sxc7YKm)*h{VSoi{~e~xmDo*Ec^WRu&nd_LBUT3y8Bq{=kL<7(;;jfIEg zm~1Fja$5cp+A+Zzb_5xKY&a|0F~@Vzi@&! z>}$$mDGFtv)@J2ifJX5=lT;rncDIZ74svD3G$)(%+2551a;DoQ;q{#LON^ENU^5ZA z0P@y5Ak={|GC=n<`!0SrGae$1xe87gLIn(kntVFcakXC%NQlQE^>CC0l87cK#CMdr zj{Y7o;Ns*f*w#&q#D&3&`qR#2a6Q~B>m|wf`8DH8-~$#zU=`l-cTuMbAyl&AE`gah zRXdseq=DJI%oa+vV1zX2%^EA2ts#4!QB_wI{fIS~f|GF;8#f<&&$7Lj{GlhWEuNZ- zSFN43#Pw3q2#b3YKM!(>X`&ZDq_T^A7(K$EivR@Cv{=5rFTV;WN7BtY_+lOWf{j-Wn@ zLIw(6jXi33YmwDR8i}@u3e`g&MhC1$dW%^bn{U&L&lj&hTlgXbbFl)BAV48lA8Y^) z8;|b{?|cvJ>-&0SD}~_S_`y+FMsWTF{T$Eqzt*R9{WX3aAG*GU~{1k4d#D{ z^k(RuGmvtaeIeFr#xUTRG`R+Bm2m^OjB|=5j>XYaTPXbC+-QW0v8`bF70!JlaAA0% z5=N}D-!3y?4tNgtl&n02GTBB~PL51|`Mg?u7VebzhZG{dA30M^jZP}K7I2>KX`7)6aQ(7+{p(qrP3;OZbP9LI0xyj)mY z;sW(*z<$V|aVE$-TmjxTKEf8zi{i`wuigZI$In~-DPH$|um{qk9P1OlKsA6~`~&Sk z=%!!z-4AT7fWL(AO+Xjn2|~{Wz76cJ@Krg@?hmTrVL3yr6kQR$4;~hOwkzX(@s{a_ zHYKIjq_9`)(OS+b2WiTy zm^bI_|H`|SAbdxr5)TyEdy#c=$>9)9+GYy@F)h)(FF1T&$^mp9yV7(8KVTWsFup>%dI}c5;jygaN4%>)om}vt?uz-Hn((# z_ZbQ&UpxGjotYrV6y2l*L!pT1k4B(slwf`o6ok-!;uD|Y1WfYrg8hEcq{re+AwDJpFZk{f4Ph1ZhrIcMBw-9+&7~e?7cUKOEak+F5%}U(M+%@NZpU4B*$@y_9FfPneRl?+NmyOJ3 zNF82a#x7WX>d-*)qa!etylIHC^UeQxzhW=!X8{+bS)LyqmBGqqq2^3-+tD>XNE1Ze z+)_q}kl6{*2si`}^VKGgiy)?u^>Tuo4$TdwS8&XUe7i!S5%$vsHIyNm&9W+n$hBWH zu!5NW4&({eKZ(d9M_?O`bD~%cWw2P%9^r}ov4HO|Fjt>!MXR?YTlb;4_zayv=VIJa z2s_giO0;^$s-0J>4ayc5WPLbzldIL;eDiH~1Hddb*ZF$Q9gQf2kT`@3GXN$nXvDf@ zNLh?KaI^Q1qNUEBjt&^hq*U`-HrnT4qjpHvpWb6}#0%*Ma%EX776o>eP#GP*0rdFR z3=3!L1nV%=;F|jyH^i&sEWT<68*vkO4$2mUJk6$cZ?CV@=filvBDxlKkZakpkR{G7 zMwYFDS6ie*3>wwi$8*d9q|Fju6@p6x_n^n)5bDnc#CFDL6I+=2-kkt3uw_DUGo@-~ zeKOaaSor_l|9`vt?|h0qA-H=Wu#7YSgU_-~cTj$h2q0+j2^7LH1`loTH=tvt={bQd zZ`$LfhZ%T`B7&xJ$&|?t=b_--^e1;5tmU~X$d)YC9zqyk|C=D=n>+#3oBje){VmAmN*9(G>UU@ zeKJ6j^^BdYxdG%~>>1`CAN9%FR-x=2X2D~;!R|D1mFUlHNO-W`hJ<$7N$Rjop@2`#Py*Z9cU8k-F&@F zofr4kPZrOZX4csyEba@K%%*cZJ#=x>A0cFv=B){F1r4S*ra7l>p?CMhjk9h$@8Fqq z;NHz7W}aE#Y|dmX9qYoQlv`+vPkc#Q=u57&7#ScjC_Hh!I1M6nK(_tO2~PSx*ST{#r|@do_{ zSz41QkK-!g2)Ly>ZY$=atswtCh~n;cFAooD#zvFar%%U65L3TwR?<-c0tt2Ad0lQt zfJceA5h`j$JR}Z6TR2vczs9@kB{KWm$S>N1l@Hf)W8h43zp;Ct_&mzk=l!iMaU8rsde2lb~pbKH#Q1K)18 zZJ@`+UR%HGDswUaUEa7&3?-nFWcZmR>{8MLq`4;CneMgH(8} zlG(~8{`jgbG*~93P_LJWgR$V{B0Eg$Qr@!FKx;JHG5#FarzqcN{5hnH#Xzj!vx7zu zgYD{pnMDbcOuxVy#o$nwy{+1#d30$QjtV5o9`U;q_ zg{?ZuQ;hy+X*3xV;}QpBcn%Z8Z(6-sx>~a+!H$!w ze}pn-8YM4KwDmi>eKDzt{KV#dfr(q_OS%O(Uf{GYfZGqE)>7-~>f%BIKrRI3EZES; ztMms<#lxnGG%ZGj-wtGNJ-~p*Efz&l`TPubiS}-WYDPP`fQ2Dr6kZ8W&*H?O$=tdv zBBZD@?~9DuUS~d&g`4q;w}D7Q;A^5nw2tXBO%mtM7)PDoF5n(CRXR=WFyC@L%}c*) zDDhZ3NDPM((_kp_83?ZgY(?QgRJ~HaD{^iw2ksoq7mC^ihWC(2^YKrWG9}-e(E~jf zW)^spM+U%&GKHd(W~GX9;77$2$U#U8`8%it$K{kuKq0AHahwMQqCh1%i9%VzNe0?4 zs2txJM!<5hqw2i&XN8dbEN>Z zN0bqk!HO$AdUOBj!xB~6%&TCfO!HWQz{poe21_<0KY=A%AR$;rS-Ut1XhXd6nfh2i z3d}#XiSV#$4EP|nWJ4mIYVN8H?EkIIU}_bAg8y7!B!0c;Tew2;Bj1ue#qd;TJG8xk zhWFzhs&N@o;TmQ9FfkUteMSFi3~9t&rpWhv3|xYx1L85zz+ndVjLQn1u3NlGJv8T} zB^6q$NyCA`NC~=4?_>$TKHS?iy7T;kfVMy{!VX81oQ0)$VRC`n^elzG%X|Va4YQoI zT{VT>KQ;7+yE@}AES>>e8GN^q5}sui(W=<#EMeQQuVz_fJ+>F3M(K9f$W;5K53xC(yt&)j%m&&&oI$?T3GkH_=Ja|Gr1EM4QX zU~b?)wKxQX!hL@K_0C|8!$uAo1KO7<8}e@7U+5v*MPX`vXNe;#F9i$o9$u z=(y04DdP169!RaGXnB<#lKoGSZWtYSrNobD_`;id*85I9k6lfX#H91-vxz0k+XTUR z$_ChZ|6YiJ{K2rrCL{J(6*%*!gZkhM4`yX1K#ELnCy z{KT^aMx8hny8r=Fcf1{steorTJEE3!{`WO~f}tME^dhv!4XjtVgoNxdy-q+w7IAE1 z(fB5#!;hag_g~+`j=s6Q|B81ZUhL50#m2{tqWWJp)OZ{4x%lQ~MNHy_Ad!OQqh*+U z;{aoV?<8fhC9JC!V?qA;9g0Q;9EZVm@y^dy2j(m|Fu_LalbuE`aF!&XT4fL*81^3* zB7J4AH}?H6ZehwK;Q1*EkH5#aVPW?6d0-X9Sc>cI226{_0)c*lZnTGyvEO!AT%E_e<` zfaNuC&lgYI`yb&WVV$_>{#6@c4@hZy!Q?|GgOhLJ7%2IXCSN~n5tp-is0GJDrRkPC z%Ta-<8=qf-&|4`qxM7zK0Og~$GC+ZkIlAV!c_th(^#f)DDu?7MRw7W?)nqpJ_O|Q6 ze(TyB6(&(u$glNwJD=HJpzP#+L~xjpz$-%{z7n!>N%;(mEGY+mf$`uU?w{_ibqE7t z_TvagJ_8*2(7}<<`rybvp=JUPk86r7`-oqXH6uvMx2wBx# zEEndBn@Bj4mZyNjQx3qYVN=@OElG$Q8`(x^;tCZvxEpZ~}X<9veRO}%$mgD8$dh|>?b@O5}2*K=WX`176c$p%S`<#kon*oy9W zB8=vGE*FF*mF6P-#SbDaRC16w%3Pggk+3a1$(t1YdcFEyUy+kRO)cl7;Miud z4>?xq{qYtq!GbFq12+rVXmJN0lrb}Dt@rrwhC7xj9~_@|EV0eB#9P=Bb-YV(v`AI*Ii{;`OXVFCi7QVat`s zsh}wQ+6WaD)}w^*&M$8nzw4C!7E%J0yOM#^`J13HdUkIB+<=vFg!R`J0`W>PM&r3DRM;;L1B7KLUIh5*VbHol=|Hc&> z>v6sIMA93Ozw#H~RVrxl+?B`>QKuCmihTa>MnxgBSp%mMmgwm1_k4r1KG zdA9g|G3-2W=rvcmiA+6zvqllC*f%+s>gwif`YY|X5I<2U#|7-2h+Iew4WO#jHXp%I zl(3r9mFYeUCUsCOqRCkSK?IjGHB=yy0mdL=0ib0^Fb7DCNtDIH80me}K3y19n-&!{Yr+v4fj@4!|){QOYlu_qFKe0(u1&y&W=XLkChs zX&)sQ|LBX54MY(D;5XZ>K7B^PYd2CEZs&M5V{e&RmdBmV&j~pQ*<3U+$3serFGPc~ zfrG~?jS!C~l)nh&dtwefwFHH!v6C-*Ql6|~N?ii~lbZQ3JgE?=FCr@U14!}8yXRA} zeItAn+h=n=*W_P2SXkg)1&4>kTVT1&!SqCsjRRrvL4D*Z^IWG>Je}Gu+;r?( z%JQ1))m7%V-~hJZdr^_^Rq+NWjHzS3Q{9Rz7?dWz32zEK$JP!k9*qkaa?C9k5p|k7 z0v3L0B6QGllR<~15P3eqSByBB>@M%0bp+|!#-lKhr(+wP)a~n6fK5%3zMjbwK|7Yj z2;#JCd#hnkQzPM|hRHDIn*X@GnLpib#e!81et&aAJ0lWu<;&4K#-k?1MG8(fmKtIB zS3iIt^t1d*$-w$W9E%aA@Pr^}SF9geAZxg?2!Dp)XRA!VoTG%C2M*<3DMgewjnqbj zP+vmdKxn)51_H$jXwG5EllDMoZZE=z(SqSMt_?dQNL;T{dfdsd^zo_V2jfn%X?(MI z&>wMMu{SO}$PiGA^i{>ORT2zNC%pdzdDj+^Jgk0Cs^2XMJhiyB1Ys=&2| z8mbCl?W=iM1a_l}RD0o;acRTC+5@d!fFwsMbj4>v!`CkD5Z}!+&d4>1J4aHGz8S4) z$F5>&7)9-qKn0)UYGPuGUSTgoolm*DPae>U2tpS$9~D!k!=-81zqc#s7%Cp^v(Z*0 zbOfDUEkCX9knWI<6B*e5*kx>}u+1I-F=u2N6%q0$3z+K*X;i^|D8sUuEga}HvxtMz zOc)Dn$7m+gIn|^>S|&y+9Ok?#yyr7E%+XfzALePoBNyAhuLVbeiO|6yYRE0R7hRb5 z7hRzDcPPF_`?K~uQe1Agy(c|l12sI|t^Nx$7zoe7U@lMtu8>i~X`+VMLc}We~xMi|F4{HLc5{miv%I0su>zm{U$w( zTyP4du<&)GtWskPF?TIZpv*sy>yxE~&tTE45dOd4oIdNPr8sqmv8Nw{2Z4{KVURSQ z<`P)N;&zi)w2;t*1k94=QYkMmh%Rj;_&1FK1Feepk21RmqBlGtcwV7CM>>>hQOF)e z<-)_s#*YpVTPk;POBb_ zku!15ULERic9MzpOl)cFeSC@L#K%Su2A+SPg`D9>I zYz2`wsaX_g$k_{6JwNT*-o308;#E-FLgMoT^rxfR4-&o6n>}Zw0?Yg(B#|420d8v3 z9xKwjV!f{c>6={!EU_?N7C~s5`ny5NyinzcbG=i61anDP^oCz2Vk7-&rxY1@39K0} zsy`~womembq^IpjOe!b)0Sj4tmeM_T;5RdSJw5saWTlV%7ZF;b-?3H^yPP7#xfE0B z*@=+XTvvgRhnPR7q=qH&u$*ttu?v@076B~JN{Y$w0jCs|R4*7rF;R`LQ8VNcJ0qN? z`9Z=7`P+`rQ?MPgWi%ma-s*MoEr2`=HMJpmAlTKa@XsE5I{y%>$-7YP2izkB?mKiH5VxKGYHmT#$zD6UAu@He|X0ukJzAxsAwbAAAi-eW)zxosW z@tvpnll?{F&crMDzsAq_;D6*>Sm!DR+$3jgRjuDz6kYa5s31`Z$kIS-hqdn?9%$BDH|E7XW)bVim`3()7v7Q~`~q%yn87WNa=7LA0idugTE9L@ zZWq+W|EgCUVm`HKE4rde@sYAU1NcAb=Z1_b9K928KjC6(J$z7P8=?vHLReuwmb&uL z-=BF`ycD0$iH50{c_}h68lh{$^6vWMW{%l^G9u)X{I!#Wu9KW{c|RA{sPzks_4tDa zY^3~}oL!6MOiZZAkd?$mo5CWx$&F`fH&H1z(yop*HEYH%r(fs3Op9)}|5qramy+ZR zdofQI%F-uS1RDeO3v};C_82g&koP<|4czRDDXSz$ob4&S17fP<0-Lr5d=jh9i+9Vt zB0`&n7nyU88sI1%T%Z|&QMUHFoPQNO2RvCx4^5HPWN||*)FyS5!JjdLKUFt;v-Sa! z3BempZKo8(|A83v)8q1S_6P_pqFx%Gn{rMWLeSNmvOqH-WD)DwD^hpSijbOC+!BJO zHflKG8la{+;$^Pbi=lCJrU>a!Q+U3dOiKAu2?>YK#VBHzkgDx{5&|e#k>+@^3BtSt z%g-JW^u@SJV7Wj^Z`LplOp*GSLV+*?n+ z>49uhN-t3D=wY+mZoeU2cBf#|9E)m8^qp$M+O=ivDy2muF6e-Ymtg2d(08}dt#QaE z6cNLYVsCVRD@O8C*_DW|KXjiL?miMe$v3hqkb~wzu>5YJ94(adVg}Jpqa=;-%P-Zz zRZ%5ta26NgMPD!e@Mu6Wb9zl1HH111oTf3@dBL`o2-6zZ$G^poKd5aF^@u+nzv2&8 zCu6lL4-!wFEOrLO<{#Zc-7wuP{Wor*|C4@p8`<&XY7Suq%nq_p?RchS%CG0_&Tyj(0MUk%+EY`Z^UdTxMDzViF!}lng!@=()b4~MbJW{ zh~N$|>vL$c&|o@ft&@Pps$lS(RTzAaWST^xEt#m_b1aBJSWH&;)#`WOln7LT|KJP1 zC?@e@M_^1-0l0E&uDYxm<2`tTs2bJ)#dY4fynz*!*#SL56vB; z6|}Pv)$|0}xcT+((8w z2_}CAV1Z*15Z_c7d8EMHeuhfg2L7l_#8U7B=|{KhqZH%dX^O~R;JkW>me$1JF)VCe zqu{cb_~?X@&7J_IciaB-R4|Dz!8OGCODSQnF~X{qdC2_l-oYYMs+odz2PsL)P)JiR zyYHlH`Ge4gkWF$#UZCh5VjFiPCFB5F>{UXJea#v=wqUTht7P)C5~WTNt;i~nU|GV% zDPFh^`Jo>+wQuN0gm$J9zrSQeJU1dFKBwZ30Cni(;8A-{7M4xdO=W=YQwZ>bzaaua zBCV(zSI9&m$+eM7ps^zTA*2RPVh~|zDKBC)wYJw}tu#C>)y*U=sq?_Y;%{b1?adCN zJ#mf7!1UbSiXPdEzJ|CT+>8iDO+fIP6%bI~3(O!{JwDt&E@SE>HY@Yd8LWF*g+RQ8 zw4uwjZD22J55l4r#Ghmt({!|{bkr$MrNLuyqVNqK3g(M$zO#xXW@F4;^wAS+s8(`( zyjRLmXHZF{01KxGABf>3CMGydSZ5O3E(300c5g`+kpMt{1A~OSz3dWa2cM55!-(O9 z51f;Ror9(JT{~wgbQk3#-=b6Ks!a8gHUBcNf}e)Ch478*5!hIj_MiZj(Exh;3B!-U ze!vojqI>Qj-q!-+IK^49#xQP1mk@l$RQR@cW`;&STbfb?iEwd4OG4ztRcP)|{_Fx^ z@@wu_-XD*2O|>QC@eu{etGnQNB_bYzCDBA8d6s0$in>kU5$ zk-XOhyVk=YVkVnZAEYzi!%_p<&CrrfO+XVCLgRlPhX@f}1v&E;#H@p3lPXzZ*Ifpe zd-pL0g-vmEYxTgVDz7J6me1V7dn^^XHpuD{xun{`UO%w67iR`$X$v%=`re&TF36b$ z@8*RReI!fS>=Cx^b!MR)Ev#L*v;O7!WVO5+MXY}C?-BnbWR{)NJQBYvIG<)pxl$mV zi&|Srd_vVt<#a{}zJBI2vS=7~R-y*uPpA)8a4HZ*D1pVg#vVy+lWZX>-0SQR!;ROG zHSB!1Y|`IjAeVq|)0I-?sMDlfd*3oi3LXGX`2xg&CdxJVeKtkAxbwiBhOVIhVfGMTIJ7Ew$T)8ci=Pp{z6 z;5m`ZZgBuq>Yj2OLPzC589s`1yTkh;ql<#6lZW}{arxqr1*@Ua-B5!ON=b;(8RXs_h1tvd z_4@u!ab2Pil$K%^+yekymOB;bfDE|+V22c3x77cTG8y2_57{#gYh+2vvSUSfBqFs( zG^_;w6VV4jkLgLlMqZOHy|$C;-16-{)p z;`r03Mxlb5pbOKEoal}`j!qwEX9tHzlgZ7&@xk%rXgt0$9t^6^_E0?u!7s@;PwhgL z2lx3^n1#$O&K|#_#i>-mGp1TcR8H%O zV?1A#Qm&eUp%q3gx!@o&eY>1S)wYp z(UX2OVpp{vm)B32S|s76hEN_I{D|5?z#H!t-|)7DG070vJGjQuFhlf&&ke3k@I1iMvELdV3^>dA?QF{?(LSW~1uwvz9F0Pv3RTQH)x=lqahfMR!bF>6MGe=nUZ}%}qzd+N&LYWEx|VO`^JwZcQ{lHfARLl5@&SprCJDdZlOom?EI(e9O1{VxAEU5$s`749))m4h@rr&3=xhXX2S73TE4l<7tLl+6SnFJ z^c&|lIes6zG+KFWt1T%rlqz6k;%xExx7p2nb(>b{$h}0C={U6k+E^%==hKO*5LF>j zmN--33?l_T=s*E@@Gj2MilD}5sHiQcaF6M&FA%7Sy})YL=yJy-R>TIjF?>*CoGs24 z_`-Z3BV=cZ^knOHgU&3b&WCqzr~6E8lL=*Map<*J9_b z=Z{NNk6ztBNYDR* zhXR!iVol(iFJsonO~1%KQ6oIE0|mmcJ6fU+^gjCQar~0(?&_2D!HSK#5GJt+#`f?I z#9%I&Zz+LQX+lXd)5GIu3)>k&O74jDisDT2Oh&7Y!us>@0`;CILi3Sbmxp%^C~Kio z2^0&YDd*S!7E(ihjsMo?$0PXQf8;Azg9>WZlzr7>wliG4@=l(lbw^J?#b!YzB_rgJ za9(CKIwRd#u6APpSLqaq}5c7eZTUMv=5sG z+h}}%FM)v<8w||4o1@m8wUOa#OcXKLVa$nOgBZ7nH-y3G5M(w) zoyQ=BAY|nreCF}&@(bK}`4vPcy~EWLB=tD0JB@m67)c7}2$Ah3L$X3-8vWppsGjx5 z{a@o3{XwUi8yCk{>XX0s`Yj&95}A!u0&5074w2X79{eE>> z!{tKTTI}AX){B1F9q@A%_K?1sBDWVw?a0gH-9msLKSNZe#s# z|7ONCgVPO5c0D!B3Y^ULk!Yc!_NyMMk1aGI%JhJ)%saIC35XW(ChGQWO8#s!>+ ze}0&$Wu|{1G~)e-v&f>A=VAIsMN({pKR_f6EsX44OkJXpdl?iB-d)pF*gHqiPV_huh&$8a6*CbR<5Jb9_fsad?JNV{Wy|oA)lBU#Edf z_-|WpU(!|p4q)gde@5b4yL>`89bg#r>-g_rEOLDd(vBNkrE2r6KwhK}^n==}n$0|% zE#?n*4=CGz22iBv>Y%OqB|n#7B`2YYGUyKbrvc*z4+ByQlg*UpF5kZUeXNan7uqho zlZJa5kPyUc);5*H2O=P7&pG~_qQM#oh@S79T%r=NMYEPr#?>0xWNu&XMR!@(66WGX zAlF!QUtna~A*`#Xo15iEqB`#V_+}nPzN2vgLTefoZ+1XncwC$dZf9~VhV|AsWAzFO zn9&xZm6!z)9Yw74R2yi#5W3lQBVP?QI*fOr#FH3`yK!u#*A*G4xspaA|d*Yh8eXM5qI9%p6!G70pGwIOwA%gmh?nH9y_w6kO9$sv^HXHAi)~%lxhxQvj6*M z3$XPz!dB=_*f(PecTLO6g@!{3s;nDT! zK@?dn8)!VTPWnIl1|aHjD^gRcXJHeB0Xkw$oFV>@GW=lnTycf-l5r*cH9bN))<{ zdczlp;CF7A1V`jE@(v7S)1Cm{Bt$SX3ND@kAc!BnZI_RU{W`5G(n-W~6P1Tmh7omK zmwwe=TaBl})hd}{U0zFe#0E!w7$l2}oMci{pp*%>=%dRqif@TVy%dDs!4e`epl#v& zN?f`!*M&OF(s4CpK~7KLvH{+XM^)GPK*P4L?l<|^c3HOIF2|7WvAT43X?}&M562*| z63s#{!Ct7L7y|Q3K6T-tL=wc7WT=v=Wkl|yI3u_6qyp4n4}`WCZ#Dhk(cEH~v`~qz z@<2Yfh$>eHEy)1>5P^!z)}j>blmI8WT9Yh+VG7RB@cCz$KZj$jTMERL5vQqi#pru; zK{hwiqd_Lz@YF_27-yuzz6_&-SvryfE{Gx+&yHW-t^mD{L=@Z{u;9)?JFI9%o@Kkb zTHPXn`ttK~@f*4fo}w+`;`8%Qf%Is3sul{`dJY|=HnEMbJ*%NE-+fWrh zW#y@HXlvm)CIF1Yi|)mqd+CF?iIp$dY* zi}|-1=IA2Swpl%JfFQ6E;`s@bkRdrc0QdeB!M8N^s1zWVFHVl68M!6yg^sqQEKzbME6mHI~tURLH|ede*qf8_X96^D$xh^PRL27FY(|yjhrM zhbGyx$9v%UF4nH^?_@T+e|UubM-OjCi$Sn_@Mb>J{teqkThSprWmfDLhz|)TVBK9h z-^pXEZ?T>PGU!V!3fi8RSF& zt!Pp7$)G08+=56jecCceH#|65U;|)-H;dc(<71B-7R5#(zK?;Yz5jZbRx?ioRlR)U zg0`WkNV*?35XyLuBdqDO-X?qgAjXSFZ#esbQX}TSYY0nF2vz~+ypz}y56BZXQiGt* zJd;G4`2fj(QA@i~z?v|3rZ|^SwH@{@oAZ>$(;XgAzQ0|ruh7B%hi@KdAZDL4y|a?C zX6(`2|E6MOmZa?21VL|aX^e^5Io?l&`93Guc=4Z!;$5)Fp z(L1(k7f>xxgsZfq^xt5^5e9w5G#e$^A!qbFW8f`S<5hU@oli_T*lWlc*lxTY7BVUt zE;<9KzVtfFK2U>3O09w$SO81Zf`}P?;sj`c2Pqin#UcJ5S+p+_?GDF)oD81`=)y-t z++NAQ2zcW&uRvIl{Dqx&`3b@cxFP_Ga3=o!hdV!g>o8vL4Zi_HHr%TI7JyCIB)vJV z_fD=S-{Q6PK7w!JN!-#=iaB6S3{8_3AQl7Xa#bpwZ772|e7z+PdF#)1T|F2{2dF zVuc>TUZf1Cu+hOx^#l7~I|424dU$*P=^WbgWJ0Q?#}k&6DMfy-7~Xc8wm+KSz7t~D zTDp`sd%BcC6}p`^*}Rva>Xk+kW~#)cx5jrRx1ss+Sfgk{XwN>tGiKGjon3G4A9Q{) zl}C|Nr$QBPB4{XjX@b8bh@0MIst$GPsx(5H!Csf+! zGe~#lE0khz#sY;8#m8BzI_QZ;K!M;5`C?RErn+@Uu_ZhV|%6Y zU3V=p9y29Q;*g9&L7!bc%$CQeyOW!B3|1d}7rZ^>xbOf0mhMycbrnil0e~i`)AvDnqfS zuxo(wTHFtXQO`1g3A~#{PjR85!l|6#RX{}+(_{3xL0hBqi-j1F!8PaRc*b=TX1iiV zIdB?oDu_jr1n`?csPtPMttxi^g<|({oRfN2+ZCp*I9!Ws+M^+~vT09Pzsv~|IQ`L> z{?E^-C}QAH%kl4S?l%i`hWUV7gi*Nc4Du*RQ-^x7;33yQZy>VX_RN#nvA`a;^DB(b z5%wfcQbrEKLrxJtL62(dDJAfqpD3%;o$5EtD=v}yc6Oaive~l?jf{xw^5!ZAc3v$% zt?CfKuxw-OINo|gEz}w(T}LXu`FagSd8$6jj@TN{M+lOdbrPCCU^UE0jLQbUZJZQ= zbYo7Xq(#(by8JH!7(&oVcRj>X1PK*rLR!YZxVyVY2PTBPni(t?3p%GZ;BFE&Ts12U z?~Em4Dssm=n?2C*I@Z%Pz6VQ#w!7$Wj_8l{VzTWGoKp62uy$p5NYHnHWaV9yCXY~& zOFszr*d@Z65aP`18x=9g(HL<=y#nSbdH)a!H?Kx0l4h;&I-dGH%;r*FMaD%^*!Vg6 zGuV{DVL#6Xy)I3>dRxp-_Zx&d$Z3QXyM20GJ+lbUma)2L!z)))!>kQT^iIj@9xR0x zoT(BHHV_|pn<%Wp4z@_#1}gI@8tj%}a|p%Rm}Nf=jG|RWwbdd9MrVq1*(3O%e~KuM zBx9rz#dD}q4I^HN84|vk&vZ&f#hQA|Vi8(q>@wQ%?6^&Rn1GI1yI5+Kwq=6O>Fhm= z8FsVvQ8Toy#*{Juww@JYNI+_znqh=*^&*iJ;|HZUBTl6+ymti=EAErEmw?oaZG1(U zGD1i%bpe4>b>l+_191wcWN|y-Pb2jz_x-rMdipeZHAkyL?Y^I!W~DMH>_fW3+$0!; z4G?Sb$kushXImsbkK-n4utH>+6r!2rR5X_@jHIARU`t_->0UX$tRp74o;p!S$B8&A z*&L+WG#!nD@p(-{6weLg7=290-Pl+wJ%siAZ_Ye~5jtWRPz}H_=QtH4@$PT1hz{R1 z$k@dyTQAmu)Iy4sy1;VBBJmW-2KP*E#>>8A9Jn7C>eja(v>v{HwgayG$A%lBtE}mA zk}T!B**k2wI)|ogN`~t7*Q{SlUCF>cwQ}HOyO__$jj|A}S=-nnfgt0S3%D*4 zf|YSsUbO><3<)BpFkk_Zk#J3|AqY=Ds7KsScvh^SxV?xcOnEhxWImc*frFguDSlRI z|Cd!2!vii+L#*4LF`hRyA|R{(gtaYIWVMZn+}(5#EC6#>7bmySz$=;;`Rh?xJ1OTdp8eM z*zW<;p>dWOrb2qY^=Kys{OC6lbFl72fJ4uSE~~rcfO3p-BN;ln34n#88LZ-jSHQck zFR*r3h=eDoiGwAiKz$aCsjzH@rfpeT61Es0ZDKzyfaM$c7+F3a6%=hm&S@^Em9qfDC zyIB+WA&uRJhK?hD7s65U*B;d>w2DpfQz_7M{ThXsoBMCtQx1ad1qE9mzy5CZuP>g7 z&~w4}EQ`$X#(XBXT&FQW^u{y46j@NDj@-E zqp`4y1r)l5uMz?v7PQG7qY#fc{5%()HUNaWU5b$qrZp+yGeFTzntzCK4?S;ux&UGl z{_lt7M#HFLU!LFng4Mx|^5vt6ptFt*KV@>FKwdO6X0Xf-`;iyIw632p{7>tSQi}nT z$iAN%9z&dY3jqz60z_meU(0%d?^@1EDjq@~mYrluspw6=GnjsG81YnEawo25X847? zVrE5v9?RyKA=7xQ78|#vSG69m9$#S=Vp_rcY=AK=2ZXpioC}u&!nHGt>ID+C5|g}T z!cr`8_oH{n~NK zdWTzvfq`j6LQ344c8uwB7q<*zDpcZN?Y-lz4AP1F7btJ=u`SRJOMH1ZA01j&P_uK| z8Y4YA9pB&+vIc`j4{4{8Mm8B@XVW;dScXwxGu3E?R6;c!i(fkx5}4kr2EbTIMThB( zsvJ4iW4XDaDRG58&qD2Z-XK&(og;GySMcfX(-WW@Ff4CZcgy)EVBMP-_rhfq85(>= z1e9PCdP63!_ivh5aACFM>-x)=mOX*TwGb*GYd^a9fn=aNqH~s)^$%0|R_$P`uodoF z;d=&>OcF6s*5HF&wO3+g_buWi&J-|l%J2}poes-$G<*kJ3(>cfMw}hL z|9XcX3mWEQnyHR(6){0X#|H<_QhpozAkBGPt3%mEXAWhJ!Y1eJ#$4qCnWq5_6wBoB zqUG4{7As%@f*Bho1GO-R9qvsN?+*7S^n#8&Rs#b29oq1mqXX-#`~D#d+Li`ew1X-a zH80?@?f346%R00pkg!z1MV46*C=RTc5}U&kYHi956BX@G)62N@b-qQ`-G(LN^rP$T zJsP59jsnCQVtbM%c&t5+!$JXbPZr0kxXTY8(xHLNVbc4EiTy|G)p z`~PX#wyeg-y>~z~D%6a{5a;WviNc?lFhsQ*8~W+(0^C&L*jA7fgIvS5yd9ry(LwZ8 zx-@@iHwFvt9~fB09>~DoDo00vj74f-4Uh|>c(p<|SLG}X>s?(l9N_M{W+`h9%~3^M zbO=L>8&)v`$`+?2Tai?SqNUc7bwDb-PA8ZP+-L$%@;R0@DuRFro0~WL8mj)!?~R*j z4tAzJf@*;+g3Kb#*9yDLa&0HK1_%@??gUt(rb=1I zsJx`~RjXtH9&=uD?IXe540{MNsqj>IOY?TJf{)2BpI7XhpP>LPI|Xnc6DySRnCj|d zGy#4%IT!*z1e5n0JWRFKYZN=Vn|}DPJ$_y;sDLk?nP_L{icAYa*#W7Ev4rO}DvR5E zP?w^4&jN4BWm07~jjtOR#@p;>)8onHy0qgp1TVjXB6!3GMI<5O{d?XArHjZd`!;!v zGF2>JM3(4!Hy^X`QoK(~FGc3#^Kn?VCA}u=rzL$87n-F(+$DgX?EnZi$OB+po&E3aG(At>HPc zdyOV+6*-k?P~ItZv4?v0{B`1`b5_M*GZ!~oxGBJ_vM8bczR@$nCTpPe%zL2c*Yat?7Y zDzb+SrD(RqfOJmX8Z?NVTRZ}mwi1j5fyRh)Wu1#vR*Pip9#iA^SAKAp%6QK#kX?aF z_?+KS0OlQ3ni(viXqgu{9?Xj<3{W7lo@;{(wZ(?aR!h<0GOx0i9(p{fgOT+Dg`*7J)PKSyUOv@NDsftGmuO$^Ro7qzd-q zBkb_o7~*P|J(9gshg@9_Z$_qZb5GWP-=zBR~?&ncCXFyX3Vh&-Y7g)oZCZfO^g`jN}Lce6P9k z%P&=`JXkI-j(QxX^z^^1Hp>vy8BI2@8L1JhimB}rHM}3ItMxYKL`Pes?xol~yRREb zYj4Od$hhCXtm6xU9|H;J|7K8ns=&Q3~u+=+kmA1v> zE)fv1F1j}KD{>KRcjYNiHdJEO0GIgV$>Vmz1cro$%$2!(!QLHE9ny$}v!PH%%whwo zlTeO;oAHgC6imU`pCI8(DzXEC?7OohJ&g?-?vpbl`}Raeo-E$1$H#aTniFC5oVAiw zsH`)%`bcEDV0l_V9A0ql)^F+@h>U6RR;b|8W#@G$y*entwL}?Q53k^@Ln8D`*2e(H#i{_fW~5y_yMiK7)KDuXQ8VVZRIs3X6Mk6n z1k+hRioijeHT#3qJYiNHzylOT2yI9SRG%oyZ7XZ#Z<54h`{cW9F>Cvn5{kb9)ccGE^C0;wA9MP{l2HS_Mjx0kOG)=cexonS0%(M&h`YSk#EI;nHgsu}?p1*L4!U^N+9U?N7N z)#Jd_7=*>vXq&-NVqHmcyaBzr%2mhcx&u8PPTbWHIhL#0Dfeaf~7x5AYtC(wsp6hs7JEiW6R*JeH9>=ba=pVm zFGZ76E=iiXgMWr7R5>{8e!+)vCmYXso!6A(wXW%XcztBhwRrNs9sQk!Ja@~DDo{y*Ivl+N z;P^HsCEkWSYG{^4e5#$9G3XkseL_IO#W#(o^IdUZ3OnxY3>9?UZ3J;vAo@YLSFFBs z0>qfM#&=$<;?dIZ)c8()E6v*OJ9IXJQn`UY94cOBV+x7mDgThd%EGl;K$=RGhY1ptlg?7EZRo70E@c+7|D}Fw#Ci(o?MafGS=YDC>7`qfgqt7GkW(M+0g@Zx*Eu zqleXUvHZGvT+XB`8imUY)~;!QA0HSagxhld6Fw56vma4Wwsnd+Ct14!ebLCt6Phi5 zUNa*4g-m4XBFW5x4~zSU<#`xP6nC=TWwc*mF4H}k=kd|^z z;<-i~*}TK+WilIQZmJVJb71u0lN`Q7T_3v-N*sY;T>jTG8V3JCbWw! zlpy>L(NrZZf-@Tu7H}s7Fb()-+~6{07zu5FCCDOV=>|=MHIuW^E_^uye4VlC*y_j| zD^W{gC3ES;lzdLZxzZFrJb%Q_LW2G}X=iixf#GploRHCWRTLj@;hN#b^hk{9eU?x$ zL$A^AR*l42YMW1jOOT+#DCzQli36cE~2Tk z#eO9*Q!W%HOW^ETu{+LbX{);)-v#fR`7T-eA?$eBJ@+TgRc}6(xj^-P}<+)Ivp!2rboo>ceKKY8W6jWr^H)V zFlLB9Yl4-Eb-YyrDhpzY?vnzgJ=c_P*b0+0$*E4=kzSG$h3zzFG zM~Gd@AU@Frd}(#Fv#TdG{zY@&3%nyP5VE+jPCHC6(#AyVgXzE_2ZHc86i;~ucY<~3 z=f7e%ZBe0VKC*+2QrRW$Z2EV1bXFupO8|gs+5u0jcKGR(jQ>u%7K0JcMCoP=a`hGb zaSyOGmO;wf;B-uXJAC|n|8#o|+}tgT2_-GvF#4u&>#wHoUd!M&Op|H}>0aI6T5ofT zu;RAX_z?5pxyO(UoQk!~`|;q2VTv**kGS*tL7u7g+=CEk3Etw|o&hfrO6%Mp_iWk% z0LVHXA!T*dI#8nhUe2&B;8mQOY}p0FR#pPAozOiJ-MVOki$qaqkEwNG5IBPmx|#+!Sd5yy@=N{b{@X_yc63TuadeKxsX( zq_KCvQVjkRT7pw`ngbuX?*FpBWBh!x6y*tsKQqH0|A}DU(pp4UZBPdCf@i5hzv!>6 z4b7!Yl#rF3KJ*!K&i0Jn;6>7~hmhzHPN|_sBHdgI$@_8ViP9cRsczRY?gA%mi)<$i$1H z1H;g*cM?6lsyjH8{L+^PtkYg6+oHNiR??L@V3$=}f~ZvT3vTMs6{fdbpq?cdkdJ8Q zB1Q^PA*n3j)Bvs5Aq=FTk=31nM&^mAFGDMc_#H$7E??7^b?#D%@IheUErvQu(YwxH zZZtt)?VHT4IbV1Wr` zyjN|ehAI}g)gfp;Oy1C_mKFR{+JkyY<3v`HF8-hs)-8!5V!AcSqX07EyU<)Idb1aa zAd)RrPm+y;lljB_)7|yk<@WPErm--BA%C5|MK0hKnCE%=D~j=m-8h3wE}huskIR29 zH&=|ReVgKP@?WNOk#HE#W-<(Gy}Vw{?`GTk+0AN$M%DWa3)V$!M{+wtZdIc+zx?{y z|Es%)fBR4C`fL1pyn?@Y{EQF&N4|wct4t+}D0KMF1mSQNCjXp<+|ac~sW;M1%u!@P zJGG}l>n3rmb9XK#3`L9Uho;@~=@_v)?ceQcG(e)h{&twx1I1*$3Gn^cj3v3C{*rlX zBB8D4(5NLUrFP22;96Q!d?vMF67?ljPvlog$Px)3L%zO1;*>I#^Wn}OHmkcWaW<6K zPNJG>+l3xJ{FC6rxVw{k$Wi1G0j01=e4T`)3n%?`BeXR1s|76qAE%SE)2Jk)L@Rs9 zij9zpg81nmQm#;5bGRt+m`NY>53UBNFmm>t!5=Aa6 zSODwLI6iBe7NT+5!F5nugrYD#8HQhq*+E~{aC6=6_863z1gV4i97_cFUTJAYfg(91 zt0g+1jT?ZVh$O?lEpr5Vw8~`Sa7YHAQR(q)%b~y)HPR^AA0W&|Bs9{bpI63OriIUs`lHhr|Zz=w_BREOsOc~%8HFID&YV6?gptnjwwUm z5I)ei>r8p{&->N21D8P5l~ci@s58*JLlKXBlN@&$1epa*6K<})et{hp-l3HhI=KW3 zX^^)H(&}?X5VE5FhAVOkS7hv5kyAkP#YBT2@(7nWcp;Yf!3G6@oisB;Tf-O*Xs3@E zCr2;C0y7@LgJpanBt9AZz>}QL-riqpW>XTIC`*<(Cip~!jcp* zwz`SCcpqko1?ZS&91L^)1JtwVG?L*NtBTouG1Njw39lKm%U`gTU2EKxS(fL8De`vq z2suy0+x1e~%;d1kGeGW$=`TyH3WH}C@x+2DCrG1}U4gD!-dnuGPEc!a01vaHBhtZz zd3x{IA^rQ}gfMvHZOTx1Hg8TM3}ucjFRsVeCszjti?b^l zF<@u}6kr0(KEo+P=f5||-(S9Vy2q7e1MQB(ew>k6doi6Oj+yI zccbXE#)MF}2(Imm$n4~u{Fz}d9U>yl+%Tw7Dk;tCJxO9L@9WD4ovYD{5#(nOK&* z1KD>PT#r3W^6^X~6*?$0HGhOC4}YLo1_LIN&aoui#}Y@fukiAG??=mx4lyYnJL^Y+u}LJ8VsOzAlo8c&3CU}J%rYF zy{0~)``4bzCzpB0+|RzbB>ps}x%dOU&;{-={} zhb?QC(%H4RP2`sF;e4~1f4kU9(`ZMsW&p>TXoSZ~RRwJ#GdOC{^3H%`EZ}Dpp$K_e zvMi2cXaI6E)Hb=ZF|ruWqBQNns#H2n%^olE;vhLA>;L6`vcQ9%&`@sn2;&7_fZ~G% z9t=mjf(Hj<$RTAMognuTS}C+hFnBesevTi+y2(S=VgqD$=|s{~C+|1ctGoGap^dU> zr-g;zgboske-L_TnQ7lZ;_p^HJ+B-kw-X0llFZ!*>YlSkj9hKa-5G=APB)*687zDr zIH18>EktfS`%nv5|Bl*KdX0EkNu0U37}~{Kcuh;P^c$g#gc*3XW^ZWAK{C^;tESAX zktRup${kuX8#gdMgYIPfSC8wjs!H8f;|8|d#p8*MiW?@&4JX!aH8NkBTYchv5WjZb zVkccg4!{098ZN?`|ftBbZzF#nk zREFLMP7fGg(uX>gU{&18Z*s90@XhP=+}q{)e)A3TmK)=)#Jl*wBnn!uQLuq5E~i~brF)p0qsJjDqh)pAxnQ+wA#$iR8>IUndnE4OWOpcw6;k99=#MZ3Zd18H zpaP++^UJQivoq*G(rmg=4;#yFd>!d7Bj4l(We0x8TK76je+yckyUyRBIsyo%C=kn@{x(x-Cw+45A?)+7NvP+HKe-k*{2W(ve58R9W9t zMf6^rT3&o;6bW}qc0m=2giW52P84p99Ouc4yKe#p%jWjU{1mm}vY{G9OQeV(%2m;r zFp6I`E6FmdJmoF&7PP)R+08mo2uYb6*P|7%M4pgz3yCet6!;RUgRVMU7cy|HV9&L7|;+)Ovbof9>emz-)w`tP!jeEd8{Hp@v}a*hagP|M#iJd~kWqd3rug3Z_?$t_3xs!(??GY>nKwv# z80cQ$!y)YnRd|EV-17gN-pfJi)baGukhu~?n5VE%VRhMT30C!@*m*l&-G;Ui-A&or zc~MO-RpqIm1{Z^OX$iB7vT$`R)I$(zNUlcv4S$G`SxJM$qojIoq@o}ML2MGG zE32NJQxJ(CBr2k`O0mJ>c)9}Ub3F&L0^H*Z-=#Y=E|E1$Wb-HpiP>*UI3aWk3P3h2 zeUo1i@9fPQa(zHGQ=9I>6CY_XXCFWrm>wIRh{hNzmSS_;X_sW6h=Tr7%7Wg@oN>{> z){aixO7GF_KW<7#*cuPF#{Lq1mNnkta#bc=r$$ieF4DRsXpMJ0yvnc}hOfF!7K6i8 z1zQMDQ=#lB2y??E)0q`p3AquRQ=yeYa5}G)mt0+I#^rwwf@!k2#cb_ho(TPy(^th5 zaD*jxXV|SisOKm*U$GBD;o2JN6`GEMgcJJO`>Z@~984^k5M-2|GQ*zkLgUw@Nt<-p zWB2oZr4b!Na*k|iYItiy|5TVD_|=&#ElLkQtqqtpG`j?G&MxK~*moSam1sRRsPcAw zrm7prH-tIXB97a`JdB{r0TR>cbuceGo|6I^xSs_l#55l=K_kHrtcM~N$f{oA2MCG?_y7xj^5z3mYd zNuLu|Pw}pJstx&fEJbdewYq0Tt*-J`#9^IXJ;2zwx|vL_u5RWBH;eJn*chTBTg*}S zCWN^MfnDpp7GF{fM3gj`2v+>4j^!HRJ6WAay0rtx#Bv?yn|g(}Uq}2-o2kE9HIP(q zXH^Fp%Nr&K90cXW*>v^0!VXCjhY=&fgo9b;O?iT=q)RgO7m}kS-%eqo(xa9k{)kEs zl`UQ87c$2QoZSNIk6qscS{eP$k$8!e)KL~Gu8FmRn=Gi*6wkeDDJ!H}#pFW_8)C;& z&I4kGtgR^yT++^7sb{3MJPsxOjB^};;5WC?YEf7TGxst&eS_jzidhY)IiqUo#TJJ6^u_J%8bhR)0)aK^QRFL@ zG(wDneF_oQ3_@fsv+vS;7pfrKna;60RqSCm0FPbk5K`5i(-Hev2UZTBi@CH~xJD?7 z12eHeVqS%|xVqz#={Bl8x_`ReA|D&*EzGqEq!9{y>cKYH5n;)|4!H*w69~qnaeM@N zV^LcD^fccPTuw3be*XPx$yZ{)GpbTXLBZqEWF&`cXDxN_C@BU-KpDKzf2eWe^LXhp zh{>WUrdm?@xmWjyvCpYN51vrYfvFD{9VKw zkvFN$pY3Jlr}(4gNhnDk)=p9S3Zf=B)jQRo$o|o3tcq6S`p3fS(f;X-HgIad`TSdG zcM){18A4eQp6W4n?vO4p@$9?dNM45Ii`OL((GEti#@*19{-tXXkHTiNd+Bw}A-Gzn zv9KvN79X4G*RRwY5i?;kVgWP*-btk}))Afa zfMMhiS%1Z31hgJmSI$L|lI`T23ZJ=42c$Dw@jndeis%d@E1|vf0FetO9>f4muF&QB zcrm}{pA%$quxxM^m-lnCAr07M(M{`;BAVDXo0|c!!NYR?IK}GXFL#f41MAaT1l@P} z%sn(kOkePm*MeurGHt)!1;l?5su<5@yU!Qdp>7X5@jYHd>uZsrE&6i)6rzdq2Q8Qy zRJ9IMmMen`pf&a4akPERa{p|NrjlMYuZ zc3e5V5xx$_i!rO`)9w4?KQ#gV3%7Jt2a>6>pDf%64P&%O6iA$YZ zr&!?vgi~UV@GvQfLi;v=`o2tJhsk@CfBqc8EI2?jpMZ7*TN&4=I4emEE<%XK;F)mj zXcRz{h7Y!i#oyg4XJ->9jS2^R6A>1^VGf=w^L&|&z~bJZ0lE3WvI^XN&<(dZ2kw*fSB3~p zX9dE4OoadN5cz66j_I0<`OQ+$9xJhH%U7~#bQuY?0>(dp8Yo7=hI8(XAk9V4DOy{^;H z?oI2RF`WFG5H@XPnec8`^Tn^<5V4xg755g|A@HG3Iw3r0h&W`1Q{c-z@}MxT7!F?V z>1$c}t|q4X9nq3dk>Sf7C!)oKkDhh#kDgyt=7P<_qTIA4EU>Jj{db7x-r@l-Iqu5k zMT02|jEK=@mOMUsH~*jSjC975duFF27WEiJuBN;rNhuuq-)VMGrtS*E$AFq39z_FJ zV71r}0#*(7%nZLN)!44Fb4Q3hV;=f)^Ei9DU!egS8%oNIGwA~&f3!P7;^bFMvjp}| zV#q9eD0R+$@YQ{Mo%{|Fiy@U6&SJJt+{Z@dHW?+Nx<>5(ohyJ6ms~no+ zmuQUc<_+) z;(7A{a9HA`M!;Pm7nVjl?Uptv1k@{1o+TgtR}StGCI@KXy4)aP{cd^x>G3l)iuH@W zJwxvyP`V}Pa$~QMLKC7WvFe50&2`Rob+sx(<$}!(N$RN%5 z4AGV5JvHJOPBh~#y@MnS6jhER8zwJftP1v8FM(y2uoA%Mdwl5r}Qk6l>rR`(an zuS--&d>6C8Il8|)Eogp`Jd+RUAKswsF!@1I+>->%0zsacy%f>z7_f%%?2(Cm{XZ5@ zdb09q9p|J_ffwJqUGzdi1EL9sT#&@tryg%`2(9EUB_Rk+b&d&!l#l&@33u(L8f?Nu z<*Aa&_+8Nf?Xor|Y=VvDq{*6h^@oKO(I_1IfctXPNMeLdvI3XBtgkAszT}B7m~EtrPDXGNUspI{brzS3wVE zj?MUN^|0jZ!oRQAzY3`0BRG>s1_i}doz9hsmQ6!B1a(+>u#987p4|9mtya^+0|tJU zx^In-UOwI2EH~`NjM>RBe9@2W9~*&-96xTpODyp0tKvZM+~x@!?rQ|u@gaBCEDFzV zQAQ>4qv!@F+jg3@B=-Jv1vaTl5jq+5qu_?S;S3o-1)A3jsfDm-nZsoc_SpNj*tK>i z^wNYmlypLf=(Zrf&^U*Tz|OCM0j9NlhQ4s3AC2Tt=Ni1`vG;UDtcM$hk_;w~>n&Q{ ziuPg8ZesF|S4Z(M10}c>#z4ZELcmDDG(bzjU&3GpFZ$R%sI8lKE(^&m}jvlS&SXRV^gr-rS66uU-I(^ z40C_&Akqdv9l%rqAysp&4O3|7Ax&fx^f&$ejXu-t78b5q2^-h60Wjw>c6L@B5R{$} zuPcLfw-T6U&Z595Szl1@v@JLeA*m^c9Io!Jh=Wv0H3v0t559GYa=X*3IbsBaBsHgU z4N#7(nd=83M85O=5yqnp*cdl8*Y5R!k;2^;h?({yAZ9`y^dW53RN`=QL{VtzW^&Fs zF%A$YvW){FNhgz_!k`b#mGS0PhTy|7N$xwgNp5@`Yc%a@0xDAMV?rYi38kUHexD<0 z7}z%hq{tBe@zx(`e1?YPSfQ5H0z)DRuuSsNSKJ}_UjO57o8`^lNRYHY#^cNN!#mjH zw`ZI60^LJHO~iQo3gtNW7oVRVuh-x1V|dddc|&CgbThyoRqCoSm8ahjGEIKQrJC_x0y90xdqf<=73=`6#S&w;4duU~a zNIr^SW{=Rw2<6xQxq&{0mZoLVR-Y{YJB0=ZQM#I- zO6>8szUhM=$_Mg3u2Pwq;75P8Ec9Jjt>XjU>BK_d;!HT{*<~$@W_z>xZFw!>vgzX8 z9gwg@9q>nP7Js&G%@K{s_y$BEM%2_|Jd6AuUU-MC) zZKnM`R6&^k4R=KHWNr=6usGJys_`{#fY3Y9l@Z+4qyPy4q~=kCrRc^vPH$|euvysd zc%;7B-1p-6cnn_nZ`Fr&eOjNP`CYu}f8<*&lH=NxSanRZ98&(TJt4%1jN3E?UVe@l zNgj8fns#NRmxEcLl-qQNVtR1M@`fqXV&J@dbhcUDEyEn$*~9vFwfK&!GXmm>hi!o$ zw@C3Rv59{^nMg;;)PNuxIFA!l9VNvJ6CLHG^(nKQm}PUhhVTjcItVtOL%#Wjd3nA~zS;K78yx=Q^J>B7biwP#v-e{w4_E82%Y_$T zajJoOkOL@YfJe&KX$;rm&N|(r5Z9Lg!A?~qJ&eFO9jXW^NiP<{lfKtysUP)H9m;V~6 z1Vp5xJ`V#4NkC+LZ@x=j!&2a|KoDw)JsziOk-)e)`S`$Dxy%sX&cCCrF5EU+H|+R; zy?l>!1$(~(IVD+_seS@m7}}}K9N;^VpUtNA;HOyPWF12&L65@`DG=k*#t02s16g%X zLFO6bJU6JuN5c@_LEMrD*ra=7FqfctoNNRq~>&NR!WYNxYh?3&A96(DEK@eq~mZcToE9ElEa`2<(uJ z?%}u}SVIV-<4iUvl#*d)hCruv9(A_7fONz)D?hRpk1oR9hLFWj2V_d8L&aytA{s;| zGiND_qSpFRPwE-mR#;G7$_2WFcil-Vx}HKASj^V;dlGKXRY2({=5mGNO*jt_2<+n} z=5E&iPs3`k5XJ=k7~V(rdSEhE)CIo4cy=-BdOyyWWg ze)g;084SaMIa2cLoV~Bd#NYN6yRu*IrkbRr;KuFe)6bZ(3ivLUwf3XL$D z%h{6Lk_^G(s%wsBh_0|LavDk#QLU?!d5(okxDIHZBAXl(L{iiTB6{$ZZc9gw zAR9DVfcu6QEuap*Mm3-KtjIq%t87`yvEQHaC-V=`K{(UCG_9jtbmWfPvdGP=8DNI= zYo&6{uw{9x$y1bxtT4r4y*UArmakXwo7XA;No^&Bg#Pe`6QFy_0a7h)IrReXzbf43p8yLjIM4?YoX_Cs{=ic=iBM6 zXw=c31|h26sG{0JM)nypmwpAM>h8+jmRRk^E#z`cg?YzyxZewe!*VRcK*p&?!^5Lj+d120`ewTrPF)2ix)z&exTj? z?sx}s&Ouj|M=md2CKCmePgyf0r5MXxg1|!MqF6(t?t!fmQFiOx5eP{|F=+#J5B+aj z`mX(KL@w&+7`l_8ChKv2zgSv;!7y@p5jSC^YFCu=R9;wn4(vl^B)3FK5CkylM4=1% z)iil<4QisOs60dwc5i;RhB@UZFZ&$Y4;eqN(d2l_$?h*|$m?UwP7Np4+bZD|v(CLN(xwe24-*^u*mfCZ43x%^ck^gf-^ z9`3*ysLvri@Sd`tF=3!2y}kIUD6&e}2A=3z$`ZEjVXb)VgP#Gnp6p`=fND=H?mk%dqIM%H5&5vZ&SSh*}=_k~l zCToT`6eLa-r**jIMzFb4K}kE-KZUI@Xrb`&{uR)!pJNuo5tqb7WGb6Awh6oB zI=;tb8>r_aFQCz8P-0OwLkoNyJC~ADt*qwb11Qw3sCQ=Ar{EstdQ2XMz2*3uH0H}0 zesvUt_v46p!bIcz`g)@es}B>=saFY|DhsuT>qJaxEM1m;-NpDNwaV6am#ikDbwwZ7 zOMjQ6%xX-FuG2e-ZuFrplui+%BhYKjOhJewt0+Vi~DMPSZ;M+@@Rv?@-DG09H<`vhEU; z4iz|bVvAC4^Chz^C9ive2+loQv8p@y2jm8ZHJ|29JId=c?7Y?(rY17kqA{sZqsK}M z6-3EpZiyO7hREF`&K*l4G0H+Dx=vqVw2}yIM!{qUX4AVfbe|n*7q|c%U=UY+D9D_j z-CMKfLIihG22W!-I(NB^(#&lzuC${>H9>x057^s20aG9T}up5bY(t})P}9s@nNq`hZBhgqYSH>-6BO`Ooo)l zk2Sj`;zcs7A1~fm&_C&1JAF~!j(P{}tjjqJ5}}WCmYPh~2-xk&j{6VBV za&a%o5wgl?LH#Ki6{p)>%^!nP8jvH4Nl=b;CZ-HEzhDtNJmt~r@`sL0vmWQo}R6ScMTA++34+v<$hH?WH0$!H4)gen;=nCKl{ zzr%n{Sm&D7(K8-u6-fHJg3%`| z{>kKXFaoujtVL!lv2T?_0928clGVL1y_ar@Z7k)uS-@$~ii=0K%PS!SmgpvCf-;2A z37FLoQb+7(u!5xeAA}%psrUJzm?-$A5DWqs(#;%hQH}z)DJHdc^N7`P)O#iGv^b?r zGl72^qJfah2pCC3|5#3ZP9F(XI8?=GPx06?MmUN^+(&Yn(jr9PUHlqDl{t`lbm3>G zXqBxh1^hRp*A6%;&FqYjwS0yVZY!c<2D-dcm`_~k3^3DN=DW=F$;105om;vx``Q4{ zgDABAXfke3;WkD09ol=^k|)X#EUp{DBMa>cxT22ih-#22usq&N?F7Zl;!5#RX$~ZEr}zha2KHnH=CMizP=|p(E=(iWI06&UMAf}v0%AnL5XR!-4|}b zH+)<_-QKn)o!E9I?`@L9`!fYug>!=$3&ll28;$Fb3J7X5&K*u{O!*W(9VXa7Fdu=# z4d20)3Pa-y&Fzn}e}z=o1)Bf&EB(saYU*&OJ9d{r@mPj^X}6cjyG0(Yw(Rm4921A< z8&u#NM^*I4&fkhU7!UAy7X+DbT_43AxXkD zOA90TX8Bj0fDFhnuzMv4gH`$rn;VCU@MuC2MlYTo*RO8Z+vS^U!{OjLj@dXA4O3(m zp0`uTexX@30`CC)8KV>rPTREIH?pTzBw$eJYKM|f{D|88XtvedRuM^E>6Xn=y2 z&B%Q)Q3eKqmhU;z)#s0TJmS=scT9zwagqH$5^&y zsw|QmFSxI3rG`9{HLpU>|R zFnDy`?hB0^69;X_wuZ)lEvg7{T!*5S8Pka`Z`W56fE1`8B9E6d%jiNcevSGt*m<~( zHM*Jp_Q?6L(-?9YKR<~9z6-)KMiubaeFD8bG_;q%FLH z8gu!JlV~PV*k9=j*K%7BDA+m#Ph9V1vngt|S4-MP zA^Jq3@|O1%8e?L&;q@ORIuga8Nr@ffC=R%n=V7@$EyctGp$XdGcQU(}$Tf6+4lZIO zKicai3ERp{i{vzELwVUIkIDhDJ1AbH3HBy{Qove6)B`D3!A;CipL>To>*+rsDH53C z^#f`nu*e5&wFU)wWJK!?Ui02-qd>(izK_k@sSbu(8YBb=YWQ(m3BCW7gIi=s zV##GN;$8`A5L#g%FUiOW3uP#dKdh(sz@nhI00I6KzeV^c$f>0gx*Z8>|x0YgTt{+N~?{HhG<4pv@{K$Mit7=w^DegaUpXUx}z%5c(7K|!! zO2b7jOlji105-%U#$q)cgb)QeOgFGWa{joi&Wu)8ZEIWbkp4h_1dkkV=w?ea_NI!( zs=bt9sx2MpoP~u4#wWAZ$Z0aafP0l&EXkb!w_3Ce$sAu*Od#A z?ZrL34}I#;Efz%s8hFn`lE>(@fC4gglFVUvasNFO-kS1=@#Z3=Va|6bTIr%9T!5+` z(oV$q@9!Al3$H;YYE=l=mch1gX?)gYWjq&RZ7~C!vcDMMI#XSEm%^5^q+YJ|q9s_UCy6wIuISYm#CW zii3Oo;QQ<E75Q|IHfx#a;RR8Do<>I!Cq7=cA zEJstxN)o*oScn%)y;-A{i5MQyzG*%SyAQ`B)KbBpc(V$6HidQToT5i-Dc(9~5YY^k znu`Y?U2VZ2t6F}b$YhN(V5g5lqZQV8X=_h0BVErKLD@%c2}JD6m1HVx*`@jfU8;{$ z4RW>k^&_@c!vh%xk5=W745u98qnM7CUO<3hJ zZ-dL#u3H7YDNUl)+jFL(IV$cl_^;H^>i_@9PJ!lf`iA+B4uDm{#bx5lU3`sQd=+=` z`TeUF=o^R!H`!L_Ny&o)8&Aw9nD^12>T&O+8zdh=+&%~ ztFE#LO(6x3L;m4VkXq(B>$!bYzZGjz315{aN`nM0RF)+Yx|3%%*bjxV3m?L<%Nsrt zbk%4k#iy>zNnY)?y|A%>z(Z1}c=0S6lqL8ZI-Z?I<> zvIWrv8?Z|Xy1jy`%R$XxZ~bWtR_`FSWK$GexCJ(N^hTugwv3B}93e#?jfQ;i7@hW) zwP~ggp9#Vrx)^t)d(H)JhcriF0{CdmY>|-e)UkJRVtVK150*jQ5&1>If1G80O;rIRd&du6G|bVYq2`6Evq_ zey|L-)q4!0)er71eF$EUU}p&FByi^J1BP@SU%LeN#;)|+dr2>}adkdnghuKKl*)>yW}kuBC& z_!XI5eRirSP)yN~G)kg_AUh1k0wsHmCe(lw5xg-ui+n$R{{%?KPfwU7t{H<&2xZs~ z0W9)?9CO8BhY3S+bHg6@Yi6!FZr@J~11=NToX}8la;|us@;UU~3Z)Z{_8>Bt_HcgV?nPJ(w5AWIH|RN#^}DbHqYNH>fq(!^ z%Kh0Dgd$&J5kaID*~Vw|tfa~Kls$upwKn>5t}0IF&qp`GpVKxE zmrP;Bj1a2gY7lj#p@FuJs`#$oVjGY#OYCv(mEu8$x%;&&S2K&h%?`1X;f=T)frSJ@ zq{%4%r~~vGw?Qf(k=>1o?Zpf|!n}hSF&uwRbNOMF>Q0d%J#j8&&|#*YNip;@OT`Ul ztxyQ5d)vrv(X9VhpWYM8^C(51MZQKlftc)1qa<&dM`2un;O7&;w$9DJZQVf&+{O9W z74_?7I3i9}LOmmHWGDo};wUSxt)`4V&oLS>uf9ma{EIG;0q8H;3WLqQOo>(5RU9^Dm)KH4s2b|*#l zFw75znnp3gE#Y`_pQT#}zqOI5iu%#n!njsU7zf|TF;!GjHqEcdVa6d|O!8TB#JTm}pG`k&TZLe{PR>5x0hWlHBquaT0r4<2$?cR5 zSjol$>7DCS_}|t0T{mBCM5h$8g%LU|Q#F>}sP94V#J(K1rV%RfatEs_>2fI+Fd3gL zN<7QtPKC0F`05#|wPJy1-+gm*H%B{4N(IMutky9y;M%JKCo}sNMz4VNz*a~&NeB}o zNMGO)5zOR!>;i$8d=ueNm?~c`(EfpcVpZfA+WKPSdcK%MhEZb4%zSu#z@VFS=;-jA zm+x!fIfx`d(685_ItJ?(B^{2fGsoNCSunSIqfD#e(gq zC$m0(Hh`msg|?zamPIgdi^ZLoRE9C2zMy~Hyrd3t9lT^1hG3K)BZ|umr>NIg>$`{f zW+{+W2?sX6VS+KI7i`?)3&{s0zVLA5Ty|mBz~EviuFYj57_T3f6S?s z_-99RR3p*%%A7O|wkh3yhct^0ry^{f_zWipid$Go`N#-3(iZikf*y6M+U`o|zf{3( z2K5Pr*E@FdEiFslyPhAt%bc5p>i83SA)>VweKA5;L>*#*gmR(~+Y2=($2))0s?FE;3aZ%|)NQ`2io1|U+YN_k_H%2L z7EZ_y<}((FhZ9S&S<)d(BRnq=fz;ACATiZE&5MjDAEepY!R*a1A5^?}z41q*45fc- z)(?PSk15BpLca4Q2(p!{gD(|xb%8#zOb|PR!E%0FU9E1B%6`Ru8q3Y-L>g;kA1SuS z`(4@!+GK(XDr+k3j|)efAW#CSYbI~Q9ygD`2L$Z&$VoaKnsOVCh~fc>5fJbeiL<=c z1b|5%J5@Zg3haK-z^)tqWs*=%sBn>@@NqPLSPNh1U?GcM6q>eh0yU|)YrH^LSOs#; ztw0fD0RdN0mZH^;!bA|P)Ci&qx1E;ZZ2&)&zrv0aNy^TqQxV6?~f*= zfd0Qo5by^O>@EwG=qPi)iX53e7FNgkux2v#fQgd%;)O%8%CuIpk;BhJpzR+6it-cc z|L3NAoE-M=Vmn3nOX-f2b6m+u0AX#W*FbGkuN)D>aN$) z#yu@&5SidezA*gn%I4bKVIPSZ9W9_$U)(_5BiO$U7^)0>x;Kl_sR;m0MpB7adRWCI z@+4No)A|3koBM}zw`(yCB_>pg6DI~{-42CRQ^|+nB`*MVtXK1N|FU6h&o-VyW z!k$&Pn8cvFczko{-3D^hQ~2NVEb(+92V@WE>6GSK-ahyBW~ zKrvVWyjg|cDXYeuNX-QLt2w&3-knoqpd{UjRuUcVE|h0I=Jj&>xLJSKCUIxAYb6~k zI@5!d1thAaVbx&+@PqYrzgvQ_DUBQF^Ly9aTz#|au&z&Qf#**iU*m=Uk#E`4;1jR1 zO))LJP%11bx78XkeXArui51Tkm|IY%NAqo#0XoJWNb$j>=u?KE-p@3aCSDL3D3__)kx5A6?2c; zOh|Qu@Ub_616L2v`2_A=&xOqVM~l{%F4L_$B9kloi;lA8oh^ZBes@`F_Xh>a;H;Z(0+pm z5-@0zVvTp`u=gKNSn9{+{nx4?08VXDYlJa?=}o*%gmpo`1z9Hij2WAaXhT+-QigyI z>k!a*5AhR-3c!u;;JDsDijS4W_wsN*^|$TF7<bUJs7*1#;1>BYo1?242ThN*-ouXgA0F3C^s;5gX)%)! zo9!mfw$I-*dYt7zLFaxzBaPv+h_A;{VIeA@Ibek3!RkzUrP7slz6eomkaz?3J2{2; zz~fvV)nKt7ERsp|1>GMm7F{LW-DZ(7tgsvI{OWcov~NR^?AuxK0Mv#-M2rbA81waNgJk1B z@H?CVY^^oXe%f~!Ym#>=@DJUUo$95|+=4Na#mm{C#7p4H$<1bcCp|xfs#(CMaeoS; zy_sc6qgF;K56Ysd-tF>bmEE*gG9zTj!zK38CozWWeQ3Y?YPQ+ex=yDS1D*>9v=%At z=CFiW)iry-#1x;u)J=(9M^Co1o6+Lr^l_jcB!sSzy*v^H zL!01(RA_}jYydn?ugz6bRu}`Rf^voNsKFOKkuTJDCI1NAgyjp@%VFRaCf|nwGkMG6jJsgqFWir#5)IsXhBF8BTwU79__!0BU?5098Wr0s= zN}%Q-J4mZ~w)j;h&uSz@6=p$L22%|3*(DU<)l*duMFojB+fElgOAp#_IJ)q0_)2lS zE}p(w9c&9$TjO3`<|?u1WELy2jS6=P>XxSsRENR8x^`Jj4#O%~SggfjLrec-Dg}WYf-2Ru&p5 z;|u1T(Y5nU#LdT=+=>6Pi{W04r_*z6>_l2OLvvGipT{Q6)7KBYAEqs)e9b66R&P8L zOx;Y!Vo(3M4XvCn{*J@=mrTkq7R(b<&90rSEoNER7Zkvp(mm-x`99ZOjUlq80TBaN z=Jn#JDhl9i?X%F30$iAkp0H2B*s#cIe17xgo3W0La0<6rrATrpl^Wd4-GiUlYZ&=2 z?F`TJi(BDbF>kLjRBA+NH@91oxNMnlIWDq8sjm|gOc#M521CBGBI!J8DwBf{zH^dZT zV_=vowUioP2DZnUVN<1Ytp3^^%s3ID`!#bm!kuI)Ow8tEZL%RiI6{cJMIIX>du0<8 z%m>7iBn0IC)>xlOm?A#&0rh>+{(tQP7BHChXD&@n$<$5pkvyLp#x*PgmVSKn^67@v z_t!4(_m2%*jBXg;6hd(y=1HLNrieMxXW z)yETd)#aR{PFQM zUicq5PmAk>r*;Q65XC)^+^X`155wWC(eQXRL(9sv1H;5kSd7-)xlm#^ZgG$9D>t(_ zgyC7iMv2_P9%tqg_S@@jhe)WsRkU53E8Ga2Q-9+{{PFMTYz+O#-fyi)b4j~mLV-+7 zl$U?vI!a&uck!nEY4?K1@b1`n93zq!^P8pA(f;zdx+OesOE?Lde#D%K`6ApZ71t8_ zk3yh}sV=1m5c0O@Z$*=;Y`cK_46?*2hn;Ca-oi(0jESLoniGO--16M}q?IqCE7)me zc}$2zrZ{LSQA)6Gv+-IX)$x2g1sqL?TTMUUv1e1?9aLmraMQ$j@l|dvmTDy7k3nOkA-H2QDhLae z%-^7r3MR!C@SiNHBSKHqo;r7gKRoB;Y{mo0Syh(?hhjGNC;J zlg;^CB_=`-ta|FX36KHFS;#`Sgd_ohZN|8N%~7otV9`WFeVXpXrxmc2INx2amveri zyvX5kQc*#S9rYpmh#=CXjsb7e>#9f{(8ChIgy69eOl}4IVfF66IM5u?@V%D)j=AnB z@2vFp>wph&2VNs!>17lHR!&j~wiCLN*smi+k4=%K zl!|IF8yH0XYS$Vfj1_AQo2CvPJ7;R~2h>WD-z_TPnRcxQ8=S)z6cswaks6L<&w~qC z2u2IWqleXUvHZ5$E@u(^HUpUQFhmE>h5lfHP8nNNk(xxK7`zF+)3$t{af_NNiAmSy z$~Q1ISn#;=`oinO_)&b*zk}EI72C4HwsZ!Z+wweW2ol2tMz&pWkzen4%V2>bbTS%O zI3nyw%Hzw1xV`{8`b$&)a8H}Xv!RE$QsAyktf{*KxK@-BriS`43_DTWEv}N8x^)CY z_?`_v#nv`x;6^l+hdmV5VU)4p>;ZD2>h+F9LMbcQp$U?G=g=%wa~|<>dVM{*IUXO} z92|`f<|l{Y<^vOGJDTSfh*FQ75Eh#;RgCfB?$c~2wz5yocDQq3=p60^_ZSs|LB_;J2)8YhictKxg0+Zf_OFC24!!I336v9LEao_{nj{i<~Ieb=#R_6!wG%Lk{ zyj^!M%&MU|I#O@nLSuAs$@ewN@lh~t+o+aMob)(f-NJa1Y6N&%W@-+T2NdrxElHFh zA!`EHBh|ZvdbdpP7U=^dy2>kL9c@Lqx4pKv1gvDbAE4D?gV6B}!H!Epl64tPGj^y4 zm_=ctO##px&N$ zkShL9eO>=nY2)A5ck1{3F?e14$nh;P6*np`J}(NR5JdSS3ZuN^s`9$wT+6LKM_Bt6 z@#~_motTb_uv4t-!Tuz=ti>h#o9_I!zPL{2ZdY2W@znm5@oMhP-UZR)+|lU){hNRI z(;*BV>8Fa%gvfP>Ng!rSVOPbpL}eJTf(~8V3cv?WR3mcMbGmA|Yd^7dooEYS$^3%K zYh11s8LcBuwTx8km-HVD4H;={dIAw>l&xe(M6pqIgwREviLM^JTD1VTj)sfU$*$D^ zJ!XsG?MLokUUXrA{YUS`S;oU{u+%EOs~YDHSR>)dk{EEkeNCJ6mY%ycz^p{a*CF?5Q|2n zSZ~Wn)C~@67OC@*adTy(iZhcC#l#DG>qBNmn~Q!b1n5I6yF29;or>X8Snx#0Qq##0 z4D_y&eYzv0e+H*KvASEZ$E-s|e{GC7-~#VwPut}dBkk@#0keAbgsya$u#5Z#pyHvU zn6$hV@Uw}DJjnjVJaY6Fna#HA&Exd!&f#nhXS4Og7H1RCHDlotHiY`Rq`w+~D5Tee zH`m^ef4!%!6+bE+ajHi1^Z9v0K$8V4bV)y^ z`gq5PwP4)ZqcWh**aa<1%mrVyJZmd+mGw@874Kj$c^@?_j^<)j5vcfrd`=tj033S&I`FKLAwYDr>CB`H=ymU(vh(C8MPGOXt>(#R4|LJ65& z2)E#)VtH`SE&D$YE|~Pn%EwGzQ{`a{E|Quq!eAIn@~Y-7k?><^$gES?nw(qcaMQuz z%CI>OLr4oDv?V;;XAV;O6K@0eePYl$3a;ZO_~1k4dWhBefLes9_H$10BeDt82E zg>R$Bt1lcYdbZ^2;zy3R&GC{p`lT5b;nZOf7~c-S0}MZs`u#Q}Ap`{V!@=ML2owEA z-eH&e3#8nPe`OAfhYl8zN{N~xG>3m#(>cj}z{0Z7SH_aCir@63X{5Ci=$u&a$nphR zrdjpDf_fcB8O2^PDAjgje^gY!+%ImQ&}Z^f*a)qi9fkUstfxYyz$3|eOc5AZz3E0E zLEXi=dk4pM#qJ$?rhEChPiU_1p4V z9A6GmQsL7X(5ol~r^v&1LgPZqy?3G1?r1&{m4CAlgY~*V)}f!-`tAaI*D&RIQumy; z%zeOTxn-QKldf?WCe?s$r?J9}I$mNo#_clDW1J7fh*QH-kiKH<1*T)C@DZQO-DPg+ z3@GR`(f);2h}pD-aIbCJp-xTYfR5~Lm7AdnK1$$NA=+*`+dTFN;R2jOievF;8f7YI zIGDRQZO*J@I>&CHgqAHl&{7CH)J05YWMktv~0GAnHU$$va7ZUNhF z^@a2Drc>xDIpKGtD}6108iAEE+zGOQ;#SY@uc4$I-;WxlQu_mLj(HOvh`-lHpqWSvzz6kXN^P87<1`}w!H4MaDWip*xL+K~!qYyP% z7^~7_O8Mcjxb(pcS*6Y63dw?JM_nO6L*Uhi-T&}$DoKWD-=~+__sLaEhDr|jBQgIL z1)}4w4z`uDIAsfC0z8=zby3pd0-;HHxbN`I>O>w<6}c=OiR1kl{+ML87cto6J#O-9 z!(uyaq=0ZbUk?QNO;EIZZk!4}A`e9t>c>T$ePv`N?saB&a@Y6?w)u zjNwqVqQ~nS^&8pf!5P->My#bAh{hb&$jP{qW^|J~m>ao;NWzmP4CoXt3hPorGXxOB znU~evq`cd_d(s*{8ymm8zRz3I553hW0*ZScW@Tj0g%&&%KVV|m-gssc9Rv^jfXbvw-J=mU#*V#6qWE#m zQN|Z&?6$lIOym5KAc(u$cZ`9QmMv!!J)TlKx3Eu{3 zyk6eS5tN<*i}h)FEp`LX+gbk6gB1?;idrpBe44m|MCz1RWZ*7R3YlP1ptz6NI9&zSTD-F>EDY^7nG;E^U#Suk#D8{a(NNw_ z{SsAf&_M@5?}eS?2sjSpQyxc-E+mPf@SA*v`(}(>8=!q~c$|Zx&CO}G+f!5#O+17XGsEO( zEOO2mQAoP<(^B{tac0DgbqobyfNd)y*euWJDp4fo+=ifWOmD0Yo#o6tl3aPZv zOA|`xfmW=`ChRuys)Mm|t*o5+G~T%ZefnT744xesTJ3kh3~h)HmA=qRXdK+L6NXtF zwQDZwW+^zzJ1Cav_QUcUIuwdB3ce7fDOWbwBd*aw)<h5O-+ zAV8p*t;nWxXWOYoY+xr8qZxLrkZjBWGaA;~q7uvAEuYhYFeNioc7_EfdHQbU5&lLI%4jaR4R!UCh{edJ(~~ zM0L7bWW)P|m@X7;l;M!y$ydxRD*!dyrqxNeZ6zPIYin`3-Ld3 z)fLz4-6$bMta>{K+KIN15Max#&)^o$#5;ULyA-vtxSKM#%rH_Ij^2@kY|^dSFx|k1 zk6<_oA+PbxQn&;V&TNfndch&3*^{e$#1Bm6(_tlmiy;NrzbKA;dK5J;n!j*>c~qwe znP2@ugGD>f;eUL`c+sOjPHb@1H^IGc!<5(_{0Hv zX4j+B!;_oi>#OmrO`&5d$9OJw`5@zv05#lV$p z$Bg=VoB^?pV~w;~=0WXBOW>+h(M4Fj%8LoH7B5R7HJ;yZ7#K#(LuU9j0!NG3+^M*) z-T@!a&b2o{h%^5y`=o_$F&@9Uoj(eGB{&&sjJVv0xte`)2#W=T-s#2Y$G0YJNq5v9od&5^n)P0HZE%(-h1PP>(ce21t&O{yAz;v`V?K%A|>>YZwg3 zkqNI4V0n8z!O-joI}d4+SQBaB;hSwBXh$Jid=NH=H#690X~L z$}3E$fI=y3>y#a8Vn|li}#}wfvY6>SQ*nQRv;>)1oIN9%h(7?$!H0G z?%uyld5J;7v$#_Pji&E(ZaHP%$8Yy;U&^3RBQKhp)y>>D%#-~Pn>TS#V5H)ehwqR< z0Ai{uvTdz*0`qm)Ii@o7DAUm+jB2{NSsVgje>5KL&99FaOR+`-K%=lqOg=b9)_c2r zAzdFGe5Uei8XjBRsIC{XQM-2^e^NdI~C2IujSk`qAG?-yuGtsxz5K**x(Q-b51 z_(G-bIszP^>n9ZFEN(FryD4Mcm_XMg%CiGPHzD$eTQT_&_N~vwd=78r$YIAGyVp2l zrnq136g7thMjm#s?V*>z%{{E6!dgImgf^dO-8!YqEnyF-XjAl(Gg5reJnG;Mcp>d{ zNLVfo9@HXuJ>FlJ^VjYB{ZL$;4N-`&mERU5V<)8KK0LP}m`-f-8NZ-~#cVi@tuP88 zPF8d0sdm!RqLaF(N0p5r(_g(>-`%0U+juuH zEQ8`w0uw^jCyU$Vd}E!3f!H8v=VkHH(W|a=3d+{@GIT7_pm0T$5ukmW*{w$2kiFQ` zBV_*WA6+Q&t!u}w2U^Ysauz8|ITfWvbu084VD^n%D&`7svZWTj)qNmAMgDqSB|> zh1~m3J})<{GsvytSOqtJ>x(F({ipFw7sKx4Fe`UAYeb?GK6>3_Yo-RhIOyg2$;L^u z@9zFgKApUW_w)uDl_y!E9_tU#rMb8@B44zb@3y|ckNVQ-NP-~_rdlt0J*bD z{CY*LN*ox>tV=SuxjkLEZ<-k*G@3;rjW{7?bRiBC9YyA-Bz8n?(Eh``9($I;Q|~g# z4}0exs*uhSFg+w3jB&0^yx&{}6djXpaLc*AtcO%POH=kl@YpvqO7MjV=c+ifrzm+2YFf%hxZz_p z))WJzaVMdrU^I=axBuAWEYJ$*H^hgui|ujt0STnKUR>BpZ|(Ri#2z3n0U|CCJ|(up7+nc1m{C z?Uu_&?UXE2tWF<4ZswTTI3ieNMndsrd*kN9D!x`pxQg*^D<8uo}Pn>Y6u2Ee%O1H~Edttb%IF02R7NqT&I+ zmbpVej`+~Daf?4=qM{*fLDosyk|Ugs*%6U2&2EofD$v%M+D?{uJ~7}xEy&OqesGES zTi=Pl^&|aLJ?Cc~tY3WASLEQXhpkX%tT5)23_<4}dd2IbNK#ZEwr?c5*9HY{qp@iA z1(sGj&2U1?G#b^Je(XXk2}mAsnTPq~>S{%NtRRi{4WFb6-slK^VlbIX4&mc{CRRi;Z;g9I9nfWBK8m+%MPF8D^n?g?|QnviyEXg7h$`?gb z$q}Ax*4qy6{Ds1hhV{f#lH*xx%H7xG^>E6?Y0}=KTTSnFslv{ZHvLUhq+VgjNFo=F zNJE4TKx`=0Y{98kW&Tt!Tf*)agQ{Vi2ZWc~b5DWtH43pr5b}*Sc`GYGC4#`QR$vEz zt|0;#S85B=sESk}@lXE)ii>}O74cf%k>4%J7PQIGg!zvvUr@|pN~psIK7+L*32R!0 z!J1r5mj9g+qsI1F3@1V+(iL{fHRjqLWNX_XJz2`Gf`7{wR-x*H0KfdZG??3R>!o1b z85YPk9L}%T=n|%R@bHZg-Il?WHX=aifE4JGF2f=iKVp2w<_N4@IwJr;ohuZDTVH$@!lcX20i_2_jHQbNXh{#SHvTs0++IHPYN26)VUHC}s zkk#?*9{E0hQ^>zWup6FKzhhr$EwJrgSqVZ07P8MfbultCo?cJC@U!Dk1A+58`0^M1 z-iR51cdI)TnmT7~chC*6fuqoot|N|;Zn@@RgV9Kz3&+a<{)E5>(nh5K9|>3GK&&A+ zEIa~|4Cg;DTwRH~+b$PF*sK`~uVCi7q2s;xBF6H17tkSS4c;vBh-)Ah&=&!5D-5n9=a^hC zqn{aQ9J7`n+^>2kwt9Kg!QnZsCTgenLbMK9w=*j%M}P_{fq+MCR!ip_qrD1zE?{3O zh@4Z{6E8d zhURR~IpQ*6wJMth-w{u(9qa1~^@-IYoyoP^_6$9wm%mBdqnJ+2A4>=n z8mPIv#8vk<#S~RGoZ`3_1Pa#*b--rZ-B7aIj@A%Gd#>LRo!Q@hUO(MlpKC=~9+(kS zijfxLGFKrmV;+kvNCQ)!G)GcPJhr8pM|-s*Zdey^C_!WzSCik}+-rxD*UlD9JW&(H z)LWn)6tgCH0SfdNYl07_^`%=E3WF^0QKjrmtGxbxKfhZoL_dcmq?Y2@j>BiLjOQ8; zJ9>4yLM@+I4fHC)OeH}}6ak#blKY`uZFepbqRKI*G#SxqdKURhKvaTqo23-MAne8h z7_nuko(q zcH|CTb_o=Ir?XZbr|Zle7^qL@Boxvp^z60G))d0K^&Iu)?l?c`USJVjEN?jWk`m` zX1YpD?Qyb-hU=vEK_gA*Rombmjo+^~%i!4|5|~?~eRxZ*rn3#n`$%H8trl2wv>pFS z3RB#CH`g%<;L#q^;~{h(jV&|U_e1|TM+cDtNPZGE8SRHIMIW!e!08Z!aR`nKC-o~1 z0)seC3b|Ap(gZ8?x%BhsDiM+eEo7&HIi&qSd4CZfK!~7}Z1GLO{sp7}J5ewOmGuyH zC&Op0C|m(K^xjqO&`;hm;yB!~ccCN)h~6b;d#o~wSx9tw?#wt#g|alzqICTsV-08T z6s-d!tHPxn01)5#`*QvuswtuqLi}*)pu$c6cLJL_0?xcrJYfKqX{(cO8_YIDk*KI) z6OqWG;W-?sVqJpoc)Wew5Me7;fyq&ri7DlTBvQyI5jG_+Ax3dX`an`m=U<@o7;6Fiq@!y}3hs zNrn-n%m4%jJ^;jv%6qv?SN#zTAme(g&i}}&%&GF6E-r`C}XF&Fvh(7Kq z^>l~rr$HG;r;(tj=l&lX-9&)p)$-HoKB_#J4n;{|2JOl6*a~olzG4j@r6jxnCHF0cQrTkHFTNt!8ur!?v5C-{&WhV!-Y zj`2kie&}yV7Nc;r>ztQE#oG_Y@3y0i=mh4!CY($}S@bM}hJ@={FnKb+Q1ZpMA67LK zu#-O$%&O-}th1UD0eF&B7-)cb;pHbbHVVm-{W&bR)y-;&5Ec5LOV%DN)iqiwu8Xs% z!>B$tYHg>DBlO;3H|Gszx&jj2@rVJI@q`W?;0U&74H(VX@Ho5MGe&zhS9ux8H%13K zkdH;#Veah&FW+iv!&VmE;ST4_!OJ7TQy)VltslP6?$%$KFkk%oZN9ml&4JqlqBapj z?fvb&UOp@l6TV-dp(0{Jm*}DjRRkrdkC~|+y%V1)q8JD#S4j`r0IiO^pwg{rvOcotn z3#GKw2W+N_VUw^Iq8Yx8c@EFE2b;+s{j+$}f26PDkpfGo_BAqN1|%6XWM)CeH<%#& z^oX8NNfzfdu#!hO`_i4UEZwhvZ|bR2caT)549(i2>Re|HR@44EeLw$Aj1+Jw#-#jm zztsUSkf^DHMKsdlu2r;Fm`FaqQyTMkXy|)(7fis~R)BK)*8*~30bvpR26)LLk)nX| zfk{#r~%&4~u z&rGX=>(v~3a~wl^A)bemQA;>GKPhdI|7_+I2ATHQCsuXAndR&u%g$T0Q+|is^RiCX zJ_*1|%B7F|w+0@jU-3KW->KjCm%!`dM~-i4Q#ucBnTHdWT(4J^`#XvcjTid9zN6t1 zecg3@^DECf_(#u=1@kOYSRS#hcuJoB%a&ZRYr{s`&rP5lEv%aOuBv}viyuTAqN(h} zLsoDb^xFhZ_2?MwAC^dQ-)aPIj{d|~lIG#+NIs$tt3~giu`_6c6Zmr6|b5^DnLh2p^{)hZi+UU?{lILZBB&)BsMvv<-7MlBnS!+7{46cIGsf;Ry+0 zSWi+AY(Z^x*vn9wYWCRByT#X4Fhy)J8t{?ve2b9+s--kI0^@Xs*$4kz+)CdcTFkir zp#RKXkIM%1GLs3UVJChk>d@h~rL{ z=-V>IWpvF4o}Drv@P7XNDkW{3a+fJvnyi6qB-KJe5yh~d1wI>UkQ`1Q)3GywHK|%Q7~>%+Y=KzrBsIBjO;38o9(k3LYG*m)z^YxrXRiw}gka z>O@4BBGTk=5RePkm`S!SF2P`29-gDoLB_&tjE6-$o5aqc+k8UnLnsNGPZ?OC@+ExMGx9SlpUS*h3n;ebq~3Vt zs>T5}^<2;J@F}C9a zyH}A?dw}bncaK=~zL2pzkSY-?><@{w-AKqr?u{?nA)_q3430_3FWRmbkI5Vtx!4kw z(q$YLrEr6){UB$VmPm6*pzEDf6+i$~_~DKYSP{wEsjN(BfpNhHW=KWtkB3U@;|>sH zKAur%BueNCinE$fWhh*N62+MsJxY`e*#H9XQm?e4+|9Q5^Ei#nju_}ANYF(F5+0Ez8?z*dj7)D;+rGZnquVvMWf(p_G0d};Tp&!u2rqwt z&sn*?r^u-0VedU4WjlrWSSv&0X>WduQ?6^rM%vl(@Uz=0Pna?1G$| zDc4mf2Pgo*GI|c)M_$Wkji*=V}&(7x9Lb_b5#3bE?v~xB5_*F7lo6` zBoRd|+QGI&ZhX6VWH6JbbGMT62{_iwxjuX+Nlv3r?P6SHuw>q<7%@VhokG1!N9Ig4 z_C0?sD2kgHl$`i2;cHNt^B!DuOc82c` z38N7Mso@pHxo{s;FCT~Em_tR$Q84g!vgOppJC^tp=83$+Bm*4t#hi!8_ayzJ7?^gL zY)`nE81NrNimn_CkwLWzqoo9MNPpvn|M71kupK{o)>q_Uu0{!n;Z~$R6xIET%4yuM zw6$vadAJ5*NT-cb*>b}NP9)B7r4UBcR-v8FXb+9r*ILXJbktDIB_LEemnp+QRgnVT zMuW!9B1>`i(sLYfoF_JiJY|G~cls1Zx8YvOc;qIK&WEb!O*)7}H%NAm;as`6>tk$@ zyq}-Zf--ag5~~BGH-jnRTe%tUfpGq`rgFgxH24_d-BnjPhLS8~_~dBq3HasWr@Rmgab+Kc@oN}; zTiiyzjKMKgo6!HpqB=uSUz5k3_Z{M^f$UW81Ttl!d3yhN@|+!&o`1MzymEZ)-|;u4 z?-#%Er~i@TapO(V?~K~0wDR?F_O)I){+7#fTPs;;jiKa-u1n8Gr>}q;hTPZ+b4oT& z93K~n6|v5`pxxZRpcH%fOvF%TeO|r z_wg7s=1drHpsr`{c@ziKn7L_#HHad=o_#brmM8NDxioL3N49+Vbc04|N+e)bsgIAt zxi21%Z`K>asUgY}P6XpPDd1AE+8q}s2x>Jt(b;6P6hQW7iSq+uy_C4z!6UqLvs68Q zK)*!MGcaDrHbFpxwA3V8;b7Ozm@L|tL~&}kY2O^LD9aVB`e^S1TJtWi1yh_g!9{H@ z(hb9FbFp<6y!Cr_@CmgvI;+Z61r{CT3u0n=!Y>;3eRX%Se%dUS>>P}a5lbq6N6Nv# z@T;yY*A7~OzLkshMap4#0o1paUK!?I%mFnb?hZ}LY!9s6V7SR70yM-fPs;|`V@Vo- zQb}Cs6CZD&iqq!^PE={PXz~)?nvkR$hbR6tqF~28g^)a1s3rz*0?_PSNH`( z=0HoE^>-!&V%$e2$#_v{HIIL5p4zZ1KLJ=Gnr@3?XX*ytdx4(mAoONG`y-6#LqJ5I^2Pmkb19Onf^!gbmu2o7T4X3MF^miK*Ns!ZcszW3 zdbmZgJLI#7DLfZf(tps-am&#kQ+!gR8OG)r5uC~pQ32DnVjU=zNr9O7XoY`|O*irHt#2y;-_4J^v14(qvjg4V+0gbnNs7x*|fZ?sxj z2!L~tO}KUEC*92e^)uShh)X&sN$8I>_FPsE-DBj~e7SZfUDrY&Lj zz-CZ49U`~v&`|ljLD-mPbx~;!U^iE7CG_6AB+587`}lWic56$jp||&E-Ic%RxYhnm zeGq-ezu$APe)O!b$iX1oO30WgRR*3;=G%}$5J{d63+h%sEW%TuD}<+Loda^Y{Z)D* zB=oRUb~@eY&B?;Njm9Nx1dWP1T9iajZtC`!n6#eA!89@vs+nz8pFTs8;u{Uzpvj-g zl`c@)g~dR@;zdHY!`85A%{$m>N5e?oOPyx$2rp7YqG6`!!Oo%77CPP08pzU$=1mul z!Z4bn%4oC`XH0K;zNkFa=W=DMa%FPOLm1y5eK7#O2Ao z=1uw_4EN|zW{04Ee1zY4;HE*AvN`!VduaeCbG{HR;D2y2*e2lNs-O5UUXa}Xz+~g> zYP+4GG4;WK@cnp=X`z8#xNJpd9eXD~3Zxt;Q%u?V?5qlmz=c(qsj8IRXv^v~k>c#NJc z{#hT^b&~j%c!uV8@uvTgZ((W0zASgOu%=8Iak{1!O1k#09(O#%7~#x}{-|Y6SGkN% zq@N_Th+3$Yva_}iC59Zg7MwsUKZU6*(Qa)AvLFxk8-6g>jSXPFhLB}gpG-`SV12|f z@QmwexEz;(2Jt=B0|8p0U_Li}Sle5K+h`M{(y&T|G?bku8~<8}r&q4X5iQawHOXIS z9^|ejC*4hSbn_L+ejtMu6N(*+r16W0)J(bU6ldmQyB(WEYXR$d^kex6KWN}+Hf3w$ z@#tZ-Tr9t>wo9$Wm2P-|G=wPc^do}2NV!cZv>_KlPJ=fSgG2^C9EAVFV>x3G{??Sn zZU_yZM8TU3&C0N%m0D9S-t35RxkXg9RDan^jUd2{_;=HMkoES3a4uno@VX9i_)p^( z{hKbFz-8|&E9ljg5=2fY+6q;jnYzx5IiG(Ml3iYh0{9Cw;ldutE}dtc*fNXMU@@n# zTYo``_vmP1mbL*5vr7`uCm}=NjM=*n!3#-eTT@?4CQD)k`G%5qnr@1T-9~9N;$62v zutts(vl>_(_PMnxarjXjWJn|cr$8!Hgzo`t!Z-O6yB1!>Ccao0K7*q-a*iBr?R*k{-QYF6Q4^Ew2HtL*64=$WL6>3Tc`t8VO)S~XetU}86sx?{Dd4a&W2yWnn`9-(@fOVAK_=%jyN(>v9-hW^wI;w zsecx4s;DX6v_J8bm7EcyD@VYNj+gh_r_C}MGS_PG7~`qT&?yHg=rM{>kN3;FtL5f{ zfEaLorwx**(o2TuRWlw5kxex>cej%*2{T;0 z6@VHY!cPm?X_XWv`!&;gt40r=-nE`WS|%k~yA7N2S)zU3RS8qXSgEsED3=v3mw~|1 z-g|VuU1Q?k_VHlLB1cPpcAI$+?m2e^d^mWiF!4-+g%vC>Zb1Q$_W0o*u+~fuy44=R z^sin%G;sB?ZtQuUk1y{qJW;-XaI(_=k!-5|+4kJQgQ5GKlpgbTUs#E5noEGQzOgH= zip>ttHLn!EWcj==k{95r)1nY#wL{PHl7=fAWxko_Bk~ZIUAv)>6Ai){l*{U3Gaa(C z&u|k$-3eR~EdkRb0Hjq%xa)+@wJ_lS)w|I>%lZDo1t~H%MJo^PxAVD$0!63>%voXT z2l*BI7ayU<8VHVn*9wrJz@e}h)Iiapu!)rda3oaN?*NYYT>_bh=;D046k|_Y%ytN| zknN(nfIcwXRcRRp=J=7(uQ>DXnahzu6rW#G2H_Nw+Z@({=9y49%lVy?TIN~SS}QmX zzVlj12Th8!+uwY#o;B8 zgt%sKbB@J_!KcZgG1myE4{yuiyv5UWi@saR(QJm?*Qa|pJa;eypKi*gLFk6~eg>{I zH%E5h|EV+tDihw%ZZLU8;gfd+^;ugy?^|{lpLr;>&yWP^1bSF#BX`B|srWmcZo36 zM~53!7@<7wmn|#3Uu-Fbcqi@>1*jdZ16*U8XOJ$4N$J+8H~kskj~|IpWSlL2)O-h@ z+E?(L6@2FZQe^-dTumY&7qh4Waum0V`=#A%N=*cVD5IzboSE^Xb$i3CtxyRf7HI}d z?+{1CrGgQwAg(#QWK#7r(Mmzu*j*u+FMn@sy7&j1N)m4v_ zk}Q~{dpiH~@9XuiqzVX(P+60auW_v_EsY`x${dbU0ptgo8V6)JNlr6@T#NZ|(qgHq zzu-YI8Pm@K#Vz6Ft!hA=kTl$|hc1357XRF(6K=j;18*NDS3JYMKGbs5rWcfkMVunK ztrVdFJctEnTdS-2Bi6KVhSNq~;Po4LQeFx1rWR;C|;v+ zZ~rksXoMxPYSd7Pv8GXLhO$xKMSBjW91XsGJiGiADkBlqd_ip%EItcb^TI9~nKDtd z1>6Vrl!H5BnGhiB2)CDu;7;BnU-awYH*Oz4IAQ!9U&vL`VewCYfW9t1(m(6N{K5Xy z_;tMS?-#G}r~i>}frBdL)UnJAGh%CUDTT+A?W(6G`v)hVI(mbr31tnt!JMNZfSUW!qU#yJU{?>(s}`NT^AtI@gFWBrAOjmbAOPk5;o!Tp+R7 zRfZ2%av3vFj=05}>rf!9VIyqois#(dKR-S^u279E4YAVsaDWA)`i<$R!H35#CljCV zKb|3hx;x+h_8ih58-$EMF@cmuMFJ!kGSVcvz+Ij}tKchmC{sh3N*f~0m76{H7XrXh zP7(}CCZa+r=^0tymtbRaxHqHFU?H|N44Fh}t!DmI4xvZyPKGCz+wB^`i(CLOPNBv* zs;1$=!4_nhO6)4*#i}VwD(#wpS>%p?C86(LLGoI4x~OL(J2e+r-&Ev*U*`6@I>)c} zEfcx64X?t}%tfEG6%n$CdX{*b@MpSJ$v{&0Q0h1w)^& zb+pR6yS>RrY~Aa{_Z(wi0INTm;&5nZZT)+#3MaiVZ1ta4baArV<7 zA9NwI?w3*AKzR-JZ&QvJgXFnXr`j+Bt-De(!XQZIk3qKnX}yRJC2ell6v9J7Dr8>(CJ7pe#+d%hi^LQ&NXeyb@FHBPc4O1oxYsZW2|TOiNQp_C@=ouKOJc7y$f zt-;i5W!2GA=kA{TmyB@t&36u^Q4n%}U+H$JTp0w5{rYFL#Wdm7gI{qe5>QJ3ttez% z*E3F`KfQXGEl!U17uTbs)1%Yn^7v*Eozp)9@L>BD_7&tg%l!6@{-W^Ipl zt96O%MpbSKJ!tm$epL5z02Zq9Gt@+Z2OzC*r+=jxTmo|sl~1Un`EQg#+yhE7xnt!M zoZ=21Fr4RXRJHe~DB8-bX;o@gtH$h>3faPNTx5=QI`bI5H9BUf4_%Zg<03^Vkn>53 zWE2_JNlQs~#cn+mOdbro%LzENp~{QfvehUOcnn`(ri7g`lReRXP@ei&L4A&(gf7_c z=9hcK2*fiD&#lT-*U-2*Yn9KCMbNDp$9k(G_B|zNY{qUR%sPZ2w z(1mMp5L#{7jWue_Q_8JbE(kt%bVy4{ZV73otY$dsiQ4r%T zGjJ96T5OocoU{QPw#Awo>B{^{;t%muNBswt$MjD>vA`R;j z^k8WQ8^Tv+BUPQ~GaM!T00x~WN2(5{NI**-8gIfxk-yprzL&Gfm2<<*LgpyB^M&M> zka40~2$@e@16PWszHVO78ETn3kTGJ-i}}O-!`Wu_70s4LVY zT}WqAcQ%0s$w?W9bfQ68mY>|tzkg(9hOCZcLsR-)!{D4wJVKVV5e9d?70<*{tmwhE zL_orbBDPv8;;N~oVkGX|pGqAezgz{A$6>rmhh6g2QMv>oJW?Ga@NKF3c?q6iHO!rO zJ6_1aSCmPe8ie_gv6X-`fCiXjbUD{l=|bP#z`i{0WcGf2J;TJNPs(6*8?b;r4( za$S%fw5$Mv18#wCWtMl!jRT86hq528M~7A5=sD99 zPPEgw1MPGi?Jt5{P+5rKVp@=7;?YMMY&G&|yo3Q_53AAW+h+b?NUyV>7b|w|Fo{F{ z=q;NXjjfqRKv;O2uw5Y45yP{vr6?6OHE<)j5^Dzj!;B~pW22anH}AOHxi*uDN3ggL zVz2;qOLYgNs8U2&s(|9zXNVK1{WzeQlZP`))6BrXiJJ+U|8YD8?(Rp>$!u0jZsu=! z1+^Q~+BHf!gC9lF*esxloMk9-jythv9ZfI05=ExzqCdL7rpYLwtj;FKSui~sAg~P& zL}`hgiJks!v6QUjPfutAY&1*Qa?*8_RweLf!kNtgIX?igWlOuGR)v)2%#x}NnVrUm z;d^NpPr@JZ#=~p(PC>m~tX6P0k1!lr9Uuj*udb4vwZc(*)$02 zRwt+j?2uLHxh)8!gm;P`A*=QV9ccZ=FinfT_Fv#e!HWKP!2(m3gcc@SF!DN-3Rr(w z-EEoZ@`Y`_Fa<{Ivm}wxt-x@Y%f=@+&nZN!!5)@m>dEc=%-)!;-*Y9 zg?nh*nMc>F?fP4P_{pm_*Al9owteuN$xNRuL4RJr~uBYSC`Fi~r6{0mm#UPHy`Qq2h4O&#d6Io`~dJ%a$3D)tl ziYE-o8Ky$%SSQ`+4o6cK(NHrw?m~j_^`73CNmRgmk_KOJ27>G74>z47m9aSuobKJ^ zyqLVvZwhq;vQlY2mOHi|bNhqq3sfkNI8sOC#i5-}1>&Anm?xT>FbFb3RQ`4i+-Wcf zRND*ya@ZF51qg}*QWMAr^kj}h6gSE~KJ#qmSP-Q?ac13);EHZ8OW%x9+uxza$r*0ziyYcWucnoRI$ka8zZ=sE_A3&2lSwBTSSl-!s zu!`$dZmPRXk6~5Bp!3Qq&`46Z4J%X1_p^w4oqJ)q$UR&S<@xZa<(RocEx~W~m`k_^ ziA`Ax%Mc^oE;cK13eezPL!CB=!PEVO{*Gf28YYpTC}InD8H&v5!Y)z)IQ31-B;g znYbQBh8r2;#cD-4q&=+dOb|f(A-vo;)8&Qk*k}wW)Pr@&A&WjY$IPh{#pK2PIC=3D zlNS%%$9?2I%sYmQC=cppp@m zlcfyPLG*3IQ>t!7XBw_9M2&p+rrW^ zEr3J@oH`8R2~^%EV%dNPw>`>jKr9#E9EDV3)su%2a3B;|323H9@=lTJ_Th91`y?w5 zvb!jXPPU0e7w&A&C39*B!c0HJF1NUe9R)#oUfIr8q(h6`r;~_L{&=v#crOT&tJN(; ziH+dUbW2fD5Rx$UJX`I5?J)|wEPI$w9sYV9+U(9lx$+Q=IiSbNYr_Q8p z>J|JUP7RyQrN3(O{AznVw4uStCa4T&jW~px!XaE%skdG=iza8=OQq^0w=SHh!h}YK z9p73IZ83ZN$v^Fb&(zJ{=c;!fTZSS)mPWNcY|CJC;tN+UDK<#pO8*-80OLwJfzP5KKoxO#=jo zv-5n_hIkzD&{W*n*`|zlH#_?H?H)g|?NAn0F;AsfGmA&Fyb(Wma{M+nF-7B&)=_D} zEwk3_)J||+i`H6#m4!!VNZ#NAMaQ|y(nung9XWIV87Fttf+hA0F3zEjSfdr`tmdM{ zPN~pv86P$5S(S>OKtlXcB8}21zKHL~V}$C8mBj@u{FN-gW6SczoK1J=`7Xx4eE8~* z&dj)^i2?*(DnP(uZ|*UMTI<#u)rTphI2zu=PD6s)$ZfgAKS4 zggSn(bMk^jSx+In4srRtjJhuh9u3f8Z@7r#B?II$yAnZtBRZK9S6zL3o5RG+N2;Z(E z?@_eiSd&1Gb-&{IoPf=r79JdKK6N)H_WxKtY;nJQHuQv z8g~b$HwY%=~ngN}4(r&gYv1RTGRp`F57A>8gl8XqvqXw4Db2M>oC!XsqnN zd=DJcV^NHz2C%*^VIPoPLg zWKy213~n@UxKg$@$a$J-Z@#jg|-e znpjfCuXOrkj8(P3v1WHRRId#fB%IHYoR` z8ntZ)v2exoZXZlfzOyBeyfD%X(gAM|+x3N36J6Cd6k_MU*hHeQb5RqX) z17YkLdiCRjSY01sC-BzwNgrlmb<*E!%@BK8A1 zbCxxTYdZGjTVe%2c>iqg1py$OD97&($M<64(t1zgk8grh2ZZG}2U{vNE0levYia@RFV zIB-}N^gmSwVr(h(F-}H%PSND(7PCYxBYGV7)q;I@N4DTET&(6_XQ^9#xKlhrR(F4b z0WMZ2o1rqg(pB70^La;EbW}*|uQ=ftE&l5H;X(6=dujCKpDfW*nep9oo-Kfui5cLA3sjq|^&iwc;_vVaP249s}_&3?^xA8^npM`?t?QVJd>i%JQhB(Q3Lxg%R z$S_!S{yS#r#7<5W4*Sh(m+;UPGXt7SH-u%Y_4T?StZ%7$#XlY${VESdvD}1q<*};f zvs4naD@2Q@f^n+<;zj)PpC~dxzv?=^IEnt`po72n{0;dZy0#d8>H8bA9BYqFxsv`A6!N39PrwqDGZT^tpt`ciB*1}-c&d0mnSG4Fx{I;IeooZ8*|`zWktkmk zPL8KdIUj`Z#YoDJ?beR4RFbJDP?OS3@dh3CoE`E6Z&NkB%Yx(HqB7DzU`}OhRzm-y z5Qg5N|?{DiX7Qm0(qJ;$JYg(r;2XnK*P? z)z>o4Jl!me*_zH$HZ0GUyDB0cA2Y^&4=|w4`H2G=3uTfPo6A@mgP`CD6qnMVWd1ph zjAm|a2=**t?~cf7Hw2-P+%*!2XqhrGh|?+G$0S#Hm^X> zLL4_-B9~>|=M{$!@!svhlmfV2ttWl zlbj}36rLg2*Nmt;QNWq3lAuh0wo+(N9F*I&flVr z{yy}AL1t>VM2KXBTA(M4HI%I66|Mdb>@juha~xvHwiKVS(FLNU8rlRui{M^6(sJYE)9{dbyO+&9ji21Ivb zvo6^kyd`q-QQcs?d!a)^|6@&d)x3jEO1uN9Ge$iKN0cmYeQ&kjQQME~q51MjT;_6^ zEe&xi_^^zji>k}IC+4~t#G>@l`mJ(Ld$Otnj7786OHLTM4a0R0mzGS^;7Ms`aETc` zA{J+hFOW~hEtTMAbfI`&Z@%ek|B1?R|9SBmZ~dRGp2%=~6BX4kJrZDb+=O_Y_(Jc+ z-;sa)9f#>p>XXzL@+Xh4@xuSfuRwH_`U*04ENuZpffagjaYe?Swn45(es`#p&`mdW z2amXbbD#*cs4Enmu=25zeZX)a=FB0*obzxB!yLKm3mpvroe3BM&oRMAT1AcaqH(*T zo)8Fp$OfG4<{Kg}BYmOzv8M>7KQ$sg)mFmS^rI}W7FNd+eS7*Kp7i%%@PzrxT=_9G)I1gXFO26yWeB(@$sY0strq{M z#sNN2i@|@TAKK@*2OJYGo9o_y${Ss5(C6;<{-2XNeR!I;RCBp>wOny#&ybjop?iK~gD_rJ?^sjtYC;*+54;;JsmM z^pb(dgoXDS$A5@@Wc)UD87CyuNSy^;`mdBg+Mfy({cc%=T^pR@n4u5arz)R({~ z#h?5NOIzCDkAJQtfMFV=-!iD8#-rok9;JoG1|aR_ZQEwZRj_%e&KBzlcMt0x6g6~V z5K>ffo{<%$2C*ri-x%Ol-5z91fggkBr#q6wnQ~j+8`wzRi24#H~X4`!5lh!LH@=E}7P20lPIg@pmwZ(ww)J zhrzqj`xn%0foK_-N#T)g(uOkd75O+v!LD4{U#O1Q*L%;5 zs6`f=XRZibUl4SboNLMq>_aF6?vfaPU(rSoH*lI&;EYd$j*~sjnjcvd$$*^M9uD3a>l5aXEKtIc}1R*UU*@78iheQdGXt|KDOR8>cv z=tOP3^_-qiW6B5EsLby64vj*06S!v2k003qd3lTeRomr;gIZ@>piHM%D@Vnrv)TG- zi=f+-HBbyKNKrL*=mQlt>Zyg7UGwK3Q#6LQQEz9&At0(CC^lxwrmL{ebYKdU8xeJJ zS5*%6;f_U9mmP7+GUOo6E?z+b1U(jlJfq_ctgQRZ67bxIWhgLZmB4tW^RYs?*cVze zL^Z;=emes}%|1Mpeeer;(;34MuZX$@&L;jX{<)CLgu>CP~*MhG8jsFxldEy_(Gz3zH_C2{GHvKe9^6cU@uy&eez66#=S>v!t*g zoBg}uQ&2`YyIFp`hd(HC^E+*z5NwO}k>e9Ly)(DCc^Pch@e17*u0LZz)tvpb2GEId zG>O@s{k&Yvzh!C`sdzTaP+t1uBVha30sI4fF7b5z;vHmx4-Y%LsY8w#FkFS0NG+U0 zZ;DWtTlF><~6u?9Kf>acskk_SjX2(1hyJUV+b|JOIB znXHAgltL;(SATGhV5u8jdM5C*Z3WQl%N~nu79+vzXNg_0#ofQ}O@M%Hacf&e!tD31 zu?ac{>>EjwN~5!L#sNhW13Ocz!#lB#)FJ(6Hf7mcWdxRZymjEl)wLCt2D=oRr-`e! zOk98qfm@vB00ogh^iRx#UT%s8MEp&BpgryDb)4DHwIeb(;*0W{42^_*%wC8Mlot!%0h`l zU0X_;W>D$S!Bl}bwC8Rjlt%2)Lm8~dSv@#B$H@(l16P=3_pn^Srl(x7m{x{^nyl;+ zs*lsgWQcK4R=wC9R_E1pEfzCj*zCWMhS~XGYF-d)=7SAI!v;EI9y%DUh^5iU_D^8Z zWA}?jOk;u-r|Ta4b{EnpfOAO2jE-)XmI8oU1tyEyJ}mF-?D=tpFw7JkbUp}J!J;x_ z7nKp5Q&=Oo?q)4i+QV}*LS0ak_gi1d(Lq(R_@i^uCM%p$B8rLQq)79aNk@50bau7; z1XYjNayBf7f+(74n|?=%N25k+28>3a#yD(Ks45*;F16Q#1sw;tLYRkDPO}D1~GK5$fKGwGBM-@@Sq4p z5gvt8EG`G`S;8nrl(U=X#Xr$YE5_3znrxso(k#P-T97i0NDw(7#>u2}I01r6M*KX5 z7IBw&mr-)Ti88@qRjytP#K=&{Nxk=dF6d^0dq3lz{0>Y%59g#{| zS-<8_&7lGgV2!pkUw5J+qJYRelYCIlIre`0a{jn}ykE>8CRbP% z!=6J}UERQw;7TSY&e?qoc27ZTOp^}N8KPa$rXa-6pe7sfGbA<;0)tLDj5%Lc%;{;* zJcolZeBfYkzBBust~f_eto3Gv0w(KcHNCp}@_u*rWw}5ohcGS1J*E7^%Cl&*mHB)u zckagwOYf_sOIsRZvLS1|+kE@Sau?E^0`qB27FHIC^xZJ_b<7za;s+w};Hqd8m<tHvxJc@HWvo5BAFM1oCIu+7cd*}|5$gKfR0Z-W3G$5 z1*zf-9EKyHBk%&J!mnjCO!yZcqDDZ_XyGJs+V}s756{!@u@5*!Tz@==86|Ah*j{l@u1hSdZrP%Z5#~Z@$QJxI51`C}SJ@cZCnMWKJ^Xg$e-<_RI zWS-aX4H;i3Hq#=vb+o-+lX``JoIE{9_-FemZ!n#19z zjyP+3GRz^NDUS#ZcuZP4B2ciJ|8qGLq__+fI0$UT46IlPuS@zoHp9Dna>s$ z?GjC>pI1v%PowVR^!V)J{OEFYG(oHl-hE*6p+d+@pnf*cZ$)=j7RSNCfw)E;5e^B_ zVmTyKkRn*J8e6PTY;9V^=CW{Kvq6Ly-zkbUL{R%Rve&(mN)PH^PCF5~8n5MGlP4Ym z4`TRt&69(D-p&r}emfpVl;ivP-BR+%zwPcHETaOtZaYlyy7q5=mAcBKie1QG$tPoT zI+R=G$he;LB|0eu-<$Kg3Rg(%?koaq26smHS#bg|@;+%yZxmrhpmYrNl!rWk#z)A5 zLKEvMh`eJL`wjK(K0Y2TO^L?i)F{bEX)J??kUdx>vW88AnWDIgZS}BvM?VZC$whx8fI;O5h$X8g9e(l-3S=%Hp~q6dd&Kt+%nh`G|QPn zCn<-}4UXm_#7`$0E`CAfXwFxTh(ZQpff8h*qLetq`f*XHB4dHerGTeE2BW43x0rQ3 zbwvZYQBkwWfd2Kfo##~fo?^8*sPLV1GGtd%snHSapA^%V21*h+F8CPdT8TMlqs$`R$}u~piC*w!z9%d z1D3zSNHb2+?o8AHV!>&RQ0mU#L_9+tHM;eY;|mx-&_-<&#D=GfRe24A#ILA~prt?* zn?D$Nx1EQevdX;zirj#*+8< z$Ehek#yP!{?jck<(ADg>#-3)pWM)`s2QfL@ETxCP!!$1 zB&!UC?*dh*+?y@F&S#i2j=R_`KK-x%_41EDUi>tjjsD{}>|69{V1tJ~EK~wcqb4r~ z3zQDWQDz2(;ClHx!p0=TjsQ4=>0>R>4smt+5PL5#`Lw8G8ejZ-A1$su8|t= zD=>Qr5SBzAbJ4}#(5y6A-m3X(HOh#RSs2yTM&uH|H>E^@T$Rw#@;?i>6xK4JZ^mvr zZI&|Q(a9*4WJ;xeIr55CF;}qF9G46h%~S}FYqU3I1$v4fxZ2H3I7d93m+r|j+6-Q}!;QsD@xmi6-9^CFW>alEAW5Q~*br)it z5GqO$qhr2?3HZ2+UX9abj3Y#|Fn3L172IPY({RZx9)p<$v?uhn|5rtL{7T>Y1N`gy z+xYW%27i2fjTin;eua&z{EwiEu?@eY$Snk=#;12{bo%-873Smoy8eB0FN3#Uep)X6 zIl0!{y6>JS1>l-j58sygcw4~SAnKwsG;|a!wNY7}ClUb#itOoaOV%5Bxp0<_%jMP= z@f;X+ak12Sm@SzyAL ztfyd$3Qp`VuLe~=ni1ep1fW3Zk9d|?5%>#`im*ZG*`s|%{5}xp$bkxi_Zwvh?(^R^ z^vzCkiflw>F6?heA?^4P+C;ST9td_xc>*Ta`Jyt0?j$v2O3$=DEVEb7j|-`k0MIZO z%UJ^y`MJ%f_sQ|kOgY(kN5`*jT@jjjjpR2+1Rc=@%V2@7ij^`XU&FTw0Ru9cBY_=(Mv>d7If5L0?nGzY|D!wXkaE&4Vh;#Iba|KO=1=* zaCV|9+~Y^-!Dq`I#g376ktT}Fic}rIIze6}*bRsfa~at`;Qn7r1gdb|1Sku;Y9TqY znv+~%(6F#kykee?It#e+2Q2jmmR2a!<#2&sav2FQj(ve_q*Umf8?Wf~{OA<+>*E%U z7i=n`D)&--H&i~v4XSldIKa@Y0GGT%HX=ZSI%_kcH2MoaF6QtY+>WCpBizmenBID~ z+hRY_<6;Bli|y>@^kjZ>e0+9te0+R&dU+wwQXCk$qh76x^X2*R<@oeyes;8+ zU!I%qT`&;}j9NkX;(V7kPqWMA(enJ_d^DP$-(8%~FYSa`Iw{XRSh6AJmh`kZNV?Q$ zhgEXG>IuG%7W0c;y4;K|aLD4H*;ml0lnffa5?Nji?(U6_?}-tbk^&##GTkUowb|`x zlahWnimmO`p8iaBzCsA&wEXL|_`4HpD`Z|EH#X~Utj9M9Zu8dKG-sF9i^scY+@L;( ze;WT<&*T5Czpc;UkB_hM!vD#yIyN9NVLNC+F~;G!CdooDGD~L-0~lybQhTiy2JGjU z%N&T=f(>{vaMm&Bk=SICUjf4Gn05T3d)Bdhb+x%)Ee*5rv_{tL8`L#Uw|~~LHx_Yx z)nIl!vXY09U2_uwmm(t2_x{|t$P!0#0HW%`gj%u{x9xZAb=vM!8T78%h1K9RhL^nWmp3S zU)va}Y6}EXxYsz$EJDN7VjZbIq?MZLISkRj2iO3$B}1aa^ryu&+GBxbJeaOPhJ(my zoM7>=UbBy1zs@jvX1hl66;q&QUyjP~cU;gDvrLsv%`Jowt6EL#a41(A9cNH@S0rk> zw)P|=If`PE4&odsQ~eh&{Gb0&8_BqXP3n8#TzszF4nG2=7_5|`j;^{Qe3cuiZDYps ziJ8Acee%<(RO2u>LMKxY5?mAzN74>j!5w#Ue@(!!^Bm&~`;>IJAe5}{Ub)yj}_u5TqW6o(~Egr)C zCq?@sU6FIa$S-fFZ$1;-@;SyroKqdopVO;FJiNVv*C0&$gu7X4H0zfV4$`CDZ{m;r ziO36f>K3(g8LAs@aG2egp1b$?LFYRfi8f@>0Tk=Z{J+o zJ;kg-P2WYI#wLl6I;hkWXf8%_HWwgV=iH-m?2nwOcf^!D)xJ*E1S}Sfs*j@*xP%fo zaZ2E_vz8ppSj?ir{RNr)DRKx9HmSWz-CQR6E$yhaS~#=!%Lh~rj{q$+S7asMpk3Pf zc7|Zo$K{Mg`830^1ZXn%^YU(v5sv!Zt$Zo-CD=mlEhxxvyErM~v0&eUd3`-5v zyho%Gb6D5f}!AT?imJ1YB?psz;kOoG8?Ul+?K#_FxZ z7tV1FA`EfQ!rbUYgTmynu$a)=rLUSmY#<(?8e(7E}>J z=n{`CHZaH5TrAKn6L{J%bkUa5$Kk{n9R(QYQ}A4{6BchHQq7i>>zQ0r@b;_ikbdAUv4Hd8{$Rrvt z!fE?$2++cwHt~-3&a?prg`wSGc0G@=7{g9@f_VLZmz(vw4Z8rKv+$Nb%~n3o2VyWI z!T|TT+-W=}$TM+HnGNeknMj+PSDW?9+-Wt}z{KGLn|b6sP*=42S|yu6#X>8d#AwTJz?)vE0a}DP_xFxQToYJ?A`9cqhg7?bCx|1! zSee=p*SzR5C-@s!8tu3yPPad<3Br}ZTfTf6vb+c#jgBQlVKFFYnP)p$iDb8QUkl#?wHJ=asG?Zt%IIEHs4evEx zF3N!7g>ts%@A#9*@zqc4j=Vo0O0G|{p)`s{XB_e)R*ob!H_Ht1g9x97&Qqsx^TDnlZ6kUtRfki(qb=Muzb^6V zoX4!YmIaMLCn)M?obbcU1?NYzJ+TDHOg`nIu>{B876Op?S$Be4cCVKPA}g0EaCA4* zCvNvq5(0HTFZ%k=pS0V*(_Y4!S%O*(sDjk zT5Nz4)2;;$=QT{62q?H)nuv_tGXkqI%$V{iM?P31LJd;wPsEw?b{v|Hh@frc_uyv{ z>VDqS-+P!aGAs1}io~I*m95W9SXwZnDnfgt$eNF`6$RqMi=`^zUC)lu1OnDkqhnF3 zj7t5MDtr1AyHH~wxZ5=_UUs^2DF?c(eij0G&XBJwuv%(a3|In0TtYtrrGUH>#^pTk zM9M*>Rgx_}rzL#P(}cjvqvA6pU&&39gB=P#_i4JX_RVguIZ({ZF5BIDuqE5Spam~w z1jIi^a}v?AybYmjth-1L^`%~+`~W>!(qtTk?g~jH^Ug`sINu1NAq^-s)b!2e>3DRr zSlo?{?&ik`BqVPTx0I*J@+kHB?PmQHBh<2zZ|@%^#XP&jP=fdOA2DHcD!l}H^CuM* zN;0Hv=|NkAiSTdn=Rb6rKoKen4zZ#Wt&5Nc?DL#BInL+A`^&0KgXU!L&7fL71w*C!pN^W52CP-&N{7=h>I_I0 zEmax-d7EIkdU(U00^oo*$L~K}PbP~8k^KOH-aR2cVE|>h53>?#A*G%?&(jqoz;}t) z%i>SvwMsxVA70?m?_y$RpGV+*s0f=FC?|h`T}UEE=Y>SUyeY@${ZW+u6~Xu?4CJtm zdM$QQI`jG`LF$SczR~y=qrQH}OlYxyC`pFhYE}OziZaDxinmQu9>)~k+`z;1hkCF- zN&IzVNtEOo3B%a_AIF0EKa09W1< zHX{Bt3I_fiz^Q5!?i%SFI;MF%{I)77ur;LyVt)Z*(lV{n1PzA;LH7kMEaXmZ(qr#-8(S4~k`e47P z4VaH!Mo|`#e_P_Asc3M*;i)@=o(F#GTZ3)V{vG2U20Zi7rwt-P$SsLzeXGG2eeD)# z|4-WMsFTO4<}cpCFmuXRsaY81H8`7?*<4~k0h^W2d=SeCsFQm;KKFUS2$Lj;e{MD} zzJ%EbnbK7gb(pU0kJBJtH!MP<&^@P-@U;JlG`+@_zRVw(pn{rNI`hviKTdrxBgFl)#A9oC$Qc!(BFw3F!j*ZgYFj-a*mK$)i`zq&&htr=gQW zM=ZR%R-z6x>@WBCR@k81gH8jbBFf9zBrs*pozd^hnA-IUAXK`8WuYC;==@7@t%4A= zM1=NCp|Xi%c@bhu=3G3b?Ub6N#BelU6=R z)V(uB$}oy4>HP29=`?J_?@M{f97Y#pL?1rZjex@H7nxJ6skxL^8itAOs_VzBhWPn@ z`vk$b5u1Eq*{)%Ne;^txishV4J5x&1!3YoM{ArMxG1X5q*ulwNbz6t_!N49cE;MUR z&UUAhkzrnlXpB8?j7zXNYST6%1zbOpSZ6-H#&}f=+2AAu{%0u z5+D|1=2AEacsB-?U96z28t#cwUYVN-9!TN5FnHeSiwLouyn9?M&o|GH{C^f3fK*3Q z=(&4r$G78v^FIGb&^Gy^&oNaq+4}n0Ns^a(iAv?HGkub8E^Rg=>AW= z_Mdw~^JXjlyzQ6sc-?h_SO)lO(iyom?&q+{nE_ zl@R{rb*MP6{DnNX77`AJW_cmJPfi(M!zm+{4dd+JqK`c&X#K4-L&PH~?`YEHagMgG z=(4Ne6%x8k3c$^ztggJr4ei3fHg1B%i_Gqbtd!LNLO`giF%$=jyTwv!BOim|eclNW zmaI`5BYNFv^_exEZ7}heP7Q1CdB7^ok*PT1Z;K`#LbpSST>Q9OV^C2S zG6k$UNub2*_dg3Q1S=LcL`-5SPm%6>FYbtIP|!64uT|7n$z!R@=#;yM@BC28`rb2l zNZeYnwV$+6fkJUpNccUdDY^Hq8>y7J+d!2Lm>;U>-yHVQ;Zt;Z=7J!Cxvrw}eb;<; zh_x=nd`-jBf9?va(T$KFvw5Nkx7_<_-YJ3od&ka=2Z|rn#WS;t_1AoD#Lz4VZ^BcH}fsVAAO-cM=Q~yL-?te zh!NRB6=E8uUvb{k!4)x^8Ulj?^a^Nm8sr)I_&P2BQ013Y!V=MQno^K9X5_SBrjG-x5951|5p; z0r7#E^-sY)`dUBt-^RoIhYk-!I*!N07yiS)c7D)Zi$gN{iyH=a;KrCS*F2pOfqu<1 z+#H1KP_jh^N5*rUTWcUu$ne(CtTr-~fh}di8|wvAcQ5iDKCrN7G?#HbjXgIwR`4e+ zYqyL-r`UkI1WL4-pGEoFc*mbW*Og{{H`VS7l=j!@ggz3XdKU-+;zmb%*3 zn@h?~sr|MhqSM3wcwt;bFQY*lhQ(ogq;sA?1`rwtnFIFz_Uh zO2CsF2IgFggrD!*H)eYvDEl)Lu@wbtzq5r)hZiDrG}7-UjT z#EJHQmbN`p4KrTj|GY@>TD=3uW)Z!@yer;9hR09zHQwrZTi&c^pOz0u`Ay&4 z>vOi60BBW$t5@^r0j!UNx4IXjQxwH$+yN-MR5%x6J%0PB-~bT_JICrrG4wSdO+zmE z$+0mPhB=1xHU)jlR?0&&Li#QGYf+f!j>to}uczgFH$~9<7aZN_bc5sF)r>jFH0?v9{J>C&}U5o zsZ@*@(+xPZGm%@=BHoxj*dp^m(!z(1SfLqNiUB6zbI9SHmV=!TBtbnIraI}#vMeTU z#u*o`E!kkOa7)q3Ds*Z9mE~U2V|9$Lnycfb7>d!*Z$$g2H^w7%^gkgESFpH#I8uw{ zs~u&dWpQj9!M*0q3g?$|6|hQl#5^&}Jw7KB{~@INg8)>rAL{H>)mGG9m9J^T!Cf3OgBdbkOK zklhHCfpyLz%WfdFvtLQ~@DvCOcDyVjR~@@qw-p_YLNhE0zg&G;tyWjBzR)$~6FT00 zMCVSN#4$=l3EgN+`%;-dnmQ7oLKPPFA9sR)AkV1#8LR_^K%EDGnpt+{K-QLB_G8g$ z1=KT+nm_?7pSbQBG#*{A*SpyJ#aam&%O|h-`h_8PXujx>Rv31YI~CK@38*a5-fUwy z+6yfZl80>&L)6?m8;S|=i!1fp8JkrSR>s$ebBo!orKwgie;lp#0PvjV@(PGfVOCBybL{8N{JvQ zFS1SS`p(%7A%;pnk7Xc3QM z>o__G_>iEDKcz#3w4n;$`Z&%0irg_V7pMj81YE?DT>t#)snElzEESq&W}WS~H0XcV zmWuz-8GC>C!Pw^tT@>iCq&-uIAQidFd_${Tl+iSve}{Uc-!0Ta0<|ZGN7n2<~GQDvB{p#ytR8n zjK=J)6&#{%W@~XJf-=QiF@;058Tv+0&nPn!(($OH85<)9J3Zy^fU|m-Ya=c`F z0YOE_4Sk1uYpBg3wk%d?G%z$@(^yl|5@gtuFEO%vIYV#0+N$sx!0Q_Ttc@)6J+@V#7VpR?>!T*xRMjqw7DY* zVrHS1NOXeR!HO`MQ~liwHtahGxinib;@b%t4Nhhlf(Eg}5m3^3s(- z&LplY6)RLZsa^%|9N&IMh!wjDM@~B2{=@)xR$2+5cIejDNQM>0DRu)pu&2C0r6nqe zHp|ue3nz`SSQv$h;!sZXkT0{B5XahCBaJSAMZd1{Nr*=<%(8wq3;T-GvR?DQy{Kc`(ju?tYicS+VclnqeZLGH8G(D+baZC0`wanaVt}x-V#smx zqu0ZG{=ftS)SA#nEqH_cq`ei^VgSol(IG@GG?1Y$>bDZwVE9NFm@ndM{ltGBzv?>7 zAKd(TJcIu>zQzmxCs*M@11k+uN%|T)T`xvEWTfZT`>pS~{zR{zT^aY}?6;T-_~EnV z0pgn7EI-~q#@LD2m#Dm_*eN1sSQdP0ax~sw5M?+#YsGT1z-WwM8|GPfRqKs3{_KQV zYLl~p1j7xz=<5W^&8fY>OoVGV$Ijj0WsGz0>nc$4Z{dT(KVnNOC1zuu5>SfCmkhK? ze?3b8;En>+>w@|GITDI+2CiQ(aKLQwbw1mD+N}R9NBrS|Ggq*Hc{VFf1YQ;MN5x$D zBtf0fqxm&`P0O0bXIG*v=0A|3&*k;JwagJvSiw#1;aJE8$vIi10D(LY=dv6Hi6 zwp)_{GZD$4Opr#T-g5N~WyEgX!}=yNbVb0ffv6x_B`_z<5_NcpZ-o@^cm##(IuL~< zXkY{%2{XSbM{0#nEAIF#wy=+sDI4XiHTm_mKwJ>tGF5TbD($ZK(B%K?{h7)Ppo*vo ztG6MUWHKl#!(Ys=w8 zGrT9wfg|aUEhv}U5R4Qkp73JH49|SGj8;@_Dz-J1_J0!=fa7OG+?3-NaWN~$Vp)kmLBzNE4h*r#t$H(;!_-lB_ zCSZpycodYnhVr)0SZM4@>lCn7(hm9Ui3jToch&F{`J^Qcld1{khvoz?&@wAn3^Mf) zZS*h<#G>vJu|YuS6fw@9uvv3Y0Cd?zZ`lI6*wN>pS@pmp1 zB+a~G`$;SZ-&GFAFty|SP`}E4GyLb+5C674tm|99qg}tk=f$7=sp8DvQ*ejHTHF-^m)4}$iX7e?wl-&*4+M*?WqAjP3f zalAOel8$A9P)0obiYQq5DnwP7%9~ujIFpDQP6F=4OCEV9M?zQ0J5U`yztA_ZIr#1r zN692XIwR;3fNx*x0mypW0s87CPl%dhyu)d6R5-1E^qv75{5(3!RE;(&BWFkfoBXYT zZ!=)YOV~d)b^RHEb9kIa5*sfHyQP+t!9~NV#I3tdQhxe zqMq1qi|sQl5Q2)79o1%@7<1&h;Amrepe|s6AF7LJ+tk7H%>k zA#E|IH?02>)Vv*k_WZb-Z~r-k;rRiCiS+1OypE9@!eP8ETpO(|QAM&_qoULYXsYeTo|X=s*Lj8F+>@!%UxJhMXZoV|bo=Zg z()9T4^KSW7rsNLBMZ6qOwfFZVqeBfnd~$iyKpdl|&2qQ-cYWvg@=Rk9 z{j(*TbGKVgynvpzc!)mk4Q=-FBm4Okg zk>ttEeDP1?5{PkVj;C)kNhtE0KQRt@s`)ewMc$3iFnj!Vy_#vu_?XF@?dBgjY25$X zWvZ&?$`Lhp^Y$l$@Z0xdv)5LO)G#aRwygQzD-4kz|_bg)l*rc*QBnFjQD2>{e zptJxp;a~gfW&u02Mb8kohXzW&V-I~}mY*QM5iI?g!BVFAz8oAbXtxP%)Hh-C!;3lW@`>t{$g+(y7mhwLeI``!k>-y2K`D&8b%il#&t za>P4Hxb0+yf}_h&wmJVDL(h#7GLRG{fQjbA~ML7@%Y2~=?%u9JX~$o3)F6g z1%^h(J-ZZ%Ds6`Amh)S+p$VEpmP&$OI6hf5P5w#JOTendvwYVA`RD&@tE0AIx+h(} zA9wza)kh3H6y%ECoWrVHAPby_D;>Mk3|MK4L%4_OU2Om8?l);|{D+Rf{y$p6AlPM! znyL6Q7fLamS`(>l3_S9ffOF|Lr49)iSYv%7F0*Jn4`vCe-)}ewXEdGV&A0QdMGfw7 zew^xs3q9E~SVk#+C@|C3X2R z?xB(SIUJY9ForY9JVX(fz`k8Ur^kRxRnV)gPXK-V5?Y_A*`KN3z1mXEusze2$EQM< z!)Eum0Kp)1b12)7OjK{HFcG-#G*kn$I7yt%m~fk-YIF{x!UrHzt#?VEAuz+ku_f)u z47zW@{a@bApC5KJ*zO-OLW1EO`3=5;leHprke|(-)~M$Frl&i1X~2-qqWUve02^(f zO5ud=tS0HQ4f}1aN6l7U$lqffgxR(J!@PmEL`bRX;E|Rfk9?x5Erh$|!2#vYJRs+r z*Q04d8ZI@LSzWyrosjX8B$q5ubBU0ekBLYr>NP2XR;(dlP>Tsfns%hF`U1d=xw`{0F7qc7?FJKjq7u}-LMu8b;UMG( zdJn`}r}dH$Bu@}_xHq=-xi7Yr{BaL4(dHAfC4Yr1hJ|eRP{SyDxM21}Oy8#GKfi$+ za*K%0o6p37e0H>idiQUS^VR)=yLxl~fPFoC`EZYN5uAd|T}BX*o&s@Ll4EqF2mj}K z{ZE`ZUD7ANvKs`*WrOJRe7g)Io^$jpP9o?i#$e418k$LYDZ+&Mt4O1aW}?L=Z;>^4 z1@iwg`D1=7^K~!KDCPcfvElvv*K%{S-jcA9mEnJgNb-TmO38r$hIlvM?6$w(?>>>4 zV!d?H0AZmGA*LAKHMw4xZ56xYj>oSa=0H7d=HCLSIN*HciW#57et1T&o5cgHqp-c4 zkUhOk4y!jY&hK#I-7=(bhcE!Q*@AGAqD~CqhCe2^D3tY_tNyLywn#XpxGffMUysNa zum?2vy?7|gDT}ekaqh8&gBfV2oC)^Do~%kC;{398SZ3mNsByN>M5AY6$6(VdV=UWL zS)daccdHwZL=yKQV$vNskp5h|;w+3z5FvjU+y}Bv6w8&L-`7{d8=d7-;IWK=Ee>Da z=y(K@%%NHW#}pn8n`JiOe{oV`pyX0-;aQXK!3A*-!AAuZ##<56iu=~im()2HoTO1f z>aY6?eW|GPWO=jO@HcQVCku0Akm;I+MnC@vnKAYil5-`k%iR)<2d0Oqi0Wyn=hLV} zN?+6_f(2M%Ng_r2mPLU2Bb>47K&e%7vRGw7r_St727!M}UD$g4k^}8MYdadC zqm96_bNLUQKaNEcR&qq>Dg{s=_@xhC%wEYdg_v@cYvAZ9l1|!@7}9Y!^S3-zloWfG z;IFP)k?|<}^s>eTLWq%T$z_@ur(@899?6xp8J{C`Y}(x4eR~hB^tiXWCR$}6mf!C; zO9S}sZEFYojW@z1VS6H(4g~od;2iz5Lj2Z%-`Cg#J-CVbMG2@IshPKdLe39sMw69f zk{iMnr)ZRhkrb0n0hyg}VHV-n71!s(1m-QHI%W|S+gMrExF_p+SEC0M{3$Kl{yKUf zg;ZER_x)G`u3o28s*WiH0c=ulyF%1X2{~XPR>1fRW^3eXfl+J$)Ex={9(RHqW;)1O z39^0Ie(TydFzN#YjKsvO2(=L&c=zXH)CrlDESnQ^G^io|I=$YZDp=*rr!^*DGRZCO z)7j6<#r)fB3c0Q(70Y&~EF{vme|*GPFZfLO2U9o%hpk_5``@|vYEHGLtD2$N=#06g z?#NV~8W1=j=O(g@<}+nyADzQM_;sz~L4Y6IoSdP`ih$l{@dWH%!Cl{15hsp zD%BnV_c{00>jZd_3-fQ?^Y^$jvYpYT9@qWDrgy)tcSuLTP^FM?%0?|oJ<6v zr;Kld*8m6;Fxc^I3s@Rosxf6|nzzYv2|7BmX)o`d%IPaXtCe8O?<%qK$>3mY6gSey z>9ZL?S&(?bNAt9|U3^-u=87fO7*ABZr-;V{t6NizyWw_@_0jhGrJJRn=r-xylvR85 ziRozLb|8EO0R>!?T|Al&_CjQtbL0ERHwjS4#%_vCiz4X?VlH#K^B{d!G*L1npRYet zNT$R{KB|Zmm#leKXJwoR2`sjecvng{F03*dvp=y0R%B@$3N1FU$XZ^H&fd)b_3aHh zUdP6yxBx3gaoGSDxQ1lcpo)pqG8!XOzqOT95T|xz7IX>D7DccCs)V}aK2^>%^8dz| z@Rfkv6zj&B&XdS*F8=jnaT$=Sa+?v`aR4e8k)Y`{dD3ux7 zfSn-1KIYMRw=EqWO$uUwwz@quWq$dW5~$>P(o1!%Cgs?#u>(dY=+bM#Hnnl7r!C_e zl2<`u?Kq_!D%@VSLQzy+?+XZwT8N84ZVf=kg--uKiq@{w6%~AAMZp!Hcl!{z5XeDhr-UT|6 z`*Dh~$QP1FtYATfN*NCD*;f%He=}RfS_N!&3QPECxvs9ac)%Mzk(5lQ6-}p{YUr>E zNohufMC~+5%q~M;Km<8zOWuwdqjVm`Gzl-_=atRsln?JFwA?i%l#g#})%DY4z}?95 z)A*x!j>(=}MK}A%Fj(;p-a2R#Ss#!$c>OC^RNv1Y;?qgih3`i_VguVZ1D*F zh+PAt>c~mc3bKVB@tA`wtI~Uq^o+B(sJD_g)}%7S#PxFA;}(qs^WUL_86}>yqQs_^ zJC#rt5=vviu?6GVsYHb)69p-_tVIUc>2mP~v?ENr*CuZTH=U-I_GN`G_t>pGc4tVr zu7>(-X}Uv`Ufe>hWm?ngu0pm#+KP`%MXKC)h~|k7ONXXSF;@_me|Qtx&75M38R#H; z(apEXKhP{Y#@|SC5Uhl-=x>kP`;U)+Edbnc(1b81tzZh;s4rZ##Yo02au-ucdqS(PbCu*iG&XrYNC<4Wv*RSyRnPQ#P zmKk4o-u}pExyX5?M=;ltlXyXNL;yyFs=D{)Ws)U8ZNeiJ>&f>%5AmkR*u zTErExxALqlZz+&lo3WhP(LL-Cjb$j~AW&W7ktmH0a??fp8B7n4ZstaALuB!j=tpv; z{(4cy@%GdD`Qa8K=V6Y4DU=z<21)TfASS5BxCzZIem+XJlEq0k7U+!8lH5jOH&N&7 z)Pdo`Fp5KxV(_JCD{z786?P3;P9)hP0>0`P-k2qI`ND!C+(V1c&_fb0DIxK)Lf}?F z13a_kBXujSRjhvsI<$o&Ve%M#8%AfksC(s+1!aRH>-|N~xrLCmT5IgC=8L;!JUA3` z#pm0zD99%y)rUdMzq>~{qIXECxmoD#+}S*W?$b2rqL@>c780K|!6HBh6Q!eS{aW~>78(=dl2 zhRLMR=x9I?Gf>y~=qH&Sv%G!xynA{k{CPQFnGVK%nFpE#h|^3!TU{$IUXT!bNdwx7 zo!I_X3h6}b51}1 zUvrh(6$?H5@mHQ+OaNN}Z2kGx>X$+y!9)6xK*oc>5JMvpX|5-mn%sS}qken*6A~F@ zvIT$yqt9QyoE`tiQPRH>QpZK*=R}!k?C~H&6*mH73;)I!W_v{wi!bz;;@^0r{*&}(Q`e3sNM z-k6a0@bVn=Zn7oMZ%Uvf$Gxm3=)(018Yx-{|4s1{Re4cI4;WtWXye+85)>e`;Qa8^B?;d+7b=d;ETI8#x;!4gGCs@*&Vo=Db#nfL4|8<7PLXMZ zA>`h>93?rT&EWnkeO<)>1N-Z@_}8@J$=G)2wE<?|6)qZ8F9KchJm$D5kV zp*Nc?r^&Mmv)-e)GD#X|v)oUwi6LT>|q6ymX<@L%?VV#GEOy{%mI5cmm2p zk%^NVT4T}{j1>asGbBR@BSmu;AVoL#Pt2JDts}trUx|XDIJXawwYmg$G_@Tyhj?Kp z-QUZ&^nPJx;m6WtX(59(Xm`0Rs7(9;m_lyfL@_Mc*jq^)N6jt8{RwhhJ%&O;-HI$C zfE3&-y~Bf|DdidYY7bNCdU#{BM2YQ@b~U})dPpEUzd5)G$FSL)o-QiH(Y`h{2u7mlXU(UC zUCX@uO9Tb(k-A%N(w2Wuo83c`_#nN!#jXx4Cu_R&PN(WGbgX}?ul>J%7mL^au&$HD zpWsD(eEbA2{Ga^F1aJ&zgY}tEnLognc{Ba#za*j0 zkjS#tYW~zZ(RlSGMlZ8~--Y3DabpZaz_3XMWJ~QsL*`-{oMO64xV9%rrrlijh~1!h zgmp$I64XfZ!Zm-dsz=0`tK*OSaRB8}F#yh4r1jeVG@DhZH_h^Y6sfkI>5Fb}TE1$R z|Fh<`tNcG!T7dW^7^x_pByxSvTv}l?d{2r*O}T08zZF~S-lNr@dC192r$MO>INOT? z@4d6;qt-N(O-7~vCw|V0Iz}~r-7rAK^q)v~xZigW<$>V$RHb5`@vzPk5&G|MsY7B^Qj*8Ay7&gm+hkIw;$Mg_Sq0 zFjg1750B1(vbC$ow$XxPj*ddet1IS%$uuw^Bo+qg$zWJr-UZI}9oo-BBbpRltEj!T zw=zqqn+^8TQAM&HI2>=L2(h+q#)fYxy&Itw_nPMbPM&ztkUGlFddzC9Qmu&SWZPQ?yF(L$<6Kcy!5xMX)L&8uLVVa7mHFOLcO}% zBc=}S)j2@rH9DhmnWCoif<#}N?$gx_M~Z1&!Oc_tkAoaZNAF;y212UifVkag3a6mn zfks-ixH}@Nf-%EBevb{;MQ-46kq>}n0-fZ>Zk7D zlzi0=PT_R>gHtY-qUa`cvaNlaYzkMjw z`h-wxV8^V)7gKtnD`k^w^VY+xqv4*1K_nGr0nZTeX``|n>MUhJrEryv0hSv{t&GN@ zjPzFUmKHz|1=)ee%Hzjf9NNvG{HD#H1K3k?c+eA3$LAOvd(eg~8Xf(Nq78KPc|@OD zts<@5{O?7S_p1`U=g?gUvO;1Ia4r1|FAQVdGdW#H5{34WlHzzlO$pvWYd2Q;ep)`D zlcO{xc(?im1=Ps9UYADOAMlEP0RaMJLn<^?TfW=Lzns?7kqXU+YTtYpR{ zSWWmztuJfzZrKd?AcAua2=}a8$~n9jmV-`#S?Wwe%^vP=7PH0nd4>$yy-`ZFFOc4u zJrbw;>ZZhhouy8JUmB;m`~MwQf^Bo@3*k}Odg-L6xp~xnRUYVWatxIBwPo=N|;t zz{FNC4Sf$s3B4th>8W96;|wm}1d)vl!~dnWzf7QJa(Z^NyjyRyE6ZfXR!J5~^lPl) z0IAe&S4|r6_yxxLp3Swu3C&bOe|+`!Cg&2wSbt;Cj?ob)>MPYvCQ4w~Oj}(E%k%(U zW$WwQl?6CSSpY4I7K4KEh7f#%P_U?+HcBI{xE{Gi#CW7erRw`0^wJF>PY9~r48Smb zhcp9y_X;$X2m4sucSUJ*mxsQ#KA5VRmXGsTn-);WEFWdI7J1tz z27Q4m14pkHB4HGH=(3B9sEEJ8ue%Yc)NPia)M`-M*@)uw4d@sL$HRNToMoE@=8}PN z37cn!;@07cjd686AuBaLqdtayzQ-s4Z9tZwGjiErEEG90sfKJ)yPBp5QHUxIxv!u> zU{mBfM^#uF4rlKqy)=Pc4Z~W}^V+W?Y@M1ZqjOn+7n_eL>d>B`*n!n&rlXm0uL2}7 z2g7>_r_%gh1J@iMV*Fkro%v(bf~jI0i{*KBxQ7YyG?Ll&9>OKE!m@5y9bDCfMohfw zlVOlkn7s-LI&}7Gej}~5G-R{|aKc5yVucMF2_6DrMA#5mPsmx^Zz()awOK?~9$^X7 ztJk}fE8QCp4uYsX#H11R1Ecqsx*J3GEr4^6ZF7#p#FN(MP`Fgav+Y>b7ZtE^%qVz7 zA#z|JAKC8cZQDj`;s-2ZnPLOF6fr}MNF0^ zUm^V4abI8h(D{^OabF*S-M?dl0Ci8Jb7^`7JpS*IaXg9{$MCFTCZM)XN_j>7yMQO0 z6$zoxLz=>jmd$ZpA0j3PEX7sF`bXzRyDv^XihNzF4s_O@^%V!qVr;Lp8!Y>X89nyb zbOBpcjA1X(hed@2v;>YHT4BNE&3pAq*S|8y0wd*EfE-`3d=}>_fE-R-_H~?93F2`K z6WBB$u^5*=Afg)8h3XI(qod>CAuhH0opkF>Qg8p`S+bo(R4T$=N<`&8rJ?6i5ehS| z><^C^M*u?LPOShQ7dLy4iZ3oerH32z?sRI1Un7)t|g5mAnPpr_@gUwTQtM;xkU4aONImUH{U)ZC4*+Sk6f!XIB}1LNPSe=(b#_ zNU3jh!;;4;%TDWF>bIu(anaqFqHEAxZbcqBlJl2Ifp73WeVkF@!Ov0-zJitJ`d{oq0PH4sYk*ZkALw zNi8u_mvBXHnLFe_08RETpsaO^W1@?e*H;u4&fP&4j-Jz^Y^kOrL?xoTSVxBJZY=a7 zmY6rJ#;$Z#bIdB$u`Sd~%moK(m+p{xCfwwYLdlm_e; zelXL7WQ40@ehHJhRwRW4k0zg^nH-}EjG%HT0UpS$yp$!fZVl;p{2$^TNSn&b7eLYA zBY^9GlEaVM7skFw7(ogg&*caI2%Q|>PbIYQs#R(h8oGtyX(CHQR9bMnd5B%ou~NHK z)cnCOIgTl&VB?yeUQEs~p#YvcPwpNVer-Twa8J%Ln0+aMcbj7}9$l~3yXs@-cmzCp zQMA;^-%xgkG2)bQ!OF;Ta?$oWpcEG~Xct6<6N}8ETmruK_rGDP56bvw^uNJ<@y_6B z!M-6;$Hw5Eq&hX1+5n>7K`!{i0@o1?j_T#tdYn62f0Mq_(^Z&0-eNh!$V$ro^^Rm~Uq!37(tF8=-SfQ-h@XTJ=gv0u=QNhpjtEN8fFF5t#s2b9(*z#|a8T z9KqeUGuriNqW-r@cYk$;rD6Xx!WCJO0zV$ zAI@G-;Z83EzfCvC`y$U6+my1}f3C0NzxI_d{$lkG=ZN+aE^cPk=%~Nks=mqU2BkD#Fr7Mx1c6WUHyjy<#2a_KNH({gl)S?0k9F!i9 ziLO%^=k-sRrw`BD`!8Xw?1A+c7xS&UC2=9mCdMVaC4BO6v;H%N@uz%``$S6f=AdYN}FU$)oZ7F@fvz>OP@w5sd(s3t#)LR2>Wslp;c;ZZN7|sg` zHuh^NxkX4HOd#$J*@2{Xo+Ml5iwdRj#4yawCG7S!^{1t8EeNATp}8X@*xpy0^~(BT zD|!>r)9^t6>q z!wpyFT}wU{3@|9cssm7hIM0YWw&rn3{Na?{OVE8!)j`MPTcJ~U;Q$AGzJ75bFXS^U zozQMc-%&-wwMxct*{m;`!aZ1Gv00x|sj?X)eHEoKU)ocXX0lDg13Hc%W3dsjeC)3A zJA&dmMz%Xei05|_8P<+fujj%h*geIE_O?ZBW*ju80|8s{rd*9 z_m-Q{*>3agAIly2SdY@5b=4oF1hgf?n)L@+;mHs0gGfK+cC&sGY!A}jHP$mVRTx4Q z2)>;KG@0el>sk@fR@_Zr;{*-iVu(J!f-P&*SZ4iW0*6C!`7U8C;8O}OyJjz=Bc$sv zAdUUX&t5*1>1n@QE57kjufdXC>17nUz8TX2J zmS(ypKB5Dz#9Ji)1&pevlql%Li4CYPZ=PoJo7?l_lZ(^&<=OGs&EnG5u#o3nsHhXl^B^NKOcQS!PA41QyyPDj zC`F?ySb&L{QZ%Yp{TeJn!Rk#J=xhtgxe$JIh$5+0!1+8UXkipez2rijKg~DWCFX%h zu9ZS5%>c`hp}Z~pG;MSUt|gC<8;l_eLj_0VcTNx74DG|Kf%J zGX}0)i-JKewzK)=<=J?Cxx77^pWL3`UD$rumPR^jsz(DCz;wc(Rd&8+y|qq%Kb6{R zv}rcl-=AWp^LA}EJG@m^@!3Y~r;j1fgt%gnj^YdbO5avVohTN=iywC|sG(zbBYh6FWhtXu8kh&j!snJKm2RNV+-kYVUo?* zI9(#`@oBs9o@o*m2-Y{&&6-xlqM>9N@Ag0Tz##SNDU8l$vy%;%GqALj0e z_qT#!fV0OnwEN_Cxs3(q@(vpXV~Gt#x#B2O(z#9^);2@53L`r^Kl9 z*5cqescGEoq0RLC6ComO!UXx6h>1RqSPzo08~KB<_T|g<(>H0s$C$2|XS3-7)v&P{ z@hRdq58r5cOL0wD{m>@Rl{eLundVk|NUH^|j9Xjr9hoVjhAss}(Vix48ZG)O7*zfC z;;g?Lt5RWMvJdMl9#bHmc{*%TS2yZa0Q8E!Ek3OD4N2FI!S+^`fGpH~sP}z22fna( zYckva=STX^=9UDu%;LZyzG4oeL`GT>iPmmPG=fyqb7C0&4?M*CHD!nvRY=S`ABiU< zO@RGm+EAlp)EWH@WAOd70^?&m`!5;&qun8{zR-wZ7lHHzSJ-S>Ecy91bR40mv`YbA zMig3TmX1wBkVBfKOSTc4C(=o?GeowP_*`(Mp}>Zr$4-bX#aTHeG^9y7P` zj?i6%&rYDre(cpR=!JxJf^R^?u;pKJAO{Q?PY;+d--krc|1e? zD|}M?$*)?1V+f8lJvnVK@E-G_E)Jcc+9wn3grWW4D3@{zuggXeIBHSUi5oWC=O=^1^U-5RB?Uw1SIrb#gC zEo(YHjsCg#qC{U08~?PcU=(<4J} zH=B2HDWffE?ia$vg1~Gskwp;eNCYXtqQK3)Y8#`a8y(DLa;dSgZ5lp{k1E6yYi*?t zMy7^!_1L1q`uCY(bGmp~&O@prm|;aXk`N2eD%ighB7jPpr6HlIK*DIGKmNeX*ppy3 zm^MLzLY&PO^>Nel$YgS9U^F96oqU!>?y*RyF-eJ0F^&WTP-9Y1zLUin!!5GaZ;LtF z%*+yk)zf@;ugSZYpO(mZY%u@Lr;E3k)5S&sP!DQ> z6=SNB9Ynh>gs*~mM*l^AlqF;ZaTF%99QlbXKR<@mWN62xumsW#wV;_#2#HGb?MsPt zN$CXU%himBaC@}}$6kJ@a z4I)0w%m7fLkf%Y>1&VC>YxAH2#(KR@^srD6+99+}=jg|p9lj2X3s)H)T@j$T0zrZ4 zf;eU76RNQjUDsE57w-p0>JA1SJ=VlCqNpIt8iq3rKSUilKYOggr=p zi-bWf>>C#5Y-aUlU}eNMd8zq<>@UQvgdaLKx5?&hlzg#Bc&p5)FY34PcwK3I>sQ@> z9#7JBm_OK`Bwi(+!G9ZH223gfwt}x(3j~B>*J_NX#VE zIDDyKTdW=#nQQKL5$m0LGxW5z6@rOl9|{*~_cV@v7RXnDsdey? z&|^7U-PM!59)=t204Pt`76RqK!JU?i4N7C34ahN;cWpY(mDXPpcZs26#DrRWB=-(O zWO{UlnD1+JGkvw*yxTl|nm@vCf*j&U5;S(pP*ikg=>acotU;NJ%y&yRW#UGBH>9+7 zlbEk!9P4$Y!^%3|W2Z!2B*L?@B#in!%YLV$E|_sYo+i5NiS&HD7S@OKaXY!%tQX5I zM{qG5$bf?5+AQC<-&vQC$szuXGDL0rbakttN>U}qEex_TCEwc^<7V|qUUOoLm9<1H zx;fXb5$?u`9r%)lvllHM3|1up{iOcf5lCjNsNo{VQ*M?u;z2QvUp>q+TJAYDhM` zRkU^=JC))$g-@1+ks7#uoR86)cd%)~YG)_N@Ujx+0k(SnutT%j#Xno4(hk`mi zb*kXNu|kHbei*@=O+UCkMxwMr?Ac64)ODjns%FQz9;@}2CtYXoUmU>1HX5`Fct%&zyFyi?U^SXEXocj}exIECnvU3TFoxu?)TdaW@k89WI zcbDn^rEyO&UhAH*Jw6I7ZzDl04H_kHg&vQ+mzfy#t(wn4z7*?$c5zZZa#PmhDyZ31 zZIBceO!y$3#^Vp`r#H(l%ZJ=hK_&;Ax7n;WJhwAh_&fiYqtwNAhBW3gT8hlK=y7X} zFWM>r)jTk!zl0i`xCD6#s-&U#oa~W=ZhA5=Jt*36`{D6Mg2Y0xMmW=PrmyW;o3b=5 z3ZvDTg~3Jb)FG;OoF;*c%l`B${jd@7@?IJkefZ=!v&4&8aN0O7JbztACb|Y&2ZdlU z%44mv=l+_}7lpJt?0ipC_OnlzXC%&CNVzy;q9W-G6s6)ZPfIZN8&P$YJAhm5*)J}? zt$Irt+TxI;R3?wtcYORT{WmaHH5LF8e(ZPy7q!q;j-_y|IpE1sDSKZb$98Cf62XHF z(t8m8o8=w4G@_Ngkvw%L`#T3HZbJ7tB)NmoFhgdAFRR34?w}tr4>W7)}#O zVPZLpoe9;KjSc_3&=r@^VVfn}D{=agw}+sNhdIkWq|kKaAfGzM2v7@Kva%qosC{u$ ziVi5DWYC4KEg}>UsKjdA#Mr_q1VM!}NTmntFU_t!tpB8e%KkQxcD2cl1Ku22$CIz_>g4uCfZoxM1#10z1i253^DVgAAU z7qbApGIJsr+<?ZfO-J7F6R2B>U!!VDs!1mfB$s9fR{5_$)3ig%s^D51>yn0Q8Gc#5v1tc zK;Pl$40Lt%Iz$G@kF{L%gq|C*xCZn^w?!DY5N93DBn5$p^7;+})b(5O(fTMphP54( zRG|cX4O1GJKSVc1$M>Au^0Zm*WME5Lb+M03L=ts|E7NKP&^NAmY^5piF$$32fpr;oHgvXZ)|6gAnCpPSxe4asYqGPzFkHH z%Hw{-CMoO_)_%M2A*)EJ6(w5MVP#u!o74`lprR_Qs~5=`={{O*50B0}u&XdG6J2$8 z$jMTx1$mDaSND*gcTaMq4=kt-L}ZCHMsNWDK>rRI#OE&+Js+M=D{l}A^i>)%1~S8D zQG|P;lC`o)pe!8p6OB3T3qyqdSW7f9WZ-i43U*wYEN}@3!4uj=@BVAK+1{@o!<_Fl zA3#W}jF}vdv*sC)`xYSq&`FQ zxA@Ti$*(##s-~g7sTX?I;`WQT^&Q2#*01z!eOTAG@#pbE&EMif|0loddgw|5X6dX7 zZjIB#mgz`=f#kuQfoT(E(vi1&5`}Lh#h$eFYTM8)l7BZuJ1TXt8y~%Y%s)MZTDVAD*Ak!dq0`o7K?- zJ={BRGMbXqyp=2$guY5dX|{<#T8z0?8*VZu?knqoMXgT0d|)wA*xsO);zBd?qtQ1H zTruarjQm$EO>T=`5>+QvQE#xzpL`3W;Un+jeZ%zbs&PvcYd*eZ`MK>8Cu&u10&#ax zq)M3bmK!zml5~*tca^_QPWZ8=CW8YqIBfKoIz#ht#~Aa@!k-lR|>q=htkDA7-F0r-Wv@X#WX zuySGa>#K%cZZ1{_51FOVayn4?7`%?Ka6{4nsER$;B7+$B@0J5-z0csNB(@LAlsW%B z=dnPH`2L+n+fYS3p3N{Be*Q4S09+(kVWZ8qm|8NuTDd?q+5xSfw&?aRxn_p>B*hGA z4Te53%XA=GE--vn-VdW91IvAYL!4^E%DOOoM_8Tuv~Y%OvOaT0xcb=1j$>w99 zeh^xQoXL6EZe=`rK%;TPS--y_&EsBmP3s8 z95_#G#O_xqxG%PzZe610P2iT)TsY1A6o-SIZ|HF7m>%%cJ?f=;{0#4$|1GgTTNGL+ zCH1x~iIXiM0eN_DSk9%(zPtw9c)8szZ(rR%EW@~`uAIzS92qph6hVI%=b>deOq0Bm zt3|6pmmPVsHjw|{D<_r^e1X0j&5Xg|7PS@GYtdSX6F~uy53x#TKW^C3`7Jhfv;HPI z^f6E?Y&3g7} z`GCgQ(>M1=OqTIEn>TPkd&J<6i63OLtI%g%TPVw1I4;(iwY62lPMfz`QUBfufQs1B z0|`U_^h5vpI}YnQNxTYP_|q1z@z(#zuR4|?vkEM9(02bLIoAIDp0eT42JevQyVs5_ zb2vKpu)Bt5a}yR;gV~qrbstD=ey3ZMcK|55HbZd2Y)^on^Sd55K7OcsPj~LGV3p7I zb}FQ?otyWcY4{#GUsdnhZW_xe-l^{(ioRmh(uWJF%C}Q-`S!pzjF8e{j4tpg`EKzs^7{NjqKr7XXb!w5kl$>_OY zB=#B*ma7maOv!ijL-;W;i|}BmHoq06w6hk2)dUeH!PPg^?^bpN|R1NA|$NDPr!HDOs^MJ9rou(uFr(iEAFHFpF4Nj{giD?3r`tNoyC_X$gerL%=+T zO!iD-fCAxZ%{P&nlHj{J^8<%?B$L^PnJ|&HJmCqfcEal9LclJsl#8*F&|L?Ys20Vb zGP+rZ#1_IWoHCl_dec=I82?l@j~KWVW?|5(Q-Zd!+AKC{NkMiCXCgm@J_gtK?ji89 z5KoYUI3@r46=EFaN~smg?Bj~jlPDcj9OzsBuZjkIq6ZXjp^}u)YL7DgNYFSfDBgh5d`tTG-ny6#3FP0ujVCpa!A}asg4>@q#1FU3ui5g_ztR5k9?!xs4_(H?tj#!t`Sh(&YMvt>;st=Jt{M z)|=V(EBrLV^EKzky10hc(v`7X9+NZ23e&@$x~As+owf)SB2bsJoZvlb05#6ygPZif zpV4A;_ib2z%m2x>mRZCtQf6jLbNNAvqoO}l3}bpm869br{;%`ZlD~T`Q`N{$PRe!q z=_*21%;L3((Dbi<;y?GF;I(~)t!qi$es^Aw+c9$(l{|?r8iD(t!G#U?+)bln3rzY< zRD`n9LsDqQ*21|?=n$?dCa>SDOsZkgE`|ST`%a+=eu0i*e4nX&Sy69|gB_FDctqSH zRjBTFr7c!MvZ!zG&lRoCSzks?ZAc3gE z!WSKq33}e#fBdxT6JE-3Z8c`DfRY76aO#*CXkMk#iL}@4kdIXC6w&;;*e~ihudZR9 z=EB;90c-@8JUcen(-SI_z#h1g%pNR1C5q#x+!O7_5M}!+1T3&>j#^Xz5p*45u+}$M z201%l+H#@A#mVIs%tRn;A7}zgDz~2yC{rsVW}9ByIso=J^rBIf!;b?br_M5Lr1+k*DD02>O!~xqp77@clpCi^e zWuQaATNhz!?d+#_Euk}pc46y{0Z_<-! z>X6ju2!++S2l1Qa9z60B6Fi*HbsfB_**yvQysem7%TM%0Wp>rD*+sKX9 z4$a&`v7i|=+_a+C7kM_Bu{gjG!&I+!y(z2dI3z*w(U1pG-%*mle!^M!TfU>_4)&H; zj4q;j49tBVxAcZe7xnSxJ1H(x2HuY5!sG$UMd%cMO`slpSL1?EsC{YpW51fg*05+^ zBUTw<9bwIKm}MkG4GfP%09<+y=~k85HZgB%nK)a(6&Toshzkae1DJ5J8*O({(yhca zJWS3>aZKMa*r3@ms zEHS8Edk}gC%a4R)2C}7IwnVL0DCLkzHX+deuy)d45tn{OW5xf|+_n5jlAQHoZOmc| zuq|WE!_pw{!5lp5>ZR^|ed56fSGuiW;C#Kmw1$tMICo8R|}_#!egE4z2V9`#gZW@SW1Mtt$TA0YAv z;oY}HNq7=6i#mR~!_HtI28UW(H;UZn?yh5Dx+2*5vNz+EYx)6MCohQkR1(HETV^N) zoeo%{h7%~aT!FL28{u_0#=JH*77Gfo1P%Zd6ilcv0$`FCi`+(O

vD_nO5{R9Lez8;M{)1!4gq7&=g6Kc(*gPSWoYrZwv!M^QvxA za85N@+(J+$Qzcn9z&sgmY9t5K-AHmgeO{-xBn*;-*>(xiM?`u?t7$sgFgsqu+i6m2 z!kf)$LZZaH&khrW;l|UqC*#v6t7`mozB-3ub8qj)8*f~@elYG|9XL8$v{T~gl!0w_ zjKp??F{Hw~Q?%wINOUn;EYh%SO&N4;B(6zaG(s){$;x9Hf=n>|E@OIve6?{E3=~2Q zwqIY(DEK3@CzNAoJ7B_uL#6HRc*}U)2+V{A+_o@-w1!(_o+H#!7;lC-c^xu0$>+fl z<2{T;;f>ote*tg#QF{*OcFtmfcZp>y0wGgm zSbzYzo`Jt(6rs#e zRYUwA>nD96%#d8YB3ptnpxcN5Vn)iY3Plprbr4DH85Yrka_dR$f=2hYlyva;X+INS zI+ArplE8ruJvKn4f0#&R1->du?H*Bq!vT|@hWp-r9kp$kn6?E9)wX*?vtjev{%u78 z37U^%JGf6d&>n(1Rjd1VZX7R9D$bOn&|4Snj2TZDSP8WYoE=%UPtLc7QnHrd&(V6v^Ev(2(+QUJT%aqNJ?v z1JVI@E9m%8s2!zg!TsIFi$Of?pU$gk_165Xf|v@6J6YVu=RwbErD<=ZrD?HjlBdIh zr`OlcD1!Fd{jJEPr5K#_zOF~qi{8YqPkB72h4 zHIOH&fpxIYH&||Olgcf(#zQB)^^^;nAHlD{k@KUrF$*T{t*YZGbnEGWHRlNsVQ@E`}%R~PG|Bb&W1GR3q~y?&kr=q^OQ zF5Va&UQV?e^oq=Rlxf<4+!NN}R%0aukDAeIimuVA**IzK3UuEsp;G#dJB$ZY6IOro z&T>^L4{(-Zo>)Qy!W?)-sxXk6orQs{*{zkeG1F`gzcz9j_&9(_83O{I|pjFAF9*xoe~Ls0S}0XOzZZK#-WYjQ@G*~oP` ztRk;U(dBr2`nrCz2B;1fX(IAj4O%+SfQ!r|SNx}AUSAuv zRGRSI>0(_K;4PRWDx@dRCG0+>`+s%$kn5eW)wYkbd#HW_Z=PpN!QyhWlMpZgldXuun2Dvme^0-DA8#DBn0Im!u*>Rz*+| zPfo;&_-3f`G%cS{{U|pYrPX9UoTesfuVqaLRSOLc%x}rlxG{rXmjw#$$dRUSL9=lX zY9VkYj`0041RRD_kWaT|K{=5e4#H8$hJuuluP*>bhXB(<{G4c*DOc73x`7WR!Mv%f z941np0dtWu3^F-sVn%WzAo7mCge%UduI2URiZvytJ?zg!8`zcju^E}RKbdo~bjM&q zDRLF*j(3pmc+;gj-obLtPe^ZZRw3i@(ejMQ1T+Wu2UT7qFESOS7iV6mpyp>57TpvI zJ`)y*d~rIrs^pf2g#xQ4#{$8xH5TmxsOJbLU#@nZ%2ClYB)q0sh!$!da!mY%5YCXi zn`GuvsS})aOdXXWLgUkv^G>HEf>p*!3b+Zx$xq=k9E5ueFk^4wO4hAE_5Ju`>9&5Q ze%;@LRkp~u0(>eYzj8z)>&W1?mnF%Uyag6NDT}}X5pT;Ier4hsAGb>;f=2s5<#r1Ml zh+fP~je{tpZbG0Brm7&iLux!C8Gs1z;7p5*dZc>pVyp*5b#>wT9kP1Fz-((I?k-Xv^dM$!#6?RQZD)Dz-l9txnTy3hF z9lZJ&R+Ihx$4+|A8As7BC;f7!8FCafp+xkTu*~WOajz?smu!q1cStVBtQa4Mk?)v4 zsxmdZor)C%Re%c?9$!(+z_Gu7{63&pJ%(zxc92MSq+o z#Wo2<5lWuEjPOe#BerQ+lG0>^>VZ9)1A(m;VK6cu?3heW+z%nU`Nx45p8+y8A?TcRGl?=Wr71Ya|sus-8Is1o~M zpuN$gg6+rc0HsOrbS;vs25!kb7XZ!~u!qy^!0)E;Q@H4_;8;!}LlxL8Ohl0XVW1jZ z#K_8%xW?Z*mlC7LH>YNWI(z?a5U6}CG_V$X`VZ3r#iYJ-Y#p>M_%kHs7NTLM6TY++ z>&RrTnL3D-t??G=VB@>16kqLA=|is0TW1E_q#nbbt#9C=Ab^IoR2(Wu)4!{|aYVAk zCQY3eZ@z5*2CyE3*ThF>@*;rj0s}Ihbf}k_%Crk`tu$*Fni_Yry{+fE0>Vy32(Gct zR-F=OC)aBBIa5i)_(!ob9C8lk3NPM4{G*s#at#AH087X_u0%Pp0!e4N8ywn0X5dIs z%F-BPNb`^%ew0xrWe3mL@O9STJvtrlZtqOCr`6GHIvVayhBGE0pe`Z#36cm=o=TVK z#f(MWi{o*))@hsRtPyGo@+OuV03x3_2!H+x&{^$z0WO@62L~-WjM(P50S}hwxIvqx z7KGtD@(g*mon>@P_Ll?gWKZCF_Q&@ZUbEn+-{d5v#q&Cn=?3bMjK6VdvBx`mD6C03 zJfv*=#9>X3bJi=Xz6p*(+^Q28$2^(~*7TS%9BG7XHxQQxOH~D=$cAon`@wQWF^H5H zf{T9Qu{Vso?%bT8ox=FBvI9i+ff$Dz7TcClT4tXO*_ z5ai*AkK5Kn36?-zBeRoWr<8qWZE)&faT!e6-$1nGoA(|~kdC57N-Dgx?TV(Iu%5KB z7mA;|i_M_Soz37H4#0Qau?gSS^meI|sA-=M+H(aGcVGr9rJae_qhl5VX-zDd8wey^ z-l-PL)iYGMWRmG^(3vM)*l^H%v8K;+u&g=-KjOUVKr%50wq+BqNmHRwtSe~OopI_n zNjZ+7faAbRY^j>R96XsKWzMiQOQ3Q8jn^Qhf%%bjM@o30`cLYt=31hCGET8|Fx4v2 zNNX}D`RR3uqzhrsQG&s)GKpIA5)#UA8wZsY*@7+^fCm6#Sks~NyvAmDK7zf>F2Xh@ zhnRcZ!e@t%QRke`gTZqY6%6dms93n{=n3wO%%O*qw>Z~AHB(z6Tn7l~9S4&XDI`=)U?mPW|B&}B~$DmhJr;9Nqkq5z11=$2&- zLH77Xj{RpqcQ4UR?+ws#*?qus&QXsg*4{tJ@SBaZ{X3^SaDAgID!b%1?x zlD+|{2m!+=rXKVzZX=peWxY>ewmrfwa@T3`-OvcxyGI3xbPKP3mc)8UKcQPW$S&Gx z!#?bnvXI#RP?S~9Fv2B?YQ+A+=?3t|?Bzy!L@i$7Hd0tKnwagtN8f;Uh|J}iee$5M zU*24v99C0QTVGKos_;AOi6b{|;2O3tw0n|f-Hm`V=Mw9Z(nw+^(tV2&{z8$OX#)#+ zKWu^r6snyC>*)L8W!y`LX@CA$rNFqs3cnD=Ns(;>Ll?$_NzQoJ0-vyb9p+W|CsLgU zm9S_ZOFjeh0|}y7#BCvsI+^4YAAlh9($gj7Lg*a8KvyygP-g&j#-T|4+#Zish#C_# zx`){93d`l)4V3O+uuiLP&`92yYh^n2%FOb{Na}P!0%~$-O5(oGD>p^C-smF5F0f3; zlV_A_wvpJ(c1E+o#^`8!wlmn>-5P}5ON%|N&JcwrLp8f+-)uZ1<{|@Bz#IrKA`UKh zu5%3kqr=I`!|DLcwJPucZ*f^{RkA=H6bzP>J;ckUZu8BqX$A4bG!q$4E$4bog{BA$ zIt8ToGzjM0y{tq}mU6_-A;Wve%WhuPwsE>RP!X6cPABK{qdDbPzVWDm~Rh#ip!i3144DfcjwL$U|KR6qZN6uO6>qH{zhZE$FF>3@A4b^QS;fx(-j()#?V(tT{N4luwbYAm(?W8tT?=H0p^ zyGAQyasL8Y`YBh!r+}WEV&~w%0VAFIzxvJc>xG)|%}uYY`0^uA>&xWE*{R?#{RF}6 zo{dYhTd>ZTgcUP*=%(DjmMoVArWH(lg2FaVf-cL2!hqO?`-Q!R-6a&#p>oOm5|hrH zFE4W(=q1}Cwj1+^S>_!xri8-5DImu7e=5URsy~S$UQ>YFe9EVu|L?kIJP7(@hNM>T zZ-h0Y`MJ*^g|}ZnULGYx|9&Wac=wg3W^9ibcMf2tQFxk~kOw>@tzC(`y*(D0$bqF8 z_Pi&Ti^KY*O;Nq!W3-;X*i9u2XlqvRtW@8#Z7o zv5ZV%0fBZa^QtZ4@1pL_I>(~|)cBdq1S?2^oxHVOxrI4-vqM$Enpa%EGbZ2Y$04wW`>y9KY^oYn&$z z!7aq3(|p#P8X7WsL{qPFI^tjAL`Rj?D0R#04;~kdSXBTX;rI4 ze$RUrXen*kK)khNuwjjxWGk{fA@o28&~Lk;Y}ZU(|9hMpq+B94jtJm&wFP$e=M*eP7HLC{aV9$W(mk46MKclSPQX zUWP-L%#>NU>r%QbpK!0gf$|wo78Ml>h2#9@?mm3^DNnRyi)*52{f+a<3UJPaL|I&j zYeQ_erCAwbZ79u(hUQYDm8a}&615b7&V(OGEW`Xuf5=L!yOR}kVgO_0RwyLb!CqEa zzJ`Llj66$V%M4UbIv)oHBEE(rl>H6L5h-T=1I!OaOoDWHpk!euYMD%e+L^3YlV_Bb z0%LLb5A#5~3XbE%icthODW#y5)#qnwHA7a5W7>)kr6~0;w7T;Lb4&+|SDsH$IPq9V z$X7NB!ourGmM}*N)8i17jX2BtfnCc`TzV1Ur>zi}YQ-C%n@Q9T9{ks#5i@nWw42bE zv6>HcM<|I(8ULVPSKY{TjthY<R*qCf= z?n?QCKuppQG6?*_@Md}=xj0PKaU5@k_&m?@?9Ur9e8G{JU%T`cG>54wxhdAtlz+`p zEsnMsMMym9)_Mmw4V*9+-atP6miE`PW1RZG#t8r_7c#@FV7IE5u)tio})wQ1SPt8mv)j&c- z@%}!Ta+1l2h>f3|%)k9avMM5o1b~JCB@}i`{ly5dJn8|0BQR+c%^*mmf@7Cz0GJBr zO%t>ei96T@&1MZ&Gg_@zsOr_&GBFr~_2h)ZMej`BR@QewobO`|U+uUxU}Zs4S7A1r z_Xfv@>T??sVKey!oZIw|XVv*+evCD`M%7q|avU&+lr9^sjoW$V2ZhB41!4>KmMfFR zJQsVBit<~Aq?ou+7leXzzrlKv24W_8sEq4vu95C!uS-jcBqBkwJUv%OB%RN)KhBU; z5u7;9X~ay&wuYi}0>i++$Ez2`~j--a3{TN%Z$@rW=t;mOtf7l$5>nPPAl#E+J zXj~7ayyumXpvOGutK*{A&~{T;sfMG zN#x^^r81u;*VM#A@({CsnY5S@_a<}ys6ESQvoI6HvX1d1*eo^$3YPAQ`DL-Qs7#B& zZkTeK2RBtMGA#*3g*4YHRS3Ia%mm%rE{rn)(oI45iok2-sHeIjH!K~39tpQ_r!J&#Sito39?g>e=HxDJ&pc8eDJ4$Az zTk?jw$5!28ivr9P!R_y#o`!7}@|@KGoZWFS`G*pm$%gQJ6KoFmo3ky+=EKA|_;4Bk z+g$mMb6d}Ll@DNTO9?<|(2;Yt5VqKF{BFsb2E+wY^*rNnqLo36BiF?^;_RnpH%*Bc zD+Uxq5|vP5=}pah`*+3N%S^bW5mic?Xi&kA)chusoTQu~5MV%9R)Q^(!3mebu5m_R zz*`c|%(pf_UUvlpz4(Z3E+6pin?j`2aa4!eg+##{8p0DRbennXt{t%>(ks*tzz?X3 z@&;u&8srtsbJDmq_S4)A?1W3-6dfl)&SYZzo?nNtz(pM%K?_=G(tDuk{>H3Q1!)D8 z4J&xW8$sznK?jp+v@z`O4*Hv$gVA<1G6<+s$tLld#+&c^y7n;J%{X=Y7;{OxT(0=* zp_RW_yV=kHI%p#FUL9J)IErE9VeUz-Z|3eMIB<_T?5S@gH!R(1`$_t%x zpjh)zA697r32?4LudtDIuK^=%gi%AfH?yS-h##l9bc`3G;=tL%WQ=LtB3B{nAv(}w zn0__4L0!pR>>!N{0_+!@@X>3B)V6&N%%f3|_ezq`Hk}xj5p+g~FBd!%Xr!0Ufzrf( zO=&s$B_Rm!NvrIuK@Lu;w_JA3OeI96silNPqlBK7eW11JY>D214*7&iwC*!vh(T*c&o{$W(sk+f<&?{xL7u3qb0=G%QnG%Z38tKT| z00SWu;{0s?E?OdKdUSZ;nG)o7A&G#(J21Bm9$gL%X6U<)Q?h+ucF7>645@Rx9r@+KK&+e=tvG?^`t)aEgH8MLHP z6OIHESu&2BY26Tj3&|m^yJY9)5G$uR@QD_F8FF7HUWxUU<;?;#qh&$%r4n)2#U}Y> zK0BG)MA>iG%Y@?b1F`!SSb+2S^5o#wQ#{%c3!FJHA|FuvV^3q=&>n<#sD?6gw73O8 zdlyj z{<;j@58wY9j&b1s`2MEXYEL!-pXhG6k7U=8D5sK%$8`i$?a!g4AH;EWdsuL#)I6|( z3ypFSUe^l}G=dxu5$ZykL*`JJtH(`2YGU1Oj$i^0Xxp!0BauA@xk3)<=Njh>ISqbI z5OPfUd9+M*K!GdkD|I3G{3YL&0H`{5!yWr?M=DAp!vrFpm&o~!_*Oo#4f6D?+5w!0vlMM8*uGGKAg(_$WFtZ+4bzS zew$p8KK-w9rGDMtgX8Rv?{C_R#4{@~Ym*nkle0&at~Wgja(8Pi14Maig*@x`d{XJK5C}D#olozSM!yNbo<-;`>La9v=R};NE7E{Aq}>2~jpK>o2a=~-C((H)?cAN8R>yE`9-b_hYNjWJ6=Dr6bZ#|1 zCNNs0miL{rbBS}~`r?k+L0K>S1JD_33t9_pv21-P8Sg(iJw{eziq#`1IN%~cZn=Yg z!V_XayQCM--CiuMh3(YbeOp1izXb%JIC5j|dsok%E#PU3@AH*>Ke8iKIjz&spFGsFhbK?29zB^K&%QFB^{&zx`NHr_`G+Oro49*hgTmiaex%p_$1vNZdwwG>0PZJjUQ0V(fH8}o!A+ApH9cs z+tcdwe9WH1Xnk~cCS8s>;zxS23xtr;7v8YbY zd(Y|L@1vhz!T%Suztb1?_~=wG{DEG#FS^(N`w~um4ganEcV5`TS+DmUy>Nxk;>XA1 zAs_Ye>D&M4g+0FhBW?c@pT&>7{Z0JzUqAo((w_g}3wwO?hk9YiXT9F9>i3KKZC|h9 z;8XZ-?O*)Z9{=>>$M~!F9t{rvK7s%A?$-VbbP@l)f&X-?wSWJUdpPU$-v1+ zz1;hA9MGIve;<5ikAM2$GyK*27x@a$xAyk_e~I6z{dK+X-Oujv(Yv3O3*V&&;~zbn zU@dR|*SJRWs<-vN@Vk3B>*1TfdcP-M;gg=_|NRwCeEU6Zzo+d_vj#dXJ^TJa*8YPp z?s4}Ye38Gxc;zgP-_HLQ2mbj#*7iTv_CNf@Z`-Z>ZO^rff0wnNz4UedY4(z|`*pif zzq8lr{e!l*^?OI#zoYFxzogN{e^=rmAN?af=?-iE-uDTjd%gF*|9SrY!GG{q_{g9C zPx!^R-+1SneDB6Pzr)`j|7_aA*55k(=dAtkdwE8GnV3w6|XGU-1j| z`7!Q9?pL|v3@6!qxwm)tD436JJ zTR;Aveofl{^lRFl9^(F4d;9(z8vFLWJ!#+DllCtgU}_)M&c45xwg1+2Y5%S3(*Ez= zv+3|kcK#)_r@rj{uiTLKFW!*$@6h1fzbo#T4!^9=-^i|8d!s-0vvp_Rgl6s8b`O2O z|L#>j?c0s|V|L1OmrW7hxu@eleN{HbAL8l;7SZO-@HgR?((^y~n=9PUPyhQj_}f16 G=l?I)D`bEG literal 0 HcmV?d00001 From 45ee131a4427db6d97531849bf4a1c3206ecbd19 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Tue, 19 May 2020 02:12:57 -0700 Subject: [PATCH 040/656] Fast CI (#1537) * don't compile in docker build stage * disable that for now * do we need that? * upload artifact already compresses * that wasn't faster This reverts commit 2221e13c71b5cc693dd3bebfa4061d4ab6821437. * try that * don't think that's used * this too * check this * less layers * that's not in the dockerfile anymore * system * even less layers and clear pipenv cache * no inline comment i guess * uninstall pipenv after we're done with it * separate build job adds too much overhead * quotes * clean that up * increase timeout * cleanup --- .github/workflows/test.yaml | 131 ++++++++++++++++-------------------- Dockerfile.openpilot | 52 ++++++++------ 2 files changed, 90 insertions(+), 93 deletions(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index e8f4ad5511..c50cd8cab6 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -1,37 +1,21 @@ -name: Openpilot Tests +name: openpilot tests on: [push, pull_request] env: RUN: docker run --shm-size 1G --rm tmppilot /bin/sh -c PERSIST: docker run --shm-size 1G --name tmppilot tmppilot /bin/sh -c - LOAD: docker load -i tmppilot.tar.gz/tmppilot.tar.gz CI_RUN: docker run -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID --rm tmppilotci /bin/bash -c UNIT_TEST: coverage run --append -m unittest discover + BUILD: | + docker pull $(grep -ioP '(?<=^from)\s+\S+' Dockerfile.openpilot) || true + docker pull docker.io/commaai/openpilot:latest || true + docker build --cache-from docker.io/commaai/openpilot:latest -t tmppilot -f Dockerfile.openpilot . jobs: - build: - name: build - runs-on: ubuntu-16.04 - steps: - - uses: actions/checkout@v2 - with: - submodules: true - - name: Build docker image - run: | - docker pull $(grep -ioP '(?<=^from)\s+\S+' Dockerfile.openpilot) || true - docker pull docker.io/commaai/openpilot:latest || true - - docker build --cache-from docker.io/commaai/openpilot:latest -t tmppilot -f Dockerfile.openpilot . - docker save tmppilot:latest | gzip > tmppilot.tar.gz - - uses: actions/upload-artifact@v2 - with: - name: tmppilot.tar.gz - path: tmppilot.tar.gz - build_release: name: build release runs-on: ubuntu-16.04 - timeout-minutes: 30 + timeout-minutes: 50 env: TEST_DIR: tmppilot steps: @@ -56,41 +40,37 @@ jobs: .coveragerc-app $TEST_DIR cd $TEST_DIR mkdir pyextra laika laika_repo tools release - - name: Build - run: | - cd $TEST_DIR - docker pull $(grep -ioP '(?<=^from)\s+\S+' Dockerfile.openpilot) || true - docker pull docker.io/commaai/openpilot:latest || true - docker build --cache-from docker.io/commaai/openpilot:latest -t tmppilot -f Dockerfile.openpilot . + - name: Build Docker image + run: cd $TEST_DIR && eval "$BUILD" + - name: Build openpilot + run: $RUN "cd /tmp/openpilot && scons -j$(nproc)" - push: - name: push + docker_push: + name: docker push runs-on: ubuntu-16.04 - needs: build if: github.ref == 'refs/heads/master' && github.event_name != 'pull_request' && github.repository == 'commaai/openpilot' + needs: linter # hack to ensure slow tests run first since this and linter are fast steps: - - uses: actions/download-artifact@v1 + - uses: actions/checkout@v2 with: - name: tmppilot.tar.gz - - name: Load image - run: $LOAD - - name: Login to dockerhub - run: docker login -u wmelching -p ${{ secrets.DOCKERHUB_TOKEN }} - - name: Tag image - run: docker tag tmppilot docker.io/commaai/openpilot:latest - - name: Push image - run: docker push docker.io/commaai/openpilot:latest + submodules: true + - name: Build Docker image + run: eval "$BUILD" + - name: Push to dockerhub + run: | + docker login -u wmelching -p ${{ secrets.DOCKERHUB_TOKEN }} + docker tag tmppilot docker.io/commaai/openpilot:latest + docker push docker.io/commaai/openpilot:latest linter: name: linter runs-on: ubuntu-16.04 - needs: build steps: - - uses: actions/download-artifact@v1 + - uses: actions/checkout@v2 with: - name: tmppilot.tar.gz - - name: Load image - run: $LOAD + submodules: true + - name: Build Docker image + run: eval "$BUILD" - name: flake8 run: $RUN "cd /tmp/openpilot/ && ./flake8_openpilot.sh" - name: pylint @@ -99,16 +79,16 @@ jobs: unit_tests: name: unit tests runs-on: ubuntu-16.04 - needs: build steps: - - uses: actions/download-artifact@v1 + - uses: actions/checkout@v2 with: - name: tmppilot.tar.gz - - name: Load image - run: $LOAD + submodules: true + - name: Build Docker image + run: eval "$BUILD" - name: Run unit tests run: | $PERSIST "cd /tmp/openpilot && \ + scons -j$(nproc) && \ coverage run selfdrive/test/test_fingerprints.py && \ $UNIT_TEST common && \ $UNIT_TEST opendbc/can && \ @@ -127,17 +107,18 @@ jobs: process_replay: name: process replay runs-on: ubuntu-16.04 - needs: build - timeout-minutes: 30 + timeout-minutes: 50 steps: - - uses: actions/download-artifact@v1 + - uses: actions/checkout@v2 with: - name: tmppilot.tar.gz - - name: Load image - run: $LOAD + submodules: true + - name: Build Docker image + run: eval "$BUILD" - name: Run replay run: | - $PERSIST "cd /tmp/openpilot && CI=1 coverage run selfdrive/test/process_replay/test_processes.py" + $PERSIST "cd /tmp/openpilot && \ + scons -j$(nproc) && \ + CI=1 coverage run selfdrive/test/process_replay/test_processes.py" - name: Upload coverage to Codecov run: | docker commit tmppilot tmppilotci @@ -158,17 +139,20 @@ jobs: test_longitudinal: name: longitudinal runs-on: ubuntu-16.04 - needs: build - timeout-minutes: 30 + timeout-minutes: 50 steps: - - uses: actions/download-artifact@v1 + - uses: actions/checkout@v2 with: - name: tmppilot.tar.gz - - name: Load image - run: $LOAD + submodules: true + - name: Build Docker image + run: eval "$BUILD" - name: Test longitudinal run: | - $PERSIST "cd /tmp/openpilot/selfdrive/test/longitudinal_maneuvers && OPTEST=1 ./test_longitudinal.py" + $PERSIST "mkdir -p /tmp/openpilot/selfdrive/test/out && \ + cd /tmp/openpilot/ && \ + scons -j$(nproc) && \ + cd selfdrive/test/longitudinal_maneuvers && \ + OPTEST=1 ./test_longitudinal.py" - name: Copy artifacts if: always() run: | @@ -183,17 +167,20 @@ jobs: test_car_models: name: test car models runs-on: ubuntu-16.04 - needs: build - timeout-minutes: 30 + timeout-minutes: 50 steps: - - uses: actions/download-artifact@v1 + - uses: actions/checkout@v2 with: - name: tmppilot.tar.gz - - name: Load image - run: $LOAD + submodules: true + - name: Build Docker image + run: eval "$BUILD" - name: Test car models run: | - $PERSIST "mkdir -p /data/params && cd /tmp/openpilot && coverage run --parallel-mode --concurrency=multiprocessing --rcfile=./.coveragerc-app selfdrive/test/test_car_models.py && coverage combine" + $PERSIST "mkdir -p /data/params && \ + cd /tmp/openpilot && \ + scons -j$(nproc) && \ + coverage run --parallel-mode --concurrency=multiprocessing --rcfile=./.coveragerc-app selfdrive/test/test_car_models.py && \ + coverage combine" - name: Upload coverage to Codecov run: | docker commit tmppilot tmppilotci diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 3c65d655c8..2a0b49f1c0 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -1,5 +1,6 @@ FROM ubuntu:16.04 ENV PYTHONUNBUFFERED 1 +ENV PYTHONPATH /tmp/openpilot:${PYTHONPATH} RUN apt-get update && apt-get install -y --no-install-recommends \ autoconf \ @@ -22,12 +23,10 @@ RUN apt-get update && apt-get install -y --no-install-recommends \ libglfw3-dev \ libglib2.0-0 \ liblzma-dev \ - libmysqlclient-dev \ libomp-dev \ libopencv-dev \ libssl-dev \ libsqlite3-dev \ - libtool \ libusb-1.0-0-dev \ libczmq-dev \ libzmq3-dev \ @@ -39,33 +38,49 @@ RUN apt-get update && apt-get install -y --no-install-recommends \ python-pip \ sudo \ wget \ - && rm -rf /var/lib/apt/lists/* + && rm -rf /var/lib/apt/lists/* RUN sed -i -e 's/# en_US.UTF-8 UTF-8/en_US.UTF-8 UTF-8/' /etc/locale.gen && locale-gen ENV LANG en_US.UTF-8 ENV LANGUAGE en_US:en ENV LC_ALL en_US.UTF-8 +# Install python dependencies RUN curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash - ENV PATH="/root/.pyenv/bin:/root/.pyenv/shims:${PATH}" -RUN pyenv install 3.8.2 && pyenv global 3.8.2 -RUN pyenv rehash - -RUN pip install --no-cache-dir pipenv==2018.11.26 COPY Pipfile Pipfile.lock /tmp/ - -RUN cd /tmp && pipenv install --system --deploy - -# Install subset of dev dependencies needed for CI -RUN pip install --no-cache-dir matplotlib==3.1.1 dictdiffer==0.8.0 fastcluster==1.1.25 aenum==2.2.1 lru-dict==1.1.6 scipy==1.4.1 tenacity==5.1.1 azure-common==1.1.23 azure-nspkg==3.0.2 azure-storage-blob==2.1.0 azure-storage-common==2.1.0 azure-storage-nspkg==3.1.0 pycurl==7.43.0.3 coverage==5.1 - -ENV PYTHONPATH /tmp/openpilot:${PYTHONPATH} +RUN pyenv install 3.8.2 && \ + pyenv global 3.8.2 && \ + pyenv rehash && \ + pip install --no-cache-dir pipenv==2018.11.26 && \ + cd /tmp && \ + pipenv install --system --deploy --clear && \ + pip uninstall -y pipenv && \ + pip install --no-cache-dir \ + matplotlib==3.1.1 \ + dictdiffer==0.8.0 \ + fastcluster==1.1.25 \ + aenum==2.2.1 \ + lru-dict==1.1.6 \ + scipy==1.4.1 \ + tenacity==5.1.1 \ + azure-common==1.1.23 \ + azure-nspkg==3.0.2 \ + azure-storage-blob==2.1.0 \ + azure-storage-common==2.1.0 \ + azure-storage-nspkg==3.1.0 \ + pycurl==7.43.0.3 \ + coverage==5.1 RUN mkdir -p /tmp/openpilot -COPY ./flake8_openpilot.sh ./pylint_openpilot.sh ./.pylintrc ./.coveragerc-app /tmp/openpilot/ +COPY SConstruct \ + flake8_openpilot.sh \ + pylint_openpilot.sh \ + .pylintrc \ + .coveragerc-app \ + /tmp/openpilot/ COPY ./pyextra /tmp/openpilot/pyextra COPY ./phonelibs /tmp/openpilot/phonelibs @@ -79,8 +94,3 @@ COPY ./opendbc /tmp/openpilot/opendbc COPY ./cereal /tmp/openpilot/cereal COPY ./panda /tmp/openpilot/panda COPY ./selfdrive /tmp/openpilot/selfdrive - -COPY SConstruct /tmp/openpilot/SConstruct - -RUN mkdir -p /tmp/openpilot/selfdrive/test/out -RUN cd /tmp/openpilot && scons -j$(nproc) From 58d8887328dcbf93ef02b1aab335120c539fe33c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 19 May 2020 12:34:59 -0700 Subject: [PATCH 041/656] update README github actions shield --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 391c937a8e..58ef0535f1 100644 --- a/README.md +++ b/README.md @@ -327,7 +327,7 @@ NO WARRANTY EXPRESSED OR IMPLIED.** -![Openpilot Tests](https://github.com/commaai/openpilot/workflows/Openpilot%20Tests/badge.svg) +[![openpilot tests](https://github.com/commaai/openpilot/workflows/openpilot%20tests/badge.svg)](https://github.com/commaai/openpilot/actions) [![Total alerts](https://img.shields.io/lgtm/alerts/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/alerts/) [![Language grade: Python](https://img.shields.io/lgtm/grade/python/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/context:python) [![Language grade: C/C++](https://img.shields.io/lgtm/grade/cpp/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/context:cpp) From bb8bbdd9ee4d610e2ae6048021407863b3f74683 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 19 May 2020 13:43:44 -0700 Subject: [PATCH 042/656] Hyundai fw query (#1540) * hyundai fw query * Change query * this works * That is not engine * hyundai fw query * Change query * this works * That is not engine * Skip FW query in test_car_models * Those routes don't fingerprint properly after speedup * only send toyota queries to subaddresses Co-authored-by: openpilot laptop --- selfdrive/car/car_helpers.py | 3 ++- selfdrive/car/fw_versions.py | 34 ++++++++++++++++++++++++++----- selfdrive/car/hyundai/values.py | 10 +++++++++ selfdrive/test/test_car_models.py | 3 +++ 4 files changed, 44 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 434ed1ef1b..23cbd1abf5 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -77,8 +77,9 @@ def only_toyota_left(candidate_cars): # **** for use live only **** def fingerprint(logcan, sendcan, has_relay): fixed_fingerprint = os.environ.get('FINGERPRINT', "") + skip_fw_query = os.environ.get('SKIP_FW_QUERY', False) - if has_relay and not fixed_fingerprint: + if has_relay and not fixed_fingerprint and not skip_fw_query: # Vin query only reliably works thorugh OBDII bus = 1 diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 95b970f125..16f20ca3f9 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -12,9 +12,11 @@ import panda.python.uds as uds from cereal import car Ecu = car.CarParams.Ecu + def p16(val): return struct.pack("!H", val) + TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT, 0x0]) TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40, 0x0]) @@ -36,6 +38,13 @@ UDS_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ UDS_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + +HYUNDAI_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + \ + p16(0xf1a0) # 4 Byte version number +HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + TOYOTA_VERSION_REQUEST = b'\x1a\x88\x01' TOYOTA_VERSION_RESPONSE = b'\x5a\x88\x01' @@ -43,24 +52,35 @@ OBD_VERSION_REQUEST = b'\x09\x04' OBD_VERSION_RESPONSE = b'\x49\x04' +# supports subaddressing, request, response REQUESTS = [ + # Hundai + ( + False, + [HYUNDAI_VERSION_REQUEST], + [HYUNDAI_VERSION_RESPONSE], + ), # Honda ( + False, [UDS_VERSION_REQUEST], - [UDS_VERSION_RESPONSE] + [UDS_VERSION_RESPONSE], ), # Toyota ( + True, [SHORT_TESTER_PRESENT_REQUEST, TOYOTA_VERSION_REQUEST], - [SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE] + [SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE], ), ( + True, [SHORT_TESTER_PRESENT_REQUEST, OBD_VERSION_REQUEST], - [SHORT_TESTER_PRESENT_RESPONSE, OBD_VERSION_RESPONSE] + [SHORT_TESTER_PRESENT_RESPONSE, OBD_VERSION_RESPONSE], ), ( + True, [TESTER_PRESENT_REQUEST, DEFAULT_DIAGNOSTIC_REQUEST, EXTENDED_DIAGNOSTIC_REQUEST, UDS_VERSION_REQUEST], - [TESTER_PRESENT_RESPONSE, DEFAULT_DIAGNOSTIC_RESPONSE, EXTENDED_DIAGNOSTIC_RESPONSE, UDS_VERSION_RESPONSE] + [TESTER_PRESENT_RESPONSE, DEFAULT_DIAGNOSTIC_RESPONSE, EXTENDED_DIAGNOSTIC_RESPONSE, UDS_VERSION_RESPONSE], ) ] @@ -134,8 +154,12 @@ def get_fw_versions(logcan, sendcan, bus, extra=None, timeout=0.1, debug=False, fw_versions = {} for i, addr in enumerate(tqdm(addrs, disable=not progress)): for addr_chunk in chunks(addr): - for request, response in REQUESTS: + for supports_sub_addr, request, response in REQUESTS: try: + # Don't send Hyundai and Honda requests to subaddress + if i != 0 and not supports_sub_addr: + continue + query = IsoTpParallelQuery(sendcan, logcan, bus, addr_chunk, request, response, debug=debug) t = 2 * timeout if i == 0 else timeout fw_versions.update(query.get_data(t)) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 480ed6f269..e072d1b294 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -135,6 +135,16 @@ ECU_FINGERPRINT = { Ecu.fwdCamera: [832, 1156, 1191, 1342] } +FW_VERSIONS = { + CAR.SONATA: { + (Ecu.esp, 0x7d1, None): [b'\xf1\x8758910-L0100\xf1\xa01.04'], + (Ecu.engine, 0x7e0, None): [b'\xf1\x87391162M003\xf1\xa0000F'], + (Ecu.eps, 0x7d4, None): [b'\xf1\x8756310L0010\x00\xf1\xa01.01'], + (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x8799110L0000\xf1\xa01.00'], + (Ecu.transmission, 0x7e1, None): [b'U903\x00\x00\x00\x00\x00\x00'], + } +} + CHECKSUM = { "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE], "6B": [CAR.KIA_SORENTO, CAR.HYUNDAI_GENESIS], diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 63f42cf556..9954612e8a 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -247,6 +247,7 @@ routes = { 'enableCamera': True, 'enableDsu': True, 'enableGasInterceptor': False, + 'fingerprintSource': 'fixed', }, "cdf2f7de565d40ae|2019-04-25--03-53-41": { 'carFingerprint': TOYOTA.RAV4_TSS2, @@ -296,6 +297,7 @@ routes = { "01b22eb2ed121565|2020-02-02--11-25-51": { 'carFingerprint': TOYOTA.LEXUS_RX_TSS2, 'enableCamera': True, + 'fingerprintSource': 'fixed', }, "ec429c0f37564e3c|2020-02-01--17-28-12": { 'carFingerprint': TOYOTA.LEXUS_NXH, @@ -426,6 +428,7 @@ if __name__ == "__main__": params.put("CommunityFeaturesToggle", "1") params.put("Passive", "1" if route in passive_routes else "0") + os.environ['SKIP_FW_QUERY'] = "1" if checks.get('fingerprintSource', None) == 'fixed': os.environ['FINGERPRINT'] = checks['carFingerprint'] else: From 8788ab36e40a413c777dd298817477a2fd7da8f9 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 19 May 2020 13:54:24 -0700 Subject: [PATCH 043/656] remove those debug prints --- selfdrive/test/test_car_models.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 9954612e8a..6eb76bc388 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -417,9 +417,7 @@ if __name__ == "__main__": results = {} for route, checks in routes.items(): - print("GETTING ROUTE LOGS") get_route_log(route) - print("DONE GETTING ROUTE LOGS") params = Params() params.clear_all() From f6f4a0b55899ad369c5665143673dc83d22d9969 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 19 May 2020 15:30:35 -0700 Subject: [PATCH 044/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index d589d5e3d8..c96381b0d6 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit d589d5e3d85a11e8011397069f196cfd58ac113d +Subproject commit c96381b0d6a1583b14d30b32541a0bd4d5c35e1e From f5a9cd2644798dd728cdd613ee331526ba074f6f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 19 May 2020 15:50:20 -0700 Subject: [PATCH 045/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index c96381b0d6..01cdf832c8 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit c96381b0d6a1583b14d30b32541a0bd4d5c35e1e +Subproject commit 01cdf832c8f164adf7a975b9e29c66c4b04bdc83 From 96605d095162c88b6e97de6262f4972c12c49c68 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 19 May 2020 16:19:00 -0700 Subject: [PATCH 046/656] This one also needs to be fixed --- selfdrive/test/test_car_models.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 6eb76bc388..ae47496e6d 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -194,6 +194,7 @@ routes = { 'carFingerprint': TOYOTA.CAMRY, 'enableCamera': True, 'enableDsu': False, + 'fingerprintSource': 'fixed', }, "f7b6be73e3dfd36c|2019-05-11--22-34-20": { 'carFingerprint': TOYOTA.AVALON, From d099e09fb77544eb00d13ba9aea34a0a3374a52e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 19 May 2020 16:45:20 -0700 Subject: [PATCH 047/656] Handle posenet and sensor alerts in locationd (#1541) * handle posenet and senor alerts in locationd * defaults now set in capnp file * Cleanup c++ version of params learner * update ref commit --- selfdrive/controls/controlsd.py | 8 +++----- selfdrive/controls/lib/pathplanner.py | 2 -- selfdrive/locationd/locationd.py | 17 +++++++++++++++-- selfdrive/locationd/locationd_yawrate.cc | 6 ------ selfdrive/locationd/locationd_yawrate.h | 4 ---- selfdrive/locationd/paramsd.cc | 16 +--------------- selfdrive/test/process_replay/process_replay.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 8 files changed, 21 insertions(+), 36 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 93353d0690..36de2fc6d7 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -50,7 +50,7 @@ class Controls: self.sm = sm if self.sm is None: self.sm = messaging.SubMaster(['thermal', 'health', 'model', 'liveCalibration', \ - 'dMonitoringState', 'plan', 'pathPlan']) + 'dMonitoringState', 'plan', 'pathPlan', 'liveLocationKalman']) self.can_sock = can_sock if can_sock is None: @@ -123,8 +123,6 @@ class Controls: self.current_alert_types = [] self.sm['liveCalibration'].calStatus = Calibration.INVALID - self.sm['pathPlan'].sensorValid = True - self.sm['pathPlan'].posenetValid = True self.sm['thermal'].freeSpace = 1. self.sm['dMonitoringState'].events = [] self.sm['dMonitoringState'].awarenessStatus = 1. @@ -201,11 +199,11 @@ class Controls: self.events.add(EventName.commIssue) if not self.sm['pathPlan'].mpcSolutionValid: self.events.add(EventName.plannerError) - if not self.sm['pathPlan'].sensorValid and os.getenv("NOSENSOR") is None: + if not self.sm['liveLocationKalman'].inputsOK and os.getenv("NOSENSOR") is None: self.events.add(EventName.sensorDataInvalid) if not self.sm['pathPlan'].paramsValid: self.events.add(EventName.vehicleModelInvalid) - if not self.sm['pathPlan'].posenetValid: + if not self.sm['liveLocationKalman'].posenetOK: self.events.add(EventName.posenetInvalid) if not self.sm['plan'].radarValid: self.events.add(EventName.radarFault) diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index 413d71d3a2..a8de48013a 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -207,8 +207,6 @@ class PathPlanner(): plan_send.pathPlan.angleOffset = float(sm['liveParameters'].angleOffsetAverage) plan_send.pathPlan.mpcSolutionValid = bool(plan_solution_valid) plan_send.pathPlan.paramsValid = bool(sm['liveParameters'].valid) - plan_send.pathPlan.sensorValid = bool(sm['liveParameters'].sensorValid) - plan_send.pathPlan.posenetValid = bool(sm['liveParameters'].posenetValid) plan_send.pathPlan.desire = desire plan_send.pathPlan.laneChangeState = self.lane_change_state diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index b8359a49b0..e6a3e38c13 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -57,6 +57,10 @@ class Localizer(): self.calibrated = 0 self.H = get_H() + self.posenet_invalid_count = 0 + self.posenet_speed = 0 + self.car_speed = 0 + @staticmethod def msg_from_state(converter, calib_from_device, H, predicted_state, predicted_cov): predicted_std = np.sqrt(np.diagonal(predicted_cov)) @@ -141,6 +145,12 @@ class Localizer(): def liveLocationMsg(self, time): fix = self.msg_from_state(self.converter, self.calib_from_device, self.H, self.kf.x, self.kf.P) + if abs(self.posenet_speed - self.car_speed) > max(0.4 * self.car_speed, 5.0): + self.posenet_invalid_count += 1 + else: + self.posenet_invalid_count = 0 + fix.posenetOK = self.posenet_invalid_count < 4 + #fix.gpsWeek = self.time.week #fix.gpsTimeOfWeek = self.time.tow fix.unixTimestampMillis = self.unix_timestamp_millis @@ -198,12 +208,12 @@ class Localizer(): self.update_kalman(current_time, ObservationKind.ECEF_POS, ecef_pos, R=ecef_pos_R) self.update_kalman(current_time, ObservationKind.ECEF_VEL, ecef_vel, R=ecef_vel_R) - def handle_car_state(self, current_time, log): self.speed_counter += 1 if self.speed_counter % SENSOR_DECIMATION == 0: self.update_kalman(current_time, ObservationKind.ODOMETRIC_SPEED, [log.vEgo]) + self.car_speed = abs(log.vEgo) if log.vEgo == 0: self.update_kalman(current_time, ObservationKind.NO_ROT, [0, 0, 0]) @@ -218,6 +228,7 @@ class Localizer(): np.concatenate([rot_device, 10*rot_device_std])) trans_device = self.device_from_calib.dot(log.trans) trans_device_std = self.device_from_calib.dot(log.transStd) + self.posenet_speed = np.linalg.norm(trans_device) self.update_kalman(current_time, ObservationKind.CAMERA_ODO_TRANSLATION, np.concatenate([trans_device, 10*trans_device_std])) @@ -263,7 +274,7 @@ class Localizer(): def locationd_thread(sm, pm, disabled_logs=[]): if sm is None: - socks = ['gpsLocationExternal', 'sensorEvents', 'cameraOdometry', 'liveCalibration'] + socks = ['gpsLocationExternal', 'sensorEvents', 'cameraOdometry', 'liveCalibration', 'carState'] sm = messaging.SubMaster(socks) if pm is None: pm = messaging.PubMaster(['liveLocationKalman']) @@ -293,6 +304,8 @@ def locationd_thread(sm, pm, disabled_logs=[]): msg.logMonoTime = t msg.liveLocationKalman = localizer.liveLocationMsg(t * 1e-9) + msg.liveLocationKalman.inputsOK = sm.all_alive_and_valid() + pm.send('liveLocationKalman', msg) diff --git a/selfdrive/locationd/locationd_yawrate.cc b/selfdrive/locationd/locationd_yawrate.cc index 4b93b68014..e682ec3909 100644 --- a/selfdrive/locationd/locationd_yawrate.cc +++ b/selfdrive/locationd/locationd_yawrate.cc @@ -32,7 +32,6 @@ void Localizer::update_state(const Eigen::Matrix &C, const double void Localizer::handle_sensor_events(capnp::List::Reader sensor_events, double current_time) { for (cereal::SensorEventData::Reader sensor_event : sensor_events){ if (sensor_event.getSensor() == 5 && sensor_event.getType() == 16) { - sensor_data_time = current_time; double meas = -sensor_event.getGyroUncalibrated().getV()[0]; update_state(C_gyro, R_gyro, current_time, meas); } @@ -43,16 +42,11 @@ void Localizer::handle_camera_odometry(cereal::CameraOdometry::Reader camera_odo double R = pow(5 * camera_odometry.getRotStd()[2], 2); double meas = camera_odometry.getRot()[2]; update_state(C_posenet, R, current_time, meas); - - auto trans = camera_odometry.getTrans(); - posenet_speed = sqrt(trans[0]*trans[0] + trans[1]*trans[1] + trans[2]*trans[2]); - camera_odometry_time = current_time; } void Localizer::handle_controls_state(cereal::ControlsState::Reader controls_state, double current_time) { steering_angle = controls_state.getAngleSteers() * DEGREES_TO_RADIANS; car_speed = controls_state.getVEgo(); - controls_state_time = current_time; } diff --git a/selfdrive/locationd/locationd_yawrate.h b/selfdrive/locationd/locationd_yawrate.h index c59734aa68..58999e5f37 100644 --- a/selfdrive/locationd/locationd_yawrate.h +++ b/selfdrive/locationd/locationd_yawrate.h @@ -25,11 +25,7 @@ public: Eigen::Matrix2d P; double steering_angle = 0; double car_speed = 0; - double posenet_speed = 0; double prev_update_time = -1; - double controls_state_time = -1; - double sensor_data_time = -1; - double camera_odometry_time = -1; Localizer(); void handle_log(cereal::Event::Reader event); diff --git a/selfdrive/locationd/paramsd.cc b/selfdrive/locationd/paramsd.cc index 8c60bc12e4..bae43ba367 100644 --- a/selfdrive/locationd/paramsd.cc +++ b/selfdrive/locationd/paramsd.cc @@ -116,23 +116,12 @@ int main(int argc, char *argv[]) { localizer.handle_log(event); auto which = event.which(); - // Throw vision failure if posenet and odometric speed too different - if (which == cereal::Event::CAMERA_ODOMETRY){ - if (std::abs(localizer.posenet_speed - localizer.car_speed) > std::max(0.4 * localizer.car_speed, 5.0)) { - posenet_invalid_count++; - } else { - posenet_invalid_count = 0; - } - } else if (which == cereal::Event::CONTROLS_STATE){ + if (which == cereal::Event::CONTROLS_STATE){ save_counter++; double yaw_rate = -localizer.x[0]; bool valid = learner.update(yaw_rate, localizer.car_speed, localizer.steering_angle); - // TODO: Fix in replay - double sensor_data_age = localizer.controls_state_time - localizer.sensor_data_time; - double camera_odometry_age = localizer.controls_state_time - localizer.camera_odometry_time; - double angle_offset_degrees = RADIANS_TO_DEGREES * learner.ao; double angle_offset_average_degrees = RADIANS_TO_DEGREES * learner.slow_ao; @@ -143,13 +132,10 @@ int main(int argc, char *argv[]) { live_params.setValid(valid); live_params.setYawRate(localizer.x[0]); live_params.setGyroBias(localizer.x[1]); - live_params.setSensorValid(sensor_data_age < 5.0); live_params.setAngleOffset(angle_offset_degrees); live_params.setAngleOffsetAverage(angle_offset_average_degrees); live_params.setStiffnessFactor(learner.x); live_params.setSteerRatio(learner.sR); - live_params.setPosenetSpeed(localizer.posenet_speed); - live_params.setPosenetValid((posenet_invalid_count < 4) && (camera_odometry_age < 5.0)); auto words = capnp::messageToFlatArray(msg); auto bytes = words.asBytes(); diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 106d871e5f..2687b24210 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -202,7 +202,7 @@ CONFIGS = [ proc_name="controlsd", pub_sub={ "can": ["controlsState", "carState", "carControl", "sendcan", "carEvents", "carParams"], - "thermal": [], "health": [], "liveCalibration": [], "dMonitoringState": [], "plan": [], "pathPlan": [], "gpsLocation": [], + "thermal": [], "health": [], "liveCalibration": [], "dMonitoringState": [], "plan": [], "pathPlan": [], "gpsLocation": [], "liveLocationKalman": [], "model": [], }, ignore=["logMonoTime", "valid", "controlsState.startMonoTime", "controlsState.cumLagMs"], diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 880f969541..baaafb0f8d 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -76e577b86d113139167275b4a7379f3591abfa02 \ No newline at end of file +59bd32350139796784708f51c233d37c18f33e6e \ No newline at end of file From 44484102db471a5f85ad078a81b9d8b9456b5233 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 19 May 2020 17:00:30 -0700 Subject: [PATCH 048/656] Paramsd handle liveLocation not valid and add alerts --- selfdrive/locationd/models/car_kf.py | 8 +++--- selfdrive/locationd/paramsd.py | 38 +++++++++++++--------------- 2 files changed, 21 insertions(+), 25 deletions(-) diff --git a/selfdrive/locationd/models/car_kf.py b/selfdrive/locationd/models/car_kf.py index 26df70a0bf..b984bf7665 100755 --- a/selfdrive/locationd/models/car_kf.py +++ b/selfdrive/locationd/models/car_kf.py @@ -49,8 +49,8 @@ class CarKalman(KalmanFilter): Q = np.diag([ (.05/100)**2, .01**2, - math.radians(0.002)**2, - math.radians(0.1)**2, + math.radians(0.02)**2, + math.radians(0.25)**2, .1**2, .01**2, math.radians(0.1)**2, @@ -60,7 +60,7 @@ class CarKalman(KalmanFilter): obs_noise = { ObservationKind.STEER_ANGLE: np.atleast_2d(math.radians(0.01)**2), - ObservationKind.ANGLE_OFFSET_FAST: np.atleast_2d(math.radians(5.0)**2), + ObservationKind.ANGLE_OFFSET_FAST: np.atleast_2d(math.radians(10.0)**2), ObservationKind.STEER_RATIO: np.atleast_2d(5.0**2), ObservationKind.STIFFNESS: np.atleast_2d(5.0**2), ObservationKind.ROAD_FRAME_X_SPEED: np.atleast_2d(0.1**2), @@ -139,7 +139,7 @@ class CarKalman(KalmanFilter): def __init__(self, generated_dir, steer_ratio=15, stiffness_factor=1, angle_offset=0): dim_state = self.initial_x.shape[0] - dim_state_err = self.initial_P_diag.shape[0] + dim_state_err = self.P_initial.shape[0] x_init = self.initial_x x_init[States.STEER_RATIO] = steer_ratio x_init[States.STIFFNESS] = stiffness_factor diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index e359870ba8..c994eced7b 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -5,12 +5,14 @@ import json import numpy as np import cereal.messaging as messaging -from cereal import car +from cereal import car, log from common.params import Params, put_nonblocking from selfdrive.locationd.models.car_kf import CarKalman, ObservationKind, States from selfdrive.locationd.models.constants import GENERATED_DIR from selfdrive.swaglog import cloudlog +FixStatus = log.LiveLocationKalman.Status + CARSTATE_DECIMATION = 5 @@ -32,6 +34,8 @@ class ParamsLearner: self.steering_angle = 0 self.carstate_counter = 0 + self.valid = True + def handle_log(self, t, which, msg): if which == 'liveLocationKalman': @@ -39,21 +43,13 @@ class ParamsLearner: yaw_rate_std = msg.angularVelocityCalibrated.std[2] if self.active: - self.kf.predict_and_observe(t, - ObservationKind.ROAD_FRAME_YAW_RATE, - np.array([[[-yaw_rate]]]), - np.array([np.atleast_2d(yaw_rate_std**2)])) - + if msg.inputsOK and msg.posenetOK and msg.status == FixStatus.valid: + self.kf.predict_and_observe(t, + ObservationKind.ROAD_FRAME_YAW_RATE, + np.array([[[-yaw_rate]]]), + np.array([np.atleast_2d(yaw_rate_std**2)])) self.kf.predict_and_observe(t, ObservationKind.ANGLE_OFFSET_FAST, np.array([[[0]]])) - # Clamp values - # x = self.kf.x - # if not (10 < x[States.STEER_RATIO] < 25): - # self.kf.predict_and_observe(t, ObservationKind.STEER_RATIO, np.array([[[15.0]]])) - - # if not (0.5 < x[States.STIFFNESS] < 3.0): - # self.kf.predict_and_observe(t, ObservationKind.STIFFNESS, np.array([[[1.0]]])) - elif which == 'carState': self.carstate_counter += 1 if self.carstate_counter % CARSTATE_DECIMATION == 0: @@ -105,6 +101,7 @@ def main(sm=None, pm=None): cloudlog.info("Parameter learner resetting to default values") learner = ParamsLearner(CP, params['steerRatio'], params['stiffnessFactor'], math.radians(params['angleOffsetAverage'])) + min_sr, max_sr = 0.5 * CP.steerRatio, 2.0 * CP.steerRatio i = 0 while True: @@ -132,6 +129,12 @@ def main(sm=None, pm=None): msg.liveParameters.stiffnessFactor = float(x[States.STIFFNESS]) msg.liveParameters.angleOffsetAverage = math.degrees(x[States.ANGLE_OFFSET]) msg.liveParameters.angleOffset = msg.liveParameters.angleOffsetAverage + math.degrees(x[States.ANGLE_OFFSET_FAST]) + msg.liveParameters.valid = all(( + abs(msg.liveParameters.angleOffsetAverage) < 10.0, + abs(msg.liveParameters.angleOffset) < 10.0, + 0.5 <= msg.liveParameters.stiffnessFactor <= 2.0, + min_sr <= msg.liveParameters.steerRatio <= max_sr, + )) i += 1 if i % 6000 == 0: # once a minute @@ -143,13 +146,6 @@ def main(sm=None, pm=None): } put_nonblocking("LiveParameters", json.dumps(params)) - # P = learner.kf.P - # print() - # print("sR", float(x[States.STEER_RATIO]), float(P[States.STEER_RATIO, States.STEER_RATIO])**0.5) - # print("x ", float(x[States.STIFFNESS]), float(P[States.STIFFNESS, States.STIFFNESS])**0.5) - # print("ao avg ", math.degrees(x[States.ANGLE_OFFSET]), math.degrees(P[States.ANGLE_OFFSET, States.ANGLE_OFFSET])**0.5) - # print("ao ", math.degrees(x[States.ANGLE_OFFSET_FAST]), math.degrees(P[States.ANGLE_OFFSET_FAST, States.ANGLE_OFFSET_FAST])**0.5) - pm.send('liveParameters', msg) From f69f2001788ed9057b907113b74e258a69ecad6d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 19 May 2020 18:13:11 -0700 Subject: [PATCH 049/656] Rename enum --- selfdrive/locationd/paramsd.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index c994eced7b..29d7c73f39 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -11,7 +11,7 @@ from selfdrive.locationd.models.car_kf import CarKalman, ObservationKind, States from selfdrive.locationd.models.constants import GENERATED_DIR from selfdrive.swaglog import cloudlog -FixStatus = log.LiveLocationKalman.Status +KalmanStatus = log.LiveLocationKalman.Status CARSTATE_DECIMATION = 5 @@ -43,7 +43,7 @@ class ParamsLearner: yaw_rate_std = msg.angularVelocityCalibrated.std[2] if self.active: - if msg.inputsOK and msg.posenetOK and msg.status == FixStatus.valid: + if msg.inputsOK and msg.posenetOK and msg.status == KalmanStatus.valid: self.kf.predict_and_observe(t, ObservationKind.ROAD_FRAME_YAW_RATE, np.array([[[-yaw_rate]]]), From 0d1ac8db76fc9026bd7ed7b69fa71792b61c58f6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 19 May 2020 23:32:43 -0700 Subject: [PATCH 050/656] update CONTRIBUTING.md --- CONTRIBUTING.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index dc42a314a5..e101650d49 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -2,7 +2,7 @@ Our software is open source so you can solve your own problems without needing help from others. And if you solve a problem and are so kind, you can upstream it for the rest of the world to use. -Most open source development activity is coordinated through our [Discord](https://discord.comma.ai). A lot of documentation is available on our [medium](https://medium.com/@comma_ai/) +Most open source development activity is coordinated through our [Discord](https://discord.comma.ai). A lot of documentation is available on our [medium](https://medium.com/@comma_ai/). ## Getting Started @@ -18,7 +18,7 @@ You can test your changes on your machine by running `run_docker_tests.sh`. This ### Automated Testing -All PRs are automatically checked by Github Actions. Check out `.github/workflows/` for what Github Actions runs. Any new tests sould be added to Github Actions. +All PRs and commits are automatically checked by Github Actions. Check out `.github/workflows/` for what Github Actions runs. Any new tests sould be added to Github Actions. ### Code Style and Linting @@ -48,3 +48,4 @@ Modules that are in seperate repositories include: * laika * opendbc * panda +* rednose From 04047d835fd0392426eb4ff22829a1dcd5eb0567 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 20 May 2020 00:00:13 -0700 Subject: [PATCH 051/656] fix run_docker_tests.sh --- run_docker_tests.sh | 25 +++++++++++++------------ 1 file changed, 13 insertions(+), 12 deletions(-) diff --git a/run_docker_tests.sh b/run_docker_tests.sh index 1247c24de1..92cd57b87a 100755 --- a/run_docker_tests.sh +++ b/run_docker_tests.sh @@ -2,21 +2,22 @@ set -e SETUP="cd /tmp/openpilot && " -RUN="docker run --shm-size 1G --rm tmppilot /bin/sh -c" +BUILD="cd /tmp/openpilot && scons -c && scons -j$(nproc) && " +RUN="docker run --shm-size 1G --rm tmppilot /bin/bash -c" docker build -t tmppilot -f Dockerfile.openpilot . $RUN "$SETUP cd /tmp/openpilot/selfdrive/test/ && ./test_fingerprints.py" $RUN "$SETUP ./flake8_openpilot.sh" $RUN "$SETUP ./pylint_openpilot.sh" -$RUN "$SETUP python -m unittest discover common" -$RUN "$SETUP python -m unittest discover opendbc/can" -$RUN "$SETUP python -m unittest discover selfdrive/boardd" -$RUN "$SETUP python -m unittest discover selfdrive/controls" -$RUN "$SETUP python -m unittest discover selfdrive/loggerd" -$RUN "$SETUP python -m unittest discover selfdrive/car" -$RUN "$SETUP python -m unittest discover selfdrive/locationd" -$RUN "$SETUP python -m unittest discover selfdrive/athena" -$RUN "$SETUP cd /tmp/openpilot/selfdrive/test/longitudinal_maneuvers && OPTEST=1 ./test_longitudinal.py" -$RUN "$SETUP cd /tmp/openpilot/selfdrive/test/process_replay/ && ./test_processes.py" -$RUN "$SETUP mkdir -p /data/params && cd /tmp/openpilot/selfdrive/test/ && ./test_car_models.py" +$RUN "$BUILD python -m unittest discover common && \ + python -m unittest discover opendbc/can && \ + python -m unittest discover selfdrive/boardd && \ + python -m unittest discover selfdrive/controls && \ + python -m unittest discover selfdrive/loggerd && \ + python -m unittest discover selfdrive/car && \ + python -m unittest discover selfdrive/locationd && \ + python -m unittest discover selfdrive/athena" +$RUN "$BUILD cd /tmp/openpilot/selfdrive/test/longitudinal_maneuvers && OPTEST=1 ./test_longitudinal.py" +$RUN "$BUILD cd /tmp/openpilot/selfdrive/test/process_replay/ && ./test_processes.py" +$RUN "$BUILD mkdir -p /data/params && cd /tmp/openpilot/selfdrive/test/ && ./test_car_models.py" From b62ce27483de8cd52b6929da01c906766b7876f7 Mon Sep 17 00:00:00 2001 From: TK211X <33460783+TK211X@users.noreply.github.com> Date: Wed, 20 May 2020 13:57:21 -0400 Subject: [PATCH 052/656] Add 2016 Optima Print (#1510) * Add 2016 Optima Print * Update values.py --- selfdrive/car/hyundai/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index e072d1b294..69dd35f93c 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -84,7 +84,7 @@ FINGERPRINTS = { 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1186: 2, 1191: 2, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 1952: 8, 1960: 8, 1988: 8, 1996: 8, 2001: 8, 2004: 8, 2008: 8, 2009: 8, 2012: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 }, { - 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 897: 8, 899: 8, 902: 8, 903: 6, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1265: 4, 1268: 8, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1491: 8, 1492: 8 + 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 897: 8, 899: 8, 902: 8, 903: 6, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1265: 4, 1268: 8, 1280: 1, 1281: 3, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1491: 8, 1492: 8 }, ], CAR.KIA_SORENTO: [{ From 9f0eac90895d9fc4cc4ab782d61f31d3b5ab9685 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 20 May 2020 11:25:27 -0700 Subject: [PATCH 053/656] Fix #1545, sensor alert on startup --- selfdrive/controls/controlsd.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 36de2fc6d7..18aa2c7b28 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -200,7 +200,8 @@ class Controls: if not self.sm['pathPlan'].mpcSolutionValid: self.events.add(EventName.plannerError) if not self.sm['liveLocationKalman'].inputsOK and os.getenv("NOSENSOR") is None: - self.events.add(EventName.sensorDataInvalid) + if self.sm.frame > 5 / DT_CTRL: # Give locationd some time to receive all the inputs + self.events.add(EventName.sensorDataInvalid) if not self.sm['pathPlan'].paramsValid: self.events.add(EventName.vehicleModelInvalid) if not self.sm['liveLocationKalman'].posenetOK: From 1162041ea63a7213b9e2b9c11edd521c89f86c99 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 20 May 2020 13:02:24 -0700 Subject: [PATCH 054/656] Only send FW query requests for the right brand (#1546) * only send requests for the right brand * this works on sonata Co-authored-by: openpilot laptop --- selfdrive/car/fingerprints.py | 9 +++-- selfdrive/car/fw_versions.py | 59 +++++++++++++++++---------------- selfdrive/car/hyundai/values.py | 4 +-- 3 files changed, 39 insertions(+), 33 deletions(-) diff --git a/selfdrive/car/fingerprints.py b/selfdrive/car/fingerprints.py index c2c39f687f..64dc56625c 100644 --- a/selfdrive/car/fingerprints.py +++ b/selfdrive/car/fingerprints.py @@ -2,7 +2,7 @@ import os from common.basedir import BASEDIR -def get_attr_from_cars(attr, result=dict): +def get_attr_from_cars(attr, result=dict, combine_brands=True): # read all the folders in selfdrive/car and return a dict where: # - keys are all the car models # - values are attr values from all car folders @@ -19,7 +19,12 @@ def get_attr_from_cars(attr, result=dict): if isinstance(attr_values, dict): for f, v in attr_values.items(): - result[f] = v + if combine_brands: + result[f] = v + else: + if car_name not in result: + result[car_name] = {} + result[car_name][f] = v elif isinstance(attr_values, list): result += attr_values diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 16f20ca3f9..0522b862f8 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -5,7 +5,7 @@ from tqdm import tqdm from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery from selfdrive.swaglog import cloudlog -from selfdrive.car.fingerprints import FW_VERSIONS +from selfdrive.car.fingerprints import get_attr_from_cars, FW_VERSIONS from selfdrive.car.toyota.values import CAR as TOYOTA import panda.python.uds as uds @@ -56,29 +56,29 @@ OBD_VERSION_RESPONSE = b'\x49\x04' REQUESTS = [ # Hundai ( - False, + "hyundai", [HYUNDAI_VERSION_REQUEST], [HYUNDAI_VERSION_RESPONSE], ), # Honda ( - False, + "honda", [UDS_VERSION_REQUEST], [UDS_VERSION_RESPONSE], ), # Toyota ( - True, + "toyota", [SHORT_TESTER_PRESENT_REQUEST, TOYOTA_VERSION_REQUEST], [SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE], ), ( - True, + "toyota", [SHORT_TESTER_PRESENT_REQUEST, OBD_VERSION_REQUEST], [SHORT_TESTER_PRESENT_RESPONSE, OBD_VERSION_RESPONSE], ), ( - True, + "toyota", [TESTER_PRESENT_REQUEST, DEFAULT_DIAGNOSTIC_REQUEST, EXTENDED_DIAGNOSTIC_REQUEST, UDS_VERSION_REQUEST], [TESTER_PRESENT_RESPONSE, DEFAULT_DIAGNOSTIC_RESPONSE, EXTENDED_DIAGNOSTIC_RESPONSE, UDS_VERSION_RESPONSE], ) @@ -132,37 +132,37 @@ def get_fw_versions(logcan, sendcan, bus, extra=None, timeout=0.1, debug=False, addrs = [] parallel_addrs = [] - versions = FW_VERSIONS + versions = get_attr_from_cars('FW_VERSIONS', combine_brands=False) if extra is not None: versions.update(extra) - for c in versions.values(): - for ecu_type, addr, sub_addr in c.keys(): - a = (addr, sub_addr) - if a not in ecu_types: - ecu_types[a] = ecu_type + for brand, brand_versions in versions.items(): + for c in brand_versions.values(): + for ecu_type, addr, sub_addr in c.keys(): + a = (brand, addr, sub_addr) + if a not in ecu_types: + ecu_types[(addr, sub_addr)] = ecu_type - if sub_addr is None: - if a not in parallel_addrs: - parallel_addrs.append(a) - else: - if [a] not in addrs: - addrs.append([a]) + if sub_addr is None: + if a not in parallel_addrs: + parallel_addrs.append(a) + else: + if [a] not in addrs: + addrs.append([a]) addrs.insert(0, parallel_addrs) fw_versions = {} for i, addr in enumerate(tqdm(addrs, disable=not progress)): for addr_chunk in chunks(addr): - for supports_sub_addr, request, response in REQUESTS: + for brand, request, response in REQUESTS: try: - # Don't send Hyundai and Honda requests to subaddress - if i != 0 and not supports_sub_addr: - continue + addrs = [(a, s) for (b, a, s) in addr_chunk if b in (brand, 'any')] - query = IsoTpParallelQuery(sendcan, logcan, bus, addr_chunk, request, response, debug=debug) - t = 2 * timeout if i == 0 else timeout - fw_versions.update(query.get_data(t)) + if addrs: + query = IsoTpParallelQuery(sendcan, logcan, bus, addrs, request, response, debug=debug) + t = 2 * timeout if i == 0 else timeout + fw_versions.update(query.get_data(t)) except Exception: cloudlog.warning(f"FW query exception: {traceback.format_exc()}") @@ -199,12 +199,13 @@ if __name__ == "__main__": extra = None if args.scan: - extra = {"DEBUG": {}} + extra = {} # Honda for i in range(256): - extra["DEBUG"][(Ecu.unknown, 0x18da00f1 + (i << 8), None)] = [] - extra["DEBUG"][(Ecu.unknown, 0x700 + i, None)] = [] - extra["DEBUG"][(Ecu.unknown, 0x750, i)] = [] + extra[(Ecu.unknown, 0x18da00f1 + (i << 8), None)] = [] + extra[(Ecu.unknown, 0x700 + i, None)] = [] + extra[(Ecu.unknown, 0x750, i)] = [] + extra = {"any": {"debug": extra}} time.sleep(1.) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 69dd35f93c..1887ab5b5e 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -84,7 +84,7 @@ FINGERPRINTS = { 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1186: 2, 1191: 2, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 1952: 8, 1960: 8, 1988: 8, 1996: 8, 2001: 8, 2004: 8, 2008: 8, 2009: 8, 2012: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 }, { - 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 897: 8, 899: 8, 902: 8, 903: 6, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1265: 4, 1268: 8, 1280: 1, 1281: 3, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1491: 8, 1492: 8 + 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 897: 8, 899: 8, 902: 8, 903: 6, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1265: 4, 1268: 8, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1491: 8, 1492: 8 }, ], CAR.KIA_SORENTO: [{ @@ -141,7 +141,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [b'\xf1\x87391162M003\xf1\xa0000F'], (Ecu.eps, 0x7d4, None): [b'\xf1\x8756310L0010\x00\xf1\xa01.01'], (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x8799110L0000\xf1\xa01.00'], - (Ecu.transmission, 0x7e1, None): [b'U903\x00\x00\x00\x00\x00\x00'], + (Ecu.transmission, 0x7e1, None): [b'\xf1\x87SALFBA4195874GJ2EVugvf\x86hgwvwww\x87wgw\x86wc_\xfb\xff\x98\x88\x8f\xff\xe23\xf1\x81U903\x00\x00\x00\x00\x00\x00'], } } From b1795235f9767ac38f1bc8c7cd2dee9d4f646cf6 Mon Sep 17 00:00:00 2001 From: Ewout ter Hoeven Date: Wed, 20 May 2020 22:16:02 +0200 Subject: [PATCH 055/656] Add workflow to update Pipfile.lock weekly (#1542) * Create workflow to update the Pipfile.lock weekly * Update-pipfile: Also install wheel * Install wheel in different step * Pipfile: Only lock major versions Assumes Semantic Versioning, and only sets the major versions of all packages * Run update-pipfile on changes in pipfile and use tensorflow Move from tensorflow-gpu to tensorflow, an excelent test for this PR * [create-pull-request] automated change Co-authored-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> --- .github/workflows/update-pipfile.yml | 25 ++ Pipfile | 24 +- Pipfile.lock | 623 +++++++++++---------------- 3 files changed, 292 insertions(+), 380 deletions(-) create mode 100644 .github/workflows/update-pipfile.yml diff --git a/.github/workflows/update-pipfile.yml b/.github/workflows/update-pipfile.yml new file mode 100644 index 0000000000..018eb9e12d --- /dev/null +++ b/.github/workflows/update-pipfile.yml @@ -0,0 +1,25 @@ +name: "Update Pipfile.lock" +on: + schedule: + - cron: '00 08 * * 1' # Every monday on 08:00 UTC + push: + paths: + - 'Pipfile' + +jobs: + piplock: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v2 + - uses: actions/setup-python@v2 + - run: pip install wheel + - run: pip install pipenv + - run: pipenv lock --requirements + - uses: actions/upload-artifact@v2 + with: + name: "Pipfile lock" + path: Pipfile.lock + - uses: peter-evans/create-pull-request@v2 + with: + title: "Update Pipfile.lock (dependencies)" + branch: update-pipfile diff --git a/Pipfile b/Pipfile index 9d1f3a3bba..1a49e70229 100644 --- a/Pipfile +++ b/Pipfile @@ -6,13 +6,13 @@ verify_ssl = true [dev-packages] opencv-python= "*" ipython = "*" -networkx = "==2.3" +networkx = "~=2.3" azure-core = "*" azure-common = "*" -azure-nspkg = "==3.0.2" -azure-storage-blob = "==2.1.0" -azure-storage-common = "==2.1.0" -azure-storage-nspkg = "==3.1.0" +azure-nspkg = "~=3.0" +azure-storage-blob = "~=2.1" +azure-storage-common = "~=2.1" +azure-storage-nspkg = "~=3.1" boto = "*" "boto3" = "*" control = "*" @@ -41,9 +41,9 @@ redis = "*" "s2sphere" = "*" "subprocess32" = "*" tenacity = "*" -tensorflow-gpu = "==2.2.0" +tensorflow = "~=2.2" keras_applications = "*" -PyMySQL = "==0.9.2" +PyMySQL = "~=0.9" Werkzeug = "*" "backports.lzma" = "*" Flask-Cors = "*" @@ -69,7 +69,7 @@ paramiko = "*" aiohttp = "*" lru-dict = "*" scikit-image = "*" -pygame = "==2.0.0.dev6" +pygame = "==2.0.0.dev8" pprofile = "*" pyprof2calltree = "*" @@ -107,10 +107,10 @@ pylint = "*" pillow = "*" scons = "*" cysignals = "*" -pycryptodome = "*" -"Jinja2" = "*" -PyJWT = "*" +pycryptodome = "*" +"Jinja2" = "*" +PyJWT = "*" pyserial = "*" [requires] -python_version = "3.8.2" +python_version = "3.8" diff --git a/Pipfile.lock b/Pipfile.lock index fbd754bd5f..c3d18686df 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,11 +1,11 @@ { "_meta": { "hash": { - "sha256": "2fca285af32720e957e1fc42d7c512e9b9a2e93b416602f77d8129d7fd8efedc" + "sha256": "a274c1844cd5ad1f8cfb1cc523e51624c8f5d58bd1b9882f41534fd7bd75f3fb" }, "pipfile-spec": 6, "requires": { - "python_version": "3.8.2" + "python_version": "3.8" }, "sources": [ { @@ -21,7 +21,6 @@ "sha256:4c17cea3e592c21b6e222f673868961bad77e1f985cb1694ed077475a89229c1", "sha256:d8506842a3faf734b81599c8b98dcc423de863adcc1999248480b18bd31a0f38" ], - "markers": "python_version >= '3.5'", "version": "==2.4.1" }, "atomicwrites": { @@ -85,14 +84,10 @@ "sha256:d2b5255c7c6349bc1bd1e59e08cd12acbbd63ce649f2588755783aa94dfb6b1a", "sha256:dacca89f4bfadd5de3d7489b7c8a566eee0d3676333fbb50030263894c38c0dc" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==7.1.2" }, "crcmod": { "hashes": [ - "sha256:50586ab48981f11e5b117523d97bb70864a2a1af246cf6e4f5c4a21ef4611cd1", - "sha256:69a2e5c6c36d0f096a7beb4cd34e5f882ec5fd232efb710cdb85d4ff196bd52e", - "sha256:737fb308fa2ce9aed2e29075f0d5980d4a89bfbec48a368c607c5c63b3efb90e", "sha256:dc7051a0db5f2bd48665a990d3ec1cc305a466a77358ca4492826f41f283601e" ], "index": "pypi", @@ -132,42 +127,42 @@ }, "cython": { "hashes": [ - "sha256:00faa77500ca2f865fd7f3126f86e77de3ec0d855dd6cf92fc85b57ebed11655", - "sha256:14e218a93d4f2e43e0063a5a0f7f26fe1783d5d20700216c5c4ff092c4553488", - "sha256:179ad5569dc101e3e0d9d04305f9a5e03fbf8acf9d93fb543340f8c1a8fb054b", - "sha256:20cdf3f918c46355128d7c7cb041872ba2863cc11313972c6e390bd3dad968ba", - "sha256:2a98c9f852b266f0b9a147da4b6699cf6da24b817375f74d51986312373689ab", - "sha256:3950ae725472ae47bfb41c6bfdb3869a8ac27b5f30405f599a51398512afa224", - "sha256:4dbb58f963f6283b31b4ddac44e4f684527b06923efdec72ecb54e70ee91c766", - "sha256:4e8d351ee840a4e491f8f0a64da19923ada0ce09d2d818bce0ae6ce1b6837aeb", - "sha256:4f35752adfd4855d39e38bf08eb6d02f7aa88b1bb420ab86e6d2e37ccd7c88c2", - "sha256:5c501742a92cbcef8f3c21d1dcba9c073b37f1218af3586957901730ac6b6665", - "sha256:6361588cb1d82875bcfbad83d7dd66c442099759f895cf547995f00601f9caf2", - "sha256:719eddf050a1c8b0abbd74b0c388523cf618c3d9fe3bf20a350f4eafa43776e6", - "sha256:785d6e88a3bb10ce6425d23f0a740a21b0bfc9e8d371fea7edba0eaa0ec57d96", - "sha256:788192badd3b1ebb1a72a5c6cc2a07b692ca4c1c1fe4431fdd3c0e439e2c0a6d", - "sha256:7c8ac5bc9726ccb1a1cce1af4ceb7589228db6c57ada3bfcd461075abe3a6a7b", - "sha256:7cec6bd82fd92f85790908fdc7a43a8a5442606e6d771d5b32a1ab8a39ad1a65", - "sha256:7d597733ad0e7fc545df39100ee3b24290ce35586466dee4fa6018d4b8815d72", - "sha256:809896928abce18e7c91a28b2705473ca4f15b9a53f433495845a882e15c09d8", - "sha256:8135cc7de72805833a118e7c8a255daddd35875d17ea21f6c356200b0fa4b732", - "sha256:86ae455b1dd7041b4b8a15499fe72f3d3f990f78a794deb799ee2ef7db389ca0", - "sha256:8ef49cafea89d99ffc2cf37af2f0f2b7d219080574f14a422f701bcaa85c7167", - "sha256:96d18413a33aa5ce51a5554615ba01e3fdb26126d8678459330d052f0bdf60ec", - "sha256:a5ebd8fe5a3d97924bd89d449914d1c5b6d084f4b124a4eb28e4412d09fb0f20", - "sha256:b19a1aa98192d44d7254613a1f9c382ef381deb79289f2ff446d1447d19085aa", - "sha256:b6f7d2cf2f6b246fd04696d6d346489628f94f72a4988682ea0591b632370a1f", - "sha256:c56f658ab6f387619a3668cd78cf2d3459324d9ea3cb39cce4d72ef5bce8f318", - "sha256:c68f3015cbb0f5bc402829bad0a6b907889413f2e28cc0873dc1443de0f1a808", - "sha256:c78fd0bdf5915f4df730298e6cc7197e4c6aa5285d7c37491366a38125b3e0ab", - "sha256:dcfee6312cf8f4f4839bae22f323a0e885c4237e2187202ab12def8a5460ca4c", - "sha256:e146b4b4ed4937a40e9e5c27b264adfce4ae4b7640d46eeffd3eef123b0170a2", - "sha256:ea75bbc076d4a5605d04c72c8c7a933f51473b0bcecd79295256b9ecd75cca49", - "sha256:f7b20838f2534ad0d231c4c6e09acbdd40fb995a9671bb05839f7879093ec5e3", - "sha256:fce2e7f500b1456f96d5b8ceefba243cae7018ad8b3f791e62c20a0f0fbba71c" - ], - "index": "pypi", - "version": "==0.29.17" + "sha256:015f7d66d0cf72e2863dcd380d9613a0baf53bb4c572fdffff873b26d2da2d6c", + "sha256:048bc66902e7ca6af9d8146cfc700a66514bea711d9496b26df5eeee64a35010", + "sha256:15732423a5c7d6e7c400fdbc00121f48ca17e8ff1f76d6d10eeff5be3d270605", + "sha256:16160de2d02cf5f9987478cee428146d8a0509315eb8b523ad5e29d460582d2e", + "sha256:1ae4f5e8ede955fe3fad216d667b8c6d6a58d21dbbe5484fccafd8dd631ef313", + "sha256:297b2821bf11ba65667f9616fe48dbc40468158e745cefccd8b175825ad1265b", + "sha256:2b0aef8336036e6ea418cb728f56f2da39388649e722a1b622ae347ea7f18415", + "sha256:3d04a59991c6e51fd49608b4c7310bf501602cb9786d4e9c35b62ddfc7d735cc", + "sha256:3f11838f66e988dc13c91c8ea2e82a2bc5754eb4251920f512f1707a7cf7443a", + "sha256:427a718f2d435e7d5fde7878e9b331911dfeb660d5778e4e3ec1c5b09a05e4b7", + "sha256:4475245552b763066a3b811fc1d4619b3675afd64405734474fa51d2ef1b57b4", + "sha256:46e9ab055eb64595f160b61037c3e65ce0b01320d144a3a53eb807000078d53f", + "sha256:4aa23cc6aec04e339d112549b51d89326a1ac89075b8f2e2ad3436723fdb1b96", + "sha256:54de099507d6705a27de9e8cad629636c18b05a8d6e276537f91c9c58d632b38", + "sha256:5546b0f1e0c84c4c241a3679f6a5e27d0bbd29542e91e7a58030162ea987a7f0", + "sha256:59f462ad92cbb8f3832516f4c2812485138aa403e3bc9815f517841649b22724", + "sha256:6ff21c1b16817cb90dae33ce65cf2855ee76bcb0e70bd03887dedf8b553a95ba", + "sha256:7720445e2a53a0634d64a6c405a5f818d398136280d23e73d3ff5727ee16b596", + "sha256:7aef66dfcf908893da5bf22747137455c0714a0c78d17847b2918be2542c597f", + "sha256:7bf0881d2277b23652c74855776791e5f2aecfb89998c98764532770d130c863", + "sha256:801ecb4c646ecf32dfe9eb84568a12f2371ab71d64d42f3b914b497f6b843459", + "sha256:81351cf2f055064e40f360705f05ae931e987d8933bc6d746f7c7331b98bceba", + "sha256:bc1af976b82b8891e473857fdbfd08ec937fd4960bfdf2b59bc338f6d45ecec8", + "sha256:c489b1ba691f0a79b8c2824332210177cde6ef24439082790143371ca8670edf", + "sha256:c76eae1fb343332617bb997e2a3da242a36791f8890e91272cc159f01dda0705", + "sha256:c7ac0b16761034fe2e0c48caedc7a5b1f56a5bf845718f921b4788d2047db1bc", + "sha256:d3a02c0bd96c6a9ce064eff4c6f198c2c2a3e1e89c1aeb2f9bec4340edd98938", + "sha256:d6918608d55b7f59dfeebcdf7549aab2b9e47db498f6f1fa0133ecf8ebf088ae", + "sha256:d6fdd0d5510ba3b4f50ec44c047815e58be4c7588624ab156d02fbaaa04aa7f9", + "sha256:d77a7f45d55755eae528a4c44f7ece2b0bbfbe191a3bf2275b90562bad78db0e", + "sha256:d9778569f848aedbab8c953453346e508e2d7d0f3288936435c863ca8c44d038", + "sha256:de70eface4532aafa045008f23eded89044b7af1d298b28e0601cf0b07febe28", + "sha256:fbde5e13f0c5c8607661f9b9abb337e8a12dd52d13f7cb2a28ff5ffbfb3b5279" + ], + "index": "pypi", + "version": "==0.29.18" }, "flake8": { "hashes": [ @@ -205,7 +200,6 @@ "sha256:7588d1c14ae4c77d74036e8c22ff447b26d0fde8f007354fd48a7814db15b7cb", "sha256:a068a21ceac8a4d63dbfd964670474107f541babbd2250d61922f029858365fa" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.9" }, "isort": { @@ -213,7 +207,6 @@ "sha256:54da7e92468955c4fceacd0c86bd0ec997b0e1ee80d97f67c35a78b719dccab1", "sha256:6e811fcb295968434526407adb8796944f1988c5b65e8139058f2014cbe100fd" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==4.3.21" }, "itsdangerous": { @@ -221,7 +214,6 @@ "sha256:321b033d07f2a4136d3ec762eac9f16a10ccd60f53c0c91af90217ace7ba1f19", "sha256:b12271b2047cb23eeb98c8b5622e2e5c5e9abd9784a153e9d8ef9cb4dd09d749" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.1.0" }, "jinja2": { @@ -264,7 +256,6 @@ "sha256:efa1909120ce98bbb3777e8b6f92237f5d5c8ea6758efea36a473e1d38f7d3e4", "sha256:f3900e8a5de27447acbf900b4750b0ddfd7ec1ea7fbaf11dfa911141bc522af0" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.4.3" }, "libusb1": { @@ -276,8 +267,7 @@ }, "logentries": { "git": "https://github.com/commaai/le_python.git", - "ref": "feaeacb48f7f4bdb02c0a8fc092326d4e101b7f2", - "version": "==0.8" + "ref": "feaeacb48f7f4bdb02c0a8fc092326d4e101b7f2" }, "markupsafe": { "hashes": [ @@ -315,7 +305,6 @@ "sha256:e249096428b3ae81b08327a63a485ad0878de3fb939049038579ac0ef61e17e7", "sha256:e8313f01ba26fbbe36c7be1966a7b7424942f670f38e666995b88d012765b9be" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.1.1" }, "mccabe": { @@ -376,7 +365,6 @@ "sha256:1f694e28c169655c50bb89a3fa07f3b854d71eb47f50783621de813979ba87f3", "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", - "sha256:70e3e0d99a0dcda66283a185f80697a9b08806963c6149c8e6c5f452b2aa59c0", "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd", "sha256:ae2b270f9a0b8822b98655cb3a59cdb1bd54a34807c6c56b76dd2e786c3b7db3", @@ -425,7 +413,6 @@ "sha256:2295e7b2f6b5bd100585ebcb1f616591b652db8a741695b3d8f5d28bdc934367", "sha256:c58a7d2815e0e8d7972bf1803331fb0152f867bd89adf8a01dfd55085434192e" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.6.0" }, "pycparser": { @@ -433,7 +420,6 @@ "sha256:2d475327684562c3a96cc71adf7dc8c4f0565175cf86b6d7a404ff4c771f15f0", "sha256:7582ad22678f0fcd81102833f60ef8d0e57288b6b5fb00323d101be910e35705" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.20" }, "pycryptodome": { @@ -477,7 +463,6 @@ "sha256:0d94e0e05a19e57a99444b6ddcf9a6eb2e5c68d3ca1e98e90707af8152c90a92", "sha256:35b2d75ee967ea93b55750aa9edbbf72813e06a66ba54438df2cfac9e3c27fc8" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.2.0" }, "pyjwt": { @@ -620,11 +605,10 @@ }, "toml": { "hashes": [ - "sha256:229f81c57791a41d65e399fc06bf0848bab550a9dfd5ed66df18ce5f05e73d5c", - "sha256:235682dd292d5899d361a811df37e04a8828a5b1da3115886b73cf81ebc9100e", - "sha256:f1db651f9657708513243e61e6cc67d101a39bad662eaa9b5546f789338e07a3" + "sha256:926b612be1e5ce0634a2ca03470f95169cf16f939018233a670519cb4ac58b0f", + "sha256:bda89d5935c2eac546d648028b9901107a595863cb36bae0c73ac804a9b4ce88" ], - "version": "==0.10.0" + "version": "==0.10.1" }, "tqdm": { "hashes": [ @@ -662,7 +646,6 @@ "sha256:2de2a5db0baeae7b2d2664949077c2ac63fbd16d98da0ff71837f7d1dea3fd43", "sha256:6c80b1e5ad3665290ea39320b91e1be1e0d5f60652b964a3070216de83d2e47c" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.0.1" }, "wrapt": { @@ -713,13 +696,6 @@ "index": "pypi", "version": "==3.6.2" }, - "appdirs": { - "hashes": [ - "sha256:7d5d0167b2b1ba821647616af46a749d1c653740dd0d2415100fe26e27afdf41", - "sha256:a841dacd6b99318a741b166adb07e19ee71a274450e68237b4650ca1055ab128" - ], - "version": "==1.4.4" - }, "applicationinsights": { "hashes": [ "sha256:30a11aafacea34f8b160fbdc35254c9029c7e325267874e3c68f6bdbcd6ed2c3", @@ -739,7 +715,6 @@ "sha256:4c17cea3e592c21b6e222f673868961bad77e1f985cb1694ed077475a89229c1", "sha256:d8506842a3faf734b81599c8b98dcc423de863adcc1999248480b18bd31a0f38" ], - "markers": "python_version >= '3.5'", "version": "==2.4.1" }, "astunparse": { @@ -754,7 +729,6 @@ "sha256:0c3c816a028d47f659d6ff5c745cb2acf1f966da1fe5c19c77a70282b25f4c5f", "sha256:4291ca197d287d274d0b6cb5d6f8f8f82d434ed288f962539ff18cc9012f9ea3" ], - "markers": "python_version >= '3.5.3'", "version": "==3.0.1" }, "attrs": { @@ -762,16 +736,15 @@ "sha256:08a96c641c3a74e44eb59afb61a24f2cb9f4d7188748e76ba4bb5edfa3cb7d1c", "sha256:f7b7ce16570fe9965acd6d30101a28f62fb4a7f9e926b3bbc9b61f8b04247e72" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==19.3.0" }, "azure-cli-core": { "hashes": [ - "sha256:5b2d3952f7edab1a34d7421b5a7ff1aabf32d9fca6614bdac5ec9938e64b7caa", - "sha256:668d45eef11ff155969c205b730d044d18d4729bf70d127f85cfd85ed69bff98" + "sha256:191a4c0ab4e606d61891c05b017fba68e90586f27f65aa45d35b9a99fe37132d", + "sha256:c1fb19abc52b1de7441e6fefbda924cba4ef663e80b713d6f9bc27e7478bb41f" ], "index": "pypi", - "version": "==2.5.1" + "version": "==2.6.0" }, "azure-cli-nspkg": { "hashes": [ @@ -887,7 +860,6 @@ "sha256:d7bdc26475679dd073ba0ed2766445bb5b20ca4793ca0db32b399dccc6bc84b7", "sha256:ff032765bb8716d9387fd5376d987a937254b0619eff0972779515b5c98820bc" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==3.1.7" }, "bleach": { @@ -895,7 +867,6 @@ "sha256:2bce3d8fab545a6528c8fa5d9f9ae8ebc85a56da365c7f85180bfe96a35ef22f", "sha256:3c4c520fdb9db59ef139915a5db79f8b51bc2a7257ea0389f30c846883430a4b" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==3.1.5" }, "boto": { @@ -908,25 +879,24 @@ }, "boto3": { "hashes": [ - "sha256:b81a6296134aec4d48319e5d25e47c2abcea2cd13ddd160f95b692e56c6ab9b7", - "sha256:c347350521e8138a42b7c877bb87ba32842405d7bc7fd86b29745abc60b9e83d" + "sha256:3c740de27ca113bcdbf5449d6d221428e5bc529e8e7d8e7dd87790602078c333", + "sha256:a396e514eb6ee57994718a7c85d3810bfda23faba01dd80c65e0aba6a5dedb1f" ], "index": "pypi", - "version": "==1.13.8" + "version": "==1.13.13" }, "botocore": { "hashes": [ - "sha256:68eb83d97a8ecdbf271c17989280bc9a533269d4ee983d2ef80289e2333042da", - "sha256:8263bba760c3f24aeb0651936b24798ba8a172828afdccf8bee5ca6d5d7c4b9c" + "sha256:5227e7a6d9d88560bae22149dc0d87b71679cf9c63ad79bf37bb2b7cd8e07db0", + "sha256:babc267e4ff043f3e722f9b0103fd808934519f9148ef7360c255d1aefcb96d7" ], - "version": "==1.16.8" + "version": "==1.16.13" }, "cachetools": { "hashes": [ "sha256:1d057645db16ca7fe1f3bd953558897603d6f0b9c51ed9d11eb4d071ec4e2aab", "sha256:de5d88f87781602201cde465d3afe837546663b168e8b39df67411b0bf10cefc" ], - "markers": "python_version ~= '3.5'", "version": "==4.1.0" }, "certifi": { @@ -982,7 +952,6 @@ "sha256:d2b5255c7c6349bc1bd1e59e08cd12acbbd63ce649f2588755783aa94dfb6b1a", "sha256:dacca89f4bfadd5de3d7489b7c8a566eee0d3676333fbb50030263894c38c0dc" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==7.1.2" }, "colorama": { @@ -990,7 +959,6 @@ "sha256:7d73d2a99753107a36ac6b455ee49046802e59d9d076ef8e47b61499fa29afff", "sha256:e96da0d330793e2cb9485e9ddfd918d456036c7149416295932478192f4436a1" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.4.3" }, "control": { @@ -1089,7 +1057,6 @@ "sha256:6687150770438374ab581bb7a1b327a847dd9c5749e396102de3fad4e8a3ef93", "sha256:f684034d135af4c6cbb949b8a4d2ed61634515257a67299e5f940fbaa34377f5" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.6.0" }, "dictdiffer": { @@ -1113,23 +1080,21 @@ "sha256:9e4d7ecfc600058e07ba661411a2b7de2fd0fafa17d1a7f7361cd47b1175c827", "sha256:a2aeea129088da402665e92e0b25b04b073c04b2dce4ab65caaa38b7ce2e1a99" ], - "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.15.2" }, "elasticsearch": { "hashes": [ - "sha256:d228b2d37ac0865f7631335268172dbdaa426adec1da3ed006dddf05134f89c8", - "sha256:f4bb05cfe55cf369bdcb4d86d0129d39d66a91fd9517b13cd4e4231fbfcf5c81" + "sha256:35de81968b78a1c708178773ccca56422661fc6e00905b81f48af8e8a9a2a6ba", + "sha256:eae591811e9bd82845ea22db3e891c30cad3d0f3e5dfd79cee80708872e5f626" ], "index": "pypi", - "version": "==7.6.0" + "version": "==7.7.0" }, "entrypoints": { "hashes": [ "sha256:589f874b313739ad35be6e0cd7efde2a4e9b6fea91edcc34e58ecbb8dbe56d19", "sha256:c70dd71abe5a8c85e55e12c19bd91ccfeec11a6e99044204511f9ed547d48451" ], - "markers": "python_version >= '2.7'", "version": "==0.3" }, "fastcluster": { @@ -1189,7 +1154,6 @@ "hashes": [ "sha256:b1bead90b70cf6ec3f0710ae53a525360fa360d306a86583adc6bf83a4db537d" ], - "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.18.2" }, "gast": { @@ -1197,16 +1161,15 @@ "sha256:8f46f5be57ae6889a4e16e2ca113b1703ef17f2b0abceb83793eaba9e1351a45", "sha256:b881ef288a49aa81440d2c5eb8aeefd4c2bb8993d5f50edae7413a85bfdb3b57" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.3.3" }, "geoalchemy2": { "hashes": [ - "sha256:379b0fc4ca5f9b5ef625719f47e22c9b8abd347aa78344e85f99d32594cfccd4", - "sha256:ec2a6e9919b522631803ac5922e88b701081da7e5d56a68f10ff263f6592d552" + "sha256:4c87177a570ed21307e255f22309e5e0a249e0b8fa9d800b9dc68a70af911074", + "sha256:85add5aa337ba697895a41608333088277144fa7ddb5eca2046a3794ade15f42" ], "index": "pypi", - "version": "==0.7.0" + "version": "==0.8.2" }, "git-pylint-commit-hook": { "hashes": [ @@ -1217,11 +1180,10 @@ }, "google-auth": { "hashes": [ - "sha256:4942ab1ff530e740866571c0416fb5a7dc9ec53233a8f8dff63e8cd7371003d1", - "sha256:82d32f6601f35309c95d5917bcdf72f3ec193c7f46c79e433b8d76ccbe68e21d" + "sha256:73b141d122942afe12e8bfdcb6900d5df35c27d39700f078363ba0b1298ad33b", + "sha256:fbf25fee328c0828ef293459d9c649ef84ee44c0b932bb999d19df0ead1b40cf" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.14.3" + "version": "==1.15.0" }, "google-auth-oauthlib": { "hashes": [ @@ -1240,39 +1202,39 @@ }, "grpcio": { "hashes": [ - "sha256:085bbf7fd0070b8d65e84aa32979f17cfe624d27b5ce23955ef770c19d2d9623", - "sha256:0ae207a47ec0ad66eb1f53a27d566674d13a236c62ced409891335318ea9b8c5", - "sha256:0c130204ff5de0b9f041bf3126db0d29369d69883592e4b0d3c19868ba0ced7e", - "sha256:0ef6b380a588c2c6b29c6cfa0ba7f5d367beb33d5504bcc68658fa241ad498d2", - "sha256:16e1edb367763ea08d0994d4635ec05f4f8db9db59c39304b061097e3b93df43", - "sha256:16f5523dacae5aaeda4cf900da7e980747f663298c38c18eb4e5317704aa007a", - "sha256:181b5078cf568f37915b8a118afcef5fc9f3128c59c38998ed93e7dd793e3928", - "sha256:245564713cb4ac7bccb0f11be63781beb62299a44d8ab69031c859dbd9461728", - "sha256:271abbe28eb99fa5c70b3f272c0c66b67dab7bb11e1d29d8e616b4e0e099d29a", - "sha256:2e1b01cba26988c811c7fb91a0bca19c9afb776cc3d228993f08d324bdd0510a", - "sha256:3366bd6412c1e73acb1ee27d7f0c7d7dbee118ad8d98c957c8173691b2effeec", - "sha256:3893b39a0a17d857dc3a42fdb02a26aa53a59bfce49987187bcc0261647f1f55", - "sha256:3c7864d5ae63b787001b01b376f6315aef1a015aa9c809535235ed0ead907919", - "sha256:42c6716adf3ec1f608b2b56e885f26dd86e80d2fc1617f51fc92d1b0b649e28e", - "sha256:4bef0756b9e0df78e8d67a5b1e0e89b7daf41525d575f74e1f14a993c55b680d", - "sha256:4fe081862e58b8fbef0e479aefc9a64f8f17f53074df1085d8c1fe825a6e5df4", - "sha256:505a8d1b4ac571a51f10c4c995d5d4714f03c886604dc3c097ef5fd57bcfcf0b", - "sha256:5c2e81b6ab9768c43f2ca1c9a4c925823aad79ae95efb351007df4b92ebce592", - "sha256:70ff2df0c1795c5cf585a72d95bb458838b40bad5653c314b9067ba819e918f9", - "sha256:97b5612fc5d4bbf0490a2d80bed5eab5b59112ef1640440c1a9ac824bafa6968", - "sha256:a35f8f4a0334ed8b05db90383aecef8e49923ab430689a4360a74052f3a89cf4", - "sha256:aafe85a8210dfa1da3c46831b7f00c3735240b7b028eeba339eaea6ffdb593fb", - "sha256:c2e53eb253840f05278a8410628419ba7060815f86d48c9d83b6047de21c9956", - "sha256:c3645887db3309fc87c3db740b977d403fb265ebab292f1f6a926c4661231fd5", - "sha256:c6565cc92853af13237b2233f331efdad07339d27fe1f5f74256bfde7dc2f587", - "sha256:cbc322c5d5615e67c2a15be631f64e6c2bab8c12505bc7c150948abdaa0bdbac", - "sha256:df749ee982ec35ab76d37a1e637b10a92b4573e2b4e1f86a5fa8a1273c40a850", - "sha256:e9439d7b801c86df13c6cbb4c5a7e181c058f3c119d5e119a94a5f3090a8f060", - "sha256:f493ac4754717f25ace3614a51dd408a32b8bff3c9c0c85e9356e7e0a120a8c8", - "sha256:f80d10bdf1a306f7063046321fd4efc7732a606acdd4e6259b8a37349079b704", - "sha256:f83b0c91796eb42865451a20e82246011078ba067ea0744f7301e12a94ae2e1b" - ], - "version": "==1.28.1" + "sha256:10cdc8946a7c2284bbc8e16d346eaa2beeaae86ea598f345df86d4ef7dfedb84", + "sha256:23bc395a32c2465564cb242e48bdd2fdbe5a4aebf307649a800da1b971ee7f29", + "sha256:2637ce96b7c954d2b71060f50eb4c72f81668f1b2faa6cbdc74677e405978901", + "sha256:3d8c510b6eabce5192ce126003d74d7751c7218d3e2ad39fcf02400d7ec43abe", + "sha256:5024b26e17a1bfc9390fb3b8077bf886eee02970af780fd23072970ef08cefe8", + "sha256:517538a54afdd67162ea2af1ac3326c0752c5d13e6ddadbc4885f6a28e91ab28", + "sha256:524ae8d3da61b856cf08abb3d0947df05402919e4be1f88328e0c1004031f72e", + "sha256:54e4658c09084b09cd83a5ea3a8bce78e4031ff1010bb8908c399a22a76a6f08", + "sha256:57c8cc2ae8cb94c3a89671af7e1380a4cdfcd6bab7ba303f4461ec32ded250ae", + "sha256:5fd9ffe938e9225c654c60eb21ff011108cc27302db85200413807e0eda99a4a", + "sha256:75b2247307a7ecaf6abc9eb2bd04af8f88816c111b87bf0044d7924396e9549c", + "sha256:7bf3cb1e0f4a9c89f7b748583b994bdce183103d89d5ff486da48a7668a052c7", + "sha256:7e02a7c40304eecee203f809a982732bd37fad4e798acad98fe73c66e44ff2db", + "sha256:806c9759f5589b3761561187408e0313a35c5c53f075c7590effab8d27d67dfe", + "sha256:80e9f9f6265149ca7c84e1c8c31c2cf3e2869c45776fbe8880a3133a11d6d290", + "sha256:81bbf78a399e0ee516c81ddad8601f12af3fc9b30f2e4b2fbd64efd327304a4d", + "sha256:886d48c32960b39e059494637eb0157a694956248d03b0de814447c188b74799", + "sha256:97b72bf2242a351a89184134adbb0ae3b422e6893c6c712bc7669e2eab21501b", + "sha256:97fcbdf1f12e0079d26db73da11ee35a09adc870b1e72fbff0211f6a8003a4e8", + "sha256:9cfb4b71cc3c8757f137d47000f9d90d4bd818733f9ab4f78bd447e052a4cb9a", + "sha256:9ef0370bcf629ece4e7e37796e4604e2514b920669be2911fc3f9c163a73a57b", + "sha256:a6dddb177b3cfa0cfe299fb9e07d6a3382cc79466bef48fe9c4326d5c5b1dcb8", + "sha256:a97ea91e31863c9a3879684b5fb3c6ab4b17c5431787548fc9f52b9483ea9c25", + "sha256:b49f243936b0f6ae8eb6adf88a1e54e736f1c6724a1bff6b591d105d708263ad", + "sha256:b85f355fc24b68a6c52f2750e7141110d1fcd07dfdc9b282de0000550fe0511b", + "sha256:c3a0ef12ee86f6e72db50e01c3dba7735a76d8c30104b9b0f7fd9d65ceb9d93f", + "sha256:da0ca9b1089d00e39a8b83deec799a4e5c37ec1b44d804495424acde50531868", + "sha256:e90f3d11185c36593186e5ff1f581acc6ddfa4190f145b0366e579de1f52803b", + "sha256:ebf0ccb782027ef9e213e03b6d00bbd8dabd80959db7d468c0738e6d94b5204c", + "sha256:eede3039c3998e2cc0f6713f4ac70f235bd32967c9b958a17bf937aceebc12c3", + "sha256:ff7931241351521b8df01d7448800ce0d59364321d8d82c49b826d455678ff08" + ], + "version": "==1.29.0" }, "gunicorn": { "hashes": [ @@ -1329,7 +1291,6 @@ "sha256:bf52ec91244819c780341a3438d5d7b09f431d3f113a475147ac9b7b167a3d12", "sha256:e78960b31198511f45fd455534ae7645a6207d33e512d2e842c766d15d9c8080" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==8.2" }, "idna": { @@ -1337,7 +1298,6 @@ "sha256:7588d1c14ae4c77d74036e8c22ff447b26d0fde8f007354fd48a7814db15b7cb", "sha256:a068a21ceac8a4d63dbfd964670474107f541babbd2250d61922f029858365fa" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.9" }, "imagecodecs": { @@ -1365,7 +1325,6 @@ "sha256:f6ac9dd40e1cdb72842fb72f147e8a51a1874c8f375629524566b388e841be20", "sha256:fbdd0d42aa3c984377421767a892e77c40249870425aca0ba5629bdcd57d3ae4" ], - "markers": "python_version >= '3.6'", "version": "==2020.2.18" }, "imageio": { @@ -1418,7 +1377,6 @@ "sha256:54da7e92468955c4fceacd0c86bd0ec997b0e1ee80d97f67c35a78b719dccab1", "sha256:6e811fcb295968434526407adb8796944f1988c5b65e8139058f2014cbe100fd" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==4.3.21" }, "itsdangerous": { @@ -1426,7 +1384,6 @@ "sha256:321b033d07f2a4136d3ec762eac9f16a10ccd60f53c0c91af90217ace7ba1f19", "sha256:b12271b2047cb23eeb98c8b5622e2e5c5e9abd9784a153e9d8ef9cb4dd09d749" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.1.0" }, "jedi": { @@ -1434,7 +1391,6 @@ "sha256:cd60c93b71944d628ccac47df9a60fec53150de53d42dc10a7fc4b5ba6aae798", "sha256:df40c97641cb943661d2db4c33c2e1ff75d491189423249e989bcea4464f3030" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.17.0" }, "jinja2": { @@ -1450,16 +1406,15 @@ "sha256:b85d0567b8666149a93172712e68920734333c0ce7e89b78b3e987f71e5ed4f9", "sha256:cdf6525904cc597730141d61b36f2e4b8ecc257c420fa2f4549bac2c2d0cb72f" ], - "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.10.0" }, "joblib": { "hashes": [ - "sha256:0630eea4f5664c463f23fbf5dcfc54a2bc6168902719fa8e19daf033022786c8", - "sha256:bdb4fd9b72915ffb49fde2229ce482dd7ae79d842ed8c2b4c932441495af1403" + "sha256:61e49189c84b3c5d99a969d314853f4d1d263316cc694bec17548ebaa9c47b6e", + "sha256:6825784ffda353cc8a1be573118085789e5b5d29401856b35b756645ab5aecb5" ], "index": "pypi", - "version": "==0.14.1" + "version": "==0.15.1" }, "json-logging-py": { "hashes": [ @@ -1489,7 +1444,6 @@ "sha256:3a32fa4d0b16d1c626b30c3002a62dfd86d6863ed39eaba3f537fade197bb756", "sha256:cde8e83aab3ec1c614f221ae54713a9a46d3bf28292609d2db1b439bef5a8c8e" ], - "markers": "python_version >= '3.5'", "version": "==6.1.3" }, "jupyter-console": { @@ -1497,7 +1451,6 @@ "sha256:6f6ead433b0534909df789ea64f0a14cdf9b6b2360757756f08182be4b9e431b", "sha256:b392155112ec86a329df03b225749a0fa903aa80811e8eda55796a40b5e470d8" ], - "markers": "python_version >= '3.5'", "version": "==6.1.0" }, "jupyter-core": { @@ -1505,7 +1458,6 @@ "sha256:394fd5dd787e7c8861741880bdf8a00ce39f95de5d18e579c74b882522219e7e", "sha256:a4ee613c060fe5697d913416fc9d553599c05e4492d58fac1192c9a6844abb21" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==4.6.3" }, "keras-applications": { @@ -1518,10 +1470,10 @@ }, "keras-preprocessing": { "hashes": [ - "sha256:138012da7bbc5508d59681515636c01618644322db08c1f4c6d66e63de8ddb73", - "sha256:c0b1ebe444e46075a9079629fa0e0d0fb1d681b4a72340ca5406b574894276a5" + "sha256:7b82029b130ff61cc99b55f3bd27427df4838576838c5b2f65940e4fcec99a7b", + "sha256:add82567c50c8bc648c14195bf544a5ce7c1f76761536956c3d2978970179ef3" ], - "version": "==1.1.1" + "version": "==1.1.2" }, "kiwisolver": { "hashes": [ @@ -1542,15 +1494,14 @@ "sha256:efcf3397ae1e3c3a4a0a0636542bcad5adad3b1dd3e8e629d0b6e201347176c8", "sha256:fccefc0d36a38c57b7bd233a9b485e2f1eb71903ca7ad7adacad6c28a56d62d2" ], - "markers": "python_version >= '3.6'", "version": "==1.2.0" }, "knack": { "hashes": [ - "sha256:4063e504db33d62e4fff00ccb0fb9563bdde6232a27764e07087db75f7de7830", - "sha256:66d1ff609ecfa1da48f731c9258f03d5dd1da324e2cf81732c78e993afc46683" + "sha256:1c4c1aa16df842caa862ce39c5f83aab79c0fcb4e992e1043f68add87250e9fd", + "sha256:fcef6040164ebe7d69629e4e089b398c9b980791446496301befcf8381dba0fc" ], - "version": "==0.7.0rc4" + "version": "==0.7.1" }, "lazy-object-proxy": { "hashes": [ @@ -1576,7 +1527,6 @@ "sha256:efa1909120ce98bbb3777e8b6f92237f5d5c8ea6758efea36a473e1d38f7d3e4", "sha256:f3900e8a5de27447acbf900b4750b0ddfd7ec1ea7fbaf11dfa911141bc522af0" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.4.3" }, "limits": { @@ -1598,7 +1548,6 @@ "sha256:1fafe3f1ecabfb514a5285fca634a53c1b32a81cb0feb154264d55bf2ff22c17", "sha256:c467cd6233885534bf0fe96e62e3cf46cfc1605112356c4f9981512b8174de59" ], - "markers": "python_version >= '3.5'", "version": "==3.2.2" }, "markupsafe": { @@ -1637,7 +1586,6 @@ "sha256:e249096428b3ae81b08327a63a485ad0878de3fb939049038579ac0ef61e17e7", "sha256:e8313f01ba26fbbe36c7be1966a7b7424942f670f38e666995b88d012765b9be" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.1.1" }, "matplotlib": { @@ -1712,10 +1660,10 @@ }, "msrest": { "hashes": [ - "sha256:22349c718f632e37beee0dd10f7ea41984ded136db2199a9d3c6f1f3942868e9", - "sha256:9050fbbb95dd9e8f4008d7227e4dc5662e8b605c89e5621b0dd09ac7f04cf01d" + "sha256:f52f880a2145c075f436083ee9a274ddc54c62181e4c41c9ac11520fbae547e5", + "sha256:f54a60084969656faa2755bfa5f614951b07a870e97dfc8f0b0b8ea94a63b5b5" ], - "version": "==0.6.13" + "version": "==0.6.14" }, "msrestazure": { "hashes": [ @@ -1726,33 +1674,31 @@ }, "multidict": { "hashes": [ - "sha256:317f96bc0950d249e96d8d29ab556d01dd38888fbe68324f46fd834b430169f1", - "sha256:42f56542166040b4474c0c608ed051732033cd821126493cf25b6c276df7dd35", - "sha256:4b7df040fb5fe826d689204f9b544af469593fb3ff3a069a6ad3409f742f5928", - "sha256:544fae9261232a97102e27a926019100a9db75bec7b37feedd74b3aa82f29969", - "sha256:620b37c3fea181dab09267cd5a84b0f23fa043beb8bc50d8474dd9694de1fa6e", - "sha256:6e6fef114741c4d7ca46da8449038ec8b1e880bbe68674c01ceeb1ac8a648e78", - "sha256:7774e9f6c9af3f12f296131453f7b81dabb7ebdb948483362f5afcaac8a826f1", - "sha256:85cb26c38c96f76b7ff38b86c9d560dea10cf3459bb5f4caf72fc1bb932c7136", - "sha256:a326f4240123a2ac66bb163eeba99578e9d63a8654a59f4688a79198f9aa10f8", - "sha256:ae402f43604e3b2bc41e8ea8b8526c7fa7139ed76b0d64fc48e28125925275b2", - "sha256:aee283c49601fa4c13adc64c09c978838a7e812f85377ae130a24d7198c0331e", - "sha256:b51249fdd2923739cd3efc95a3d6c363b67bbf779208e9f37fd5e68540d1a4d4", - "sha256:bb519becc46275c594410c6c28a8a0adc66fe24fef154a9addea54c1adb006f5", - "sha256:c2c37185fb0af79d5c117b8d2764f4321eeb12ba8c141a95d0aa8c2c1d0a11dd", - "sha256:dc561313279f9d05a3d0ffa89cd15ae477528ea37aa9795c4654588a3287a9ab", - "sha256:e439c9a10a95cb32abd708bb8be83b2134fa93790a4fb0535ca36db3dda94d20", - "sha256:fc3b4adc2ee8474cb3cd2a155305d5f8eda0a9c91320f83e55748e1fcb68f8e3" - ], - "markers": "python_version >= '3.5'", - "version": "==4.7.5" + "sha256:1ece5a3369835c20ed57adadc663400b5525904e53bae59ec854a5d36b39b21a", + "sha256:275ca32383bc5d1894b6975bb4ca6a7ff16ab76fa622967625baeebcf8079000", + "sha256:3750f2205b800aac4bb03b5ae48025a64e474d2c6cc79547988ba1d4122a09e2", + "sha256:4538273208e7294b2659b1602490f4ed3ab1c8cf9dbdd817e0e9db8e64be2507", + "sha256:5141c13374e6b25fe6bf092052ab55c0c03d21bd66c94a0e3ae371d3e4d865a5", + "sha256:51a4d210404ac61d32dada00a50ea7ba412e6ea945bbe992e4d7a595276d2ec7", + "sha256:5cf311a0f5ef80fe73e4f4c0f0998ec08f954a6ec72b746f3c179e37de1d210d", + "sha256:6513728873f4326999429a8b00fc7ceddb2509b01d5fd3f3be7881a257b8d463", + "sha256:7388d2ef3c55a8ba80da62ecfafa06a1c097c18032a501ffd4cabbc52d7f2b19", + "sha256:9456e90649005ad40558f4cf51dbb842e32807df75146c6d940b6f5abb4a78f3", + "sha256:c026fe9a05130e44157b98fea3ab12969e5b60691a276150db9eda71710cd10b", + "sha256:d14842362ed4cf63751648e7672f7174c9818459d169231d03c56e84daf90b7c", + "sha256:e0d072ae0f2a179c375f67e3da300b47e1a83293c554450b29c900e50afaae87", + "sha256:f07acae137b71af3bb548bd8da720956a3bc9f9a0b87733e0899226a2317aeb7", + "sha256:fbb77a75e529021e7c4a8d4e823d88ef4d23674a202be4f5addffc72cbb91430", + "sha256:fcfbb44c59af3f8ea984de67ec7c306f618a3ec771c2843804069917a8f2e255", + "sha256:feed85993dbdb1dbc29102f50bca65bdc68f2c0c8d352468c25b54874f23c39d" + ], + "version": "==4.7.6" }, "nbconvert": { "hashes": [ "sha256:21fb48e700b43e82ba0e3142421a659d7739b65568cc832a13976a77be16b523", "sha256:f0d6ec03875f96df45aa13e21fd9b8450c42d7e1830418cccc008c0df725fcee" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==5.6.1" }, "nbformat": { @@ -1760,22 +1706,21 @@ "sha256:049af048ed76b95c3c44043620c17e56bc001329e07f83fec4f177f0e3d7b757", "sha256:276343c78a9660ab2a63c28cc33da5f7c58c092b3f3a40b6017ae2ce6689320d" ], - "markers": "python_version >= '3.5'", "version": "==5.0.6" }, "networkx": { "hashes": [ - "sha256:8311ddef63cf5c5c5e7c1d0212dd141d9a1fe3f474915281b73597ed5f1d4e3d" + "sha256:cdfbf698749a5014bf2ed9db4a07a5295df1d3a53bf80bf3cbd61edf9df05fa1", + "sha256:f8f4ff0b6f96e4f9b16af6b84622597b5334bf9cae8cf9b2e42e7985d5c95c64" ], "index": "pypi", - "version": "==2.3" + "version": "==2.4" }, "notebook": { "hashes": [ "sha256:3edc616c684214292994a3af05eaea4cc043f6b4247d830f3a2f209fa7639a80", "sha256:47a9092975c9e7965ada00b9a20f0cf637d001db60d241d479f53c0be117ad48" ], - "markers": "python_version >= '3.5'", "version": "==6.0.3" }, "numpy": { @@ -1810,7 +1755,6 @@ "sha256:bee41cc35fcca6e988463cacc3bcb8a96224f470ca547e697b604cc697b2f889", "sha256:df884cd6cbe20e32633f1db1072e9356f53638e4361bef4e8b03c9127c9328ea" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==3.1.0" }, "opencv-python": { @@ -1844,7 +1788,6 @@ "sha256:83b76a98d18ae6a5cc7a0d88955a7f74881f0e567a0f4c949d24c942753eb998", "sha256:96f819d46da2f937eaf326336a114aaeccbcbdb9de460d42e8b5f480a69adca7" ], - "markers": "python_version >= '3.5'", "version": "==3.2.1" }, "osmium": { @@ -1879,11 +1822,10 @@ }, "packaging": { "hashes": [ - "sha256:3c292b474fda1671ec57d46d739d072bfd495a4f51ad01a055121d81e952b7a3", - "sha256:82f77b9bee21c1bafbf35a84905d604d5d1223801d639cf3ed140bd651c08752" + "sha256:4357f74f47b9c12db93624a82154e9b120fa8293699949152b22065d556079f8", + "sha256:998416ba6962ae7fbd6596850b80e17859a5753ba17c32284f67bfff33784181" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==20.3" + "version": "==20.4" }, "pandas": { "hashes": [ @@ -1904,7 +1846,6 @@ "sha256:ca84a44cf727f211752e91eab2d1c6c1ab0f0540d5636a8382a3af428542826e", "sha256:d234bcf669e8b4d6cbcd99e3ce7a8918414520aeb113e2a81aeb02d0a533d7f7" ], - "markers": "python_version >= '3.6.1'", "version": "==1.0.3" }, "pandocfilters": { @@ -1926,7 +1867,6 @@ "sha256:158c140fc04112dc45bca311633ae5033c2c2a7b732fa33d0955bad8152a8dd0", "sha256:908e9fae2144a076d72ae4e25539143d40b8e3eafbaeae03c1bfe226f4cdf12c" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.7.0" }, "pexpect": { @@ -1953,7 +1893,6 @@ "sha256:1f694e28c169655c50bb89a3fa07f3b854d71eb47f50783621de813979ba87f3", "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", - "sha256:70e3e0d99a0dcda66283a185f80697a9b08806963c6149c8e6c5f452b2aa59c0", "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd", "sha256:ae2b270f9a0b8822b98655cb3a59cdb1bd54a34807c6c56b76dd2e786c3b7db3", @@ -1980,14 +1919,6 @@ ], "version": "==1.5.0.1" }, - "pooch": { - "hashes": [ - "sha256:453448b430ab4821178a5a5271bffece8163d4ca4e282a470f5700d55d26c697", - "sha256:b29687cd3a553d96d73c1fcbaa7551ff5b02a5503bdcd0fa1b1c96d18049d2c3" - ], - "markers": "python_version >= '3.5'", - "version": "==1.1.0" - }, "portalocker": { "hashes": [ "sha256:091364838ed6fbb68ea291c28982d1e56125c0d9e3fad5a4ac001db54dd862dc", @@ -2013,32 +1944,28 @@ "sha256:563d1a4140b63ff9dd587bda9557cffb2fe73650205ab6f4383092fb882e7dc8", "sha256:df7e9e63aea609b1da3a65641ceaf5bc7d05e0a04de5bd45d05dbeffbabf9e04" ], - "markers": "python_version >= '3.6.1'", "version": "==3.0.5" }, "protobuf": { "hashes": [ - "sha256:0bae429443cc4748be2aadfdaf9633297cfaeb24a9a02d0ab15849175ce90fab", - "sha256:24e3b6ad259544d717902777b33966a1a069208c885576254c112663e6a5bb0f", - "sha256:2affcaba328c4662f3bc3c0e9576ea107906b2c2b6422344cdad961734ff6b93", - "sha256:310a7aca6e7f257510d0c750364774034272538d51796ca31d42c3925d12a52a", - "sha256:52e586072612c1eec18e1174f8e3bb19d08f075fc2e3f91d3b16c919078469d0", - "sha256:73152776dc75f335c476d11d52ec6f0f6925774802cd48d6189f4d5d7fe753f4", - "sha256:7774bbbaac81d3ba86de646c39f154afc8156717972bf0450c9dbfa1dc8dbea2", - "sha256:82d7ac987715d8d1eb4068bf997f3053468e0ce0287e2729c30601feb6602fee", - "sha256:8eb9c93798b904f141d9de36a0ba9f9b73cc382869e67c9e642c0aba53b0fc07", - "sha256:adf0e4d57b33881d0c63bb11e7f9038f98ee0c3e334c221f0858f826e8fb0151", - "sha256:c40973a0aee65422d8cb4e7d7cbded95dfeee0199caab54d5ab25b63bce8135a", - "sha256:c77c974d1dadf246d789f6dad1c24426137c9091e930dbf50e0a29c1fcf00b1f", - "sha256:dd9aa4401c36785ea1b6fff0552c674bdd1b641319cb07ed1fe2392388e9b0d7", - "sha256:e11df1ac6905e81b815ab6fd518e79be0a58b5dc427a2cf7208980f30694b956", - "sha256:e2f8a75261c26b2f5f3442b0525d50fd79a71aeca04b5ec270fc123536188306", - "sha256:e512b7f3a4dd780f59f1bf22c302740e27b10b5c97e858a6061772668cd6f961", - "sha256:ef2c2e56aaf9ee914d3dccc3408d42661aaf7d9bb78eaa8f17b2e6282f214481", - "sha256:fac513a9dc2a74b99abd2e17109b53945e364649ca03d9f7a0b96aa8d1807d0a", - "sha256:fdfb6ad138dbbf92b5dbea3576d7c8ba7463173f7d2cb0ca1bd336ec88ddbd80" - ], - "version": "==3.11.3" + "sha256:00c2c276aca3af220d422e6a8625b1f5399c821c9b6f1c83e8a535aa8f48cc6c", + "sha256:0d69d76b00d0eb5124cb33a34a793383a5bbbf9ac3e633207c09988717c5da85", + "sha256:1c55277377dd35e508e9d86c67a545f6d8d242d792af487678eeb75c07974ee2", + "sha256:35bc1b96241b8ea66dbf386547ef2e042d73dcc0bf4b63566e3ef68722bb24d1", + "sha256:47a541ac44f2dcc8d49b615bcf3ed7ba4f33af9791118cecc3d17815fab652d9", + "sha256:61364bcd2d85277ab6155bb7c5267e6a64786a919f1a991e29eb536aa5330a3d", + "sha256:7aaa820d629f8a196763dd5ba21fd272fa038f775a845a52e21fa67862abcd35", + "sha256:9593a6cdfc491f2caf62adb1c03170e9e8748d0a69faa2b3970e39a92fbd05a2", + "sha256:95f035bbafec7dbaa0f1c72eda8108b763c1671fcb6e577e93da2d52eb47fbcf", + "sha256:9d6a517ce33cbdc64b52a17c56ce17b0b20679c945ed7420e7c6bc6686ff0494", + "sha256:a7532d971e4ab2019a9f6aa224b209756b6b9e702940ca85a4b1ed1d03f45396", + "sha256:b4e8ecb1eb3d011f0ccc13f8bb0a2d481aa05b733e6e22e9d46a3f61dbbef0de", + "sha256:bb1aced9dcebc46f0b320f24222cc8ffdfd2e47d2bafd4d2e5913cc6f7e3fc98", + "sha256:ccce142ebcfbc35643a5012cf398497eb18e8d021333cced4d5401f034a8cef5", + "sha256:d538eecc0b80accfb73c8167f39aaa167a5a50f31b1295244578c8eff8e9d602", + "sha256:eab18765eb5c7bad1b2de7ae3774192b46e1873011682e36bcd70ccf75f2748a" + ], + "version": "==3.12.0" }, "ptyprocess": { "hashes": [ @@ -2057,54 +1984,33 @@ }, "pyasn1-modules": { "hashes": [ - "sha256:0845a5582f6a02bb3e1bde9ecfc4bfcae6ec3210dd270522fee602365430c3f8", - "sha256:0fe1b68d1e486a1ed5473f1302bd991c1611d319bba158e98b106ff86e1d7199", - "sha256:15b7c67fabc7fc240d87fb9aabf999cf82311a6d6fb2c70d00d3d0604878c811", - "sha256:426edb7a5e8879f1ec54a1864f16b882c2837bfd06eee62f2c982315ee2473ed", - "sha256:65cebbaffc913f4fe9e4808735c95ea22d7a7775646ab690518c056784bc21b4", "sha256:905f84c712230b2c592c19470d3ca8d552de726050d1d1716282a1f6146be65e", - "sha256:a50b808ffeb97cb3601dd25981f6b016cbb3d31fbf57a8b8a87428e6158d0c74", - "sha256:a99324196732f53093a84c4369c996713eb8c89d360a496b599fb1a9c47fc3eb", - "sha256:b80486a6c77252ea3a3e9b1e360bc9cf28eaac41263d173c032581ad2f20fe45", - "sha256:c29a5e5cc7a3f05926aff34e097e84f8589cd790ce0ed41b67aed6857b26aafd", - "sha256:cbac4bc38d117f2a49aeedec4407d23e8866ea4ac27ff2cf7fb3e5b570df19e0", - "sha256:f39edd8c4ecaa4556e989147ebf219227e2cd2e8a43c7e7fcb1f1c18c5fd6a3d", - "sha256:fe0644d9ab041506b62782e92b06b8c68cca799e1a9636ec398675459e031405" + "sha256:a50b808ffeb97cb3601dd25981f6b016cbb3d31fbf57a8b8a87428e6158d0c74" ], "version": "==0.2.8" }, "pycocotools": { "git": "https://github.com/cocodataset/cocoapi.git", "ref": "8c9bcc3cf640524c4c20a9c40e89cb6a2f2fa0e9", - "subdirectory": "PythonAPI", - "version": "==2.0" + "subdirectory": "PythonAPI" }, "pycparser": { "hashes": [ "sha256:2d475327684562c3a96cc71adf7dc8c4f0565175cf86b6d7a404ff4c771f15f0", "sha256:7582ad22678f0fcd81102833f60ef8d0e57288b6b5fb00323d101be910e35705" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.20" }, "pycurl": { "hashes": [ "sha256:1957c867e2a341f5526c107c7bbc5014d6e75fdc2a14294fcb8a47663fbd2e15", - "sha256:404862665c4e2dbe814c9495d1193a65ae0f291a7074ae1ef1f0bffd93c14ea6", "sha256:50aee0469511a9708a1f1a50d510b5ec2013fc6f5e720c32bbcb3b9c7b0f45b1", "sha256:667db26516e50ce4a853745906f3b149c24756d85061b9d966eb7ec43a8c48a4", - "sha256:789a76e9265cdb7c947ec0afde2330492ccc0f2cee8e3ca8c0822082b6ae213e", "sha256:7cc13d3421cbd31921d77e22d1f57c0e1a8d0fb461938a587689a93162ccef2f", "sha256:a0c62dbc66b9b947832307d6cf7bdb5e4da906ce7b3efe6f74292e8f3dc5abe3", "sha256:a6966e8d9ccda31c6d077c4f8673aaa88141cc73d50e110e93e627b816d17fd1", - "sha256:b393aa90abf07ddd51d750c0c6a801155af07f938af6ec8b89ea00ff3f892887", - "sha256:b58e4d7888edd74dce40b9481962f0537dc77a44d99b5cc3385c3ffdaf2abf93", - "sha256:b6512b864466b242ffc3997e982d4590e035d056d37e63136fa137a4044ce2f1", - "sha256:b651f47c61c051ea93299b0e7a341860d33bfe2cf524237be0fb56399f026d98", "sha256:beadfa7f052626864d70eb33cec8f2aeece12dfb483c2424cc07b057f83b7d35", "sha256:c5c379c8cc777dda397f86f0d0049480250ae84a82a9d99d668f461d368fb39c", - "sha256:daa017e8dc887129e4a2cd88b7be8c431e434b89737348eaa12096026020756a", - "sha256:e1aea68b1d39dbcafc7298214f51f6ebd5f188c06aa418e9c046dfe419fe7ecf", "sha256:ec7dd291545842295b7b56c12c90ffad2976cc7070c98d7b1517b7b6cd5994b3" ], "index": "pypi", @@ -2112,44 +2018,37 @@ }, "pygame": { "hashes": [ - "sha256:026e835dc69ab50db3f62e01884dceeee25283c04f5dbe992f059e24c11e29b3", - "sha256:07d9f21e2aee6679bcff760b93d336ca0981000a5bb6e665708ea9f08e9c06f6", - "sha256:134be66f54e1d588d3198f308afed3d495e5e9c1b1c36ffe71efc0afd2057eaf", - "sha256:1b153b52e1d46f1e779ef773707d23f03d23f014819ad3a822c2e357adbeed78", - "sha256:33795983f9fdce22b6e934f62d813364dbbd8846de25500fb9328f2a0ea619f9", - "sha256:33b50c90559b944b466f1cd0181a3019f80f50783fe58f43369b078c0c7172ef", - "sha256:3438463f73cc3d413b8c30daf194b5471b565cd74e4cfe0379562af534d44f22", - "sha256:34b03b5c411b60e1dca096f0237a59521b5cab0d32b388c5b3a00c1d371a5266", - "sha256:46211c0e87486c70a272246087bb8c221f546f0a5d258e7e722372de3bbfb887", - "sha256:545da86be8ed0f9af19e636ecf1c6ed2d2851d64abed7f1a64e517abb2f3058b", - "sha256:54b55f9f2fcf80aaf8c8ce2fd465e1b5cac948ccbd5a1d74561e63a9d9abd5f5", - "sha256:56fb61d0dcd8dfe9d35f402ee417bc4bc96ea41a84525efb3cda5403f9e13bda", - "sha256:587a5d52ba71ea16b299dce672d8d986364c9a4b0640fef49351839fa14a5950", - "sha256:7183302b00706ed6a886fac9775fb7f44e7a96b60aab75c73473a763a19f62b8", - "sha256:72238e9681713e68576483c8e8d7ea63c1b3bf7ee0d316f60239c5132a5b1115", - "sha256:7a01dced9d7880b4107b0b7fe65fc427c8886f26f36e4ada6eec809259742767", - "sha256:7d56c36ea9a71edb2aacdf5f628d31a9ffbf4bde025b1c9b77f707e8400dd910", - "sha256:7f6f710e7fd07adafdda139d4d43f358da666db2544608eabf0a43b1fb5dc5a4", - "sha256:8be68d1ddbb7a21ae2df8bf9621b7f6cc6bb6a15a49e76e105bd7fe9d88b84b3", - "sha256:8cf102e4b7ff37e6303b310ec38585a153a31c1eed3b5ceeae0df6f01d35ae01", - "sha256:94b3bae28d5811c400673918a0dd656f6deeb691b3530f25ee367180c822dfbe", - "sha256:9d122c30c731226efab9d1454919bb6595275345754513017b5798378f748200", - "sha256:a2062458a8b3646a13a93dbd557b46f57d6fc884486d4f14b1cb232c4014c03c", - "sha256:a39205e3e0d30a35cdab72fd22808db561599cb95e7c73ca6a113b7273f15529", - "sha256:a6c4ebb9a8c5dfa5ad8547a78b34550c2968a1ab2fe0c29a5af2e71d53a1da6b", - "sha256:a7fcfd5fadc91828bb9b0f7a8699f6c7ae900131b095e79bb1c5ca211bf9acd5", - "sha256:a9389e8b5fe55b1a1b62ccbcf8df55907bbe0250536bf39c2686f6d40d6c3e5a", - "sha256:b82470b9719dcccd1e26db132af055d5dd2fedd347ba272cc3788bf4723314de", - "sha256:bd6aca8554745760b3aade96586272fd724438b20aaa2c7335ffb8bab293e852", - "sha256:c1c5043fdc10629debabadb21854d8ff9f5642103d61f02df71104a270c2d0cc", - "sha256:d8cd6bc002b1725da0937cb5e789cb71bee6b05de90b436a2448a47ac64c9196", - "sha256:db9332d5b6040c3c0c6eed54fcd75b6fd592a219734c7bfb1cc5ecced82f0683", - "sha256:dbddf8921a3b19cfa09ad35a6a02d82f545cacd6d8e5d1dc41e26a2a468e43e9", - "sha256:e649cda58ebc5480e83db0fa217751ea5e73b3bd556ff019319acdf9a381d67c", - "sha256:feb72207824d0e77fc5c13ade0f5c9207ce0e4d0b14aa30e7e0e16f61ec36b25" - ], - "index": "pypi", - "version": "==2.0.0.dev6" + "sha256:010c2e49f15de8ca24e15ce51df6911f5d0804f2c484bd9c67ffc8ed78e452f0", + "sha256:0267b4def5c07e3b08329f80cb51c8c457d514221f6a2d5ec175569bd02280c9", + "sha256:071f0e4d50a5af008a86d43236fc3dc0a903fc6dab1872b4282e1022e8b888b6", + "sha256:0b3b26f6ad21a651301acf48c48fdc541bd3dbbdeb214d82bbad5c9403ed71e8", + "sha256:10743ba4d4d07fb2437f7399fe65b99b99202b92899b0b8f085d3f97bdd408e0", + "sha256:10ea85a1a2a06de7e9ee4b52c391f574104017bdc8a5569d92a95d4b6e4df9cc", + "sha256:1361dbc180786f17fe399f632a0809881bbaa588c094a613a5d139f0a9f5bb17", + "sha256:1f648ee199a7359b8bdd9534fbbb6d046910ed821ca565d23083eb4e128b38ce", + "sha256:370202bbc33b5747986eee24f44e2e84d5fb18a48398ec944018c288e9298874", + "sha256:56eefff1c9c4338533673f4cb00c975b1a807d41b429a66ecd6e0cae274b99b2", + "sha256:660ab9e8dd960d312f0bd1b0b7b62d22891fb6e188ebd980cc78d57336d067d2", + "sha256:68c3a9224bb9e878f244aad9cd842ccef10e9c074c6284b61ec2fd9931e67def", + "sha256:71d629fae5b20a88cdbf541abc4f2025b823731ee73b8b2380d9c86160640d11", + "sha256:7df846da4d24e85a38240e1bcc1d5579d72e4a8b675b4bc77aad899cb8d53feb", + "sha256:7fd14b068e784b118b51eda271a8fc3bfe2b0c54b6146ac6e34f66858ac27834", + "sha256:8068af05b2a2fc9984e55ad05f9131ec767b2fc312df0f50972e88c4485f5d8e", + "sha256:83029fa1ad72bf07aa6a6c8e05cfc5d1a07c08c648d21dfb3176d38c8f0db3b4", + "sha256:842f8991ae60c93493d548b34da4d9c9523eaa066d5dc849273cec080f9b46b8", + "sha256:8a80cff2fd8818daec3b084b4caa5c5ecbe2a2460d9c10f96682350032c3b5fe", + "sha256:921d6565b40ff3da1e505efa1f75f0438214ca0d6b413e19a481fb52bff1ca7a", + "sha256:96bc63d8e56998f079d1d92e077213935f3dea800300912e4176c2a300135e13", + "sha256:b47875c58b507b74361cecd0083411e0b19ae15dff7da45e104da86d8a1fefcb", + "sha256:bdeb5399d90d352a393c2461ff19f2d627c602706be7ea1415021b4862ce720d", + "sha256:d72e3a583b081058107e5157b706cc409b3afdae892f560481ef298fd4154a29", + "sha256:d76183fa2a6070006d0f8e95fb707edface752564248f63267bdd98464b55feb", + "sha256:e63c0d05c384337b3354e6368769204f0b965b092d167f55eea26e13e97208d8", + "sha256:ecad810029f8058712ae649588fc0b2faaf0746be84aa225de285b2a000aba8f", + "sha256:f6d0ea74b97a487e1f491c75386d494ecd573851af4e08090eacfa707ba43428" + ], + "index": "pypi", + "version": "==2.0.0.dev8" }, "pygments": { "hashes": [ @@ -2223,12 +2122,10 @@ "sha256:a60756d55f0887023b3899e6c2923ba5f0042fb11b1d17810b4e07395404f33e", "sha256:a676bd2fbc2309092b9bbb0083d35718b5420af3a42135ebb1e4c3633f56604d", "sha256:a732838c78554c1257ff2492f5c8c4c7312d0aecd7f732149e255f3749edd5ee", - "sha256:ad3dc88dfe61f0f1f9b99c6bc833ea2f45203a937a18f0d2faa57c6952656012", "sha256:ae65d65fde4135ef423a2608587c9ef585a3551fc2e4e431e7c7e527047581be", "sha256:b070a4f064a9edb70f921bfdc270725cff7a78c22036dd37a767c51393fb956f", "sha256:b6da85949aa91e9f8c521681344bd2e163de894a5492337fba8b05c409225a4f", "sha256:bbf47110765b2a999803a7de457567389253f8670f7daafb98e059c899ce9764", - "sha256:bd9c1e6f92b4888ae3ef7ae23262c513b962f09f3fb3b48581dde5df7d7a860a", "sha256:c06b3f998d2d7160db58db69adfb807d2ec307e883e2f17f6b87a1ef6c723f11", "sha256:c318fb70542be16d3d4063cde6010b1e4d328993a793529c15a619251f517c39", "sha256:c4aef42e5fa4c9d5a99f751fb79caa880dac7eaf8a65121549318b984676a1b7", @@ -2238,7 +2135,6 @@ "sha256:e2b46e092ea54b732d98c476720386ff2ccd126de1e52076b470b117bff7e409", "sha256:e334c4f39a2863a239d38b5829e442a87f241a92da9941861ee6ec5d6380b7fe", "sha256:e5c54f04ca42bbb5153aec5d4f2e3d9f81e316945220ac318abd4083308143f5", - "sha256:f4d06764a06b137e48db6d569dc95614d9d225c89842c885669ee8abc9f28c7a", "sha256:f96333f9d2517c752c20a35ff95de5fc2763ac8cdb1653df0f6f45d281620606" ], "index": "pypi", @@ -2246,11 +2142,11 @@ }, "pymysql": { "hashes": [ - "sha256:95f057328357e0e13a30e67857a8c694878b0175797a9a203ee7adbfb9b1ec5f", - "sha256:9ec760cbb251c158c19d6c88c17ca00a8632bac713890e465b2be01fdc30713f" + "sha256:3943fbbbc1e902f41daf7f9165519f140c4451c179380677e6a848587042561a", + "sha256:d8c059dcd81dedb85a9f034d5e22dcb4442c0b201908bede99e306d65ea7c8e7" ], "index": "pypi", - "version": "==0.9.2" + "version": "==0.9.3" }, "pynacl": { "hashes": [ @@ -2298,7 +2194,6 @@ "sha256:c203ec8783bf771a155b207279b9bccb8dea02d8f0c9e5f8ead507bc3246ecc1", "sha256:ef9d7589ef3c200abe66653d3f1ab1033c3c419ae9b9bdb1240a85b024efc88b" ], - "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.4.7" }, "pyprof2calltree": { @@ -2411,7 +2306,6 @@ "sha256:d510aef84d9852653d079c84f2f81a82d5d09815e625f35c95714e7364570ad4", "sha256:e02a0558e0c2ac8b8bbe6a6ac18c136767ec56b96a321e0dfde2173adfa5a504" ], - "markers": "python_version >= '3.5'", "version": "==1.1.1" }, "pyyaml": { @@ -2467,10 +2361,10 @@ }, "qtconsole": { "hashes": [ - "sha256:8f5ae5571f0e921db9f2d12613ed667c350ee22c7db598d9bbbe143e8533f932", - "sha256:e7882df6e95ec710b5893ec3a7ebfd54e410e63d801e4bbf8c785d74758c2329" + "sha256:89442727940126c65c2f94a058f1b4693a0f5d4c4b192fd6518ba3b11f4791aa", + "sha256:fd48bf1051d6e69cec1f9e2596cfaa94e3c726c70c5d848681ebce10c029f5fd" ], - "version": "==4.7.3" + "version": "==4.7.4" }, "qtpy": { "hashes": [ @@ -2481,11 +2375,11 @@ }, "redis": { "hashes": [ - "sha256:6e9d2722a95d10ddf854596e66516d316d99c6a483e5db3b35c34e1158b2bfa1", - "sha256:a5b0e25890d216d8189636742c50ab992e42eea699bcc1b08cc2d6bf3adff52a" + "sha256:2ef11f489003f151777c064c5dbc6653dfb9f3eade159bcadc524619fddc2242", + "sha256:6d65e84bc58091140081ee9d9c187aab0480097750fac44239307a3bdf0b1251" ], "index": "pypi", - "version": "==3.5.1" + "version": "==3.5.2" }, "requests": { "hashes": [ @@ -2498,8 +2392,7 @@ "requests-oauthlib": { "hashes": [ "sha256:7f71572defaecd16372f9006f33c2ec8c077c3cfa6f5911a9a90202beb513f3d", - "sha256:b4261601a71fd721a8bd6d7aa1cc1d6a8a93b4a9f5e96626f8e4d91e8beeaa6a", - "sha256:fa6c47b933f01060936d87ae9327fead68768b69c6c9ea2109c48be30f2d4dbc" + "sha256:b4261601a71fd721a8bd6d7aa1cc1d6a8a93b4a9f5e96626f8e4d91e8beeaa6a" ], "version": "==1.3.0" }, @@ -2534,22 +2427,22 @@ }, "scikit-image": { "hashes": [ - "sha256:11bcc65ca2927c1842212b37ab64fe589a3eb6de375ea09cea0d7cd99bbde418", - "sha256:1247803e7afad51b4257fc6e7187eb4da63c8d8d2d51888baaca818b3a814ca9", - "sha256:1e2e2cf2572549bdb20b88a0f0ac275eea9f04f78b2b6973afdc3f329a73c75c", - "sha256:45629ef09d96739a575136fa28a8fd0b709d132325a140cdc8c8375df180c456", - "sha256:9cb106875c11236e4b1a04725c86745e2d65b32887cd2febbd0061c88491181b", - "sha256:a5d5d38842eaeb8feaa8427fb76240208feefc8d1b0afe109999a5458fe07455", - "sha256:a5f0c923ebac6e53286c07df79141e236cc161a463ea4a9edf4042a9db495e7b", - "sha256:acd5e9176e1fbc2ed869cc781b128471ffd3e1e60b267ffc532230c4dc2808df", - "sha256:bec5ea27cd975cbdcd1688c8631852f578e63bd26a4645dd03ed6f596fe2fc24", - "sha256:d402c947b9af4e42c875e4b80bad26c8aced87b791931d6ca020dc509ec7e108", - "sha256:d42c6b87e25905e867c4038a08ef790ba1ac7764a1830a4bb89955d159e69ff4", - "sha256:f4cd4464792d744c6f4c1cf7f0aea9945ea7664eaf5124f783703a1df80560f5", - "sha256:ff9521c170b4f8081825e675879f2cbd14f4a7572111fad8fc2c6ec82ba705f3" + "sha256:113bcacdfc839854f527a166a71768708328208e7b66e491050d6a57fa6727c7", + "sha256:11eec2e65cd4cd6487fe1089aa3538dbe25525aec7a36f5a0f14145df0163ce7", + "sha256:178210582cc62a5b25c633966658f1f2598615f9c3f27f36cf45055d2a74b401", + "sha256:1fda9109a19dc9d7a4ac152d1fc226fed7282ad186a099f14c0aa9151f0c758e", + "sha256:6b65a103edbc34b22640daf3b084dc9e470c358d3298c10aa9e3b424dcc02db6", + "sha256:7bedd3881ca4fea657a894815bcd5e5bf80944c26274f6b6417bb770c3f4f8e6", + "sha256:86a834f9a4d30201c0803a48a25364fe8f93f9feb3c58f2c483d3ce0a3e5fe4a", + "sha256:87ca5168c6fc36b7a298a1db2d185a8298f549854342020f282f747a4e4ddce9", + "sha256:bd954c0588f0f7e81d9763dc95e06950e68247d540476e06cb77bcbcd8c2d8b3", + "sha256:c0876e562991b0babff989ff4d00f35067a2ddef82e5fdd895862555ffbaec25", + "sha256:c5c277704b12e702e34d1f7b7a04d5ee8418735f535d269c74c02c6c9f8abee2", + "sha256:e99fa7514320011b250a21ab855fdd61ddcc05d3c77ec9e8f13edcc15d3296b5", + "sha256:ee3db438b5b9f8716a91ab26a61377a8a63356b186706f5b979822cc7241006d" ], "index": "pypi", - "version": "==0.17.1" + "version": "==0.17.2" }, "scipy": { "hashes": [ @@ -2623,29 +2516,17 @@ "sha256:0fe3994207485efb63d8f10a833ff31236ed27e3b23dadd0bf51c9900313f8f2", "sha256:17163e643dbf125bb552de17c826b0161c68c970335d270e174363d19e7ea882", "sha256:1d1e929cdd15151f3c0b2efe953b3281b2fd5ad5f234f77aca725f28486466f6", - "sha256:1d346c2c1d7dd79c118f0cc7ec5a1c4127e0c8ffc83e7b13fc5709ff78c9bb84", "sha256:1ea59f570b9d4916ae5540a9181f9c978e16863383738b69a70363bc5e63c4cb", - "sha256:1fbba86098bbfc1f85c5b69dc9a6d009055104354e0d9880bb00b692e30e0078", - "sha256:229edb079d5dd81bf12da952d4d825bd68d1241381b37d3acf961b384c9934de", "sha256:22a7acb81968a7c64eba7526af2cf566e7e2ded1cb5c83f0906b17ff1540f866", "sha256:2b4b2b738b3b99819a17feaf118265d0753d5536049ea570b3c43b51c4701e81", "sha256:4cf91aab51b02b3327c9d51897960c554f00891f9b31abd8a2f50fd4a0071ce8", - "sha256:4fd5f79590694ebff8dc980708e1c182d41ce1fda599a12189f0ca96bf41ad70", - "sha256:5cfd495527f8b85ce21db806567de52d98f5078a8e9427b18e251c68bd573a26", - "sha256:60aad424e47c5803276e332b2a861ed7a0d46560e8af53790c4c4fb3420c26c2", - "sha256:7739940d68b200877a15a5ff5149e1599737d6dd55e302625650629350466418", "sha256:7cce4bac7e0d66f3a080b80212c2238e063211fe327f98d764c6acbc214497fc", "sha256:8027bd5f1e633eb61b8239994e6fc3aba0346e76294beac22a892eb8faa92ba1", "sha256:86afc5b5cbd42d706efd33f280fec7bd7e2772ef54e3f34cf6b30777cd19a614", "sha256:87d349517b572964350cc1adc5a31b493bbcee284505e81637d0174b2758ba17", - "sha256:8de378d589eccbc75941e480b4d5b4db66f22e4232f87543b136b1f093fff342", "sha256:926bcbef9eb60e798eabda9cd0bbcb0fca70d2779aa0aa56845749d973eb7ad5", "sha256:9a126c3a91df5b1403e965ba63b304a50b53d8efc908a8c71545ed72535374a3", - "sha256:ad8dd3454d0c65c0f92945ac86f7b9efb67fa2040ba1b0189540e984df904378", - "sha256:d140e9376e7f73c1f9e0a8e3836caf5eec57bbafd99259d56979da05a6356388", - "sha256:da00675e5e483ead345429d4f1374ab8b949fba4429d60e71ee9d030ced64037", "sha256:daaf4d11db982791be74b23ff4729af2c7da79316de0bebf880fa2d60bcc8c5a", - "sha256:f4b64a1031acf33e281fd9052336d6dad4d35eee3404c95431c8c6bc7a9c0588", "sha256:fc046afda0ed8f5295212068266c92991ab1f4a50c6a7144b69364bdee4a0159", "sha256:fc9051d249dd5512e541f20330a74592f7a65b2d62e18122ca89bf71f94db748" ], @@ -2662,28 +2543,37 @@ }, "sqlalchemy": { "hashes": [ - "sha256:083e383a1dca8384d0ea6378bd182d83c600ed4ff4ec8247d3b2442cf70db1ad", - "sha256:0a690a6486658d03cc6a73536d46e796b6570ac1f8a7ec133f9e28c448b69828", - "sha256:114b6ace30001f056e944cebd46daef38fdb41ebb98f5e5940241a03ed6cad43", - "sha256:128f6179325f7597a46403dde0bf148478f868df44841348dfc8d158e00db1f9", - "sha256:13d48cd8b925b6893a4e59b2dfb3e59a5204fd8c98289aad353af78bd214db49", - "sha256:211a1ce7e825f7142121144bac76f53ac28b12172716a710f4bf3eab477e730b", - "sha256:2dc57ee80b76813759cccd1a7affedf9c4dbe5b065a91fb6092c9d8151d66078", - "sha256:3e625e283eecc15aee5b1ef77203bfb542563fa4a9aa622c7643c7b55438ff49", - "sha256:43078c7ec0457387c79b8d52fff90a7ad352ca4c7aa841c366238c3e2cf52fdf", - "sha256:5b1bf3c2c2dca738235ce08079783ef04f1a7fc5b21cf24adaae77f2da4e73c3", - "sha256:6056b671aeda3fc451382e52ab8a753c0d5f66ef2a5ccc8fa5ba7abd20988b4d", - "sha256:68d78cf4a9dfade2e6cf57c4be19f7b82ed66e67dacf93b32bb390c9bed12749", - "sha256:7025c639ce7e170db845e94006cf5f404e243e6fc00d6c86fa19e8ad8d411880", - "sha256:7224e126c00b8178dfd227bc337ba5e754b197a3867d33b9f30dc0208f773d70", - "sha256:7d98e0785c4cd7ae30b4a451416db71f5724a1839025544b4edbd92e00b91f0f", - "sha256:8d8c21e9d4efef01351bf28513648ceb988031be4159745a7ad1b3e28c8ff68a", - "sha256:bbb545da054e6297242a1bb1ba88e7a8ffb679f518258d66798ec712b82e4e07", - "sha256:d00b393f05dbd4ecd65c989b7f5a81110eae4baea7a6a4cdd94c20a908d1456e", - "sha256:e18752cecaef61031252ca72031d4d6247b3212ebb84748fc5d1a0d2029c23ea" - ], - "index": "pypi", - "version": "==1.3.16" + "sha256:128bc917ed20d78143a45024455ff0aed7d3b96772eba13d5dbaf9cc57e5c41b", + "sha256:156a27548ba4e1fed944ff9fcdc150633e61d350d673ae7baaf6c25c04ac1f71", + "sha256:27e2efc8f77661c9af2681755974205e7462f1ae126f498f4fe12a8b24761d15", + "sha256:2a12f8be25b9ea3d1d5b165202181f2b7da4b3395289000284e5bb86154ce87c", + "sha256:31c043d5211aa0e0773821fcc318eb5cbe2ec916dfbc4c6eea0c5188971988eb", + "sha256:65eb3b03229f684af0cf0ad3bcc771970c1260a82a791a8d07bffb63d8c95bcc", + "sha256:6cd157ce74a911325e164441ff2d9b4e244659a25b3146310518d83202f15f7a", + "sha256:703c002277f0fbc3c04d0ae4989a174753a7554b2963c584ce2ec0cddcf2bc53", + "sha256:869bbb637de58ab0a912b7f20e9192132f9fbc47fc6b5111cd1e0f6cdf5cf9b0", + "sha256:8a0e0cd21da047ea10267c37caf12add400a92f0620c8bc09e4a6531a765d6d7", + "sha256:8d01e949a5d22e5c4800d59b50617c56125fc187fbeb8fa423e99858546de616", + "sha256:925b4fe5e7c03ed76912b75a9a41dfd682d59c0be43bce88d3b27f7f5ba028fb", + "sha256:9cb1819008f0225a7c066cac8bb0cf90847b2c4a6eb9ebb7431dbd00c56c06c5", + "sha256:a87d496884f40c94c85a647c385f4fd5887941d2609f71043e2b73f2436d9c65", + "sha256:a9030cd30caf848a13a192c5e45367e3c6f363726569a56e75dc1151ee26d859", + "sha256:a9e75e49a0f1583eee0ce93270232b8e7bb4b1edc89cc70b07600d525aef4f43", + "sha256:b50f45d0e82b4562f59f0e0ca511f65e412f2a97d790eea5f60e34e5f1aabc9a", + "sha256:b7878e59ec31f12d54b3797689402ee3b5cfcb5598f2ebf26491732758751908", + "sha256:ce1ddaadee913543ff0154021d31b134551f63428065168e756d90bdc4c686f5", + "sha256:ce2646e4c0807f3461be0653502bb48c6e91a5171d6e450367082c79e12868bf", + "sha256:ce6c3d18b2a8ce364013d47b9cad71db815df31d55918403f8db7d890c9d07ae", + "sha256:e4e2664232005bd306f878b0f167a31f944a07c4de0152c444f8c61bbe3cfb38", + "sha256:e8aa395482728de8bdcca9cc0faf3765ab483e81e01923aaa736b42f0294f570", + "sha256:eb4fcf7105bf071c71068c6eee47499ab8d4b8f5a11fc35147c934f0faa60f23", + "sha256:ed375a79f06cad285166e5be74745df1ed6845c5624aafadec4b7a29c25866ef", + "sha256:f35248f7e0d63b234a109dd72fbfb4b5cb6cb6840b221d0df0ecbf54ab087654", + "sha256:f502ef245c492b391e0e23e94cba030ab91722dcc56963c85bfd7f3441ea2bbe", + "sha256:fe01bac7226499aedf472c62fa3b85b2c619365f3f14dd222ffe4f3aa91e5f98" + ], + "index": "pypi", + "version": "==1.3.17" }, "subprocess32": { "hashes": [ @@ -2712,7 +2602,6 @@ "hashes": [ "sha256:9a2a2dc9856187679e93f3c95e5dc771dd47e3257db09767b4be118d734b4dc2" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.2.1" }, "tensorboard-plugin-wit": { @@ -2722,24 +2611,28 @@ ], "version": "==1.6.0.post3" }, - "tensorflow-estimator": { + "tensorflow": { "hashes": [ - "sha256:d09dacdd127f2579cea8d5af21f4a918036b8ae246adc82f26b61f91cc247dc2" + "sha256:267017724a49c367ca5df536e5f6d3d59643eaed946c82233d6b371e62b5ddc8", + "sha256:3ee8819732d8594913b7d22ded7b22e48a49aa015050d8dd8464eaa010ba2e41", + "sha256:572f69d2d0a3d3d83ebfb2c24e6d73d88b85a09f5da796974ef4a0ad83ff7cde", + "sha256:6735486ee9c3cb0807476e2b36ef7a4cd6c597cb24abf496e66b703360e1e54e", + "sha256:68ea22aee9c269a6a0c1061c141f1ec1cd1b1be7569390519c1bf4773f434a40", + "sha256:784ab8217e4b0eb4d121c28430c6cdc2ce56c02634a9720d84fb30598b338b8c", + "sha256:7ed67b47cdf6598a79583de5b57c595493eac2b8b6b3a828f912354716cb8149", + "sha256:8f364528f70d895b96a0de36c7c6002644bf4c5df1ee3fbfa775f5cee6571ad7", + "sha256:bbcfb04738099bd46822db91584db74703fdddacf4cd0a76acfc5e086956b5ba", + "sha256:c332c7fc5cfd54cb86d5da99787c9693e3a924848097c54df1b71ee595a39c93", + "sha256:dc5548562308acde7931f040e73d46ae31b398924cf675c3486fd3504e00a4af", + "sha256:f5f27528570fc0d7b90668be10c5dfd90d6ceb8fd2ed62d7d679554acb616bfe" ], + "index": "pypi", "version": "==2.2.0" }, - "tensorflow-gpu": { + "tensorflow-estimator": { "hashes": [ - "sha256:3cd3fa2b13a505902704a63d6b2f256cdc85ddfd6c70dc7093796b7e490d09c4", - "sha256:453f0e3d8e56c47f4b374fba17cb5e0b57afbe34cd17f565b5498b5a0ccf33ac", - "sha256:4c698dc157ba74aa69fc7bb41669f4f34f63f07bd722dd3b5aea33458a660066", - "sha256:5853b595cf82f803d3dddc9b9c00996a514dcfc831d2f899f0bb8073795f6301", - "sha256:845f261b0b922740bdd7f21fa3a4bed8ffd9e1712decd552fb33621da4d8ec45", - "sha256:b706f0ed98d3c216ad65272c3a08a92f6fe7e38f57b54d3f9b5800043600e215", - "sha256:ba1e16249cf9aa4057d0af443df493f8a1683be113703f6d7f184f144ac673e4", - "sha256:f0b37fc5847987c1ca4f453273667497782a8920716a804f66247e0c095fef38" + "sha256:d09dacdd127f2579cea8d5af21f4a918036b8ae246adc82f26b61f91cc247dc2" ], - "index": "pypi", "version": "==2.2.0" }, "termcolor": { @@ -2753,7 +2646,6 @@ "sha256:4804a774f802306a7d9af7322193c5390f1da0abb429e082a10ef1d46e6fb2c2", "sha256:a43dcb3e353bc680dd0783b1d9c3fc28d529f190bc54ba9a229f72fe6e7a54d7" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.8.3" }, "testpath": { @@ -2768,16 +2660,14 @@ "sha256:2e110ea3a6381df534261a85091490a5678faa4535aa14cc11b8ea8379dcbf01", "sha256:abfce379f2b4b97759796c1489ea0e73c349fc71bf09bea2a5d076cbe7cfd4eb" ], - "markers": "python_version >= '3.6'", "version": "==2020.5.11" }, "toml": { "hashes": [ - "sha256:229f81c57791a41d65e399fc06bf0848bab550a9dfd5ed66df18ce5f05e73d5c", - "sha256:235682dd292d5899d361a811df37e04a8828a5b1da3115886b73cf81ebc9100e", - "sha256:f1db651f9657708513243e61e6cc67d101a39bad662eaa9b5546f789338e07a3" + "sha256:926b612be1e5ce0634a2ca03470f95169cf16f939018233a670519cb4ac58b0f", + "sha256:bda89d5935c2eac546d648028b9901107a595863cb36bae0c73ac804a9b4ce88" ], - "version": "==0.10.0" + "version": "==0.10.1" }, "tornado": { "hashes": [ @@ -2791,7 +2681,6 @@ "sha256:c952975c8ba74f546ae6de2e226ab3cc3cc11ae47baf607459a6728585bb542a", "sha256:c98232a3ac391f5faea6821b53db8db461157baa788f5d6222a193e9456e1740" ], - "markers": "python_version >= '3.5'", "version": "==6.0.4" }, "traitlets": { @@ -2828,7 +2717,6 @@ "sha256:2de2a5db0baeae7b2d2664949077c2ac63fbd16d98da0ff71837f7d1dea3fd43", "sha256:6c80b1e5ad3665290ea39320b91e1be1e0d5f60652b964a3070216de83d2e47c" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.0.1" }, "wheel": { @@ -2872,7 +2760,6 @@ "sha256:d8cdee92bc930d8b09d8bd2043cedd544d9c8bd7436a77678dd602467a993080", "sha256:e15199cdb423316e15f108f51249e44eb156ae5dba232cb73be555324a1d49c2" ], - "markers": "python_version >= '3.5'", "version": "==1.4.2" } } From 3f8afe593f14a4a6f94ddb9c2f1aed1419d2f69a Mon Sep 17 00:00:00 2001 From: Ewout ter Hoeven Date: Wed, 20 May 2020 22:17:54 +0200 Subject: [PATCH 056/656] Pip: Move from tensorflow-gpu to tensorflow package (#1530) * Pip: Move from tensorflow-gpu to tensorflow package Since tensorflow 2.1 the regular tensorflow package contains GPU support and replaces the tensorflow-gpu package, which will be depreceated at some point. * Readme: Update Tensorflow version * Update Pipfile.lock Co-authored-by: Willem Melching --- tools/ubuntu_setup.sh | 2 +- tools/webcam/README.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/ubuntu_setup.sh b/tools/ubuntu_setup.sh index 27e9d6d78e..9f09279d34 100755 --- a/tools/ubuntu_setup.sh +++ b/tools/ubuntu_setup.sh @@ -89,7 +89,7 @@ pipenv install --system --deploy pip install -r tools/requirements.txt # to make modeld work on PC with nvidia GPU -pip install tensorflow-gpu==2.2 +pip install tensorflow==2.2 # for loggerd to work on ubuntu # TODO: PC should log somewhere else diff --git a/tools/webcam/README.md b/tools/webcam/README.md index 89f1ac3a62..74676f35a7 100644 --- a/tools/webcam/README.md +++ b/tools/webcam/README.md @@ -17,7 +17,7 @@ git clone https://github.com/commaai/openpilot.git ``` - Follow [this readme](https://github.com/commaai/openpilot/tree/master/tools) to install the requirements - Add line "export PYTHONPATH=$HOME/openpilot" to your ~/.bashrc -- You also need to install tensorflow-gpu 2.1.0 (if not working, try 2.0.0) and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 +- You also need to install tensorflow 2.2 and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 - Install [OpenCL Driver](http://registrationcenter-download.intel.com/akdlm/irc_nas/12556/opencl_runtime_16.1.2_x64_rh_6.4.0.37.tgz) - (Note: the code assumes cl platforms order to be 0.GPU/1.CPU when running clinfo; if reverse, change the -1 to -2 in selfdrive/modeld/modeld.cc#L130; helping us refactor this mess is encouraged) - Install [OpenCV4](https://www.pyimagesearch.com/2018/08/15/how-to-install-opencv-4-on-ubuntu/) (ignore the Python part) From b8cc31f888d4301b7db59ff9419db9215868a3f7 Mon Sep 17 00:00:00 2001 From: openpilot laptop Date: Wed, 20 May 2020 14:07:04 -0700 Subject: [PATCH 057/656] Add single fw requests for hyundai ECUs not supporting multi requests --- selfdrive/car/fw_versions.py | 20 ++++++++++++++++++-- selfdrive/car/hyundai/values.py | 9 +++++---- 2 files changed, 23 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 0522b862f8..b3ed4eb788 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -39,12 +39,18 @@ UDS_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) -HYUNDAI_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ +HYUNDAI_VERSION_REQUEST_SHORT = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf1a0) # 4 Byte version number +HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf100) # 4 Byte version number +HYUNDAI_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + \ + p16(0xf100) + \ p16(0xf1a0) # 4 Byte version number HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + TOYOTA_VERSION_REQUEST = b'\x1a\x88\x01' TOYOTA_VERSION_RESPONSE = b'\x5a\x88\x01' @@ -57,7 +63,17 @@ REQUESTS = [ # Hundai ( "hyundai", - [HYUNDAI_VERSION_REQUEST], + [HYUNDAI_VERSION_REQUEST_SHORT], + [HYUNDAI_VERSION_RESPONSE], + ), + ( + "hyundai", + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + ), + ( + "hyundai", + [HYUNDAI_VERSION_REQUEST_MULTI], [HYUNDAI_VERSION_RESPONSE], ), # Honda diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 1887ab5b5e..2921a1f167 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -137,11 +137,12 @@ ECU_FINGERPRINT = { FW_VERSIONS = { CAR.SONATA: { - (Ecu.esp, 0x7d1, None): [b'\xf1\x8758910-L0100\xf1\xa01.04'], + (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 '], + (Ecu.esp, 0x7d1, None): [b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100\xf1\xa01.04'], (Ecu.engine, 0x7e0, None): [b'\xf1\x87391162M003\xf1\xa0000F'], - (Ecu.eps, 0x7d4, None): [b'\xf1\x8756310L0010\x00\xf1\xa01.01'], - (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x8799110L0000\xf1\xa01.00'], - (Ecu.transmission, 0x7e1, None): [b'\xf1\x87SALFBA4195874GJ2EVugvf\x86hgwvwww\x87wgw\x86wc_\xfb\xff\x98\x88\x8f\xff\xe23\xf1\x81U903\x00\x00\x00\x00\x00\x00'], + (Ecu.eps, 0x7d4, None): [b'\xf1\x8756310L0010\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101\xf1\xa01.01'], + (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016'], + (Ecu.transmission, 0x7e1, None): [b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v'], } } From 68ef23f97b7530e4eab54b79508c1d4a393f65ab Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 20 May 2020 14:10:55 -0700 Subject: [PATCH 058/656] Fixup comments --- selfdrive/car/fw_versions.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index b3ed4eb788..673b16942c 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -42,12 +42,12 @@ UDS_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) HYUNDAI_VERSION_REQUEST_SHORT = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ p16(0xf1a0) # 4 Byte version number HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf100) # 4 Byte version number + p16(0xf100) # Long description HYUNDAI_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + \ p16(0xf100) + \ - p16(0xf1a0) # 4 Byte version number + p16(0xf1a0) HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) From 8f3e932f96dbd6c6c27a74644bc5d1abbb166898 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 20 May 2020 14:18:28 -0700 Subject: [PATCH 059/656] Locationd fixes --- selfdrive/locationd/locationd.py | 24 +++++++++++++++--------- 1 file changed, 15 insertions(+), 9 deletions(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index e6a3e38c13..6b4928872a 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -21,6 +21,7 @@ from sympy.utilities.lambdify import lambdify from rednose.helpers.sympy_helpers import euler_rotate +OUTPUT_DECIMATION = 2 VISION_DECIMATION = 2 SENSOR_DECIMATION = 10 @@ -61,6 +62,9 @@ class Localizer(): self.posenet_speed = 0 self.car_speed = 0 + self.converter = coord.LocalCoord.from_ecef(self.kf.x[States.ECEF_POS]) + self.unix_timestamp_millis = 0 + @staticmethod def msg_from_state(converter, calib_from_device, H, predicted_state, predicted_cov): predicted_std = np.sqrt(np.diagonal(predicted_cov)) @@ -271,15 +275,15 @@ class Localizer(): self.speed_counter = 0 self.cam_counter = 0 - def locationd_thread(sm, pm, disabled_logs=[]): if sm is None: socks = ['gpsLocationExternal', 'sensorEvents', 'cameraOdometry', 'liveCalibration', 'carState'] - sm = messaging.SubMaster(socks) + sm = messaging.SubMaster(socks, ignore_alive=['gpsLocationExternal']) if pm is None: pm = messaging.PubMaster(['liveLocationKalman']) localizer = Localizer(disabled_logs=disabled_logs) + camera_odometry_cnt = 0 while True: sm.update() @@ -298,15 +302,17 @@ def locationd_thread(sm, pm, disabled_logs=[]): elif sock == "liveCalibration": localizer.handle_live_calib(t, sm[sock]) - if sm.updated['gpsLocationExternal']: - t = sm.logMonoTime['gpsLocationExternal'] - msg = messaging.new_message('liveLocationKalman') - msg.logMonoTime = t + if sm.updated['cameraOdometry']: + camera_odometry_cnt += 1 - msg.liveLocationKalman = localizer.liveLocationMsg(t * 1e-9) - msg.liveLocationKalman.inputsOK = sm.all_alive_and_valid() + if camera_odometry_cnt % OUTPUT_DECIMATION == 0: + t = sm.logMonoTime['cameraOdometry'] + msg = messaging.new_message('liveLocationKalman') + msg.logMonoTime = t - pm.send('liveLocationKalman', msg) + msg.liveLocationKalman = localizer.liveLocationMsg(t * 1e-9) + msg.liveLocationKalman.inputsOK = sm.all_alive_and_valid() + pm.send('liveLocationKalman', msg) def main(sm=None, pm=None): From 5870b48210628592e5bde01ef767fb109815b6a5 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 20 May 2020 14:23:57 -0700 Subject: [PATCH 060/656] Locationd actually runs in jenkins now. Give more cpu allowance --- common/manager_helpers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/manager_helpers.py b/common/manager_helpers.py index e5ae067035..4aaf4dd213 100644 --- a/common/manager_helpers.py +++ b/common/manager_helpers.py @@ -12,7 +12,7 @@ def print_cpu_usage(first_proc, last_proc): ("selfdrive.controls.radard", 9.54), ("./_ui", 9.54), ("./camerad", 7.07), - ("selfdrive.locationd.locationd", 13.96), + ("selfdrive.locationd.locationd", 27.46), ("./_sensord", 6.17), ("selfdrive.controls.dmonitoringd", 5.48), ("./boardd", 3.63), From fde1a5e9af1c1e84ed6f82b642a50bae21f25bbe Mon Sep 17 00:00:00 2001 From: Alice Knag Date: Wed, 20 May 2020 18:12:00 -0600 Subject: [PATCH 061/656] add support for Sonata 2019 (#1538) * add sonata interface update values.py update values.py * change sonata_1 to sonata_2019 * add sonata 2019 and forte 2019 to README prettier fucked me up pretty hard at first sdfsd * update README.md * mock test --- README.md | 4 ++-- selfdrive/car/hyundai/interface.py | 7 +++++++ selfdrive/car/hyundai/values.py | 7 ++++++- selfdrive/test/test_car_models.py | 1 + 4 files changed, 16 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 58ef0535f1..4f653b45a3 100644 --- a/README.md +++ b/README.md @@ -146,10 +146,10 @@ Community Maintained Cars and Features | Hyundai | Kona 2019 EV2 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Palisade 20202 | All | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | -| Hyundai | Sonata 2020 | All | Stock | 0mph | 0mph | +| Hyundai | Sonata 2019-20 | All | Stock | 0mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019 | Adaptive Cruise | Stock | 0mph | 39mph | -| Kia | Forte 20182 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Forte 2018-192 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Optima 20172 | SCC + LKAS/LDWS | Stock | 0mph | 32mph | | Kia | Optima 20192 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Sorento 20182 | SCC + LKAS | Stock | 0mph | 0mph | diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 183ab7eed1..a45706e6dd 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -43,6 +43,13 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + elif candidate == CAR.SONATA_2019: + ret.lateralTuning.pid.kf = 0.00005 + ret.mass = 4497. * CV.LB_TO_KG + ret.wheelbase = 2.804 + ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.PALISADE: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1999. + STD_CARGO_KG diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 2921a1f167..fdcfd7e7a1 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -30,6 +30,7 @@ class CAR: SANTA_FE = "HYUNDAI SANTA FE LIMITED 2019" SANTA_FE_1 = "HYUNDAI SANTA FE has no scc" SONATA = "HYUNDAI SONATA 2020" + SONATA_2019 = "HYUNDAI SONATA 2019" PALISADE = "HYUNDAI PALISADE 2020" @@ -79,6 +80,9 @@ FINGERPRINTS = { CAR.SONATA: [ {67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 549: 8, 550: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 8, 865: 8, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 908: 8, 909: 8, 912: 7, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1089: 5, 1107: 5, 1108: 8, 1114: 8, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1184: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1268: 8, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1330: 8, 1339: 8, 1342: 6, 1343: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1394: 8, 1407: 8, 1419: 8, 1427: 6, 1446: 8, 1456: 4, 1460: 8, 1470: 8, 1485: 8, 1504: 3}, ], + CAR.SONATA_2019: [ + {66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1397: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2008: 8, 2009: 8, 2012: 8, 2013: 8, 2014: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8}, + ], CAR.KIA_OPTIMA: [ { 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1186: 2, 1191: 2, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 1952: 8, 1960: 8, 1988: 8, 1996: 8, 2001: 8, 2004: 8, 2008: 8, 2009: 8, 2012: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 @@ -153,7 +157,7 @@ CHECKSUM = { FEATURES = { "use_cluster_gears": [CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30], # Use Cluster for Gear Selection, rather than Transmission - "use_tcu_gears": [CAR.KIA_OPTIMA], # Use TCU Message for Gear Selection + "use_tcu_gears": [CAR.KIA_OPTIMA, CAR.SONATA_2019], # Use TCU Message for Gear Selection "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV], # Use TCU Message for Gear Selection } @@ -174,6 +178,7 @@ DBC = { CAR.KONA_EV: dbc_dict('hyundai_kia_generic', None), CAR.SANTA_FE: dbc_dict('hyundai_kia_generic', None), CAR.SONATA: dbc_dict('hyundai_kia_generic', None), + CAR.SONATA_2019: dbc_dict('hyundai_kia_generic', None), CAR.PALISADE: dbc_dict('hyundai_kia_generic', None), } diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index ae47496e6d..69e673fc37 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -390,6 +390,7 @@ non_tested_cars = [ HYUNDAI.KIA_STINGER, HYUNDAI.KONA, HYUNDAI.KONA_EV, + HYUNDAI.SONATA_2019, TOYOTA.CAMRYH, TOYOTA.CHR, TOYOTA.CHRH, From ef2ea14ecce0133b5596074712162931cbaebdc3 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 20 May 2020 17:20:17 -0700 Subject: [PATCH 062/656] add sonata 2019 to test_car_modelsg --- selfdrive/test/test_car_models.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 69e673fc37..cd98a4d903 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -181,6 +181,10 @@ routes = { 'carFingerprint': HYUNDAI.SONATA, 'enableCamera': True, }, + "b2a38c712dcf90bd|2020-05-18--18-12-48": { + 'carFingerprint': HYUNDAI.SONATA_2019, + 'enableCamera': True, + }, "9c917ba0d42ffe78|2020-04-17--12-43-19": { 'carFingerprint': HYUNDAI.PALISADE, 'enableCamera': True, @@ -390,7 +394,6 @@ non_tested_cars = [ HYUNDAI.KIA_STINGER, HYUNDAI.KONA, HYUNDAI.KONA_EV, - HYUNDAI.SONATA_2019, TOYOTA.CAMRYH, TOYOTA.CHR, TOYOTA.CHRH, From 7ffaff029f8b6d770809e601d748ec6ccb55b928 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 20 May 2020 19:21:03 -0700 Subject: [PATCH 063/656] Calib in settings (#1543) * test test * yo dawg * yo dawg 2 * yo dawg 3 * calib in ui * no pitch and yaw * no more drive rating * stricter * param is no longer a vp * less wall of test * less is more * better language * cleaner --- apk/ai.comma.plus.offroad.apk | 4 ++-- selfdrive/locationd/calibrationd.py | 14 +++++--------- 2 files changed, 7 insertions(+), 11 deletions(-) diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk index 8a59c2b227..35f9cb672f 100644 --- a/apk/ai.comma.plus.offroad.apk +++ b/apk/ai.comma.plus.offroad.apk @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:d7b79038dccaa97d84bd38544573d3a52929770b76a259b25a27311464230e22 -size 13732809 +oid sha256:695622033fe2a531a2e263f5a0d19ee1fee8aadbad781092f71a3448bddd48d5 +size 13699616 diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index e7836c05ca..7d8e440b84 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -24,9 +24,8 @@ INPUTS_WANTED = 50 # We want a little bit more than we need for stability WRITE_CYCLES = 10 # write every 1000 cycles VP_INIT = np.array([W/2., H/2.]) -# These validity corners were chosen by looking at 1000 -# and taking most extreme cases with some margin. -VP_VALIDITY_CORNERS = np.array([[W//2 - 120, 300], [W//2 + 120, 520]]) +# These values are needed to accomodate biggest modelframe +VP_VALIDITY_CORNERS = np.array([[W//2 - 63, 300], [W//2 + 63, 520]]) DEBUG = os.getenv("DEBUG") is not None @@ -38,8 +37,8 @@ def is_calibration_valid(vp): def sanity_clip(vp): if np.isnan(vp).any(): vp = VP_INIT - return np.array([np.clip(vp[0], VP_VALIDITY_CORNERS[0,0] - 20, VP_VALIDITY_CORNERS[1,0] + 20), - np.clip(vp[1], VP_VALIDITY_CORNERS[0,1] - 20, VP_VALIDITY_CORNERS[1,1] + 20)]) + return np.array([np.clip(vp[0], VP_VALIDITY_CORNERS[0,0] - 5, VP_VALIDITY_CORNERS[1,0] + 5), + np.clip(vp[1], VP_VALIDITY_CORNERS[0,1] - 5, VP_VALIDITY_CORNERS[1,1] + 5)]) def intrinsics_from_vp(vp): @@ -69,10 +68,7 @@ class Calibrator(): if calibration_params: try: calibration_params = json.loads(calibration_params) - if 'calib_radians' in calibration_params: - self.vp = vp_from_rpy(calibration_params["calib_radians"]) - else: - self.vp = np.array(calibration_params["vanishing_point"]) + self.vp = vp_from_rpy(calibration_params["calib_radians"]) if not np.isfinite(self.vp).all(): self.vp = copy.copy(VP_INIT) self.vps = np.tile(self.vp, (INPUTS_WANTED, 1)) From 95e1dec8b8c1a7fa232ec080281b83e92c798e82 Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Wed, 20 May 2020 19:41:56 -0700 Subject: [PATCH 064/656] remove external/opencl/ --- external/opencl/intel-opencl-devel_0r3.1-58621_amd64.deb | 3 --- external/opencl/intel.icd | 1 - external/opencl/opencl-1.2-base-pset_6.4.0.37-2_all.deb | 3 --- external/opencl/opencl-1.2-base_6.4.0.37-2_amd64.deb | 3 --- external/opencl/opencl-1.2-intel-cpu_6.4.0.37-2_amd64.deb | 3 --- 5 files changed, 13 deletions(-) delete mode 100644 external/opencl/intel-opencl-devel_0r3.1-58621_amd64.deb delete mode 100644 external/opencl/intel.icd delete mode 100644 external/opencl/opencl-1.2-base-pset_6.4.0.37-2_all.deb delete mode 100644 external/opencl/opencl-1.2-base_6.4.0.37-2_amd64.deb delete mode 100644 external/opencl/opencl-1.2-intel-cpu_6.4.0.37-2_amd64.deb diff --git a/external/opencl/intel-opencl-devel_0r3.1-58621_amd64.deb b/external/opencl/intel-opencl-devel_0r3.1-58621_amd64.deb deleted file mode 100644 index 52cd5b3a72..0000000000 --- a/external/opencl/intel-opencl-devel_0r3.1-58621_amd64.deb +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:e3c75edadf2e267be8a18870cafc911ea23d3b52dcff07fbe025edf815c06f5d -size 68732 diff --git a/external/opencl/intel.icd b/external/opencl/intel.icd deleted file mode 100644 index b31f24d7bc..0000000000 --- a/external/opencl/intel.icd +++ /dev/null @@ -1 +0,0 @@ -/opt/intel/opencl-1.2-6.4.0.37/lib64/libintelocl.so diff --git a/external/opencl/opencl-1.2-base-pset_6.4.0.37-2_all.deb b/external/opencl/opencl-1.2-base-pset_6.4.0.37-2_all.deb deleted file mode 100644 index a3c7fba5f4..0000000000 --- a/external/opencl/opencl-1.2-base-pset_6.4.0.37-2_all.deb +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:381814ea42344b895624597bf31c24ebc13f3449aaaaf65245f4a041d953b4c6 -size 17276236 diff --git a/external/opencl/opencl-1.2-base_6.4.0.37-2_amd64.deb b/external/opencl/opencl-1.2-base_6.4.0.37-2_amd64.deb deleted file mode 100644 index feff0b9705..0000000000 --- a/external/opencl/opencl-1.2-base_6.4.0.37-2_amd64.deb +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:25aaa33f5c338b6dcc33436fdebb5e6ad727cf85a9fae921be8d3b834166ab01 -size 11432 diff --git a/external/opencl/opencl-1.2-intel-cpu_6.4.0.37-2_amd64.deb b/external/opencl/opencl-1.2-intel-cpu_6.4.0.37-2_amd64.deb deleted file mode 100644 index dd17f9b0b6..0000000000 --- a/external/opencl/opencl-1.2-intel-cpu_6.4.0.37-2_amd64.deb +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f7300ebee63820b519c54a50c93847516dcaf37765a698826fde666990747459 -size 20290860 From 260e6aff53f5f579298f81e1d3a01a0e1d6dc7fb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 21 May 2020 09:59:39 -0700 Subject: [PATCH 065/656] fix possible FileNotFoundError --- selfdrive/controls/controlsd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 18aa2c7b28..d2cc2b8669 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -76,7 +76,7 @@ class Controls: internet_needed or not openpilot_enabled_toggle # detect sound card presence and ensure successful init - sounds_available = not os.path.isfile('/EON') or (os.path.isdir('/proc/asound/card0') \ + sounds_available = not os.path.isfile('/EON') or (os.path.isdir('/proc/asound/card0/state') \ and open('/proc/asound/card0/state').read().strip() == 'ONLINE') car_recognized = self.CP.carName != 'mock' From 2d89f3c6d995e958bd521e185b4603e7977d3dfa Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Thu, 21 May 2020 22:03:30 +0300 Subject: [PATCH 066/656] update OpenCL Driver 16.1 > 18.1 (#1524) --- tools/webcam/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/webcam/README.md b/tools/webcam/README.md index 74676f35a7..f03f811b35 100644 --- a/tools/webcam/README.md +++ b/tools/webcam/README.md @@ -18,7 +18,7 @@ git clone https://github.com/commaai/openpilot.git - Follow [this readme](https://github.com/commaai/openpilot/tree/master/tools) to install the requirements - Add line "export PYTHONPATH=$HOME/openpilot" to your ~/.bashrc - You also need to install tensorflow 2.2 and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 -- Install [OpenCL Driver](http://registrationcenter-download.intel.com/akdlm/irc_nas/12556/opencl_runtime_16.1.2_x64_rh_6.4.0.37.tgz) +- Install [OpenCL Driver](http://registrationcenter-download.intel.com/akdlm/irc_nas/vcp/15532/l_opencl_p_18.1.0.015.tgz) - (Note: the code assumes cl platforms order to be 0.GPU/1.CPU when running clinfo; if reverse, change the -1 to -2 in selfdrive/modeld/modeld.cc#L130; helping us refactor this mess is encouraged) - Install [OpenCV4](https://www.pyimagesearch.com/2018/08/15/how-to-install-opencv-4-on-ubuntu/) (ignore the Python part) From b01abfa9cb9506bfe74866d2ff26831ee53c6fce Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 21 May 2020 13:58:08 -0700 Subject: [PATCH 067/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 01cdf832c8..30838d40a4 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 01cdf832c8f164adf7a975b9e29c66c4b04bdc83 +Subproject commit 30838d40a42bf3335e8168d66ae4c50f4f5b1cbe From 517826c1e1263f0445c125a002223906b73538a8 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 21 May 2020 14:43:07 -0700 Subject: [PATCH 068/656] Add percent sign to calibration screen --- selfdrive/controls/lib/events.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 512d0044bd..4693f0c9cc 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -170,7 +170,7 @@ def calibration_incomplete_alert(CP, sm, metric): speed = int(Filter.MIN_SPEED * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH)) unit = "kph" if metric else "mph" return Alert( - "Calibration in Progress: %d" % sm['liveCalibration'].calPerc, + "Calibration in Progress: %d%%" % sm['liveCalibration'].calPerc, "Drive Above %d %s" % (speed, unit), AlertStatus.normal, AlertSize.mid, Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2) From 41da10ff38abfb29c42e66250344176da14e2f65 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 21 May 2020 14:46:18 -0700 Subject: [PATCH 069/656] Sounds available isdir -> isfile --- selfdrive/controls/controlsd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index d2cc2b8669..cb7bca7f53 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -76,7 +76,7 @@ class Controls: internet_needed or not openpilot_enabled_toggle # detect sound card presence and ensure successful init - sounds_available = not os.path.isfile('/EON') or (os.path.isdir('/proc/asound/card0/state') \ + sounds_available = not os.path.isfile('/EON') or (os.path.isfile('/proc/asound/card0/state') \ and open('/proc/asound/card0/state').read().strip() == 'ONLINE') car_recognized = self.CP.carName != 'mock' From 0abf99dbe01cfe87617bb293c8eb047d93f709dd Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 21 May 2020 14:53:40 -0700 Subject: [PATCH 070/656] Add permanent CAN error alert --- selfdrive/controls/lib/events.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 4693f0c9cc..0202119337 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -607,6 +607,11 @@ EVENTS = { EventName.canError: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("CAN Error: Check Connections"), ET.NO_ENTRY: NoEntryAlert("CAN Error: Check Connections"), + ET.PERMANENT: Alert( + "CAN Error: Check Connections", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), }, EventName.steerUnavailable: { From 5f0ae7d26eb0ebbfb258ab005c99c79404bc9af5 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 21 May 2020 15:06:58 -0700 Subject: [PATCH 071/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 30838d40a4..4bb1eb826d 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 30838d40a42bf3335e8168d66ae4c50f4f5b1cbe +Subproject commit 4bb1eb826d319237f42791c4ac20ad719cba7524 From e6f24f239041da4dc0d889492f8fbcfda111cd7b Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 21 May 2020 15:30:16 -0700 Subject: [PATCH 072/656] Revert "Add permanent CAN error alert" This reverts commit 0abf99dbe01cfe87617bb293c8eb047d93f709dd. --- selfdrive/controls/lib/events.py | 5 ----- 1 file changed, 5 deletions(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 0202119337..4693f0c9cc 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -607,11 +607,6 @@ EVENTS = { EventName.canError: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("CAN Error: Check Connections"), ET.NO_ENTRY: NoEntryAlert("CAN Error: Check Connections"), - ET.PERMANENT: Alert( - "CAN Error: Check Connections", - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), }, EventName.steerUnavailable: { From ab5af232b243ba8137695f68c125f922fb412d44 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 21 May 2020 16:04:33 -0700 Subject: [PATCH 073/656] Use C++ version of SubMaster and PubMaster (#1548) * add PubMaster & SubMaster remove 'delete msg' remove headers * use constructor to initial all submster * modify drain sockets * fix typo in ssconscript.remove lines no checkValid in loggerd last modify handle_message:event->&event fix type remove heads event to auto * new interface * api changed * Revert "use constructor to initial all submster" This reverts commit 73be7ea46250a325ce41d3a0445e34395a2ae692. * change to new api * revert loggerd * dd * use new PubSub api * update to new interface don't modify loggerd reset panda reset opendbc remove empty lines * switch to new pubMaster * update to the new inteface change remove error code . to -> merge paramsd.cc update panda fix typo simplify fix typo * Fix build * always conflate Co-authored-by: deanlee --- selfdrive/boardd/SConscript | 4 +- selfdrive/boardd/boardd.cc | 159 +++++----------- selfdrive/camerad/SConscript | 4 +- .../camerad/cameras/camera_frame_stream.cc | 21 +-- selfdrive/camerad/main.cc | 98 +++------- selfdrive/clocksd/SConscript | 4 +- selfdrive/clocksd/clocksd.cc | 13 +- selfdrive/locationd/SConscript | 4 +- selfdrive/locationd/paramsd.cc | 127 +++++-------- selfdrive/locationd/ublox_msg.cc | 6 - selfdrive/locationd/ubloxd.cc | 4 - selfdrive/locationd/ubloxd_main.cc | 49 ++--- selfdrive/locationd/ubloxd_test.cc | 4 - selfdrive/logcatd/SConscript | 4 +- selfdrive/logcatd/logcatd.cc | 15 +- selfdrive/loggerd/SConscript | 4 +- selfdrive/loggerd/loggerd.cc | 3 - selfdrive/modeld/SConscript | 4 +- selfdrive/modeld/dmonitoringmodeld.cc | 25 +-- selfdrive/modeld/modeld.cc | 93 +++------- selfdrive/modeld/models/dmonitoring.cc | 7 +- selfdrive/modeld/models/dmonitoring.h | 4 +- selfdrive/modeld/models/driving.cc | 16 +- selfdrive/modeld/models/driving.h | 6 +- selfdrive/proclogd/SConscript | 4 +- selfdrive/proclogd/proclogd.cc | 17 +- selfdrive/sensord/SConscript | 6 +- selfdrive/sensord/gpsd.cc | 27 +-- selfdrive/sensord/sensors.cc | 19 +- selfdrive/ui/ui.cc | 172 ++++++------------ selfdrive/ui/ui.hpp | 23 +-- 31 files changed, 266 insertions(+), 680 deletions(-) diff --git a/selfdrive/boardd/SConscript b/selfdrive/boardd/SConscript index 14c1ff780d..d7e575d064 100644 --- a/selfdrive/boardd/SConscript +++ b/selfdrive/boardd/SConscript @@ -1,6 +1,6 @@ -Import('env', 'common', 'messaging') +Import('env', 'common', 'cereal', 'messaging') -env.Program('boardd.cc', LIBS=['usb-1.0', common, messaging, 'pthread', 'zmq', 'capnp', 'kj']) +env.Program('boardd.cc', LIBS=['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj']) env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) env.Command(['boardd_api_impl.so'], diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index d5990bc1d8..b1f17a4bc1 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -2,7 +2,6 @@ #include #include #include -#include #include #include #include @@ -16,8 +15,6 @@ #include -#include -#include "cereal/gen/cpp/log.capnp.h" #include "cereal/gen/cpp/car.capnp.h" #include "common/util.h" @@ -281,7 +278,7 @@ void handle_usb_issue(int err, const char func[]) { // TODO: check other errors, is simply retrying okay? } -void can_recv(PubSocket *publisher) { +void can_recv(PubMaster &pm) { int err; uint32_t data[RECV_SIZE/4]; int recv; @@ -333,13 +330,10 @@ void can_recv(PubSocket *publisher) { canData[i].setSrc((data[i*4+1] >> 4) & 0xff); } - // send to can - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - publisher->send((char*)bytes.begin(), bytes.size()); + pm.send("can", msg); } -void can_health(PubSocket *publisher) { +void can_health(PubMaster &pm) { int cnt; int err; @@ -384,10 +378,7 @@ void can_health(PubSocket *publisher) { // No panda connected, send empty health packet if (!received){ healthData.setHwType(cereal::HealthData::HwType::UNKNOWN); - - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - publisher->send((char*)bytes.begin(), bytes.size()); + pm.send("health", msg); return; } @@ -532,9 +523,7 @@ void can_health(PubSocket *publisher) { } } // send to health - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - publisher->send((char*)bytes.begin(), bytes.size()); + pm.send("health", msg); // send heartbeat back to panda pthread_mutex_lock(&usb_lock); @@ -543,20 +532,11 @@ void can_health(PubSocket *publisher) { } -void can_send(SubSocket *subscriber) { +void can_send(cereal::Event::Reader &event) { int err; - // recv from sendcan - Message * msg = subscriber->receive(); - - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); if (nanos_since_boot() - event.getLogMonoTime() > 1e9) { //Older than 1 second. Dont send. - delete msg; return; } int msg_count = event.getSendcan().size(); @@ -578,14 +558,10 @@ void can_send(SubSocket *subscriber) { memcpy(&send[i*4+2], cmsg.getDat().begin(), cmsg.getDat().size()); } - // release msg - delete msg; - // send to board int sent; pthread_mutex_lock(&usb_lock); - if (!fake_send) { do { // Try sending can messages. If the receive buffer on the panda is full it will NAK @@ -611,29 +587,17 @@ void can_send(SubSocket *subscriber) { void *can_send_thread(void *crap) { LOGD("start send thread"); - - // sendcan = 8017 - Context * context = Context::create(); - SubSocket * subscriber = SubSocket::create(context, "sendcan"); - assert(subscriber != NULL); - + SubMaster sm({"sendcan"}); // drain sendcan to delete any stale messages from previous runs - while (true){ - Message * msg = subscriber->receive(true); - if (msg == NULL){ - break; - } - delete msg; - } - + sm.drain(); // run as fast as messages come in while (!do_exit) { - can_send(subscriber); + if (sm.update(1000) > 0){ + can_send(sm["sendcan"]); + } } - delete subscriber; - delete context; return NULL; } @@ -641,16 +605,14 @@ void *can_recv_thread(void *crap) { LOGD("start recv thread"); // can = 8006 - Context * c = Context::create(); - PubSocket * publisher = PubSocket::create(c, "can"); - assert(publisher != NULL); + PubMaster pm({"can"}); // run at 100hz const uint64_t dt = 10000000ULL; uint64_t next_frame_time = nanos_since_boot() + dt; while (!do_exit) { - can_recv(publisher); + can_recv(pm); uint64_t cur_time = nanos_since_boot(); int64_t remaining = next_frame_time - cur_time; @@ -664,39 +626,26 @@ void *can_recv_thread(void *crap) { next_frame_time += dt; } - - delete publisher; - delete c; return NULL; } void *can_health_thread(void *crap) { LOGD("start health thread"); // health = 8011 - Context * c = Context::create(); - PubSocket * publisher = PubSocket::create(c, "health"); - assert(publisher != NULL); + PubMaster pm({"health"}); // run at 2hz while (!do_exit) { - can_health(publisher); + can_health(pm); usleep(500*1000); } - delete publisher; - delete c; return NULL; } void *hardware_control_thread(void *crap) { LOGD("start hardware control thread"); - Context * c = Context::create(); - SubSocket * thermal_sock = SubSocket::create(c, "thermal"); - SubSocket * front_frame_sock = SubSocket::create(c, "frontFrame"); - assert(thermal_sock != NULL); - assert(front_frame_sock != NULL); - - Poller * poller = Poller::create({thermal_sock, front_frame_sock}); + SubMaster sm({"thermal", "frontFrame"}); // Wait for hardware type to be set. while (hw_type == cereal::HealthData::HwType::UNKNOWN){ @@ -714,42 +663,30 @@ void *hardware_control_thread(void *crap) { while (!do_exit) { cnt++; - for (auto sock : poller->poll(1000)){ - Message * msg = sock->receive(); - if (msg == NULL) continue; - - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); - - delete msg; - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); - - auto type = event.which(); - if(type == cereal::Event::THERMAL){ - uint16_t fan_speed = event.getThermal().getFanSpeed(); - if (fan_speed != prev_fan_speed || cnt % 100 == 0){ - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0x40, 0xb1, fan_speed, 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); - - prev_fan_speed = fan_speed; - } - } else if (type == cereal::Event::FRONT_FRAME){ - float cur_front_gain = event.getFrontFrame().getGainFrac(); - last_front_frame_t = event.getLogMonoTime(); - - if (cur_front_gain <= CUTOFF_GAIN) { - ir_pwr = 100.0 * MIN_IR_POWER; - } else if (cur_front_gain > SATURATE_GAIN) { - ir_pwr = 100.0 * MAX_IR_POWER; - } else { - ir_pwr = 100.0 * (MIN_IR_POWER + ((cur_front_gain - CUTOFF_GAIN) * (MAX_IR_POWER - MIN_IR_POWER) / (SATURATE_GAIN - CUTOFF_GAIN))); - } + sm.update(1000); + if (sm.updated("thermal")){ + uint16_t fan_speed = sm["thermal"].getThermal().getFanSpeed(); + if (fan_speed != prev_fan_speed || cnt % 100 == 0){ + pthread_mutex_lock(&usb_lock); + libusb_control_transfer(dev_handle, 0x40, 0xb1, fan_speed, 0, NULL, 0, TIMEOUT); + pthread_mutex_unlock(&usb_lock); + + prev_fan_speed = fan_speed; + } + } + if (sm.updated("frontFrame")){ + auto event = sm["frontFrame"]; + float cur_front_gain = event.getFrontFrame().getGainFrac(); + last_front_frame_t = event.getLogMonoTime(); + + if (cur_front_gain <= CUTOFF_GAIN) { + ir_pwr = 100.0 * MIN_IR_POWER; + } else if (cur_front_gain > SATURATE_GAIN) { + ir_pwr = 100.0 * MAX_IR_POWER; + } else { + ir_pwr = 100.0 * (MIN_IR_POWER + ((cur_front_gain - CUTOFF_GAIN) * (MAX_IR_POWER - MIN_IR_POWER) / (SATURATE_GAIN - CUTOFF_GAIN))); } } - // Disable ir_pwr on front frame timeout uint64_t cur_t = nanos_since_boot(); if (cur_t - last_front_frame_t > 1e9){ @@ -765,10 +702,6 @@ void *hardware_control_thread(void *crap) { } - delete poller; - delete thermal_sock; - delete c; - return NULL; } @@ -865,7 +798,7 @@ void pigeon_init() { LOGW("panda GPS on"); } -static void pigeon_publish_raw(PubSocket *publisher, unsigned char *dat, int alen) { +static void pigeon_publish_raw(PubMaster &pm, unsigned char *dat, int alen) { // create message capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); @@ -873,18 +806,13 @@ static void pigeon_publish_raw(PubSocket *publisher, unsigned char *dat, int ale auto ublox_raw = event.initUbloxRaw(alen); memcpy(ublox_raw.begin(), dat, alen); - // send to ubloxRaw - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - publisher->send((char*)bytes.begin(), bytes.size()); + pm.send("ubloxRaw", msg); } void *pigeon_thread(void *crap) { // ubloxRaw = 8042 - Context * context = Context::create(); - PubSocket * publisher = PubSocket::create(context, "ubloxRaw"); - assert(publisher != NULL); + PubMaster pm({"ubloxRaw"}); // run at ~100hz unsigned char dat[0x1000]; @@ -910,7 +838,7 @@ void *pigeon_thread(void *crap) { LOGW("received invalid ublox message, resetting panda GPS"); pigeon_init(); } else { - pigeon_publish_raw(publisher, dat, alen); + pigeon_publish_raw(pm, dat, alen); } } @@ -918,9 +846,6 @@ void *pigeon_thread(void *crap) { usleep(10*1000); cnt++; } - - delete publisher; - delete context; return NULL; } diff --git a/selfdrive/camerad/SConscript b/selfdrive/camerad/SConscript index e1930a83f9..618df342c8 100644 --- a/selfdrive/camerad/SConscript +++ b/selfdrive/camerad/SConscript @@ -1,6 +1,6 @@ -Import('env', 'arch', 'messaging', 'common', 'gpucommon', 'visionipc', 'cereal', 'webcam') +Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'webcam') -libs = ['m', 'pthread', common, 'jpeg', cereal, 'OpenCL', messaging, 'czmq', 'zmq', 'capnp', 'kj', visionipc, gpucommon] +libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', cereal, messaging, 'czmq', 'zmq', 'capnp', 'kj', visionipc, gpucommon] if arch == "aarch64": libs += ['gsl', 'CB', 'adreno_utils', 'EGL', 'GLESv3', 'cutils', 'ui'] diff --git a/selfdrive/camerad/cameras/camera_frame_stream.cc b/selfdrive/camerad/cameras/camera_frame_stream.cc index 0061fe6185..37045f4378 100644 --- a/selfdrive/camerad/cameras/camera_frame_stream.cc +++ b/selfdrive/camerad/cameras/camera_frame_stream.cc @@ -1,15 +1,11 @@ #include "camera_frame_stream.h" -#include #include -#include #include #include #include #include -#include -#include "cereal/gen/cpp/log.capnp.h" #include "messaging.hpp" #include "common/util.h" @@ -53,22 +49,15 @@ void camera_init(CameraState *s, int camera_id, unsigned int fps) { void run_frame_stream(DualCameraState *s) { int err; - Context * context = Context::create(); - SubSocket * recorder_sock = SubSocket::create(context, "frame"); - assert(recorder_sock != NULL); + SubMaster sm({"frame"}); CameraState *const rear_camera = &s->rear; auto *tb = &rear_camera->camera_tb; while (!do_exit) { - Message * msg = recorder_sock->receive(); + if (sm.update(1000) == 0) continue; - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); - auto frame = event.getFrame(); + auto frame = sm["frame"].getFrame(); const int buf_idx = tbuffer_select(tb); rear_camera->camera_bufs_metadata[buf_idx] = { @@ -94,11 +83,7 @@ void run_frame_stream(DualCameraState *s) { clWaitForEvents(1, &map_event); clReleaseEvent(map_event); tbuffer_dispatch(tb, buf_idx); - delete msg; - } - delete recorder_sock; - delete context; } } // namespace diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index 286978016c..f914989ead 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -29,9 +29,7 @@ #include #include -#include #include -#include "cereal/gen/cpp/log.capnp.h" #define UI_BUF_COUNT 4 #define YUV_COUNT 40 @@ -143,10 +141,7 @@ struct VisionState { zsock_t *terminate_pub; - Context * msg_context; - PubSocket *frame_sock; - PubSocket *front_frame_sock; - PubSocket *thumbnail_sock; + PubMaster *pm; pthread_mutex_t clients_lock; VisionClientState clients[MAX_CLIENTS]; @@ -158,16 +153,9 @@ void* frontview_thread(void *arg) { VisionState *s = (VisionState*)arg; set_thread_name("frontview"); - - s->msg_context = Context::create(); - // we subscribe to this for placement of the AE metering box // TODO: the loop is bad, ideally models shouldn't affect sensors - Context *msg_context = Context::create(); - SubSocket *monitoring_sock = SubSocket::create(msg_context, "driverState", "127.0.0.1", true); - SubSocket *dmonstate_sock = SubSocket::create(msg_context, "dMonitoringState", "127.0.0.1", true); - assert(monitoring_sock != NULL); - assert(dmonstate_sock != NULL); + SubMaster sm({"driverState", "dMonitoringState"}); cl_command_queue q = clCreateCommandQueue(s->context, s->device_id, 0, &err); assert(err == 0); @@ -211,54 +199,34 @@ void* frontview_thread(void *arg) { tbuffer_release(&s->cameras.front.camera_tb, buf_idx); visionbuf_sync(&s->rgb_front_bufs[ui_idx], VISIONBUF_SYNC_FROM_DEVICE); + sm.update(0); // no more check after gps check - if (!s->rhd_front_checked) { - Message *msg_dmon = dmonstate_sock->receive(true); - if (msg_dmon != NULL) { - auto amsg = kj::heapArray((msg_dmon->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg_dmon->getData(), msg_dmon->getSize()); - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); - - s->rhd_front = event.getDMonitoringState().getIsRHD(); - s->rhd_front_checked = event.getDMonitoringState().getRhdChecked(); - - delete msg_dmon; - } + if (!s->rhd_front_checked && sm.updated("dMonitoringState")) { + auto state = sm["dMonitoringState"].getDMonitoringState(); + s->rhd_front = state.getIsRHD(); + s->rhd_front_checked = state.getRhdChecked(); } - Message *msg = monitoring_sock->receive(true); - if (msg != NULL) { - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); - - float face_prob = event.getDriverState().getFaceProb(); + if (sm.updated("driverState")) { + auto state = sm["driverState"].getDriverState(); + float face_prob = state.getFaceProb(); float face_position[2]; - face_position[0] = event.getDriverState().getFacePosition()[0]; - face_position[1] = event.getDriverState().getFacePosition()[1]; + face_position[0] = state.getFacePosition()[0]; + face_position[1] = state.getFacePosition()[1]; // set front camera metering target - if (face_prob > 0.4) - { + if (face_prob > 0.4) { int x_offset = s->rhd_front ? 0:s->rgb_front_width - 0.5 * s->rgb_front_height; s->front_meteringbox_xmin = x_offset + (face_position[0] + 0.5) * (0.5 * s->rgb_front_height) - 72; s->front_meteringbox_xmax = x_offset + (face_position[0] + 0.5) * (0.5 * s->rgb_front_height) + 72; s->front_meteringbox_ymin = (face_position[1] + 0.5) * (s->rgb_front_height) - 72; s->front_meteringbox_ymax = (face_position[1] + 0.5) * (s->rgb_front_height) + 72; - } - else // use default setting if no face - { + } else {// use default setting if no face s->front_meteringbox_ymin = s->rgb_front_height * 1 / 3; s->front_meteringbox_ymax = s->rgb_front_height * 1; s->front_meteringbox_xmin = s->rhd_front ? 0:s->rgb_front_width * 3 / 5; s->front_meteringbox_xmax = s->rhd_front ? s->rgb_front_width * 2 / 5:s->rgb_front_width; } - - delete msg; } // auto exposure @@ -330,7 +298,7 @@ void* frontview_thread(void *arg) { // send frame event { - if (s->front_frame_sock != NULL) { + if (s->pm != NULL) { capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); event.setLogMonoTime(nanos_since_boot()); @@ -349,9 +317,7 @@ void* frontview_thread(void *arg) { framed.setGainFrac(frame_data.gain_frac); framed.setFrameType(cereal::FrameData::FrameType::FRONT); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - s->front_frame_sock->send((char*)bytes.begin(), bytes.size()); + s->pm->send("frontFrame", msg); } } @@ -367,9 +333,6 @@ void* frontview_thread(void *arg) { //LOGD("front process: %.2fms", t2-t1); } - delete monitoring_sock; - delete dmonstate_sock; - return NULL; } // processing @@ -534,7 +497,7 @@ void* processing_thread(void *arg) { // send frame event { - if (s->frame_sock != NULL) { + if (s->pm != NULL) { capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); event.setLogMonoTime(nanos_since_boot()); @@ -570,9 +533,7 @@ void* processing_thread(void *arg) { kj::ArrayPtr transform_vs(&s->yuv_transform.v[0], 9); framed.setTransform(transform_vs); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - s->frame_sock->send((char*)bytes.begin(), bytes.size()); + s->pm->send("frame", msg); } } @@ -633,10 +594,8 @@ void* processing_thread(void *arg) { thumbnaild.setTimestampEof(frame_data.timestamp_eof); thumbnaild.setThumbnail(kj::arrayPtr((const uint8_t*)thumbnail_buffer, thumbnail_len)); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - if (s->thumbnail_sock != NULL) { - s->thumbnail_sock->send((char*)bytes.begin(), bytes.size()); + if (s->pm != NULL) { + s->pm->send("thumbnail", msg); } free(thumbnail_buffer); @@ -1103,7 +1062,7 @@ void init_buffers(VisionState *s) { s->rgb_front_width = s->cameras.front.ci.frame_width; s->rgb_front_height = s->cameras.front.ci.frame_height; } - + for (int i=0; irgb_front_width, s->rgb_front_height, &s->rgb_front_bufs[i]); @@ -1171,7 +1130,7 @@ void init_buffers(VisionState *s) { assert(err == 0); } - s->prg_rgb_laplacian = build_conv_program(s, s->rgb_width/NUM_SEGMENTS_X, s->rgb_height/NUM_SEGMENTS_Y, + s->prg_rgb_laplacian = build_conv_program(s, s->rgb_width/NUM_SEGMENTS_X, s->rgb_height/NUM_SEGMENTS_Y, 3); s->krnl_rgb_laplacian = clCreateKernel(s->prg_rgb_laplacian, "rgb2gray_conv2d", &err); assert(err == 0); @@ -1297,13 +1256,7 @@ int main(int argc, char *argv[]) { init_buffers(s); #if defined(QCOM) || defined(QCOM2) - s->msg_context = Context::create(); - s->frame_sock = PubSocket::create(s->msg_context, "frame"); - s->front_frame_sock = PubSocket::create(s->msg_context, "frontFrame"); - s->thumbnail_sock = PubSocket::create(s->msg_context, "thumbnail"); - assert(s->frame_sock != NULL); - assert(s->front_frame_sock != NULL); - assert(s->thumbnail_sock != NULL); + s->pm = new PubMaster({"frame", "frontFrame", "thumbnail"}); #endif cameras_open(&s->cameras, &s->camera_bufs[0], &s->focus_bufs[0], &s->stats_bufs[0], &s->front_camera_bufs[0]); @@ -1311,10 +1264,7 @@ int main(int argc, char *argv[]) { party(s); #if defined(QCOM) || defined(QCOM2) - delete s->frame_sock; - delete s->front_frame_sock; - delete s->thumbnail_sock; - delete s->msg_context; + delete s->pm; #endif free_buffers(s); diff --git a/selfdrive/clocksd/SConscript b/selfdrive/clocksd/SConscript index 63c508c4fe..601e64bf16 100644 --- a/selfdrive/clocksd/SConscript +++ b/selfdrive/clocksd/SConscript @@ -1,2 +1,2 @@ -Import('env', 'common', 'messaging') -env.Program('clocksd.cc', LIBS=['diag', 'time_genoff', common, messaging, 'capnp', 'zmq', 'kj']) \ No newline at end of file +Import('env', 'common', 'cereal', 'messaging') +env.Program('clocksd.cc', LIBS=['diag', 'time_genoff', common, cereal, messaging, 'capnp', 'zmq', 'kj']) \ No newline at end of file diff --git a/selfdrive/clocksd/clocksd.cc b/selfdrive/clocksd/clocksd.cc index d289387a8b..2e17058e0e 100644 --- a/selfdrive/clocksd/clocksd.cc +++ b/selfdrive/clocksd/clocksd.cc @@ -4,10 +4,8 @@ #include #include #include -#include #include "messaging.hpp" #include "common/timing.h" -#include "cereal/gen/cpp/log.capnp.h" namespace { int64_t arm_cntpct() { @@ -21,10 +19,7 @@ int main() { setpriority(PRIO_PROCESS, 0, -13); int err = 0; - Context *context = Context::create(); - - PubSocket* clock_publisher = PubSocket::create(context, "clocks"); - assert(clock_publisher != NULL); + PubMaster pm({"clocks"}); int timerfd = timerfd_create(CLOCK_BOOTTIME, 0); assert(timerfd >= 0); @@ -60,13 +55,9 @@ int main() { clocks.setWallTimeNanos(wall_time); clocks.setModemUptimeMillis(modem_uptime_v); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - clock_publisher->send((char*)bytes.begin(), bytes.size()); + pm.send("clocks", msg); } close(timerfd); - delete clock_publisher; - delete context; return 0; } \ No newline at end of file diff --git a/selfdrive/locationd/SConscript b/selfdrive/locationd/SConscript index 29b5d00d01..fbecaa1bae 100644 --- a/selfdrive/locationd/SConscript +++ b/selfdrive/locationd/SConscript @@ -1,9 +1,9 @@ -Import('env', 'common', 'messaging') +Import('env', 'common', 'cereal', 'messaging') loc_objs = [ "locationd_yawrate.cc", "params_learner.cc", "paramsd.cc"] -loc_libs = [messaging, 'zmq', common, 'capnp', 'kj', 'json11', 'pthread'] +loc_libs = [cereal, messaging, 'zmq', common, 'capnp', 'kj', 'json11', 'pthread'] env.Program("paramsd", loc_objs, LIBS=loc_libs) env.SharedLibrary("locationd", loc_objs, LIBS=loc_libs) diff --git a/selfdrive/locationd/paramsd.cc b/selfdrive/locationd/paramsd.cc index bae43ba367..80eda71053 100644 --- a/selfdrive/locationd/paramsd.cc +++ b/selfdrive/locationd/paramsd.cc @@ -4,12 +4,8 @@ #include #include - -#include #include - #include "json11.hpp" -#include "cereal/gen/cpp/log.capnp.h" #include "common/swaglog.h" #include "common/messaging.h" @@ -30,18 +26,8 @@ void sigpipe_handler(int sig) { int main(int argc, char *argv[]) { signal(SIGPIPE, (sighandler_t)sigpipe_handler); - Context * c = Context::create(); - SubSocket * controls_state_sock = SubSocket::create(c, "controlsState"); - SubSocket * sensor_events_sock = SubSocket::create(c, "sensorEvents"); - SubSocket * camera_odometry_sock = SubSocket::create(c, "cameraOdometry"); - PubSocket * live_parameters_sock = PubSocket::create(c, "liveParameters"); - - assert(controls_state_sock != NULL); - assert(sensor_events_sock != NULL); - assert(camera_odometry_sock != NULL); - assert(live_parameters_sock != NULL); - - Poller * poller = Poller::create({controls_state_sock, sensor_events_sock, camera_odometry_sock}); + SubMaster sm({"controlsState", "sensorEvents", "cameraOdometry"}); + PubMaster pm({"liveParameters"}); Localizer localizer; @@ -104,70 +90,55 @@ int main(int argc, char *argv[]) { // Main loop int save_counter = 0; while (true){ - for (auto s : poller->poll(100)){ - Message * msg = s->receive(); - - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); - - capnp::FlatArrayMessageReader capnp_msg(amsg); - cereal::Event::Reader event = capnp_msg.getRoot(); - - localizer.handle_log(event); - - auto which = event.which(); - if (which == cereal::Event::CONTROLS_STATE){ - save_counter++; - - double yaw_rate = -localizer.x[0]; - bool valid = learner.update(yaw_rate, localizer.car_speed, localizer.steering_angle); - - double angle_offset_degrees = RADIANS_TO_DEGREES * learner.ao; - double angle_offset_average_degrees = RADIANS_TO_DEGREES * learner.slow_ao; - - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto live_params = event.initLiveParameters(); - live_params.setValid(valid); - live_params.setYawRate(localizer.x[0]); - live_params.setGyroBias(localizer.x[1]); - live_params.setAngleOffset(angle_offset_degrees); - live_params.setAngleOffsetAverage(angle_offset_average_degrees); - live_params.setStiffnessFactor(learner.x); - live_params.setSteerRatio(learner.sR); - - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - live_parameters_sock->send((char*)bytes.begin(), bytes.size()); - - // Save parameters every minute - if (save_counter % 6000 == 0) { - json11::Json json = json11::Json::object { - {"carVin", vin}, - {"carFingerprint", fingerprint}, - {"steerRatio", learner.sR}, - {"stiffnessFactor", learner.x}, - {"angleOffsetAverage", angle_offset_average_degrees}, - }; - - std::string out = json.dump(); - std::async(std::launch::async, - [out]{ - write_db_value("LiveParameters", out.c_str(), out.length()); - }); - } + if (sm.update(100) == 0) continue; + + if (sm.updated("controlsState")){ + localizer.handle_log(sm["controlsState"]); + save_counter++; + + double yaw_rate = -localizer.x[0]; + bool valid = learner.update(yaw_rate, localizer.car_speed, localizer.steering_angle); + + double angle_offset_degrees = RADIANS_TO_DEGREES * learner.ao; + double angle_offset_average_degrees = RADIANS_TO_DEGREES * learner.slow_ao; + + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto live_params = event.initLiveParameters(); + live_params.setValid(valid); + live_params.setYawRate(localizer.x[0]); + live_params.setGyroBias(localizer.x[1]); + live_params.setAngleOffset(angle_offset_degrees); + live_params.setAngleOffsetAverage(angle_offset_average_degrees); + live_params.setStiffnessFactor(learner.x); + live_params.setSteerRatio(learner.sR); + + pm.send("liveParameters", msg); + + // Save parameters every minute + if (save_counter % 6000 == 0) { + json11::Json json = json11::Json::object { + {"carVin", vin}, + {"carFingerprint", fingerprint}, + {"steerRatio", learner.sR}, + {"stiffnessFactor", learner.x}, + {"angleOffsetAverage", angle_offset_average_degrees}, + }; + + std::string out = json.dump(); + std::async(std::launch::async, + [out]{ + write_db_value("LiveParameters", out.c_str(), out.length()); + }); } - delete msg; } + if (sm.updated("sensorEvents")){ + localizer.handle_log(sm["sensorEvents"]); + } + if (sm.updated("cameraOdometry")){ + localizer.handle_log(sm["cameraOdometry"]); + } } - - delete live_parameters_sock; - delete controls_state_sock; - delete camera_odometry_sock; - delete sensor_events_sock; - delete poller; - delete c; - return 0; } diff --git a/selfdrive/locationd/ublox_msg.cc b/selfdrive/locationd/ublox_msg.cc index 42ea38e6d6..6f3bd6b635 100644 --- a/selfdrive/locationd/ublox_msg.cc +++ b/selfdrive/locationd/ublox_msg.cc @@ -1,6 +1,5 @@ #include #include -#include #include #include #include @@ -12,13 +11,8 @@ #include #include #include -#include -#include #include -#include -#include "cereal/gen/cpp/log.capnp.h" - #include "common/params.h" #include "common/swaglog.h" #include "common/timing.h" diff --git a/selfdrive/locationd/ubloxd.cc b/selfdrive/locationd/ubloxd.cc index 2c28f14228..13420f05a5 100644 --- a/selfdrive/locationd/ubloxd.cc +++ b/selfdrive/locationd/ubloxd.cc @@ -12,12 +12,8 @@ #include #include #include -#include -#include #include "messaging.hpp" -#include -#include "cereal/gen/cpp/log.capnp.h" #include "common/params.h" #include "common/swaglog.h" diff --git a/selfdrive/locationd/ubloxd_main.cc b/selfdrive/locationd/ubloxd_main.cc index 4e07932fff..43989a338a 100644 --- a/selfdrive/locationd/ubloxd_main.cc +++ b/selfdrive/locationd/ubloxd_main.cc @@ -12,13 +12,8 @@ #include #include #include -#include -#include #include "messaging.hpp" -#include -#include "cereal/gen/cpp/log.capnp.h" - #include "common/util.h" #include "common/params.h" #include "common/swaglog.h" @@ -33,7 +28,7 @@ void set_do_exit(int sig) { } using namespace ublox; - +const long ZMQ_POLL_TIMEOUT = 1000; // In miliseconds int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) { LOGW("starting ubloxd"); signal(SIGINT, (sighandler_t) set_do_exit); @@ -41,30 +36,15 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) UbloxMsgParser parser; - Context * c = Context::create(); - PubSocket * gpsLocationExternal = PubSocket::create(c, "gpsLocationExternal"); - PubSocket * ubloxGnss = PubSocket::create(c, "ubloxGnss"); - SubSocket * ubloxRaw = SubSocket::create(c, "ubloxRaw"); - - assert(gpsLocationExternal != NULL); - assert(ubloxGnss != NULL); - assert(ubloxRaw != NULL); - - Poller * poller = Poller::create({ubloxRaw}); - + SubMaster sm({"ubloxRaw"}); + PubMaster pm({"ubloxGnss", "gpsLocationExternal"}); while (!do_exit) { - Message * msg = poll_func(poller); - if (msg == NULL) continue; - - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); + if (sm.update(ZMQ_POLL_TIMEOUT) == 0) continue; - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); - - const uint8_t *data = event.getUbloxRaw().begin(); - size_t len = event.getUbloxRaw().size(); + auto ubloxRaw = sm["ubloxRaw"].getUbloxRaw(); + const uint8_t *data = ubloxRaw.begin(); + size_t len = ubloxRaw.size(); size_t bytes_consumed = 0; while(bytes_consumed < len && !do_exit) { size_t bytes_consumed_this_time = 0U; @@ -76,7 +56,7 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) auto words = parser.gen_solution(); if(words.size() > 0) { auto bytes = words.asBytes(); - send_func(gpsLocationExternal, bytes.begin(), bytes.size()); + pm.send("gpsLocationExternal", bytes.begin(), bytes.size()); } } else LOGW("Unknown nav msg id: 0x%02X", parser.msg_id()); @@ -86,14 +66,14 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) auto words = parser.gen_raw(); if(words.size() > 0) { auto bytes = words.asBytes(); - send_func(ubloxGnss, bytes.begin(), bytes.size()); + pm.send("ubloxGnss", bytes.begin(), bytes.size()); } } else if(parser.msg_id() == MSG_RXM_SFRBX) { //LOGD("MSG_RXM_SFRBX"); auto words = parser.gen_nav_data(); if(words.size() > 0) { auto bytes = words.asBytes(); - send_func(ubloxGnss, bytes.begin(), bytes.size()); + pm.send("ubloxGnss", bytes.begin(), bytes.size()); } } else LOGW("Unknown rxm msg id: 0x%02X", parser.msg_id()); @@ -103,7 +83,7 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) auto words = parser.gen_mon_hw(); if(words.size() > 0) { auto bytes = words.asBytes(); - send_func(ubloxGnss, bytes.begin(), bytes.size()); + pm.send("ubloxGnss", bytes.begin(), bytes.size()); } } else { LOGW("Unknown mon msg id: 0x%02X", parser.msg_id()); @@ -114,14 +94,7 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) } bytes_consumed += bytes_consumed_this_time; } - delete msg; } - delete poller; - delete ubloxRaw; - delete ubloxGnss; - delete gpsLocationExternal; - delete c; - return 0; } diff --git a/selfdrive/locationd/ubloxd_test.cc b/selfdrive/locationd/ubloxd_test.cc index ec65577f2a..fc7146625f 100644 --- a/selfdrive/locationd/ubloxd_test.cc +++ b/selfdrive/locationd/ubloxd_test.cc @@ -12,14 +12,10 @@ #include #include #include -#include -#include #include #include "messaging.hpp" #include "impl_zmq.hpp" -#include -#include "cereal/gen/cpp/log.capnp.h" #include "common/params.h" #include "common/swaglog.h" diff --git a/selfdrive/logcatd/SConscript b/selfdrive/logcatd/SConscript index 1040c3af70..67ad673002 100644 --- a/selfdrive/logcatd/SConscript +++ b/selfdrive/logcatd/SConscript @@ -1,2 +1,2 @@ -Import('env', 'messaging') -env.Program('logcatd.cc', LIBS=[messaging, 'cutils', 'zmq', 'czmq', 'capnp', 'kj']) +Import('env', 'cereal', 'messaging') +env.Program('logcatd.cc', LIBS=[cereal, messaging, 'cutils', 'zmq', 'czmq', 'capnp', 'kj']) diff --git a/selfdrive/logcatd/logcatd.cc b/selfdrive/logcatd/logcatd.cc index 9a7f1ba520..181e29df11 100644 --- a/selfdrive/logcatd/logcatd.cc +++ b/selfdrive/logcatd/logcatd.cc @@ -7,9 +7,7 @@ #include #include -#include #include "common/timing.h" -#include "cereal/gen/cpp/log.capnp.h" #include "messaging.hpp" int main() { @@ -27,10 +25,7 @@ int main() { assert(crash_logger); struct logger *kernel_logger = android_logger_open(logger_list, (log_id_t)5); // LOG_ID_KERNEL assert(kernel_logger); - - Context * c = Context::create(); - PubSocket * androidLog = PubSocket::create(c, "androidLog"); - assert(androidLog != NULL); + PubMaster pm({"androidLog"}); while (1) { log_msg log_msg; @@ -57,15 +52,9 @@ int main() { androidEntry.setTag(entry.tag); androidEntry.setMessage(entry.message); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - androidLog->send((char*)bytes.begin(), bytes.size()); + pm.send("androidLog", msg); } android_logger_list_close(logger_list); - - delete androidLog; - delete c; - return 0; } diff --git a/selfdrive/loggerd/SConscript b/selfdrive/loggerd/SConscript index cb5dfa6ee9..2e5dae5553 100644 --- a/selfdrive/loggerd/SConscript +++ b/selfdrive/loggerd/SConscript @@ -1,9 +1,9 @@ -Import('env', 'arch', 'messaging', 'common', 'visionipc') +Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc') src = ['loggerd.cc', 'logger.cc'] libs = ['zmq', 'czmq', 'capnp', 'kj', 'z', 'avformat', 'avcodec', 'swscale', 'avutil', - 'yuv', 'bz2', common, messaging, visionipc] + 'yuv', 'bz2', common, cereal, messaging, visionipc] if arch == "aarch64": src += ['encoder.c', 'raw_logger.cc'] diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index 93e80abbf0..b7c7303c0e 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -21,10 +21,7 @@ #include #include - #include -#include - #ifdef QCOM #include #endif diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index f70057d649..1bf1d345de 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -1,7 +1,7 @@ -Import('env', 'arch', 'messaging', 'common', 'gpucommon', 'visionipc') +Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc') lenv = env.Clone() -libs = [messaging, common, 'OpenCL', 'SNPE', 'capnp', 'zmq', 'kj', 'yuv', gpucommon, visionipc] +libs = [cereal, messaging, common, 'OpenCL', 'SNPE', 'capnp', 'zmq', 'kj', 'yuv', gpucommon, visionipc] TEST_THNEED = False diff --git a/selfdrive/modeld/dmonitoringmodeld.cc b/selfdrive/modeld/dmonitoringmodeld.cc index d17247f9e5..c987e44482 100644 --- a/selfdrive/modeld/dmonitoringmodeld.cc +++ b/selfdrive/modeld/dmonitoringmodeld.cc @@ -26,10 +26,8 @@ int main(int argc, char **argv) { set_realtime_priority(1); // messaging - Context *msg_context = Context::create(); - PubSocket *dmonitoring_sock = PubSocket::create(msg_context, "driverState"); - SubSocket *dmonstate_sock = SubSocket::create(msg_context, "dMonitoringState", "127.0.0.1", true); - assert(dmonstate_sock != NULL); + SubMaster sm({"dMonitoringState"}); + PubMaster pm({"driverState"}); // init the models DMonitoringModelState dmonitoringmodel; @@ -61,17 +59,10 @@ int main(int argc, char **argv) { //printf("frame_id: %d %dx%d\n", extra.frame_id, buf_info.width, buf_info.height); if (!dmonitoringmodel.is_rhd_checked) { if (chk_counter >= RHD_CHECK_INTERVAL) { - Message *msg = dmonstate_sock->receive(true); - if (msg != NULL) { - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); - - dmonitoringmodel.is_rhd = event.getDMonitoringState().getIsRHD(); - dmonitoringmodel.is_rhd_checked = event.getDMonitoringState().getRhdChecked(); - delete msg; + if (sm.update(0) > 0) { + auto state = sm["dMonitoringState"].getDMonitoringState(); + dmonitoringmodel.is_rhd = state.getIsRHD(); + dmonitoringmodel.is_rhd_checked = state.getRhdChecked(); } chk_counter = 0; } @@ -85,7 +76,7 @@ int main(int argc, char **argv) { double t2 = millis_since_boot(); // send dm packet - dmonitoring_publish(dmonitoring_sock, extra.frame_id, res); + dmonitoring_publish(pm, extra.frame_id, res); LOGD("dmonitoring process: %.2fms, from last %.2fms", t2-t1, t1-last); last = t1; @@ -95,8 +86,6 @@ int main(int argc, char **argv) { visionstream_destroy(&stream); - delete dmonitoring_sock; - delete msg_context; dmonitoring_free(&dmonitoringmodel); return 0; diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 3c5011eb2a..764f9aadeb 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -7,7 +7,7 @@ #include "common/swaglog.h" #include "models/driving.h" - +#include "messaging.hpp" volatile sig_atomic_t do_exit = 0; static void set_do_exit(int sig) { @@ -23,12 +23,7 @@ void* live_thread(void *arg) { int err; set_thread_name("live"); - Context * c = Context::create(); - SubSocket * live_calibration_sock = SubSocket::create(c, "liveCalibration"); - assert(live_calibration_sock != NULL); - - Poller * poller = Poller::create({live_calibration_sock}); - + SubMaster sm({"liveCalibration"}); /* import numpy as np from common.transformations.model import medmodel_frame_from_road_frame @@ -48,49 +43,31 @@ void* live_thread(void *arg) { 0.0, 0.0, 1.0; while (!do_exit) { - for (auto sock : poller->poll(10)){ - Message * msg = sock->receive(); - - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); - - if (event.isLiveCalibration()) { - pthread_mutex_lock(&transform_lock); + if (sm.update(10) > 0){ + pthread_mutex_lock(&transform_lock); - auto extrinsic_matrix = event.getLiveCalibration().getExtrinsicMatrix(); - Eigen::Matrix extrinsic_matrix_eigen; - for (int i = 0; i < 4*3; i++){ - extrinsic_matrix_eigen(i / 4, i % 4) = extrinsic_matrix[i]; - } + auto extrinsic_matrix = sm["liveCalibration"].getLiveCalibration().getExtrinsicMatrix(); + Eigen::Matrix extrinsic_matrix_eigen; + for (int i = 0; i < 4*3; i++){ + extrinsic_matrix_eigen(i / 4, i % 4) = extrinsic_matrix[i]; + } - auto camera_frame_from_road_frame = eon_intrinsics * extrinsic_matrix_eigen; - Eigen::Matrix camera_frame_from_ground; - camera_frame_from_ground.col(0) = camera_frame_from_road_frame.col(0); - camera_frame_from_ground.col(1) = camera_frame_from_road_frame.col(1); - camera_frame_from_ground.col(2) = camera_frame_from_road_frame.col(3); + auto camera_frame_from_road_frame = eon_intrinsics * extrinsic_matrix_eigen; + Eigen::Matrix camera_frame_from_ground; + camera_frame_from_ground.col(0) = camera_frame_from_road_frame.col(0); + camera_frame_from_ground.col(1) = camera_frame_from_road_frame.col(1); + camera_frame_from_ground.col(2) = camera_frame_from_road_frame.col(3); - auto warp_matrix = camera_frame_from_ground * ground_from_medmodel_frame; + auto warp_matrix = camera_frame_from_ground * ground_from_medmodel_frame; - for (int i=0; i<3*3; i++) { - cur_transform.v[i] = warp_matrix(i / 3, i % 3); - } - - run_model = true; - pthread_mutex_unlock(&transform_lock); + for (int i=0; i<3*3; i++) { + cur_transform.v[i] = warp_matrix(i / 3, i % 3); } - delete msg; + run_model = true; + pthread_mutex_unlock(&transform_lock); } - } - - delete live_calibration_sock; - delete poller; - delete c; - return NULL; } @@ -104,14 +81,8 @@ int main(int argc, char **argv) { assert(err == 0); // messaging - Context *msg_context = Context::create(); - PubSocket *model_sock = PubSocket::create(msg_context, "model"); - PubSocket *posenet_sock = PubSocket::create(msg_context, "cameraOdometry"); - SubSocket *pathplan_sock = SubSocket::create(msg_context, "pathPlan", "127.0.0.1", true); - - assert(model_sock != NULL); - assert(posenet_sock != NULL); - assert(pathplan_sock != NULL); + PubMaster pm({"model", "cameraOdometry"}); + SubMaster sm({"pathPlan"}); // cl init cl_device_id device_id; @@ -194,18 +165,9 @@ int main(int argc, char **argv) { const bool run_model_this_iter = run_model; pthread_mutex_unlock(&transform_lock); - Message *msg = pathplan_sock->receive(true); - if (msg != NULL) { - // TODO: copy and pasted from camerad/main.cc - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); - + if (sm.update(0) > 0){ // TODO: path planner timeout? - desire = ((int)event.getPathPlan().getDesire()) - 1; - delete msg; + desire = ((int)sm["pathPlan"].getPathPlan().getDesire()) - 1; } double mt1 = 0, mt2 = 0; @@ -227,8 +189,8 @@ int main(int argc, char **argv) { model_transform, NULL, vec_desire); mt2 = millis_since_boot(); - model_publish(model_sock, extra.frame_id, model_buf, extra.timestamp_eof); - posenet_publish(posenet_sock, extra.frame_id, model_buf, extra.timestamp_eof); + model_publish(pm, extra.frame_id, model_buf, extra.timestamp_eof); + posenet_publish(pm, extra.frame_id, model_buf, extra.timestamp_eof); LOGD("model process: %.2fms, from last %.2fms", mt2-mt1, mt1-last); last = mt1; @@ -240,11 +202,6 @@ int main(int argc, char **argv) { visionstream_destroy(&stream); - delete model_sock; - delete posenet_sock; - delete pathplan_sock; - delete msg_context; - model_free(&model); LOG("joining live_thread"); diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 41de617ad6..21fac61c28 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -143,7 +143,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ return ret; } -void dmonitoring_publish(PubSocket* sock, uint32_t frame_id, const DMonitoringResult res) { +void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult res) { // make msg capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); @@ -166,10 +166,7 @@ void dmonitoring_publish(PubSocket* sock, uint32_t frame_id, const DMonitoringRe framed.setLeftBlinkProb(res.left_blink_prob); framed.setRightBlinkProb(res.right_blink_prob); - // send message - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - sock->send((char*)bytes.begin(), bytes.size()); + pm.send("driverState", msg); } void dmonitoring_free(DMonitoringModelState* s) { diff --git a/selfdrive/modeld/models/dmonitoring.h b/selfdrive/modeld/models/dmonitoring.h index dc5d116e98..e8a496dee9 100644 --- a/selfdrive/modeld/models/dmonitoring.h +++ b/selfdrive/modeld/models/dmonitoring.h @@ -5,8 +5,6 @@ #include "commonmodel.h" #include "runners/run.h" -#include "cereal/gen/cpp/log.capnp.h" -#include #include "messaging.hpp" #ifdef __cplusplus @@ -37,7 +35,7 @@ typedef struct DMonitoringModelState { void dmonitoring_init(DMonitoringModelState* s); DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height); -void dmonitoring_publish(PubSocket *sock, uint32_t frame_id, const DMonitoringResult res); +void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult res); void dmonitoring_free(DMonitoringModelState* s); #ifdef __cplusplus diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 5aed70ee68..817fe85662 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -246,7 +246,7 @@ void fill_longi(cereal::ModelData::LongitudinalData::Builder longi, const float longi.setAccelerations(accel); } -void model_publish(PubSocket *sock, uint32_t frame_id, +void model_publish(PubMaster &pm, uint32_t frame_id, const ModelDataRaw net_outputs, uint64_t timestamp_eof) { // make msg capnp::MallocMessageBuilder msg; @@ -292,14 +292,10 @@ void model_publish(PubSocket *sock, uint32_t frame_id, auto meta = framed.initMeta(); fill_meta(meta, net_outputs.meta); - - // send message - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - sock->send((char*)bytes.begin(), bytes.size()); + pm.send("model", msg); } -void posenet_publish(PubSocket *sock, uint32_t frame_id, +void posenet_publish(PubMaster &pm, uint32_t frame_id, const ModelDataRaw net_outputs, uint64_t timestamp_eof) { capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); @@ -331,7 +327,5 @@ void posenet_publish(PubSocket *sock, uint32_t frame_id, posenetd.setTimestampEof(timestamp_eof); posenetd.setFrameId(frame_id); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - sock->send((char*)bytes.begin(), bytes.size()); - } + pm.send("cameraOdometry", msg); +} diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index 1a2ac94e1a..a852db4022 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -13,9 +13,7 @@ #include "commonmodel.h" #include "runners/run.h" -#include "cereal/gen/cpp/log.capnp.h" #include -#include #include "messaging.hpp" #define MODEL_WIDTH 512 @@ -73,8 +71,8 @@ ModelDataRaw model_eval_frame(ModelState* s, cl_command_queue q, void model_free(ModelState* s); void poly_fit(float *in_pts, float *in_stds, float *out); -void model_publish(PubSocket* sock, uint32_t frame_id, +void model_publish(PubMaster &pm, uint32_t frame_id, const ModelDataRaw data, uint64_t timestamp_eof); -void posenet_publish(PubSocket* sock, uint32_t frame_id, +void posenet_publish(PubMaster &pm, uint32_t frame_id, const ModelDataRaw data, uint64_t timestamp_eof); #endif diff --git a/selfdrive/proclogd/SConscript b/selfdrive/proclogd/SConscript index 2b87f8d5e5..e7677099e9 100644 --- a/selfdrive/proclogd/SConscript +++ b/selfdrive/proclogd/SConscript @@ -1,2 +1,2 @@ -Import('env', 'messaging') -env.Program('proclogd.cc', LIBS=[messaging, 'pthread', 'zmq', 'czmq', 'capnp', 'kj']) +Import('env', 'cereal', 'messaging') +env.Program('proclogd.cc', LIBS=[cereal, messaging, 'pthread', 'zmq', 'czmq', 'capnp', 'kj']) diff --git a/selfdrive/proclogd/proclogd.cc b/selfdrive/proclogd/proclogd.cc index 2e7503ca75..878ebc499e 100644 --- a/selfdrive/proclogd/proclogd.cc +++ b/selfdrive/proclogd/proclogd.cc @@ -5,9 +5,6 @@ #include #include - -#include -#include #include #include #include @@ -17,8 +14,6 @@ #include #include "messaging.hpp" -#include -#include "cereal/gen/cpp/log.capnp.h" #include "common/timing.h" #include "common/utilpp.h" @@ -35,10 +30,7 @@ struct ProcCache { int main() { int err; - - Context * c = Context::create(); - PubSocket * publisher = PubSocket::create(c, "procLog"); - assert(publisher != NULL); + PubMaster publisher({"procLog"}); double jiffy = sysconf(_SC_CLK_TCK); size_t page_size = sysconf(_SC_PAGE_SIZE); @@ -233,15 +225,10 @@ int main() { } } - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - publisher->send((char*)bytes.begin(), bytes.size()); + publisher.send("procLog", msg); usleep(2000000); // 2 secs } - delete publisher; - delete c; - return 0; } diff --git a/selfdrive/sensord/SConscript b/selfdrive/sensord/SConscript index 4c9e24329a..b578ac9514 100644 --- a/selfdrive/sensord/SConscript +++ b/selfdrive/sensord/SConscript @@ -1,5 +1,5 @@ -Import('env', 'common', 'messaging') -env.Program('_sensord', 'sensors.cc', LIBS=['hardware', common, messaging, 'capnp', 'zmq', 'kj']) +Import('env', 'common', 'cereal', 'messaging') +env.Program('_sensord', 'sensors.cc', LIBS=['hardware', common, cereal, messaging, 'capnp', 'zmq', 'kj']) lenv = env.Clone() lenv['LIBPATH'] += ['/system/vendor/lib64'] -lenv.Program('_gpsd', ['gpsd.cc'], LIBS=['hardware', common, 'diag', 'time_genoff', messaging, 'capnp', 'zmq', 'kj']) +lenv.Program('_gpsd', ['gpsd.cc'], LIBS=['hardware', common, 'diag', 'time_genoff', cereal, messaging, 'capnp', 'zmq', 'kj']) diff --git a/selfdrive/sensord/gpsd.cc b/selfdrive/sensord/gpsd.cc index 4f3b7079b1..7fdad45c6b 100644 --- a/selfdrive/sensord/gpsd.cc +++ b/selfdrive/sensord/gpsd.cc @@ -16,21 +16,15 @@ #include #include -#include - #include "messaging.hpp" #include "common/timing.h" #include "common/swaglog.h" -#include "cereal/gen/cpp/log.capnp.h" - volatile sig_atomic_t do_exit = 0; namespace { -Context *gps_context; -PubSocket *gps_publisher; -PubSocket *gps_location_publisher; +PubMaster *pm; const GpsInterface* gGpsInterface = NULL; const AGpsInterface* gAGpsInterface = NULL; @@ -53,10 +47,7 @@ void nmea_callback(GpsUtcTime timestamp, const char* nmea, int length) { nmeaData.setLocalWallTime(log_time_wall); nmeaData.setNmea(nmea); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - // printf("gps send %d\n", bytes.size()); - gps_publisher->send((char*)bytes.begin(), bytes.size()); + pm->send("gpsNMEA", msg); } void location_callback(GpsLocation* location) { @@ -78,9 +69,7 @@ void location_callback(GpsLocation* location) { locationData.setTimestamp(location->timestamp); locationData.setSource(cereal::GpsLocationData::SensorSource::ANDROID); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - gps_location_publisher->send((char*)bytes.begin(), bytes.size()); + pm->send("gpsLocation", msg); } pthread_t create_thread_callback(const char* name, void (*start)(void *), void* arg) { @@ -125,9 +114,8 @@ AGpsCallbacks agps_callbacks = { create_thread_callback, }; - - void gps_init() { + pm = new PubMaster({"gpsNMEA", "gpsLocation"}); LOG("*** init GPS"); hw_module_t* module = NULL; hw_get_module(GPS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); @@ -156,15 +144,10 @@ void gps_init() { GPS_POSITION_RECURRENCE_PERIODIC, 100, 0, 0); - gps_context = Context::create(); - gps_publisher = PubSocket::create(gps_context, "gpsNMEA"); - gps_location_publisher = PubSocket::create(gps_context, "gpsLocation"); - - assert(gps_publisher != NULL); - assert(gps_location_publisher != NULL); } void gps_destroy() { + delete pm; gGpsInterface->stop(); gGpsInterface->cleanup(); } diff --git a/selfdrive/sensord/sensors.cc b/selfdrive/sensord/sensors.cc index 5e8741dbb3..b42482d853 100644 --- a/selfdrive/sensord/sensors.cc +++ b/selfdrive/sensord/sensors.cc @@ -13,18 +13,13 @@ #include #include - #include #include -#include - #include "messaging.hpp" #include "common/timing.h" #include "common/swaglog.h" -#include "cereal/gen/cpp/log.capnp.h" - #define SENSOR_ACCELEROMETER 1 #define SENSOR_MAGNETOMETER 2 #define SENSOR_GYRO 4 @@ -51,15 +46,10 @@ void sigpipe_handler(int sig) { re_init_sensors = true; } - void sensor_loop() { LOG("*** sensor loop"); - - while (!do_exit) { - Context * c = Context::create(); - PubSocket * sensor_events_sock = PubSocket::create(c, "sensorEvents"); - assert(sensor_events_sock != NULL); + PubMaster pm({"sensorEvents"}); struct sensors_poll_device_t* device; struct sensors_module_t* module; @@ -107,7 +97,6 @@ void sensor_loop() { static const size_t numEvents = 16; sensors_event_t buffer[numEvents]; - while (!do_exit) { int n = device->poll(device, buffer, numEvents); if (n == 0) continue; @@ -215,9 +204,7 @@ void sensor_loop() { log_i++; } - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - sensor_events_sock->send((char*)bytes.begin(), bytes.size()); + pm.send("sensorEvents", msg); if (re_init_sensors){ LOGE("Resetting sensors"); @@ -226,8 +213,6 @@ void sensor_loop() { } } sensors_close(device); - delete sensor_events_sock; - delete c; } } diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 03eed94192..29c866cab0 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -1,4 +1,3 @@ -#include "ui.hpp" #include #include #include @@ -6,7 +5,6 @@ #include #include #include -#include #include #include "common/util.h" #include "common/timing.h" @@ -14,6 +12,7 @@ #include "common/touch.h" #include "common/visionimg.h" #include "common/params.h" +#include "ui.hpp" static int last_brightness = -1; static void set_brightness(UIState *s, int brightness) { @@ -72,9 +71,7 @@ static void update_offroad_layout_state(UIState *s) { auto layout = event.initUiLayoutState(); layout.setActiveApp(s->active_app); layout.setSidebarCollapsed(s->scene.uilayout_sidebarcollapsed); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - s->offroad_sock->send((char*)bytes.begin(), bytes.size()); + s->pm->send("offroadLayout", msg); LOGD("setting active app to %d with sidebar %d", (int)s->active_app, s->scene.uilayout_sidebarcollapsed); } @@ -214,50 +211,13 @@ static void ui_init(UIState *s) { memset(s, 0, sizeof(UIState)); pthread_mutex_init(&s->lock, NULL); - - s->ctx = Context::create(); - s->model_sock = SubSocket::create(s->ctx, "model"); - s->controlsstate_sock = SubSocket::create(s->ctx, "controlsState"); - s->uilayout_sock = SubSocket::create(s->ctx, "uiLayoutState"); - s->livecalibration_sock = SubSocket::create(s->ctx, "liveCalibration"); - s->radarstate_sock = SubSocket::create(s->ctx, "radarState"); - s->thermal_sock = SubSocket::create(s->ctx, "thermal"); - s->health_sock = SubSocket::create(s->ctx, "health"); - s->ubloxgnss_sock = SubSocket::create(s->ctx, "ubloxGnss"); - s->driverstate_sock = SubSocket::create(s->ctx, "driverState"); - s->dmonitoring_sock = SubSocket::create(s->ctx, "dMonitoringState"); - s->offroad_sock = PubSocket::create(s->ctx, "offroadLayout"); - - assert(s->model_sock != NULL); - assert(s->controlsstate_sock != NULL); - assert(s->uilayout_sock != NULL); - assert(s->livecalibration_sock != NULL); - assert(s->radarstate_sock != NULL); - assert(s->thermal_sock != NULL); - assert(s->health_sock != NULL); - assert(s->ubloxgnss_sock != NULL); - assert(s->driverstate_sock != NULL); - assert(s->dmonitoring_sock != NULL); - assert(s->offroad_sock != NULL); - - s->poller = Poller::create({ - s->model_sock, - s->controlsstate_sock, - s->uilayout_sock, - s->livecalibration_sock, - s->radarstate_sock, - s->thermal_sock, - s->health_sock, - s->ubloxgnss_sock, - s->driverstate_sock, - s->dmonitoring_sock - }); - + s->sm = new SubMaster({"model", "controlsState", "uiLayoutState", "liveCalibration", "radarState", "thermal", + "health", "ubloxGnss", "driverState", "dMonitoringState", "offroadLayout" #ifdef SHOW_SPEEDLIMIT - s->map_data_sock = SubSocket::create(s->ctx, "liveMapData"); - assert(s->map_data_sock != NULL); - s->poller->registerSocket(s->map_data_sock); + , "liveMapData" #endif + }); + s->pm = new PubMaster({"offroadLayout"}); s->ipc_fd = -1; @@ -369,17 +329,11 @@ static void update_status(UIState *s, int status) { } } -void handle_message(UIState *s, Message* msg) { - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); - - auto which = event.which(); +void handle_message(UIState *s, SubMaster &sm) { UIScene &scene = s->scene; - if (which == cereal::Event::CONTROLS_STATE && s->started) { + if (s->started && sm.updated("controlsState")) { + auto event = sm["controlsState"]; auto data = event.getControlsState(); - s->controls_timeout = 1 * UI_FREQ; scene.frontview = data.getRearViewCam(); if (!scene.frontview){ s->controls_seen = true; } @@ -394,7 +348,6 @@ void handle_message(UIState *s, Message* msg) { scene.engageable = data.getEngageable(); scene.gps_planner_active = data.getGpsPlannerActive(); scene.monitoring_active = data.getDriverMonitoringOn(); - scene.decel_for_model = data.getDecelForModel(); auto alert_sound = data.getAlertSound(); const auto sound_none = cereal::CarControl::HUDControl::AudibleAlert::NONE; @@ -438,8 +391,9 @@ void handle_message(UIState *s, Message* msg) { } } } - } else if (which == cereal::Event::RADAR_STATE) { - auto data = event.getRadarState(); + } + if (sm.updated("radarState")) { + auto data = sm["radarState"].getRadarState(); auto leaddatad = data.getLeadOne(); scene.lead_status = leaddatad.getStatus(); @@ -451,40 +405,44 @@ void handle_message(UIState *s, Message* msg) { scene.lead_d_rel2 = leaddatad2.getDRel(); scene.lead_y_rel2 = leaddatad2.getYRel(); scene.lead_v_rel2 = leaddatad2.getVRel(); - s->livempc_or_radarstate_changed = true; - } else if (which == cereal::Event::LIVE_CALIBRATION) { + } + if (sm.updated("liveCalibration")) { scene.world_objects_visible = true; - auto extrinsicl = event.getLiveCalibration().getExtrinsicMatrix(); + auto extrinsicl = sm["liveCalibration"].getLiveCalibration().getExtrinsicMatrix(); for (int i = 0; i < 3 * 4; i++) { scene.extrinsic_matrix.v[i] = extrinsicl[i]; } - } else if (which == cereal::Event::MODEL) { - scene.model = read_model(event.getModel()); + } + if (sm.updated("model")) { + scene.model = read_model(sm["model"].getModel()); s->model_changed = true; - } else if (which == cereal::Event::LIVE_MPC) { - auto data = event.getLiveMpc(); - - auto x_list = data.getX(); - auto y_list = data.getY(); - for (int i = 0; i < 50; i++){ - scene.mpc_x[i] = x_list[i]; - scene.mpc_y[i] = y_list[i]; - } - s->livempc_or_radarstate_changed = true; - } else if (which == cereal::Event::UI_LAYOUT_STATE) { - auto data = event.getUiLayoutState(); - + } + // else if (which == cereal::Event::LIVE_MPC) { + // auto data = event.getLiveMpc(); + // auto x_list = data.getX(); + // auto y_list = data.getY(); + // for (int i = 0; i < 50; i++){ + // scene.mpc_x[i] = x_list[i]; + // scene.mpc_y[i] = y_list[i]; + // } + // s->livempc_or_radarstate_changed = true; + // } + if (sm.updated("uiLayoutState")) { + auto data = sm["uiLayoutState"].getUiLayoutState(); s->active_app = data.getActiveApp(); scene.uilayout_sidebarcollapsed = data.getSidebarCollapsed(); if (data.getMockEngaged() != scene.uilayout_mockengaged) { scene.uilayout_mockengaged = data.getMockEngaged(); } - } else if (which == cereal::Event::LIVE_MAP_DATA) { - scene.map_valid = event.getLiveMapData().getMapValid(); - } else if (which == cereal::Event::THERMAL) { - auto data = event.getThermal(); - + } +#ifdef SHOW_SPEEDLIMIT + if (sm.updated("liveMapData")) { + scene.map_valid = sm["liveMapData"].getLiveMapData().getMapValid(); + } +#endif + if (sm.updated("thermal")) { + auto data = sm["thermal"].getThermal(); scene.networkType = data.getNetworkType(); scene.networkStrength = data.getNetworkStrength(); scene.batteryPercent = data.getBatteryPercent(); @@ -494,22 +452,26 @@ void handle_message(UIState *s, Message* msg) { scene.paTemp = data.getPa0(); s->thermal_started = data.getStarted(); - } else if (which == cereal::Event::UBLOX_GNSS) { - auto data = event.getUbloxGnss(); + } + if (sm.updated("ubloxGnss")) { + auto data = sm["ubloxGnss"].getUbloxGnss(); if (data.which() == cereal::UbloxGnss::MEASUREMENT_REPORT) { scene.satelliteCount = data.getMeasurementReport().getNumMeas(); } - } else if (which == cereal::Event::HEALTH) { - scene.hwType = event.getHealth().getHwType(); + } + if (sm.updated("health")) { + scene.hwType = sm["health"].getHealth().getHwType(); s->hardware_timeout = 5*30; // 5 seconds at 30 fps - } else if (which == cereal::Event::DRIVER_STATE) { - auto data = event.getDriverState(); + } + if (sm.updated("driverState")) { + auto data = sm["driverState"].getDriverState(); scene.face_prob = data.getFaceProb(); auto fxy_list = data.getFacePosition(); scene.face_x = fxy_list[0]; scene.face_y = fxy_list[1]; - } else if (which == cereal::Event::D_MONITORING_STATE) { - auto data = event.getDMonitoringState(); + } + if (sm.updated("dMonitoringState")) { + auto data = sm["dMonitoringState"].getDMonitoringState(); scene.is_rhd = data.getIsRHD(); scene.awareness_status = data.getAwarenessStatus(); s->preview_started = data.getIsPreview(); @@ -535,19 +497,10 @@ void handle_message(UIState *s, Message* msg) { } static void check_messages(UIState *s) { - while(true) { - auto polls = s->poller->poll(0); - - if (polls.size() == 0) + while (true) { + if (s->sm->update(0) == 0) break; - - for (auto sock : polls){ - Message *msg = sock->receive(); - if (msg) { - handle_message(s, msg); - delete msg; - } - } + handle_message(s, *(s->sm)); } } @@ -772,17 +725,7 @@ static void* vision_connect_thread(void *args) { s->vision_connect_firstrun = true; // Drain sockets - while (true){ - auto polls = s->poller->poll(0); - if (polls.size() == 0) - break; - - for (auto sock : polls){ - Message * msg = sock->receive(); - if (msg == NULL) continue; - delete msg; - } - } + s->sm->drain(); pthread_mutex_unlock(&s->lock); } @@ -1071,6 +1014,7 @@ int main(int argc, char* argv[]) { err = pthread_join(connect_thread_handle, NULL); assert(err == 0); - + delete s->sm; + delete s->pm; return 0; } diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 771b5501cc..9d3f15fa33 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -1,6 +1,8 @@ #ifndef _UI_H #define _UI_H -#include "cereal/gen/cpp/log.capnp.h" + +#include "messaging.hpp" + #ifdef __APPLE__ #include #define NANOVG_GL3_IMPLEMENTATION @@ -12,7 +14,6 @@ #define nvgCreate nvgCreateGLES3 #endif -#include #include #include "nanovg.h" @@ -21,7 +22,6 @@ #include "common/visionimg.h" #include "common/framebuffer.h" #include "common/modeldata.h" -#include "messaging.hpp" #include "sound.hpp" #define STATUS_STOPPED 0 @@ -203,21 +203,8 @@ typedef struct UIState { int img_network[6]; // sockets - Context *ctx; - SubSocket *model_sock; - SubSocket *controlsstate_sock; - SubSocket *livecalibration_sock; - SubSocket *radarstate_sock; - SubSocket *map_data_sock; - SubSocket *uilayout_sock; - SubSocket *thermal_sock; - SubSocket *health_sock; - SubSocket *ubloxgnss_sock; - SubSocket *driverstate_sock; - SubSocket *dmonitoring_sock; - PubSocket *offroad_sock; - Poller * poller; - Poller * ublox_poller; + SubMaster *sm; + PubMaster *pm; cereal::UiLayoutState::App active_app; From fcf879d783c345ccbf80252de23f649427c35fbd Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 21 May 2020 16:08:05 -0700 Subject: [PATCH 074/656] Add permanent CAN error alert (#1549) * Add permanent CAN error alert * canValid needs some time to initialize * update ref --- selfdrive/controls/controlsd.py | 4 ++-- selfdrive/controls/lib/events.py | 5 +++++ selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index cb7bca7f53..c8ea55088c 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -210,8 +210,8 @@ class Controls: self.events.add(EventName.radarFault) if self.sm['plan'].radarCanError: self.events.add(EventName.radarCanError) - if not CS.canValid: - self.events.add(EventName.canError) + if not CS.canValid and self.sm.frame > 5 / DT_CTRL: + self.events.add(EventName.canError) if log.HealthData.FaultType.relayMalfunction in self.sm['health'].faults: self.events.add(EventName.relayMalfunction) if self.sm['plan'].fcw: diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 4693f0c9cc..0202119337 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -607,6 +607,11 @@ EVENTS = { EventName.canError: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("CAN Error: Check Connections"), ET.NO_ENTRY: NoEntryAlert("CAN Error: Check Connections"), + ET.PERMANENT: Alert( + "CAN Error: Check Connections", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), }, EventName.steerUnavailable: { diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index baaafb0f8d..012e6ca16c 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -59bd32350139796784708f51c233d37c18f33e6e \ No newline at end of file +dadb4f96017c4f6b36fd829c41315b0a7f31c8e5 \ No newline at end of file From 00e05bc7d881feaf82529b4066789e41ee555c42 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Thu, 21 May 2020 17:47:05 -0700 Subject: [PATCH 075/656] needed for stability --- selfdrive/locationd/models/live_kf.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/models/live_kf.py b/selfdrive/locationd/models/live_kf.py index c8d4c7ed24..c583d7813b 100755 --- a/selfdrive/locationd/models/live_kf.py +++ b/selfdrive/locationd/models/live_kf.py @@ -168,7 +168,7 @@ class LiveKalman(): h_acc_sym = (gravity + acceleration) h_phone_rot_sym = sp.Matrix([vroll, vpitch, vyaw]) - speed = sp.sqrt(vx**2 + vy**2 + vz**2) + speed = sp.sqrt(vx**2 + vy**2 + vz**2 + 1e-6) h_speed_sym = sp.Matrix([speed * odo_scale]) h_pos_sym = sp.Matrix([x, y, z]) From 02eae5eb52f700e33ffed23c3691ee84f3c2f648 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 21 May 2020 20:38:25 -0700 Subject: [PATCH 076/656] Calib reset fix (#1553) * fix reset * this should be good --- apk/ai.comma.plus.offroad.apk | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk index 35f9cb672f..bf72f55619 100644 --- a/apk/ai.comma.plus.offroad.apk +++ b/apk/ai.comma.plus.offroad.apk @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:695622033fe2a531a2e263f5a0d19ee1fee8aadbad781092f71a3448bddd48d5 -size 13699616 +oid sha256:fbfb2e9870d4833819542833d62ce934b5ad284b30d727604188fd2a3676f0e6 +size 13699659 From ee371919c1fd2866a2f76344083cc24dc23a0398 Mon Sep 17 00:00:00 2001 From: "Tunder (Chris in RL)" <34691234+Tundergit@users.noreply.github.com> Date: Fri, 22 May 2020 10:37:05 -0700 Subject: [PATCH 077/656] add missing 2020 pacifica value (#1551) --- selfdrive/car/chrysler/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index ac1ede5f9f..1043f7f00b 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -41,7 +41,7 @@ FINGERPRINTS = { ], CAR.PACIFICA_2020: [ { - 55: 8, 179: 8, 181: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 650: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 926: 3, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 7, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1284: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 2016: 8, 2024: 8 + 55: 8, 179: 8, 181: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 650: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 926: 3, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 7, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1284: 8, 1568: 8, 1570:8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 2016: 8, 2024: 8 } ], CAR.PACIFICA_2018_HYBRID: [ From 676fd8ecbceac444e50c1aab2df7197f95b918cc Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Fri, 22 May 2020 10:37:19 -0700 Subject: [PATCH 078/656] Add Engine FW (#1556) --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 4b16485d0b..353ea3eea0 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -438,6 +438,7 @@ FW_VERSIONS = { b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B12361\x00\x00\x00\x00\x00\x00', From a623ad2ab376e21b216e4a19aaeec6111adb32fa Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 22 May 2020 13:40:06 -0700 Subject: [PATCH 079/656] That corolla eps version was probably merged by mistake --- selfdrive/car/toyota/values.py | 1 - 1 file changed, 1 deletion(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 353ea3eea0..c563cf6568 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -479,7 +479,6 @@ FW_VERSIONS = { (Ecu.eps, 0x7a1, None): [ b'8965B12361\x00\x00\x00\x00\x00\x00', b'8965B12451\x00\x00\x00\x00\x00\x00', - b'8965B42170\x00\x00\x00\x00\x00\x00', b'\x018965B12350\x00\x00\x00\x00\x00\x00', b'\x018965B12470\x00\x00\x00\x00\x00\x00', b'\x018965B12500\x00\x00\x00\x00\x00\x00', From bfe7cbfe5fda226af6195a1e0de61083a18971bb Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 22 May 2020 14:00:20 -0700 Subject: [PATCH 080/656] Split TSS2 RAV4 tuning based on fw version (#1558) --- selfdrive/car/toyota/interface.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 84fe1b8b3a..8c8161f6ab 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -161,6 +161,12 @@ class CarInterface(CarInterfaceBase): ret.mass = 3370. * CV.LB_TO_KG + STD_CARGO_KG ret.lateralTuning.pid.kf = 0.00004 + for fw in car_fw: + if fw.ecu == "eps" and fw.fwVersion == b"8965B42170\x00\x00\x00\x00\x00\x00": + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] + ret.lateralTuning.pid.kf = 0.00007818594 + break + elif candidate == CAR.RAV4H_TSS2: stop_and_go = True ret.safetyParam = 73 @@ -171,6 +177,12 @@ class CarInterface(CarInterfaceBase): ret.mass = 3800. * CV.LB_TO_KG + STD_CARGO_KG ret.lateralTuning.pid.kf = 0.00004 + for fw in car_fw: + if fw.ecu == "eps" and fw.fwVersion == b"8965B42170\x00\x00\x00\x00\x00\x00": + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] + ret.lateralTuning.pid.kf = 0.00007818594 + break + elif candidate in [CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2]: stop_and_go = True ret.safetyParam = 73 From ea1b19256540289732257df35c683730e329cf98 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 22 May 2020 14:42:22 -0700 Subject: [PATCH 081/656] bump panda after hyundai checksum --- panda | 2 +- selfdrive/test/test_panda_safety.py | 49 +++++++++++++++++++++++++++++ 2 files changed, 50 insertions(+), 1 deletion(-) create mode 100755 selfdrive/test/test_panda_safety.py diff --git a/panda b/panda index 5307bf7277..0657064594 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 5307bf7277c267075aa03799c8749a60463c8804 +Subproject commit 06570645941c33a5d83808606b0559e9943fd7b2 diff --git a/selfdrive/test/test_panda_safety.py b/selfdrive/test/test_panda_safety.py new file mode 100755 index 0000000000..67d08b914e --- /dev/null +++ b/selfdrive/test/test_panda_safety.py @@ -0,0 +1,49 @@ +#!/usr/bin/env python3 + +import os +import sys +import bz2 +import struct +from panda import Panda +from panda.tests.safety_replay.replay_drive import replay_drive +from tools.lib.logreader import LogReader +from xx.chffr.lib.route import Route + +# get a complete canlog (sendcan and can) for a drive +def get_canlog(route): + if os.path.isfile(route + ".bz2"): + return + + r = Route(route) + log_msgs = [] + for i, segment in enumerate(r.log_paths()): + print("downloading segment %d/%d" % (i+1, len(r.log_paths()))) + log = LogReader(segment) + log_msgs.extend(filter(lambda msg: msg.which() in ('can', 'sendcan'), log)) + log_msgs.sort(key=lambda msg: msg.logMonoTime) + + dat = b"".join(m.as_builder().to_bytes() for m in log_msgs) + dat = bz2.compress(dat) + with open(route + ".bz2", "wb") as f: + f.write(dat) + + +def get_logreader(route): + try: + lr = LogReader(route + ".bz2") + except IOError: + print("downloading can log") + get_canlog(route) + lr = LogReader(route + ".bz2") + + return lr + +if __name__ == "__main__": + route = sys.argv[1] + mode = int(sys.argv[2]) + param = 0 if len(sys.argv) < 4 else int(sys.argv[3]) + + lr = get_logreader(route) + print("replaying drive %s with safety model %d and param %d" % (route, mode, param)) + + replay_drive(lr, mode, param) From b251eff7645035e51f6379209a9c492c2c980a37 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 22 May 2020 14:50:08 -0700 Subject: [PATCH 082/656] remove that script --- selfdrive/test/test_panda_safety.py | 49 ----------------------------- 1 file changed, 49 deletions(-) delete mode 100755 selfdrive/test/test_panda_safety.py diff --git a/selfdrive/test/test_panda_safety.py b/selfdrive/test/test_panda_safety.py deleted file mode 100755 index 67d08b914e..0000000000 --- a/selfdrive/test/test_panda_safety.py +++ /dev/null @@ -1,49 +0,0 @@ -#!/usr/bin/env python3 - -import os -import sys -import bz2 -import struct -from panda import Panda -from panda.tests.safety_replay.replay_drive import replay_drive -from tools.lib.logreader import LogReader -from xx.chffr.lib.route import Route - -# get a complete canlog (sendcan and can) for a drive -def get_canlog(route): - if os.path.isfile(route + ".bz2"): - return - - r = Route(route) - log_msgs = [] - for i, segment in enumerate(r.log_paths()): - print("downloading segment %d/%d" % (i+1, len(r.log_paths()))) - log = LogReader(segment) - log_msgs.extend(filter(lambda msg: msg.which() in ('can', 'sendcan'), log)) - log_msgs.sort(key=lambda msg: msg.logMonoTime) - - dat = b"".join(m.as_builder().to_bytes() for m in log_msgs) - dat = bz2.compress(dat) - with open(route + ".bz2", "wb") as f: - f.write(dat) - - -def get_logreader(route): - try: - lr = LogReader(route + ".bz2") - except IOError: - print("downloading can log") - get_canlog(route) - lr = LogReader(route + ".bz2") - - return lr - -if __name__ == "__main__": - route = sys.argv[1] - mode = int(sys.argv[2]) - param = 0 if len(sys.argv) < 4 else int(sys.argv[3]) - - lr = get_logreader(route) - print("replaying drive %s with safety model %d and param %d" % (route, mode, param)) - - replay_drive(lr, mode, param) From 86057f785bbf77ce38ea2d6869fdf7377613ca4b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 23 May 2020 15:39:22 -0700 Subject: [PATCH 083/656] fix interface init for mock car --- selfdrive/car/interfaces.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index ca83cabb7d..3639b2836e 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -23,9 +23,10 @@ class CarInterfaceBase(): self.frame = 0 self.low_speed_alert = False - self.CS = CarState(CP) - self.cp = self.CS.get_can_parser(CP) - self.cp_cam = self.CS.get_cam_can_parser(CP) + if CarState is not None: + self.CS = CarState(CP) + self.cp = self.CS.get_can_parser(CP) + self.cp_cam = self.CS.get_cam_can_parser(CP) self.CC = None if CarController is not None: From b8571710e09e58b9e67170a9924eef79f32c480b Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Sun, 24 May 2020 03:33:36 -0700 Subject: [PATCH 084/656] remove the clCreateProgramWithSource interceptor (#1559) * remove the clCreateProgramWithSource interceptor * that's old code, thneed is better * label them thneed_, we shouldn't need to touch CL for anything not SNPE related --- selfdrive/modeld/test/opencl_hooks/build.sh | 3 - selfdrive/modeld/test/opencl_hooks/hook.c | 155 -------------------- selfdrive/modeld/thneed/thneed.cc | 22 +-- 3 files changed, 12 insertions(+), 168 deletions(-) delete mode 100755 selfdrive/modeld/test/opencl_hooks/build.sh delete mode 100644 selfdrive/modeld/test/opencl_hooks/hook.c diff --git a/selfdrive/modeld/test/opencl_hooks/build.sh b/selfdrive/modeld/test/opencl_hooks/build.sh deleted file mode 100755 index 03f8115354..0000000000 --- a/selfdrive/modeld/test/opencl_hooks/build.sh +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh -gcc -fPIC -I /data/openpilot/phonelibs/opencl/include -shared hook.c - diff --git a/selfdrive/modeld/test/opencl_hooks/hook.c b/selfdrive/modeld/test/opencl_hooks/hook.c deleted file mode 100644 index f2ee2c0d51..0000000000 --- a/selfdrive/modeld/test/opencl_hooks/hook.c +++ /dev/null @@ -1,155 +0,0 @@ -#include -#include -#include -#include -#include -#include - -static inline uint64_t nanos_since_boot() { - struct timespec t; - clock_gettime(CLOCK_BOOTTIME, &t); - return t.tv_sec * 1000000000ULL + t.tv_nsec; -} - -struct kernel { - cl_kernel k; - const char *name; - cl_program p; -}; - - -int k_index = 0; -struct kernel kk[0x1000] = {0}; - -FILE *f = NULL; - -cl_program clCreateProgramWithSource(cl_context context, - cl_uint count, - const char **strings, - const size_t *lengths, - cl_int *errcode_ret) { - printf("clCreateProgramWithSource: %d\n", count); - - if (f == NULL) { - f = fopen("/tmp/kernels.cl", "w"); - } - - fprintf(f, "/* ************************ PROGRAM BREAK ****************************/\n"); - for (int i = 0; i < count; i++) { - fprintf(f, "%s\n", strings[i]); - if (i != 0) fprintf(f, "/* ************************ SECTION BREAK ****************************/\n"); - } - fflush(f); - - cl_program (*my_clCreateProgramWithSource)(cl_context context, - cl_uint count, - const char **strings, - const size_t *lengths, - cl_int *errcode_ret) = dlsym(RTLD_NEXT, "REAL_clCreateProgramWithSource"); - - return my_clCreateProgramWithSource(context, count, strings, lengths, errcode_ret); -} - -cl_program clCreateProgramWithBinary(cl_context context, - cl_uint num_devices, - const cl_device_id *device_list, - const size_t *lengths, - const unsigned char **binaries, - cl_int *binary_status, - cl_int *errcode_ret) { - printf("clCreateProgramWithBinary\n"); - - cl_program (*my_clCreateProgramWithBinary)(cl_context context, - cl_uint num_devices, - const cl_device_id *device_list, - const size_t *lengths, - const unsigned char **binaries, - cl_int *binary_status, - cl_int *errcode_ret) = dlsym(RTLD_NEXT, "REAL_clCreateProgramWithBinary"); - - return my_clCreateProgramWithBinary(context, num_devices, device_list, lengths, binaries, binary_status, errcode_ret); -} - -cl_kernel clCreateKernel(cl_program program, const char *kernel_name, cl_int *errcode_ret) { - cl_kernel (*my_clCreateKernel)(cl_program program, const char *kernel_name, cl_int *errcode_ret); - my_clCreateKernel = dlsym(RTLD_NEXT, "REAL_clCreateKernel"); - cl_kernel ret = my_clCreateKernel(program, kernel_name, errcode_ret); - //printf("clCreateKernel: %s -> %p\n", kernel_name, ret); - - char *tmp = (char*)malloc(strlen(kernel_name)+1); - strcpy(tmp, kernel_name); - - kk[k_index].k = ret; - kk[k_index].name = tmp; - kk[k_index].p = program; - k_index++; - return ret; -} - - -uint64_t start_time = 0; -int cnt = 0; - -cl_int clEnqueueNDRangeKernel(cl_command_queue command_queue, - cl_kernel kernel, - cl_uint work_dim, - const size_t *global_work_offset, - const size_t *global_work_size, - const size_t *local_work_size, - cl_uint num_events_in_wait_list, - const cl_event *event_wait_list, - cl_event *event) { - - cl_int (*my_clEnqueueNDRangeKernel)(cl_command_queue, cl_kernel, cl_uint, - const size_t *, const size_t *, const size_t *, - cl_uint, const cl_event *, cl_event *) = NULL; - my_clEnqueueNDRangeKernel = dlsym(RTLD_NEXT, "REAL_clEnqueueNDRangeKernel"); - - if (start_time == 0) { - start_time = nanos_since_boot(); - } - - // get kernel name - const char *name = NULL; - cl_program p; - for (int i = 0; i < k_index; i++) { - if (kk[i].k == kernel) { - name = kk[i].name; - p = kk[i].p; - break; - } - } - - uint64_t tb = nanos_since_boot(); - cl_int ret = my_clEnqueueNDRangeKernel(command_queue, kernel, work_dim, - global_work_offset, global_work_size, local_work_size, - num_events_in_wait_list, event_wait_list, event); - uint64_t te = nanos_since_boot(); - - printf("%10lu run%8d in %5ld us command_queue:%p work_dim:%d event:%p ", (tb-start_time)/1000, cnt++, (te-tb)/1000, - command_queue, work_dim, event); - for (int i = 0; i < work_dim; i++) { - printf("%4zu ", global_work_size[i]); - } - printf("%p %s\n", p, name); - return ret; -} - -void *dlsym(void *handle, const char *symbol) { - void *(*my_dlsym)(void *handle, const char *symbol) = (void*)dlopen-0x2d4; - if (memcmp("REAL_", symbol, 5) == 0) { - return my_dlsym(handle, symbol+5); - } else if (strcmp("clEnqueueNDRangeKernel", symbol) == 0) { - return clEnqueueNDRangeKernel; - } else if (strcmp("clCreateKernel", symbol) == 0) { - return clCreateKernel; - } else if (strcmp("clCreateProgramWithSource", symbol) == 0) { - return clCreateProgramWithSource; - } else if (strcmp("clCreateProgramWithBinary", symbol) == 0) { - return clCreateProgramWithBinary; - } else { - printf("dlsym %s\n", symbol); - return my_dlsym(handle, symbol); - } -} - diff --git a/selfdrive/modeld/thneed/thneed.cc b/selfdrive/modeld/thneed/thneed.cc index 6bacd5440d..cd1242b086 100644 --- a/selfdrive/modeld/thneed/thneed.cc +++ b/selfdrive/modeld/thneed/thneed.cc @@ -269,8 +269,10 @@ void Thneed::execute(float **finputs, float *foutput, bool slow) { } } +// TODO: with a different way of getting the input and output buffers, we don't have to intercept CL at all + cl_int (*my_clSetKernelArg)(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) = NULL; -cl_int clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) { +cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) { if (my_clSetKernelArg == NULL) my_clSetKernelArg = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clSetKernelArg")); if (arg_value != NULL) { g_args[std::make_pair(kernel, arg_index)] = std::string((char*)arg_value, arg_size); @@ -280,7 +282,7 @@ cl_int clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, cons } cl_int (*my_clEnqueueNDRangeKernel)(cl_command_queue, cl_kernel, cl_uint, const size_t *, const size_t *, const size_t *, cl_uint, const cl_event *, cl_event *) = NULL; -cl_int clEnqueueNDRangeKernel(cl_command_queue command_queue, +cl_int thneed_clEnqueueNDRangeKernel(cl_command_queue command_queue, cl_kernel kernel, cl_uint work_dim, const size_t *global_work_offset, @@ -403,17 +405,15 @@ cl_int clEnqueueNDRangeKernel(cl_command_queue command_queue, //#define SAVE_KERNELS #ifdef SAVE_KERNELS - std::map program_source; -#endif +std::map program_source; cl_program (*my_clCreateProgramWithSource)(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) = NULL; -cl_program clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) { +cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) { if (my_clCreateProgramWithSource == NULL) my_clCreateProgramWithSource = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clCreateProgramWithSource")); assert(count == 1); size_t my_lengths[1]; my_lengths[0] = lengths[0]; -#ifdef SAVE_KERNELS char fn[0x100]; snprintf(fn, sizeof(fn), "/tmp/program_%zu.cl", strlen(strings[0])); FILE *f = fopen(fn, "wb"); @@ -433,22 +433,24 @@ cl_program clCreateProgramWithSource(cl_context context, cl_uint count, const ch } program_source[ret] = strings[0]; -#endif cl_program ret = my_clCreateProgramWithSource(context, count, strings, my_lengths, errcode_ret); return ret; } +#endif void *dlsym(void *handle, const char *symbol) { void *(*my_dlsym)(void *handle, const char *symbol) = (void *(*)(void *handle, const char *symbol))((uintptr_t)dlopen-0x2d4); if (memcmp("REAL_", symbol, 5) == 0) { return my_dlsym(handle, symbol+5); } else if (strcmp("clEnqueueNDRangeKernel", symbol) == 0) { - return (void*)clEnqueueNDRangeKernel; + return (void*)thneed_clEnqueueNDRangeKernel; } else if (strcmp("clSetKernelArg", symbol) == 0) { - return (void*)clSetKernelArg; + return (void*)thneed_clSetKernelArg; +#ifdef SAVE_KERNELS } else if (strcmp("clCreateProgramWithSource", symbol) == 0) { - return (void*)clCreateProgramWithSource; + return (void*)thneed_clCreateProgramWithSource; +#endif } else { return my_dlsym(handle, symbol); } From 2b23111e0e3eeb10019023d74f177e8e21b37cd5 Mon Sep 17 00:00:00 2001 From: Ewout ter Hoeven Date: Mon, 25 May 2020 12:19:57 +0200 Subject: [PATCH 085/656] GitHub Actions: Fix Update Pipfile.lock workflow (#1562) * Remove --requirements * Add commit-message to PRs in pipfile workflow --- .github/workflows/update-pipfile.yml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/update-pipfile.yml b/.github/workflows/update-pipfile.yml index 018eb9e12d..5fdbdddad0 100644 --- a/.github/workflows/update-pipfile.yml +++ b/.github/workflows/update-pipfile.yml @@ -5,6 +5,7 @@ on: push: paths: - 'Pipfile' + - '.github/workflows/update-pipfile.yml' jobs: piplock: @@ -14,7 +15,7 @@ jobs: - uses: actions/setup-python@v2 - run: pip install wheel - run: pip install pipenv - - run: pipenv lock --requirements + - run: pipenv lock - uses: actions/upload-artifact@v2 with: name: "Pipfile lock" @@ -23,3 +24,4 @@ jobs: with: title: "Update Pipfile.lock (dependencies)" branch: update-pipfile + commit-message: "[Bot] Update Pipfile.lock dependencies" From 84067d0b936c3431897d3b262f075c24092a1e60 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 25 May 2020 03:25:47 -0700 Subject: [PATCH 086/656] run pipfile update action at 8 pacific time --- .github/workflows/update-pipfile.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/update-pipfile.yml b/.github/workflows/update-pipfile.yml index 5fdbdddad0..391747f19b 100644 --- a/.github/workflows/update-pipfile.yml +++ b/.github/workflows/update-pipfile.yml @@ -1,7 +1,7 @@ name: "Update Pipfile.lock" on: schedule: - - cron: '00 08 * * 1' # Every monday on 08:00 UTC + - cron: '00 15 * * 1' # Every monday on 15:00 UTC push: paths: - 'Pipfile' From e73e0bc2caf3d9ef77632d3c64af0dffb16741bf Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 25 May 2020 22:15:01 -0700 Subject: [PATCH 087/656] add dependency for new CI test so test branch doesn't invalidate cache --- Dockerfile.openpilot | 1 + 1 file changed, 1 insertion(+) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 2a0b49f1c0..e5b1f2491c 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -10,6 +10,7 @@ RUN apt-get update && apt-get install -y --no-install-recommends \ libcapnp-dev \ clang \ cmake \ + cppcheck \ curl \ ffmpeg \ git \ From a63814866bfa561e3fb6a57f916f9c09e147bb30 Mon Sep 17 00:00:00 2001 From: "Tunder (Chris in RL)" <34691234+Tundergit@users.noreply.github.com> Date: Tue, 26 May 2020 09:43:05 -0700 Subject: [PATCH 088/656] add missing 2020 stinger value (#1565) 1371: 8 (not always present on startup, causes intermittent dashcam mode) --- selfdrive/car/hyundai/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index fdcfd7e7a1..b5c76a0123 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -95,7 +95,7 @@ FINGERPRINTS = { 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1384: 8, 1407: 8, 1411: 8, 1419: 8, 1425: 2, 1427: 6, 1444: 8, 1456: 4, 1470: 8, 1489: 1 }], CAR.KIA_STINGER: [{ - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8 + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8 }], CAR.GENESIS_G80: [{ 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1024: 2, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8 From d5858955ee5aa9c8fae7c9f26e7754e86353377a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 27 May 2020 00:57:14 +0800 Subject: [PATCH 089/656] reduce the scope of mutex (#1561) --- selfdrive/modeld/modeld.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 764f9aadeb..217654dc21 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -44,8 +44,7 @@ void* live_thread(void *arg) { while (!do_exit) { if (sm.update(10) > 0){ - pthread_mutex_lock(&transform_lock); - + auto extrinsic_matrix = sm["liveCalibration"].getLiveCalibration().getExtrinsicMatrix(); Eigen::Matrix extrinsic_matrix_eigen; for (int i = 0; i < 4*3; i++){ @@ -60,6 +59,7 @@ void* live_thread(void *arg) { auto warp_matrix = camera_frame_from_ground * ground_from_medmodel_frame; + pthread_mutex_lock(&transform_lock); for (int i=0; i<3*3; i++) { cur_transform.v[i] = warp_matrix(i / 3, i % 3); } From b3ab7ae3921e19c237284ec02683e739e68387f3 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 27 May 2020 00:59:49 +0800 Subject: [PATCH 090/656] change light_sensor to atomic variable (#1560) --- selfdrive/ui/ui.cc | 5 ++--- selfdrive/ui/ui.hpp | 4 ++-- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 29c866cab0..b573c3f42f 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -208,8 +208,7 @@ static void update_offroad_layout_timeout(UIState *s, int* timeout) { } static void ui_init(UIState *s) { - memset(s, 0, sizeof(UIState)); - + pthread_mutex_init(&s->lock, NULL); s->sm = new SubMaster({"model", "controlsState", "uiLayoutState", "liveCalibration", "radarState", "thermal", "health", "ubloxGnss", "driverState", "dMonitoringState", "offroadLayout" @@ -810,7 +809,7 @@ int main(int argc, char* argv[]) { zsys_handler_set(NULL); signal(SIGINT, (sighandler_t)set_do_exit); - UIState uistate; + UIState uistate = {}; UIState *s = &uistate; ui_init(s); enable_event_processing(true); diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 9d3f15fa33..3cab8ee668 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -13,7 +13,7 @@ #define NANOVG_GLES3_IMPLEMENTATION #define nvgCreate nvgCreateGLES3 #endif - +#include #include #include "nanovg.h" @@ -269,7 +269,7 @@ typedef struct UIState { bool thermal_started, preview_started; bool vision_seen; - float light_sensor; + std::atomic light_sensor; int touch_fd; From 50f3f1d3357b356c5b1144c518f35375f5bb9924 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 26 May 2020 13:27:01 -0700 Subject: [PATCH 091/656] -Werror (#1567) * werror * -Wno-inconsistent-missing-override * Silence ffmpeg deprecation warnings * add some more pragmas to ignore warnings Co-authored-by: Comma Device --- SConstruct | 8 +++----- selfdrive/controls/lib/cluster/fastcluster_dm.cpp | 4 ++-- selfdrive/loggerd/encoder.c | 5 ++++- selfdrive/loggerd/raw_logger.cc | 2 ++ selfdrive/modeld/runners/snpemodel.cc | 2 ++ selfdrive/ui/paint.cc | 11 ++++++----- selfdrive/ui/ui.cc | 8 ++++---- 7 files changed, 23 insertions(+), 17 deletions(-) diff --git a/SConstruct b/SConstruct index f6024a0f33..285a1743b6 100644 --- a/SConstruct +++ b/SConstruct @@ -106,11 +106,9 @@ env = Environment( "-g", "-fPIC", "-O2", - "-Werror=implicit-function-declaration", - "-Werror=incompatible-pointer-types", - "-Werror=int-conversion", - "-Werror=return-type", - "-Werror=format-extra-args", + "-Werror", + "-Wno-deprecated-register", + "-Wno-inconsistent-missing-override", ] + cflags + ccflags_asan, CPPPATH=cpppath + [ diff --git a/selfdrive/controls/lib/cluster/fastcluster_dm.cpp b/selfdrive/controls/lib/cluster/fastcluster_dm.cpp index 8834bc24a0..ee6670c204 100644 --- a/selfdrive/controls/lib/cluster/fastcluster_dm.cpp +++ b/selfdrive/controls/lib/cluster/fastcluster_dm.cpp @@ -49,8 +49,8 @@ #ifdef NO_INCLUDE_FENV #pragma message("Do not use fenv header.") #else -#pragma message("Use fenv header. If there is a warning about unknown #pragma STDC FENV_ACCESS, this can be ignored.") -#pragma STDC FENV_ACCESS on +//#pragma message("Use fenv header. If there is a warning about unknown #pragma STDC FENV_ACCESS, this can be ignored.") +//#pragma STDC FENV_ACCESS on #include #endif diff --git a/selfdrive/loggerd/encoder.c b/selfdrive/loggerd/encoder.c index 1509ff1130..3b9beb4d61 100644 --- a/selfdrive/loggerd/encoder.c +++ b/selfdrive/loggerd/encoder.c @@ -1,3 +1,5 @@ +#pragma clang diagnostic ignored "-Wdeprecated-declarations" + #include #include #include @@ -24,6 +26,7 @@ #include "encoder.h" + //#define ALOG(...) __android_log_print(ANDROID_LOG_VERBOSE, "omxapp", ##__VA_ARGS__) // encoder: lossey codec using hardware hevc @@ -226,7 +229,7 @@ void encoder_init(EncoderState *s, const char* filename, int width, int height, in_port.format.video.xFramerate = (s->fps * 65536); in_port.format.video.eCompressionFormat = OMX_VIDEO_CodingUnused; // in_port.format.video.eColorFormat = OMX_COLOR_FormatYUV420SemiPlanar; - in_port.format.video.eColorFormat = QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m; + in_port.format.video.eColorFormat = (OMX_COLOR_FORMATTYPE)QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m; err = OMX_SetParameter(s->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port); diff --git a/selfdrive/loggerd/raw_logger.cc b/selfdrive/loggerd/raw_logger.cc index 37b3f28428..d9fc289ded 100644 --- a/selfdrive/loggerd/raw_logger.cc +++ b/selfdrive/loggerd/raw_logger.cc @@ -1,3 +1,5 @@ +#pragma clang diagnostic ignored "-Wdeprecated-declarations" + #include #include #include diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 4f3d8f58a3..19740f9a93 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -1,3 +1,5 @@ +#pragma clang diagnostic ignored "-Wexceptions" + #include #include #include "common/util.h" diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index ff1db9a251..588f20c3a6 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -1,6 +1,7 @@ #include "ui.hpp" #include #include +#include #include "common/util.h" #define NANOVG_GLES3_IMPLEMENTATION @@ -396,7 +397,7 @@ static void ui_draw_world(UIState *s) { if (scene->lead_status) { draw_lead(s, scene->lead_d_rel, scene->lead_v_rel, scene->lead_y_rel); } - if ((scene->lead_status2) && (fabs(scene->lead_d_rel - scene->lead_d_rel2) > 3.0)) { + if ((scene->lead_status2) && (std::abs(scene->lead_d_rel - scene->lead_d_rel2) > 3.0)) { draw_lead(s, scene->lead_d_rel2, scene->lead_v_rel2, scene->lead_y_rel2); } nvgRestore(s->vg); @@ -617,9 +618,9 @@ static void ui_draw_driver_view(UIState *s) { } else { fbox_x = valid_frame_x + valid_frame_w - box_h / 2 + (scene->face_x + 0.5) * (box_h / 2) - 0.5 * 0.6 * box_h / 2; } - if (abs(scene->face_x) <= 0.35 && abs(scene->face_y) <= 0.4) { + if (std::abs(scene->face_x) <= 0.35 && std::abs(scene->face_y) <= 0.4) { ui_draw_rect(s->vg, fbox_x, fbox_y, 0.6 * box_h / 2, 0.6 * box_h / 2, - nvgRGBAf(1.0, 1.0, 1.0, 0.8 - ((abs(scene->face_x) > abs(scene->face_y) ? abs(scene->face_x) : abs(scene->face_y))) * 0.6 / 0.375), + nvgRGBAf(1.0, 1.0, 1.0, 0.8 - ((std::abs(scene->face_x) > std::abs(scene->face_y) ? std::abs(scene->face_x) : std::abs(scene->face_y))) * 0.6 / 0.375), 35, 10); } else { ui_draw_rect(s->vg, fbox_x, fbox_y, 0.6 * box_h / 2, 0.6 * box_h / 2, nvgRGBAf(1.0, 1.0, 1.0, 0.2), 35, 10); @@ -959,9 +960,9 @@ void ui_nvg_init(UIState *s) { s->rear_frame_mat = matmul(device_transform, frame_transform); for(int i = 0;i < UI_BUF_COUNT; i++) { - s->khr[i] = NULL; + s->khr[i] = 0; s->priv_hnds[i] = NULL; - s->khr_front[i] = NULL; + s->khr_front[i] = 0; s->priv_hnds_front[i] = NULL; } } diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index b573c3f42f..fa33e9cf6c 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -208,7 +208,7 @@ static void update_offroad_layout_timeout(UIState *s, int* timeout) { } static void ui_init(UIState *s) { - + pthread_mutex_init(&s->lock, NULL); s->sm = new SubMaster({"model", "controlsState", "uiLayoutState", "liveCalibration", "radarState", "thermal", "health", "ubloxGnss", "driverState", "dMonitoringState", "offroadLayout" @@ -426,7 +426,7 @@ void handle_message(UIState *s, SubMaster &sm) { // scene.mpc_y[i] = y_list[i]; // } // s->livempc_or_radarstate_changed = true; - // } + // } if (sm.updated("uiLayoutState")) { auto data = sm["uiLayoutState"].getUiLayoutState(); s->active_app = data.getActiveApp(); @@ -511,7 +511,7 @@ static void ui_update(UIState *s) { // do this here for now in lieu of a run_on_main_thread event for (int i=0; ikhr[i] != NULL) { + if(s->khr[i] != 0) { visionimg_destroy_gl(s->khr[i], s->priv_hnds[i]); glDeleteTextures(1, &s->frame_texs[i]); } @@ -541,7 +541,7 @@ static void ui_update(UIState *s) { } for (int i=0; ikhr_front[i] != NULL) { + if(s->khr_front[i] != 0) { visionimg_destroy_gl(s->khr_front[i], s->priv_hnds_front[i]); glDeleteTextures(1, &s->frame_front_texs[i]); } From 4de2c57bd104b18557a0364f7b3e08aa1df45827 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 26 May 2020 13:41:02 -0700 Subject: [PATCH 092/656] Fix #1566, athena status flicker in sidebar --- selfdrive/ui/ui.cc | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index fa33e9cf6c..c4daf3591c 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -185,7 +185,7 @@ static void read_param_float_timeout(float* param, const char* param_name, int* static int read_param_uint64_timeout(uint64_t* dest, const char* param_name, int* timeout, bool persistent_param = false) { if (*timeout > 0){ (*timeout)--; - return 0; + return -1; } else { *timeout = 2 * UI_FREQ; // 0.5Hz return read_param_uint64(dest, param_name, persistent_param); @@ -976,12 +976,14 @@ int main(int argc, char* argv[]) { read_param_bool_timeout(&s->limit_set_speed, "LimitSetSpeed", &s->limit_set_speed_timeout); read_param_float_timeout(&s->speed_lim_off, "SpeedLimitOffset", &s->limit_set_speed_timeout); int param_read = read_param_uint64_timeout(&s->last_athena_ping, "LastAthenaPingTime", &s->last_athena_ping_timeout); - if (param_read != 0) { - s->scene.athenaStatus = NET_DISCONNECTED; - } else if (nanos_since_boot() - s->last_athena_ping < 70e9) { - s->scene.athenaStatus = NET_CONNECTED; - } else { - s->scene.athenaStatus = NET_ERROR; + if (param_read != -1) { // Param was updated this loop + if (param_read != 0) { // Failed to read param + s->scene.athenaStatus = NET_DISCONNECTED; + } else if (nanos_since_boot() - s->last_athena_ping < 70e9) { + s->scene.athenaStatus = NET_CONNECTED; + } else { + s->scene.athenaStatus = NET_ERROR; + } } update_offroad_layout_timeout(s, &s->offroad_layout_timeout); From ac8617581e07f4b5f960ba97cb931ebad7606906 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Tue, 26 May 2020 13:43:30 -0700 Subject: [PATCH 093/656] Update Pipfile.lock (dependencies) (#1563) * [Bot] Update Pipfile.lock dependencies * trigger ci Co-authored-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: Willem Melching --- Pipfile.lock | 159 ++++++++++++++++++++++++--------------------------- 1 file changed, 76 insertions(+), 83 deletions(-) diff --git a/Pipfile.lock b/Pipfile.lock index c3d18686df..e8c8955f0f 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -127,50 +127,42 @@ }, "cython": { "hashes": [ - "sha256:015f7d66d0cf72e2863dcd380d9613a0baf53bb4c572fdffff873b26d2da2d6c", - "sha256:048bc66902e7ca6af9d8146cfc700a66514bea711d9496b26df5eeee64a35010", - "sha256:15732423a5c7d6e7c400fdbc00121f48ca17e8ff1f76d6d10eeff5be3d270605", - "sha256:16160de2d02cf5f9987478cee428146d8a0509315eb8b523ad5e29d460582d2e", - "sha256:1ae4f5e8ede955fe3fad216d667b8c6d6a58d21dbbe5484fccafd8dd631ef313", - "sha256:297b2821bf11ba65667f9616fe48dbc40468158e745cefccd8b175825ad1265b", - "sha256:2b0aef8336036e6ea418cb728f56f2da39388649e722a1b622ae347ea7f18415", - "sha256:3d04a59991c6e51fd49608b4c7310bf501602cb9786d4e9c35b62ddfc7d735cc", - "sha256:3f11838f66e988dc13c91c8ea2e82a2bc5754eb4251920f512f1707a7cf7443a", - "sha256:427a718f2d435e7d5fde7878e9b331911dfeb660d5778e4e3ec1c5b09a05e4b7", - "sha256:4475245552b763066a3b811fc1d4619b3675afd64405734474fa51d2ef1b57b4", - "sha256:46e9ab055eb64595f160b61037c3e65ce0b01320d144a3a53eb807000078d53f", - "sha256:4aa23cc6aec04e339d112549b51d89326a1ac89075b8f2e2ad3436723fdb1b96", - "sha256:54de099507d6705a27de9e8cad629636c18b05a8d6e276537f91c9c58d632b38", - "sha256:5546b0f1e0c84c4c241a3679f6a5e27d0bbd29542e91e7a58030162ea987a7f0", - "sha256:59f462ad92cbb8f3832516f4c2812485138aa403e3bc9815f517841649b22724", - "sha256:6ff21c1b16817cb90dae33ce65cf2855ee76bcb0e70bd03887dedf8b553a95ba", - "sha256:7720445e2a53a0634d64a6c405a5f818d398136280d23e73d3ff5727ee16b596", - "sha256:7aef66dfcf908893da5bf22747137455c0714a0c78d17847b2918be2542c597f", - "sha256:7bf0881d2277b23652c74855776791e5f2aecfb89998c98764532770d130c863", - "sha256:801ecb4c646ecf32dfe9eb84568a12f2371ab71d64d42f3b914b497f6b843459", - "sha256:81351cf2f055064e40f360705f05ae931e987d8933bc6d746f7c7331b98bceba", - "sha256:bc1af976b82b8891e473857fdbfd08ec937fd4960bfdf2b59bc338f6d45ecec8", - "sha256:c489b1ba691f0a79b8c2824332210177cde6ef24439082790143371ca8670edf", - "sha256:c76eae1fb343332617bb997e2a3da242a36791f8890e91272cc159f01dda0705", - "sha256:c7ac0b16761034fe2e0c48caedc7a5b1f56a5bf845718f921b4788d2047db1bc", - "sha256:d3a02c0bd96c6a9ce064eff4c6f198c2c2a3e1e89c1aeb2f9bec4340edd98938", - "sha256:d6918608d55b7f59dfeebcdf7549aab2b9e47db498f6f1fa0133ecf8ebf088ae", - "sha256:d6fdd0d5510ba3b4f50ec44c047815e58be4c7588624ab156d02fbaaa04aa7f9", - "sha256:d77a7f45d55755eae528a4c44f7ece2b0bbfbe191a3bf2275b90562bad78db0e", - "sha256:d9778569f848aedbab8c953453346e508e2d7d0f3288936435c863ca8c44d038", - "sha256:de70eface4532aafa045008f23eded89044b7af1d298b28e0601cf0b07febe28", - "sha256:fbde5e13f0c5c8607661f9b9abb337e8a12dd52d13f7cb2a28ff5ffbfb3b5279" - ], - "index": "pypi", - "version": "==0.29.18" + "sha256:00348a2675b53282535aa22c4d444076b08010aa47f4bf10622542c213c37452", + "sha256:0fa549d45e8aa658e270a7e85a0e7b8bf7b3dfdc59fcd4f4dbf54d854f4abdb5", + "sha256:111941da36709f53170af6b0f81ec3df883364ff02d20f742e815b27ea37dfa0", + "sha256:22b7c38d3f1af1bc7906b1a7b42354b4cf47d36bbdf687a581a050e72ddd249b", + "sha256:29960b4c2789a9d6024be5fff75a55e52ae7f32d265fe52c0e40414f20d4d6db", + "sha256:32ae95d3c3fe4dbb5d3f430accdc93247e2204791f4f70a5f2a8fac2d3105524", + "sha256:381f8570ab287670c14f8138591788c1a801b185899939d08f4c60c284b4940d", + "sha256:44d9acf4dd75d66b456c21d2ee0bcea3b49065775aa955a11be62a64fc5210ec", + "sha256:4b971daa8c05c3277c4c7be4be5e7cd2e4971377ca752563c55a1c1f88d819c8", + "sha256:58598e9a35cb89916c2fd80c0b2f4b7443542281f804206e90eae7f9acb79b81", + "sha256:61bff7ae850986ebdf8b7fb01c63be94e75ba73f2dcbc9338ca687ff810488b8", + "sha256:69ae45714b1fd5ebb309d787c278b5316cb504b287dae95456ccf50d8c55f537", + "sha256:7a1ebe4f811ce0c1642d432ef8ae9bea1db93c7215eb1e95eb4bcb7503a42107", + "sha256:8418a201c229f8af7eae11b3d22df699a37cfe934a113e032d59369a13a7ef13", + "sha256:97f98a7dc0d58ea833dc1f8f8b3ce07adf4c0f030d1886c5399a2135ed415258", + "sha256:9fde858f57952c9e55fae20cffeaf0bd5554a0630f0bd537879e57e60d8f105f", + "sha256:ad5abd7ee54f48be7efa95f4ad0d7df44a84970d57330b151a049642ffc1705b", + "sha256:b31f3dc2931b84c99d0038013304986cd690f5debb8471dbba1ca8584601b230", + "sha256:c50fa9238c37b43d17234c8083371f4d4da208153d13f86d9db8925c16bb2850", + "sha256:cd262da047a60f0d90fa83d6416e901519a5de6d4d68218d62dcb15f12fdcb1b", + "sha256:e7838dadab758a7caa4f726e523930d491dbc4f93c4a01d9de6828f342ea1188", + "sha256:edf5b76f6fff07f236510bb578b6ba6387e534af9ecdbe7892c591dbe1ea3314", + "sha256:ee9a913482dfc5a62242ea66abff93f3dbe28729bce590014c8445e39af3d95c", + "sha256:f4bb0e06a463cc280562cc54e53fefb2bf14b0b8d00c042781c71f17e78b1847", + "sha256:ffd24c9bd35127138215f56ad833db1966cdc47ac659a31bde96949018e477c2" + ], + "index": "pypi", + "version": "==0.29.19" }, "flake8": { "hashes": [ - "sha256:6c1193b0c3f853ef763969238f6c81e9e63ace9d024518edc020d5f1d6d93195", - "sha256:ea6623797bf9a52f4c9577d780da0bb17d65f870213f7b5bcc9fca82540c31d5" + "sha256:c69ac1668e434d37a2d2880b3ca9aafd54b3a10a3ac1ab101d22f29e29cf8634", + "sha256:ccaa799ef9893cebe69fdfefed76865aeaefbb94cb8545617b2298786a4de9a5" ], "index": "pypi", - "version": "==3.8.1" + "version": "==3.8.2" }, "flask": { "hashes": [ @@ -582,11 +574,11 @@ }, "six": { "hashes": [ - "sha256:236bdbdce46e6e6a3d61a337c0f8b763ca1e8717c03b369e87a7ec7ce1319c0a", - "sha256:8f3cd2e254d8f793e7f3d6d9df77b92252b52637291d0f0da013c76ea2724b6c" + "sha256:30639c035cdb23534cd4aa2dd52c3bf48f06e5f4a941509c8bafd8ce11080259", + "sha256:8b74bedcbbbaca38ff6d7491d76f2b06b3592611af620f8426e82dddb04a5ced" ], "index": "pypi", - "version": "==1.14.0" + "version": "==1.15.0" }, "smbus2": { "hashes": [ @@ -597,11 +589,11 @@ }, "sympy": { "hashes": [ - "sha256:4880d3a351558063bd89febda302f220dc4b88de393bba81fa6539a3966f03fa", - "sha256:d77901d748287d15281f5ffe5b0fef62dd38f357c2b827c44ff07f35695f4e7e" + "sha256:7af1e11e9fcb72362c47a481dc010e518cfcb60a594d1ee8bd268f86ea7d6cbf", + "sha256:9769e3d2952e211b1245f1d0dfdbfbdde1f7779a3953832b7dd2b88a21ca6cc6" ], "index": "pypi", - "version": "==1.5.1" + "version": "==1.6" }, "toml": { "hashes": [ @@ -879,18 +871,18 @@ }, "boto3": { "hashes": [ - "sha256:3c740de27ca113bcdbf5449d6d221428e5bc529e8e7d8e7dd87790602078c333", - "sha256:a396e514eb6ee57994718a7c85d3810bfda23faba01dd80c65e0aba6a5dedb1f" + "sha256:2a97c9e8fd2c0f8d8a92262a0ccbd00aad8c4786acb74f620f54164070cb72ff", + "sha256:650d67b0d47b7bc0d79f04cc944506823dbbc2f76f60e64ce6d7cdd89f60a2eb" ], "index": "pypi", - "version": "==1.13.13" + "version": "==1.13.16" }, "botocore": { "hashes": [ - "sha256:5227e7a6d9d88560bae22149dc0d87b71679cf9c63ad79bf37bb2b7cd8e07db0", - "sha256:babc267e4ff043f3e722f9b0103fd808934519f9148ef7360c255d1aefcb96d7" + "sha256:0275023d023f0e3f9c27e5f23c437dd09ee715577cc628cf724e8bfbba2b459e", + "sha256:70d52f606bab2867971c0ea0c7723a769d81aa3cfd09f819d2b56e186e64ea0b" ], - "version": "==1.16.13" + "version": "==1.16.16" }, "cachetools": { "hashes": [ @@ -1337,11 +1329,11 @@ }, "ipykernel": { "hashes": [ - "sha256:003c9c1ab6ff87d11f531fee2b9ca59affab19676fc6b2c21da329aef6e73499", - "sha256:2937373c356fa5b634edb175c5ea0e4b25de8008f7c194f2d49cfbd1f9c970a8" + "sha256:731adb3f2c4ebcaff52e10a855ddc87670359a89c9c784d711e62d66fccdafae", + "sha256:a8362e3ae365023ca458effe93b026b8cdadc0b73ff3031472128dd8a2cf0289" ], "index": "pypi", - "version": "==5.2.1" + "version": "==5.3.0" }, "ipython": { "hashes": [ @@ -1935,9 +1927,10 @@ }, "prometheus-client": { "hashes": [ - "sha256:71cd24a2b3eb335cb800c7159f423df1bd4dcd5171b234be15e3f31ec9f622da" + "sha256:983c7ac4b47478720db338f1491ef67a100b474e3bc7dafcbaefb7d0b8f9b01c", + "sha256:c6e6b706833a6bd1fd51711299edee907857be10ece535126a158f911ee80915" ], - "version": "==0.7.1" + "version": "==0.8.0" }, "prompt-toolkit": { "hashes": [ @@ -1948,24 +1941,24 @@ }, "protobuf": { "hashes": [ - "sha256:00c2c276aca3af220d422e6a8625b1f5399c821c9b6f1c83e8a535aa8f48cc6c", - "sha256:0d69d76b00d0eb5124cb33a34a793383a5bbbf9ac3e633207c09988717c5da85", - "sha256:1c55277377dd35e508e9d86c67a545f6d8d242d792af487678eeb75c07974ee2", - "sha256:35bc1b96241b8ea66dbf386547ef2e042d73dcc0bf4b63566e3ef68722bb24d1", - "sha256:47a541ac44f2dcc8d49b615bcf3ed7ba4f33af9791118cecc3d17815fab652d9", - "sha256:61364bcd2d85277ab6155bb7c5267e6a64786a919f1a991e29eb536aa5330a3d", - "sha256:7aaa820d629f8a196763dd5ba21fd272fa038f775a845a52e21fa67862abcd35", - "sha256:9593a6cdfc491f2caf62adb1c03170e9e8748d0a69faa2b3970e39a92fbd05a2", - "sha256:95f035bbafec7dbaa0f1c72eda8108b763c1671fcb6e577e93da2d52eb47fbcf", - "sha256:9d6a517ce33cbdc64b52a17c56ce17b0b20679c945ed7420e7c6bc6686ff0494", - "sha256:a7532d971e4ab2019a9f6aa224b209756b6b9e702940ca85a4b1ed1d03f45396", - "sha256:b4e8ecb1eb3d011f0ccc13f8bb0a2d481aa05b733e6e22e9d46a3f61dbbef0de", - "sha256:bb1aced9dcebc46f0b320f24222cc8ffdfd2e47d2bafd4d2e5913cc6f7e3fc98", - "sha256:ccce142ebcfbc35643a5012cf398497eb18e8d021333cced4d5401f034a8cef5", - "sha256:d538eecc0b80accfb73c8167f39aaa167a5a50f31b1295244578c8eff8e9d602", - "sha256:eab18765eb5c7bad1b2de7ae3774192b46e1873011682e36bcd70ccf75f2748a" - ], - "version": "==3.12.0" + "sha256:04d0b2bd99050d09393875a5a25fd12337b17f3ac2e29c0c1b8e65b277cbfe72", + "sha256:05288e44638e91498f13127a3699a6528dec6f9d3084d60959d721bfb9ea5b98", + "sha256:175d85370947f89e33b3da93f4ccdda3f326bebe3e599df5915ceb7f804cd9df", + "sha256:440a8c77531b3652f24999b249256ed01fd44c498ab0973843066681bd276685", + "sha256:49fb6fab19cd3f30fa0e976eeedcbf2558e9061e5fa65b4fe51ded1f4002e04d", + "sha256:4c7cae1f56056a4a2a2e3b00b26ab8550eae738bd9548f4ea0c2fcb88ed76ae5", + "sha256:519abfacbb421c3591d26e8daf7a4957763428db7267f7207e3693e29f6978db", + "sha256:60f32af25620abc4d7928d8197f9f25d49d558c5959aa1e08c686f974ac0b71a", + "sha256:613ac49f6db266fba243daf60fb32af107cfe3678e5c003bb40a381b6786389d", + "sha256:954bb14816edd24e746ba1a6b2d48c43576393bbde2fb8e1e3bd6d4504c7feac", + "sha256:9b1462c033a2cee7f4e8eb396905c69de2c532c3b835ff8f71f8e5fb77c38023", + "sha256:c0767f4d93ce4288475afe0571663c78870924f1f8881efd5406c10f070c75e4", + "sha256:c45f5980ce32879391144b5766120fd7b8803129f127ce36bd060dd38824801f", + "sha256:eeb7502f59e889a88bcb59f299493e215d1864f3d75335ea04a413004eb4fe24", + "sha256:fdb1742f883ee4662e39fcc5916f2725fec36a5191a52123fec60f8c53b70495", + "sha256:fe554066c4962c2db0a1d4752655223eb948d2bfa0fb1c4a7f2c00ec07324f1c" + ], + "version": "==3.12.1" }, "ptyprocess": { "hashes": [ @@ -2248,10 +2241,10 @@ }, "python-engineio": { "hashes": [ - "sha256:222926adb4bc6e03a8fc8e0ef2a3309f030c1c3f8e0fcc94c9ba214574565f02", - "sha256:2481732d93646998f7372ef0ecf003af7817b82720b881db173c3d50b4887916" + "sha256:2da5e1e5565e170a17169d1a76eb6a099cc96f0a25a5b1e0f9785f151485daea", + "sha256:5423045623f094df67ace05d53737b88e39395ac3b1129798a31be2dbc6011cf" ], - "version": "==3.12.1" + "version": "==3.13.0" }, "python-logstash": { "hashes": [ @@ -2270,10 +2263,10 @@ }, "python-socketio": { "hashes": [ - "sha256:149b98c33f8c3d09273fb4ebeb83781e4dc9411b56b27d9f058bec1bd1ed74b7", - "sha256:81280cbbb7018d8ecdd006bf6025979733d347c0f2612282c1e21f6ed7d3b55b" + "sha256:358d8fbbc029c4538ea25bcaa283e47f375be0017fcba829de8a3a731c9df25a", + "sha256:d437f797c44b6efba2f201867cf02b8c96b97dff26d4e4281ac08b45817cd522" ], - "version": "==4.5.1" + "version": "==4.6.0" }, "pytz": { "hashes": [ @@ -2535,11 +2528,11 @@ }, "six": { "hashes": [ - "sha256:236bdbdce46e6e6a3d61a337c0f8b763ca1e8717c03b369e87a7ec7ce1319c0a", - "sha256:8f3cd2e254d8f793e7f3d6d9df77b92252b52637291d0f0da013c76ea2724b6c" + "sha256:30639c035cdb23534cd4aa2dd52c3bf48f06e5f4a941509c8bafd8ce11080259", + "sha256:8b74bedcbbbaca38ff6d7491d76f2b06b3592611af620f8426e82dddb04a5ced" ], "index": "pypi", - "version": "==1.14.0" + "version": "==1.15.0" }, "sqlalchemy": { "hashes": [ From dd16990952980bfd5c8eac919309052be084a7ee Mon Sep 17 00:00:00 2001 From: Thaixican Date: Tue, 26 May 2020 13:49:18 -0700 Subject: [PATCH 094/656] Add 2020 Lexus RX Hybrid support (#1547) * Add 2020 Lexus RX Hybrid support * Add 2020 Lexus RX Hybrid to IGNORED_FINGERPRINTS and route to test_car_models per @pd0wm --- README.md | 1 + selfdrive/car/toyota/interface.py | 10 ++++++++++ selfdrive/car/toyota/values.py | 32 +++++++++++++++++++++++++++---- selfdrive/test/test_car_models.py | 5 +++++ 4 files changed, 44 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 4f653b45a3..bd3c791ea3 100644 --- a/README.md +++ b/README.md @@ -91,6 +91,7 @@ Supported Cars | Lexus | RX 2016-17 | All | Stock3| 0mph | 0mph | | Lexus | RX 2020 | All | openpilot | 0mph | 0mph | | Lexus | RX Hybrid 2016-19 | All | Stock3| 0mph | 0mph | +| Lexus | RX Hybrid 2020 | All | openpilot | 0mph | 0mph | | Toyota | Avalon 2016 | TSS-P | Stock3| 20mph1 | 0mph | | Toyota | Avalon 2017-18 | All | Stock3| 20mph1 | 0mph | | Toyota | Camry 2018-20 | All | Stock | 0mph4 | 0mph | diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 8c8161f6ab..78c4285573 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -101,6 +101,16 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] ret.lateralTuning.pid.kf = 0.00007818594 + elif candidate == CAR.LEXUS_RXH_TSS2: + stop_and_go = True + ret.safetyParam = 73 + ret.wheelbase = 2.79 + ret.steerRatio = 16.0 # 14.8 is spec end-to-end + tire_stiffness_factor = 0.444 # not optimized yet + ret.mass = 4481.0 * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.15]] + ret.lateralTuning.pid.kf = 0.00007818594 + elif candidate in [CAR.CHR, CAR.CHRH]: stop_and_go = True ret.safetyParam = 73 diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index c563cf6568..8b64181538 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -17,6 +17,7 @@ class CAR: LEXUS_RX = "LEXUS RX 350 2016" LEXUS_RXH = "LEXUS RX HYBRID 2017" LEXUS_RX_TSS2 = "LEXUS RX350 2020" + LEXUS_RXH_TSS2 = "LEXUS RX450 HYBRID 2020" CHR = "TOYOTA C-HR 2018" CHRH = "TOYOTA C-HR HYBRID 2018" CAMRY = "TOYOTA CAMRY 2018" @@ -133,6 +134,11 @@ FINGERPRINTS = { { 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 740: 5, 742: 8, 743: 8, 764: 8, 765: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8,1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594:8, 1595: 8, 1600: 8, 1649: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 }], + CAR.LEXUS_RXH_TSS2: [ + # 2020 Lexus RX 450h + { + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 744: 8, 764: 8, 765: 8, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 942: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 987: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1600: 8, 1649: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1792: 8, 1808: 8, 1809: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1937: 8, 1940: 8, 1941: 8, 1945: 8, 1948: 8, 1949: 8, 1952: 8, 1953: 8, 1956: 8, 1960: 8, 1961: 8, 1968: 8, 1976: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8, 2015: 8, 2016: 8, 2024: 8 + }], CAR.CHR: [{ 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 705: 8, 740: 5, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 913: 8, 918: 8, 921: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8 }], @@ -261,7 +267,7 @@ FINGERPRINTS = { } # Don't use theses fingerprints for fingerprinting, they are still needed for ECU detection -IGNORED_FINGERPRINTS = [CAR.RAV4H_TSS2, CAR.HIGHLANDERH_TSS2] +IGNORED_FINGERPRINTS = [CAR.RAV4H_TSS2, CAR.HIGHLANDERH_TSS2, CAR.LEXUS_RXH_TSS2] FW_VERSIONS = { CAR.AVALON: { @@ -873,6 +879,23 @@ FW_VERSIONS = { b'8646F4809000\x00\x00\x00\x00', ], }, + CAR.LEXUS_RXH_TSS2: { + (Ecu.engine, 0x7e0, None): [ + b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x7b0, None): [ + b'F152648831\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B48271\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + ], + }, } STEER_THRESHOLD = 100 @@ -885,6 +908,7 @@ DBC = { CAR.LEXUS_RX: dbc_dict('lexus_rx_350_2016_pt_generated', 'toyota_adas'), CAR.LEXUS_RXH: dbc_dict('lexus_rx_hybrid_2017_pt_generated', 'toyota_adas'), CAR.LEXUS_RX_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), + CAR.LEXUS_RXH_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), CAR.CHR: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), CAR.CHRH: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_adas'), CAR.CAMRY: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), @@ -906,6 +930,6 @@ DBC = { CAR.LEXUS_NXH: dbc_dict('lexus_nx300h_2018_pt_generated', 'toyota_adas'), } -NO_DSU_CAR = [CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH, CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2] -TSS2_CAR = [CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2] -NO_STOP_TIMER_CAR = [CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.SIENNA, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2] # no resume button press required +NO_DSU_CAR = [CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH, CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2] +TSS2_CAR = [CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2] +NO_STOP_TIMER_CAR = [CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.SIENNA, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2] # no resume button press required diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index cd98a4d903..ca817a443c 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -303,6 +303,11 @@ routes = { 'carFingerprint': TOYOTA.LEXUS_RX_TSS2, 'enableCamera': True, 'fingerprintSource': 'fixed', + }, + "b74758c690a49668|2020-05-20--15-58-57": { + 'carFingerprint': TOYOTA.LEXUS_RXH_TSS2, + 'enableCamera': True, + 'fingerprintSource': 'fixed', }, "ec429c0f37564e3c|2020-02-01--17-28-12": { 'carFingerprint': TOYOTA.LEXUS_NXH, From 38f0846b6452a2ce4a3722b9f29b9675e978a435 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 26 May 2020 16:09:10 -0700 Subject: [PATCH 095/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 0657064594..b48c74c2e9 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 06570645941c33a5d83808606b0559e9943fd7b2 +Subproject commit b48c74c2e94fda21792c7afe8832a2e03e29a2bd From 2ecc7d9f6f85818765da23cfac614d186111abb7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 26 May 2020 17:53:55 -0700 Subject: [PATCH 096/656] Fix blank mdMonoTime and controlsStateMonoTime in radard --- selfdrive/controls/radard.py | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 0b8523313f..116968143d 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -91,9 +91,6 @@ class RadarD(): self.tracks = defaultdict(dict) self.kalman_params = KalmanParams(radar_ts) - self.last_md_ts = 0 - self.last_controls_state_ts = 0 - self.active = 0 # v_ego @@ -165,10 +162,10 @@ class RadarD(): # *** publish radarState *** dat = messaging.new_message('radarState') dat.valid = sm.all_alive_and_valid(service_list=['controlsState', 'model']) - dat.radarState.mdMonoTime = self.last_md_ts + dat.radarState.mdMonoTime = sm.logMonoTime['model'] dat.radarState.canMonoTimes = list(rr.canMonoTimes) dat.radarState.radarErrors = list(rr.errors) - dat.radarState.controlsStateMonoTime = self.last_controls_state_ts + dat.radarState.controlsStateMonoTime = sm.logMonoTime['controlsState'] if has_radar: dat.radarState.leadOne = get_lead(self.v_ego, self.ready, clusters, sm['model'].lead, low_speed_override=True) From a1ffcdd2535b82ff1883879bd53a16f17042419f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 26 May 2020 18:12:12 -0700 Subject: [PATCH 097/656] update refs after radarState fields populated --- selfdrive/test/process_replay/ref_commit | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 012e6ca16c..9f87784143 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -dadb4f96017c4f6b36fd829c41315b0a7f31c8e5 \ No newline at end of file +2ecc7d9f6f85818765da23cfac614d186111abb7 \ No newline at end of file From c78602e8ccf242be6f8a1806ba9e2f0e4f79275b Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Tue, 26 May 2020 20:48:41 -0700 Subject: [PATCH 098/656] Remove incomplete Hyundai Ioniq port (#1570) --- README.md | 2 -- selfdrive/car/hyundai/interface.py | 18 ------------------ selfdrive/car/hyundai/values.py | 12 +----------- selfdrive/test/test_car_models.py | 2 -- 4 files changed, 1 insertion(+), 33 deletions(-) diff --git a/README.md b/README.md index bd3c791ea3..8da9b06c30 100644 --- a/README.md +++ b/README.md @@ -141,8 +141,6 @@ Community Maintained Cars and Features | Holden | Astra 20171 | Adaptive Cruise | openpilot | 0mph | 7mph | | Hyundai | Elantra 2017-192 | SCC + LKAS | Stock | 19mph | 34mph | | Hyundai | Genesis 2015-162 | SCC + LKAS | Stock | 19mph | 37mph | -| Hyundai | Ioniq 20172 | SCC + LKAS | Stock | 0mph | 32mph | -| Hyundai | Ioniq 2019 Electric | SCC + LKAS | Stock | 0mph | 32mph | | Hyundai | Kona 2017-192 | SCC + LKAS | Stock | 22mph | 0mph | | Hyundai | Kona 2019 EV2 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Palisade 20202 | All | Stock | 0mph | 0mph | diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index a45706e6dd..598a52e5e7 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -117,15 +117,6 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate == CAR.IONIQ: - ret.lateralTuning.pid.kf = 0.00006 - ret.mass = 1275. + STD_CARGO_KG - ret.wheelbase = 2.7 - ret.steerRatio = 13.73 #Spec - tire_stiffness_factor = 0.385 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.KONA_EV: ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1685. + STD_CARGO_KG @@ -134,15 +125,6 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate == CAR.IONIQ_EV_LTD: - ret.lateralTuning.pid.kf = 0.00006 - ret.mass = 1490. + STD_CARGO_KG #weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx - ret.wheelbase = 2.7 - ret.steerRatio = 13.73 #Spec - tire_stiffness_factor = 0.385 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.KIA_FORTE: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3558. * CV.LB_TO_KG diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index b5c76a0123..307e1a4293 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -18,8 +18,6 @@ class CAR: GENESIS_G80 = "GENESIS G80 2017" GENESIS_G90 = "GENESIS G90 2017" HYUNDAI_GENESIS = "HYUNDAI GENESIS 2015-2016" - IONIQ = "HYUNDAI IONIQ HYBRID PREMIUM 2017" - IONIQ_EV_LTD = "HYUNDAI IONIQ ELECTRIC LIMITED 2019" KIA_FORTE = "KIA FORTE E 2018" KIA_OPTIMA = "KIA OPTIMA SX 2019 & 2016" KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019" @@ -109,12 +107,6 @@ FINGERPRINTS = { CAR.GENESIS_G90: [{ 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1162: 4, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2003: 8, 2004: 8, 2005: 8, 2008: 8, 2011: 8, 2012: 8, 2013: 8 }], - CAR.IONIQ: [{ - 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576: 8, 593: 8, 688: 5, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1173: 8, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1322: 8, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470:8, 1476: 8, 1535: 8 - }], - CAR.IONIQ_EV_LTD: [{ - 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1425: 2, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1507: 8, 1535: 8 - }], CAR.KONA: [{ 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 909: 8, 916: 8, 1040: 8, 1078: 4, 1107: 5, 1136: 8, 1156: 8, 1170: 8, 1173: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8,1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 2004: 8, 2009: 8, 2012: 8 }], @@ -158,7 +150,7 @@ CHECKSUM = { FEATURES = { "use_cluster_gears": [CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30], # Use Cluster for Gear Selection, rather than Transmission "use_tcu_gears": [CAR.KIA_OPTIMA, CAR.SONATA_2019], # Use TCU Message for Gear Selection - "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV], # Use TCU Message for Gear Selection + "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.KONA_EV], # Use TCU Message for Gear Selection } DBC = { @@ -167,8 +159,6 @@ DBC = { CAR.GENESIS_G80: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G90: dbc_dict('hyundai_kia_generic', None), CAR.HYUNDAI_GENESIS: dbc_dict('hyundai_kia_generic', None), - CAR.IONIQ: dbc_dict('hyundai_kia_generic', None), - CAR.IONIQ_EV_LTD: dbc_dict('hyundai_kia_generic', None), CAR.KIA_FORTE: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index ca817a443c..954f204188 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -390,8 +390,6 @@ non_tested_cars = [ HYUNDAI.GENESIS_G80, HYUNDAI.GENESIS_G90, HYUNDAI.HYUNDAI_GENESIS, - HYUNDAI.IONIQ, - HYUNDAI.IONIQ_EV_LTD, HYUNDAI.KIA_FORTE, HYUNDAI.KIA_OPTIMA, HYUNDAI.KIA_OPTIMA_H, From 7c8d6cbdeff7b6c7ea5af9c4ed8843fea97c58a1 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 26 May 2020 20:49:14 -0700 Subject: [PATCH 099/656] pure init (#1569) --- common/transformations/coordinates.py | 2 ++ selfdrive/locationd/models/gnss_kf.py | 9 +++++---- selfdrive/locationd/models/live_kf.py | 2 +- selfdrive/locationd/models/loc_kf.py | 8 ++++---- 4 files changed, 12 insertions(+), 9 deletions(-) diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index 864bc4d807..c5d76b6e0b 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -78,6 +78,8 @@ class LocalCoord(): [-np.sin(lat)*np.sin(lon), np.cos(lon), -np.cos(lat)*np.sin(lon)], [np.cos(lat), 0, -np.sin(lat)]]) self.ecef2ned_matrix = self.ned2ecef_matrix.T + self.ecef_from_ned_matrix = self.ned2ecef_matrix + self.ned_from_ecef_matrix = self.ecef2ned_matrix @classmethod def from_geodetic(cls, init_geodetic): diff --git a/selfdrive/locationd/models/gnss_kf.py b/selfdrive/locationd/models/gnss_kf.py index a672e67ed6..d3f8885f84 100755 --- a/selfdrive/locationd/models/gnss_kf.py +++ b/selfdrive/locationd/models/gnss_kf.py @@ -28,15 +28,15 @@ class GNSSKalman(): 0, 0]) # state covariance - P_initial = np.diag([10000**2, 10000**2, 10000**2, + P_initial = np.diag([1e16, 1e16, 1e16, 10**2, 10**2, 10**2, - (2000000)**2, (100)**2, (0.5)**2, + 1e14, (100)**2, (0.2)**2, (10)**2, (1)**2]) # process noise - Q = np.diag([0.3**2, 0.3**2, 0.3**2, + Q = np.diag([0.03**2, 0.03**2, 0.03**2, 3**2, 3**2, 3**2, - (.1)**2, (0)**2, (0.01)**2, + (.1)**2, (0)**2, (0.005)**2, .1**2, (.01)**2]) maha_test_kinds = [] # ObservationKind.PSEUDORANGE_RATE, ObservationKind.PSEUDORANGE, ObservationKind.PSEUDORANGE_GLONASS] @@ -119,6 +119,7 @@ class GNSSKalman(): # init filter self.filter = EKF_sym(generated_dir, self.name, self.Q, self.x_initial, self.P_initial, self.dim_state, self.dim_state, maha_test_kinds=self.maha_test_kinds) + self.init_state(GNSSKalman.x_initial, covs=GNSSKalman.P_initial) @property def x(self): diff --git a/selfdrive/locationd/models/live_kf.py b/selfdrive/locationd/models/live_kf.py index c583d7813b..71d4d31fbe 100755 --- a/selfdrive/locationd/models/live_kf.py +++ b/selfdrive/locationd/models/live_kf.py @@ -46,7 +46,7 @@ class LiveKalman(): 0, 0, 0]) # state covariance - initial_P_diag = np.array([1e14, 1e14, 1e14, + initial_P_diag = np.array([1e16, 1e16, 1e16, 1e6, 1e6, 1e6, 1e4, 1e4, 1e4, 1**2, 1**2, 1**2, diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index 7401fa8b8e..f1834b14c9 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -82,18 +82,18 @@ class LocKalman(): 0]) # state covariance - P_initial = np.diag([10000**2, 10000**2, 10000**2, + P_initial = np.diag([1e16, 1e16, 1e16, 10**2, 10**2, 10**2, 10**2, 10**2, 10**2, 1**2, 1**2, 1**2, - (200000)**2, (100)**2, + 1e14, (100)**2, 0.05**2, 0.05**2, 0.05**2, 0.02**2, - 1**2, 1**2, 1**2, + 2**2, 2**2, 2**2, 0.01**2, (0.01)**2, (0.01)**2, (0.01)**2, 10**2, 1**2, - 0.05**2]) + 0.2**2]) # process noise Q = np.diag([0.03**2, 0.03**2, 0.03**2, From 109ba298b118e79644c7513eed6d08ace00abf83 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Wed, 27 May 2020 12:16:05 -0700 Subject: [PATCH 100/656] better values --- selfdrive/locationd/models/loc_kf.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index f1834b14c9..9411265acb 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -97,8 +97,8 @@ class LocKalman(): # process noise Q = np.diag([0.03**2, 0.03**2, 0.03**2, - 0.0**2, 0.0**2, 0.0**2, - 0.0**2, 0.0**2, 0.0**2, + 0.0005**2, 0.001**2, 0.0005**2, + 0.001**2, 0.001**2, 0.001**2, 0.1**2, 0.1**2, 0.1**2, (.1)**2, (0.0)**2, (0.005 / 100)**2, (0.005 / 100)**2, (0.005 / 100)**2, From 6596dd62ae0a4111066537cb93bce520b05441b3 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Wed, 27 May 2020 22:24:04 +0300 Subject: [PATCH 101/656] add pygmae dependencies (#1573) https://www.pygame.org/wiki/CompileUbuntu#Python%203.x%20into%20virtual%20environment --- tools/ubuntu_setup.sh | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tools/ubuntu_setup.sh b/tools/ubuntu_setup.sh index 9f09279d34..9d3abc7993 100755 --- a/tools/ubuntu_setup.sh +++ b/tools/ubuntu_setup.sh @@ -33,6 +33,8 @@ sudo apt-get update && sudo apt-get install -y \ libusb-1.0-0-dev \ libzmq3-dev \ libczmq-dev \ + libsdl-image1.2-dev libsdl-mixer1.2-dev libsdl-ttf2.0-dev libsmpeg-dev \ + libsdl1.2-dev libportmidi-dev libswscale-dev libavformat-dev libavcodec-dev libfreetype6-dev \ locales \ ocl-icd-libopencl1 \ ocl-icd-opencl-dev \ From 221d9b3fe28d4267bdff08c0e8336c4729e8c2cf Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 27 May 2020 13:37:00 -0700 Subject: [PATCH 102/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index b48c74c2e9..bdec1398e5 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit b48c74c2e94fda21792c7afe8832a2e03e29a2bd +Subproject commit bdec1398e5150bfa00a0872413603a3e2c0c5cd0 From 67017d69fe02d9ed6a9cfba54565a403e59afcc4 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 27 May 2020 14:35:01 -0700 Subject: [PATCH 103/656] Minor fixes (#1571) * was 5 seconds not .2! * threshold for moving car highers, this can give FPw --- selfdrive/controls/lib/pathplanner.py | 4 ++-- selfdrive/controls/radard.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index a8de48013a..a92efa1ade 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -126,8 +126,8 @@ class PathPlanner(): # starting elif self.lane_change_state == LaneChangeState.laneChangeStarting: - # fade out over .2s - self.lane_change_ll_prob = max(self.lane_change_ll_prob - DT_MDL/5, 0.0) + # fade out over .5s + self.lane_change_ll_prob = max(self.lane_change_ll_prob - 2*DT_MDL, 0.0) # 98% certainty if lane_change_prob < 0.02 and self.lane_change_ll_prob < 0.01: self.lane_change_state = LaneChangeState.laneChangeFinishing diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 116968143d..e4d6f97234 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -52,7 +52,7 @@ def match_vision_to_cluster(v_ego, lead, clusters): # if no 'sane' match is found return -1 # stationary radar points can be false positives dist_sane = abs(cluster.dRel - offset_vision_dist) < max([(offset_vision_dist)*.25, 5.0]) - vel_sane = (abs(cluster.vRel - lead.relVel) < 10) or (v_ego + cluster.vRel > 2) + vel_sane = (abs(cluster.vRel - lead.relVel) < 10) or (v_ego + cluster.vRel > 3) if dist_sane and vel_sane: return cluster else: From 8ea8f405db489f262d396989626209a3e92b23ac Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 27 May 2020 15:13:31 -0700 Subject: [PATCH 104/656] add gpsOK flag to liveLocationKalman --- cereal | 2 +- selfdrive/locationd/locationd.py | 8 ++++++++ 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/cereal b/cereal index 4bb1eb826d..f27222f8f8 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 4bb1eb826d319237f42791c4ac20ad719cba7524 +Subproject commit f27222f8f87688b7c6808d66acf6da56aecaf622 diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 6b4928872a..bc5cd97c3f 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -63,7 +63,9 @@ class Localizer(): self.car_speed = 0 self.converter = coord.LocalCoord.from_ecef(self.kf.x[States.ECEF_POS]) + self.unix_timestamp_millis = 0 + self.last_gps_fix = 0 @staticmethod def msg_from_state(converter, calib_from_device, H, predicted_state, predicted_cov): @@ -183,6 +185,9 @@ class Localizer(): # ignore the message if the fix is invalid if log.flags % 2 == 0: return + + self.last_gps_fix = current_time + self.converter = coord.LocalCoord.from_geodetic([log.latitude, log.longitude, log.altitude]) ecef_pos = self.converter.ned2ecef([0, 0, 0]) ecef_vel = self.converter.ned2ecef_matrix.dot(np.array(log.vNED)) @@ -312,6 +317,9 @@ def locationd_thread(sm, pm, disabled_logs=[]): msg.liveLocationKalman = localizer.liveLocationMsg(t * 1e-9) msg.liveLocationKalman.inputsOK = sm.all_alive_and_valid() + + gps_age = (t / 1e9) - localizer.last_gps_fix + msg.liveLocationKalman.gpsOK = gps_age < 1.0 pm.send('liveLocationKalman', msg) From 5a841c28560e79f613f1f4e2fcd72877bb42379d Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Wed, 27 May 2020 17:11:11 -0700 Subject: [PATCH 105/656] Revert "better values" This reverts commit 109ba298b118e79644c7513eed6d08ace00abf83. --- selfdrive/locationd/models/loc_kf.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index 9411265acb..f1834b14c9 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -97,8 +97,8 @@ class LocKalman(): # process noise Q = np.diag([0.03**2, 0.03**2, 0.03**2, - 0.0005**2, 0.001**2, 0.0005**2, - 0.001**2, 0.001**2, 0.001**2, + 0.0**2, 0.0**2, 0.0**2, + 0.0**2, 0.0**2, 0.0**2, 0.1**2, 0.1**2, 0.1**2, (.1)**2, (0.0)**2, (0.005 / 100)**2, (0.005 / 100)**2, (0.005 / 100)**2, From db8f3aee1189533b3cd733b8723c9b01e0c157dc Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 27 May 2020 18:48:53 -0700 Subject: [PATCH 106/656] only run pipfile action on schedule --- .github/workflows/update-pipfile.yml | 4 ---- 1 file changed, 4 deletions(-) diff --git a/.github/workflows/update-pipfile.yml b/.github/workflows/update-pipfile.yml index 391747f19b..15bab0ec38 100644 --- a/.github/workflows/update-pipfile.yml +++ b/.github/workflows/update-pipfile.yml @@ -2,10 +2,6 @@ name: "Update Pipfile.lock" on: schedule: - cron: '00 15 * * 1' # Every monday on 15:00 UTC - push: - paths: - - 'Pipfile' - - '.github/workflows/update-pipfile.yml' jobs: piplock: From 64e1145b50393a253d9938cc8c8dd52e7e1c08b1 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 27 May 2020 18:50:22 -0700 Subject: [PATCH 107/656] Add pre commit config to docker --- Dockerfile.openpilot | 1 + 1 file changed, 1 insertion(+) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index e5b1f2491c..686fc2a8ef 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -80,6 +80,7 @@ COPY SConstruct \ flake8_openpilot.sh \ pylint_openpilot.sh \ .pylintrc \ + .pre-commit-config.yaml \ .coveragerc-app \ /tmp/openpilot/ From c1886486a56037588f71b8638c6e650bb7309862 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 27 May 2020 18:50:53 -0700 Subject: [PATCH 108/656] Revert "Add pre commit config to docker" This reverts commit 64e1145b50393a253d9938cc8c8dd52e7e1c08b1. --- Dockerfile.openpilot | 1 - 1 file changed, 1 deletion(-) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 686fc2a8ef..e5b1f2491c 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -80,7 +80,6 @@ COPY SConstruct \ flake8_openpilot.sh \ pylint_openpilot.sh \ .pylintrc \ - .pre-commit-config.yaml \ .coveragerc-app \ /tmp/openpilot/ From bd0643424357864287ae0485da03f66df85e1fb1 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 27 May 2020 20:00:14 -0700 Subject: [PATCH 109/656] pre-commit pylint (#1580) * "The commit-hook project sounds interesting though. I would definitely merge something that runs flake8 and pylint on the modified files!" - pd0wm, https://github.com/commaai/openpilot/pull/1575#issuecomment-634974344 * add pylint to pre-commit and make everything pass * Remove uncommented stuff Co-authored-by: J --- .pre-commit-config.yaml | 18 + .pylintrc | 2 +- Pipfile | 1 + Pipfile.lock | 369 ++++++++++++------ common/url_file.py | 2 + common/window.py | 5 +- scripts/waste.py | 3 +- selfdrive/controls/tests/test_clustering.py | 2 + selfdrive/debug/internal/cycle_alerts.py | 50 --- .../internal/sounds/test_sound_stability.py | 2 +- selfdrive/debug/internal/test_paramsd.py | 2 + selfdrive/locationd/models/loc_kf.py | 2 - selfdrive/loggerd/ethernetsniffer.py | 3 +- selfdrive/test/process_replay/inject_model.py | 5 - selfdrive/test/test_eon_fan.py | 4 +- selfdrive/test/test_leeco_alt_fan.py | 3 +- selfdrive/test/test_leeco_fan.py | 3 +- tools/lib/framereader.py | 2 + tools/lib/kbhit.py | 47 +-- tools/lib/mkvparse/mkvgen.py | 16 +- tools/lib/mkvparse/mkvindex.py | 5 +- tools/lib/mkvparse/mkvparse.py | 35 +- tools/replay/unlog_segment.py | 2 + tools/replay/unlogger.py | 2 +- tools/sim/bridge.py | 5 +- tools/sim/lib/can.py | 3 +- tools/sim/lib/manual_ctrl.py | 4 +- tools/streamer/streamerd.py | 2 + 28 files changed, 350 insertions(+), 249 deletions(-) create mode 100644 .pre-commit-config.yaml delete mode 100644 selfdrive/debug/internal/cycle_alerts.py diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 0000000000..990e27819f --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,18 @@ +repos: +- repo: https://github.com/pre-commit/pre-commit-hooks + rev: master + hooks: + - id: check-ast + - id: check-json + - id: check-xml + - id: check-yaml +- repo: local + hooks: + - id: pylint + name: pylint + entry: pylint + language: system + types: [python] + exclude: '^(pyextra)|(external)/' + args: + - --disable=R,C,W diff --git a/.pylintrc b/.pylintrc index 64a55daf8f..9a55710c45 100644 --- a/.pylintrc +++ b/.pylintrc @@ -3,7 +3,7 @@ # A comma-separated list of package or module names from where C extensions may # be loaded. Extensions are loading into the active Python interpreter and may # run arbitrary code -extension-pkg-whitelist=scipy +extension-pkg-whitelist=scipy cereal.messaging.messaging_pyx # Add files or directories to the blacklist. They should be base names, not # paths. diff --git a/Pipfile b/Pipfile index 1a49e70229..d18512d0ae 100644 --- a/Pipfile +++ b/Pipfile @@ -72,6 +72,7 @@ scikit-image = "*" pygame = "==2.0.0.dev8" pprofile = "*" pyprof2calltree = "*" +pre-commit = "*" [packages] atomicwrites = "*" diff --git a/Pipfile.lock b/Pipfile.lock index e8c8955f0f..572eb9a073 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "a274c1844cd5ad1f8cfb1cc523e51624c8f5d58bd1b9882f41534fd7bd75f3fb" + "sha256": "681eef4e45758b560f2f76736c039d051c62cc910e6bc7556b3add318110dea0" }, "pipfile-spec": 6, "requires": { @@ -21,6 +21,7 @@ "sha256:4c17cea3e592c21b6e222f673868961bad77e1f985cb1694ed077475a89229c1", "sha256:d8506842a3faf734b81599c8b98dcc423de863adcc1999248480b18bd31a0f38" ], + "markers": "python_version >= '3.5'", "version": "==2.4.1" }, "atomicwrites": { @@ -84,10 +85,14 @@ "sha256:d2b5255c7c6349bc1bd1e59e08cd12acbbd63ce649f2588755783aa94dfb6b1a", "sha256:dacca89f4bfadd5de3d7489b7c8a566eee0d3676333fbb50030263894c38c0dc" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==7.1.2" }, "crcmod": { "hashes": [ + "sha256:737fb308fa2ce9aed2e29075f0d5980d4a89bfbec48a368c607c5c63b3efb90e", + "sha256:69a2e5c6c36d0f096a7beb4cd34e5f882ec5fd232efb710cdb85d4ff196bd52e", + "sha256:50586ab48981f11e5b117523d97bb70864a2a1af246cf6e4f5c4a21ef4611cd1", "sha256:dc7051a0db5f2bd48665a990d3ec1cc305a466a77358ca4492826f41f283601e" ], "index": "pypi", @@ -192,6 +197,7 @@ "sha256:7588d1c14ae4c77d74036e8c22ff447b26d0fde8f007354fd48a7814db15b7cb", "sha256:a068a21ceac8a4d63dbfd964670474107f541babbd2250d61922f029858365fa" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.9" }, "isort": { @@ -199,6 +205,7 @@ "sha256:54da7e92468955c4fceacd0c86bd0ec997b0e1ee80d97f67c35a78b719dccab1", "sha256:6e811fcb295968434526407adb8796944f1988c5b65e8139058f2014cbe100fd" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==4.3.21" }, "itsdangerous": { @@ -206,6 +213,7 @@ "sha256:321b033d07f2a4136d3ec762eac9f16a10ccd60f53c0c91af90217ace7ba1f19", "sha256:b12271b2047cb23eeb98c8b5622e2e5c5e9abd9784a153e9d8ef9cb4dd09d749" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.1.0" }, "jinja2": { @@ -248,6 +256,7 @@ "sha256:efa1909120ce98bbb3777e8b6f92237f5d5c8ea6758efea36a473e1d38f7d3e4", "sha256:f3900e8a5de27447acbf900b4750b0ddfd7ec1ea7fbaf11dfa911141bc522af0" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.4.3" }, "libusb1": { @@ -259,7 +268,8 @@ }, "logentries": { "git": "https://github.com/commaai/le_python.git", - "ref": "feaeacb48f7f4bdb02c0a8fc092326d4e101b7f2" + "ref": "feaeacb48f7f4bdb02c0a8fc092326d4e101b7f2", + "version": "==0.8" }, "markupsafe": { "hashes": [ @@ -297,6 +307,7 @@ "sha256:e249096428b3ae81b08327a63a485ad0878de3fb939049038579ac0ef61e17e7", "sha256:e8313f01ba26fbbe36c7be1966a7b7424942f670f38e666995b88d012765b9be" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.1.1" }, "mccabe": { @@ -350,28 +361,29 @@ }, "pillow": { "hashes": [ - "sha256:04766c4930c174b46fd72d450674612ab44cca977ebbcc2dde722c6933290107", - "sha256:0e2a3bceb0fd4e0cb17192ae506d5f082b309ffe5fc370a5667959c9b2f85fa3", - "sha256:0f01e63c34f0e1e2580cc0b24e86a5ccbbfa8830909a52ee17624c4193224cd9", + "sha256:ccc9ad2460eb5bee5642eaf75a0438d7f8887d484490d5117b98edd7f33118b7", "sha256:12e4bad6bddd8546a2f9771485c7e3d2b546b458ae8ff79621214119ac244523", + "sha256:0e2a3bceb0fd4e0cb17192ae506d5f082b309ffe5fc370a5667959c9b2f85fa3", + "sha256:04766c4930c174b46fd72d450674612ab44cca977ebbcc2dde722c6933290107", "sha256:1f694e28c169655c50bb89a3fa07f3b854d71eb47f50783621de813979ba87f3", - "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", - "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", - "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", - "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd", "sha256:ae2b270f9a0b8822b98655cb3a59cdb1bd54a34807c6c56b76dd2e786c3b7db3", "sha256:b37bb3bd35edf53125b0ff257822afa6962649995cbdfde2791ddb62b239f891", - "sha256:b532bcc2f008e96fd9241177ec580829dee817b090532f43e54074ecffdcd97f", "sha256:b67a6c47ed963c709ed24566daa3f95a18f07d3831334da570c71da53d97d088", - "sha256:b943e71c2065ade6fef223358e56c167fc6ce31c50bc7a02dd5c17ee4338e8ac", - "sha256:ccc9ad2460eb5bee5642eaf75a0438d7f8887d484490d5117b98edd7f33118b7", "sha256:d23e2aa9b969cf9c26edfb4b56307792b8b374202810bd949effd1c6e11ebd6d", - "sha256:eaa83729eab9c60884f362ada982d3a06beaa6cc8b084cf9f76cae7739481dfa", + "sha256:0f01e63c34f0e1e2580cc0b24e86a5ccbbfa8830909a52ee17624c4193224cd9", "sha256:ee94fce8d003ac9fd206496f2707efe9eadcb278d94c271f129ab36aa7181344", "sha256:f455efb7a98557412dc6f8e463c1faf1f1911ec2432059fa3e582b6000fc90e2", "sha256:f46e0e024346e1474083c729d50de909974237c72daca05393ee32389dabe457", + "sha256:b943e71c2065ade6fef223358e56c167fc6ce31c50bc7a02dd5c17ee4338e8ac", + "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", + "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", + "sha256:f784aad988f12c80aacfa5b381ec21fd3f38f851720f652b9f33facc5101cf4d", + "sha256:eaa83729eab9c60884f362ada982d3a06beaa6cc8b084cf9f76cae7739481dfa", "sha256:f54be399340aa602066adb63a86a6a5d4f395adfdd9da2b9a0162ea808c7b276", - "sha256:f784aad988f12c80aacfa5b381ec21fd3f38f851720f652b9f33facc5101cf4d" + "sha256:b532bcc2f008e96fd9241177ec580829dee817b090532f43e54074ecffdcd97f", + "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", + "sha256:70e3e0d99a0dcda66283a185f80697a9b08806963c6149c8e6c5f452b2aa59c0", + "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd" ], "index": "pypi", "version": "==7.1.2" @@ -405,6 +417,7 @@ "sha256:2295e7b2f6b5bd100585ebcb1f616591b652db8a741695b3d8f5d28bdc934367", "sha256:c58a7d2815e0e8d7972bf1803331fb0152f867bd89adf8a01dfd55085434192e" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.6.0" }, "pycparser": { @@ -412,6 +425,7 @@ "sha256:2d475327684562c3a96cc71adf7dc8c4f0565175cf86b6d7a404ff4c771f15f0", "sha256:7582ad22678f0fcd81102833f60ef8d0e57288b6b5fb00323d101be910e35705" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.20" }, "pycryptodome": { @@ -455,6 +469,7 @@ "sha256:0d94e0e05a19e57a99444b6ddcf9a6eb2e5c68d3ca1e98e90707af8152c90a92", "sha256:35b2d75ee967ea93b55750aa9edbbf72813e06a66ba54438df2cfac9e3c27fc8" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.2.0" }, "pyjwt": { @@ -638,6 +653,7 @@ "sha256:2de2a5db0baeae7b2d2664949077c2ac63fbd16d98da0ff71837f7d1dea3fd43", "sha256:6c80b1e5ad3665290ea39320b91e1be1e0d5f60652b964a3070216de83d2e47c" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.0.1" }, "wrapt": { @@ -688,6 +704,13 @@ "index": "pypi", "version": "==3.6.2" }, + "appdirs": { + "hashes": [ + "sha256:7d5d0167b2b1ba821647616af46a749d1c653740dd0d2415100fe26e27afdf41", + "sha256:a841dacd6b99318a741b166adb07e19ee71a274450e68237b4650ca1055ab128" + ], + "version": "==1.4.4" + }, "applicationinsights": { "hashes": [ "sha256:30a11aafacea34f8b160fbdc35254c9029c7e325267874e3c68f6bdbcd6ed2c3", @@ -707,6 +730,7 @@ "sha256:4c17cea3e592c21b6e222f673868961bad77e1f985cb1694ed077475a89229c1", "sha256:d8506842a3faf734b81599c8b98dcc423de863adcc1999248480b18bd31a0f38" ], + "markers": "python_version >= '3.5'", "version": "==2.4.1" }, "astunparse": { @@ -721,6 +745,7 @@ "sha256:0c3c816a028d47f659d6ff5c745cb2acf1f966da1fe5c19c77a70282b25f4c5f", "sha256:4291ca197d287d274d0b6cb5d6f8f8f82d434ed288f962539ff18cc9012f9ea3" ], + "markers": "python_version >= '3.5.3'", "version": "==3.0.1" }, "attrs": { @@ -728,6 +753,7 @@ "sha256:08a96c641c3a74e44eb59afb61a24f2cb9f4d7188748e76ba4bb5edfa3cb7d1c", "sha256:f7b7ce16570fe9965acd6d30101a28f62fb4a7f9e926b3bbc9b61f8b04247e72" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==19.3.0" }, "azure-cli-core": { @@ -852,6 +878,7 @@ "sha256:d7bdc26475679dd073ba0ed2766445bb5b20ca4793ca0db32b399dccc6bc84b7", "sha256:ff032765bb8716d9387fd5376d987a937254b0619eff0972779515b5c98820bc" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==3.1.7" }, "bleach": { @@ -859,6 +886,7 @@ "sha256:2bce3d8fab545a6528c8fa5d9f9ae8ebc85a56da365c7f85180bfe96a35ef22f", "sha256:3c4c520fdb9db59ef139915a5db79f8b51bc2a7257ea0389f30c846883430a4b" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==3.1.5" }, "boto": { @@ -871,24 +899,25 @@ }, "boto3": { "hashes": [ - "sha256:2a97c9e8fd2c0f8d8a92262a0ccbd00aad8c4786acb74f620f54164070cb72ff", - "sha256:650d67b0d47b7bc0d79f04cc944506823dbbc2f76f60e64ce6d7cdd89f60a2eb" + "sha256:1bdab4f87ff39d5aab59b0aae69965bf604fa5608984c673877f4c62c1f16240", + "sha256:2b4924ccc1603d562969b9f3c8c74ff4a1f3bdbafe857c990422c73d8e2e229e" ], "index": "pypi", - "version": "==1.13.16" + "version": "==1.13.18" }, "botocore": { "hashes": [ - "sha256:0275023d023f0e3f9c27e5f23c437dd09ee715577cc628cf724e8bfbba2b459e", - "sha256:70d52f606bab2867971c0ea0c7723a769d81aa3cfd09f819d2b56e186e64ea0b" + "sha256:93574cf95a64c71d35c12c93a23f6214cf2f4b461be3bda3a436381cbe126a84", + "sha256:e65eb27cae262a510e335bc0c0e286e9e42381b1da0aafaa79fa13c1d8d74a95" ], - "version": "==1.16.16" + "version": "==1.16.18" }, "cachetools": { "hashes": [ "sha256:1d057645db16ca7fe1f3bd953558897603d6f0b9c51ed9d11eb4d071ec4e2aab", "sha256:de5d88f87781602201cde465d3afe837546663b168e8b39df67411b0bf10cefc" ], + "markers": "python_version ~= '3.5'", "version": "==4.1.0" }, "certifi": { @@ -932,6 +961,14 @@ "index": "pypi", "version": "==1.14.0" }, + "cfgv": { + "hashes": [ + "sha256:1ccf53320421aeeb915275a196e23b3b8ae87dea8ac6698b1638001d4a486d53", + "sha256:c8e8f552ffcc6194f4e18dd4f68d9aef0c0d58ae7e7be8c82bee3c5e9edfa513" + ], + "markers": "python_version >= '3.6.1'", + "version": "==3.1.0" + }, "chardet": { "hashes": [ "sha256:84ab92ed1c4d4f16916e05906b6b75a6c0fb5db821cc65e70cbd64a3e2a5eaae", @@ -944,6 +981,7 @@ "sha256:d2b5255c7c6349bc1bd1e59e08cd12acbbd63ce649f2588755783aa94dfb6b1a", "sha256:dacca89f4bfadd5de3d7489b7c8a566eee0d3676333fbb50030263894c38c0dc" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==7.1.2" }, "colorama": { @@ -951,6 +989,7 @@ "sha256:7d73d2a99753107a36ac6b455ee49046802e59d9d076ef8e47b61499fa29afff", "sha256:e96da0d330793e2cb9485e9ddfd918d456036c7149416295932478192f4436a1" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.4.3" }, "control": { @@ -1049,6 +1088,7 @@ "sha256:6687150770438374ab581bb7a1b327a847dd9c5749e396102de3fad4e8a3ef93", "sha256:f684034d135af4c6cbb949b8a4d2ed61634515257a67299e5f940fbaa34377f5" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.6.0" }, "dictdiffer": { @@ -1059,6 +1099,12 @@ "index": "pypi", "version": "==0.8.1" }, + "distlib": { + "hashes": [ + "sha256:2e166e231a26b36d6dfe35a48c4464346620f8645ed0ace01ee31822b288de21" + ], + "version": "==0.3.0" + }, "dlib": { "hashes": [ "sha256:d0eeaca07bc4c75973ad0f739a541d8fa4003af778f0dc1c2c595d470823819a" @@ -1072,21 +1118,23 @@ "sha256:9e4d7ecfc600058e07ba661411a2b7de2fd0fafa17d1a7f7361cd47b1175c827", "sha256:a2aeea129088da402665e92e0b25b04b073c04b2dce4ab65caaa38b7ce2e1a99" ], + "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.15.2" }, "elasticsearch": { "hashes": [ - "sha256:35de81968b78a1c708178773ccca56422661fc6e00905b81f48af8e8a9a2a6ba", - "sha256:eae591811e9bd82845ea22db3e891c30cad3d0f3e5dfd79cee80708872e5f626" + "sha256:9bfcb2bd137d6d7ca123e252b9d7261cfe4f7723f7b749a99c52b47766cf387c", + "sha256:e9138aa9de7624a6c6fbf5d0300bb11617cfe0a056fc6731665748731961d693" ], "index": "pypi", - "version": "==7.7.0" + "version": "==7.7.1" }, "entrypoints": { "hashes": [ "sha256:589f874b313739ad35be6e0cd7efde2a4e9b6fea91edcc34e58ecbb8dbe56d19", "sha256:c70dd71abe5a8c85e55e12c19bd91ccfeec11a6e99044204511f9ed547d48451" ], + "markers": "python_version >= '2.7'", "version": "==0.3" }, "fastcluster": { @@ -1118,6 +1166,13 @@ "index": "pypi", "version": "==1.1.26" }, + "filelock": { + "hashes": [ + "sha256:18d82244ee114f543149c66a6e0c14e9c4f8a1044b5cdaadd0f82159d6a6ff59", + "sha256:929b7d63ec5b7d6b71b0fa5ac14e030b3f70b75747cef1b10da9b879fef15836" + ], + "version": "==3.0.12" + }, "flask": { "hashes": [ "sha256:4efa1ae2d7c9865af48986de8aeb8504bf32c7f3d6fdc9353d34b21f4b127060", @@ -1146,6 +1201,7 @@ "hashes": [ "sha256:b1bead90b70cf6ec3f0710ae53a525360fa360d306a86583adc6bf83a4db537d" ], + "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.18.2" }, "gast": { @@ -1153,15 +1209,16 @@ "sha256:8f46f5be57ae6889a4e16e2ca113b1703ef17f2b0abceb83793eaba9e1351a45", "sha256:b881ef288a49aa81440d2c5eb8aeefd4c2bb8993d5f50edae7413a85bfdb3b57" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.3.3" }, "geoalchemy2": { "hashes": [ - "sha256:4c87177a570ed21307e255f22309e5e0a249e0b8fa9d800b9dc68a70af911074", - "sha256:85add5aa337ba697895a41608333088277144fa7ddb5eca2046a3794ade15f42" + "sha256:4385da5e24d01ee9d2af8ef0179994745d2a39931a84df04e74ebdb9a49c0c41", + "sha256:a5a2444d90ce7f2c6b2d7bd7346c8aed16fd32c3e190e631576a51814e8f7ee9" ], "index": "pypi", - "version": "==0.8.2" + "version": "==0.8.3" }, "git-pylint-commit-hook": { "hashes": [ @@ -1175,6 +1232,7 @@ "sha256:73b141d122942afe12e8bfdcb6900d5df35c27d39700f078363ba0b1298ad33b", "sha256:fbf25fee328c0828ef293459d9c649ef84ee44c0b932bb999d19df0ead1b40cf" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.15.0" }, "google-auth-oauthlib": { @@ -1283,42 +1341,25 @@ "sha256:bf52ec91244819c780341a3438d5d7b09f431d3f113a475147ac9b7b167a3d12", "sha256:e78960b31198511f45fd455534ae7645a6207d33e512d2e842c766d15d9c8080" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==8.2" }, + "identify": { + "hashes": [ + "sha256:be66b9673d59336acd18a3a0e0c10d35b8a780309561edf16c46b6b74b83f6af", + "sha256:ef6fa3d125c27516f8d1aaa2038c3263d741e8723825eb38350cdc0288ab35eb" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", + "version": "==1.4.17" + }, "idna": { "hashes": [ "sha256:7588d1c14ae4c77d74036e8c22ff447b26d0fde8f007354fd48a7814db15b7cb", "sha256:a068a21ceac8a4d63dbfd964670474107f541babbd2250d61922f029858365fa" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.9" }, - "imagecodecs": { - "hashes": [ - "sha256:0538f7a4def1f6745b2d83d21883dcd61e82bc8faaca810e3a35e6b551b455d1", - "sha256:22f3c39755752fe3a91a92fcf24002ca57a51efca1ab99e9919cf783f90b4026", - "sha256:286b87ee09506c35f099585e6b5ce245fb62c2a826aac4e0497cdfdfba631cc7", - "sha256:2bda6c7b13be73dfd202b3c23dc4b3003fdc02209835e348e4bd31ddca124d76", - "sha256:2c130b89fcb70bab3aa57ee0671423ab0e053c6ff7ed26646bf425592fa3116d", - "sha256:6275213bd611156fa2fd73ce81b29ca708c4344d36fe3686f567cd104ccf4d18", - "sha256:6f63ae2592086b1abbd40b699816c054dc7aad616df2b14c2e15cd2372b77653", - "sha256:91eb82b0167ff022a6a8dcf86e5871b635bfbe96801557e00d6b1e2a10ac25dd", - "sha256:9742b392640c1b2d05c6aaad956bd7e3bf461c7e0f403f7b25ee464a5c949c8c", - "sha256:9a9abc5498121f0005fb00dfbed57a062337445d32a39569e4378286b503125b", - "sha256:adc09e5f9af6927eccc35d60ae1ec422cd9791cee4d5456d39af6903dff19477", - "sha256:c019b19438dff31365fee3002b438992c16bc9955a036f466c600d80699cb5a2", - "sha256:c5667d4b8e97cf10b3754f5e8159d60620cdd35052ffc298346273d42284430f", - "sha256:c7367e01a199228b6526f05dc7fe7a85adac19f1b19e08a99edbdd2523cfcdc4", - "sha256:cf855a00bf5cb5a7cf1d608e7588ddc535d714e5422c3095dd811829b559f237", - "sha256:d1b0b2de7be918a8eada62c8d2339931381c86dbd43216a064e35ace5957e350", - "sha256:e0f3cfc2fc77c19118e173dca6af0dbed4a3cef75d3296762db687fd00fb7921", - "sha256:e8f460145258a28544d4119f58cab2daf87ac6653429ab9df7dff7d2cc30714f", - "sha256:eedf5be2c9c65a0d92970bda98dfd7e9525c137e631e1956753bb6ce369b08f9", - "sha256:f6722cd6a73501c508b361f485259f172898d3cf2530e6de71f3e89394a0a713", - "sha256:f6ac9dd40e1cdb72842fb72f147e8a51a1874c8f375629524566b388e841be20", - "sha256:fbdd0d42aa3c984377421767a892e77c40249870425aca0ba5629bdcd57d3ae4" - ], - "version": "==2020.2.18" - }, "imageio": { "hashes": [ "sha256:1e4ab29b3775bb093c7a35854a0412857145450183344678829b30e72263b001", @@ -1369,6 +1410,7 @@ "sha256:54da7e92468955c4fceacd0c86bd0ec997b0e1ee80d97f67c35a78b719dccab1", "sha256:6e811fcb295968434526407adb8796944f1988c5b65e8139058f2014cbe100fd" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==4.3.21" }, "itsdangerous": { @@ -1376,6 +1418,7 @@ "sha256:321b033d07f2a4136d3ec762eac9f16a10ccd60f53c0c91af90217ace7ba1f19", "sha256:b12271b2047cb23eeb98c8b5622e2e5c5e9abd9784a153e9d8ef9cb4dd09d749" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.1.0" }, "jedi": { @@ -1383,6 +1426,7 @@ "sha256:cd60c93b71944d628ccac47df9a60fec53150de53d42dc10a7fc4b5ba6aae798", "sha256:df40c97641cb943661d2db4c33c2e1ff75d491189423249e989bcea4464f3030" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.17.0" }, "jinja2": { @@ -1398,6 +1442,7 @@ "sha256:b85d0567b8666149a93172712e68920734333c0ce7e89b78b3e987f71e5ed4f9", "sha256:cdf6525904cc597730141d61b36f2e4b8ecc257c420fa2f4549bac2c2d0cb72f" ], + "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.10.0" }, "joblib": { @@ -1436,6 +1481,7 @@ "sha256:3a32fa4d0b16d1c626b30c3002a62dfd86d6863ed39eaba3f537fade197bb756", "sha256:cde8e83aab3ec1c614f221ae54713a9a46d3bf28292609d2db1b439bef5a8c8e" ], + "markers": "python_version >= '3.5'", "version": "==6.1.3" }, "jupyter-console": { @@ -1443,6 +1489,7 @@ "sha256:6f6ead433b0534909df789ea64f0a14cdf9b6b2360757756f08182be4b9e431b", "sha256:b392155112ec86a329df03b225749a0fa903aa80811e8eda55796a40b5e470d8" ], + "markers": "python_version >= '3.5'", "version": "==6.1.0" }, "jupyter-core": { @@ -1450,6 +1497,7 @@ "sha256:394fd5dd787e7c8861741880bdf8a00ce39f95de5d18e579c74b882522219e7e", "sha256:a4ee613c060fe5697d913416fc9d553599c05e4492d58fac1192c9a6844abb21" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==4.6.3" }, "keras-applications": { @@ -1486,6 +1534,7 @@ "sha256:efcf3397ae1e3c3a4a0a0636542bcad5adad3b1dd3e8e629d0b6e201347176c8", "sha256:fccefc0d36a38c57b7bd233a9b485e2f1eb71903ca7ad7adacad6c28a56d62d2" ], + "markers": "python_version >= '3.6'", "version": "==1.2.0" }, "knack": { @@ -1519,6 +1568,7 @@ "sha256:efa1909120ce98bbb3777e8b6f92237f5d5c8ea6758efea36a473e1d38f7d3e4", "sha256:f3900e8a5de27447acbf900b4750b0ddfd7ec1ea7fbaf11dfa911141bc522af0" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.4.3" }, "limits": { @@ -1540,6 +1590,7 @@ "sha256:1fafe3f1ecabfb514a5285fca634a53c1b32a81cb0feb154264d55bf2ff22c17", "sha256:c467cd6233885534bf0fe96e62e3cf46cfc1605112356c4f9981512b8174de59" ], + "markers": "python_version >= '3.5'", "version": "==3.2.2" }, "markupsafe": { @@ -1578,6 +1629,7 @@ "sha256:e249096428b3ae81b08327a63a485ad0878de3fb939049038579ac0ef61e17e7", "sha256:e8313f01ba26fbbe36c7be1966a7b7424942f670f38e666995b88d012765b9be" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.1.1" }, "matplotlib": { @@ -1684,6 +1736,7 @@ "sha256:fcfbb44c59af3f8ea984de67ec7c306f618a3ec771c2843804069917a8f2e255", "sha256:feed85993dbdb1dbc29102f50bca65bdc68f2c0c8d352468c25b54874f23c39d" ], + "markers": "python_version >= '3.5'", "version": "==4.7.6" }, "nbconvert": { @@ -1691,6 +1744,7 @@ "sha256:21fb48e700b43e82ba0e3142421a659d7739b65568cc832a13976a77be16b523", "sha256:f0d6ec03875f96df45aa13e21fd9b8450c42d7e1830418cccc008c0df725fcee" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==5.6.1" }, "nbformat": { @@ -1698,6 +1752,7 @@ "sha256:049af048ed76b95c3c44043620c17e56bc001329e07f83fec4f177f0e3d7b757", "sha256:276343c78a9660ab2a63c28cc33da5f7c58c092b3f3a40b6017ae2ce6689320d" ], + "markers": "python_version >= '3.5'", "version": "==5.0.6" }, "networkx": { @@ -1708,11 +1763,18 @@ "index": "pypi", "version": "==2.4" }, + "nodeenv": { + "hashes": [ + "sha256:5b2438f2e42af54ca968dd1b374d14a1194848955187b0e5e4be1f73813a5212" + ], + "version": "==1.3.5" + }, "notebook": { "hashes": [ "sha256:3edc616c684214292994a3af05eaea4cc043f6b4247d830f3a2f209fa7639a80", "sha256:47a9092975c9e7965ada00b9a20f0cf637d001db60d241d479f53c0be117ad48" ], + "markers": "python_version >= '3.5'", "version": "==6.0.3" }, "numpy": { @@ -1747,6 +1809,7 @@ "sha256:bee41cc35fcca6e988463cacc3bcb8a96224f470ca547e697b604cc697b2f889", "sha256:df884cd6cbe20e32633f1db1072e9356f53638e4361bef4e8b03c9127c9328ea" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==3.1.0" }, "opencv-python": { @@ -1780,6 +1843,7 @@ "sha256:83b76a98d18ae6a5cc7a0d88955a7f74881f0e567a0f4c949d24c942753eb998", "sha256:96f819d46da2f937eaf326336a114aaeccbcbdb9de460d42e8b5f480a69adca7" ], + "markers": "python_version >= '3.5'", "version": "==3.2.1" }, "osmium": { @@ -1817,6 +1881,7 @@ "sha256:4357f74f47b9c12db93624a82154e9b120fa8293699949152b22065d556079f8", "sha256:998416ba6962ae7fbd6596850b80e17859a5753ba17c32284f67bfff33784181" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==20.4" }, "pandas": { @@ -1838,6 +1903,7 @@ "sha256:ca84a44cf727f211752e91eab2d1c6c1ab0f0540d5636a8382a3af428542826e", "sha256:d234bcf669e8b4d6cbcd99e3ce7a8918414520aeb113e2a81aeb02d0a533d7f7" ], + "markers": "python_version >= '3.6.1'", "version": "==1.0.3" }, "pandocfilters": { @@ -1859,6 +1925,7 @@ "sha256:158c140fc04112dc45bca311633ae5033c2c2a7b732fa33d0955bad8152a8dd0", "sha256:908e9fae2144a076d72ae4e25539143d40b8e3eafbaeae03c1bfe226f4cdf12c" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.7.0" }, "pexpect": { @@ -1878,28 +1945,29 @@ }, "pillow": { "hashes": [ - "sha256:04766c4930c174b46fd72d450674612ab44cca977ebbcc2dde722c6933290107", - "sha256:0e2a3bceb0fd4e0cb17192ae506d5f082b309ffe5fc370a5667959c9b2f85fa3", - "sha256:0f01e63c34f0e1e2580cc0b24e86a5ccbbfa8830909a52ee17624c4193224cd9", + "sha256:ccc9ad2460eb5bee5642eaf75a0438d7f8887d484490d5117b98edd7f33118b7", "sha256:12e4bad6bddd8546a2f9771485c7e3d2b546b458ae8ff79621214119ac244523", + "sha256:0e2a3bceb0fd4e0cb17192ae506d5f082b309ffe5fc370a5667959c9b2f85fa3", + "sha256:04766c4930c174b46fd72d450674612ab44cca977ebbcc2dde722c6933290107", "sha256:1f694e28c169655c50bb89a3fa07f3b854d71eb47f50783621de813979ba87f3", - "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", - "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", - "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", - "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd", "sha256:ae2b270f9a0b8822b98655cb3a59cdb1bd54a34807c6c56b76dd2e786c3b7db3", "sha256:b37bb3bd35edf53125b0ff257822afa6962649995cbdfde2791ddb62b239f891", - "sha256:b532bcc2f008e96fd9241177ec580829dee817b090532f43e54074ecffdcd97f", "sha256:b67a6c47ed963c709ed24566daa3f95a18f07d3831334da570c71da53d97d088", - "sha256:b943e71c2065ade6fef223358e56c167fc6ce31c50bc7a02dd5c17ee4338e8ac", - "sha256:ccc9ad2460eb5bee5642eaf75a0438d7f8887d484490d5117b98edd7f33118b7", "sha256:d23e2aa9b969cf9c26edfb4b56307792b8b374202810bd949effd1c6e11ebd6d", - "sha256:eaa83729eab9c60884f362ada982d3a06beaa6cc8b084cf9f76cae7739481dfa", + "sha256:0f01e63c34f0e1e2580cc0b24e86a5ccbbfa8830909a52ee17624c4193224cd9", "sha256:ee94fce8d003ac9fd206496f2707efe9eadcb278d94c271f129ab36aa7181344", "sha256:f455efb7a98557412dc6f8e463c1faf1f1911ec2432059fa3e582b6000fc90e2", "sha256:f46e0e024346e1474083c729d50de909974237c72daca05393ee32389dabe457", + "sha256:b943e71c2065ade6fef223358e56c167fc6ce31c50bc7a02dd5c17ee4338e8ac", + "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", + "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", + "sha256:f784aad988f12c80aacfa5b381ec21fd3f38f851720f652b9f33facc5101cf4d", + "sha256:eaa83729eab9c60884f362ada982d3a06beaa6cc8b084cf9f76cae7739481dfa", "sha256:f54be399340aa602066adb63a86a6a5d4f395adfdd9da2b9a0162ea808c7b276", - "sha256:f784aad988f12c80aacfa5b381ec21fd3f38f851720f652b9f33facc5101cf4d" + "sha256:b532bcc2f008e96fd9241177ec580829dee817b090532f43e54074ecffdcd97f", + "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", + "sha256:70e3e0d99a0dcda66283a185f80697a9b08806963c6149c8e6c5f452b2aa59c0", + "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd" ], "index": "pypi", "version": "==7.1.2" @@ -1925,6 +1993,14 @@ "index": "pypi", "version": "==2.0.4" }, + "pre-commit": { + "hashes": [ + "sha256:5559e09afcac7808933951ffaf4ff9aac524f31efbc3f24d021540b6c579813c", + "sha256:703e2e34cbe0eedb0d319eff9f7b83e2022bb5a3ab5289a6a8841441076514d0" + ], + "index": "pypi", + "version": "==2.4.0" + }, "prometheus-client": { "hashes": [ "sha256:983c7ac4b47478720db338f1491ef67a100b474e3bc7dafcbaefb7d0b8f9b01c", @@ -1937,28 +2013,29 @@ "sha256:563d1a4140b63ff9dd587bda9557cffb2fe73650205ab6f4383092fb882e7dc8", "sha256:df7e9e63aea609b1da3a65641ceaf5bc7d05e0a04de5bd45d05dbeffbabf9e04" ], + "markers": "python_version >= '3.6.1'", "version": "==3.0.5" }, "protobuf": { "hashes": [ - "sha256:04d0b2bd99050d09393875a5a25fd12337b17f3ac2e29c0c1b8e65b277cbfe72", - "sha256:05288e44638e91498f13127a3699a6528dec6f9d3084d60959d721bfb9ea5b98", - "sha256:175d85370947f89e33b3da93f4ccdda3f326bebe3e599df5915ceb7f804cd9df", - "sha256:440a8c77531b3652f24999b249256ed01fd44c498ab0973843066681bd276685", - "sha256:49fb6fab19cd3f30fa0e976eeedcbf2558e9061e5fa65b4fe51ded1f4002e04d", - "sha256:4c7cae1f56056a4a2a2e3b00b26ab8550eae738bd9548f4ea0c2fcb88ed76ae5", - "sha256:519abfacbb421c3591d26e8daf7a4957763428db7267f7207e3693e29f6978db", - "sha256:60f32af25620abc4d7928d8197f9f25d49d558c5959aa1e08c686f974ac0b71a", - "sha256:613ac49f6db266fba243daf60fb32af107cfe3678e5c003bb40a381b6786389d", - "sha256:954bb14816edd24e746ba1a6b2d48c43576393bbde2fb8e1e3bd6d4504c7feac", - "sha256:9b1462c033a2cee7f4e8eb396905c69de2c532c3b835ff8f71f8e5fb77c38023", - "sha256:c0767f4d93ce4288475afe0571663c78870924f1f8881efd5406c10f070c75e4", - "sha256:c45f5980ce32879391144b5766120fd7b8803129f127ce36bd060dd38824801f", - "sha256:eeb7502f59e889a88bcb59f299493e215d1864f3d75335ea04a413004eb4fe24", - "sha256:fdb1742f883ee4662e39fcc5916f2725fec36a5191a52123fec60f8c53b70495", - "sha256:fe554066c4962c2db0a1d4752655223eb948d2bfa0fb1c4a7f2c00ec07324f1c" - ], - "version": "==3.12.1" + "sha256:304e08440c4a41a0f3592d2a38934aad6919d692bb0edfb355548786728f9a5e", + "sha256:50b5fee674878b14baea73b4568dc478c46a31dd50157a5b5d2f71138243b1a9", + "sha256:5524c7020eb1fb7319472cb75c4c3206ef18b34d6034d2ee420a60f99cddeb07", + "sha256:612bc97e42b22af10ba25e4140963fbaa4c5181487d163f4eb55b0b15b3dfcd2", + "sha256:6f349adabf1c004aba53f7b4633459f8ca8a09654bf7e69b509c95a454755776", + "sha256:85b94d2653b0fdf6d879e39d51018bf5ccd86c81c04e18a98e9888694b98226f", + "sha256:87535dc2d2ef007b9d44e309d2b8ea27a03d2fa09556a72364d706fcb7090828", + "sha256:a7ab28a8f1f043c58d157bceb64f80e4d2f7f1b934bc7ff5e7f7a55a337ea8b0", + "sha256:b5a114ea9b7fc90c2cc4867a866512672a47f66b154c6d7ee7e48ddb68b68122", + "sha256:be04fe14ceed7f8641e30f36077c1a654ff6f17d0c7a5283b699d057d150d82a", + "sha256:bff02030bab8b969f4de597543e55bd05e968567acb25c0a87495a31eb09e925", + "sha256:c9ca9f76805e5a637605f171f6c4772fc4a81eced4e2f708f79c75166a2c99ea", + "sha256:e1464a4a2cf12f58f662c8e6421772c07947266293fb701cb39cd9c1e183f63c", + "sha256:e72736dd822748b0721f41f9aaaf6a5b6d5cfc78f6c8690263aef8bba4457f0e", + "sha256:eafe9fa19fcefef424ee089fb01ac7177ff3691af7cc2ae8791ae523eb6ca907", + "sha256:f4b73736108a416c76c17a8a09bc73af3d91edaa26c682aaa460ef91a47168d3" + ], + "version": "==3.12.2" }, "ptyprocess": { "hashes": [ @@ -1970,40 +2047,72 @@ }, "pyasn1": { "hashes": [ + "sha256:014c0e9976956a08139dc0712ae195324a75e142284d5f87f1a87ee1b068a359", + "sha256:03840c999ba71680a131cfaee6fab142e1ed9bbd9c693e285cc6aca0d555e576", + "sha256:0458773cfe65b153891ac249bcf1b5f8f320b7c2ce462151f8fa74de8934becf", + "sha256:08c3c53b75eaa48d71cf8c710312316392ed40899cb34710d092e96745a358b7", "sha256:39c7e2ec30515947ff4e87fb6f456dfc6e84857d34be479c9d4a4ba4bf46aa5d", - "sha256:aef77c9fb94a3ac588e87841208bdec464471d9871bd5050a287cc9a475cd0ba" + "sha256:5c9414dcfede6e441f7e8f81b43b34e834731003427e5b09e4e00e3172a10f00", + "sha256:6e7545f1a61025a4e58bb336952c5061697da694db1cae97b116e9c46abcf7c8", + "sha256:78fa6da68ed2727915c4767bb386ab32cdba863caa7dbe473eaae45f9959da86", + "sha256:7ab8a544af125fb704feadb008c99a88805126fb525280b2270bb25cc1d78a12", + "sha256:99fcc3c8d804d1bc6d9a099921e39d827026409a58f2a720dcdb89374ea0c776", + "sha256:aef77c9fb94a3ac588e87841208bdec464471d9871bd5050a287cc9a475cd0ba", + "sha256:e89bf84b5437b532b0803ba5c9a5e054d21fec423a89952a74f87fa2c9b7bce2", + "sha256:fec3e9d8e36808a28efb59b489e4528c10ad0f480e57dcc32b4de5c9d8c9fdf3" ], "version": "==0.4.8" }, "pyasn1-modules": { "hashes": [ + "sha256:0845a5582f6a02bb3e1bde9ecfc4bfcae6ec3210dd270522fee602365430c3f8", + "sha256:0fe1b68d1e486a1ed5473f1302bd991c1611d319bba158e98b106ff86e1d7199", + "sha256:15b7c67fabc7fc240d87fb9aabf999cf82311a6d6fb2c70d00d3d0604878c811", + "sha256:426edb7a5e8879f1ec54a1864f16b882c2837bfd06eee62f2c982315ee2473ed", + "sha256:65cebbaffc913f4fe9e4808735c95ea22d7a7775646ab690518c056784bc21b4", "sha256:905f84c712230b2c592c19470d3ca8d552de726050d1d1716282a1f6146be65e", - "sha256:a50b808ffeb97cb3601dd25981f6b016cbb3d31fbf57a8b8a87428e6158d0c74" + "sha256:a50b808ffeb97cb3601dd25981f6b016cbb3d31fbf57a8b8a87428e6158d0c74", + "sha256:a99324196732f53093a84c4369c996713eb8c89d360a496b599fb1a9c47fc3eb", + "sha256:b80486a6c77252ea3a3e9b1e360bc9cf28eaac41263d173c032581ad2f20fe45", + "sha256:c29a5e5cc7a3f05926aff34e097e84f8589cd790ce0ed41b67aed6857b26aafd", + "sha256:cbac4bc38d117f2a49aeedec4407d23e8866ea4ac27ff2cf7fb3e5b570df19e0", + "sha256:f39edd8c4ecaa4556e989147ebf219227e2cd2e8a43c7e7fcb1f1c18c5fd6a3d", + "sha256:fe0644d9ab041506b62782e92b06b8c68cca799e1a9636ec398675459e031405" ], "version": "==0.2.8" }, "pycocotools": { "git": "https://github.com/cocodataset/cocoapi.git", "ref": "8c9bcc3cf640524c4c20a9c40e89cb6a2f2fa0e9", - "subdirectory": "PythonAPI" + "subdirectory": "PythonAPI", + "version": "==2.0" }, "pycparser": { "hashes": [ "sha256:2d475327684562c3a96cc71adf7dc8c4f0565175cf86b6d7a404ff4c771f15f0", "sha256:7582ad22678f0fcd81102833f60ef8d0e57288b6b5fb00323d101be910e35705" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.20" }, "pycurl": { "hashes": [ "sha256:1957c867e2a341f5526c107c7bbc5014d6e75fdc2a14294fcb8a47663fbd2e15", + "sha256:404862665c4e2dbe814c9495d1193a65ae0f291a7074ae1ef1f0bffd93c14ea6", "sha256:50aee0469511a9708a1f1a50d510b5ec2013fc6f5e720c32bbcb3b9c7b0f45b1", "sha256:667db26516e50ce4a853745906f3b149c24756d85061b9d966eb7ec43a8c48a4", + "sha256:789a76e9265cdb7c947ec0afde2330492ccc0f2cee8e3ca8c0822082b6ae213e", "sha256:7cc13d3421cbd31921d77e22d1f57c0e1a8d0fb461938a587689a93162ccef2f", "sha256:a0c62dbc66b9b947832307d6cf7bdb5e4da906ce7b3efe6f74292e8f3dc5abe3", "sha256:a6966e8d9ccda31c6d077c4f8673aaa88141cc73d50e110e93e627b816d17fd1", + "sha256:b393aa90abf07ddd51d750c0c6a801155af07f938af6ec8b89ea00ff3f892887", + "sha256:b58e4d7888edd74dce40b9481962f0537dc77a44d99b5cc3385c3ffdaf2abf93", + "sha256:b6512b864466b242ffc3997e982d4590e035d056d37e63136fa137a4044ce2f1", + "sha256:b651f47c61c051ea93299b0e7a341860d33bfe2cf524237be0fb56399f026d98", "sha256:beadfa7f052626864d70eb33cec8f2aeece12dfb483c2424cc07b057f83b7d35", "sha256:c5c379c8cc777dda397f86f0d0049480250ae84a82a9d99d668f461d368fb39c", + "sha256:daa017e8dc887129e4a2cd88b7be8c431e434b89737348eaa12096026020756a", + "sha256:e1aea68b1d39dbcafc7298214f51f6ebd5f188c06aa418e9c046dfe419fe7ecf", "sha256:ec7dd291545842295b7b56c12c90ffad2976cc7070c98d7b1517b7b6cd5994b3" ], "index": "pypi", @@ -2017,13 +2126,16 @@ "sha256:0b3b26f6ad21a651301acf48c48fdc541bd3dbbdeb214d82bbad5c9403ed71e8", "sha256:10743ba4d4d07fb2437f7399fe65b99b99202b92899b0b8f085d3f97bdd408e0", "sha256:10ea85a1a2a06de7e9ee4b52c391f574104017bdc8a5569d92a95d4b6e4df9cc", + "sha256:1162be5304d72e84d173c1c0cfa68ba742a6d20f166095e945ee8f3952a25a25", "sha256:1361dbc180786f17fe399f632a0809881bbaa588c094a613a5d139f0a9f5bb17", + "sha256:1f2d9df9374677a963d41e3247eea9a9da768a8556d055ffbd55fff0a48d8a1a", "sha256:1f648ee199a7359b8bdd9534fbbb6d046910ed821ca565d23083eb4e128b38ce", "sha256:370202bbc33b5747986eee24f44e2e84d5fb18a48398ec944018c288e9298874", "sha256:56eefff1c9c4338533673f4cb00c975b1a807d41b429a66ecd6e0cae274b99b2", "sha256:660ab9e8dd960d312f0bd1b0b7b62d22891fb6e188ebd980cc78d57336d067d2", "sha256:68c3a9224bb9e878f244aad9cd842ccef10e9c074c6284b61ec2fd9931e67def", "sha256:71d629fae5b20a88cdbf541abc4f2025b823731ee73b8b2380d9c86160640d11", + "sha256:7ae141466b6783abeaf66e10884a2824b3e47ab681f411e83b5c9884e15ba81b", "sha256:7df846da4d24e85a38240e1bcc1d5579d72e4a8b675b4bc77aad899cb8d53feb", "sha256:7fd14b068e784b118b51eda271a8fc3bfe2b0c54b6146ac6e34f66858ac27834", "sha256:8068af05b2a2fc9984e55ad05f9131ec767b2fc312df0f50972e88c4485f5d8e", @@ -2032,10 +2144,13 @@ "sha256:8a80cff2fd8818daec3b084b4caa5c5ecbe2a2460d9c10f96682350032c3b5fe", "sha256:921d6565b40ff3da1e505efa1f75f0438214ca0d6b413e19a481fb52bff1ca7a", "sha256:96bc63d8e56998f079d1d92e077213935f3dea800300912e4176c2a300135e13", + "sha256:a0fe0dcdbba303cd5dd01d46231cbeabf0bbe2f9c88e6066458c8eeb584352de", "sha256:b47875c58b507b74361cecd0083411e0b19ae15dff7da45e104da86d8a1fefcb", "sha256:bdeb5399d90d352a393c2461ff19f2d627c602706be7ea1415021b4862ce720d", + "sha256:d4e0cd3392ebc88c321175b205ebeb0c3247ceb2468d940d90fcb849075b468f", "sha256:d72e3a583b081058107e5157b706cc409b3afdae892f560481ef298fd4154a29", "sha256:d76183fa2a6070006d0f8e95fb707edface752564248f63267bdd98464b55feb", + "sha256:da1d869fb24e2f852c259b79e80f47c6f38a1176f872bb79aa866ca79b052867", "sha256:e63c0d05c384337b3354e6368769204f0b965b092d167f55eea26e13e97208d8", "sha256:ecad810029f8058712ae649588fc0b2faaf0746be84aa225de285b2a000aba8f", "sha256:f6d0ea74b97a487e1f491c75386d494ecd573851af4e08090eacfa707ba43428" @@ -2115,10 +2230,12 @@ "sha256:a60756d55f0887023b3899e6c2923ba5f0042fb11b1d17810b4e07395404f33e", "sha256:a676bd2fbc2309092b9bbb0083d35718b5420af3a42135ebb1e4c3633f56604d", "sha256:a732838c78554c1257ff2492f5c8c4c7312d0aecd7f732149e255f3749edd5ee", + "sha256:ad3dc88dfe61f0f1f9b99c6bc833ea2f45203a937a18f0d2faa57c6952656012", "sha256:ae65d65fde4135ef423a2608587c9ef585a3551fc2e4e431e7c7e527047581be", "sha256:b070a4f064a9edb70f921bfdc270725cff7a78c22036dd37a767c51393fb956f", "sha256:b6da85949aa91e9f8c521681344bd2e163de894a5492337fba8b05c409225a4f", "sha256:bbf47110765b2a999803a7de457567389253f8670f7daafb98e059c899ce9764", + "sha256:bd9c1e6f92b4888ae3ef7ae23262c513b962f09f3fb3b48581dde5df7d7a860a", "sha256:c06b3f998d2d7160db58db69adfb807d2ec307e883e2f17f6b87a1ef6c723f11", "sha256:c318fb70542be16d3d4063cde6010b1e4d328993a793529c15a619251f517c39", "sha256:c4aef42e5fa4c9d5a99f751fb79caa880dac7eaf8a65121549318b984676a1b7", @@ -2128,6 +2245,7 @@ "sha256:e2b46e092ea54b732d98c476720386ff2ccd126de1e52076b470b117bff7e409", "sha256:e334c4f39a2863a239d38b5829e442a87f241a92da9941861ee6ec5d6380b7fe", "sha256:e5c54f04ca42bbb5153aec5d4f2e3d9f81e316945220ac318abd4083308143f5", + "sha256:f4d06764a06b137e48db6d569dc95614d9d225c89842c885669ee8abc9f28c7a", "sha256:f96333f9d2517c752c20a35ff95de5fc2763ac8cdb1653df0f6f45d281620606" ], "index": "pypi", @@ -2143,29 +2261,25 @@ }, "pynacl": { "hashes": [ - "sha256:05c26f93964373fc0abe332676cb6735f0ecad27711035b9472751faa8521255", - "sha256:0c6100edd16fefd1557da078c7a31e7b7d7a52ce39fdca2bec29d4f7b6e7600c", - "sha256:0d0a8171a68edf51add1e73d2159c4bc19fc0718e79dec51166e940856c2f28e", - "sha256:1c780712b206317a746ace34c209b8c29dbfd841dfbc02aa27f2084dd3db77ae", - "sha256:2424c8b9f41aa65bbdbd7a64e73a7450ebb4aa9ddedc6a081e7afcc4c97f7621", - "sha256:2d23c04e8d709444220557ae48ed01f3f1086439f12dbf11976e849a4926db56", - "sha256:30f36a9c70450c7878053fa1344aca0145fd47d845270b43a7ee9192a051bf39", - "sha256:37aa336a317209f1bb099ad177fef0da45be36a2aa664507c5d72015f956c310", - "sha256:4943decfc5b905748f0756fdd99d4f9498d7064815c4cf3643820c9028b711d1", - "sha256:53126cd91356342dcae7e209f840212a58dcf1177ad52c1d938d428eebc9fee5", - "sha256:57ef38a65056e7800859e5ba9e6091053cd06e1038983016effaffe0efcd594a", - "sha256:5bd61e9b44c543016ce1f6aef48606280e45f892a928ca7068fba30021e9b786", - "sha256:6482d3017a0c0327a49dddc8bd1074cc730d45db2ccb09c3bac1f8f32d1eb61b", - "sha256:7d3ce02c0784b7cbcc771a2da6ea51f87e8716004512493a2b69016326301c3b", - "sha256:a14e499c0f5955dcc3991f785f3f8e2130ed504fa3a7f44009ff458ad6bdd17f", - "sha256:a39f54ccbcd2757d1d63b0ec00a00980c0b382c62865b61a505163943624ab20", - "sha256:aabb0c5232910a20eec8563503c153a8e78bbf5459490c49ab31f6adf3f3a415", - "sha256:bd4ecb473a96ad0f90c20acba4f0bf0df91a4e03a1f4dd6a4bdc9ca75aa3a715", - "sha256:bf459128feb543cfca16a95f8da31e2e65e4c5257d2f3dfa8c0c1031139c9c92", - "sha256:e2da3c13307eac601f3de04887624939aca8ee3c9488a0bb0eca4fb9401fc6b1", - "sha256:f67814c38162f4deb31f68d590771a29d5ae3b1bd64b75cf232308e5c74777e0" - ], - "version": "==1.3.0" + "sha256:06cbb4d9b2c4bd3c8dc0d267416aaed79906e7b33f114ddbf0911969794b1cc4", + "sha256:11335f09060af52c97137d4ac54285bcb7df0cef29014a1a4efe64ac065434c4", + "sha256:2fe0fc5a2480361dcaf4e6e7cea00e078fcda07ba45f811b167e3f99e8cff574", + "sha256:30f9b96db44e09b3304f9ea95079b1b7316b2b4f3744fe3aaecccd95d547063d", + "sha256:511d269ee845037b95c9781aa702f90ccc36036f95d0f31373a6a79bd8242e25", + "sha256:537a7ccbea22905a0ab36ea58577b39d1fa9b1884869d173b5cf111f006f689f", + "sha256:54e9a2c849c742006516ad56a88f5c74bf2ce92c9f67435187c3c5953b346505", + "sha256:757250ddb3bff1eecd7e41e65f7f833a8405fede0194319f87899690624f2122", + "sha256:7757ae33dae81c300487591c68790dfb5145c7d03324000433d9a2c141f82af7", + "sha256:7c6092102219f59ff29788860ccb021e80fffd953920c4a8653889c029b2d420", + "sha256:8122ba5f2a2169ca5da936b2e5a511740ffb73979381b4229d9188f6dcb22f1f", + "sha256:9c4a7ea4fb81536c1b1f5cc44d54a296f96ae78c1ebd2311bd0b60be45a48d96", + "sha256:cd401ccbc2a249a47a3a1724c2918fcd04be1f7b54eb2a5a71ff915db0ac51c6", + "sha256:d452a6746f0a7e11121e64625109bc4468fc3100452817001dbe018bb8b08514", + "sha256:ea6841bc3a76fa4942ce00f3bda7d436fda21e2d91602b9e21b7ca9ecab8f3ff", + "sha256:f8851ab9041756003119368c1e6cd0b9c631f46d686b3904b18c0139f4419f80" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", + "version": "==1.4.0" }, "pynmea2": { "hashes": [ @@ -2187,6 +2301,7 @@ "sha256:c203ec8783bf771a155b207279b9bccb8dea02d8f0c9e5f8ead507bc3246ecc1", "sha256:ef9d7589ef3c200abe66653d3f1ab1033c3c419ae9b9bdb1240a85b024efc88b" ], + "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.4.7" }, "pyprof2calltree": { @@ -2299,6 +2414,7 @@ "sha256:d510aef84d9852653d079c84f2f81a82d5d09815e625f35c95714e7364570ad4", "sha256:e02a0558e0c2ac8b8bbe6a6ac18c136767ec56b96a321e0dfde2173adfa5a504" ], + "markers": "python_version >= '3.5'", "version": "==1.1.1" }, "pyyaml": { @@ -2385,7 +2501,8 @@ "requests-oauthlib": { "hashes": [ "sha256:7f71572defaecd16372f9006f33c2ec8c077c3cfa6f5911a9a90202beb513f3d", - "sha256:b4261601a71fd721a8bd6d7aa1cc1d6a8a93b4a9f5e96626f8e4d91e8beeaa6a" + "sha256:b4261601a71fd721a8bd6d7aa1cc1d6a8a93b4a9f5e96626f8e4d91e8beeaa6a", + "sha256:fa6c47b933f01060936d87ae9327fead68768b69c6c9ea2109c48be30f2d4dbc" ], "version": "==1.3.0" }, @@ -2509,17 +2626,29 @@ "sha256:0fe3994207485efb63d8f10a833ff31236ed27e3b23dadd0bf51c9900313f8f2", "sha256:17163e643dbf125bb552de17c826b0161c68c970335d270e174363d19e7ea882", "sha256:1d1e929cdd15151f3c0b2efe953b3281b2fd5ad5f234f77aca725f28486466f6", + "sha256:1d346c2c1d7dd79c118f0cc7ec5a1c4127e0c8ffc83e7b13fc5709ff78c9bb84", "sha256:1ea59f570b9d4916ae5540a9181f9c978e16863383738b69a70363bc5e63c4cb", + "sha256:1fbba86098bbfc1f85c5b69dc9a6d009055104354e0d9880bb00b692e30e0078", + "sha256:229edb079d5dd81bf12da952d4d825bd68d1241381b37d3acf961b384c9934de", "sha256:22a7acb81968a7c64eba7526af2cf566e7e2ded1cb5c83f0906b17ff1540f866", "sha256:2b4b2b738b3b99819a17feaf118265d0753d5536049ea570b3c43b51c4701e81", "sha256:4cf91aab51b02b3327c9d51897960c554f00891f9b31abd8a2f50fd4a0071ce8", + "sha256:4fd5f79590694ebff8dc980708e1c182d41ce1fda599a12189f0ca96bf41ad70", + "sha256:5cfd495527f8b85ce21db806567de52d98f5078a8e9427b18e251c68bd573a26", + "sha256:60aad424e47c5803276e332b2a861ed7a0d46560e8af53790c4c4fb3420c26c2", + "sha256:7739940d68b200877a15a5ff5149e1599737d6dd55e302625650629350466418", "sha256:7cce4bac7e0d66f3a080b80212c2238e063211fe327f98d764c6acbc214497fc", "sha256:8027bd5f1e633eb61b8239994e6fc3aba0346e76294beac22a892eb8faa92ba1", "sha256:86afc5b5cbd42d706efd33f280fec7bd7e2772ef54e3f34cf6b30777cd19a614", "sha256:87d349517b572964350cc1adc5a31b493bbcee284505e81637d0174b2758ba17", + "sha256:8de378d589eccbc75941e480b4d5b4db66f22e4232f87543b136b1f093fff342", "sha256:926bcbef9eb60e798eabda9cd0bbcb0fca70d2779aa0aa56845749d973eb7ad5", "sha256:9a126c3a91df5b1403e965ba63b304a50b53d8efc908a8c71545ed72535374a3", + "sha256:ad8dd3454d0c65c0f92945ac86f7b9efb67fa2040ba1b0189540e984df904378", + "sha256:d140e9376e7f73c1f9e0a8e3836caf5eec57bbafd99259d56979da05a6356388", + "sha256:da00675e5e483ead345429d4f1374ab8b949fba4429d60e71ee9d030ced64037", "sha256:daaf4d11db982791be74b23ff4729af2c7da79316de0bebf880fa2d60bcc8c5a", + "sha256:f4b64a1031acf33e281fd9052336d6dad4d35eee3404c95431c8c6bc7a9c0588", "sha256:fc046afda0ed8f5295212068266c92991ab1f4a50c6a7144b69364bdee4a0159", "sha256:fc9051d249dd5512e541f20330a74592f7a65b2d62e18122ca89bf71f94db748" ], @@ -2595,6 +2724,7 @@ "hashes": [ "sha256:9a2a2dc9856187679e93f3c95e5dc771dd47e3257db09767b4be118d734b4dc2" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.2.1" }, "tensorboard-plugin-wit": { @@ -2639,6 +2769,7 @@ "sha256:4804a774f802306a7d9af7322193c5390f1da0abb429e082a10ef1d46e6fb2c2", "sha256:a43dcb3e353bc680dd0783b1d9c3fc28d529f190bc54ba9a229f72fe6e7a54d7" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==0.8.3" }, "testpath": { @@ -2650,10 +2781,11 @@ }, "tifffile": { "hashes": [ - "sha256:2e110ea3a6381df534261a85091490a5678faa4535aa14cc11b8ea8379dcbf01", - "sha256:abfce379f2b4b97759796c1489ea0e73c349fc71bf09bea2a5d076cbe7cfd4eb" + "sha256:12a9ffc702de8f5ea6a7c39f69654143fb419059773e964be6293a16a0b2cbf9", + "sha256:b212b7eb7651208c79ec95899f0dfe5684d68f4254cf782247af4f56f8e00cc8" ], - "version": "==2020.5.11" + "markers": "python_version >= '3.6'", + "version": "==2020.5.25" }, "toml": { "hashes": [ @@ -2674,6 +2806,7 @@ "sha256:c952975c8ba74f546ae6de2e226ab3cc3cc11ae47baf607459a6728585bb542a", "sha256:c98232a3ac391f5faea6821b53db8db461157baa788f5d6222a193e9456e1740" ], + "markers": "python_version >= '3.5'", "version": "==6.0.4" }, "traitlets": { @@ -2691,6 +2824,14 @@ "index": "pypi", "version": "==1.25.9" }, + "virtualenv": { + "hashes": [ + "sha256:a116629d4e7f4d03433b8afa27f43deba09d48bc48f5ecefa4f015a178efb6cf", + "sha256:a730548b27366c5e6cbdf6f97406d861cccece2e22275e8e1a757aeff5e00c70" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", + "version": "==20.0.21" + }, "wcwidth": { "hashes": [ "sha256:cafe2186b3c009a04067022ce1dcd79cb38d8d65ee4f4791b8888d6599d1bbe1", @@ -2710,6 +2851,7 @@ "sha256:2de2a5db0baeae7b2d2664949077c2ac63fbd16d98da0ff71837f7d1dea3fd43", "sha256:6c80b1e5ad3665290ea39320b91e1be1e0d5f60652b964a3070216de83d2e47c" ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==1.0.1" }, "wheel": { @@ -2753,6 +2895,7 @@ "sha256:d8cdee92bc930d8b09d8bd2043cedd544d9c8bd7436a77678dd602467a993080", "sha256:e15199cdb423316e15f108f51249e44eb156ae5dba232cb73be555324a1d49c2" ], + "markers": "python_version >= '3.5'", "version": "==1.4.2" } } diff --git a/common/url_file.py b/common/url_file.py index 1f6d4a0813..184b7452b9 100644 --- a/common/url_file.py +++ b/common/url_file.py @@ -1,3 +1,5 @@ +# pylint: skip-file + import os import time import tempfile diff --git a/common/window.py b/common/window.py index 5af3d83cd0..7454a86207 100644 --- a/common/window.py +++ b/common/window.py @@ -27,10 +27,10 @@ class Window(): def getkey(self): while 1: event = pygame.event.wait() - if event.type == QUIT: + if event.type == pygame.QUIT: pygame.quit() sys.exit() - if event.type == KEYDOWN: + if event.type == pygame.KEYDOWN: return event.key def getclick(self): @@ -47,4 +47,3 @@ if __name__ == "__main__": print("draw") img += 1 win.draw(img) - diff --git a/scripts/waste.py b/scripts/waste.py index 55aeba066a..2834dea191 100755 --- a/scripts/waste.py +++ b/scripts/waste.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 from multiprocessing import Process -from setproctitle import setproctitle +from setproctitle import setproctitle # pylint: disable=no-name-in-module import os import numpy as np from common.realtime import sec_since_boot @@ -32,4 +32,3 @@ def main(gctx=None): if __name__ == "__main__": main() - diff --git a/selfdrive/controls/tests/test_clustering.py b/selfdrive/controls/tests/test_clustering.py index e899ff7d57..290b267029 100644 --- a/selfdrive/controls/tests/test_clustering.py +++ b/selfdrive/controls/tests/test_clustering.py @@ -1,3 +1,5 @@ +# pylint: skip-file + import time import unittest import numpy as np diff --git a/selfdrive/debug/internal/cycle_alerts.py b/selfdrive/debug/internal/cycle_alerts.py deleted file mode 100644 index cc073aaa29..0000000000 --- a/selfdrive/debug/internal/cycle_alerts.py +++ /dev/null @@ -1,50 +0,0 @@ -# USAGE: python cycle_alerts.py [duration_millis=1000] -# Then start manager - -import argparse -import time - -import cereal.messaging as messaging -from selfdrive.controls.lib.alerts import ALERTS - -def now_millis(): return time.time() * 1000 - -default_alerts = sorted(ALERTS, key=lambda alert: (alert.alert_size, len(alert.alert_text_2))) - -def cycle_alerts(duration_millis, alerts=None): - if alerts is None: - alerts = default_alerts - - controls_state = messaging.pub_sock('controlsState') - - last_pop_millis = now_millis() - alert = alerts.pop() - while 1: - if (now_millis() - last_pop_millis) > duration_millis: - alerts.insert(0, alert) - alert = alerts.pop() - last_pop_millis = now_millis() - print('sending {}'.format(str(alert))) - - dat = messaging.new_message('controlsState') - - dat.controlsState.alertType = alert.alert_type - dat.controlsState.alertText1 = alert.alert_text_1 - dat.controlsState.alertText2 = alert.alert_text_2 - dat.controlsState.alertSize = alert.alert_size - dat.controlsState.alertStatus = alert.alert_status - dat.controlsState.alertSound = alert.audible_alert - controls_state.send(dat.to_bytes()) - - time.sleep(0.01) - -if __name__ == '__main__': - parser = argparse.ArgumentParser() - parser.add_argument('--duration', type=int, default=1000) - parser.add_argument('--alert-types', nargs='+') - args = parser.parse_args() - alerts = None - if args.alert_types: - alerts = [next(a for a in ALERTS if a.alert_type==alert_type) for alert_type in args.alert_types] - - cycle_alerts(args.duration, alerts=alerts) diff --git a/selfdrive/debug/internal/sounds/test_sound_stability.py b/selfdrive/debug/internal/sounds/test_sound_stability.py index 18b87abb2e..2b86622081 100755 --- a/selfdrive/debug/internal/sounds/test_sound_stability.py +++ b/selfdrive/debug/internal/sounds/test_sound_stability.py @@ -6,7 +6,7 @@ import datetime import random from common.basedir import BASEDIR -from selfdrive import messaging +import cereal.messaging as messaging if __name__ == "__main__": diff --git a/selfdrive/debug/internal/test_paramsd.py b/selfdrive/debug/internal/test_paramsd.py index 356edfaef6..3553949ac8 100755 --- a/selfdrive/debug/internal/test_paramsd.py +++ b/selfdrive/debug/internal/test_paramsd.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +# pylint: skip-file + import numpy as np import math from tqdm import tqdm diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index f1834b14c9..fbb6b1b58d 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -443,8 +443,6 @@ class LocKalman(): r = self.predict_and_update_orb_features(data, t, kind) elif kind == ObservationKind.MSCKF_TEST: r = self.predict_and_update_msckf_test(data, t, kind) - elif kind == ObservationKind.FEATURE_TRACK_TEST: - r = self.predict_and_update_feature_track_test(data, t, kind) elif kind == ObservationKind.ODOMETRIC_SPEED: r = self.predict_and_update_odo_speed(data, t, kind) else: diff --git a/selfdrive/loggerd/ethernetsniffer.py b/selfdrive/loggerd/ethernetsniffer.py index 023dacc90b..3c3ffb338c 100755 --- a/selfdrive/loggerd/ethernetsniffer.py +++ b/selfdrive/loggerd/ethernetsniffer.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +# pylint: skip-file + import cereal.messaging as messaging import pcap @@ -13,4 +15,3 @@ def main(): if __name__ == "__main__": main() - diff --git a/selfdrive/test/process_replay/inject_model.py b/selfdrive/test/process_replay/inject_model.py index 08fd74a621..38647b4519 100755 --- a/selfdrive/test/process_replay/inject_model.py +++ b/selfdrive/test/process_replay/inject_model.py @@ -85,8 +85,3 @@ def inject_model(msgs, segment_name): assert abs(len(new_msgs) - len(list(msgs))) < 2 return new_msgs - - - -if __name__ == "__main__": - inject_model("0375fdf7b1ce594d|2019-06-13--08-32-25/3") diff --git a/selfdrive/test/test_eon_fan.py b/selfdrive/test/test_eon_fan.py index 4d683cf4d1..c7e435741b 100755 --- a/selfdrive/test/test_eon_fan.py +++ b/selfdrive/test/test_eon_fan.py @@ -2,7 +2,7 @@ import sys import time -from selfdrive.thermald import setup_eon_fan, set_eon_fan +from selfdrive.thermald.thermald import setup_eon_fan, set_eon_fan if __name__ == "__main__": val = 0 @@ -18,5 +18,3 @@ if __name__ == "__main__": time.sleep(2) val += 1 val %= 4 - - diff --git a/selfdrive/test/test_leeco_alt_fan.py b/selfdrive/test/test_leeco_alt_fan.py index 882ca787a1..c10ede34a7 100755 --- a/selfdrive/test/test_leeco_alt_fan.py +++ b/selfdrive/test/test_leeco_alt_fan.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +# pylint: skip-file + import time from smbus2 import SMBus @@ -18,4 +20,3 @@ def setup_leon_fan(): bus.close() setup_leon_fan() - diff --git a/selfdrive/test/test_leeco_fan.py b/selfdrive/test/test_leeco_fan.py index 2ecccf3053..55267285ba 100755 --- a/selfdrive/test/test_leeco_fan.py +++ b/selfdrive/test/test_leeco_fan.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +# pylint: skip-file + import time from smbus2 import SMBus @@ -20,4 +22,3 @@ def setup_leon_fan(): bus.close() setup_leon_fan() - diff --git a/tools/lib/framereader.py b/tools/lib/framereader.py index 87c6d6e944..741f51dae6 100644 --- a/tools/lib/framereader.py +++ b/tools/lib/framereader.py @@ -1,3 +1,5 @@ +# pylint: skip-file + import os import sys import json diff --git a/tools/lib/kbhit.py b/tools/lib/kbhit.py index 30587590a4..99b88bfbcc 100644 --- a/tools/lib/kbhit.py +++ b/tools/lib/kbhit.py @@ -1,18 +1,17 @@ #!/usr/bin/env python -import os import sys import termios import atexit from select import select + class KBHit: - def __init__(self): '''Creates a KBHit object that you can call to do various keyboard things. ''' - self.set_kbhit_terminal() - + self.set_kbhit_terminal() + def set_kbhit_terminal(self): # Save the terminal settings self.fd = sys.stdin.fileno() @@ -29,12 +28,8 @@ class KBHit: def set_normal_term(self): ''' Resets to normal terminal. On Windows this is a no-op. ''' - - if os.name == 'nt': - pass - - else: - termios.tcsetattr(self.fd, termios.TCSAFLUSH, self.old_term) + + termios.tcsetattr(self.fd, termios.TCSAFLUSH, self.old_term) def getch(self): @@ -42,7 +37,7 @@ class KBHit: Should not be called in the same program as getarrow(). ''' return sys.stdin.read(1) - + def getarrow(self): ''' Returns an arrow-key code after kbhit() has been called. Codes are @@ -52,29 +47,23 @@ class KBHit: 3 : left Should not be called in the same program as getch(). ''' - - if os.name == 'nt': - msvcrt.getch() # skip 0xE0 - c = msvcrt.getch() - vals = [72, 77, 80, 75] - - else: - c = sys.stdin.read(3)[2] - vals = [65, 67, 66, 68] - + + c = sys.stdin.read(3)[2] + vals = [65, 67, 66, 68] + return vals.index(ord(c.decode('utf-8'))) - + def kbhit(self): ''' Returns True if keyboard character was hit, False otherwise. - ''' + ''' dr,dw,de = select([sys.stdin], [], [], 0) return dr != [] - - -# Test + + +# Test if __name__ == "__main__": - + kb = KBHit() print('Hit any key, or ESC to exit') @@ -86,7 +75,5 @@ if __name__ == "__main__": if ord(c) == 27: # ESC break print(c) - - kb.set_normal_term() - + kb.set_normal_term() diff --git a/tools/lib/mkvparse/mkvgen.py b/tools/lib/mkvparse/mkvgen.py index 963d60d019..df1781278d 100755 --- a/tools/lib/mkvparse/mkvgen.py +++ b/tools/lib/mkvparse/mkvgen.py @@ -4,7 +4,7 @@ import random import math # Simple hacky Matroska generator -# Reads mp3 file "q.mp3" and jpeg images from img/0.jpg, img/1.jpg and so on and +# Reads mp3 file "q.mp3" and jpeg images from img/0.jpg, img/1.jpg and so on and # writes Matroska file with mjpeg and mp3 to stdout # License=MIT @@ -71,7 +71,7 @@ def random_uid(): def rint(): return int(random.random()*(0x100**4)) return ben(rint()) + ben(rint()) + ben(rint()) + ben(rint()) - + def example(): write_ebml_header(sys.stdout, "matroska", 2, 2) @@ -133,7 +133,7 @@ def example(): def mp3framesgenerator(f): debt="" while True: - for i in xrange(0,len(debt)+1): + for i in range(0,len(debt)+1): if i >= len(debt)-1: debt = debt + f.read(8192) break @@ -144,13 +144,13 @@ def example(): # sys.stderr.write("len="+str(i)+"\n") debt = debt[i:] break - + mp3 = mp3framesgenerator(mp3file) - mp3.next() + next(mp3) - for i in xrange(0,530): + for i in range(0,530): framefile = open("img/"+str(i)+".jpg", "rb") framedata = framefile.read() framefile.close() @@ -168,8 +168,8 @@ def example(): + framedata ))) - for u in xrange(0,4): - mp3f=mp3.next() + for u in range(0,4): + mp3f=next(mp3) if random.random()<1: sys.stdout.write(ebml_element(0x1F43B675, "" # Cluster + ebml_element(0xE7, ben(i*26*4+u*26)) # TimeCode, uint, milliseconds diff --git a/tools/lib/mkvparse/mkvindex.py b/tools/lib/mkvparse/mkvindex.py index c05423006a..694965fbf6 100644 --- a/tools/lib/mkvparse/mkvindex.py +++ b/tools/lib/mkvparse/mkvindex.py @@ -1,5 +1,5 @@ #!/usr/bin/env python -# Copyright (c) 2016, Comma.ai, Inc. +# flake8: noqa import re import binascii @@ -15,7 +15,7 @@ class MatroskaIndex(mkvparse.MatroskaHandler): self.frameindex = [] def tracks_available(self): - _, self.config_record = self.tracks[1]['CodecPrivate'] + _, self.config_record = self.tracks[1]['CodecPrivate'] # pylint: disable=no-member def frame(self, track_id, timestamp, pos, length, more_laced_frames, duration, keyframe, invisible, discardable): @@ -62,4 +62,3 @@ def simple_gen(of, config_record, w, h, framedata): + ebml_element(0xE7, ben(0)) # TimeCode, uint, milliseconds # + ebml_element(0xA7, ben(0)) # Position, uint + ''.join(blocks))) - diff --git a/tools/lib/mkvparse/mkvparse.py b/tools/lib/mkvparse/mkvparse.py index 114fb4ccea..ea4b7e0104 100644 --- a/tools/lib/mkvparse/mkvparse.py +++ b/tools/lib/mkvparse/mkvparse.py @@ -7,6 +7,7 @@ # No proper EOF handling unfortunately # See "mkvuser.py" for the example +# pylint: skip-file import traceback from struct import unpack @@ -15,7 +16,7 @@ import sys import datetime if sys.version < '3': - range=xrange + range=xrange # pylint disable=undefined-variable else: #identity=lambda x:x def ord(something): @@ -159,7 +160,7 @@ def read_fixedlength_number(f, length, signed=False): buf = f.read(length) (r, pos) = parse_fixedlength_number(buf, 0, length, signed) return r - + def read_ebml_element_header(f): ''' Read Element ID and size @@ -180,10 +181,10 @@ class EbmlElementType: FLOAT=7 DATE=8 - JUST_GO_ON=10 # For "Segment". - # Actually MASTER, but don't build the tree for all subelements, + JUST_GO_ON=10 # For "Segment". + # Actually MASTER, but don't build the tree for all subelements, # interpreting all child elements as if they were top-level elements - + EET=EbmlElementType @@ -510,7 +511,7 @@ def read_ebml_element_tree(f, total_size): while(total_size>0): (id_, size, hsize) = read_ebml_element_header(f) if size == -1: - sys.stderr.write("mkvparse: Element %x without size? Damaged data? Skipping %d bytes\n" % (id_, size, total_size)) + sys.stderr.write("mkvparse: Element %x without size? Damaged data? Skipping %d bytes\n" % (id_, size, total_size)) # pylint disable=too-many-format-args f.read(total_size); break; if size>total_size: @@ -523,9 +524,9 @@ def read_ebml_element_tree(f, total_size): (type_, name) = element_types_names[id_] data = read_simple_element(f, type_, size) total_size-=(size+hsize) - childs.append((name, (type_, data))) + childs.append((name, (type_, data))) return childs - + class MatroskaHandler: """ User for mkvparse should override these methods """ @@ -569,7 +570,7 @@ def handle_block(buffer, buffer_pos, handler, cluster_timecode, timecode_scale=1 handler.frame(tracknum, block_timecode, buffer_pos+pos, len(buffer)-pos, 0, duration, f_keyframe, f_invisible, f_discardable) return - + numframes = ord(buffer[pos]); pos+=1 numframes+=1 @@ -628,9 +629,9 @@ def resync(f): if b2 == b"\x54\xAE\x6B": (seglen ,x )= read_matroska_number(f) return (0x1654AE6B, seglen, x+4) # tracks - - - + + + def mkvparse(f, handler): ''' @@ -655,14 +656,14 @@ def mkvparse(f, handler): (id_, size, hsize) = read_ebml_element_header(f) except StopIteration: break; - if not (id_ in element_types_names): + if not (id_ in element_types_names): sys.stderr.write("mkvparse: Unknown element with id %x and size %d\n"%(id_, size)) (resync_element_id, resync_element_size, resync_element_headersize) = resync(f) if resync_element_id: continue; else: break; - else: + else: id_ = resync_element_id size=resync_element_size hsize=resync_element_headersize @@ -686,7 +687,7 @@ def mkvparse(f, handler): continue; else: break; - + if name=="EBML" and type(data) == list: d = dict(tree) if 'EBMLReadVersion' in d: @@ -694,12 +695,12 @@ def mkvparse(f, handler): if 'DocTypeReadVersion' in d: if d['DocTypeReadVersion'][1]>2: sys.stderr.write("mkvparse: Warning: DocTypeReadVersion too big\n") dt = d['DocType'][1] - if dt != "matroska" and dt != "webm": + if dt != "matroska" and dt != "webm": sys.stderr.write("mkvparse: Warning: EBML DocType is not \"matroska\" or \"webm\"") elif name=="Info" and type(data) == list: handler.segment_info = tree handler.segment_info_available() - + d = dict(tree) if "TimecodeScale" in d: timecode_scale = d["TimecodeScale"][1] diff --git a/tools/replay/unlog_segment.py b/tools/replay/unlog_segment.py index cea3c96971..1c80cd0470 100755 --- a/tools/replay/unlog_segment.py +++ b/tools/replay/unlog_segment.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +# pylint: skip-file + import argparse import bisect import select diff --git a/tools/replay/unlogger.py b/tools/replay/unlogger.py index 920d9d0b34..3463660e86 100755 --- a/tools/replay/unlogger.py +++ b/tools/replay/unlogger.py @@ -421,7 +421,7 @@ def main(argv): if not p.is_alive(): [p.terminate() for p in subprocesses.values()] exit() - signal.signal(signal.SIGCHLD, signal.SIGIGN) + signal.signal(signal.SIGCHLD, signal.SIG_IGN) signal.signal(signal.SIGCHLD, exit_if_children_dead) if args.interactive: diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index 0235e1d9ff..f2949239ea 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -79,7 +79,7 @@ def go(q): threading.Thread(target=health_function).start() threading.Thread(target=fake_driver_monitoring).start() - import carla + import carla # pylint: disable=import-error client = carla.Client("127.0.0.1", 2000) client.set_timeout(5.0) world = client.load_world('Town04') @@ -231,7 +231,7 @@ if __name__ == "__main__": print("WARNING: NO CARLA") while 1: time.sleep(1) - + from multiprocessing import Process, Queue q = Queue() p = Process(target=go, args=(q,)) @@ -246,4 +246,3 @@ if __name__ == "__main__": # start input poll for keyboard from lib.keyboard_ctrl import keyboard_poll_thread keyboard_poll_thread(q) - diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index 3948e818b5..a446d38cd5 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import cereal.messaging as messaging from opendbc.can.packer import CANPacker -from selfdrive.boardd.boardd_api_impl import can_list_to_can_capnp +from selfdrive.boardd.boardd_api_impl import can_list_to_can_capnp # pylint: disable=no-name-in-module from selfdrive.car.honda.values import FINGERPRINTS, CAR from selfdrive.car import crc8_pedal import math @@ -88,4 +88,3 @@ def sendcan_function(sendcan): steer_torque = 0.0 return (gas, brake, steer_torque) - diff --git a/tools/sim/lib/manual_ctrl.py b/tools/sim/lib/manual_ctrl.py index a32d606d43..4c94c13f7b 100755 --- a/tools/sim/lib/manual_ctrl.py +++ b/tools/sim/lib/manual_ctrl.py @@ -132,8 +132,8 @@ def wheel_poll_thread(q): print('%d buttons found: %s' % (num_buttons, ', '.join(button_map))) # Enable FF - import evdev - from evdev import ecodes, InputDevice, ff + import evdev # pylint: disable=import-error + from evdev import ecodes, InputDevice, ff # pylint: disable=import-error device = evdev.list_devices()[0] evtdev = InputDevice(device) val = 24000 diff --git a/tools/streamer/streamerd.py b/tools/streamer/streamerd.py index 6ce940afc0..81b20fa2d2 100755 --- a/tools/streamer/streamerd.py +++ b/tools/streamer/streamerd.py @@ -1,4 +1,6 @@ #!/usr/bin/env python +# pylint: skip-file + import os import sys import zmq From 29aaa44740b5dae3c1cc0c273c72c7eb53135e5e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 27 May 2020 20:33:05 -0700 Subject: [PATCH 110/656] flake8 in pre-commit(#1583) --- .pre-commit-config.yaml | 7 +++++++ common/tests/test_numpy_fast.py | 1 - selfdrive/camerad/test/frame_test.py | 2 -- selfdrive/locationd/liblocationd_py.py | 1 - selfdrive/locationd/models/loc_kf.py | 2 +- selfdrive/test/eon_testing_slave.py | 12 ++++++------ selfdrive/test/process_replay/inject_model.py | 7 ++----- selfdrive/test/profiling/controlsd.py | 1 - selfdrive/test/test_leeco_alt_fan.py | 6 +++--- selfdrive/test/update_ci_routes.py | 5 +---- tools/lib/framereader.py | 9 ++++----- tools/lib/mkvparse/mkvgen.py | 1 - tools/lib/mkvparse/mkvparse.py | 1 + tools/replay/ui.py | 1 - tools/sim/bridge.py | 1 - tools/sim/lib/keyboard_ctrl.py | 6 +++--- tools/sim/lib/manual_ctrl.py | 2 +- tools/streamer/streamerd.py | 10 +++++----- 18 files changed, 34 insertions(+), 41 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 990e27819f..96ba5e5e96 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -6,6 +6,13 @@ repos: - id: check-json - id: check-xml - id: check-yaml +- repo: https://gitlab.com/PyCQA/flake8 + rev: master + hooks: + - id: flake8 + exclude: '^(pyextra)|(external)/' + args: + - --select=F - repo: local hooks: - id: pylint diff --git a/common/tests/test_numpy_fast.py b/common/tests/test_numpy_fast.py index bf34de2ed7..2fb8a1cef3 100644 --- a/common/tests/test_numpy_fast.py +++ b/common/tests/test_numpy_fast.py @@ -1,6 +1,5 @@ import numpy as np import unittest -import timeit from common.numpy_fast import interp diff --git a/selfdrive/camerad/test/frame_test.py b/selfdrive/camerad/test/frame_test.py index 2518e80344..d7b677c232 100755 --- a/selfdrive/camerad/test/frame_test.py +++ b/selfdrive/camerad/test/frame_test.py @@ -1,5 +1,4 @@ #!/usr/bin/env python3 -import time import numpy as np import cereal.messaging as messaging from PIL import ImageFont, ImageDraw, Image @@ -36,4 +35,3 @@ if __name__ == "__main__": idx += 1 rk.keep_time() #time.sleep(1.0) - diff --git a/selfdrive/locationd/liblocationd_py.py b/selfdrive/locationd/liblocationd_py.py index d9f71b8c30..09d2bb756c 100644 --- a/selfdrive/locationd/liblocationd_py.py +++ b/selfdrive/locationd/liblocationd_py.py @@ -1,5 +1,4 @@ import os -from common.basedir import BASEDIR from cffi import FFI diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index fbb6b1b58d..06e16045d6 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -340,7 +340,7 @@ class LocKalman(): for n in range(N): idx = dim_main + n * dim_augment - err_idx = dim_main_err + n * dim_augment_err # FIXME: Why is this not used? + # err_idx = dim_main_err + n * dim_augment_err # FIXME: Why is this not used? x, y, z = state[idx:idx + 3] q = state[idx + 3:idx + 7] quat_rot = quat_rotate(*q) diff --git a/selfdrive/test/eon_testing_slave.py b/selfdrive/test/eon_testing_slave.py index 008b8c6343..e4b8ae1c8b 100755 --- a/selfdrive/test/eon_testing_slave.py +++ b/selfdrive/test/eon_testing_slave.py @@ -36,11 +36,11 @@ def get_workdir(): def heartbeat(): work_dir = get_workdir() - env = { - "LD_LIBRARY_PATH": "", - "ANDROID_DATA": "/data", - "ANDROID_ROOT": "/system", - } + # env = { + # "LD_LIBRARY_PATH": "", + # "ANDROID_DATA": "/data", + # "ANDROID_ROOT": "/system", + # } while True: try: @@ -53,7 +53,7 @@ def heartbeat(): try: tmux = os.popen('tail -n 100 /tmp/tmux_out').read() - except: + except Exception: pass params = Params() diff --git a/selfdrive/test/process_replay/inject_model.py b/selfdrive/test/process_replay/inject_model.py index 38647b4519..98a6794d7e 100755 --- a/selfdrive/test/process_replay/inject_model.py +++ b/selfdrive/test/process_replay/inject_model.py @@ -1,14 +1,12 @@ #!/usr/bin/env python3 -import os import time - from tqdm import tqdm + +import selfdrive.manager as manager from cereal.messaging import PubMaster, recv_one, sub_sock from tools.lib.framereader import FrameReader -import subprocess -import selfdrive.manager as manager def rreplace(s, old, new, occurrence): @@ -22,7 +20,6 @@ def regen_model(msgs, pm, frame_reader, model_sock): if msg.which() == 'liveCalibration': pm.send('liveCalibration', msg.as_builder()) - out_msgs = [] fidx = 0 for msg in tqdm(msgs): diff --git a/selfdrive/test/profiling/controlsd.py b/selfdrive/test/profiling/controlsd.py index 6ea3114429..38ce860d35 100755 --- a/selfdrive/test/profiling/controlsd.py +++ b/selfdrive/test/profiling/controlsd.py @@ -1,7 +1,6 @@ #!/usr/bin/env python3 import os -import time import cProfile import pprofile import pyprof2calltree diff --git a/selfdrive/test/test_leeco_alt_fan.py b/selfdrive/test/test_leeco_alt_fan.py index c10ede34a7..c14d943e2c 100755 --- a/selfdrive/test/test_leeco_alt_fan.py +++ b/selfdrive/test/test_leeco_alt_fan.py @@ -11,10 +11,10 @@ def setup_leon_fan(): for i in [0,1,2,3]: print("FAN SPEED", i) if i == 0: - ret = bus.write_i2c_block_data(0x67, 0xa, [0]) + bus.write_i2c_block_data(0x67, 0xa, [0]) else: - ret = bus.write_i2c_block_data(0x67, 0xa, [0x20]) - ret = bus.write_i2c_block_data(0x67, 0x8, [(i-1)<<6]) + bus.write_i2c_block_data(0x67, 0xa, [0x20]) + bus.write_i2c_block_data(0x67, 0x8, [(i-1)<<6]) time.sleep(1) bus.close() diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py index 09b8d170d7..77db292915 100755 --- a/selfdrive/test/update_ci_routes.py +++ b/selfdrive/test/update_ci_routes.py @@ -1,6 +1,4 @@ #!/usr/bin/env python3 -import tempfile -import shutil import subprocess from common.basedir import BASEDIR from azure.storage.blob import BlockBlobService @@ -8,8 +6,7 @@ from azure.storage.blob import BlockBlobService from selfdrive.test.test_car_models import routes as test_car_models_routes from selfdrive.test.process_replay.test_processes import segments as replay_segments from xx.chffr.lib import azureutil -from xx.chffr.lib.storage import upload_dir_serial, download_dir_tpe -from xx.chffr.lib.storage import _DATA_ACCOUNT_PRODUCTION, _DATA_ACCOUNT_CI, _DATA_BUCKET_PRODUCTION, _DATA_BUCKET_CI +from xx.chffr.lib.storage import _DATA_ACCOUNT_PRODUCTION, _DATA_ACCOUNT_CI, _DATA_BUCKET_PRODUCTION SOURCES = [ (_DATA_ACCOUNT_PRODUCTION, _DATA_BUCKET_PRODUCTION), diff --git a/tools/lib/framereader.py b/tools/lib/framereader.py index 741f51dae6..695be4ab6a 100644 --- a/tools/lib/framereader.py +++ b/tools/lib/framereader.py @@ -8,6 +8,7 @@ import tempfile import threading import xml.etree.ElementTree as ET import numpy as np +import _io if sys.version_info >= (3,0): import queue import pickle @@ -83,7 +84,7 @@ def ffprobe(fn, fmt=None): try: ffprobe_output = subprocess.check_output(cmd) - except subprocess.CalledProcessError as e: + except subprocess.CalledProcessError: raise DataUnreadableError(fn) return json.loads(ffprobe_output) @@ -99,7 +100,7 @@ def vidindex(fn, typ): tempfile.NamedTemporaryFile() as index_f: try: subprocess.check_call([vidindex, typ, fn, prefix_f.name, index_f.name]) - except subprocess.CalledProcessError as e: + except subprocess.CalledProcessError: raise DataUnreadableError("vidindex failed on file %s" % fn) with open(index_f.name, "rb") as f: index = f.read() @@ -388,8 +389,6 @@ def index_pstream(fns, typ, cache_prefix=None): assert frame_b >= 0 assert index[frame_b, 0] == H264_SLICE_I - end_len = len(index)-frame_b - with FileReader(fns[i]) as vid: vid.seek(index[frame_b, 1]) end_data = vid.read() @@ -433,7 +432,7 @@ def _set_pdeathsig(sig=signal.SIGTERM): def vidindex_mp4(fn): try: xmls = subprocess.check_output(["MP4Box", fn, "-diso", "-out", "/dev/stdout"]) - except subprocess.CalledProcessError as e: + except subprocess.CalledProcessError: raise DataUnreadableError(fn) tree = ET.fromstring(xmls) diff --git a/tools/lib/mkvparse/mkvgen.py b/tools/lib/mkvparse/mkvgen.py index df1781278d..a98fa299b0 100755 --- a/tools/lib/mkvparse/mkvgen.py +++ b/tools/lib/mkvparse/mkvgen.py @@ -1,7 +1,6 @@ #!/usr/bin/env python import sys import random -import math # Simple hacky Matroska generator # Reads mp3 file "q.mp3" and jpeg images from img/0.jpg, img/1.jpg and so on and diff --git a/tools/lib/mkvparse/mkvparse.py b/tools/lib/mkvparse/mkvparse.py index ea4b7e0104..8e9816347c 100644 --- a/tools/lib/mkvparse/mkvparse.py +++ b/tools/lib/mkvparse/mkvparse.py @@ -8,6 +8,7 @@ # See "mkvuser.py" for the example # pylint: skip-file +# flake8: noqa import traceback from struct import unpack diff --git a/tools/replay/ui.py b/tools/replay/ui.py index 2a91c1b55b..ee07a28137 100755 --- a/tools/replay/ui.py +++ b/tools/replay/ui.py @@ -63,7 +63,6 @@ def ui_thread(addr, frame_address): camera_surface = pygame.surface.Surface((640, 480), 0, 24).convert() cameraw_surface = pygame.surface.Surface(MODEL_INPUT_SIZE, 0, 24).convert() - cameraw_test_surface = pygame.surface.Surface(MODEL_INPUT_SIZE, 0, 24) top_down_surface = pygame.surface.Surface((UP.lidar_x, UP.lidar_y),0,8) frame = messaging.sub_sock('frame', addr=addr, conflate=True) diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index f2949239ea..b3857683c0 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -79,7 +79,6 @@ def go(q): threading.Thread(target=health_function).start() threading.Thread(target=fake_driver_monitoring).start() - import carla # pylint: disable=import-error client = carla.Client("127.0.0.1", 2000) client.set_timeout(5.0) world = client.load_world('Town04') diff --git a/tools/sim/lib/keyboard_ctrl.py b/tools/sim/lib/keyboard_ctrl.py index 8be3ca0dda..84436d5387 100644 --- a/tools/sim/lib/keyboard_ctrl.py +++ b/tools/sim/lib/keyboard_ctrl.py @@ -1,7 +1,8 @@ -import time import sys import termios -from termios import * +import time +from termios import (BRKINT, VMIN, CS8, CSIZE, ECHO, ICANON, ICRNL, IEXTEN, + INPCK, ISIG, ISTRIP, IXON, PARENB, VTIME) # Indexes for termios list. IFLAG = 0 @@ -58,4 +59,3 @@ if __name__ == '__main__': p.start() keyboard_poll_thread(q) - diff --git a/tools/sim/lib/manual_ctrl.py b/tools/sim/lib/manual_ctrl.py index 4c94c13f7b..6e7fe6e6a2 100755 --- a/tools/sim/lib/manual_ctrl.py +++ b/tools/sim/lib/manual_ctrl.py @@ -133,7 +133,7 @@ def wheel_poll_thread(q): # Enable FF import evdev # pylint: disable=import-error - from evdev import ecodes, InputDevice, ff # pylint: disable=import-error + from evdev import ecodes, InputDevice # pylint: disable=import-error device = evdev.list_devices()[0] evtdev = InputDevice(device) val = 24000 diff --git a/tools/streamer/streamerd.py b/tools/streamer/streamerd.py index 81b20fa2d2..9cbb2f064b 100755 --- a/tools/streamer/streamerd.py +++ b/tools/streamer/streamerd.py @@ -40,12 +40,12 @@ def receiver_thread(): ctx = av.codec.codec.Codec('hevc', 'r').create() ctx.decode(av.packet.Packet(start.decode("hex"))) - import time + # import time while 1: - t1 = time.time() + # t1 = time.time() ts, raw = s.recv_multipart() ts = struct.unpack('q', ts)[0] * 1000 - t1, t2 = time.time(), t1 + # t1, t2 = time.time(), t1 #print 'ms to get frame:', (t1-t2)*1000 pkt = av.packet.Packet(raw) @@ -53,14 +53,14 @@ def receiver_thread(): if not f: continue f = f[0] - t1, t2 = time.time(), t1 + # t1, t2 = time.time(), t1 #print 'ms to decode:', (t1-t2)*1000 y_plane = np.frombuffer(f.planes[0], np.uint8).reshape((874, 1216))[:, 0:1164] u_plane = np.frombuffer(f.planes[1], np.uint8).reshape((437, 608))[:, 0:582] v_plane = np.frombuffer(f.planes[2], np.uint8).reshape((437, 608))[:, 0:582] yuv_img = y_plane.tobytes() + u_plane.tobytes() + v_plane.tobytes() - t1, t2 = time.time(), t1 + # t1, t2 = time.time(), t1 #print 'ms to make yuv:', (t1-t2)*1000 #print 'tsEof:', ts From 0499ae46b7842e8e49067ebba03016c6cd305d4e Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Thu, 28 May 2020 01:46:30 -0700 Subject: [PATCH 111/656] Static C/C++ analysis in CI (#1564) --- .github/workflows/test.yaml | 26 ++++++++++++++++++-------- .gitignore | 1 + Dockerfile.openpilot | 2 +- cppcheck_openpilot.sh | 4 ++++ 4 files changed, 24 insertions(+), 9 deletions(-) create mode 100755 cppcheck_openpilot.sh diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index c50cd8cab6..c1f5c524f0 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -37,7 +37,7 @@ jobs: # need these so docker copy won't fail cp Pipfile Pipfile.lock flake8_openpilot.sh pylint_openpilot.sh .pylintrc \ - .coveragerc-app $TEST_DIR + cppcheck_openpilot.sh .coveragerc-app $TEST_DIR cd $TEST_DIR mkdir pyextra laika laika_repo tools release - name: Build Docker image @@ -49,7 +49,7 @@ jobs: name: docker push runs-on: ubuntu-16.04 if: github.ref == 'refs/heads/master' && github.event_name != 'pull_request' && github.repository == 'commaai/openpilot' - needs: linter # hack to ensure slow tests run first since this and linter are fast + needs: static_analysis # hack to ensure slow tests run first since this and static_analysis are fast steps: - uses: actions/checkout@v2 with: @@ -62,8 +62,8 @@ jobs: docker tag tmppilot docker.io/commaai/openpilot:latest docker push docker.io/commaai/openpilot:latest - linter: - name: linter + static_analysis: + name: static analysis runs-on: ubuntu-16.04 steps: - uses: actions/checkout@v2 @@ -75,6 +75,18 @@ jobs: run: $RUN "cd /tmp/openpilot/ && ./flake8_openpilot.sh" - name: pylint run: $RUN "cd /tmp/openpilot/ && ./pylint_openpilot.sh" + - name: cppcheck + run: $PERSIST "cd /tmp/openpilot/ && ./cppcheck_openpilot.sh 2> cppcheck_report.txt" + - name: Print cppcheck report + if: always() + run: | + docker cp tmppilot:/tmp/openpilot/cppcheck_report.txt cppcheck_report.txt + cat cppcheck_report.txt + - uses: actions/upload-artifact@v2 + if: always() + with: + name: cppcheck_report.txt + path: cppcheck_report.txt unit_tests: name: unit tests @@ -123,13 +135,11 @@ jobs: run: | docker commit tmppilot tmppilotci $CI_RUN "cd /tmp/openpilot && bash <(curl -s https://codecov.io/bash) -Z -F process_replay" - - name: Copy diff + - name: Print diff if: always() run: | docker cp tmppilot:/tmp/openpilot/selfdrive/test/process_replay/diff.txt diff.txt - - name: Print diff - if: always() - run: cat diff.txt + cat diff.txt - uses: actions/upload-artifact@v2 if: always() with: diff --git a/.gitignore b/.gitignore index c6efe5cf35..8f21086a7c 100644 --- a/.gitignore +++ b/.gitignore @@ -57,6 +57,7 @@ panda_jungle .coverage* coverage.xml +cppcheck_report.txt htmlcov pandaextra diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index e5b1f2491c..205e5f198c 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -46,7 +46,6 @@ ENV LANG en_US.UTF-8 ENV LANGUAGE en_US:en ENV LC_ALL en_US.UTF-8 -# Install python dependencies RUN curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash ENV PATH="/root/.pyenv/bin:/root/.pyenv/shims:${PATH}" @@ -77,6 +76,7 @@ RUN pyenv install 3.8.2 && \ RUN mkdir -p /tmp/openpilot COPY SConstruct \ + cppcheck_openpilot.sh \ flake8_openpilot.sh \ pylint_openpilot.sh \ .pylintrc \ diff --git a/cppcheck_openpilot.sh b/cppcheck_openpilot.sh new file mode 100755 index 0000000000..6f6520806f --- /dev/null +++ b/cppcheck_openpilot.sh @@ -0,0 +1,4 @@ +#!/bin/bash + +cppcheck --force -j$(nproc) selfdrive/ common/ opendbc/ cereal/ installer/ 2> cppcheck_report.txt + From 2bcab668d4db5ca940d6f82ee43dd486f13cad3a Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Thu, 28 May 2020 11:07:07 -0500 Subject: [PATCH 112/656] Added CAR.COROLLA_TSS2 EPS f/w x018965B12520 (#1587) As seen in Discord, for DongleID/route 35794509ea3b423e|2020-05-28--14-51-06 (Euro Toyota Corolla Hatchback Hybrid)... https://discord.com/channels/469524606043160576/524327905937850394/715579226186579985 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 8b64181538..75ea689ca8 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -450,6 +450,7 @@ FW_VERSIONS = { b'8965B12361\x00\x00\x00\x00\x00\x00', b'\x018965B12350\x00\x00\x00\x00\x00\x00', b'\x018965B12500\x00\x00\x00\x00\x00\x00', + b'\x018965B12520\x00\x00\x00\x00\x00\x00', b'\x018965B12530\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ From 44851ae93441fc918fabde908078058befde8323 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 28 May 2020 11:53:06 -0700 Subject: [PATCH 113/656] bump opendbc --- opendbc | 2 +- selfdrive/car/toyota/toyotacan.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/opendbc b/opendbc index 45c0d9ecce..d1185a53e5 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 45c0d9ecce255e028163539e22e9a169735de69d +Subproject commit d1185a53e5b942a5dda7ddb8c827e23fa667c10a diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py index bdd84e7128..93176b359c 100644 --- a/selfdrive/car/toyota/toyotacan.py +++ b/selfdrive/car/toyota/toyotacan.py @@ -36,7 +36,7 @@ def create_accel_command(packer, accel, pcm_cancel, standstill_req, lead): "DISTANCE": 0, "MINI_CAR": lead, "SET_ME_X3": 3, - "SET_ME_1": 1, + "PERMIT_BRAKING": 1, "RELEASE_STANDSTILL": not standstill_req, "CANCEL_REQ": pcm_cancel, } From 639cf2288f3527230d103ba9e12652f52d38ad39 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 28 May 2020 12:45:38 -0700 Subject: [PATCH 114/656] framereader only has to support h265 and raw (#1588) --- tools/lib/framereader.py | 843 ++++++--------------------------- tools/lib/mkvparse/README.md | 24 - tools/lib/mkvparse/__init__.py | 0 tools/lib/mkvparse/mkvgen.py | 187 -------- tools/lib/mkvparse/mkvindex.py | 64 --- tools/lib/mkvparse/mkvparse.py | 763 ----------------------------- 6 files changed, 152 insertions(+), 1729 deletions(-) delete mode 100644 tools/lib/mkvparse/README.md delete mode 100644 tools/lib/mkvparse/__init__.py delete mode 100755 tools/lib/mkvparse/mkvgen.py delete mode 100644 tools/lib/mkvparse/mkvindex.py delete mode 100644 tools/lib/mkvparse/mkvparse.py diff --git a/tools/lib/framereader.py b/tools/lib/framereader.py index 695be4ab6a..dd27ba1706 100644 --- a/tools/lib/framereader.py +++ b/tools/lib/framereader.py @@ -1,55 +1,51 @@ # pylint: skip-file - -import os -import sys import json +import os +import pickle +import queue import struct +import subprocess import tempfile import threading -import xml.etree.ElementTree as ET -import numpy as np -import _io -if sys.version_info >= (3,0): - import queue - import pickle - from io import BytesIO as StringIO -else: - import Queue as queue - import cPickle as pickle - from cStringIO import StringIO +from functools import wraps -import subprocess +import numpy as np from aenum import Enum from lru import LRU -from functools import wraps +import _io from tools.lib.cache import cache_path_for_file_path from tools.lib.exceptions import DataUnreadableError +from tools.lib.file_helpers import atomic_write_in_dir + try: from xx.chffr.lib.filereader import FileReader except ImportError: from tools.lib.filereader import FileReader -from tools.lib.file_helpers import atomic_write_in_dir -from tools.lib.mkvparse import mkvindex -from tools.lib.route import Route - -H264_SLICE_P = 0 -H264_SLICE_B = 1 -H264_SLICE_I = 2 HEVC_SLICE_B = 0 HEVC_SLICE_P = 1 HEVC_SLICE_I = 2 -SLICE_I = 2 # hevc and h264 are the same :) + +class GOPReader: + def get_gop(self, num): + # returns (start_frame_num, num_frames, frames_to_skip, gop_data) + raise NotImplementedError + + +class DoNothingContextManager: + def __enter__(self): + return self + + def __exit__(self, *x): + pass + class FrameType(Enum): raw = 1 h265_stream = 2 - h264_mp4 = 3 - h264_pstream = 4 - ffv1_mkv = 5 - ffvhuff_mkv = 6 + def fingerprint_video(fn): with FileReader(fn) as f: @@ -61,23 +57,17 @@ def fingerprint_video(fn): elif header == b"\x00\x00\x00\x01": if 'hevc' in fn: return FrameType.h265_stream - elif os.path.basename(fn) in ("camera", "acamera"): - return FrameType.h264_pstream else: raise NotImplementedError(fn) - elif header == b"\x00\x00\x00\x1c": - return FrameType.h264_mp4 - elif header == b"\x1a\x45\xdf\xa3": - return FrameType.ffv1_mkv else: raise NotImplementedError(fn) def ffprobe(fn, fmt=None): cmd = ["ffprobe", - "-v", "quiet", - "-print_format", "json", - "-show_format", "-show_streams"] + "-v", "quiet", + "-print_format", "json", + "-show_format", "-show_streams"] if fmt: cmd += ["-f", fmt] cmd += [fn] @@ -94,7 +84,7 @@ def vidindex(fn, typ): vidindex_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "vidindex") vidindex = os.path.join(vidindex_dir, "vidindex") - subprocess.check_call(["make"], cwd=vidindex_dir, stdout=open("/dev/null","w")) + subprocess.check_call(["make"], cwd=vidindex_dir, stdout=open("/dev/null", "w")) with tempfile.NamedTemporaryFile() as prefix_f, \ tempfile.NamedTemporaryFile() as index_f: @@ -138,9 +128,10 @@ def cache_fn(func): return cache_inner + @cache_fn def index_stream(fn, typ): - assert typ in ("hevc", "h264") + assert typ in ("hevc", ) with FileReader(fn) as f: assert os.path.exists(f.name), fn @@ -153,22 +144,6 @@ def index_stream(fn, typ): 'probe': probe } -@cache_fn -def index_mp4(fn): - with FileReader(fn) as f: - return vidindex_mp4(f.name) - -@cache_fn -def index_mkv(fn): - with FileReader(fn) as f: - probe = ffprobe(f.name, "matroska") - with open(f.name, "rb") as d_f: - config_record, index = mkvindex.mkvindex(d_f) - return { - 'probe': probe, - 'config_record': config_record, - 'index': index - } def index_videos(camera_paths, cache_prefix=None): """Requires that paths in camera_paths are contiguous and of the same type.""" @@ -176,11 +151,9 @@ def index_videos(camera_paths, cache_prefix=None): raise ValueError("must provide at least one video to index") frame_type = fingerprint_video(camera_paths[0]) - if frame_type == FrameType.h264_pstream: - index_pstream(camera_paths, "h264", cache_prefix) - else: - for fn in camera_paths: - index_video(fn, frame_type, cache_prefix) + for fn in camera_paths: + index_video(fn, frame_type, cache_prefix) + def index_video(fn, frame_type=None, cache_prefix=None): cache_path = cache_path_for_file_path(fn, cache_prefix) @@ -191,20 +164,11 @@ def index_video(fn, frame_type=None, cache_prefix=None): if frame_type is None: frame_type = fingerprint_video(fn[0]) - if frame_type == FrameType.h264_pstream: - #hack: try to index the whole route now - route = Route.from_file_path(fn) - - camera_paths = route.camera_paths() - if fn not in camera_paths: - raise DataUnreadableError("Not a contiguous route camera file: {}".format(fn)) - - print("no pstream cache for %s, indexing route %s now" % (fn, route.name)) - index_pstream(route.camera_paths(), "h264", cache_prefix) - elif frame_type == FrameType.h265_stream: + if frame_type == FrameType.h265_stream: index_stream(fn, "hevc", cache_prefix=cache_prefix) - elif frame_type == FrameType.h264_mp4: - index_mp4(fn, cache_prefix=cache_prefix) + else: + raise NotImplementedError("Only h265 supported") + def get_video_index(fn, frame_type, cache_prefix=None): cache_path = cache_path_for_file_path(fn, cache_prefix) @@ -217,202 +181,6 @@ def get_video_index(fn, frame_type, cache_prefix=None): with open(cache_path, "rb") as cache_file: return pickle.load(cache_file) -def pstream_predecompress(fns, probe, indexes, global_prefix, cache_prefix, multithreaded=False): - assert len(fns) == len(indexes) - out_fns = [cache_path_for_file_path(fn, cache_prefix, extension=".predecom.mkv") for fn in fns] - out_exists = map(os.path.exists, out_fns) - if all(out_exists): - return - - w = probe['streams'][0]['width'] - h = probe['streams'][0]['height'] - - frame_size = w*h*3/2 # yuv420p - - decompress_proc = subprocess.Popen( - ["ffmpeg", - "-threads", "0" if multithreaded else "1", - "-vsync", "0", - "-f", "h264", - "-i", "pipe:0", - "-threads", "0" if multithreaded else "1", - "-f", "rawvideo", - "-pix_fmt", "yuv420p", - "pipe:1"], - stdin=subprocess.PIPE, stdout=subprocess.PIPE, stderr=open("/dev/null", "wb")) - - def write_thread(): - for fn in fns: - with FileReader(fn) as f: - decompress_proc.stdin.write(f.read()) - decompress_proc.stdin.close() - - def read_frame(): - frame = None - try: - frame = decompress_proc.stdout.read(frame_size) - except (IOError, ValueError): - pass - if frame is None or frame == "" or len(frame) != frame_size: - raise DataUnreadableError("pre-decompression failed for %s" % fn) - return frame - - t = threading.Thread(target=write_thread) - t.daemon = True - t.start() - - try: - for fn, out_fn, out_exist, index in zip(fns, out_fns, out_exists, indexes): - if out_exist: - for fi in range(index.shape[0]-1): - read_frame() - continue - - with atomic_write_in_dir(out_fn, mode="w+b", overwrite=True) as out_tmp: - compress_proc = subprocess.Popen( - ["ffmpeg", - "-threads", "0" if multithreaded else "1", - "-y", - "-vsync", "0", - "-f", "rawvideo", - "-pix_fmt", "yuv420p", - "-s", "%dx%d" % (w, h), - "-i", "pipe:0", - "-threads", "0" if multithreaded else "1", - "-f", "matroska", - "-vcodec", "ffv1", - "-g", "0", - out_tmp.name], - stdin=subprocess.PIPE, stderr=open("/dev/null", "wb")) - try: - for fi in range(index.shape[0]-1): - frame = read_frame() - compress_proc.stdin.write(frame) - compress_proc.stdin.close() - except: - compress_proc.kill() - raise - - assert compress_proc.wait() == 0 - - cache_path = cache_path_for_file_path(fn, cache_prefix) - with atomic_write_in_dir(cache_path, mode="wb", overwrite=True) as cache_file: - pickle.dump({ - 'predecom': os.path.basename(out_fn), - 'index': index, - 'probe': probe, - 'global_prefix': global_prefix, - }, cache_file, -1) - - except: - decompress_proc.kill() - raise - finally: - t.join() - - rc = decompress_proc.wait() - if rc != 0: - raise DataUnreadableError(fns[0]) - - -def index_pstream(fns, typ, cache_prefix=None): - if typ != "h264": - raise NotImplementedError(typ) - - if not fns: - raise DataUnreadableError("chffr h264 requires contiguous files") - - out_fns = [cache_path_for_file_path(fn, cache_prefix) for fn in fns] - out_exists = map(os.path.exists, out_fns) - if all(out_exists): return - - # load existing index files to avoid re-doing work - existing_indexes = [] - for out_fn, exists in zip(out_fns, out_exists): - existing = None - if exists: - with open(out_fn, "rb") as cache_file: - existing = pickle.load(cache_file) - existing_indexes.append(existing) - - # probe the first file - if existing_indexes[0]: - probe = existing_indexes[0]['probe'] - else: - with FileReader(fns[0]) as f: - probe = ffprobe(f.name, typ) - - global_prefix = None - - # get the video index of all the segments in this stream - indexes = [] - for i, fn in enumerate(fns): - if existing_indexes[i]: - index = existing_indexes[i]['index'] - prefix = existing_indexes[i]['global_prefix'] - else: - with FileReader(fn) as f: - index, prefix = vidindex(f.name, typ) - if i == 0: - # assert prefix - if not prefix: - raise DataUnreadableError("vidindex failed for %s" % fn) - global_prefix = prefix - indexes.append(index) - - assert global_prefix - - if np.sum(indexes[0][:, 0] == H264_SLICE_I) <= 1: - print("pstream %s is unseekable. pre-decompressing all the segments..." % (fns[0])) - pstream_predecompress(fns, probe, indexes, global_prefix, cache_prefix) - return - - # generate what's required to make each segment self-contained - # (the partial GOP from the end of each segments are put asside to add - # to the start of the following segment) - prefix_data = ["" for _ in fns] - prefix_index = [[] for _ in fns] - for i in range(len(fns)-1): - if indexes[i+1][0, 0] == H264_SLICE_I and indexes[i+1][0, 1] <= 1: - # next file happens to start with a i-frame, dont need use this file's end - continue - - index = indexes[i] - if i == 0 and np.sum(index[:, 0] == H264_SLICE_I) <= 1: - raise NotImplementedError("No I-frames in pstream.") - - # find the last GOP in the index - frame_b = len(index)-1 - while frame_b > 0 and index[frame_b, 0] != H264_SLICE_I: - frame_b -= 1 - - assert frame_b >= 0 - assert index[frame_b, 0] == H264_SLICE_I - - with FileReader(fns[i]) as vid: - vid.seek(index[frame_b, 1]) - end_data = vid.read() - - prefix_data[i+1] = end_data - prefix_index[i+1] = index[frame_b:-1] - # indexes[i] = index[:frame_b] - - for i, fn in enumerate(fns): - cache_path = out_fns[i] - - if os.path.exists(cache_path): - continue - - segment_index = { - 'index': indexes[i], - 'global_prefix': global_prefix, - 'probe': probe, - 'prefix_frame_data': prefix_data[i], # data to prefix the first GOP with - 'num_prefix_frames': len(prefix_index[i]), # number of frames to skip in the first GOP - } - - with atomic_write_in_dir(cache_path, mode="wb", overwrite=True) as cache_file: - pickle.dump(segment_index, cache_file, -1) def read_file_check_size(f, sz, cookie): buff = bytearray(sz) @@ -421,118 +189,65 @@ def read_file_check_size(f, sz, cookie): return buff -import signal -import ctypes -def _set_pdeathsig(sig=signal.SIGTERM): - def f(): - libc = ctypes.CDLL('libc.so.6') - return libc.prctl(1, sig) - return f - -def vidindex_mp4(fn): - try: - xmls = subprocess.check_output(["MP4Box", fn, "-diso", "-out", "/dev/stdout"]) - except subprocess.CalledProcessError: - raise DataUnreadableError(fn) - - tree = ET.fromstring(xmls) - - def parse_content(s): - assert s.startswith("data:application/octet-string,") - return s[len("data:application/octet-string,"):].decode("hex") - - avc_element = tree.find(".//AVCSampleEntryBox") - width = int(avc_element.attrib['Width']) - height = int(avc_element.attrib['Height']) +def rgb24toyuv420(rgb): + yuv_from_rgb = np.array([[ 0.299 , 0.587 , 0.114 ], + [-0.14714119, -0.28886916, 0.43601035 ], + [ 0.61497538, -0.51496512, -0.10001026 ]]) + img = np.dot(rgb.reshape(-1, 3), yuv_from_rgb.T).reshape(rgb.shape) - sps_element = avc_element.find(".//AVCDecoderConfigurationRecord/SequenceParameterSet") - pps_element = avc_element.find(".//AVCDecoderConfigurationRecord/PictureParameterSet") + y_len = img.shape[0] * img.shape[1] + uv_len = y_len / 4 - sps = parse_content(sps_element.attrib['content']) - pps = parse_content(pps_element.attrib['content']) + ys = img[:, :, 0] + us = (img[::2, ::2, 1] + img[1::2, ::2, 1] + img[::2, 1::2, 1] + img[1::2, 1::2, 1]) / 4 + 128 + vs = (img[::2, ::2, 2] + img[1::2, ::2, 2] + img[::2, 1::2, 2] + img[1::2, 1::2, 2]) / 4 + 128 - media_header = tree.find("MovieBox/TrackBox/MediaBox/MediaHeaderBox") - time_scale = int(media_header.attrib['TimeScale']) + yuv420 = np.empty(y_len + 2 * uv_len, dtype=img.dtype) + yuv420[:y_len] = ys.reshape(-1) + yuv420[y_len:y_len + uv_len] = us.reshape(-1) + yuv420[y_len + uv_len:y_len + 2 * uv_len] = vs.reshape(-1) - sample_sizes = [ - int(entry.attrib['Size']) for entry in tree.findall( - "MovieBox/TrackBox/MediaBox/MediaInformationBox/SampleTableBox/SampleSizeBox/SampleSizeEntry") - ] + return yuv420.clip(0,255).astype('uint8') - sample_dependency = [ - entry.attrib['dependsOnOther'] == "yes" for entry in tree.findall( - "MovieBox/TrackBox/MediaBox/MediaInformationBox/SampleTableBox/SampleDependencyTypeBox/SampleDependencyEntry") - ] - assert len(sample_sizes) == len(sample_dependency) +def decompress_video_data(rawdat, vid_fmt, w, h, pix_fmt, multithreaded=False): + # using a tempfile is much faster than proc.communicate for some reason - chunk_offsets = [ - int(entry.attrib['offset']) for entry in tree.findall( - "MovieBox/TrackBox/MediaBox/MediaInformationBox/SampleTableBox/ChunkOffsetBox/ChunkEntry") - ] + with tempfile.TemporaryFile() as tmpf: + tmpf.write(rawdat) + tmpf.seek(0) - sample_chunk_table = [ - (int(entry.attrib['FirstChunk'])-1, int(entry.attrib['SamplesPerChunk'])) for entry in tree.findall( - "MovieBox/TrackBox/MediaBox/MediaInformationBox/SampleTableBox/SampleToChunkBox/SampleToChunkEntry") - ] + proc = subprocess.Popen( + ["ffmpeg", + "-threads", "0" if multithreaded else "1", + "-vsync", "0", + "-f", vid_fmt, + "-flags2", "showall", + "-i", "pipe:0", + "-threads", "0" if multithreaded else "1", + "-f", "rawvideo", + "-pix_fmt", pix_fmt, + "pipe:1"], + stdin=tmpf, stdout=subprocess.PIPE, stderr=open("/dev/null")) - sample_offsets = [None for _ in sample_sizes] + # dat = proc.communicate()[0] + dat = proc.stdout.read() + if proc.wait() != 0: + raise DataUnreadableError("ffmpeg failed") - sample_i = 0 - for i, (first_chunk, samples_per_chunk) in enumerate(sample_chunk_table): - if i == len(sample_chunk_table)-1: - last_chunk = len(chunk_offsets)-1 - else: - last_chunk = sample_chunk_table[i+1][0]-1 - for k in range(first_chunk, last_chunk+1): - sample_offset = chunk_offsets[k] - for _ in range(samples_per_chunk): - sample_offsets[sample_i] = sample_offset - sample_offset += sample_sizes[sample_i] - sample_i += 1 - - assert sample_i == len(sample_sizes) - - pts_offset_table = [ - ( int(entry.attrib['CompositionOffset']), int(entry.attrib['SampleCount']) ) for entry in tree.findall( - "MovieBox/TrackBox/MediaBox/MediaInformationBox/SampleTableBox/CompositionOffsetBox/CompositionOffsetEntry") - ] - sample_pts_offset = [0 for _ in sample_sizes] - sample_i = 0 - for dt, count in pts_offset_table: - for _ in range(count): - sample_pts_offset[sample_i] = dt - sample_i += 1 - - sample_time_table = [ - ( int(entry.attrib['SampleDelta']), int(entry.attrib['SampleCount']) ) for entry in tree.findall( - "MovieBox/TrackBox/MediaBox/MediaInformationBox/SampleTableBox/TimeToSampleBox/TimeToSampleEntry") - ] - sample_time = [None for _ in sample_sizes] - cur_ts = 0 - sample_i = 0 - for dt, count in sample_time_table: - for _ in range(count): - sample_time[sample_i] = (cur_ts + sample_pts_offset[sample_i]) * 1000 / time_scale - - cur_ts += dt - sample_i += 1 - - sample_time.sort() # because we ony decode GOPs in PTS order + if pix_fmt == "rgb24": + ret = np.frombuffer(dat, dtype=np.uint8).reshape(-1, h, w, 3) + elif pix_fmt == "yuv420p": + ret = np.frombuffer(dat, dtype=np.uint8).reshape(-1, (h*w*3//2)) + elif pix_fmt == "yuv444p": + ret = np.frombuffer(dat, dtype=np.uint8).reshape(-1, 3, h, w) + else: + raise NotImplementedError - return { - 'width': width, - 'height': height, - 'sample_offsets': sample_offsets, - 'sample_sizes': sample_sizes, - 'sample_dependency': sample_dependency, - 'sample_time': sample_time, - 'sps': sps, - 'pps': pps - } + return ret -class BaseFrameReader(object): +class BaseFrameReader: # properties: frame_type, frame_count, w, h def __enter__(self): @@ -547,48 +262,20 @@ class BaseFrameReader(object): def get(self, num, count=1, pix_fmt="yuv420p"): raise NotImplementedError + def FrameReader(fn, cache_prefix=None, readahead=False, readbehind=False, multithreaded=True, index_data=None): frame_type = fingerprint_video(fn) if frame_type == FrameType.raw: return RawFrameReader(fn) - elif frame_type in (FrameType.h265_stream, FrameType.h264_pstream): + elif frame_type in (FrameType.h265_stream,): if not index_data: index_data = get_video_index(fn, frame_type, cache_prefix) - if index_data is not None and "predecom" in index_data: - cache_path = cache_path_for_file_path(fn, cache_prefix) - return MKVFrameReader( - os.path.join(os.path.dirname(cache_path), index_data["predecom"])) - else: - return StreamFrameReader(fn, frame_type, index_data, - readahead=readahead, readbehind=readbehind, multithreaded=multithreaded) - elif frame_type == FrameType.h264_mp4: - return MP4FrameReader(fn, readahead=readahead) - elif frame_type == FrameType.ffv1_mkv: - return MKVFrameReader(fn) + return StreamFrameReader(fn, frame_type, index_data, readahead=readahead, readbehind=readbehind, multithreaded=multithreaded) else: raise NotImplementedError(frame_type) -def rgb24toyuv420(rgb): - yuv_from_rgb = np.array([[ 0.299 , 0.587 , 0.114 ], - [-0.14714119, -0.28886916, 0.43601035 ], - [ 0.61497538, -0.51496512, -0.10001026 ]]) - img = np.dot(rgb.reshape(-1, 3), yuv_from_rgb.T).reshape(rgb.shape) - - y_len = img.shape[0] * img.shape[1] - uv_len = y_len / 4 - - ys = img[:, :, 0] - us = (img[::2, ::2, 1] + img[1::2, ::2, 1] + img[::2, 1::2, 1] + img[1::2, 1::2, 1]) / 4 + 128 - vs = (img[::2, ::2, 2] + img[1::2, ::2, 2] + img[::2, 1::2, 2] + img[1::2, 1::2, 2]) / 4 + 128 - yuv420 = np.empty(y_len + 2 * uv_len, dtype=img.dtype) - yuv420[:y_len] = ys.reshape(-1) - yuv420[y_len:y_len + uv_len] = us.reshape(-1) - yuv420[y_len + uv_len:y_len + 2 * uv_len] = vs.reshape(-1) - - return yuv420.clip(0,255).astype('uint8') - -class RawData(object): +class RawData: def __init__(self, f): self.f = _io.FileIO(f, 'rb') self.lenn = struct.unpack("I", self.f.read(4))[0] @@ -598,6 +285,7 @@ class RawData(object): self.f.seek((self.lenn+4)*i + 4) return self.f.read(self.lenn) + class RawFrameReader(BaseFrameReader): def __init__(self, fn): # raw camera @@ -609,12 +297,9 @@ class RawFrameReader(BaseFrameReader): def load_and_debayer(self, img): img = np.frombuffer(img, dtype='uint8').reshape(960, 1280) - cimg = np.dstack([img[0::2, 1::2], ( - (img[0::2, 0::2].astype("uint16") + img[1::2, 1::2].astype("uint16")) - >> 1).astype("uint8"), img[1::2, 0::2]]) + cimg = np.dstack([img[0::2, 1::2], ((img[0::2, 0::2].astype("uint16") + img[1::2, 1::2].astype("uint16")) >> 1).astype("uint8"), img[1::2, 0::2]]) return cimg - def get(self, num, count=1, pix_fmt="yuv420p"): assert self.frame_count is not None assert num+count <= self.frame_count @@ -635,43 +320,8 @@ class RawFrameReader(BaseFrameReader): return app -def decompress_video_data(rawdat, vid_fmt, w, h, pix_fmt, multithreaded=False): - # using a tempfile is much faster than proc.communicate for some reason - - with tempfile.TemporaryFile() as tmpf: - tmpf.write(rawdat) - tmpf.seek(0) - - proc = subprocess.Popen( - ["ffmpeg", - "-threads", "0" if multithreaded else "1", - "-vsync", "0", - "-f", vid_fmt, - "-flags2", "showall", - "-i", "pipe:0", - "-threads", "0" if multithreaded else "1", - "-f", "rawvideo", - "-pix_fmt", pix_fmt, - "pipe:1"], - stdin=tmpf, stdout=subprocess.PIPE, stderr=open("/dev/null")) - - # dat = proc.communicate()[0] - dat = proc.stdout.read() - if proc.wait() != 0: - raise DataUnreadableError("ffmpeg failed") - - if pix_fmt == "rgb24": - ret = np.frombuffer(dat, dtype=np.uint8).reshape(-1, h, w, 3) - elif pix_fmt == "yuv420p": - ret = np.frombuffer(dat, dtype=np.uint8).reshape(-1, (h*w*3//2)) - elif pix_fmt == "yuv444p": - ret = np.frombuffer(dat, dtype=np.uint8).reshape(-1, 3, h, w) - else: - raise NotImplementedError - - return ret -class VideoStreamDecompressor(object): +class VideoStreamDecompressor: def __init__(self, vid_fmt, w, h, pix_fmt, multithreaded=False): self.vid_fmt = vid_fmt self.w = w @@ -750,56 +400,74 @@ class VideoStreamDecompressor(object): assert self.proc.wait() == 0 -class MKVFrameReader(BaseFrameReader): - def __init__(self, fn): +class StreamGOPReader(GOPReader): + def __init__(self, fn, frame_type, index_data): + assert frame_type == FrameType.h265_stream + self.fn = fn - #print("MKVFrameReader", fn) - index_data = index_mkv(fn) - stream = index_data['probe']['streams'][0] - self.w = stream['width'] - self.h = stream['height'] + self.frame_type = frame_type + self.frame_count = None + self.w, self.h = None, None - if stream['codec_name'] == 'ffv1': - self.frame_type = FrameType.ffv1_mkv - elif stream['codec_name'] == 'ffvhuff': - self.frame_type = FrameType.ffvhuff_mkv - else: - raise NotImplementedError + self.prefix = None + self.index = None - self.config_record = index_data['config_record'] self.index = index_data['index'] + self.prefix = index_data['global_prefix'] + probe = index_data['probe'] - self.frame_count = len(self.index) + self.prefix_frame_data = None + self.num_prefix_frames = 0 + self.vid_fmt = "hevc" - def get(self, num, count=1, pix_fmt="yuv420p"): - assert 0 < num+count <= self.frame_count + i = 0 + while i < self.index.shape[0] and self.index[i, 0] != HEVC_SLICE_I: + i += 1 + self.first_iframe = i - frame_dats = [] - with FileReader(self.fn) as f: - for i in range(num, num+count): - pos, length, _ = self.index[i] - f.seek(pos) - frame_dats.append(f.read(length)) + assert self.first_iframe == 0 + + self.frame_count = len(self.index) - 1 + + self.w = probe['streams'][0]['width'] + self.h = probe['streams'][0]['height'] - of = StringIO() - mkvindex.simple_gen(of, self.config_record, self.w, self.h, frame_dats) + def _lookup_gop(self, num): + frame_b = num + while frame_b > 0 and self.index[frame_b, 0] != HEVC_SLICE_I: + frame_b -= 1 - r = decompress_video_data(of.getvalue(), "matroska", self.w, self.h, pix_fmt) - assert len(r) == count + frame_e = num + 1 + while frame_e < (len(self.index) - 1) and self.index[frame_e, 0] != HEVC_SLICE_I: + frame_e += 1 - return r + offset_b = self.index[frame_b, 1] + offset_e = self.index[frame_e, 1] + return (frame_b, frame_e, offset_b, offset_e) -class GOPReader(object): def get_gop(self, num): - # returns (start_frame_num, num_frames, frames_to_skip, gop_data) - raise NotImplementedError + frame_b, frame_e, offset_b, offset_e = self._lookup_gop(num) + assert frame_b <= num < frame_e + num_frames = frame_e - frame_b -class DoNothingContextManager(object): - def __enter__(self): return self - def __exit__(*x): pass + with FileReader(self.fn) as f: + f.seek(offset_b) + rawdat = f.read(offset_e - offset_b) + + if num < self.first_iframe: + assert self.prefix_frame_data + rawdat = self.prefix_frame_data + rawdat + + rawdat = self.prefix + rawdat + + skip_frames = 0 + if num < self.first_iframe: + skip_frames = self.num_prefix_frames + + return frame_b, num_frames, skip_frames, rawdat class GOPFrameReader(BaseFrameReader): @@ -850,10 +518,10 @@ class GOPFrameReader(BaseFrameReader): num, pix_fmt = self.readahead_last if self.readbehind: - for k in range(num-1, max(0, num-self.readahead_len), -1): + for k in range(num - 1, max(0, num - self.readahead_len), -1): self._get_one(k, pix_fmt) else: - for k in range(num, min(self.frame_count, num+self.readahead_len)): + for k in range(num, min(self.frame_count, num + self.readahead_len)): self._get_one(k, pix_fmt) def _get_one(self, num, pix_fmt): @@ -897,151 +565,6 @@ class GOPFrameReader(BaseFrameReader): return ret -class MP4GOPReader(GOPReader): - def __init__(self, fn): - self.fn = fn - self.frame_type = FrameType.h264_mp4 - - self.index = index_mp4(fn) - - self.w = self.index['width'] - self.h = self.index['height'] - self.sample_sizes = self.index['sample_sizes'] - self.sample_offsets = self.index['sample_offsets'] - self.sample_dependency = self.index['sample_dependency'] - - self.vid_fmt = "h264" - - self.frame_count = len(self.sample_sizes) - - self.prefix = "\x00\x00\x00\x01"+self.index['sps']+"\x00\x00\x00\x01"+self.index['pps'] - - def _lookup_gop(self, num): - frame_b = num - while frame_b > 0 and self.sample_dependency[frame_b]: - frame_b -= 1 - - frame_e = num+1 - while frame_e < (len(self.sample_dependency)-1) and self.sample_dependency[frame_e]: - frame_e += 1 - - return (frame_b, frame_e) - - def get_gop(self, num): - frame_b, frame_e = self._lookup_gop(num) - assert frame_b <= num < frame_e - - num_frames = frame_e-frame_b - - with FileReader(self.fn) as f: - rawdat = [] - - sample_i = frame_b - while sample_i < frame_e: - size = self.sample_sizes[sample_i] - start_offset = self.sample_offsets[sample_i] - - # try to read contiguously because a read could actually be a http request - sample_i += 1 - while sample_i < frame_e and size < 10000000 and start_offset+size == self.sample_offsets[sample_i]: - size += self.sample_sizes[sample_i] - sample_i += 1 - - f.seek(start_offset) - sampledat = f.read(size) - - # read length-prefixed NALUs and output in Annex-B - i = 0 - while i < len(sampledat): - nal_len, = struct.unpack(">I", sampledat[i:i+4]) - rawdat.append("\x00\x00\x00\x01"+sampledat[i+4:i+4+nal_len]) - i = i+4+nal_len - assert i == len(sampledat) - - rawdat = self.prefix+''.join(rawdat) - - return frame_b, num_frames, 0, rawdat - -class MP4FrameReader(MP4GOPReader, GOPFrameReader): - def __init__(self, fn, readahead=False): - MP4GOPReader.__init__(self, fn) - GOPFrameReader.__init__(self, readahead) - -class StreamGOPReader(GOPReader): - def __init__(self, fn, frame_type, index_data): - self.fn = fn - - self.frame_type = frame_type - self.frame_count = None - self.w, self.h = None, None - - self.prefix = None - self.index = None - - self.index = index_data['index'] - self.prefix = index_data['global_prefix'] - probe = index_data['probe'] - - if self.frame_type == FrameType.h265_stream: - self.prefix_frame_data = None - self.num_prefix_frames = 0 - self.vid_fmt = "hevc" - - elif self.frame_type == FrameType.h264_pstream: - self.prefix_frame_data = index_data['prefix_frame_data'] - self.num_prefix_frames = index_data['num_prefix_frames'] - - self.vid_fmt = "h264" - - i = 0 - while i < self.index.shape[0] and self.index[i, 0] != SLICE_I: - i += 1 - self.first_iframe = i - - if self.frame_type == FrameType.h265_stream: - assert self.first_iframe == 0 - - self.frame_count = len(self.index)-1 - - self.w = probe['streams'][0]['width'] - self.h = probe['streams'][0]['height'] - - - def _lookup_gop(self, num): - frame_b = num - while frame_b > 0 and self.index[frame_b, 0] != SLICE_I: - frame_b -= 1 - - frame_e = num+1 - while frame_e < (len(self.index)-1) and self.index[frame_e, 0] != SLICE_I: - frame_e += 1 - - offset_b = self.index[frame_b, 1] - offset_e = self.index[frame_e, 1] - - return (frame_b, frame_e, offset_b, offset_e) - - def get_gop(self, num): - frame_b, frame_e, offset_b, offset_e = self._lookup_gop(num) - assert frame_b <= num < frame_e - - num_frames = frame_e-frame_b - - with FileReader(self.fn) as f: - f.seek(offset_b) - rawdat = f.read(offset_e-offset_b) - - if num < self.first_iframe: - assert self.prefix_frame_data - rawdat = self.prefix_frame_data + rawdat - - rawdat = self.prefix + rawdat - - skip_frames = 0 - if num < self.first_iframe: - skip_frames = self.num_prefix_frames - - return frame_b, num_frames, skip_frames, rawdat class StreamFrameReader(StreamGOPReader, GOPFrameReader): def __init__(self, fn, frame_type, index_data, readahead=False, readbehind=False, multithreaded=False): @@ -1049,16 +572,12 @@ class StreamFrameReader(StreamGOPReader, GOPFrameReader): GOPFrameReader.__init__(self, readahead, readbehind, multithreaded) - - def GOPFrameIterator(gop_reader, pix_fmt, multithreaded=True): # this is really ugly. ill think about how to refactor it when i can think good - IN_FLIGHT_GOPS = 6 # should be enough that the stream decompressor starts returning data - - with VideoStreamDecompressor( - gop_reader.vid_fmt, gop_reader.w, gop_reader.h, pix_fmt, multithreaded) as dec: + IN_FLIGHT_GOPS = 6 # should be enough that the stream decompressor starts returning data + with VideoStreamDecompressor(gop_reader.vid_fmt, gop_reader.w, gop_reader.h, pix_fmt, multithreaded) as dec: read_work = [] def readthing(): @@ -1083,79 +602,21 @@ def GOPFrameIterator(gop_reader, pix_fmt, multithreaded=True): read_work.append([skip_frames, num_frames]) while len(read_work) >= IN_FLIGHT_GOPS: - for v in readthing(): yield v + for v in readthing(): + yield v dec.eos() while read_work: - for v in readthing(): yield v + for v in readthing(): + yield v def FrameIterator(fn, pix_fmt, **kwargs): fr = FrameReader(fn, **kwargs) if isinstance(fr, GOPReader): - for v in GOPFrameIterator(fr, pix_fmt, kwargs.get("multithreaded", True)): yield v + for v in GOPFrameIterator(fr, pix_fmt, kwargs.get("multithreaded", True)): + yield v else: for i in range(fr.frame_count): yield fr.get(i, pix_fmt=pix_fmt)[0] - - -def FrameWriter(ofn, frames, vid_fmt=FrameType.ffvhuff_mkv, pix_fmt="rgb24", framerate=20, multithreaded=False): - if pix_fmt not in ("rgb24", "yuv420p"): - raise NotImplementedError - - if vid_fmt == FrameType.ffv1_mkv: - assert ofn.endswith(".mkv") - vcodec = "ffv1" - elif vid_fmt == FrameType.ffvhuff_mkv: - assert ofn.endswith(".mkv") - vcodec = "ffvhuff" - else: - raise NotImplementedError - - frame_gen = iter(frames) - first_frame = next(frame_gen) - - # assert len(frames) > 1 - if pix_fmt == "rgb24": - h, w = first_frame.shape[:2] - elif pix_fmt == "yuv420p": - w = first_frame.shape[1] - h = 2*first_frame.shape[0]//3 - else: - raise NotImplementedError - - compress_proc = subprocess.Popen( - ["ffmpeg", - "-threads", "0" if multithreaded else "1", - "-y", - "-framerate", str(framerate), - "-vsync", "0", - "-f", "rawvideo", - "-pix_fmt", pix_fmt, - "-s", "%dx%d" % (w, h), - "-i", "pipe:0", - "-threads", "0" if multithreaded else "1", - "-f", "matroska", - "-vcodec", vcodec, - "-g", "0", - ofn], - stdin=subprocess.PIPE, stderr=open("/dev/null", "wb")) - try: - compress_proc.stdin.write(first_frame.tobytes()) - for frame in frame_gen: - compress_proc.stdin.write(frame.tobytes()) - compress_proc.stdin.close() - except: - compress_proc.kill() - raise - - assert compress_proc.wait() == 0 - -if __name__ == "__main__": - fn = "cd:/1c79456b0c90f15a/2017-05-10--08-17-00/2/fcamera.hevc" - f = FrameReader(fn) - # print f.get(0, 1).shape - # print f.get(15, 1).shape - for v in GOPFrameIterator(f, "yuv420p"): - print(v) diff --git a/tools/lib/mkvparse/README.md b/tools/lib/mkvparse/README.md deleted file mode 100644 index 2d82f190b9..0000000000 --- a/tools/lib/mkvparse/README.md +++ /dev/null @@ -1,24 +0,0 @@ -Simple easy-to-use hacky matroska parser - -Define your handler class: - - class MyMatroskaHandler(mkvparse.MatroskaHandler): - def tracks_available(self): - ... - - def segment_info_available(self): - ... - - def frame(self, track_id, timestamp, data, more_laced_blocks, duration, keyframe_flag, invisible_flag, discardable_flag): - ... - -and `mkvparse.mkvparse(file, MyMatroskaHandler())` - - -Supports lacing and setting global timecode scale, subtitles (BlockGroup). Does not support cues, tags, chapters, seeking and so on. Supports resyncing when something bad is encountered in matroska stream. - -Also contains example of generation of Matroska files from python - -Subtitles should remain as text, binary data gets encoded to hex. - -Licence=MIT diff --git a/tools/lib/mkvparse/__init__.py b/tools/lib/mkvparse/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/tools/lib/mkvparse/mkvgen.py b/tools/lib/mkvparse/mkvgen.py deleted file mode 100755 index a98fa299b0..0000000000 --- a/tools/lib/mkvparse/mkvgen.py +++ /dev/null @@ -1,187 +0,0 @@ -#!/usr/bin/env python -import sys -import random - -# Simple hacky Matroska generator -# Reads mp3 file "q.mp3" and jpeg images from img/0.jpg, img/1.jpg and so on and -# writes Matroska file with mjpeg and mp3 to stdout - -# License=MIT - -# unsigned -def big_endian_number(number): - if(number<0x100): - return chr(number) - return big_endian_number(number>>8) + chr(number&0xFF) - -ben=big_endian_number - -def ebml_encode_number(number): - def trailing_bits(rest_of_number, number_of_bits): - # like big_endian_number, but can do padding zeroes - if number_of_bits==8: - return chr(rest_of_number&0xFF); - else: - return trailing_bits(rest_of_number>>8, number_of_bits-8) + chr(rest_of_number&0xFF) - - if number == -1: - return chr(0xFF) - if number < 2**7 - 1: - return chr(number|0x80) - if number < 2**14 - 1: - return chr(0x40 | (number>>8)) + trailing_bits(number, 8) - if number < 2**21 - 1: - return chr(0x20 | (number>>16)) + trailing_bits(number, 16) - if number < 2**28 - 1: - return chr(0x10 | (number>>24)) + trailing_bits(number, 24) - if number < 2**35 - 1: - return chr(0x08 | (number>>32)) + trailing_bits(number, 32) - if number < 2**42 - 1: - return chr(0x04 | (number>>40)) + trailing_bits(number, 40) - if number < 2**49 - 1: - return chr(0x02 | (number>>48)) + trailing_bits(number, 48) - if number < 2**56 - 1: - return chr(0x01) + trailing_bits(number, 56) - raise Exception("NUMBER TOO BIG") - -def ebml_element(element_id, data, length=None): - if length==None: - length = len(data) - return big_endian_number(element_id) + ebml_encode_number(length) + data - - -def write_ebml_header(f, content_type, version, read_version): - f.write( - ebml_element(0x1A45DFA3, "" # EBML - + ebml_element(0x4286, ben(1)) # EBMLVersion - + ebml_element(0x42F7, ben(1)) # EBMLReadVersion - + ebml_element(0x42F2, ben(4)) # EBMLMaxIDLength - + ebml_element(0x42F3, ben(8)) # EBMLMaxSizeLength - + ebml_element(0x4282, content_type) # DocType - + ebml_element(0x4287, ben(version)) # DocTypeVersion - + ebml_element(0x4285, ben(read_version)) # DocTypeReadVersion - )) - -def write_infinite_segment_header(f): - # write segment element header - f.write(ebml_element(0x18538067,"",-1)) # Segment (unknown length) - -def random_uid(): - def rint(): - return int(random.random()*(0x100**4)) - return ben(rint()) + ben(rint()) + ben(rint()) + ben(rint()) - - -def example(): - write_ebml_header(sys.stdout, "matroska", 2, 2) - write_infinite_segment_header(sys.stdout) - - - # write segment info (optional) - sys.stdout.write(ebml_element(0x1549A966, "" # SegmentInfo - + ebml_element(0x73A4, random_uid()) # SegmentUID - + ebml_element(0x7BA9, "mkvgen.py test") # Title - + ebml_element(0x4D80, "mkvgen.py") # MuxingApp - + ebml_element(0x5741, "mkvgen.py") # WritingApp - )) - - # write trans data (codecs etc.) - sys.stdout.write(ebml_element(0x1654AE6B, "" # Tracks - + ebml_element(0xAE, "" # TrackEntry - + ebml_element(0xD7, ben(1)) # TrackNumber - + ebml_element(0x73C5, ben(0x77)) # TrackUID - + ebml_element(0x83, ben(0x01)) # TrackType - #0x01 track is a video track - #0x02 track is an audio track - #0x03 track is a complex track, i.e. a combined video and audio track - #0x10 track is a logo track - #0x11 track is a subtitle track - #0x12 track is a button track - #0x20 track is a control track - + ebml_element(0x536E, "mjpeg data") # Name - + ebml_element(0x86, "V_MJPEG") # CodecID - #+ ebml_element(0x23E383, ben(100000000)) # DefaultDuration (opt.), nanoseconds - #+ ebml_element(0x6DE7, ben(100)) # MinCache - + ebml_element(0xE0, "" # Video - + ebml_element(0xB0, ben(640)) # PixelWidth - + ebml_element(0xBA, ben(480)) # PixelHeight - ) - ) - + ebml_element(0xAE, "" # TrackEntry - + ebml_element(0xD7, ben(2)) # TrackNumber - + ebml_element(0x73C5, ben(0x78)) # TrackUID - + ebml_element(0x83, ben(0x02)) # TrackType - #0x01 track is a video track - #0x02 track is an audio track - #0x03 track is a complex track, i.e. a combined video and audio track - #0x10 track is a logo track - #0x11 track is a subtitle track - #0x12 track is a button track - #0x20 track is a control track - + ebml_element(0x536E, "content of mp3 file") # Name - #+ ebml_element(0x6DE7, ben(100)) # MinCache - + ebml_element(0x86, "A_MPEG/L3") # CodecID - #+ ebml_element(0xE1, "") # Audio - ) - )) - - - mp3file = open("q.mp3", "rb") - mp3file.read(500000); - - def mp3framesgenerator(f): - debt="" - while True: - for i in range(0,len(debt)+1): - if i >= len(debt)-1: - debt = debt + f.read(8192) - break - #sys.stderr.write("i="+str(i)+" len="+str(len(debt))+"\n") - if ord(debt[i])==0xFF and (ord(debt[i+1]) & 0xF0)==0XF0 and i>700: - if i>0: - yield debt[0:i] - # sys.stderr.write("len="+str(i)+"\n") - debt = debt[i:] - break - - - mp3 = mp3framesgenerator(mp3file) - next(mp3) - - - for i in range(0,530): - framefile = open("img/"+str(i)+".jpg", "rb") - framedata = framefile.read() - framefile.close() - - # write cluster (actual video data) - - if random.random()<1: - sys.stdout.write(ebml_element(0x1F43B675, "" # Cluster - + ebml_element(0xE7, ben(int(i*26*4))) # TimeCode, uint, milliseconds - # + ebml_element(0xA7, ben(0)) # Position, uint - + ebml_element(0xA3, "" # SimpleBlock - + ebml_encode_number(1) # track number - + chr(0x00) + chr(0x00) # timecode, relative to Cluster timecode, sint16, in milliseconds - + chr(0x00) # flags - + framedata - ))) - - for u in range(0,4): - mp3f=next(mp3) - if random.random()<1: - sys.stdout.write(ebml_element(0x1F43B675, "" # Cluster - + ebml_element(0xE7, ben(i*26*4+u*26)) # TimeCode, uint, milliseconds - + ebml_element(0xA3, "" # SimpleBlock - + ebml_encode_number(2) # track number - + chr(0x00) + chr(0x00) # timecode, relative to Cluster timecode, sint16, in milliseconds - + chr(0x00) # flags - + mp3f - ))) - - - - - -if __name__ == '__main__': - example() diff --git a/tools/lib/mkvparse/mkvindex.py b/tools/lib/mkvparse/mkvindex.py deleted file mode 100644 index 694965fbf6..0000000000 --- a/tools/lib/mkvparse/mkvindex.py +++ /dev/null @@ -1,64 +0,0 @@ -#!/usr/bin/env python -# flake8: noqa - -import re -import binascii - -from tools.lib.mkvparse import mkvparse -from tools.lib.mkvparse import mkvgen -from tools.lib.mkvparse.mkvgen import ben, ebml_element, ebml_encode_number - -class MatroskaIndex(mkvparse.MatroskaHandler): - # def __init__(self, banlist, nocluster_mode): - # pass - def __init__(self): - self.frameindex = [] - - def tracks_available(self): - _, self.config_record = self.tracks[1]['CodecPrivate'] # pylint: disable=no-member - - def frame(self, track_id, timestamp, pos, length, more_laced_frames, duration, - keyframe, invisible, discardable): - self.frameindex.append((pos, length, keyframe)) - - - -def mkvindex(f): - handler = MatroskaIndex() - mkvparse.mkvparse(f, handler) - return handler.config_record, handler.frameindex - - -def simple_gen(of, config_record, w, h, framedata): - mkvgen.write_ebml_header(of, "matroska", 2, 2) - mkvgen.write_infinite_segment_header(of) - - of.write(ebml_element(0x1654AE6B, "" # Tracks - + ebml_element(0xAE, "" # TrackEntry - + ebml_element(0xD7, ben(1)) # TrackNumber - + ebml_element(0x73C5, ben(1)) # TrackUID - + ebml_element(0x83, ben(1)) # TrackType = video track - + ebml_element(0x86, "V_MS/VFW/FOURCC") # CodecID - + ebml_element(0xE0, "" # Video - + ebml_element(0xB0, ben(w)) # PixelWidth - + ebml_element(0xBA, ben(h)) # PixelHeight - ) - + ebml_element(0x63A2, config_record) # CodecPrivate (ffv1 configuration record) - ) - )) - - blocks = [] - for fd in framedata: - blocks.append( - ebml_element(0xA3, "" # SimpleBlock - + ebml_encode_number(1) # track number - + chr(0x00) + chr(0x00) # timecode, relative to Cluster timecode, sint16, in milliseconds - + chr(0x80) # flags (keyframe) - + fd - ) - ) - - of.write(ebml_element(0x1F43B675, "" # Cluster - + ebml_element(0xE7, ben(0)) # TimeCode, uint, milliseconds - # + ebml_element(0xA7, ben(0)) # Position, uint - + ''.join(blocks))) diff --git a/tools/lib/mkvparse/mkvparse.py b/tools/lib/mkvparse/mkvparse.py deleted file mode 100644 index 8e9816347c..0000000000 --- a/tools/lib/mkvparse/mkvparse.py +++ /dev/null @@ -1,763 +0,0 @@ -# Licence==MIT; Vitaly "_Vi" Shukela 2012 - -# Simple easy-to-use hacky matroska parser - -# Supports SimpleBlock and BlockGroup, lacing, TimecodeScale. -# Does not support seeking, cues, chapters and other features. -# No proper EOF handling unfortunately - -# See "mkvuser.py" for the example -# pylint: skip-file -# flake8: noqa - -import traceback -from struct import unpack - -import sys -import datetime - -if sys.version < '3': - range=xrange # pylint disable=undefined-variable -else: - #identity=lambda x:x - def ord(something): - if type(something)==bytes: - if something == b"": - raise StopIteration - return something[0] - else: - return something - -def get_major_bit_number(n): - ''' - Takes uint8, returns number of the most significant bit plus the number with that bit cleared. - Examples: - 0b10010101 -> (0, 0b00010101) - 0b00010101 -> (3, 0b00000101) - 0b01111111 -> (1, 0b00111111) - ''' - if not n: - raise Exception("Bad number") - i=0x80; - r=0 - while not n&i: - r+=1 - i>>=1 - return (r,n&~i); - -def read_matroska_number(f, unmodified=False, signed=False): - ''' - Read ebml number. Unmodified means don't clear the length bit (as in Element IDs) - Returns the number and it's length as a tuple - - See examples in "parse_matroska_number" function - ''' - if unmodified and signed: - raise Exception("Contradictary arguments") - first_byte=f.read(1) - if(first_byte==""): - raise StopIteration - r = ord(first_byte) - (n,r2) = get_major_bit_number(r) - if not unmodified: - r=r2 - # from now "signed" means "negative" - i=n - while i: - r = r * 0x100 + ord(f.read(1)) - i-=1 - if signed: - r-=(2**(7*n+7)-1) - else: - if r==2**(7*n+7)-1: - return (-1, n+1) - return (r,n+1) - -def parse_matroska_number(data, pos, unmodified=False, signed=False): - ''' - Parse ebml number from buffer[pos:]. Just like read_matroska_number. - Unmodified means don't clear the length bit (as in Element IDs) - Returns the number plus the new position in input buffer - - Examples: - "\x81" -> (1, pos+1) - "\x40\x01" -> (1, pos+2) - "\x20\x00\x01" -> (1, pos+3) - "\x3F\xFF\xFF" -> (0x1FFFFF, pos+3) - "\x20\x00\x01" unmodified -> (0x200001, pos+3) - "\xBF" signed -> (0, pos+1) - "\xBE" signed -> (-1, pos+1) - "\xC0" signed -> (1, pos+1) - "\x5F\xEF" signed -> (-16, pos+2) - ''' - if unmodified and signed: - raise Exception("Contradictary arguments") - r = ord(data[pos]) - pos+=1 - (n,r2) = get_major_bit_number(r) - if not unmodified: - r=r2 - # from now "signed" means "negative" - i=n - while i: - r = r * 0x100 + ord(data[pos]) - pos+=1 - i-=1 - if signed: - r-=(2**(7*n+6)-1) - else: - if r==2**(7*n+7)-1: - return (-1, pos) - return (r,pos) - -def parse_xiph_number(data, pos): - ''' - Parse the Xiph lacing number from data[pos:] - Returns the number plus the new position - - Examples: - "\x01" -> (1, pos+1) - "\x55" -> (0x55, pos+1) - "\xFF\x04" -> (0x103, pos+2) - "\xFF\xFF\x04" -> (0x202, pos+3) - "\xFF\xFF\x00" -> (0x1FE, pos+3) - ''' - v = ord(data[pos]) - pos+=1 - - r=0 - while v==255: - r+=v - v = ord(data[pos]) - pos+=1 - - r+=v - return (r, pos) - - -def parse_fixedlength_number(data, pos, length, signed=False): - ''' - Read the big-endian number from data[pos:pos+length] - Returns the number plus the new position - - Examples: - "\x01" -> (0x1, pos+1) - "\x55" -> (0x55, pos+1) - "\x55" signed -> (0x55, pos+1) - "\xFF\x04" -> (0xFF04, pos+2) - "\xFF\x04" signed -> (-0x00FC, pos+2) - ''' - r=0 - for i in range(length): - r=r*0x100+ord(data[pos+i]) - if signed: - if ord(data[pos]) & 0x80: - r-=2**(8*length) - return (r, pos+length) - -def read_fixedlength_number(f, length, signed=False): - """ Read length bytes and parse (parse_fixedlength_number) it. - Returns only the number""" - buf = f.read(length) - (r, pos) = parse_fixedlength_number(buf, 0, length, signed) - return r - -def read_ebml_element_header(f): - ''' - Read Element ID and size - Returns id, element size and this header size - ''' - (id_, n) = read_matroska_number(f, unmodified=True) - (size, n2) = read_matroska_number(f) - return (id_, size, n+n2) - -class EbmlElementType: - VOID=0 - MASTER=1 # read all subelements and return tree. Don't use this too large things like Segment - UNSIGNED=2 - SIGNED=3 - TEXTA=4 - TEXTU=5 - BINARY=6 - FLOAT=7 - DATE=8 - - JUST_GO_ON=10 # For "Segment". - # Actually MASTER, but don't build the tree for all subelements, - # interpreting all child elements as if they were top-level elements - - -EET=EbmlElementType - -# lynx -width=10000 -dump http://matroska.org/technical/specs/index.html -# | sed 's/not 0/not0/g; s/> 0/>0/g; s/Sampling Frequency/SamplingFrequency/g' -# | awk '{print $1 " " $3 " " $8}' -# | grep '\[..\]' -# | perl -ne '/(\S+) (\S+) (.)/; -# $name=$1; $id=$2; $type=$3; -# $id=~s/\[|\]//g; -# %types = (m=>"EET.MASTER", -# u=>"EET.UNSIGNED", -# i=>"EET.SIGNED", -# 8=>"EET.TEXTU", -# s=>"EET.TEXTA", -# b=>"EET.BINARY", -# f=>"EET.FLOAT", -# d=>"EET.DATE"); -# $t=$types{$type}; -# next unless $t; -# $t="EET.JUST_GO_ON" if $name eq "Segment" or $name eq "Cluster"; -# print "\t0x$id: ($t, \"$name\"),\n";' - -element_types_names = { - 0x1A45DFA3: (EET.MASTER, "EBML"), - 0x4286: (EET.UNSIGNED, "EBMLVersion"), - 0x42F7: (EET.UNSIGNED, "EBMLReadVersion"), - 0x42F2: (EET.UNSIGNED, "EBMLMaxIDLength"), - 0x42F3: (EET.UNSIGNED, "EBMLMaxSizeLength"), - 0x4282: (EET.TEXTA, "DocType"), - 0x4287: (EET.UNSIGNED, "DocTypeVersion"), - 0x4285: (EET.UNSIGNED, "DocTypeReadVersion"), - 0xEC: (EET.BINARY, "Void"), - 0xBF: (EET.BINARY, "CRC-32"), - 0x1B538667: (EET.MASTER, "SignatureSlot"), - 0x7E8A: (EET.UNSIGNED, "SignatureAlgo"), - 0x7E9A: (EET.UNSIGNED, "SignatureHash"), - 0x7EA5: (EET.BINARY, "SignaturePublicKey"), - 0x7EB5: (EET.BINARY, "Signature"), - 0x7E5B: (EET.MASTER, "SignatureElements"), - 0x7E7B: (EET.MASTER, "SignatureElementList"), - 0x6532: (EET.BINARY, "SignedElement"), - 0x18538067: (EET.JUST_GO_ON, "Segment"), - 0x114D9B74: (EET.MASTER, "SeekHead"), - 0x4DBB: (EET.MASTER, "Seek"), - 0x53AB: (EET.BINARY, "SeekID"), - 0x53AC: (EET.UNSIGNED, "SeekPosition"), - 0x1549A966: (EET.MASTER, "Info"), - 0x73A4: (EET.BINARY, "SegmentUID"), - 0x7384: (EET.TEXTU, "SegmentFilename"), - 0x3CB923: (EET.BINARY, "PrevUID"), - 0x3C83AB: (EET.TEXTU, "PrevFilename"), - 0x3EB923: (EET.BINARY, "NextUID"), - 0x3E83BB: (EET.TEXTU, "NextFilename"), - 0x4444: (EET.BINARY, "SegmentFamily"), - 0x6924: (EET.MASTER, "ChapterTranslate"), - 0x69FC: (EET.UNSIGNED, "ChapterTranslateEditionUID"), - 0x69BF: (EET.UNSIGNED, "ChapterTranslateCodec"), - 0x69A5: (EET.BINARY, "ChapterTranslateID"), - 0x2AD7B1: (EET.UNSIGNED, "TimecodeScale"), - 0x4489: (EET.FLOAT, "Duration"), - 0x4461: (EET.DATE, "DateUTC"), - 0x7BA9: (EET.TEXTU, "Title"), - 0x4D80: (EET.TEXTU, "MuxingApp"), - 0x5741: (EET.TEXTU, "WritingApp"), - 0x1F43B675: (EET.JUST_GO_ON, "Cluster"), - 0xE7: (EET.UNSIGNED, "Timecode"), - 0x5854: (EET.MASTER, "SilentTracks"), - 0x58D7: (EET.UNSIGNED, "SilentTrackNumber"), - 0xA7: (EET.UNSIGNED, "Position"), - 0xAB: (EET.UNSIGNED, "PrevSize"), - 0xA3: (EET.BINARY, "SimpleBlock"), - 0xA0: (EET.MASTER, "BlockGroup"), - 0xA1: (EET.BINARY, "Block"), - 0xA2: (EET.BINARY, "BlockVirtual"), - 0x75A1: (EET.MASTER, "BlockAdditions"), - 0xA6: (EET.MASTER, "BlockMore"), - 0xEE: (EET.UNSIGNED, "BlockAddID"), - 0xA5: (EET.BINARY, "BlockAdditional"), - 0x9B: (EET.UNSIGNED, "BlockDuration"), - 0xFA: (EET.UNSIGNED, "ReferencePriority"), - 0xFB: (EET.SIGNED, "ReferenceBlock"), - 0xFD: (EET.SIGNED, "ReferenceVirtual"), - 0xA4: (EET.BINARY, "CodecState"), - 0x8E: (EET.MASTER, "Slices"), - 0xE8: (EET.MASTER, "TimeSlice"), - 0xCC: (EET.UNSIGNED, "LaceNumber"), - 0xCD: (EET.UNSIGNED, "FrameNumber"), - 0xCB: (EET.UNSIGNED, "BlockAdditionID"), - 0xCE: (EET.UNSIGNED, "Delay"), - 0xCF: (EET.UNSIGNED, "SliceDuration"), - 0xC8: (EET.MASTER, "ReferenceFrame"), - 0xC9: (EET.UNSIGNED, "ReferenceOffset"), - 0xCA: (EET.UNSIGNED, "ReferenceTimeCode"), - 0xAF: (EET.BINARY, "EncryptedBlock"), - 0x1654AE6B: (EET.MASTER, "Tracks"), - 0xAE: (EET.MASTER, "TrackEntry"), - 0xD7: (EET.UNSIGNED, "TrackNumber"), - 0x73C5: (EET.UNSIGNED, "TrackUID"), - 0x83: (EET.UNSIGNED, "TrackType"), - 0xB9: (EET.UNSIGNED, "FlagEnabled"), - 0x88: (EET.UNSIGNED, "FlagDefault"), - 0x55AA: (EET.UNSIGNED, "FlagForced"), - 0x9C: (EET.UNSIGNED, "FlagLacing"), - 0x6DE7: (EET.UNSIGNED, "MinCache"), - 0x6DF8: (EET.UNSIGNED, "MaxCache"), - 0x23E383: (EET.UNSIGNED, "DefaultDuration"), - 0x23314F: (EET.FLOAT, "TrackTimecodeScale"), - 0x537F: (EET.SIGNED, "TrackOffset"), - 0x55EE: (EET.UNSIGNED, "MaxBlockAdditionID"), - 0x536E: (EET.TEXTU, "Name"), - 0x22B59C: (EET.TEXTA, "Language"), - 0x86: (EET.TEXTA, "CodecID"), - 0x63A2: (EET.BINARY, "CodecPrivate"), - 0x258688: (EET.TEXTU, "CodecName"), - 0x7446: (EET.UNSIGNED, "AttachmentLink"), - 0x3A9697: (EET.TEXTU, "CodecSettings"), - 0x3B4040: (EET.TEXTA, "CodecInfoURL"), - 0x26B240: (EET.TEXTA, "CodecDownloadURL"), - 0xAA: (EET.UNSIGNED, "CodecDecodeAll"), - 0x6FAB: (EET.UNSIGNED, "TrackOverlay"), - 0x6624: (EET.MASTER, "TrackTranslate"), - 0x66FC: (EET.UNSIGNED, "TrackTranslateEditionUID"), - 0x66BF: (EET.UNSIGNED, "TrackTranslateCodec"), - 0x66A5: (EET.BINARY, "TrackTranslateTrackID"), - 0xE0: (EET.MASTER, "Video"), - 0x9A: (EET.UNSIGNED, "FlagInterlaced"), - 0x53B8: (EET.UNSIGNED, "StereoMode"), - 0x53B9: (EET.UNSIGNED, "OldStereoMode"), - 0xB0: (EET.UNSIGNED, "PixelWidth"), - 0xBA: (EET.UNSIGNED, "PixelHeight"), - 0x54AA: (EET.UNSIGNED, "PixelCropBottom"), - 0x54BB: (EET.UNSIGNED, "PixelCropTop"), - 0x54CC: (EET.UNSIGNED, "PixelCropLeft"), - 0x54DD: (EET.UNSIGNED, "PixelCropRight"), - 0x54B0: (EET.UNSIGNED, "DisplayWidth"), - 0x54BA: (EET.UNSIGNED, "DisplayHeight"), - 0x54B2: (EET.UNSIGNED, "DisplayUnit"), - 0x54B3: (EET.UNSIGNED, "AspectRatioType"), - 0x2EB524: (EET.BINARY, "ColourSpace"), - 0x2FB523: (EET.FLOAT, "GammaValue"), - 0x2383E3: (EET.FLOAT, "FrameRate"), - 0xE1: (EET.MASTER, "Audio"), - 0xB5: (EET.FLOAT, "SamplingFrequency"), - 0x78B5: (EET.FLOAT, "OutputSamplingFrequency"), - 0x9F: (EET.UNSIGNED, "Channels"), - 0x7D7B: (EET.BINARY, "ChannelPositions"), - 0x6264: (EET.UNSIGNED, "BitDepth"), - 0xE2: (EET.MASTER, "TrackOperation"), - 0xE3: (EET.MASTER, "TrackCombinePlanes"), - 0xE4: (EET.MASTER, "TrackPlane"), - 0xE5: (EET.UNSIGNED, "TrackPlaneUID"), - 0xE6: (EET.UNSIGNED, "TrackPlaneType"), - 0xE9: (EET.MASTER, "TrackJoinBlocks"), - 0xED: (EET.UNSIGNED, "TrackJoinUID"), - 0xC0: (EET.UNSIGNED, "TrickTrackUID"), - 0xC1: (EET.BINARY, "TrickTrackSegmentUID"), - 0xC6: (EET.UNSIGNED, "TrickTrackFlag"), - 0xC7: (EET.UNSIGNED, "TrickMasterTrackUID"), - 0xC4: (EET.BINARY, "TrickMasterTrackSegmentUID"), - 0x6D80: (EET.MASTER, "ContentEncodings"), - 0x6240: (EET.MASTER, "ContentEncoding"), - 0x5031: (EET.UNSIGNED, "ContentEncodingOrder"), - 0x5032: (EET.UNSIGNED, "ContentEncodingScope"), - 0x5033: (EET.UNSIGNED, "ContentEncodingType"), - 0x5034: (EET.MASTER, "ContentCompression"), - 0x4254: (EET.UNSIGNED, "ContentCompAlgo"), - 0x4255: (EET.BINARY, "ContentCompSettings"), - 0x5035: (EET.MASTER, "ContentEncryption"), - 0x47E1: (EET.UNSIGNED, "ContentEncAlgo"), - 0x47E2: (EET.BINARY, "ContentEncKeyID"), - 0x47E3: (EET.BINARY, "ContentSignature"), - 0x47E4: (EET.BINARY, "ContentSigKeyID"), - 0x47E5: (EET.UNSIGNED, "ContentSigAlgo"), - 0x47E6: (EET.UNSIGNED, "ContentSigHashAlgo"), - 0x1C53BB6B: (EET.MASTER, "Cues"), - 0xBB: (EET.MASTER, "CuePoint"), - 0xB3: (EET.UNSIGNED, "CueTime"), - 0xB7: (EET.MASTER, "CueTrackPositions"), - 0xF7: (EET.UNSIGNED, "CueTrack"), - 0xF1: (EET.UNSIGNED, "CueClusterPosition"), - 0x5378: (EET.UNSIGNED, "CueBlockNumber"), - 0xEA: (EET.UNSIGNED, "CueCodecState"), - 0xDB: (EET.MASTER, "CueReference"), - 0x96: (EET.UNSIGNED, "CueRefTime"), - 0x97: (EET.UNSIGNED, "CueRefCluster"), - 0x535F: (EET.UNSIGNED, "CueRefNumber"), - 0xEB: (EET.UNSIGNED, "CueRefCodecState"), - 0x1941A469: (EET.MASTER, "Attachments"), - 0x61A7: (EET.MASTER, "AttachedFile"), - 0x467E: (EET.TEXTU, "FileDescription"), - 0x466E: (EET.TEXTU, "FileName"), - 0x4660: (EET.TEXTA, "FileMimeType"), - 0x465C: (EET.BINARY, "FileData"), - 0x46AE: (EET.UNSIGNED, "FileUID"), - 0x4675: (EET.BINARY, "FileReferral"), - 0x4661: (EET.UNSIGNED, "FileUsedStartTime"), - 0x4662: (EET.UNSIGNED, "FileUsedEndTime"), - 0x1043A770: (EET.MASTER, "Chapters"), - 0x45B9: (EET.MASTER, "EditionEntry"), - 0x45BC: (EET.UNSIGNED, "EditionUID"), - 0x45BD: (EET.UNSIGNED, "EditionFlagHidden"), - 0x45DB: (EET.UNSIGNED, "EditionFlagDefault"), - 0x45DD: (EET.UNSIGNED, "EditionFlagOrdered"), - 0xB6: (EET.MASTER, "ChapterAtom"), - 0x73C4: (EET.UNSIGNED, "ChapterUID"), - 0x91: (EET.UNSIGNED, "ChapterTimeStart"), - 0x92: (EET.UNSIGNED, "ChapterTimeEnd"), - 0x98: (EET.UNSIGNED, "ChapterFlagHidden"), - 0x4598: (EET.UNSIGNED, "ChapterFlagEnabled"), - 0x6E67: (EET.BINARY, "ChapterSegmentUID"), - 0x6EBC: (EET.UNSIGNED, "ChapterSegmentEditionUID"), - 0x63C3: (EET.UNSIGNED, "ChapterPhysicalEquiv"), - 0x8F: (EET.MASTER, "ChapterTrack"), - 0x89: (EET.UNSIGNED, "ChapterTrackNumber"), - 0x80: (EET.MASTER, "ChapterDisplay"), - 0x85: (EET.TEXTU, "ChapString"), - 0x437C: (EET.TEXTA, "ChapLanguage"), - 0x437E: (EET.TEXTA, "ChapCountry"), - 0x6944: (EET.MASTER, "ChapProcess"), - 0x6955: (EET.UNSIGNED, "ChapProcessCodecID"), - 0x450D: (EET.BINARY, "ChapProcessPrivate"), - 0x6911: (EET.MASTER, "ChapProcessCommand"), - 0x6922: (EET.UNSIGNED, "ChapProcessTime"), - 0x6933: (EET.BINARY, "ChapProcessData"), - 0x1254C367: (EET.MASTER, "Tags"), - 0x7373: (EET.MASTER, "Tag"), - 0x63C0: (EET.MASTER, "Targets"), - 0x68CA: (EET.UNSIGNED, "TargetTypeValue"), - 0x63CA: (EET.TEXTA, "TargetType"), - 0x63C5: (EET.UNSIGNED, "TagTrackUID"), - 0x63C9: (EET.UNSIGNED, "TagEditionUID"), - 0x63C4: (EET.UNSIGNED, "TagChapterUID"), - 0x63C6: (EET.UNSIGNED, "TagAttachmentUID"), - 0x67C8: (EET.MASTER, "SimpleTag"), - 0x45A3: (EET.TEXTU, "TagName"), - 0x447A: (EET.TEXTA, "TagLanguage"), - 0x4484: (EET.UNSIGNED, "TagDefault"), - 0x4487: (EET.TEXTU, "TagString"), - 0x4485: (EET.BINARY, "TagBinary"), - 0x56AA: (EET.UNSIGNED, "CodecDelay"), - 0x56BB: (EET.UNSIGNED, "SeekPreRoll"), - 0xF0: (EET.UNSIGNED, "CueRelativePosition"), - 0x53C0: (EET.UNSIGNED, "AlphaMode"), - 0x55B2: (EET.UNSIGNED, "BitsPerChannel"), - 0x55B5: (EET.UNSIGNED, "CbSubsamplingHorz"), - 0x55B6: (EET.UNSIGNED, "CbSubsamplingVert"), - 0x5654: (EET.TEXTU, "ChapterStringUID"), - 0x55B7: (EET.UNSIGNED, "ChromaSitingHorz"), - 0x55B8: (EET.UNSIGNED, "ChromaSitingVert"), - 0x55B3: (EET.UNSIGNED, "ChromaSubsamplingHorz"), - 0x55B4: (EET.UNSIGNED, "ChromaSubsamplingVert"), - 0x55B0: (EET.MASTER, "Colour"), - 0x234E7A: (EET.UNSIGNED, "DefaultDecodedFieldDuration"), - 0x75A2: (EET.SIGNED, "DiscardPadding"), - 0x9D: (EET.UNSIGNED, "FieldOrder"), - 0x55D9: (EET.FLOAT, "LuminanceMax"), - 0x55DA: (EET.FLOAT, "LuminanceMin"), - 0x55D0: (EET.MASTER, "MasteringMetadata"), - 0x55B1: (EET.UNSIGNED, "MatrixCoefficients"), - 0x55BC: (EET.UNSIGNED, "MaxCLL"), - 0x55BD: (EET.UNSIGNED, "MaxFALL"), - 0x55BB: (EET.UNSIGNED, "Primaries"), - 0x55D5: (EET.FLOAT, "PrimaryBChromaticityX"), - 0x55D6: (EET.FLOAT, "PrimaryBChromaticityY"), - 0x55D3: (EET.FLOAT, "PrimaryGChromaticityX"), - 0x55D4: (EET.FLOAT, "PrimaryGChromaticityY"), - 0x55D1: (EET.FLOAT, "PrimaryRChromaticityX"), - 0x55D2: (EET.FLOAT, "PrimaryRChromaticityY"), - 0x55B9: (EET.UNSIGNED, "Range"), - 0x55BA: (EET.UNSIGNED, "TransferCharacteristics"), - 0x55D7: (EET.FLOAT, "WhitePointChromaticityX"), - 0x55D8: (EET.FLOAT, "WhitePointChromaticityY"), -} - -def read_simple_element(f, type_, size): - date = None - if size==0: - return "" - - if type_==EET.UNSIGNED: - data=read_fixedlength_number(f, size, False) - elif type_==EET.SIGNED: - data=read_fixedlength_number(f, size, True) - elif type_==EET.TEXTA: - data=f.read(size) - data = data.replace(b"\x00", b"") # filter out \0, for gstreamer - data = data.decode("ascii") - elif type_==EET.TEXTU: - data=f.read(size) - data = data.replace(b"\x00", b"") # filter out \0, for gstreamer - data = data.decode("UTF-8") - elif type_==EET.MASTER: - data=read_ebml_element_tree(f, size) - elif type_==EET.DATE: - data=read_fixedlength_number(f, size, True) - data*= 1e-9 - data+= (datetime.datetime(2001, 1, 1) - datetime.datetime(1970, 1, 1)).total_seconds() - # now should be UNIX date - elif type_==EET.FLOAT: - if size==4: - data = f.read(4) - data = unpack(">f", data)[0] - elif size==8: - data = f.read(8) - data = unpack(">d", data)[0] - else: - data=read_fixedlength_number(f, size, False) - sys.stderr.write("mkvparse: Floating point of size %d is not supported\n" % size) - data = None - else: - data=f.read(size) - return data - -def read_ebml_element_tree(f, total_size): - ''' - Build tree of elements, reading f until total_size reached - Don't use for the whole segment, it's not Haskell - - Returns list of pairs (element_name, element_value). - element_value can also be list of pairs - ''' - childs=[] - while(total_size>0): - (id_, size, hsize) = read_ebml_element_header(f) - if size == -1: - sys.stderr.write("mkvparse: Element %x without size? Damaged data? Skipping %d bytes\n" % (id_, size, total_size)) # pylint disable=too-many-format-args - f.read(total_size); - break; - if size>total_size: - sys.stderr.write("mkvparse: Element %x with size %d? Damaged data? Skipping %d bytes\n" % (id_, size, total_size)) - f.read(total_size); - break - type_ = EET.BINARY - name = "unknown_%x"%id_ - if id_ in element_types_names: - (type_, name) = element_types_names[id_] - data = read_simple_element(f, type_, size) - total_size-=(size+hsize) - childs.append((name, (type_, data))) - return childs - - -class MatroskaHandler: - """ User for mkvparse should override these methods """ - def tracks_available(self): - pass - def segment_info_available(self): - pass - def frame(self, track_id, timestamp, data, more_laced_frames, duration, keyframe, invisible, discardable): - pass - def ebml_top_element(self, id_, name_, type_, data_): - pass - def before_handling_an_element(self): - pass - def begin_handling_ebml_element(self, id_, name, type_, headersize, datasize): - return type_ - def element_data_available(self, id_, name, type_, headersize, data): - pass - -def handle_block(buffer, buffer_pos, handler, cluster_timecode, timecode_scale=1000000, duration=None, header_removal_headers_for_tracks={}): - ''' - Decode a block, handling all lacings, send it to handler with appropriate timestamp, track number - ''' - pos=0 - (tracknum, pos) = parse_matroska_number(buffer, pos, signed=False) - (tcode, pos) = parse_fixedlength_number(buffer, pos, 2, signed=True) - flags = ord(buffer[pos]); pos+=1 - f_keyframe = (flags&0x80 == 0x80) - f_invisible = (flags&0x08 == 0x08) - f_discardable = (flags&0x01 == 0x01) - laceflags=flags&0x06 - - block_timecode = (cluster_timecode + tcode)*(timecode_scale*0.000000001) - - header_removal_prefix = b"" - if tracknum in header_removal_headers_for_tracks: - # header_removal_prefix = header_removal_headers_for_tracks[tracknum] - raise NotImplementedError - - if laceflags == 0x00: # no lacing - # buf = buffer[pos:] - handler.frame(tracknum, block_timecode, buffer_pos+pos, len(buffer)-pos, - 0, duration, f_keyframe, f_invisible, f_discardable) - return - - numframes = ord(buffer[pos]); pos+=1 - numframes+=1 - - lengths=[] - - if laceflags == 0x02: # Xiph lacing - accumlength=0 - for i in range(numframes-1): - (l, pos) = parse_xiph_number(buffer, pos) - lengths.append(l) - accumlength+=l - lengths.append(len(buffer)-pos-accumlength) - elif laceflags == 0x06: # EBML lacing - accumlength=0 - if numframes: - (flength, pos) = parse_matroska_number(buffer, pos, signed=False) - lengths.append(flength) - accumlength+=flength - for i in range(numframes-2): - (l, pos) = parse_matroska_number(buffer, pos, signed=True) - flength+=l - lengths.append(flength) - accumlength+=flength - lengths.append(len(buffer)-pos-accumlength) - elif laceflags==0x04: # Fixed size lacing - fl=int((len(buffer)-pos)/numframes) - for i in range(numframes): - lengths.append(fl) - - more_laced_frames=numframes-1 - for i in lengths: - # buf = buffer[pos:pos+i] - handler.frame(tracknum, block_timecode, buffer_pos+pos, i, more_laced_frames, duration, - f_keyframe, f_invisible, f_discardable) - pos+=i - more_laced_frames-=1 - - -def resync(f): - sys.stderr.write("mvkparse: Resyncing\n") - while True: - b = f.read(1); - if b == b"": return (None, None); - if b == b"\x1F": - b2 = f.read(3); - if b2 == b"\x43\xB6\x75": - (seglen, x) = read_matroska_number(f) - return (0x1F43B675, seglen, x+4) # cluster - if b == b"\x18": - b2 = f.read(3) - if b2 == b"\x53\x80\x67": - (seglen, x) = read_matroska_number(f) - return (0x18538067, seglen, x+4) # segment - if b == b"\x16": - b2 = f.read(3) - if b2 == b"\x54\xAE\x6B": - (seglen ,x )= read_matroska_number(f) - return (0x1654AE6B, seglen, x+4) # tracks - - - - -def mkvparse(f, handler): - ''' - Read mkv file f and call handler methods when track or segment information is ready or when frame is read. - Handles lacing, timecodes (except of per-track scaling) - ''' - timecode_scale = 1000000 - current_cluster_timecode = 0 - resync_element_id = None - resync_element_size = None - resync_element_headersize = None - header_removal_headers_for_tracks = {} - while f: - (id_, size, hsize) = (None, None, None) - tree = None - data = None - (type_, name) = (None, None) - try: - if not resync_element_id: - try: - handler.before_handling_an_element() - (id_, size, hsize) = read_ebml_element_header(f) - except StopIteration: - break; - if not (id_ in element_types_names): - sys.stderr.write("mkvparse: Unknown element with id %x and size %d\n"%(id_, size)) - (resync_element_id, resync_element_size, resync_element_headersize) = resync(f) - if resync_element_id: - continue; - else: - break; - else: - id_ = resync_element_id - size=resync_element_size - hsize=resync_element_headersize - resync_element_id = None - resync_element_size = None - resync_element_headersize = None - - (type_, name) = element_types_names[id_] - (type_, name) = element_types_names[id_] - type_ = handler.begin_handling_ebml_element(id_, name, type_, hsize, size) - - if type_ == EET.MASTER: - tree = read_ebml_element_tree(f, size) - data = tree - - except Exception: - traceback.print_exc() - handler.before_handling_an_element() - (resync_element_id, resync_element_size, resync_element_headersize) = resync(f) - if resync_element_id: - continue; - else: - break; - - if name=="EBML" and type(data) == list: - d = dict(tree) - if 'EBMLReadVersion' in d: - if d['EBMLReadVersion'][1]>1: sys.stderr.write("mkvparse: Warning: EBMLReadVersion too big\n") - if 'DocTypeReadVersion' in d: - if d['DocTypeReadVersion'][1]>2: sys.stderr.write("mkvparse: Warning: DocTypeReadVersion too big\n") - dt = d['DocType'][1] - if dt != "matroska" and dt != "webm": - sys.stderr.write("mkvparse: Warning: EBML DocType is not \"matroska\" or \"webm\"") - elif name=="Info" and type(data) == list: - handler.segment_info = tree - handler.segment_info_available() - - d = dict(tree) - if "TimecodeScale" in d: - timecode_scale = d["TimecodeScale"][1] - elif name=="Tracks" and type(data) == list: - handler.tracks={} - for (ten, (_t, track)) in tree: - if ten != "TrackEntry": continue - d = dict(track) - n = d['TrackNumber'][1] - handler.tracks[n]=d - tt = d['TrackType'][1] - if tt==0x01: d['type']='video' - elif tt==0x02: d['type']='audio' - elif tt==0x03: d['type']='complex' - elif tt==0x10: d['type']='logo' - elif tt==0x11: d['type']='subtitle' - elif tt==0x12: d['type']='button' - elif tt==0x20: d['type']='control' - if 'TrackTimecodeScale' in d: - sys.stderr.write("mkvparse: Warning: TrackTimecodeScale is not supported\n") - if 'ContentEncodings' in d: - try: - compr = dict(d["ContentEncodings"][1][0][1][1][0][1][1]) - if compr["ContentCompAlgo"][1] == 3: - header_removal_headers_for_tracks[n] = compr["ContentCompSettings"][1] - else: - sys.stderr.write("mkvparse: Warning: compression other than " \ - "header removal is not supported\n") - except: - sys.stderr.write("mkvparse: Warning: unsuccessfully tried " \ - "to handle header removal compression\n") - handler.tracks_available() - # cluster contents: - elif name=="Timecode" and type_ == EET.UNSIGNED: - data=read_fixedlength_number(f, size, False) - current_cluster_timecode = data; - elif name=="SimpleBlock" and type_ == EET.BINARY: - pos = f.tell() - data=f.read(size) - handle_block(data, pos, handler, current_cluster_timecode, timecode_scale, None, header_removal_headers_for_tracks) - elif name=="BlockGroup" and type_ == EET.MASTER: - d2 = dict(tree) - duration=None - raise NotImplementedError - # if 'BlockDuration' in d2: - # duration = d2['BlockDuration'][1] - # duration = duration*0.000000001*timecode_scale - # if 'Block' in d2: - # handle_block(d2['Block'][1], None, handler, current_cluster_timecode, timecode_scale, duration, header_removal_headers_for_tracks) - else: - if type_!=EET.JUST_GO_ON and type_!=EET.MASTER: - data = read_simple_element(f, type_, size) - - handler.ebml_top_element(id_, name, type_, data); - - - -if __name__ == '__main__': - print("Run mkvuser.py for the example") From bee15f8abef98b35d070e931d5b34fd01ca8128e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 28 May 2020 13:20:28 -0700 Subject: [PATCH 115/656] make pre-commit pass without xx present --- selfdrive/debug/internal/get_fingerprint_from_route.py | 2 +- selfdrive/test/update_ci_routes.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/debug/internal/get_fingerprint_from_route.py b/selfdrive/debug/internal/get_fingerprint_from_route.py index 42df3029c9..278aaadd4c 100755 --- a/selfdrive/debug/internal/get_fingerprint_from_route.py +++ b/selfdrive/debug/internal/get_fingerprint_from_route.py @@ -2,7 +2,7 @@ import sys from tools.lib.logreader import MultiLogIterator -from xx.chffr.lib.route import Route +from xx.chffr.lib.route import Route # pylint: disable=import-error def get_fingerprint(lr): diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py index 77db292915..0ce1b5c8f1 100755 --- a/selfdrive/test/update_ci_routes.py +++ b/selfdrive/test/update_ci_routes.py @@ -5,8 +5,8 @@ from azure.storage.blob import BlockBlobService from selfdrive.test.test_car_models import routes as test_car_models_routes from selfdrive.test.process_replay.test_processes import segments as replay_segments -from xx.chffr.lib import azureutil -from xx.chffr.lib.storage import _DATA_ACCOUNT_PRODUCTION, _DATA_ACCOUNT_CI, _DATA_BUCKET_PRODUCTION +from xx.chffr.lib import azureutil # pylint: disable=import-error +from xx.chffr.lib.storage import _DATA_ACCOUNT_PRODUCTION, _DATA_ACCOUNT_CI, _DATA_BUCKET_PRODUCTION # pylint: disable=import-error SOURCES = [ (_DATA_ACCOUNT_PRODUCTION, _DATA_BUCKET_PRODUCTION), From cff745bc6e4bd052006fc8e11a9015e87ea8c45e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 28 May 2020 13:24:33 -0700 Subject: [PATCH 116/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index bdec1398e5..9bece64e8f 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit bdec1398e5150bfa00a0872413603a3e2c0c5cd0 +Subproject commit 9bece64e8f37895f27ca50afde9308745110f801 From 2d0686faa1876d65642f6c982a4352630a842676 Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Thu, 28 May 2020 13:39:28 -0700 Subject: [PATCH 117/656] framereader single threaded env var --- tools/lib/framereader.py | 20 +++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/tools/lib/framereader.py b/tools/lib/framereader.py index dd27ba1706..9efe7961e0 100644 --- a/tools/lib/framereader.py +++ b/tools/lib/framereader.py @@ -210,9 +210,12 @@ def rgb24toyuv420(rgb): return yuv420.clip(0,255).astype('uint8') -def decompress_video_data(rawdat, vid_fmt, w, h, pix_fmt, multithreaded=False): +def decompress_video_data(rawdat, vid_fmt, w, h, pix_fmt, multithreaded=None): # using a tempfile is much faster than proc.communicate for some reason + if multithreaded is None: + multithreaded = not os.getenv('SINGLETHREADED') + with tempfile.TemporaryFile() as tmpf: tmpf.write(rawdat) tmpf.seek(0) @@ -263,7 +266,7 @@ class BaseFrameReader: raise NotImplementedError -def FrameReader(fn, cache_prefix=None, readahead=False, readbehind=False, multithreaded=True, index_data=None): +def FrameReader(fn, cache_prefix=None, readahead=False, readbehind=False, multithreaded=None, index_data=None): frame_type = fingerprint_video(fn) if frame_type == FrameType.raw: return RawFrameReader(fn) @@ -322,12 +325,15 @@ class RawFrameReader(BaseFrameReader): class VideoStreamDecompressor: - def __init__(self, vid_fmt, w, h, pix_fmt, multithreaded=False): + def __init__(self, vid_fmt, w, h, pix_fmt, multithreaded=None): self.vid_fmt = vid_fmt self.w = w self.h = h self.pix_fmt = pix_fmt + if multithreaded is None: + multithreaded = not os.getenv('SINGLETHREADED') + if pix_fmt == "yuv420p": self.out_size = w*h*3//2 # yuv420p elif pix_fmt in ("rgb24", "yuv444p"): @@ -473,7 +479,7 @@ class StreamGOPReader(GOPReader): class GOPFrameReader(BaseFrameReader): #FrameReader with caching and readahead for formats that are group-of-picture based - def __init__(self, readahead=False, readbehind=False, multithreaded=True): + def __init__(self, readahead=False, readbehind=False, multithreaded=None): self.open_ = True self.multithreaded = multithreaded @@ -567,12 +573,12 @@ class GOPFrameReader(BaseFrameReader): class StreamFrameReader(StreamGOPReader, GOPFrameReader): - def __init__(self, fn, frame_type, index_data, readahead=False, readbehind=False, multithreaded=False): + def __init__(self, fn, frame_type, index_data, readahead=False, readbehind=False, multithreaded=None): StreamGOPReader.__init__(self, fn, frame_type, index_data) GOPFrameReader.__init__(self, readahead, readbehind, multithreaded) -def GOPFrameIterator(gop_reader, pix_fmt, multithreaded=True): +def GOPFrameIterator(gop_reader, pix_fmt, multithreaded=None): # this is really ugly. ill think about how to refactor it when i can think good IN_FLIGHT_GOPS = 6 # should be enough that the stream decompressor starts returning data @@ -615,7 +621,7 @@ def GOPFrameIterator(gop_reader, pix_fmt, multithreaded=True): def FrameIterator(fn, pix_fmt, **kwargs): fr = FrameReader(fn, **kwargs) if isinstance(fr, GOPReader): - for v in GOPFrameIterator(fr, pix_fmt, kwargs.get("multithreaded", True)): + for v in GOPFrameIterator(fr, pix_fmt, kwargs.get("multithreaded", None)): yield v else: for i in range(fr.frame_count): From e47b8b5d1aff12fc932bc99f1e3e58f629bc9b83 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 28 May 2020 14:07:18 -0700 Subject: [PATCH 118/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 9bece64e8f..a618e64d1a 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 9bece64e8f37895f27ca50afde9308745110f801 +Subproject commit a618e64d1a1778f5b3ac95dcd8a41b64d1a18a3f From 2752df82664d1a45e60f09ede09760c67903f135 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 28 May 2020 14:40:25 -0700 Subject: [PATCH 119/656] timeouts for all CI jobs --- .github/workflows/test.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index c1f5c524f0..43c90dc97a 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -48,6 +48,7 @@ jobs: docker_push: name: docker push runs-on: ubuntu-16.04 + timeout-minutes: 50 if: github.ref == 'refs/heads/master' && github.event_name != 'pull_request' && github.repository == 'commaai/openpilot' needs: static_analysis # hack to ensure slow tests run first since this and static_analysis are fast steps: @@ -65,6 +66,7 @@ jobs: static_analysis: name: static analysis runs-on: ubuntu-16.04 + timeout-minutes: 50 steps: - uses: actions/checkout@v2 with: @@ -91,6 +93,7 @@ jobs: unit_tests: name: unit tests runs-on: ubuntu-16.04 + timeout-minutes: 50 steps: - uses: actions/checkout@v2 with: From 9e73f65a7db364606d11d6c2715db555dfdb1803 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 28 May 2020 14:44:19 -0700 Subject: [PATCH 120/656] bump rednose --- rednose_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rednose_repo b/rednose_repo index 9cfff6ba92..86b047637c 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit 9cfff6ba929398155cfb5888db500ebd86a45910 +Subproject commit 86b047637c228ce72873b958b733ebbd38c5dc95 From 3d08dcc3b27936cb14c0eae63605be9a6c077380 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 28 May 2020 15:05:04 -0700 Subject: [PATCH 121/656] Run mypy commit hook (#1591) * run mypy commit hook * fix mypy errors --- .gitignore | 1 + .pre-commit-config.yaml | 5 + Pipfile | 1 + Pipfile.lock | 131 +++++++++++++----- common/params.py | 22 --- common/spinner.py | 2 +- common/text_window.py | 2 +- mypy.ini | 4 + selfdrive/athena/athenad.py | 30 ++-- selfdrive/car/fw_versions.py | 14 +- selfdrive/crash.py | 2 +- selfdrive/debug/check_freq.py | 2 + selfdrive/debug/check_lag.py | 2 + selfdrive/debug/cpu_usage_stat.py | 1 + .../internal/get_fingerprint_from_route.py | 1 + .../internal/measure_steering_accuracy.py | 4 +- .../internal/measure_torque_time_to_max.py | 2 + selfdrive/debug/mpc/test_mpc_wobble.py | 1 + selfdrive/debug/mpc/tune_lateral.py | 2 + selfdrive/debug/mpc/tune_longitudinal.py | 1 + selfdrive/debug/test_fw_query_on_routes.py | 2 + selfdrive/locationd/models/car_kf.py | 5 +- selfdrive/locationd/models/gnss_kf.py | 5 +- selfdrive/locationd/test/ci_test.py | 1 + selfdrive/locationd/test/ubloxd.py | 1 + selfdrive/locationd/test/ubloxd_easy.py | 1 + selfdrive/locationd/test/ubloxd_py_test.py | 2 + selfdrive/manager.py | 10 +- .../test/longitudinal_maneuvers/plant_ui.py | 119 ---------------- selfdrive/test/process_replay/compare_logs.py | 2 +- .../process_replay/flycheck_compare_logs.py | 72 ++++++++++ .../test/process_replay/process_replay.py | 2 +- .../test/process_replay/test_processes.py | 7 +- selfdrive/test/test_car_models.py | 27 ++-- tools/lib/auth.py | 3 +- tools/replay/lib/ui_helpers.py | 7 +- tools/replay/rqplot.py | 2 +- tools/sim/bridge.py | 1 + tools/sim/lib/keyboard_ctrl.py | 7 +- 39 files changed, 273 insertions(+), 233 deletions(-) create mode 100644 mypy.ini delete mode 100755 selfdrive/test/longitudinal_maneuvers/plant_ui.py create mode 100644 selfdrive/test/process_replay/flycheck_compare_logs.py diff --git a/.gitignore b/.gitignore index 8f21086a7c..9f2de0181e 100644 --- a/.gitignore +++ b/.gitignore @@ -61,3 +61,4 @@ cppcheck_report.txt htmlcov pandaextra +.mypy_cache/ diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 96ba5e5e96..71f442a536 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -6,6 +6,11 @@ repos: - id: check-json - id: check-xml - id: check-yaml +- repo: https://github.com/pre-commit/mirrors-mypy + rev: master + hooks: + - id: mypy + exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' - repo: https://gitlab.com/PyCQA/flake8 rev: master hooks: diff --git a/Pipfile b/Pipfile index d18512d0ae..5fb643ad85 100644 --- a/Pipfile +++ b/Pipfile @@ -73,6 +73,7 @@ pygame = "==2.0.0.dev8" pprofile = "*" pyprof2calltree = "*" pre-commit = "*" +mypy = "*" [packages] atomicwrites = "*" diff --git a/Pipfile.lock b/Pipfile.lock index 572eb9a073..e297d667e1 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "681eef4e45758b560f2f76736c039d051c62cc910e6bc7556b3add318110dea0" + "sha256": "ebed80be69f5b38143ddf30e96b8d7f6d3214a4296088276e01795f15ad6e1c2" }, "pipfile-spec": 6, "requires": { @@ -90,9 +90,9 @@ }, "crcmod": { "hashes": [ - "sha256:737fb308fa2ce9aed2e29075f0d5980d4a89bfbec48a368c607c5c63b3efb90e", - "sha256:69a2e5c6c36d0f096a7beb4cd34e5f882ec5fd232efb710cdb85d4ff196bd52e", "sha256:50586ab48981f11e5b117523d97bb70864a2a1af246cf6e4f5c4a21ef4611cd1", + "sha256:69a2e5c6c36d0f096a7beb4cd34e5f882ec5fd232efb710cdb85d4ff196bd52e", + "sha256:737fb308fa2ce9aed2e29075f0d5980d4a89bfbec48a368c607c5c63b3efb90e", "sha256:dc7051a0db5f2bd48665a990d3ec1cc305a466a77358ca4492826f41f283601e" ], "index": "pypi", @@ -361,29 +361,29 @@ }, "pillow": { "hashes": [ - "sha256:ccc9ad2460eb5bee5642eaf75a0438d7f8887d484490d5117b98edd7f33118b7", - "sha256:12e4bad6bddd8546a2f9771485c7e3d2b546b458ae8ff79621214119ac244523", - "sha256:0e2a3bceb0fd4e0cb17192ae506d5f082b309ffe5fc370a5667959c9b2f85fa3", "sha256:04766c4930c174b46fd72d450674612ab44cca977ebbcc2dde722c6933290107", + "sha256:0e2a3bceb0fd4e0cb17192ae506d5f082b309ffe5fc370a5667959c9b2f85fa3", + "sha256:0f01e63c34f0e1e2580cc0b24e86a5ccbbfa8830909a52ee17624c4193224cd9", + "sha256:12e4bad6bddd8546a2f9771485c7e3d2b546b458ae8ff79621214119ac244523", "sha256:1f694e28c169655c50bb89a3fa07f3b854d71eb47f50783621de813979ba87f3", + "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", + "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", + "sha256:70e3e0d99a0dcda66283a185f80697a9b08806963c6149c8e6c5f452b2aa59c0", + "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", + "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd", "sha256:ae2b270f9a0b8822b98655cb3a59cdb1bd54a34807c6c56b76dd2e786c3b7db3", "sha256:b37bb3bd35edf53125b0ff257822afa6962649995cbdfde2791ddb62b239f891", + "sha256:b532bcc2f008e96fd9241177ec580829dee817b090532f43e54074ecffdcd97f", "sha256:b67a6c47ed963c709ed24566daa3f95a18f07d3831334da570c71da53d97d088", + "sha256:b943e71c2065ade6fef223358e56c167fc6ce31c50bc7a02dd5c17ee4338e8ac", + "sha256:ccc9ad2460eb5bee5642eaf75a0438d7f8887d484490d5117b98edd7f33118b7", "sha256:d23e2aa9b969cf9c26edfb4b56307792b8b374202810bd949effd1c6e11ebd6d", - "sha256:0f01e63c34f0e1e2580cc0b24e86a5ccbbfa8830909a52ee17624c4193224cd9", + "sha256:eaa83729eab9c60884f362ada982d3a06beaa6cc8b084cf9f76cae7739481dfa", "sha256:ee94fce8d003ac9fd206496f2707efe9eadcb278d94c271f129ab36aa7181344", "sha256:f455efb7a98557412dc6f8e463c1faf1f1911ec2432059fa3e582b6000fc90e2", "sha256:f46e0e024346e1474083c729d50de909974237c72daca05393ee32389dabe457", - "sha256:b943e71c2065ade6fef223358e56c167fc6ce31c50bc7a02dd5c17ee4338e8ac", - "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", - "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", - "sha256:f784aad988f12c80aacfa5b381ec21fd3f38f851720f652b9f33facc5101cf4d", - "sha256:eaa83729eab9c60884f362ada982d3a06beaa6cc8b084cf9f76cae7739481dfa", "sha256:f54be399340aa602066adb63a86a6a5d4f395adfdd9da2b9a0162ea808c7b276", - "sha256:b532bcc2f008e96fd9241177ec580829dee817b090532f43e54074ecffdcd97f", - "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", - "sha256:70e3e0d99a0dcda66283a185f80697a9b08806963c6149c8e6c5f452b2aa59c0", - "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd" + "sha256:f784aad988f12c80aacfa5b381ec21fd3f38f851720f652b9f33facc5101cf4d" ], "index": "pypi", "version": "==7.1.2" @@ -1229,11 +1229,11 @@ }, "google-auth": { "hashes": [ - "sha256:73b141d122942afe12e8bfdcb6900d5df35c27d39700f078363ba0b1298ad33b", - "sha256:fbf25fee328c0828ef293459d9c649ef84ee44c0b932bb999d19df0ead1b40cf" + "sha256:1b3732b121917124adfe602de148ef5cba351792cf9527f99e6b61b84f74a7f5", + "sha256:7a9119c4ed518e4ea596cc896e6c567b923b57db40be70e5aec990055aea85d3" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.15.0" + "version": "==1.16.0" }, "google-auth-oauthlib": { "hashes": [ @@ -1739,6 +1739,33 @@ "markers": "python_version >= '3.5'", "version": "==4.7.6" }, + "mypy": { + "hashes": [ + "sha256:15b948e1302682e3682f11f50208b726a246ab4e6c1b39f9264a8796bb416aa2", + "sha256:219a3116ecd015f8dca7b5d2c366c973509dfb9a8fc97ef044a36e3da66144a1", + "sha256:3b1fc683fb204c6b4403a1ef23f0b1fac8e4477091585e0c8c54cbdf7d7bb164", + "sha256:3beff56b453b6ef94ecb2996bea101a08f1f8a9771d3cbf4988a61e4d9973761", + "sha256:7687f6455ec3ed7649d1ae574136835a4272b65b3ddcf01ab8704ac65616c5ce", + "sha256:7ec45a70d40ede1ec7ad7f95b3c94c9cf4c186a32f6bacb1795b60abd2f9ef27", + "sha256:86c857510a9b7c3104cf4cde1568f4921762c8f9842e987bc03ed4f160925754", + "sha256:8a627507ef9b307b46a1fea9513d5c98680ba09591253082b4c48697ba05a4ae", + "sha256:8dfb69fbf9f3aeed18afffb15e319ca7f8da9642336348ddd6cab2713ddcf8f9", + "sha256:a34b577cdf6313bf24755f7a0e3f3c326d5c1f4fe7422d1d06498eb25ad0c600", + "sha256:a8ffcd53cb5dfc131850851cc09f1c44689c2812d0beb954d8138d4f5fc17f65", + "sha256:b90928f2d9eb2f33162405f32dde9f6dcead63a0971ca8a1b50eb4ca3e35ceb8", + "sha256:c56ffe22faa2e51054c5f7a3bc70a370939c2ed4de308c690e7949230c995913", + "sha256:f91c7ae919bbc3f96cd5e5b2e786b2b108343d1d7972ea130f7de27fdd547cf3" + ], + "index": "pypi", + "version": "==0.770" + }, + "mypy-extensions": { + "hashes": [ + "sha256:090fedd75945a69ae91ce1303b5824f428daf5a028d2f6ab8a299250a846f15d", + "sha256:2d82818f5bb3e369420cb3c4060a7970edba416647068eb4c5343488a6c604a8" + ], + "version": "==0.4.3" + }, "nbconvert": { "hashes": [ "sha256:21fb48e700b43e82ba0e3142421a659d7739b65568cc832a13976a77be16b523", @@ -1945,29 +1972,29 @@ }, "pillow": { "hashes": [ - "sha256:ccc9ad2460eb5bee5642eaf75a0438d7f8887d484490d5117b98edd7f33118b7", - "sha256:12e4bad6bddd8546a2f9771485c7e3d2b546b458ae8ff79621214119ac244523", - "sha256:0e2a3bceb0fd4e0cb17192ae506d5f082b309ffe5fc370a5667959c9b2f85fa3", "sha256:04766c4930c174b46fd72d450674612ab44cca977ebbcc2dde722c6933290107", + "sha256:0e2a3bceb0fd4e0cb17192ae506d5f082b309ffe5fc370a5667959c9b2f85fa3", + "sha256:0f01e63c34f0e1e2580cc0b24e86a5ccbbfa8830909a52ee17624c4193224cd9", + "sha256:12e4bad6bddd8546a2f9771485c7e3d2b546b458ae8ff79621214119ac244523", "sha256:1f694e28c169655c50bb89a3fa07f3b854d71eb47f50783621de813979ba87f3", + "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", + "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", + "sha256:70e3e0d99a0dcda66283a185f80697a9b08806963c6149c8e6c5f452b2aa59c0", + "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", + "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd", "sha256:ae2b270f9a0b8822b98655cb3a59cdb1bd54a34807c6c56b76dd2e786c3b7db3", "sha256:b37bb3bd35edf53125b0ff257822afa6962649995cbdfde2791ddb62b239f891", + "sha256:b532bcc2f008e96fd9241177ec580829dee817b090532f43e54074ecffdcd97f", "sha256:b67a6c47ed963c709ed24566daa3f95a18f07d3831334da570c71da53d97d088", + "sha256:b943e71c2065ade6fef223358e56c167fc6ce31c50bc7a02dd5c17ee4338e8ac", + "sha256:ccc9ad2460eb5bee5642eaf75a0438d7f8887d484490d5117b98edd7f33118b7", "sha256:d23e2aa9b969cf9c26edfb4b56307792b8b374202810bd949effd1c6e11ebd6d", - "sha256:0f01e63c34f0e1e2580cc0b24e86a5ccbbfa8830909a52ee17624c4193224cd9", + "sha256:eaa83729eab9c60884f362ada982d3a06beaa6cc8b084cf9f76cae7739481dfa", "sha256:ee94fce8d003ac9fd206496f2707efe9eadcb278d94c271f129ab36aa7181344", "sha256:f455efb7a98557412dc6f8e463c1faf1f1911ec2432059fa3e582b6000fc90e2", "sha256:f46e0e024346e1474083c729d50de909974237c72daca05393ee32389dabe457", - "sha256:b943e71c2065ade6fef223358e56c167fc6ce31c50bc7a02dd5c17ee4338e8ac", - "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", - "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", - "sha256:f784aad988f12c80aacfa5b381ec21fd3f38f851720f652b9f33facc5101cf4d", - "sha256:eaa83729eab9c60884f362ada982d3a06beaa6cc8b084cf9f76cae7739481dfa", "sha256:f54be399340aa602066adb63a86a6a5d4f395adfdd9da2b9a0162ea808c7b276", - "sha256:b532bcc2f008e96fd9241177ec580829dee817b090532f43e54074ecffdcd97f", - "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", - "sha256:70e3e0d99a0dcda66283a185f80697a9b08806963c6149c8e6c5f452b2aa59c0", - "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd" + "sha256:f784aad988f12c80aacfa5b381ec21fd3f38f851720f652b9f33facc5101cf4d" ], "index": "pypi", "version": "==7.1.2" @@ -2019,6 +2046,7 @@ "protobuf": { "hashes": [ "sha256:304e08440c4a41a0f3592d2a38934aad6919d692bb0edfb355548786728f9a5e", + "sha256:49ef8ab4c27812a89a76fa894fe7a08f42f2147078392c0dee51d4a444ef6df5", "sha256:50b5fee674878b14baea73b4568dc478c46a31dd50157a5b5d2f71138243b1a9", "sha256:5524c7020eb1fb7319472cb75c4c3206ef18b34d6034d2ee420a60f99cddeb07", "sha256:612bc97e42b22af10ba25e4140963fbaa4c5181487d163f4eb55b0b15b3dfcd2", @@ -2026,6 +2054,7 @@ "sha256:85b94d2653b0fdf6d879e39d51018bf5ccd86c81c04e18a98e9888694b98226f", "sha256:87535dc2d2ef007b9d44e309d2b8ea27a03d2fa09556a72364d706fcb7090828", "sha256:a7ab28a8f1f043c58d157bceb64f80e4d2f7f1b934bc7ff5e7f7a55a337ea8b0", + "sha256:a96f8fc625e9ff568838e556f6f6ae8eca8b4837cdfb3f90efcb7c00e342a2eb", "sha256:b5a114ea9b7fc90c2cc4867a866512672a47f66b154c6d7ee7e48ddb68b68122", "sha256:be04fe14ceed7f8641e30f36077c1a654ff6f17d0c7a5283b699d057d150d82a", "sha256:bff02030bab8b969f4de597543e55bd05e968567acb25c0a87495a31eb09e925", @@ -2722,10 +2751,10 @@ }, "tensorboard": { "hashes": [ - "sha256:9a2a2dc9856187679e93f3c95e5dc771dd47e3257db09767b4be118d734b4dc2" + "sha256:a3feb73e1221c0a512398ad2cd08570fb082d8a2ba364aa0562543ecbd3659ef" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==2.2.1" + "version": "==2.2.2" }, "tensorboard-plugin-wit": { "hashes": [ @@ -2816,6 +2845,40 @@ ], "version": "==4.3.3" }, + "typed-ast": { + "hashes": [ + "sha256:0666aa36131496aed8f7be0410ff974562ab7eeac11ef351def9ea6fa28f6355", + "sha256:0c2c07682d61a629b68433afb159376e24e5b2fd4641d35424e462169c0a7919", + "sha256:249862707802d40f7f29f6e1aad8d84b5aa9e44552d2cc17384b209f091276aa", + "sha256:24995c843eb0ad11a4527b026b4dde3da70e1f2d8806c99b7b4a7cf491612652", + "sha256:269151951236b0f9a6f04015a9004084a5ab0d5f19b57de779f908621e7d8b75", + "sha256:4083861b0aa07990b619bd7ddc365eb7fa4b817e99cf5f8d9cf21a42780f6e01", + "sha256:498b0f36cc7054c1fead3d7fc59d2150f4d5c6c56ba7fb150c013fbc683a8d2d", + "sha256:4e3e5da80ccbebfff202a67bf900d081906c358ccc3d5e3c8aea42fdfdfd51c1", + "sha256:6daac9731f172c2a22ade6ed0c00197ee7cc1221aa84cfdf9c31defeb059a907", + "sha256:715ff2f2df46121071622063fc7543d9b1fd19ebfc4f5c8895af64a77a8c852c", + "sha256:73d785a950fc82dd2a25897d525d003f6378d1cb23ab305578394694202a58c3", + "sha256:8c8aaad94455178e3187ab22c8b01a3837f8ee50e09cf31f1ba129eb293ec30b", + "sha256:8ce678dbaf790dbdb3eba24056d5364fb45944f33553dd5869b7580cdbb83614", + "sha256:aaee9905aee35ba5905cfb3c62f3e83b3bec7b39413f0a7f19be4e547ea01ebb", + "sha256:bcd3b13b56ea479b3650b82cabd6b5343a625b0ced5429e4ccad28a8973f301b", + "sha256:c9e348e02e4d2b4a8b2eedb48210430658df6951fa484e59de33ff773fbd4b41", + "sha256:d205b1b46085271b4e15f670058ce182bd1199e56b317bf2ec004b6a44f911f6", + "sha256:d43943ef777f9a1c42bf4e552ba23ac77a6351de620aa9acf64ad54933ad4d34", + "sha256:d5d33e9e7af3b34a40dc05f498939f0ebf187f07c385fd58d591c533ad8562fe", + "sha256:fc0fea399acb12edbf8a628ba8d2312f583bdbdb3335635db062fa98cf71fca4", + "sha256:fe460b922ec15dd205595c9b5b99e2f056fd98ae8f9f56b888e7a17dc2b757e7" + ], + "version": "==1.4.1" + }, + "typing-extensions": { + "hashes": [ + "sha256:6e95524d8a547a91e08f404ae485bbb71962de46967e1b71a0cb89af24e761c5", + "sha256:79ee589a3caca649a9bfd2a8de4709837400dfa00b6cc81962a1e6a1815969ae", + "sha256:f8d2bd89d25bc39dabe7d23df520442fa1d8969b82544370e03d88b5a591c392" + ], + "version": "==3.7.4.2" + }, "urllib3": { "hashes": [ "sha256:3018294ebefce6572a474f0604c2021e33b3fd8006ecd11d62107a5d2a963527", diff --git a/common/params.py b/common/params.py index 787235bf13..0a7e6daf9e 100755 --- a/common/params.py +++ b/common/params.py @@ -22,10 +22,7 @@ file in place without messing with /d. """ import time import os -import string -import binascii import errno -import sys import shutil import fcntl import tempfile @@ -401,22 +398,3 @@ def put_nonblocking(key, val): t = threading.Thread(target=f, args=(key, val)) t.start() return t - - -if __name__ == "__main__": - params = Params() - if len(sys.argv) > 2: - params.put(sys.argv[1], sys.argv[2]) - else: - for k in keys: - pp = params.get(k) - if pp is None: - print("%s is None" % k) - elif all(chr(c) in string.printable for c in pp): - print("%s = %s" % (k, pp)) - else: - print("%s = %s" % (k, binascii.hexlify(pp))) - - # Test multiprocess: - # seq 0 100000 | xargs -P20 -I{} python common/params.py DongleId {} && sleep 0.05 - # while python common/params.py DongleId; do sleep 0.05; done diff --git a/common/spinner.py b/common/spinner.py index da8084037e..370d54c815 100644 --- a/common/spinner.py +++ b/common/spinner.py @@ -40,7 +40,7 @@ class Spinner(): self.close() -class FakeSpinner(): +class FakeSpinner(Spinner): def __init__(self): pass diff --git a/common/text_window.py b/common/text_window.py index 0d94bc7470..50fdcb6440 100755 --- a/common/text_window.py +++ b/common/text_window.py @@ -43,7 +43,7 @@ class TextWindow(): self.close() -class FakeTextWindow(): +class FakeTextWindow(TextWindow): def __init__(self, s): pass diff --git a/mypy.ini b/mypy.ini new file mode 100644 index 0000000000..66b82bd5df --- /dev/null +++ b/mypy.ini @@ -0,0 +1,4 @@ +[mypy] +python_version = 3.8 +ignore_missing_imports = True + diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index b9e8d79e6f..cbebb08e56 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -1,29 +1,31 @@ #!/usr/bin/env python3 -import json -import os +import base64 import hashlib import io +import json +import os +import queue import random import select import socket -import time import threading -import base64 -import requests -import queue +import time from collections import namedtuple from functools import partial +from typing import Any + +import requests from jsonrpc import JSONRPCResponseManager, dispatcher -from websocket import create_connection, WebSocketTimeoutException, ABNF -from selfdrive.loggerd.config import ROOT +from websocket import ABNF, WebSocketTimeoutException, create_connection import cereal.messaging as messaging +from cereal.services import service_list from common import android -from common.basedir import PERSIST from common.api import Api +from common.basedir import PERSIST from common.params import Params from common.realtime import sec_since_boot -from cereal.services import service_list +from selfdrive.loggerd.config import ROOT from selfdrive.swaglog import cloudlog ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') @@ -31,10 +33,10 @@ HANDLER_THREADS = os.getenv('HANDLER_THREADS', 4) LOCAL_PORT_WHITELIST = set([8022]) dispatcher["echo"] = lambda s: s -payload_queue = queue.Queue() -response_queue = queue.Queue() -upload_queue = queue.Queue() -cancelled_uploads = set() +payload_queue: Any = queue.Queue() +response_queue: Any = queue.Queue() +upload_queue: Any = queue.Queue() +cancelled_uploads: Any = set() UploadItem = namedtuple('UploadItem', ['path', 'url', 'headers', 'created_at', 'id']) def handle_long_poll(ws): diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 673b16942c..f42e1c09d8 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -1,15 +1,17 @@ #!/usr/bin/env python3 -import traceback import struct +import traceback +from typing import Any + from tqdm import tqdm +import panda.python.uds as uds +from cereal import car +from selfdrive.car.fingerprints import FW_VERSIONS, get_attr_from_cars from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from selfdrive.swaglog import cloudlog -from selfdrive.car.fingerprints import get_attr_from_cars, FW_VERSIONS from selfdrive.car.toyota.values import CAR as TOYOTA -import panda.python.uds as uds +from selfdrive.swaglog import cloudlog -from cereal import car Ecu = car.CarParams.Ecu @@ -213,7 +215,7 @@ if __name__ == "__main__": logcan = messaging.sub_sock('can') sendcan = messaging.pub_sock('sendcan') - extra = None + extra: Any = None if args.scan: extra = {} # Honda diff --git a/selfdrive/crash.py b/selfdrive/crash.py index a8cb758a7e..000109dc90 100644 --- a/selfdrive/crash.py +++ b/selfdrive/crash.py @@ -9,7 +9,7 @@ from selfdrive.swaglog import cloudlog from common.android import ANDROID if os.getenv("NOLOG") or os.getenv("NOCRASH") or not ANDROID: - def capture_exception(*exc_info): + def capture_exception(*args, **kwargs): pass def bind_user(**kwargs): pass diff --git a/selfdrive/debug/check_freq.py b/selfdrive/debug/check_freq.py index 75c0b8f89a..fd4f510c2b 100755 --- a/selfdrive/debug/check_freq.py +++ b/selfdrive/debug/check_freq.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +# type: ignore + import argparse import numpy as np from collections import defaultdict, deque diff --git a/selfdrive/debug/check_lag.py b/selfdrive/debug/check_lag.py index 418f1f872b..c922642982 100755 --- a/selfdrive/debug/check_lag.py +++ b/selfdrive/debug/check_lag.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +# type: ignore + import cereal.messaging as messaging from cereal.services import service_list diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index d59a148558..c3f54f9439 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +# type: ignore import psutil import time import os diff --git a/selfdrive/debug/internal/get_fingerprint_from_route.py b/selfdrive/debug/internal/get_fingerprint_from_route.py index 278aaadd4c..2a0f99fab2 100755 --- a/selfdrive/debug/internal/get_fingerprint_from_route.py +++ b/selfdrive/debug/internal/get_fingerprint_from_route.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +# type: ignore import sys from tools.lib.logreader import MultiLogIterator diff --git a/selfdrive/debug/internal/measure_steering_accuracy.py b/selfdrive/debug/internal/measure_steering_accuracy.py index fabf8030d1..706af73989 100755 --- a/selfdrive/debug/internal/measure_steering_accuracy.py +++ b/selfdrive/debug/internal/measure_steering_accuracy.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +# type: ignore + import os import argparse import signal @@ -28,7 +30,7 @@ if __name__ == "__main__": stats = defaultdict(lambda: {'err': 0, "cnt": 0, "=": 0, "+": 0, "-": 0}) cnt = 0 total_error = 0 - + while messaging.recv_one(carControl): sm.update() msg_cnt += 1 diff --git a/selfdrive/debug/internal/measure_torque_time_to_max.py b/selfdrive/debug/internal/measure_torque_time_to_max.py index d1beeae44d..58a29532cd 100755 --- a/selfdrive/debug/internal/measure_torque_time_to_max.py +++ b/selfdrive/debug/internal/measure_torque_time_to_max.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +# type: ignore + import os import argparse import struct diff --git a/selfdrive/debug/mpc/test_mpc_wobble.py b/selfdrive/debug/mpc/test_mpc_wobble.py index 5f9f1b3355..6117779d8b 100755 --- a/selfdrive/debug/mpc/test_mpc_wobble.py +++ b/selfdrive/debug/mpc/test_mpc_wobble.py @@ -1,4 +1,5 @@ #! /usr/bin/env python +# type: ignore import matplotlib.pyplot as plt from selfdrive.controls.lib.lateral_mpc import libmpc_py from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT diff --git a/selfdrive/debug/mpc/tune_lateral.py b/selfdrive/debug/mpc/tune_lateral.py index 4a8ec2ce0b..95bf6023bc 100755 --- a/selfdrive/debug/mpc/tune_lateral.py +++ b/selfdrive/debug/mpc/tune_lateral.py @@ -1,4 +1,6 @@ #! /usr/bin/env python +# type: ignore + import numpy as np from collections import OrderedDict import matplotlib.pyplot as plt diff --git a/selfdrive/debug/mpc/tune_longitudinal.py b/selfdrive/debug/mpc/tune_longitudinal.py index ed3eb6378a..f7fd43c48d 100755 --- a/selfdrive/debug/mpc/tune_longitudinal.py +++ b/selfdrive/debug/mpc/tune_longitudinal.py @@ -1,4 +1,5 @@ #! /usr/bin/env python +# type: ignore import numpy as np import matplotlib.pyplot as plt from selfdrive.controls.lib.longitudinal_mpc import libmpc_py diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index 2e668046e9..0cba85a480 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +# type: ignore + import argparse import os import traceback diff --git a/selfdrive/locationd/models/car_kf.py b/selfdrive/locationd/models/car_kf.py index b984bf7665..dda5cea1b2 100755 --- a/selfdrive/locationd/models/car_kf.py +++ b/selfdrive/locationd/models/car_kf.py @@ -1,6 +1,7 @@ #!/usr/bin/env python3 -import sys import math +import sys +from typing import Any, Dict import numpy as np import sympy as sp @@ -58,7 +59,7 @@ class CarKalman(KalmanFilter): ]) P_initial = Q.copy() - obs_noise = { + obs_noise : Dict[int, Any] = { ObservationKind.STEER_ANGLE: np.atleast_2d(math.radians(0.01)**2), ObservationKind.ANGLE_OFFSET_FAST: np.atleast_2d(math.radians(10.0)**2), ObservationKind.STEER_RATIO: np.atleast_2d(5.0**2), diff --git a/selfdrive/locationd/models/gnss_kf.py b/selfdrive/locationd/models/gnss_kf.py index d3f8885f84..59c3877e44 100755 --- a/selfdrive/locationd/models/gnss_kf.py +++ b/selfdrive/locationd/models/gnss_kf.py @@ -1,11 +1,12 @@ #!/usr/bin/env python3 import sys +from typing import List import numpy as np import sympy as sp -from selfdrive.locationd.models.constants import ObservationKind from rednose.helpers.ekf_sym import EKF_sym, gen_code +from selfdrive.locationd.models.constants import ObservationKind from selfdrive.locationd.models.loc_kf import parse_pr, parse_prr @@ -39,7 +40,7 @@ class GNSSKalman(): (.1)**2, (0)**2, (0.005)**2, .1**2, (.01)**2]) - maha_test_kinds = [] # ObservationKind.PSEUDORANGE_RATE, ObservationKind.PSEUDORANGE, ObservationKind.PSEUDORANGE_GLONASS] + maha_test_kinds: List[int] = [] # ObservationKind.PSEUDORANGE_RATE, ObservationKind.PSEUDORANGE, ObservationKind.PSEUDORANGE_GLONASS] @staticmethod def generate_code(generated_dir): diff --git a/selfdrive/locationd/test/ci_test.py b/selfdrive/locationd/test/ci_test.py index 5b23e8326a..b715a499af 100755 --- a/selfdrive/locationd/test/ci_test.py +++ b/selfdrive/locationd/test/ci_test.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +# type: ignore import subprocess import os import sys diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index 65fdfce9b5..5dbe8cff45 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +# type: ignore import os import serial diff --git a/selfdrive/locationd/test/ubloxd_easy.py b/selfdrive/locationd/test/ubloxd_easy.py index 8f226604ec..0f90b012bb 100755 --- a/selfdrive/locationd/test/ubloxd_easy.py +++ b/selfdrive/locationd/test/ubloxd_easy.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +# type: ignore import os from selfdrive.locationd.test import ublox diff --git a/selfdrive/locationd/test/ubloxd_py_test.py b/selfdrive/locationd/test/ubloxd_py_test.py index bca9ddc421..7a573631b4 100755 --- a/selfdrive/locationd/test/ubloxd_py_test.py +++ b/selfdrive/locationd/test/ubloxd_py_test.py @@ -1,3 +1,5 @@ +# type: ignore + import sys import os diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 1fe4a02780..bf237ee76c 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -9,8 +9,10 @@ import shutil import subprocess import datetime import textwrap +from typing import Dict, List from selfdrive.swaglog import cloudlog, add_logentries_handler + from common.basedir import BASEDIR, PARAMS from common.android import ANDROID WEBCAM = os.getenv("WEBCAM") is not None @@ -99,7 +101,7 @@ if not prebuilt: # Read progress from stderr and update spinner while scons.poll() is None: try: - line = scons.stderr.readline() + line = scons.stderr.readline() # type: ignore if line is None: continue line = line.rstrip() @@ -117,7 +119,7 @@ if not prebuilt: if scons.returncode != 0: # Read remaining output - r = scons.stderr.read().split(b'\n') + r = scons.stderr.read().split(b'\n') # type: ignore compile_output += r if retry: @@ -194,7 +196,7 @@ daemon_processes = { "manage_athenad": ("selfdrive.athena.manage_athenad", "AthenadPid"), } -running = {} +running: Dict[str, Process] = {} def get_running(): return running @@ -202,7 +204,7 @@ def get_running(): unkillable_processes = ['camerad'] # processes to end with SIGINT instead of SIGTERM -interrupt_processes = [] +interrupt_processes: List[str] = [] # processes to end with SIGKILL instead of SIGTERM kill_processes = ['sensord', 'paramsd'] diff --git a/selfdrive/test/longitudinal_maneuvers/plant_ui.py b/selfdrive/test/longitudinal_maneuvers/plant_ui.py deleted file mode 100755 index 3c73f83291..0000000000 --- a/selfdrive/test/longitudinal_maneuvers/plant_ui.py +++ /dev/null @@ -1,119 +0,0 @@ -#!/usr/bin/env python3 -import pygame # pylint: disable=import-error -from selfdrive.test.longitudinal_maneuvers.plant import Plant -from selfdrive.car.honda.values import CruiseButtons -import numpy as np -import cereal.messaging as messaging -import math - -CAR_WIDTH = 2.0 -CAR_LENGTH = 4.5 - -METER = 8 - -def rot_center(image, angle): - """rotate an image while keeping its center and size""" - orig_rect = image.get_rect() - rot_image = pygame.transform.rotate(image, angle) - rot_rect = orig_rect.copy() - rot_rect.center = rot_image.get_rect().center - rot_image = rot_image.subsurface(rot_rect).copy() - return rot_image - -def car_w_color(c): - car = pygame.Surface((METER*CAR_LENGTH, METER*CAR_LENGTH)) # pylint: disable=too-many-function-args - car.set_alpha(0) - car.fill((10,10,10)) - car.set_alpha(128) - pygame.draw.rect(car, c, (METER*1.25, 0, METER*CAR_WIDTH, METER*CAR_LENGTH), 1) - return car - -if __name__ == "__main__": - pygame.init() - display = pygame.display.set_mode((1000, 1000)) - pygame.display.set_caption('Plant UI') - - car = car_w_color((255,0,255)) - leadcar = car_w_color((255,0,0)) - - carx, cary, heading = 10.0, 50.0, 0.0 - - plant = Plant(100, distance_lead = 40.0) - - control_offset = 2.0 - control_pts = list(zip(np.arange(0, 100.0, 10.0), [50.0 + control_offset]*10)) - - def pt_to_car(pt): - x,y = pt - x -= carx - y -= cary - rx = x * math.cos(-heading) + y * -math.sin(-heading) - ry = x * math.sin(-heading) + y * math.cos(-heading) - return rx, ry - - def pt_from_car(pt): - x,y = pt - rx = x * math.cos(heading) + y * -math.sin(heading) - ry = x * math.sin(heading) + y * math.cos(heading) - rx += carx - ry += cary - return rx, ry - - while 1: - if plant.rk.frame%100 >= 20 and plant.rk.frame%100 <= 25: - cruise_buttons = CruiseButtons.RES_ACCEL - else: - cruise_buttons = 0 - - md = messaging.new_message('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 = [pt_to_car(pt) for pt in 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/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py index 731e716723..addcfa9310 100755 --- a/selfdrive/test/process_replay/compare_logs.py +++ b/selfdrive/test/process_replay/compare_logs.py @@ -8,7 +8,7 @@ import dictdiffer if "CI" in os.environ: tqdm = lambda x: x else: - from tqdm import tqdm + from tqdm import tqdm # type: ignore from tools.lib.logreader import LogReader diff --git a/selfdrive/test/process_replay/flycheck_compare_logs.py b/selfdrive/test/process_replay/flycheck_compare_logs.py new file mode 100644 index 0000000000..addcfa9310 --- /dev/null +++ b/selfdrive/test/process_replay/flycheck_compare_logs.py @@ -0,0 +1,72 @@ +#!/usr/bin/env python3 +import bz2 +import os +import sys +import numbers + +import dictdiffer +if "CI" in os.environ: + tqdm = lambda x: x +else: + from tqdm import tqdm # type: ignore + +from tools.lib.logreader import LogReader + +def save_log(dest, log_msgs): + dat = b"" + for msg in tqdm(log_msgs): + dat += msg.as_builder().to_bytes() + dat = bz2.compress(dat) + + with open(dest, "wb") as f: + f.write(dat) + +def remove_ignored_fields(msg, ignore): + msg = msg.as_builder() + for key in ignore: + attr = msg + keys = key.split(".") + if msg.which() not in key and len(keys) > 1: + continue + + for k in keys[:-1]: + try: + attr = getattr(msg, k) + except: + break + else: + v = getattr(attr, keys[-1]) + if isinstance(v, bool): + val = False + elif isinstance(v, numbers.Number): + val = 0 + else: + raise NotImplementedError + setattr(attr, keys[-1], val) + return msg.as_reader() + +def compare_logs(log1, log2, ignore_fields=[], ignore_msgs=[]): + filter_msgs = lambda m: m.which() not in ignore_msgs + log1, log2 = [list(filter(filter_msgs, log)) for log in (log1, log2)] + assert len(log1) == len(log2), "logs are not same length: " + str(len(log1)) + " VS " + str(len(log2)) + + diff = [] + for msg1, msg2 in tqdm(zip(log1, log2)): + if msg1.which() != msg2.which(): + print(msg1, msg2) + raise Exception("msgs not aligned between logs") + + msg1_bytes = remove_ignored_fields(msg1, ignore_fields).as_builder().to_bytes() + msg2_bytes = remove_ignored_fields(msg2, ignore_fields).as_builder().to_bytes() + + if msg1_bytes != msg2_bytes: + msg1_dict = msg1.to_dict(verbose=True) + msg2_dict = msg2.to_dict(verbose=True) + dd = dictdiffer.diff(msg1_dict, msg2_dict, ignore=ignore_fields, tolerance=0) + diff.extend(dd) + return diff + +if __name__ == "__main__": + log1 = list(LogReader(sys.argv[1])) + log2 = list(LogReader(sys.argv[2])) + print(compare_logs(log1, log2, sys.argv[3:])) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 2687b24210..46eb5a09ef 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -7,7 +7,7 @@ import importlib if "CI" in os.environ: tqdm = lambda x: x else: - from tqdm import tqdm + from tqdm import tqdm # type: ignore from cereal import car, log from selfdrive.car.car_helpers import get_car diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 06f1b9bcd6..c4315bfc52 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -2,13 +2,14 @@ import argparse import os import sys +from typing import Any from selfdrive.car.car_helpers import interface_names -from selfdrive.test.process_replay.process_replay import replay_process, CONFIGS from selfdrive.test.process_replay.compare_logs import compare_logs +from selfdrive.test.process_replay.process_replay import (CONFIGS, + replay_process) from tools.lib.logreader import LogReader - INJECT_MODEL = 0 segments = [ @@ -134,7 +135,7 @@ if __name__ == "__main__": untested = (set(interface_names) - set(excluded_interfaces)) - tested_cars assert len(untested) == 0, "Cars missing routes: %s" % (str(untested)) - results = {} + results: Any = {} for car_brand, segment in segments: if (cars_whitelisted and car_brand.upper() not in args.whitelist_cars) or \ (not cars_whitelisted and car_brand.upper() in args.blacklist_cars): diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 954f204188..685cb485f4 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -1,27 +1,28 @@ #!/usr/bin/env python3 -import time import os -import sys import signal import subprocess +import sys +import time +from typing import List, cast + import requests -from cereal import car -import selfdrive.manager as manager import cereal.messaging as messaging -from common.params import Params +import selfdrive.manager as manager +from cereal import car from common.basedir import BASEDIR +from common.params import Params +from selfdrive.car.chrysler.values import CAR as CHRYSLER from selfdrive.car.fingerprints import all_known_cars -from selfdrive.car.honda.values import CAR as HONDA -from selfdrive.car.toyota.values import CAR as TOYOTA -from selfdrive.car.gm.values import CAR as GM from selfdrive.car.ford.values import CAR as FORD +from selfdrive.car.gm.values import CAR as GM +from selfdrive.car.honda.values import CAR as HONDA from selfdrive.car.hyundai.values import CAR as HYUNDAI -from selfdrive.car.chrysler.values import CAR as CHRYSLER +from selfdrive.car.nissan.values import CAR as NISSAN from selfdrive.car.subaru.values import CAR as SUBARU +from selfdrive.car.toyota.values import CAR as TOYOTA from selfdrive.car.volkswagen.values import CAR as VOLKSWAGEN -from selfdrive.car.nissan.values import CAR as NISSAN - os.environ['NOCRASH'] = '1' @@ -363,7 +364,7 @@ routes = { }, } -passive_routes = [ +passive_routes: List[str] = [ ] forced_dashcam_routes = [ @@ -436,7 +437,7 @@ if __name__ == "__main__": os.environ['SKIP_FW_QUERY'] = "1" if checks.get('fingerprintSource', None) == 'fixed': - os.environ['FINGERPRINT'] = checks['carFingerprint'] + os.environ['FINGERPRINT'] = cast(str, checks['carFingerprint']) else: os.environ['FINGERPRINT'] = "" diff --git a/tools/lib/auth.py b/tools/lib/auth.py index 57e0eb0ae4..870eb6b0bc 100755 --- a/tools/lib/auth.py +++ b/tools/lib/auth.py @@ -5,9 +5,10 @@ from http.server import HTTPServer, BaseHTTPRequestHandler from urllib.parse import urlencode, parse_qs from tools.lib.api import CommaApi, APIError from tools.lib.auth_config import set_token +from typing import Dict, Any class ClientRedirectServer(HTTPServer): - query_params = {} + query_params: Dict[str, Any] = {} class ClientRedirectHandler(BaseHTTPRequestHandler): def do_GET(self): diff --git a/tools/replay/lib/ui_helpers.py b/tools/replay/lib/ui_helpers.py index 8aaf40afcb..4debec40e2 100644 --- a/tools/replay/lib/ui_helpers.py +++ b/tools/replay/lib/ui_helpers.py @@ -1,15 +1,16 @@ from collections import namedtuple +from typing import Any, Dict, Tuple import matplotlib import matplotlib.pyplot as plt import numpy as np import pygame -from tools.lib.lazy_property import lazy_property -from selfdrive.config import UIParams as UP from selfdrive.config import RADAR_TO_CAMERA +from selfdrive.config import UIParams as UP from selfdrive.controls.lib.lane_planner import (compute_path_pinv, model_polyfit) +from tools.lib.lazy_property import lazy_property RED = (255, 0, 0) GREEN = (0, 255, 0) @@ -34,7 +35,7 @@ METER_WIDTH = 20 ModelUIData = namedtuple("ModelUIData", ["cpath", "lpath", "rpath", "lead", "lead_future"]) -_COLOR_CACHE = {} +_COLOR_CACHE : Dict[Tuple[int, int, int], Any] = {} def find_color(lidar_surface, color): if color in _COLOR_CACHE: return _COLOR_CACHE[color] diff --git a/tools/replay/rqplot.py b/tools/replay/rqplot.py index 3c3c5239c5..8886cf7f37 100755 --- a/tools/replay/rqplot.py +++ b/tools/replay/rqplot.py @@ -1,4 +1,5 @@ #!/usr/bin/env python +# type: ignore import sys import matplotlib.pyplot as plt import numpy as np @@ -78,4 +79,3 @@ if __name__ == "__main__": # just a bit of wait to avoid 100% CPU usage time.sleep(0.001) - diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index b3857683c0..b0ea6fa7cb 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +# type: ignore import time import math import atexit diff --git a/tools/sim/lib/keyboard_ctrl.py b/tools/sim/lib/keyboard_ctrl.py index 84436d5387..18a491fec0 100644 --- a/tools/sim/lib/keyboard_ctrl.py +++ b/tools/sim/lib/keyboard_ctrl.py @@ -1,8 +1,9 @@ import sys import termios import time -from termios import (BRKINT, VMIN, CS8, CSIZE, ECHO, ICANON, ICRNL, IEXTEN, - INPCK, ISIG, ISTRIP, IXON, PARENB, VTIME) +from termios import (BRKINT, CS8, CSIZE, ECHO, ICANON, ICRNL, IEXTEN, INPCK, + ISIG, ISTRIP, IXON, PARENB, VMIN, VTIME) +from typing import Any # Indexes for termios list. IFLAG = 0 @@ -53,7 +54,7 @@ def test(q): if __name__ == '__main__': from multiprocessing import Process, Queue - q = Queue() + q : Any = Queue() p = Process(target=test, args=(q,)) p.daemon = True p.start() From 108a13ead84ea5f06bba77d81cae371a08c020c6 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 29 May 2020 06:10:49 +0800 Subject: [PATCH 122/656] UI: better read_model (#1586) * update model struct inplace * refer params * pass path by refer --- selfdrive/ui/paint.cc | 2 +- selfdrive/ui/ui.cc | 30 ++++++++++++------------------ 2 files changed, 13 insertions(+), 19 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 588f20c3a6..b1d2133bf5 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -322,7 +322,7 @@ static void update_lane_line_data(UIState *s, const float *points, float off, bo } } -static void update_all_lane_lines_data(UIState *s, const PathData path, model_path_vertices_data *pstart) { +static void update_all_lane_lines_data(UIState *s, const PathData &path, model_path_vertices_data *pstart) { update_lane_line_data(s, path.points, 0.025*path.prob, false, pstart); float var = fmin(path.std, 0.7); update_lane_line_data(s, path.points, -var, true, pstart + 1); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index c4daf3591c..e70197b268 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -288,38 +288,32 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, s->limit_set_speed_timeout = UI_FREQ; } -static PathData read_path(cereal::ModelData::PathData::Reader pathp) { - PathData ret = {0}; +static void read_path(PathData& p, const cereal::ModelData::PathData::Reader &pathp) { + p = {}; - ret.prob = pathp.getProb(); - ret.std = pathp.getStd(); + p.prob = pathp.getProb(); + p.std = pathp.getStd(); auto polyp = pathp.getPoly(); for (int i = 0; i < POLYFIT_DEGREE; i++) { - ret.poly[i] = polyp[i]; + p.poly[i] = polyp[i]; } // Compute points locations for (int i = 0; i < MODEL_PATH_DISTANCE; i++) { - ret.points[i] = ret.poly[0] * (i*i*i) + ret.poly[1] * (i*i)+ ret.poly[2] * i + ret.poly[3]; + p.points[i] = p.poly[0] * (i*i*i) + p.poly[1] * (i*i)+ p.poly[2] * i + p.poly[3]; } - - return ret; } -static ModelData read_model(cereal::ModelData::Reader model) { - ModelData d = {0}; - - d.path = read_path(model.getPath()); - d.left_lane = read_path(model.getLeftLane()); - d.right_lane = read_path(model.getRightLane()); - +static void read_model(ModelData &d, const cereal::ModelData::Reader &model) { + d = {}; + read_path(d.path, model.getPath()); + read_path(d.left_lane, model.getLeftLane()); + read_path(d.right_lane, model.getRightLane()); auto leadd = model.getLead(); d.lead = (LeadData){ .dist = leadd.getDist(), .prob = leadd.getProb(), .std = leadd.getStd(), }; - - return d; } static void update_status(UIState *s, int status) { @@ -414,7 +408,7 @@ void handle_message(UIState *s, SubMaster &sm) { } } if (sm.updated("model")) { - scene.model = read_model(sm["model"].getModel()); + read_model(scene.model, sm["model"].getModel()); s->model_changed = true; } // else if (which == cereal::Event::LIVE_MPC) { From ba2ac1207a554d277e01af5b9514de4500d4f66a Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 28 May 2020 15:40:48 -0700 Subject: [PATCH 123/656] Running pre-commit in CI (#1590) * Running pre-commit in CI * fix dockerfile syntax * dont run on submodule repo folders * Fix some import errors in ci * more stuff * That should be the last one --- .github/workflows/test.yaml | 4 ++- .pre-commit-config.yaml | 4 +-- Dockerfile.openpilot | 4 ++- common/window.py | 4 +-- release/remote_build.py | 2 +- selfdrive/camerad/test/yuv_bench/cnv.py | 2 +- selfdrive/debug/internal/design_lqr.py | 2 +- selfdrive/modeld/runners/keras_runner.py | 9 +++-- selfdrive/modeld/test/tf_test/pb_loader.py | 3 +- selfdrive/test/profiling/controlsd.py | 6 ++-- tools/carcontrols/joystick_test.py | 38 +++++++++++----------- tools/carcontrols/joystickd.py | 2 +- tools/livedm/helpers.py | 3 +- tools/livedm/livedm.py | 4 +-- tools/replay/camera.py | 4 +-- tools/replay/lib/ui_helpers.py | 2 +- tools/replay/sensorium.py | 4 +-- tools/replay/ui.py | 4 +-- tools/sim/lib/can.py | 2 +- tools/webcam/front_mount_helper.py | 4 +-- tools/webcam/warp_vis.py | 4 +-- 21 files changed, 54 insertions(+), 57 deletions(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 43c90dc97a..57821c9c6f 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -37,7 +37,7 @@ jobs: # need these so docker copy won't fail cp Pipfile Pipfile.lock flake8_openpilot.sh pylint_openpilot.sh .pylintrc \ - cppcheck_openpilot.sh .coveragerc-app $TEST_DIR + cppcheck_openpilot.sh .coveragerc-app .pre-commit-config.yaml $TEST_DIR cd $TEST_DIR mkdir pyextra laika laika_repo tools release - name: Build Docker image @@ -77,6 +77,8 @@ jobs: run: $RUN "cd /tmp/openpilot/ && ./flake8_openpilot.sh" - name: pylint run: $RUN "cd /tmp/openpilot/ && ./pylint_openpilot.sh" + - name: pre-commit + run: $RUN "cd /tmp/openpilot/ && git init && git add -A && pre-commit run --all" - name: cppcheck run: $PERSIST "cd /tmp/openpilot/ && ./cppcheck_openpilot.sh 2> cppcheck_report.txt" - name: Print cppcheck report diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 71f442a536..a347c57bf2 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -15,7 +15,7 @@ repos: rev: master hooks: - id: flake8 - exclude: '^(pyextra)|(external)/' + exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - --select=F - repo: local @@ -25,6 +25,6 @@ repos: entry: pylint language: system types: [python] - exclude: '^(pyextra)|(external)/' + exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - --disable=R,C,W diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 205e5f198c..0ef6912418 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -71,7 +71,8 @@ RUN pyenv install 3.8.2 && \ azure-storage-common==2.1.0 \ azure-storage-nspkg==3.1.0 \ pycurl==7.43.0.3 \ - coverage==5.1 + coverage==5.1 \ + pre-commit==2.4.0 RUN mkdir -p /tmp/openpilot @@ -80,6 +81,7 @@ COPY SConstruct \ flake8_openpilot.sh \ pylint_openpilot.sh \ .pylintrc \ + .pre-commit-config.yaml \ .coveragerc-app \ /tmp/openpilot/ diff --git a/common/window.py b/common/window.py index 7454a86207..8c36fa5432 100644 --- a/common/window.py +++ b/common/window.py @@ -1,6 +1,6 @@ import sys -import pygame -import cv2 +import pygame # pylint: disable=import-error +import cv2 # pylint: disable=import-error class Window(): def __init__(self, w, h, caption="window", double=False): diff --git a/release/remote_build.py b/release/remote_build.py index f80843cef9..d9785e0b6f 100755 --- a/release/remote_build.py +++ b/release/remote_build.py @@ -1,5 +1,5 @@ #!/usr/bin/env python2 -import paramiko +import paramiko # pylint: disable=import-error import os import sys import re diff --git a/selfdrive/camerad/test/yuv_bench/cnv.py b/selfdrive/camerad/test/yuv_bench/cnv.py index 86fd0c9982..24fde0875a 100644 --- a/selfdrive/camerad/test/yuv_bench/cnv.py +++ b/selfdrive/camerad/test/yuv_bench/cnv.py @@ -1,5 +1,5 @@ import numpy as np -import cv2 +import cv2 # pylint: disable=import-error # img_bgr = np.zeros((874, 1164, 3), dtype=np.uint8) # for y in range(874): diff --git a/selfdrive/debug/internal/design_lqr.py b/selfdrive/debug/internal/design_lqr.py index 0304df5aa1..fcc2524f2c 100755 --- a/selfdrive/debug/internal/design_lqr.py +++ b/selfdrive/debug/internal/design_lqr.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 import numpy as np -import control +import control # pylint: disable=import-error dt = 0.01 A = np.array([[ 0. , 1. ], [-0.78823806, 1.78060701]]) diff --git a/selfdrive/modeld/runners/keras_runner.py b/selfdrive/modeld/runners/keras_runner.py index 4dfd197673..5ed0e6d79c 100755 --- a/selfdrive/modeld/runners/keras_runner.py +++ b/selfdrive/modeld/runners/keras_runner.py @@ -2,13 +2,13 @@ # TODO: why are the keras models saved with python 2? from __future__ import print_function -import tensorflow as tf +import tensorflow as tf # pylint: disable=import-error import os import sys -import tensorflow.keras as keras +import tensorflow.keras as keras # pylint: disable=import-error import numpy as np -from tensorflow.keras.models import Model -from tensorflow.keras.models import load_model +from tensorflow.keras.models import Model # pylint: disable=import-error +from tensorflow.keras.models import load_model # pylint: disable=import-error def read(sz): dd = [] @@ -55,4 +55,3 @@ if __name__ == "__main__": no = keras.layers.Concatenate()(m(tii)) m = Model(inputs=ri, outputs=[no]) run_loop(m) - diff --git a/selfdrive/modeld/test/tf_test/pb_loader.py b/selfdrive/modeld/test/tf_test/pb_loader.py index d4db20eb66..78fd33aef2 100755 --- a/selfdrive/modeld/test/tf_test/pb_loader.py +++ b/selfdrive/modeld/test/tf_test/pb_loader.py @@ -1,9 +1,8 @@ #!/usr/bin/env python3 import sys -import tensorflow as tf +import tensorflow as tf # pylint: disable=import-error with open(sys.argv[1], "rb") as f: graph_def = tf.compat.v1.GraphDef() graph_def.ParseFromString(f.read()) #tf.io.write_graph(graph_def, '', sys.argv[1]+".try") - diff --git a/selfdrive/test/profiling/controlsd.py b/selfdrive/test/profiling/controlsd.py index 38ce860d35..329e6a8d93 100755 --- a/selfdrive/test/profiling/controlsd.py +++ b/selfdrive/test/profiling/controlsd.py @@ -1,9 +1,9 @@ #!/usr/bin/env python3 import os -import cProfile -import pprofile -import pyprof2calltree +import cProfile # pylint: disable=import-error +import pprofile # pylint: disable=import-error +import pyprof2calltree # pylint: disable=import-error from tools.lib.logreader import LogReader from selfdrive.controls.controlsd import main as controlsd_thread diff --git a/tools/carcontrols/joystick_test.py b/tools/carcontrols/joystick_test.py index e031fb506f..1a41d4729c 100755 --- a/tools/carcontrols/joystick_test.py +++ b/tools/carcontrols/joystick_test.py @@ -1,5 +1,5 @@ #!/usr/bin/env python -import pygame +import pygame # pylint: disable=import-error # Define some colors BLACK = ( 0, 0, 0) @@ -17,21 +17,21 @@ class TextPrint: textBitmap = self.font.render(textString, True, BLACK) screen.blit(textBitmap, [self.x, self.y]) self.y += self.line_height - + def reset(self): self.x = 10 self.y = 10 self.line_height = 15 - + def indent(self): self.x += 10 - + def unindent(self): self.x -= 10 - + pygame.init() - + # Set the width and height of the screen [width,height] size = [500, 700] screen = pygame.display.set_mode(size) @@ -46,7 +46,7 @@ clock = pygame.time.Clock() # Initialize the joysticks pygame.joystick.init() - + # Get ready to print textPrint = TextPrint() @@ -56,14 +56,14 @@ while done==False: for event in pygame.event.get(): # User did something if event.type == pygame.QUIT: # If user clicked close done=True # Flag that we are done so we exit this loop - + # Possible joystick actions: JOYAXISMOTION JOYBALLMOTION JOYBUTTONDOWN JOYBUTTONUP JOYHATMOTION if event.type == pygame.JOYBUTTONDOWN: print("Joystick button pressed.") if event.type == pygame.JOYBUTTONUP: print("Joystick button released.") - - + + # DRAWING STEP # First, clear the screen to white. Don't put other drawing commands # above this, or they will be erased with this command. @@ -75,29 +75,29 @@ while done==False: textPrint.printf(screen, "Number of joysticks: {}".format(joystick_count) ) textPrint.indent() - + # For each joystick: joystick = pygame.joystick.Joystick(0) joystick.init() - + textPrint.printf(screen, "Joystick {}".format(0) ) textPrint.indent() - + # Get the name from the OS for the controller/joystick name = joystick.get_name() textPrint.printf(screen, "Joystick name: {}".format(name) ) - + # Usually axis run in pairs, up/down for one, and left/right for # the other. axes = joystick.get_numaxes() textPrint.printf(screen, "Number of axes: {}".format(axes) ) textPrint.indent() - + for i in range( axes ): axis = joystick.get_axis( i ) textPrint.printf(screen, "Axis {} value: {:>6.3f}".format(i, axis) ) textPrint.unindent() - + buttons = joystick.get_numbuttons() textPrint.printf(screen, "Number of buttons: {}".format(buttons) ) textPrint.indent() @@ -110,15 +110,15 @@ while done==False: textPrint.unindent() - + # ALL CODE TO DRAW SHOULD GO ABOVE THIS COMMENT - + # Go ahead and update the screen with what we've drawn. pygame.display.flip() # Limit to 20 frames per second clock.tick(20) - + # Close the window and quit. # If you forget this line, the program will 'hang' # on exit if running from IDLE. diff --git a/tools/carcontrols/joystickd.py b/tools/carcontrols/joystickd.py index b262694e6f..a441763709 100755 --- a/tools/carcontrols/joystickd.py +++ b/tools/carcontrols/joystickd.py @@ -6,7 +6,7 @@ ### this process needs pygame and can't run on the EON ### -import pygame +import pygame # pylint: disable=import-error import cereal.messaging as messaging def joystick_thread(): diff --git a/tools/livedm/helpers.py b/tools/livedm/helpers.py index 47a79a67cb..df392bfd9b 100644 --- a/tools/livedm/helpers.py +++ b/tools/livedm/helpers.py @@ -1,5 +1,5 @@ import numpy as np -import cv2 +import cv2 # pylint: disable=import-error def rot_matrix(roll, pitch, yaw): cr, sr = np.cos(roll), np.sin(roll) @@ -27,4 +27,3 @@ def draw_pose(img, pose, loc, W=160, H=320, xyoffset=(0,0), faceprob=0): else: color = (64,64,64) cv2.circle(img, tr, 7, color=color) - \ No newline at end of file diff --git a/tools/livedm/livedm.py b/tools/livedm/livedm.py index 60361d9207..360aaee602 100644 --- a/tools/livedm/livedm.py +++ b/tools/livedm/livedm.py @@ -1,9 +1,9 @@ #!/usr/bin/env python3 import os import argparse -import pygame +import pygame # pylint: disable=import-error import numpy as np -import cv2 +import cv2 # pylint: disable=import-error from cereal import log import cereal.messaging as messaging diff --git a/tools/replay/camera.py b/tools/replay/camera.py index c312f52737..9860f7521b 100755 --- a/tools/replay/camera.py +++ b/tools/replay/camera.py @@ -6,9 +6,9 @@ os.environ['BASEDIR'] = BASEDIR SCALE = float(os.getenv("SCALE", 1.0)) import argparse -import pygame +import pygame # pylint: disable=import-error import numpy as np -import cv2 +import cv2 # pylint: disable=import-error import sys import cereal.messaging as messaging diff --git a/tools/replay/lib/ui_helpers.py b/tools/replay/lib/ui_helpers.py index 4debec40e2..78cbefddf5 100644 --- a/tools/replay/lib/ui_helpers.py +++ b/tools/replay/lib/ui_helpers.py @@ -4,7 +4,7 @@ from typing import Any, Dict, Tuple import matplotlib import matplotlib.pyplot as plt import numpy as np -import pygame +import pygame # pylint: disable=import-error from selfdrive.config import RADAR_TO_CAMERA from selfdrive.config import UIParams as UP diff --git a/tools/replay/sensorium.py b/tools/replay/sensorium.py index b85d6ef8c0..a7d9ee6819 100755 --- a/tools/replay/sensorium.py +++ b/tools/replay/sensorium.py @@ -3,7 +3,7 @@ # Question: Can a human drive from this data? import os -import cv2 +import cv2 # pylint: disable=import-error import numpy as np import cereal.messaging as messaging from common.window import Window @@ -49,5 +49,3 @@ if __name__ == "__main__": flags=cv2.WARP_INVERSE_MAP | cv2.INTER_CUBIC) win.draw(imgw) - - diff --git a/tools/replay/ui.py b/tools/replay/ui.py index ee07a28137..9d30c38522 100755 --- a/tools/replay/ui.py +++ b/tools/replay/ui.py @@ -5,9 +5,9 @@ import sys os.environ["OMP_NUM_THREADS"] = "1" -import cv2 +import cv2 # pylint: disable=import-error import numpy as np -import pygame +import pygame # pylint: disable=import-error from common.basedir import BASEDIR from common.transformations.camera import FULL_FRAME_SIZE, eon_intrinsics diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index a446d38cd5..9fbb2006f1 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import cereal.messaging as messaging from opendbc.can.packer import CANPacker -from selfdrive.boardd.boardd_api_impl import can_list_to_can_capnp # pylint: disable=no-name-in-module +from selfdrive.boardd.boardd_api_impl import can_list_to_can_capnp # pylint: disable=no-name-in-module,import-error from selfdrive.car.honda.values import FINGERPRINTS, CAR from selfdrive.car import crc8_pedal import math diff --git a/tools/webcam/front_mount_helper.py b/tools/webcam/front_mount_helper.py index 1fdca3225a..78b707950e 100755 --- a/tools/webcam/front_mount_helper.py +++ b/tools/webcam/front_mount_helper.py @@ -18,7 +18,7 @@ webcam_intrinsics = np.array([ cam_id = 2 if __name__ == "__main__": - import cv2 + import cv2 # pylint: disable=import-error trans_webcam_to_eon_front = np.dot(eon_dcam_intrinsics,np.linalg.inv(webcam_intrinsics)) @@ -32,4 +32,4 @@ if __name__ == "__main__": img = cv2.warpPerspective(img, trans_webcam_to_eon_front, (1152,864), borderMode=cv2.BORDER_CONSTANT, borderValue=0) img = img[:,-864//2:,:] cv2.imshow('preview', img) - cv2.waitKey(10) \ No newline at end of file + cv2.waitKey(10) diff --git a/tools/webcam/warp_vis.py b/tools/webcam/warp_vis.py index 547f1be99a..a1cb3e7e45 100755 --- a/tools/webcam/warp_vis.py +++ b/tools/webcam/warp_vis.py @@ -23,7 +23,7 @@ webcam_intrinsics = np.array([ [ 0., 0., 1.]]) if __name__ == "__main__": - import cv2 + import cv2 # pylint: disable=import-error trans_webcam_to_eon_rear = np.dot(eon_intrinsics,np.linalg.inv(webcam_intrinsics)) trans_webcam_to_eon_front = np.dot(eon_dcam_intrinsics,np.linalg.inv(webcam_intrinsics)) print("trans_webcam_to_eon_rear:\n", trans_webcam_to_eon_rear) @@ -41,5 +41,3 @@ if __name__ == "__main__": print(img.shape, end='\r') cv2.imshow('preview', img) cv2.waitKey(10) - - From d112a58366d9d9a8830fa344efe6c50bf587cd00 Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Thu, 28 May 2020 17:33:22 -0700 Subject: [PATCH 124/656] FrameReader env vars FFMPEG_THREADS and FFMPEG_CUDA --- tools/lib/framereader.py | 44 +++++++++++++++++++--------------------- 1 file changed, 21 insertions(+), 23 deletions(-) diff --git a/tools/lib/framereader.py b/tools/lib/framereader.py index 9efe7961e0..5a1403591c 100644 --- a/tools/lib/framereader.py +++ b/tools/lib/framereader.py @@ -210,24 +210,24 @@ def rgb24toyuv420(rgb): return yuv420.clip(0,255).astype('uint8') -def decompress_video_data(rawdat, vid_fmt, w, h, pix_fmt, multithreaded=None): +def decompress_video_data(rawdat, vid_fmt, w, h, pix_fmt): # using a tempfile is much faster than proc.communicate for some reason - if multithreaded is None: - multithreaded = not os.getenv('SINGLETHREADED') - with tempfile.TemporaryFile() as tmpf: tmpf.write(rawdat) tmpf.seek(0) + threads = os.getenv("FFMPEG_THREADS", "0") + cuda = os.getenv("FFMPEG_CUDA", "0") == "1" proc = subprocess.Popen( ["ffmpeg", - "-threads", "0" if multithreaded else "1", + "-threads", threads, + "-c:v", "hevc" if not cuda else "hevc_cuvid", "-vsync", "0", "-f", vid_fmt, "-flags2", "showall", "-i", "pipe:0", - "-threads", "0" if multithreaded else "1", + "-threads", threads, "-f", "rawvideo", "-pix_fmt", pix_fmt, "pipe:1"], @@ -266,14 +266,14 @@ class BaseFrameReader: raise NotImplementedError -def FrameReader(fn, cache_prefix=None, readahead=False, readbehind=False, multithreaded=None, index_data=None): +def FrameReader(fn, cache_prefix=None, readahead=False, readbehind=False, index_data=None): frame_type = fingerprint_video(fn) if frame_type == FrameType.raw: return RawFrameReader(fn) elif frame_type in (FrameType.h265_stream,): if not index_data: index_data = get_video_index(fn, frame_type, cache_prefix) - return StreamFrameReader(fn, frame_type, index_data, readahead=readahead, readbehind=readbehind, multithreaded=multithreaded) + return StreamFrameReader(fn, frame_type, index_data, readahead=readahead, readbehind=readbehind) else: raise NotImplementedError(frame_type) @@ -325,15 +325,12 @@ class RawFrameReader(BaseFrameReader): class VideoStreamDecompressor: - def __init__(self, vid_fmt, w, h, pix_fmt, multithreaded=None): + def __init__(self, vid_fmt, w, h, pix_fmt): self.vid_fmt = vid_fmt self.w = w self.h = h self.pix_fmt = pix_fmt - if multithreaded is None: - multithreaded = not os.getenv('SINGLETHREADED') - if pix_fmt == "yuv420p": self.out_size = w*h*3//2 # yuv420p elif pix_fmt in ("rgb24", "yuv444p"): @@ -343,9 +340,12 @@ class VideoStreamDecompressor: self.out_q = queue.Queue() + threads = os.getenv("FFMPEG_THREADS", "0") + cuda = os.getenv("FFMPEG_CUDA", "0") == "1" self.proc = subprocess.Popen( ["ffmpeg", - "-threads", "0" if multithreaded else "1", + "-threads", threads, + "-c:v", "hevc" if not cuda else "hevc_cuvid", # "-avioflags", "direct", "-analyzeduration", "0", "-probesize", "32", @@ -354,7 +354,7 @@ class VideoStreamDecompressor: "-vsync", "0", "-f", vid_fmt, "-i", "pipe:0", - "-threads", "0" if multithreaded else "1", + "-threads", threads, "-f", "rawvideo", "-pix_fmt", pix_fmt, "pipe:1"], @@ -479,10 +479,9 @@ class StreamGOPReader(GOPReader): class GOPFrameReader(BaseFrameReader): #FrameReader with caching and readahead for formats that are group-of-picture based - def __init__(self, readahead=False, readbehind=False, multithreaded=None): + def __init__(self, readahead=False, readbehind=False): self.open_ = True - self.multithreaded = multithreaded self.readahead = readahead self.readbehind = readbehind self.frame_cache = LRU(64) @@ -542,8 +541,7 @@ class GOPFrameReader(BaseFrameReader): frame_b, num_frames, skip_frames, rawdat = self.get_gop(num) - ret = decompress_video_data(rawdat, self.vid_fmt, self.w, self.h, pix_fmt, - multithreaded=self.multithreaded) + ret = decompress_video_data(rawdat, self.vid_fmt, self.w, self.h, pix_fmt) ret = ret[skip_frames:] assert ret.shape[0] == num_frames @@ -573,17 +571,17 @@ class GOPFrameReader(BaseFrameReader): class StreamFrameReader(StreamGOPReader, GOPFrameReader): - def __init__(self, fn, frame_type, index_data, readahead=False, readbehind=False, multithreaded=None): + def __init__(self, fn, frame_type, index_data, readahead=False, readbehind=False): StreamGOPReader.__init__(self, fn, frame_type, index_data) - GOPFrameReader.__init__(self, readahead, readbehind, multithreaded) + GOPFrameReader.__init__(self, readahead, readbehind) -def GOPFrameIterator(gop_reader, pix_fmt, multithreaded=None): +def GOPFrameIterator(gop_reader, pix_fmt): # this is really ugly. ill think about how to refactor it when i can think good IN_FLIGHT_GOPS = 6 # should be enough that the stream decompressor starts returning data - with VideoStreamDecompressor(gop_reader.vid_fmt, gop_reader.w, gop_reader.h, pix_fmt, multithreaded) as dec: + with VideoStreamDecompressor(gop_reader.vid_fmt, gop_reader.w, gop_reader.h, pix_fmt) as dec: read_work = [] def readthing(): @@ -621,7 +619,7 @@ def GOPFrameIterator(gop_reader, pix_fmt, multithreaded=None): def FrameIterator(fn, pix_fmt, **kwargs): fr = FrameReader(fn, **kwargs) if isinstance(fr, GOPReader): - for v in GOPFrameIterator(fr, pix_fmt, kwargs.get("multithreaded", None)): + for v in GOPFrameIterator(fr, pix_fmt): yield v else: for i in range(fr.frame_count): From 266dfe5a9b521d62cfdfdca73ffe622deee82013 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 28 May 2020 17:45:22 -0700 Subject: [PATCH 125/656] use github url instead of gitlab mirror --- .pre-commit-config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index a347c57bf2..5eebcfa4b9 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -11,7 +11,7 @@ repos: hooks: - id: mypy exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' -- repo: https://gitlab.com/PyCQA/flake8 +- repo: https://github.com/PyCQA/flake8 rev: master hooks: - id: flake8 From 6a8b4fe793a94cf4e5f74959f7e98a70181f60ba Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 28 May 2020 17:48:04 -0700 Subject: [PATCH 126/656] bump submodules --- cereal | 2 +- opendbc | 2 +- rednose_repo | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/cereal b/cereal index f27222f8f8..c8be73d10c 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit f27222f8f87688b7c6808d66acf6da56aecaf622 +Subproject commit c8be73d10c957bff769998588595107d62e9e738 diff --git a/opendbc b/opendbc index d1185a53e5..2ade6eeba8 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit d1185a53e5b942a5dda7ddb8c827e23fa667c10a +Subproject commit 2ade6eeba82d2b3be0ab5f3ee0061de228ea6d65 diff --git a/rednose_repo b/rednose_repo index 86b047637c..ffab6b4a36 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit 86b047637c228ce72873b958b733ebbd38c5dc95 +Subproject commit ffab6b4a369f809cc2058155d8316dfef75de2a9 From 7961d5ffd71328f4e104c01244cc6e08152d76fa Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 28 May 2020 20:39:13 -0700 Subject: [PATCH 127/656] Fix below steer speed alert text not updating --- selfdrive/controls/lib/events.py | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 0202119337..5b2fdf6ad1 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -396,11 +396,7 @@ EVENTS = { }, EventName.belowSteerSpeed: { - ET.WARNING: Alert( - "TAKE CONTROL", - "Steer Unavailable Below ", - AlertStatus.userPrompt, AlertSize.mid, - Priority.MID, VisualAlert.steerRequired, AudibleAlert.none, 0., 0.4, .3), + ET.WARNING: below_steer_speed_alert, }, EventName.preLaneChangeLeft: { From 34b9b5e849fcd192bbd8c3060ce725ef61d725ab Mon Sep 17 00:00:00 2001 From: Jafar Al-Gharaibeh Date: Fri, 29 May 2020 00:15:19 -0500 Subject: [PATCH 128/656] Bounty: Mazda (#988) * Mazda Port Signed-off-by: Jafar Al-Gharaibeh * Update checksum to account for steer angle signal used in some cars Signed-off-by: Jafar Al-Gharaibeh * Add test drive/segment ID to pass CI tests Signed-off-by: Jafar Al-Gharaibeh * Process gear and brake signals, add new fingerprints Signed-off-by: Jafar Al-Gharaibeh * Refactor some car interface code Signed-off-by: Jafar Al-Gharaibeh * Drop redundant call, use Ecu, move warning to carstate, fix cruise speed Signed-off-by: Jafar Al-Gharaibeh * Drop unused variables, cleanup handsoff tracking Signed-off-by: Jafar Al-Gharaibeh * Update to steerError and steeringRate Signed-off-by: Jafar Al-Gharaibeh * Refactor parse gear, update lkas signals from the new dbc Signed-off-by: Jafar Al-Gharaibeh * Better tracking of engage and warning events Signed-off-by: Jafar Al-Gharaibeh * remove commented lines, update speed_kph to match panda Signed-off-by: Jafar Al-Gharaibeh * Steer Error Signed-off-by: Jafar Al-Gharaibeh * Set lkas enable speed to 52 kph Signed-off-by: Jafar Al-Gharaibeh * Drop block signal use, fix LGTM alerts Signed-off-by: Jafar Al-Gharaibeh * When gas is pressed OP will disengage, sync local state with it Signed-off-by: Jafar Al-Gharaibeh * Use car's speed signal instead of wheel speed Signed-off-by: Jafar Al-Gharaibeh * Tidy up disengage events Signed-off-by: Jafar Al-Gharaibeh * Rebase/Refactor with upstream Signed-off-by: Jafar Al-Gharaibeh * Sync stock ACC state with OP Signed-off-by: Jafar Al-Gharaibeh * mazda dbc file renamed Signed-off-by: Jafar Al-Gharaibeh * Improve acc stock and go by removing the 3 seconds limit Signed-off-by: Jafar Al-Gharaibeh * Dashcam Signed-off-by: Jafar Al-Gharaibeh * PR Feedback Signed-off-by: Jafar Al-Gharaibeh * Send ACC cancel only if we are sure cruise is enabled Otherwise we run the risk of disabling main cruise Signed-off-by: Jafar Al-Gharaibeh * updated route Signed-off-by: Jafar Al-Gharaibeh * no process replay for now * add to release files * Revert "updated route" This reverts commit 233db4f1bc2d8eefaa86488be4f6f88360d20793. Co-authored-by: Adeeb Shihadeh --- release/files_common | 7 + selfdrive/car/mazda/__init__.py | 1 + selfdrive/car/mazda/carcontroller.py | 44 +++++ selfdrive/car/mazda/carstate.py | 185 ++++++++++++++++++ selfdrive/car/mazda/interface.py | 94 +++++++++ selfdrive/car/mazda/mazdacan.py | 104 ++++++++++ selfdrive/car/mazda/radar_interface.py | 6 + selfdrive/car/mazda/values.py | 64 ++++++ .../test/process_replay/test_processes.py | 5 +- selfdrive/test/test_car_models.py | 7 + 10 files changed, 515 insertions(+), 2 deletions(-) create mode 100644 selfdrive/car/mazda/__init__.py create mode 100644 selfdrive/car/mazda/carcontroller.py create mode 100644 selfdrive/car/mazda/carstate.py create mode 100755 selfdrive/car/mazda/interface.py create mode 100644 selfdrive/car/mazda/mazdacan.py create mode 100755 selfdrive/car/mazda/radar_interface.py create mode 100644 selfdrive/car/mazda/values.py diff --git a/release/files_common b/release/files_common index eb849cce95..03509a3023 100644 --- a/release/files_common +++ b/release/files_common @@ -157,6 +157,13 @@ selfdrive/car/subaru/radar_interface.py selfdrive/car/subaru/values.py selfdrive/car/subaru/carcontroller.py selfdrive/car/subaru/subarucan.py +selfdrive/car/mazda/__init__.py +selfdrive/car/mazda/carstate.py +selfdrive/car/mazda/interface.py +selfdrive/car/mazda/radar_interface.py +selfdrive/car/mazda/values.py +selfdrive/car/mazda/carcontroller.py +selfdrive/car/mazda/mazdacan.py selfdrive/car/mock/*.py selfdrive/clocksd/.gitignore diff --git a/selfdrive/car/mazda/__init__.py b/selfdrive/car/mazda/__init__.py new file mode 100644 index 0000000000..8b13789179 --- /dev/null +++ b/selfdrive/car/mazda/__init__.py @@ -0,0 +1 @@ + diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py new file mode 100644 index 0000000000..5714bdaf0d --- /dev/null +++ b/selfdrive/car/mazda/carcontroller.py @@ -0,0 +1,44 @@ +from selfdrive.car.mazda import mazdacan +from selfdrive.car.mazda.values import SteerLimitParams, Buttons +from opendbc.can.packer import CANPacker +from selfdrive.car import apply_std_steer_torque_limits + +class CarController(): + def __init__(self, dbc_name, CP, VM): + self.apply_steer_last = 0 + self.packer = CANPacker(dbc_name) + self.steer_rate_limited = False + + def update(self, enabled, CS, frame, actuators): + """ Controls thread """ + + can_sends = [] + + ### STEER ### + + if enabled: + # calculate steer and also set limits due to driver torque + new_steer = int(round(actuators.steer * SteerLimitParams.STEER_MAX)) + apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, + CS.out.steeringTorque, SteerLimitParams) + self.steer_rate_limited = new_steer != apply_steer + + if CS.out.standstill and frame % 50 == 0: + # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds + # Send Resume button at 2hz if we're engaged at standstill to support full stop and go! + # TODO: improve the resume trigger logic by looking at actual radar data + can_sends.append(mazdacan.create_button_cmd(self.packer, CS.CP.carFingerprint, Buttons.RESUME)) + else: + apply_steer = 0 + self.steer_rate_limited = False + if CS.out.cruiseState.enabled and frame % 10 == 0: + # Cancel Stock ACC if it's enabled while OP is disengaged + # Match stock message rate which is sent at 10hz + can_sends.append(mazdacan.create_button_cmd(self.packer, CS.CP.carFingerprint, Buttons.CANCEL)) + + + self.apply_steer_last = apply_steer + + can_sends.append(mazdacan.create_steering_control(self.packer, CS.CP.carFingerprint, + frame, apply_steer, CS.cam_lkas)) + return can_sends diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py new file mode 100644 index 0000000000..a089ea13ee --- /dev/null +++ b/selfdrive/car/mazda/carstate.py @@ -0,0 +1,185 @@ +from cereal import car +from selfdrive.config import Conversions as CV +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from selfdrive.car.interfaces import CarStateBase +from selfdrive.car.mazda.values import DBC, LKAS_LIMITS, CAR + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + + can_define = CANDefine(DBC[CP.carFingerprint]['pt']) + self.shifter_values = can_define.dv["GEAR"]['GEAR'] + + self.cruise_speed = 0 + self.acc_active_last = False + self.low_speed_lockout = True + self.low_speed_alert = False + self.lkas_allowed = False + + def update(self, cp, cp_cam): + + ret = car.CarState.new_message() + ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS"]['FL'] * CV.KPH_TO_MS + ret.wheelSpeeds.fr = cp.vl["WHEEL_SPEEDS"]['FR'] * CV.KPH_TO_MS + ret.wheelSpeeds.rl = cp.vl["WHEEL_SPEEDS"]['RL'] * CV.KPH_TO_MS + ret.wheelSpeeds.rr = cp.vl["WHEEL_SPEEDS"]['RR'] * CV.KPH_TO_MS + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + + # Match panda speed reading + speed_kph = cp.vl["ENGINE_DATA"]['SPEED'] + ret.standstill = speed_kph < .1 + + can_gear = int(cp.vl["GEAR"]['GEAR']) + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) + + ret.leftBlinker = cp.vl["BLINK_INFO"]['LEFT_BLINK'] == 1 + ret.rightBlinker = cp.vl["BLINK_INFO"]['RIGHT_BLINK'] == 1 + + ret.steeringAngle = cp.vl["STEER"]['STEER_ANGLE'] + ret.steeringTorque = cp.vl["STEER_TORQUE"]['STEER_TORQUE_SENSOR'] + ret.steeringPressed = abs(ret.steeringTorque) > LKAS_LIMITS.STEER_THRESHOLD + + ret.steeringTorqueEps = cp.vl["STEER_TORQUE"]['STEER_TORQUE_MOTOR'] + ret.steeringRate = cp.vl["STEER_RATE"]['STEER_ANGLE_RATE'] + + ret.brakePressed = cp.vl["PEDALS"]['BRAKE_ON'] == 1 + ret.brake = cp.vl["BRAKE"]['BRAKE_PRESSURE'] + ret.brakeLights = ret.brakePressed + + ret.seatbeltUnlatched = cp.vl["SEATBELT"]['DRIVER_SEATBELT'] == 0 + ret.doorOpen = any([cp.vl["DOORS"]['FL'], cp.vl["DOORS"]['FR'], + cp.vl["DOORS"]['BL'], cp.vl["DOORS"]['BR']]) + + ret.gas = cp.vl["ENGINE_DATA"]['PEDAL_GAS'] + ret.gasPressed = ret.gas > 0 + + + # LKAS is enabled at 52kph going up and disabled at 45kph going down + if speed_kph > LKAS_LIMITS.ENABLE_SPEED: + self.lkas_allowed = True + elif speed_kph < LKAS_LIMITS.DISABLE_SPEED: + self.lkas_allowed = False + + # if any of the cruize buttons is pressed force state update + if any([cp.vl["CRZ_BTNS"]['RES'], + cp.vl["CRZ_BTNS"]['SET_P'], + cp.vl["CRZ_BTNS"]['SET_M']]): + self.cruise_speed = ret.vEgoRaw + + ret.cruiseState.available = True + ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]['CRZ_ACTIVE'] == 1 + ret.cruiseState.speed = self.cruise_speed + + if ret.cruiseState.enabled: + if not self.lkas_allowed: + if not self.acc_active_last: + self.low_speed_lockout = True + else: + self.low_speed_alert = True + else: + self.low_speed_lockout = False + self.low_speed_alert = False + + # On if no driver torque the last 5 seconds + ret.steerWarning = cp.vl["STEER_RATE"]['HANDS_OFF_5_SECONDS'] == 1 + + self.acc_active_last = ret.cruiseState.enabled + + self.cam_lkas = cp_cam.vl["CAM_LKAS"] + ret.steerError = cp_cam.vl["CAM_LKAS"]['ERR_BIT_1'] == 1 + + return ret + + @staticmethod + def get_can_parser(CP): + # this function generates lists for signal, messages and initial values + signals = [ + # sig_name, sig_address, default + ("LEFT_BLINK", "BLINK_INFO", 0), + ("RIGHT_BLINK", "BLINK_INFO", 0), + ("STEER_ANGLE", "STEER", 0), + ("STEER_ANGLE_RATE", "STEER_RATE", 0), + ("STEER_TORQUE_SENSOR", "STEER_TORQUE", 0), + ("STEER_TORQUE_MOTOR", "STEER_TORQUE", 0), + ("FL", "WHEEL_SPEEDS", 0), + ("FR", "WHEEL_SPEEDS", 0), + ("RL", "WHEEL_SPEEDS", 0), + ("RR", "WHEEL_SPEEDS", 0), + ] + + checks = [ + # sig_address, frequency + ("BLINK_INFO", 10), + ("STEER", 67), + ("STEER_RATE", 83), + ("STEER_TORQUE", 83), + ("WHEEL_SPEEDS", 100), + ] + + if CP.carFingerprint == CAR.CX5: + signals += [ + ("LKAS_BLOCK", "STEER_RATE", 0), + ("LKAS_TRACK_STATE", "STEER_RATE", 0), + ("HANDS_OFF_5_SECONDS", "STEER_RATE", 0), + ("CRZ_ACTIVE", "CRZ_CTRL", 0), + ("STANDSTILL","PEDALS", 0), + ("BRAKE_ON","PEDALS", 0), + ("BRAKE_PRESSURE","BRAKE", 0), + ("GEAR","GEAR", 0), + ("DRIVER_SEATBELT", "SEATBELT", 0), + ("FL", "DOORS", 0), + ("FR", "DOORS", 0), + ("BL", "DOORS", 0), + ("BR", "DOORS", 0), + ("PEDAL_GAS", "ENGINE_DATA", 0), + ("SPEED", "ENGINE_DATA", 0), + ("RES", "CRZ_BTNS", 0), + ("SET_P", "CRZ_BTNS", 0), + ("SET_M", "CRZ_BTNS", 0), + ("CTR", "CRZ_BTNS", 0), + ] + + checks += [ + ("ENGINE_DATA", 100), + ("CRZ_CTRL", 50), + ("CRZ_BTNS", 10), + ("PEDALS", 50), + ("BRAKE", 50), + ("SEATBELT", 10), + ("DOORS", 10), + ("GEAR", 20), + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) + + + @staticmethod + def get_cam_can_parser(CP): + signals = [ ] + checks = [ ] + + if CP.carFingerprint == CAR.CX5: + signals += [ + # sig_name, sig_address, default + ("LKAS_REQUEST", "CAM_LKAS", 0), + ("CTR", "CAM_LKAS", 0), + ("ERR_BIT_1", "CAM_LKAS", 0), + ("LINE_NOT_VISIBLE", "CAM_LKAS", 0), + ("LDW", "CAM_LKAS", 0), + ("BIT_1", "CAM_LKAS", 1), + ("ERR_BIT_2", "CAM_LKAS", 0), + ("STEERING_ANGLE", "CAM_LKAS", 0), + ("ANGLE_ENABLED", "CAM_LKAS", 0), + ("CHKSUM", "CAM_LKAS", 0), + ] + + checks += [ + # sig_address, frequency + ("CAM_LKAS", 16), + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) + diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py new file mode 100755 index 0000000000..1e6b05ba02 --- /dev/null +++ b/selfdrive/car/mazda/interface.py @@ -0,0 +1,94 @@ +#!/usr/bin/env python3 +from cereal import car +from selfdrive.config import Conversions as CV +from selfdrive.car.mazda.values import CAR, LKAS_LIMITS, FINGERPRINTS, ECU_FINGERPRINT, Ecu +from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, is_ecu_disconnected +from selfdrive.car.interfaces import CarInterfaceBase + +ButtonType = car.CarState.ButtonEvent.Type +EventName = car.CarEvent.EventName + +class CarInterface(CarInterfaceBase): + + @staticmethod + def compute_gb(accel, speed): + return float(accel) / 4.0 + + @staticmethod + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) + + ret.carName = "mazda" + ret.safetyModel = car.CarParams.SafetyModel.mazda + + ret.dashcamOnly = True + + ret.radarOffCan = True + + # Mazda port is a community feature for now + ret.communityFeature = True + + ret.steerActuatorDelay = 0.1 + ret.steerRateCost = 1.0 + ret.steerLimitTimer = 0.8 + tire_stiffness_factor = 0.70 # not optimized yet + + if candidate in [CAR.CX5]: + ret.mass = 3655 * CV.LB_TO_KG + STD_CARGO_KG + ret.wheelbase = 2.7 + ret.steerRatio = 15.5 + + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.2]] + + ret.lateralTuning.pid.kf = 0.00006 + + # No steer below disable speed + ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS + + + ret.centerToFront = ret.wheelbase * 0.41 + + # TODO: get actual value, for now starting with reasonable value for + # civic and scaling by mass and wheelbase + ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) + + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by + # mass and CG position, so all cars will have approximately similar dyn behaviors + ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, + tire_stiffness_factor=tire_stiffness_factor) + + ret.enableCamera = is_ecu_disconnected(fingerprint[0], FINGERPRINTS, ECU_FINGERPRINT, candidate, Ecu.fwdCamera) or has_relay + + return ret + + # returns a car.CarState + def update(self, c, can_strings): + + self.cp.update_strings(can_strings) + self.cp_cam.update_strings(can_strings) + + ret = self.CS.update(self.cp, self.cp_cam) + ret.canValid = self.cp.can_valid and self.cp_cam.can_valid + + # TODO: button presses + ret.buttonEvents = [] + + # events + events = self.create_common_events(ret) + + if self.CS.low_speed_lockout: + events.add(EventName.speedTooLow) + + if self.CS.low_speed_alert: + events.add(EventName.belowSteerSpeed) + + ret.events = events.to_msg() + + self.CS.out = ret.as_reader() + return self.CS.out + + def apply(self, c): + can_sends = self.CC.update(c.enabled, self.CS, self.frame, c.actuators) + self.frame += 1 + return can_sends diff --git a/selfdrive/car/mazda/mazdacan.py b/selfdrive/car/mazda/mazdacan.py new file mode 100644 index 0000000000..3fae424fa8 --- /dev/null +++ b/selfdrive/car/mazda/mazdacan.py @@ -0,0 +1,104 @@ +from selfdrive.car.mazda.values import CAR, Buttons + +def create_steering_control(packer, car_fingerprint, frame, apply_steer, lkas): + + tmp = apply_steer + 2048 + + lo = tmp & 0xFF + hi = tmp >> 8 + + b1 = int(lkas["BIT_1"]) + ldw = int(lkas["LDW"]) + er1= int(lkas["ERR_BIT_1"]) + lnv = 0 + er2= int(lkas["ERR_BIT_2"]) + + steering_angle = int(lkas["STEERING_ANGLE"]) + b2 = int(lkas["ANGLE_ENABLED"]) + + tmp = steering_angle + 2048 + ahi = tmp >> 10 + amd = (tmp & 0x3FF) >> 2 + amd = (amd >> 4) | (( amd & 0xF) << 4) + alo = (tmp & 0x3) << 2 + + ctr = frame % 16 + # bytes: [ 1 ] [ 2 ] [ 3 ] [ 4 ] + csum = 249 - ctr - hi - lo - (lnv << 3) - er1 - (ldw << 7) - ( er2 << 4) - (b1 << 5) + + #bytes [ 5 ] [ 6 ] [ 7 ] + csum = csum - ahi - amd - alo - b2 + + if ahi == 1: + csum = csum + 15 + + if csum < 0: + if csum < -256: + csum = csum + 512 + else: + csum = csum + 256 + + csum = csum % 256 + + if car_fingerprint == CAR.CX5: + values = { + "LKAS_REQUEST" : apply_steer, + "CTR" : ctr, + "ERR_BIT_1" : er1, + "LINE_NOT_VISIBLE" : lnv, + "LDW" : ldw, + "BIT_1" : b1, + "ERR_BIT_2" : er2, + "STEERING_ANGLE" : steering_angle, + "ANGLE_ENABLED" : b2, + "CHKSUM" : csum + } + + return packer.make_can_msg("CAM_LKAS", 0, values) + + +def create_button_cmd(packer, car_fingerprint, button): + + if button == Buttons.CANCEL: + can = 1 + res = 0 + elif button == Buttons.RESUME: + can = 0 + res = 1 + else: + can = 0 + res = 0 + + if car_fingerprint == CAR.CX5: + values = { + "CAN_OFF" : can, + "CAN_OFF_INV" : (can + 1) % 2, + + "SET_P" : 0, + "SET_P_INV" : 1, + + "RES" : res, + "RES_INV" : (res + 1) % 2, + + "SET_M" : 0, + "SET_M_INV" : 1, + + "DISTANCE_LESS" : 0, + "DISTANCE_LESS_INV" : 1, + + "DISTANCE_MORE" : 0, + "DISTANCE_MORE_INV" : 1, + + "MODE_X" : 0, + "MODE_X_INV" : 1, + + "MODE_Y" : 0, + "MODE_Y_INV" : 1, + + "BIT1" : 1, + "BIT2" : 1, + "BIT3" : 1, + "CTR" : 0 + } + + return packer.make_can_msg("CRZ_BTNS", 0, values) diff --git a/selfdrive/car/mazda/radar_interface.py b/selfdrive/car/mazda/radar_interface.py new file mode 100755 index 0000000000..55f92f6326 --- /dev/null +++ b/selfdrive/car/mazda/radar_interface.py @@ -0,0 +1,6 @@ +#!/usr/bin/env python3 +from selfdrive.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass + diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py new file mode 100644 index 0000000000..2cab11d1f9 --- /dev/null +++ b/selfdrive/car/mazda/values.py @@ -0,0 +1,64 @@ +from selfdrive.car import dbc_dict +from cereal import car +Ecu = car.CarParams.Ecu + + +# Steer torque limits + +class SteerLimitParams: + STEER_MAX = 600 # max_steer 2048 + STEER_STEP = 1 # how often we update the steer cmd + STEER_DELTA_UP = 10 # torque increase per refresh + STEER_DELTA_DOWN = 20 # torque decrease per refresh + STEER_DRIVER_ALLOWANCE = 15 # allowed driver torque before start limiting + STEER_DRIVER_MULTIPLIER = 1 # weight driver torque + STEER_DRIVER_FACTOR = 1 # from dbc + +class CAR: + CX5 = "Mazda CX-5 2017" + +class LKAS_LIMITS: + STEER_THRESHOLD = 15 + DISABLE_SPEED = 45 #kph + ENABLE_SPEED = 52 #kph + +class Buttons: + NONE = 0 + SET_PLUS = 1 + SET_MINUS = 2 + RESUME = 3 + CANCEL = 4 + +FINGERPRINTS = { + CAR.CX5: [ + # CX-5 2017 GT + { + 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 608: 8, 628: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8 + }, + + # CX-5 2019 GTR + { + 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 254: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 608: 8, 628: 8, 736: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1171: 8, 1173: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1244: 8, 1260: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8, 1776: 8, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 + }, + + # Mazda 6 2017 GT + { + 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 628: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1182: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1456: 8, 1479: 8 + }, + + # CX-9 2017 Australia + { + 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 138: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 522: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 583: 8, 605: 8, 606: 8, 628: 8, 832: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1177: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1247: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8 + }, + ], + +} + +ECU_FINGERPRINT = { + Ecu.fwdCamera: [579], # steer torque cmd +} + + +DBC = { + CAR.CX5: dbc_dict('mazda_2017', None), +} diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index c4315bfc52..f9deac6713 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -22,13 +22,14 @@ segments = [ #("CHRYSLER", "b6e1317e1bfbefa6|2020-03-04--13-11-40"), # CHRYSLER.JEEP_CHEROKEE ("SUBARU", "7873afaf022d36e2|2019-07-03--18-46-44--0"), # SUBARU.IMPREZA ("VOLKSWAGEN", "76b83eb0245de90e|2020-03-05--19-16-05--3"), # VW.GOLF + ("NISSAN", "fbbfa6af821552b9|2020-03-03--08-09-43--0"), # NISSAN.XTRAIL # Enable when port is tested and dascamOnly is no longer set - ("NISSAN", "fbbfa6af821552b9|2020-03-03--08-09-43--0"), # NISSAN.XTRAIL + #("MAZDA", "32a319f057902bb3|2020-04-27--15-18-58--2"), # MAZDA.CX5 ] # ford doesn't need to be tested until a full port is done -excluded_interfaces = ["mock", "ford"] +excluded_interfaces = ["mock", "ford", "mazda"] BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 685cb485f4..06d333094a 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -20,6 +20,7 @@ from selfdrive.car.gm.values import CAR as GM from selfdrive.car.honda.values import CAR as HONDA from selfdrive.car.hyundai.values import CAR as HYUNDAI from selfdrive.car.nissan.values import CAR as NISSAN +from selfdrive.car.mazda.values import CAR as MAZDA from selfdrive.car.subaru.values import CAR as SUBARU from selfdrive.car.toyota.values import CAR as TOYOTA from selfdrive.car.volkswagen.values import CAR as VOLKSWAGEN @@ -362,6 +363,10 @@ routes = { 'carFingerprint': NISSAN.LEAF, 'enableCamera': True, }, + "32a319f057902bb3|2020-04-27--15-18-58": { + 'carFingerprint': MAZDA.CX5, + 'enableCamera': True, + }, } passive_routes: List[str] = [ @@ -371,6 +376,8 @@ forced_dashcam_routes = [ # Ford fusion "f1b4c567731f4a1b|2018-04-18--11-29-37", "f1b4c567731f4a1b|2018-04-30--10-15-35", + # Mazda + "32a319f057902bb3|2020-04-27--15-18-58", ] # TODO: add routes for these cars From f10c2eff7d8bbbaab62f1fc3712309a29558be07 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 29 May 2020 00:44:27 -0700 Subject: [PATCH 129/656] minor LGTM fixes --- common/spinner.py | 2 +- common/text_window.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/common/spinner.py b/common/spinner.py index 370d54c815..da8084037e 100644 --- a/common/spinner.py +++ b/common/spinner.py @@ -40,7 +40,7 @@ class Spinner(): self.close() -class FakeSpinner(Spinner): +class FakeSpinner(): def __init__(self): pass diff --git a/common/text_window.py b/common/text_window.py index 50fdcb6440..0d94bc7470 100755 --- a/common/text_window.py +++ b/common/text_window.py @@ -43,7 +43,7 @@ class TextWindow(): self.close() -class FakeTextWindow(TextWindow): +class FakeTextWindow(): def __init__(self, s): pass From 6230f366c5f0b319755e537f4cc621f0805b270d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 29 May 2020 11:10:48 -0700 Subject: [PATCH 130/656] Revert "minor LGTM fixes" This reverts commit f10c2eff7d8bbbaab62f1fc3712309a29558be07. --- common/spinner.py | 2 +- common/text_window.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/common/spinner.py b/common/spinner.py index da8084037e..370d54c815 100644 --- a/common/spinner.py +++ b/common/spinner.py @@ -40,7 +40,7 @@ class Spinner(): self.close() -class FakeSpinner(): +class FakeSpinner(Spinner): def __init__(self): pass diff --git a/common/text_window.py b/common/text_window.py index 0d94bc7470..50fdcb6440 100755 --- a/common/text_window.py +++ b/common/text_window.py @@ -43,7 +43,7 @@ class TextWindow(): self.close() -class FakeTextWindow(): +class FakeTextWindow(TextWindow): def __init__(self, s): pass From 916448af25d61a9acf1d35356fafccdfc800c440 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 29 May 2020 12:00:29 -0700 Subject: [PATCH 131/656] break canError into two separate events --- cereal | 2 +- selfdrive/controls/controlsd.py | 10 +++++++--- selfdrive/controls/lib/events.py | 13 ++++++++----- 3 files changed, 16 insertions(+), 9 deletions(-) diff --git a/cereal b/cereal index c8be73d10c..0adfc7e77e 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit c8be73d10c957bff769998588595107d62e9e738 +Subproject commit 0adfc7e77efbf1ebc21bf2629a85d165b319b23e diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index c8ea55088c..e3e502c1a8 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -117,6 +117,7 @@ class Controls: self.v_cruise_kph_last = 0 self.mismatch_counter = 0 self.can_error_counter = 0 + self.consecutive_can_error_count = 0 self.last_blinker_frame = 0 self.saturated_count = 0 self.events_prev = [] @@ -188,8 +189,13 @@ class Controls: LaneChangeState.laneChangeFinishing]: self.events.add(EventName.laneChange) - if self.can_rcv_error: + if self.can_rcv_error or (not CS.canValid and self.sm.frame > 5 / DT_CTRL): self.events.add(EventName.canError) + self.consecutive_can_error_count += 1 + else: + self.consecutive_can_error_count = 0 + if self.consecutive_can_error_count > 2 / DT_CTRL: + self.events.add(EventName.canErrorPersistent) if self.mismatch_counter >= 200: self.events.add(EventName.controlsMismatch) if not self.sm.alive['plan'] and self.sm.alive['pathPlan']: @@ -210,8 +216,6 @@ class Controls: self.events.add(EventName.radarFault) if self.sm['plan'].radarCanError: self.events.add(EventName.radarCanError) - if not CS.canValid and self.sm.frame > 5 / DT_CTRL: - self.events.add(EventName.canError) if log.HealthData.FaultType.relayMalfunction in self.sm['health'].faults: self.events.add(EventName.relayMalfunction) if self.sm['plan'].fcw: diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 5b2fdf6ad1..bf2dcaf049 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -305,6 +305,14 @@ EVENTS = { Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimePrompt, 1., 2., 3.), }, + EventName.canErrorPersistent: { + ET.PERMANENT: Alert( + "CAN Error: Check Connections", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + }, + # ********** events only containing alerts that display while engaged ********** EventName.vehicleModelInvalid: { @@ -603,11 +611,6 @@ EVENTS = { EventName.canError: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("CAN Error: Check Connections"), ET.NO_ENTRY: NoEntryAlert("CAN Error: Check Connections"), - ET.PERMANENT: Alert( - "CAN Error: Check Connections", - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), }, EventName.steerUnavailable: { From ad099c43c729a0371dc94faa1fc9ec898110ea34 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 29 May 2020 12:08:45 -0700 Subject: [PATCH 132/656] update release notes --- RELEASES.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index b8b821e6a4..1fa837bacd 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,7 +1,9 @@ -Version 0.7.6 (2020-xx-xx) +Version 0.7.6 (2020-06-05) ======================== * White panda is deprecated, upgrade to comma two or black panda * 2019 Nissan X-Trail and 2018 Nissan Leaf support thanks to avolmensky! +* Huge CPU savings in modeld by using thneed! +* Lots of code cleanup and refactors Version 0.7.5 (2020-05-13) ======================== From 7a37594320b77ed514b11125e54b6f515150d6c1 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 29 May 2020 12:08:53 -0700 Subject: [PATCH 133/656] bump submodules --- laika_repo | 2 +- opendbc | 2 +- panda | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/laika_repo b/laika_repo index d172b27f4f..90b4c98502 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit d172b27f4f346e642802a4c7cbf14405a4161d35 +Subproject commit 90b4c98502ade83df62fb215ee44375eee46b3d5 diff --git a/opendbc b/opendbc index 2ade6eeba8..0430bfa5c2 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 2ade6eeba82d2b3be0ab5f3ee0061de228ea6d65 +Subproject commit 0430bfa5c2b08f9cc6ab32470fe8ac9465e7a876 diff --git a/panda b/panda index a618e64d1a..b8267341a1 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit a618e64d1a1778f5b3ac95dcd8a41b64d1a18a3f +Subproject commit b8267341a15feed3308870b91255a5d4de842df9 From 2d898bc0edb2cef132e90c695e77911c2720c026 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 29 May 2020 12:41:20 -0700 Subject: [PATCH 134/656] update refs --- selfdrive/test/process_replay/ref_commit | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 9f87784143..01551e683d 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -2ecc7d9f6f85818765da23cfac614d186111abb7 \ No newline at end of file +7a37594320b77ed514b11125e54b6f515150d6c1 \ No newline at end of file From f3bd6ad48a12b590de3695fe6e080af8c33d7538 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 29 May 2020 14:02:30 -0700 Subject: [PATCH 135/656] add mazda to release notes --- RELEASES.md | 1 + 1 file changed, 1 insertion(+) diff --git a/RELEASES.md b/RELEASES.md index 1fa837bacd..2c497a296f 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -2,6 +2,7 @@ Version 0.7.6 (2020-06-05) ======================== * White panda is deprecated, upgrade to comma two or black panda * 2019 Nissan X-Trail and 2018 Nissan Leaf support thanks to avolmensky! +* 2017 Mazda CX-5 support in dashcam mode thanks to Jafaral! * Huge CPU savings in modeld by using thneed! * Lots of code cleanup and refactors From e958b371a29c3f3338379da4e491fe00446c7b17 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 29 May 2020 15:43:53 -0700 Subject: [PATCH 136/656] Fix Nissan model years in readme and release notes --- README.md | 4 ++-- RELEASES.md | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 8da9b06c30..b1bd090e94 100644 --- a/README.md +++ b/README.md @@ -153,8 +153,8 @@ Community Maintained Cars and Features | Kia | Optima 20192 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Sorento 20182 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Stinger 20182 | SCC + LKAS | Stock | 0mph | 0mph | -| Nissan | Leaf 20192 | Propilot | Stock | 0mph | 0mph | -| Nissan | X-Trail 20182 | Propilot | Stock | 0mph | 0mph | +| Nissan | Leaf 20182 | Propilot | Stock | 0mph | 0mph | +| Nissan | X-Trail 20172 | Propilot | Stock | 0mph | 0mph | | Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | | Subaru | Impreza 2018-20 | EyeSight | Stock | 0mph | 0mph | | Volkswagen| Golf 2015-19 | Driver Assistance | Stock | 0mph | 0mph | diff --git a/RELEASES.md b/RELEASES.md index 2c497a296f..6ff8d9e447 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,7 +1,7 @@ Version 0.7.6 (2020-06-05) ======================== * White panda is deprecated, upgrade to comma two or black panda -* 2019 Nissan X-Trail and 2018 Nissan Leaf support thanks to avolmensky! +* 2017 Nissan X-Trail and 2018 Nissan Leaf support thanks to avolmensky! * 2017 Mazda CX-5 support in dashcam mode thanks to Jafaral! * Huge CPU savings in modeld by using thneed! * Lots of code cleanup and refactors From 3d7cd9ec78c07d25489078c890bee4249475ef68 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Fri, 29 May 2020 17:26:05 -0700 Subject: [PATCH 137/656] Add Camry Hybrid 2018 Engine FW --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 75ea689ca8..d73a96572c 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -327,6 +327,7 @@ FW_VERSIONS = { b'\x028966306R5000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', b'\x028966306R6000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306N8100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152633712\x00\x00\x00\x00\x00\x00', From 7b54dad0b8635d745d976073cd6551beee7177e5 Mon Sep 17 00:00:00 2001 From: martinl Date: Sat, 30 May 2020 09:32:51 +0300 Subject: [PATCH 138/656] Add Subaru blindspot monitoring signals (#1374) * Add blindspot signals to carstate * Change blindspot signals to boolean --- selfdrive/car/subaru/carstate.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index ebfbaaa39a..41bc129ebb 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -38,6 +38,9 @@ class CarState(CarStateBase): self.right_blinker_cnt = 50 if cp.vl["Dashlights"]['RIGHT_BLINKER'] else max(self.right_blinker_cnt - 1, 0) ret.rightBlinker = self.right_blinker_cnt > 0 + ret.leftBlindspot = cp.vl["BSD_RCTA"]['L_ADJACENT'] == 1 + ret.rightBlindspot = cp.vl["BSD_RCTA"]['R_ADJACENT'] == 1 + can_gear = int(cp.vl["Transmission"]['Gear']) ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) @@ -87,6 +90,8 @@ class CarState(CarStateBase): ("DOOR_OPEN_RL", "BodyInfo", 1), ("Units", "Dash_State", 1), ("Gear", "Transmission", 0), + ("L_ADJACENT", "BSD_RCTA", 0), + ("R_ADJACENT", "BSD_RCTA", 0), ] checks = [ From cc2137bdedb8c65d6d9d32a1234250225dc2d3dc Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Sat, 30 May 2020 10:04:56 -0700 Subject: [PATCH 139/656] pyextra isn't a submodule anymore (#1601) --- .github/workflows/test.yaml | 2 +- release/build_devel.sh | 3 +-- release/files_common | 2 ++ 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 57821c9c6f..eb0499c32d 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -39,7 +39,7 @@ jobs: cp Pipfile Pipfile.lock flake8_openpilot.sh pylint_openpilot.sh .pylintrc \ cppcheck_openpilot.sh .coveragerc-app .pre-commit-config.yaml $TEST_DIR cd $TEST_DIR - mkdir pyextra laika laika_repo tools release + mkdir laika laika_repo tools release - name: Build Docker image run: cd $TEST_DIR && eval "$BUILD" - name: Build openpilot diff --git a/release/build_devel.sh b/release/build_devel.sh index 26f92445a3..c3028d5520 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -65,7 +65,6 @@ git clean -xdf add_subtree "cereal" "cereal" master add_subtree "panda" "panda" master add_subtree "opendbc" "opendbc" master -add_subtree "openpilot-pyextra" "pyextra" master # leave .git alone echo "[-] erasing old openpilot T=$SECONDS" @@ -75,7 +74,7 @@ rm -rf $TARGET_DIR/* $TARGET_DIR/.gitmodules find . -maxdepth 1 -type f -delete # dont delete our subtrees -git checkout -- cereal panda opendbc pyextra +git checkout -- cereal panda opendbc # reset tree and get version cd $SOURCE_DIR diff --git a/release/files_common b/release/files_common index 03509a3023..cb760dcc8f 100644 --- a/release/files_common +++ b/release/files_common @@ -442,4 +442,6 @@ installer/updater/Makefile scripts/update_now.sh scripts/stop_updater.sh +pyextra/** + rednose/** From 3ddbb7fe5baac45b561f9c0efbac05e2f552637c Mon Sep 17 00:00:00 2001 From: Yahya Lmallas <1588632+Maroc-OS@users.noreply.github.com> Date: Sat, 30 May 2020 18:06:29 +0100 Subject: [PATCH 140/656] Call to gmtime is potentially dangerous (#1598) * Call to gmtime is potentially dangerous * Revert "Call to gmtime is potentially dangerous" This reverts commit cc531e4e1969f7a615230d8462f0be3258ba3378. * Call to gmtime is potentially dangerous * oops * not a pointer * Little identation fix --- selfdrive/boardd/boardd.cc | 26 ++++++++++++++------------ 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index b1f17a4bc1..b1674818cc 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -230,17 +230,18 @@ bool usb_connect() { time_t rawtime; time(&rawtime); - struct tm * sys_time = gmtime(&rawtime); + struct tm sys_time; + gmtime_r(&rawtime, &sys_time); // Get time from RTC timestamp_t rtc_time; libusb_control_transfer(dev_handle, 0xc0, 0xa0, 0, 0, (unsigned char*)&rtc_time, sizeof(rtc_time), TIMEOUT); - //printf("System: %d-%d-%d\t%d:%d:%d\n", 1900 + sys_time->tm_year, 1 + sys_time->tm_mon, sys_time->tm_mday, sys_time->tm_hour, sys_time->tm_min, sys_time->tm_sec); + //printf("System: %d-%d-%d\t%d:%d:%d\n", 1900 + sys_time.tm_year, 1 + sys_time.tm_mon, sys_time.tm_mday, sys_time.tm_hour, sys_time.tm_min, sys_time.tm_sec); //printf("RTC: %d-%d-%d\t%d:%d:%d\n", rtc_time.year, rtc_time.month, rtc_time.day, rtc_time.hour, rtc_time.minute, rtc_time.second); // Update system time from RTC if it looks off, and RTC time is good - if (1900 + sys_time->tm_year < 2019 && rtc_time.year >= 2019){ + if (1900 + sys_time.tm_year < 2019 && rtc_time.year >= 2019){ LOGE("System time wrong, setting from RTC"); struct tm new_time = { 0 }; @@ -472,18 +473,19 @@ void can_health(PubMaster &pm) { time_t rawtime; time(&rawtime); - struct tm * sys_time = gmtime(&rawtime); + struct tm sys_time; + gmtime_r(&rawtime, &sys_time); // Write time to RTC if it looks reasonable - if (1900 + sys_time->tm_year >= 2019){ + if (1900 + sys_time.tm_year >= 2019){ pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0x40, 0xa1, (uint16_t)(1900 + sys_time->tm_year), 0, NULL, 0, TIMEOUT); - libusb_control_transfer(dev_handle, 0x40, 0xa2, (uint16_t)(1 + sys_time->tm_mon), 0, NULL, 0, TIMEOUT); - libusb_control_transfer(dev_handle, 0x40, 0xa3, (uint16_t)sys_time->tm_mday, 0, NULL, 0, TIMEOUT); - // libusb_control_transfer(dev_handle, 0x40, 0xa4, (uint16_t)(1 + sys_time->tm_wday), 0, NULL, 0, TIMEOUT); - libusb_control_transfer(dev_handle, 0x40, 0xa5, (uint16_t)sys_time->tm_hour, 0, NULL, 0, TIMEOUT); - libusb_control_transfer(dev_handle, 0x40, 0xa6, (uint16_t)sys_time->tm_min, 0, NULL, 0, TIMEOUT); - libusb_control_transfer(dev_handle, 0x40, 0xa7, (uint16_t)sys_time->tm_sec, 0, NULL, 0, TIMEOUT); + libusb_control_transfer(dev_handle, 0x40, 0xa1, (uint16_t)(1900 + sys_time.tm_year), 0, NULL, 0, TIMEOUT); + libusb_control_transfer(dev_handle, 0x40, 0xa2, (uint16_t)(1 + sys_time.tm_mon), 0, NULL, 0, TIMEOUT); + libusb_control_transfer(dev_handle, 0x40, 0xa3, (uint16_t)sys_time.tm_mday, 0, NULL, 0, TIMEOUT); + // libusb_control_transfer(dev_handle, 0x40, 0xa4, (uint16_t)(1 + sys_time.tm_wday), 0, NULL, 0, TIMEOUT); + libusb_control_transfer(dev_handle, 0x40, 0xa5, (uint16_t)sys_time.tm_hour, 0, NULL, 0, TIMEOUT); + libusb_control_transfer(dev_handle, 0x40, 0xa6, (uint16_t)sys_time.tm_min, 0, NULL, 0, TIMEOUT); + libusb_control_transfer(dev_handle, 0x40, 0xa7, (uint16_t)sys_time.tm_sec, 0, NULL, 0, TIMEOUT); pthread_mutex_unlock(&usb_lock); } } From 94b2d4d522108c8897b89a1c0727b394ad3c5892 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Sat, 30 May 2020 12:07:23 -0500 Subject: [PATCH 141/656] CAR.SIENNA Engine, ESP, and DSU f/w was missing (#1597) DongleID 307249a92f279059... verified working via TeamViewer, as FPv2 switched to `fingerprintsource = fw` --- selfdrive/car/toyota/values.py | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index d73a96572c..ec3235ec04 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -799,14 +799,25 @@ FW_VERSIONS = { b'\x01896630842000\x00\x00\x00\x00', b'\x01896630851100\x00\x00\x00\x00', b'\x01896630860000\x00\x00\x00\x00', + b'\x01896630852100\x00\x00\x00\x00', b'\x01896630859000\x00\x00\x00\x00', ], - (Ecu.eps, 0x7a1, None): [b'8965B45070\x00\x00\x00\x00\x00\x00'], + (Ecu.eps, 0x7a1, None): [ + b'8965B45070\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x7b0, None): [ + b'F152608130\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510801100\x00\x00\x00\x00', + ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F4702100\x00\x00\x00\x00', b'8821F4702300\x00\x00\x00\x00', ], - (Ecu.fwdCamera, 0x750, 0x6d): [b'8646F0801100\x00\x00\x00\x00'], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0801100\x00\x00\x00\x00', + ], }, CAR.LEXUS_ESH_TSS2: { (Ecu.engine, 0x700, None): [ From af36aa28abeb55a4445cbc1ff13ac55993d989d9 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 31 May 2020 01:08:44 +0800 Subject: [PATCH 142/656] driving.cc: Pass ModelDataRaw by reference (#1600) * pass ModelDataRaw by reference * pass NVGpaint by refer --- selfdrive/modeld/models/driving.cc | 4 ++-- selfdrive/modeld/models/driving.h | 4 ++-- selfdrive/ui/paint.cc | 2 +- selfdrive/ui/ui.hpp | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 817fe85662..3b14199867 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -247,7 +247,7 @@ void fill_longi(cereal::ModelData::LongitudinalData::Builder longi, const float } void model_publish(PubMaster &pm, uint32_t frame_id, - const ModelDataRaw net_outputs, uint64_t timestamp_eof) { + const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { // make msg capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); @@ -296,7 +296,7 @@ void model_publish(PubMaster &pm, uint32_t frame_id, } void posenet_publish(PubMaster &pm, uint32_t frame_id, - const ModelDataRaw net_outputs, uint64_t timestamp_eof) { + const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); event.setLogMonoTime(nanos_since_boot()); diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index a852db4022..223a540b37 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -72,7 +72,7 @@ void model_free(ModelState* s); void poly_fit(float *in_pts, float *in_stds, float *out); void model_publish(PubMaster &pm, uint32_t frame_id, - const ModelDataRaw data, uint64_t timestamp_eof); + const ModelDataRaw &data, uint64_t timestamp_eof); void posenet_publish(PubMaster &pm, uint32_t frame_id, - const ModelDataRaw data, uint64_t timestamp_eof); + const ModelDataRaw &data, uint64_t timestamp_eof); #endif diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index b1d2133bf5..8e40314e3d 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -791,7 +791,7 @@ void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGcolor c } } -void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint paint, float r){ +void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint &paint, float r){ nvgBeginPath(vg); r > 0? nvgRoundedRect(vg, x, y, w, h, r) : nvgRect(vg, x, y, w, h); nvgFillPaint(vg, paint); diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 3cab8ee668..25215fe08b 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -292,7 +292,7 @@ void ui_draw(UIState *s); void ui_draw_sidebar(UIState *s); void ui_draw_image(NVGcontext *vg, float x, float y, float w, float h, int image, float alpha); void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGcolor color, float r = 0, int width = 0); -void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint paint, float r = 0); +void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint &paint, float r = 0); void ui_nvg_init(UIState *s); #endif From 9256530a1d41a4ad65616815f8e9ab047c63f61e Mon Sep 17 00:00:00 2001 From: Kishan Karunaratne Date: Sat, 30 May 2020 10:17:04 -0700 Subject: [PATCH 143/656] [GM] Show FCW from OP on dashboard UI / LED (#1596) --- selfdrive/car/gm/carcontroller.py | 13 ++++++++++++- selfdrive/car/gm/gmcan.py | 5 +++-- 2 files changed, 15 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index bda8ef22cd..f84ea3e322 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -60,6 +60,7 @@ class CarController(): self.apply_steer_last = 0 self.lka_icon_status_last = (False, False) self.steer_rate_limited = False + self.fcw_frames = 0 self.params = CarControllerParams() @@ -74,6 +75,10 @@ class CarController(): # Send CAN commands. can_sends = [] + # FCW: trigger FCWAlert for 100 frames (4 seconds) + if hud_alert == VisualAlert.fcw: + self.fcw_frames = 100 + ### STEER ### if (frame % P.STEER_STEP) == 0: @@ -122,7 +127,13 @@ class CarController(): # Send dashboard UI commands (ACC status), 25hz if (frame % 4) == 0: - can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, CanBus.POWERTRAIN, enabled, hud_v_cruise * CV.MS_TO_KPH, hud_show_car)) + # Send FCW if applicable + send_fcw = 0 + if self.fcw_frames > 0: + send_fcw = 0x3 + self.fcw_frames -= 1 + + can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, CanBus.POWERTRAIN, enabled, hud_v_cruise * CV.MS_TO_KPH, hud_show_car, send_fcw)) # Radar needs to know current speed and yaw rate (50hz), # and that ADAS is alive (10hz) diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py index 23b521f55b..ba13df9219 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/selfdrive/car/gm/gmcan.py @@ -60,7 +60,7 @@ def create_friction_brake_command(packer, bus, apply_brake, idx, near_stop, at_f return packer.make_can_msg("EBCMFrictionBrakeCmd", bus, values) -def create_acc_dashboard_command(packer, bus, acc_engaged, target_speed_kph, lead_car_in_sight): +def create_acc_dashboard_command(packer, bus, acc_engaged, target_speed_kph, lead_car_in_sight, fcw): # Not a bit shift, dash can round up based on low 4 bits. target_speed = int(target_speed_kph * 16) & 0xfff @@ -71,7 +71,8 @@ def create_acc_dashboard_command(packer, bus, acc_engaged, target_speed_kph, lea "ACCGapLevel" : 3 * acc_engaged, # 3 "far", 0 "inactive" "ACCCmdActive" : acc_engaged, "ACCAlwaysOne2" : 1, - "ACCLeadCar" : lead_car_in_sight + "ACCLeadCar" : lead_car_in_sight, + "FCWAlert": fcw } return packer.make_can_msg("ASCMActiveCruiseControlStatus", bus, values) From 4cec8bcc30ed93136a0378f55bed55c34d89644f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sat, 30 May 2020 10:31:40 -0700 Subject: [PATCH 144/656] Fix indentation in board.cc --- selfdrive/boardd/boardd.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index b1674818cc..ad6363440f 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -241,7 +241,7 @@ bool usb_connect() { //printf("RTC: %d-%d-%d\t%d:%d:%d\n", rtc_time.year, rtc_time.month, rtc_time.day, rtc_time.hour, rtc_time.minute, rtc_time.second); // Update system time from RTC if it looks off, and RTC time is good - if (1900 + sys_time.tm_year < 2019 && rtc_time.year >= 2019){ + if (1900 + sys_time.tm_year < 2019 && rtc_time.year >= 2019){ LOGE("System time wrong, setting from RTC"); struct tm new_time = { 0 }; @@ -599,7 +599,7 @@ void *can_send_thread(void *crap) { can_send(sm["sendcan"]); } } - + return NULL; } From d9202905449b8e2ea25ddb2ebb392eccb384471b Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sat, 30 May 2020 13:38:42 -0700 Subject: [PATCH 145/656] add RAV4H_TSS2 EPS firmware version --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index ec3235ec04..24305382b6 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -765,6 +765,7 @@ FW_VERSIONS = { b'8965B42171\x00\x00\x00\x00\x00\x00', b'8965B42181\x00\x00\x00\x00\x00\x00', b'\x028965B0R01200\x00\x00\x00\x008965B0R02200\x00\x00\x00\x00', + b'\x028965B0R01300\x00\x00\x00\x008965B0R02300\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301200\x00\x00\x00\x00', From 18afb979fe5ef00ebb9079991a0fcbfdf3734eb1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 30 May 2020 14:40:00 -0700 Subject: [PATCH 146/656] remove file that shouldn't have been committed --- .../process_replay/flycheck_compare_logs.py | 72 ------------------- 1 file changed, 72 deletions(-) delete mode 100644 selfdrive/test/process_replay/flycheck_compare_logs.py diff --git a/selfdrive/test/process_replay/flycheck_compare_logs.py b/selfdrive/test/process_replay/flycheck_compare_logs.py deleted file mode 100644 index addcfa9310..0000000000 --- a/selfdrive/test/process_replay/flycheck_compare_logs.py +++ /dev/null @@ -1,72 +0,0 @@ -#!/usr/bin/env python3 -import bz2 -import os -import sys -import numbers - -import dictdiffer -if "CI" in os.environ: - tqdm = lambda x: x -else: - from tqdm import tqdm # type: ignore - -from tools.lib.logreader import LogReader - -def save_log(dest, log_msgs): - dat = b"" - for msg in tqdm(log_msgs): - dat += msg.as_builder().to_bytes() - dat = bz2.compress(dat) - - with open(dest, "wb") as f: - f.write(dat) - -def remove_ignored_fields(msg, ignore): - msg = msg.as_builder() - for key in ignore: - attr = msg - keys = key.split(".") - if msg.which() not in key and len(keys) > 1: - continue - - for k in keys[:-1]: - try: - attr = getattr(msg, k) - except: - break - else: - v = getattr(attr, keys[-1]) - if isinstance(v, bool): - val = False - elif isinstance(v, numbers.Number): - val = 0 - else: - raise NotImplementedError - setattr(attr, keys[-1], val) - return msg.as_reader() - -def compare_logs(log1, log2, ignore_fields=[], ignore_msgs=[]): - filter_msgs = lambda m: m.which() not in ignore_msgs - log1, log2 = [list(filter(filter_msgs, log)) for log in (log1, log2)] - assert len(log1) == len(log2), "logs are not same length: " + str(len(log1)) + " VS " + str(len(log2)) - - diff = [] - for msg1, msg2 in tqdm(zip(log1, log2)): - if msg1.which() != msg2.which(): - print(msg1, msg2) - raise Exception("msgs not aligned between logs") - - msg1_bytes = remove_ignored_fields(msg1, ignore_fields).as_builder().to_bytes() - msg2_bytes = remove_ignored_fields(msg2, ignore_fields).as_builder().to_bytes() - - if msg1_bytes != msg2_bytes: - msg1_dict = msg1.to_dict(verbose=True) - msg2_dict = msg2.to_dict(verbose=True) - dd = dictdiffer.diff(msg1_dict, msg2_dict, ignore=ignore_fields, tolerance=0) - diff.extend(dd) - return diff - -if __name__ == "__main__": - log1 = list(LogReader(sys.argv[1])) - log2 = list(LogReader(sys.argv[2])) - print(compare_logs(log1, log2, sys.argv[3:])) From b5a2cec913f44438aa15b8b49e2cfee2b033c5e6 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sat, 30 May 2020 17:04:10 -0700 Subject: [PATCH 147/656] Improved tune for VW Golf Mk7. #1603 commit 012049274fd5573bdc5d2d0f198817646dfd5a1b Author: Willem Melching Date: Sat May 30 10:40:49 2020 -0700 update ref commit d50cc2d81fd73dcfccfe1a8e2726879941ec5327 Author: Jason Young Date: Sat May 30 10:32:25 2020 -0400 Discard no-longer-used import commit c092e6f5092535a3b4bb5cabb6f5ecf83ef754c7 Author: Jason Young Date: Sat May 30 10:21:57 2020 -0400 Improved tune from community --- selfdrive/car/volkswagen/interface.py | 35 ++++++++---------------- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 12 insertions(+), 25 deletions(-) diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 8e2797de9c..3632b7b0c9 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -1,5 +1,4 @@ from cereal import car -from selfdrive.config import Conversions as CV from selfdrive.car.volkswagen.values import CAR, BUTTON_STATES from common.params import put_nonblocking from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint @@ -33,35 +32,23 @@ class CarInterface(CarInterfaceBase): ret.safetyModel = car.CarParams.SafetyModel.volkswagen # Additional common MQB parameters that may be overridden per-vehicle - ret.steerRateCost = 0.5 - ret.steerActuatorDelay = 0.05 # Hopefully all MQB racks are similar here + ret.steerRateCost = 1.0 + ret.steerActuatorDelay = 0.05 # Hopefully all MQB racks are similar here ret.steerLimitTimer = 0.4 - # As a starting point for speed-adjusted lateral tuning, use the example - # map speed breakpoints from a VW Tiguan (SSP 399 page 9). It's unclear - # whether the driver assist map breakpoints have any direct bearing on - # HCA assist torque, but if they're good breakpoints for the driver, - # they're probably good breakpoints for HCA as well. OP won't be driving - # 250kph/155mph but it provides interpolation scaling above 100kmh/62mph. - ret.lateralTuning.pid.kpBP = [0., 15 * CV.KPH_TO_MS, 50 * CV.KPH_TO_MS] - ret.lateralTuning.pid.kiBP = [0., 15 * CV.KPH_TO_MS, 50 * CV.KPH_TO_MS] - - # FIXME: Per-vehicle parameters need to be reintegrated. - # For the time being, per-vehicle stuff is being archived since we - # can't auto-detect very well yet. Now that tuning is figured out, - # averaged params should work reasonably on a range of cars. Owners - # can tweak here, as needed, until we have car type auto-detection. - - ret.mass = 1700 + STD_CARGO_KG - ret.wheelbase = 2.75 + ret.lateralTuning.pid.kpBP = [0.] + ret.lateralTuning.pid.kiBP = [0.] + + ret.mass = 1500 + STD_CARGO_KG + ret.wheelbase = 2.64 ret.centerToFront = ret.wheelbase * 0.45 ret.steerRatio = 15.6 ret.lateralTuning.pid.kf = 0.00006 - ret.lateralTuning.pid.kpV = [0.15, 0.25, 0.60] - ret.lateralTuning.pid.kiV = [0.05, 0.05, 0.05] - tire_stiffness_factor = 0.6 + ret.lateralTuning.pid.kpV = [0.6] + ret.lateralTuning.pid.kiV = [0.2] + tire_stiffness_factor = 1.0 - ret.enableCamera = True # Stock camera detection doesn't apply to VW + ret.enableCamera = True # Stock camera detection doesn't apply to VW ret.transmissionType = car.CarParams.TransmissionType.automatic # TODO: get actual value, for now starting with reasonable value for diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 01551e683d..7e5f01eb3d 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -7a37594320b77ed514b11125e54b6f515150d6c1 \ No newline at end of file +d50cc2d81fd73dcfccfe1a8e2726879941ec5327 \ No newline at end of file From 4fcf47812bee79a82919799d9a9b9cac115dea99 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sat, 30 May 2020 17:15:41 -0700 Subject: [PATCH 148/656] add some sanity checks on returned params --- selfdrive/car/tests/test_car_interfaces.py | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index f320e0be29..c6c908efd8 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -30,6 +30,17 @@ class TestCarInterfaces(unittest.TestCase): assert car_params assert car_interface + self.assertGreater(car_params.mass, 1) + self.assertGreater(car_params.steerRateCost, 1e-3) + + tuning = car_params.lateralTuning.which() + if tuning == 'pid': + self.assertTrue(len(car_params.lateralTuning.pid.kpV)) + elif tuning == 'lqr': + self.assertTrue(len(car_params.lateralTuning.lqr.a)) + elif tuning == 'indi': + self.assertGreater(car_params.lateralTuning.indi.outerLoopGain, 1e-3) + # Run car interface CC = car.CarControl.new_message() for _ in range(10): From d9bf9f0a4036f55411f6dfbb438990a5eb7f4930 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Sat, 30 May 2020 20:14:58 -0700 Subject: [PATCH 149/656] Enable more flake8 checks (#1602) * enable some more flake8 checks * some more quick ones * bump opendbc * e401 * e711 e712 * e115 e116 * e222 * e301 * remove that * e129 * e701 e702 * e125 e131 * e227 * e306 * e262 * W503 * e713 * e704 * e731 * bump opendbc * fix some e722 --- .pre-commit-config.yaml | 3 +- common/android.py | 3 +- common/api/__init__.py | 1 - common/basedir.py | 1 - common/file_helpers.py | 6 ++-- common/logging_extra.py | 7 +++-- common/numpy_fast.py | 5 ++-- common/params.py | 3 +- common/profiler.py | 1 - common/stat_live.py | 2 +- common/string_helpers.py | 2 +- common/testing.py | 1 - common/timeout.py | 1 - common/transformations/camera.py | 1 - common/transformations/coordinates.py | 2 +- common/url_file.py | 6 +++- opendbc | 2 +- scripts/code_stats.py | 2 +- selfdrive/boardd/tests/boardd_old.py | 4 +-- selfdrive/camerad/test/frame_test.py | 4 +-- selfdrive/car/__init__.py | 1 - selfdrive/car/ford/carcontroller.py | 2 +- selfdrive/car/ford/fordcan.py | 2 +- selfdrive/car/gm/carcontroller.py | 3 +- selfdrive/car/gm/carstate.py | 6 ++-- selfdrive/car/gm/gmcan.py | 1 - selfdrive/car/gm/interface.py | 6 ++-- selfdrive/car/gm/radar_interface.py | 2 +- selfdrive/car/honda/carstate.py | 4 +-- selfdrive/car/hyundai/carcontroller.py | 2 +- selfdrive/car/hyundai/carstate.py | 4 +-- selfdrive/car/hyundai/interface.py | 4 +-- selfdrive/car/mazda/__init__.py | 1 - selfdrive/car/mazda/carcontroller.py | 2 +- selfdrive/car/mazda/carstate.py | 5 ++-- selfdrive/car/mazda/interface.py | 2 +- selfdrive/car/mazda/mazdacan.py | 8 +++--- selfdrive/car/mazda/radar_interface.py | 1 - selfdrive/car/mazda/values.py | 4 +-- selfdrive/car/subaru/__init__.py | 1 - selfdrive/car/toyota/carcontroller.py | 6 ++-- selfdrive/car/toyota/interface.py | 6 ++-- selfdrive/car/toyota/radar_interface.py | 2 +- selfdrive/car/toyota/values.py | 28 +++++++++---------- selfdrive/car/volkswagen/__init__.py | 1 - selfdrive/car/volkswagen/carcontroller.py | 2 +- selfdrive/config.py | 1 - selfdrive/controls/controlsd.py | 4 +-- selfdrive/controls/lib/driverview.py | 2 +- selfdrive/controls/lib/latcontrol_indi.py | 2 +- selfdrive/controls/lib/latcontrol_lqr.py | 4 +-- selfdrive/controls/lib/vehicle_model.py | 1 - selfdrive/controls/tests/test_events.py | 3 +- selfdrive/controls/tests/test_monitoring.py | 2 +- selfdrive/crash.py | 4 +++ selfdrive/launcher.py | 2 +- selfdrive/locationd/calibration_helpers.py | 1 - selfdrive/locationd/test/ephemeris.py | 2 -- selfdrive/locationd/test/ublox.py | 13 +++++---- selfdrive/locationd/test/ubloxd.py | 14 +++++----- selfdrive/loggerd/tools/mark_unuploaded.py | 1 - selfdrive/loggerd/uploader.py | 4 ++- .../longitudinal_maneuvers/maneuverplots.py | 11 ++++---- .../test/longitudinal_maneuvers/plant.py | 14 +++++----- selfdrive/test/process_replay/compare_logs.py | 8 +++--- .../test/process_replay/process_replay.py | 6 ++-- .../test/process_replay/test_processes.py | 6 ++-- selfdrive/test/test_car_models.py | 10 +++---- selfdrive/test/test_leeco_alt_fan.py | 2 +- selfdrive/thermald/thermald.py | 2 +- tools/carcontrols/joystick_test.py | 4 +-- tools/lib/route.py | 12 +++++--- tools/lib/route_framereader.py | 7 +++-- tools/replay/lib/ui_helpers.py | 14 ++++------ tools/replay/unlogger.py | 10 +++++-- tools/sim/bridge.py | 2 +- tools/sim/lib/can.py | 6 ++-- tools/sim/lib/manual_ctrl.py | 4 ++- tools/webcam/accept_terms.py | 2 +- 79 files changed, 179 insertions(+), 164 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 5eebcfa4b9..020c7e9e7f 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,7 +17,8 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - - --select=F + - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E221,E225,E226,E231,E241,E251,E261,E265,E266,E302,E303,E305,E402,E501,E502,E722,E741,W504 + - --statistics - repo: local hooks: - id: pylint diff --git a/common/android.py b/common/android.py index 4342a4259a..cb6a7748d2 100644 --- a/common/android.py +++ b/common/android.py @@ -25,7 +25,7 @@ def get_imei(slot): ret = parse_service_call_string(service_call(["iphonesubinfo", "3" ,"i32", str(slot)])) if not ret: # allow non android to be identified differently - ret = "%015d" % random.randint(0, 1<<32) + ret = "%015d" % random.randint(0, 1 << 32) return ret def get_serial(): @@ -132,6 +132,7 @@ def get_network_type(): def get_network_strength(network_type): network_strength = NetworkStrength.unknown + # from SignalStrength.java def get_lte_level(rsrp, rssnr): INT_MAX = 2147483647 diff --git a/common/api/__init__.py b/common/api/__init__.py index 38fe6b2477..f44e48f963 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -39,4 +39,3 @@ def api_get(endpoint, method='GET', timeout=None, access_token=None, **params): headers['User-Agent'] = "openpilot-" + version return requests.request(method, backend+endpoint, timeout=timeout, headers = headers, params=params) - diff --git a/common/basedir.py b/common/basedir.py index e928ded4c4..4d62fdc19c 100644 --- a/common/basedir.py +++ b/common/basedir.py @@ -8,4 +8,3 @@ if ANDROID: else: PERSIST = os.path.join(BASEDIR, "persist") PARAMS = os.path.join(BASEDIR, "persist", "params") - diff --git a/common/file_helpers.py b/common/file_helpers.py index 40c89fab0e..187f0f9ac6 100644 --- a/common/file_helpers.py +++ b/common/file_helpers.py @@ -44,7 +44,8 @@ class AutoMoveTempdir(): def close(self): os.rename(self._path, self._target_path) - def __enter__(self): return self + def __enter__(self): + return self def __exit__(self, type, value, traceback): if type is None: @@ -63,7 +64,8 @@ class NamedTemporaryDir(): def close(self): shutil.rmtree(self._path) - def __enter__(self): return self + def __enter__(self): + return self def __exit__(self, type, value, traceback): self.close() diff --git a/common/logging_extra.py b/common/logging_extra.py index b5d07f2209..2c49561fb9 100644 --- a/common/logging_extra.py +++ b/common/logging_extra.py @@ -68,8 +68,11 @@ class SwagErrorFilter(logging.Filter): def filter(self, record): return record.levelno < logging.ERROR -_tmpfunc = lambda: 0 -_srcfile = os.path.normcase(_tmpfunc.__code__.co_filename) +def _tmpfunc(): + return 0 + +def _srcfile(): + return os.path.normcase(_tmpfunc.__code__.co_filename) class SwagLogger(logging.Logger): def __init__(self): diff --git a/common/numpy_fast.py b/common/numpy_fast.py index a5d5ad3f50..a8361214d1 100644 --- a/common/numpy_fast.py +++ b/common/numpy_fast.py @@ -6,6 +6,7 @@ def clip(x, lo, hi): def interp(x, xp, fp): N = len(xp) + def get_interp(xv): hi = 0 while hi < N and xv > xp[hi]: @@ -14,8 +15,8 @@ def interp(x, xp, fp): return fp[-1] if hi == N and xv > xp[low] else ( fp[0] if hi == 0 else (xv - xp[low]) * (fp[hi] - fp[low]) / (xp[hi] - xp[low]) + fp[low]) - return [get_interp(v) for v in x] if hasattr( - x, '__iter__') else get_interp(x) + + return [get_interp(v) for v in x] if hasattr(x, '__iter__') else get_interp(x) def mean(x): return sum(x) / len(x) diff --git a/common/params.py b/common/params.py index 0a7e6daf9e..b92f17ca26 100755 --- a/common/params.py +++ b/common/params.py @@ -195,7 +195,8 @@ class DBReader(DBAccessor): finally: lock.release() - def __exit__(self, type, value, traceback): pass + def __exit__(self, type, value, traceback): + pass class DBWriter(DBAccessor): diff --git a/common/profiler.py b/common/profiler.py index f8262dd83e..ac28bdac40 100644 --- a/common/profiler.py +++ b/common/profiler.py @@ -43,4 +43,3 @@ class Profiler(): else: print("%30s: %9.2f percent: %3.0f" % (n, ms*1000.0, ms/self.tot*100)) print("Iter clock: %2.6f TOTAL: %2.2f" % (self.tot/self.iter, self.tot)) - diff --git a/common/stat_live.py b/common/stat_live.py index e528c3deac..bab982888d 100644 --- a/common/stat_live.py +++ b/common/stat_live.py @@ -32,7 +32,7 @@ class RunningStat(): self.S_last = 0. else: self.M = self.M_last + (new_data - self.M_last) / self.n - self.S = self.S_last + (new_data - self.M_last) * (new_data - self.M); + self.S = self.S_last + (new_data - self.M_last) * (new_data - self.M) self.M_last = self.M self.S_last = self.S diff --git a/common/string_helpers.py b/common/string_helpers.py index 8a7624a277..3038605fbb 100644 --- a/common/string_helpers.py +++ b/common/string_helpers.py @@ -3,4 +3,4 @@ def replace_right(s, old, new, occurrence): # replace_right('1232425', '2', ' ', 2) -> '123 4 5' split = s.rsplit(old, occurrence) - return new.join(split) \ No newline at end of file + return new.join(split) diff --git a/common/testing.py b/common/testing.py index 7e8b16d5cf..95c43b574d 100644 --- a/common/testing.py +++ b/common/testing.py @@ -6,4 +6,3 @@ def phone_only(x): return x else: return nottest(x) - diff --git a/common/timeout.py b/common/timeout.py index c2c1f69712..4d424cdc0a 100644 --- a/common/timeout.py +++ b/common/timeout.py @@ -25,4 +25,3 @@ class Timeout: def __exit__(self, exc_type, exc_val, exc_tb): signal.alarm(0) - diff --git a/common/transformations/camera.py b/common/transformations/camera.py index 5ca9eb57d5..3e8ee16e37 100644 --- a/common/transformations/camera.py +++ b/common/transformations/camera.py @@ -145,4 +145,3 @@ def pretransform_from_calib(calib): camera_frame_from_road_frame = np.dot(eon_intrinsics, view_frame_from_road_frame) camera_frame_from_calib_frame = get_camera_frame_from_calib_frame(camera_frame_from_road_frame) return np.linalg.inv(camera_frame_from_calib_frame) - diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index c5d76b6e0b..3f9ba23f29 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -52,7 +52,7 @@ def ecef2geodetic(ecef, radians=False): S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C)) P = F / (3 * pow((S + 1 / S + 1), 2) * G * G) Q = np.sqrt(1 + 2 * esq * esq * P) - r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \ + r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \ P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r) U = np.sqrt(pow((r - esq * r_0), 2) + z * z) V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z) diff --git a/common/url_file.py b/common/url_file.py index 184b7452b9..4ba8192049 100644 --- a/common/url_file.py +++ b/common/url_file.py @@ -50,12 +50,16 @@ class URLFile(object): if self._debug: print("downloading", self._url) + def header(x): if b'MISS' in x: print(x.strip()) + c.setopt(pycurl.HEADERFUNCTION, header) + def test(debug_type, debug_msg): print(" debug(%d): %s" % (debug_type, debug_msg.strip())) + c.setopt(pycurl.VERBOSE, 1) c.setopt(pycurl.DEBUGFUNCTION, test) t1 = time.time() @@ -68,7 +72,7 @@ class URLFile(object): print("get %s %r %.f slow" % (self._url, trange, t2-t1)) response_code = c.getinfo(pycurl.RESPONSE_CODE) - if response_code == 416: # Requested Range Not Satisfiable + if response_code == 416: # Requested Range Not Satisfiable return "" if response_code != 206 and response_code != 200: raise Exception("Error {} ({}): {}".format(response_code, self._url, repr(dats.getvalue())[:500])) diff --git a/opendbc b/opendbc index 0430bfa5c2..b15edbc1b5 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 0430bfa5c2b08f9cc6ab32470fe8ac9465e7a876 +Subproject commit b15edbc1b5a68fd725ea45ba9442a6c9be875971 diff --git a/scripts/code_stats.py b/scripts/code_stats.py index ccd32c7e50..d3bc48bcec 100755 --- a/scripts/code_stats.py +++ b/scripts/code_stats.py @@ -20,6 +20,7 @@ class Analyzer(ast.NodeVisitor): for alias in node.names: imps.add(alias.name) self.generic_visit(node) + def visit_ImportFrom(self, node): imps.add(node.module) self.generic_visit(node) @@ -38,4 +39,3 @@ for f in sorted(pyf): print("%d lines of parsed openpilot python" % tlns) #print(sorted(list(imps))) - diff --git a/selfdrive/boardd/tests/boardd_old.py b/selfdrive/boardd/tests/boardd_old.py index f6ca7eb87d..c5ff9263b5 100755 --- a/selfdrive/boardd/tests/boardd_old.py +++ b/selfdrive/boardd/tests/boardd_old.py @@ -21,7 +21,7 @@ SafetyModel = car.CarParams.SafetyModel # USB is optional try: import usb1 - from usb1 import USBErrorIO, USBErrorOverflow #pylint: disable=no-name-in-module + from usb1 import USBErrorIO, USBErrorOverflow # pylint: disable=no-name-in-module except Exception: pass @@ -57,7 +57,7 @@ def __parse_can_buffer(dat): for j in range(0, len(dat), 0x10): ddat = dat[j:j+0x10] f1, f2 = struct.unpack("II", ddat[0:8]) - ret.append((f1 >> 21, f2>>16, ddat[8:8+(f2&0xF)], (f2>>4)&0xFF)) + ret.append((f1 >> 21, f2 >> 16, ddat[8:8 + (f2 & 0xF)], (f2 >> 4) & 0xFF)) return ret def can_send_many(arr): diff --git a/selfdrive/camerad/test/frame_test.py b/selfdrive/camerad/test/frame_test.py index d7b677c232..6b8b99ae81 100755 --- a/selfdrive/camerad/test/frame_test.py +++ b/selfdrive/camerad/test/frame_test.py @@ -6,7 +6,7 @@ from PIL import ImageFont, ImageDraw, Image font = ImageFont.truetype("arial", size=72) def get_frame(idx): img = np.zeros((874, 1164, 3), np.uint8) - img[100:400, 100:100+(idx%10)*100] = 255 + img[100:400, 100:100+(idx % 10)* 100] = 255 # big number im2 = Image.new("RGB", (200,200)) @@ -28,7 +28,7 @@ if __name__ == "__main__": dat.valid = True dat.frame = { "frameId": idx, - "image": frm[idx%len(frm)], + "image": frm[idx % len(frm)], } pm.send('frame', dat) diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 6ad29d4b3a..1d579543a6 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -128,4 +128,3 @@ def is_ecu_disconnected(fingerprint, fingerprint_list, ecu_fingerprint, car, ecu def make_can_msg(addr, dat, bus): return [addr, 0, dat, bus] - diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py index 4c0a37ab02..648fa07741 100644 --- a/selfdrive/car/ford/carcontroller.py +++ b/selfdrive/car/ford/carcontroller.py @@ -78,7 +78,7 @@ class CarController(): static_msgs = range(1653, 1658) for addr in static_msgs: cnt = (frame % 10) + 1 - can_sends.append(make_can_msg(addr, (cnt<<4).to_bytes(1, 'little') + b'\x00\x00\x00\x00\x00\x00\x00', 1)) + can_sends.append(make_can_msg(addr, (cnt << 4).to_bytes(1, 'little') + b'\x00\x00\x00\x00\x00\x00\x00', 1)) self.enabled_last = enabled self.main_on_last = CS.out.cruiseState.available diff --git a/selfdrive/car/ford/fordcan.py b/selfdrive/car/ford/fordcan.py index dd0c15415e..f2ebb9100b 100644 --- a/selfdrive/car/ford/fordcan.py +++ b/selfdrive/car/ford/fordcan.py @@ -6,7 +6,7 @@ def create_steer_command(packer, angle_cmd, enabled, lkas_state, angle_steers, c """Creates a CAN message for the Ford Steer Command.""" #if enabled and lkas available: - if enabled and lkas_state in [2,3]: #and (frame % 500) >= 3: + if enabled and lkas_state in [2,3]: # and (frame % 500) >= 3: action = lkas_action else: action = 0xf diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index f84ea3e322..06f87113ae 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -161,8 +161,7 @@ class CarController(): lka_active = CS.lkas_status == 1 lka_critical = lka_active and abs(actuators.steer) > 0.9 lka_icon_status = (lka_active, lka_critical) - if frame % P.CAMERA_KEEPALIVE_STEP == 0 \ - or lka_icon_status != self.lka_icon_status_last: + if frame % P.CAMERA_KEEPALIVE_STEP == 0 or lka_icon_status != self.lka_icon_status_last: steer_alert = hud_alert == VisualAlert.steerRequired can_sends.append(gmcan.create_lka_icon_command(CanBus.SW_GMLAN, lka_active, lka_critical, steer_alert)) self.lka_icon_status_last = lka_icon_status diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index ac866ba226..2eb3ff7cdb 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -44,9 +44,9 @@ class CarState(CarStateBase): # 1 - open, 0 - closed ret.doorOpen = (pt_cp.vl["BCMDoorBeltStatus"]['FrontLeftDoor'] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]['FrontRightDoor'] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]['RearLeftDoor'] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]['RearRightDoor'] == 1) + pt_cp.vl["BCMDoorBeltStatus"]['FrontRightDoor'] == 1 or + pt_cp.vl["BCMDoorBeltStatus"]['RearLeftDoor'] == 1 or + pt_cp.vl["BCMDoorBeltStatus"]['RearRightDoor'] == 1) # 1 - latched ret.seatbeltUnlatched = pt_cp.vl["BCMDoorBeltStatus"]['LeftSeatBelt'] == 0 diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py index ba13df9219..67acb7c487 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/selfdrive/car/gm/gmcan.py @@ -121,4 +121,3 @@ def create_lka_icon_command(bus, active, critical, steer): else: dat = b"\x00\x00\x00" return make_can_msg(0x104c006c, dat, bus) - diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 55dffce205..18baf8886d 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -71,15 +71,15 @@ class CarInterface(CarInterfaceBase): ret.minEnableSpeed = -1. # engage speed is decided by pcm ret.mass = 4353. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.86 - ret.steerRatio = 14.4 #end to end is 13.46 + ret.steerRatio = 14.4 # end to end is 13.46 ret.steerRatioRear = 0. ret.centerToFront = ret.wheelbase * 0.4 elif candidate == CAR.BUICK_REGAL: ret.minEnableSpeed = 18 * CV.MPH_TO_MS ret.mass = 3779. * CV.LB_TO_KG + STD_CARGO_KG # (3849+3708)/2 - ret.wheelbase = 2.83 #111.4 inches in meters - ret.steerRatio = 14.4 # guess for tourx + ret.wheelbase = 2.83 # 111.4 inches in meters + ret.steerRatio = 14.4 # guess for tourx ret.steerRatioRear = 0. ret.centerToFront = ret.wheelbase * 0.4 # guess for tourx diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py index 8a2f9a2e69..b63acaddc9 100755 --- a/selfdrive/car/gm/radar_interface.py +++ b/selfdrive/car/gm/radar_interface.py @@ -103,7 +103,7 @@ class RadarInterface(RadarInterfaceBase): self.pts[targetId].yvRel = float('nan') for oldTarget in list(self.pts.keys()): - if not oldTarget in currentTargets: + if oldTarget not in currentTargets: del self.pts[oldTarget] ret.points = list(self.pts.values()) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 91124564e7..71c0299dd6 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -20,7 +20,7 @@ def calc_cruise_offset(offset, speed): def get_can_signals(CP): -# this function generates lists for signal, messages and initial values + # this function generates lists for signal, messages and initial values signals = [ ("XMISSION_SPEED", "ENGINE_DATA", 0), ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), @@ -345,5 +345,5 @@ class CarState(CarStateBase): if CP.carFingerprint in [CAR.CRV, CAR.CRV_EU, CAR.ACURA_RDX, CAR.ODYSSEY_CHN]: checks = [(0x194, 100)] - bus_cam = 1 if CP.carFingerprint in HONDA_BOSCH and not CP.isPandaBlack else 2 + bus_cam = 1 if CP.carFingerprint in HONDA_BOSCH and not CP.isPandaBlack else 2 return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, bus_cam) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 59fef40d20..e31a0bcea7 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -13,7 +13,7 @@ def process_hud_alert(enabled, fingerprint, visual_alert, left_lane, # initialize to no line visible sys_state = 1 - if left_lane and right_lane or sys_warning: #HUD alert only display when LKAS status is active + if left_lane and right_lane or sys_warning: # HUD alert only display when LKAS status is active if enabled or sys_warning: sys_state = 3 else: diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index d6f7d30ec5..c108bd5838 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -113,7 +113,7 @@ class CarState(CarStateBase): self.lkas11 = cp_cam.vl["LKAS11"] self.clu11 = cp.vl["CLU11"] self.park_brake = cp.vl["CGW1"]['CF_Gway_ParkBrakeSw'] - self.steer_state = cp.vl["MDPS12"]['CF_Mdps_ToiActive'] #0 NOT ACTIVE, 1 ACTIVE + self.steer_state = cp.vl["MDPS12"]['CF_Mdps_ToiActive'] # 0 NOT ACTIVE, 1 ACTIVE self.lead_distance = cp.vl["SCC11"]['ACC_ObjDist'] return ret @@ -163,7 +163,7 @@ class CarState(CarStateBase): ("ESC_Off_Step", "TCS15", 0), - ("CF_Lvr_GearInf", "LVR11", 0), #Transmission Gear (0 = N or P, 1-8 = Fwd, 14 = Rev) + ("CF_Lvr_GearInf", "LVR11", 0), # Transmission Gear (0 = N or P, 1-8 = Fwd, 14 = Rev) ("CR_Mdps_StrColTq", "MDPS12", 0), ("CF_Mdps_ToiActive", "MDPS12", 0), diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 598a52e5e7..5b28d573b1 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -113,7 +113,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1275. + STD_CARGO_KG ret.wheelbase = 2.7 - ret.steerRatio = 13.73 #Spec + ret.steerRatio = 13.73 # Spec tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] @@ -121,7 +121,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1685. + STD_CARGO_KG ret.wheelbase = 2.7 - ret.steerRatio = 13.73 #Spec + ret.steerRatio = 13.73 # Spec tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] diff --git a/selfdrive/car/mazda/__init__.py b/selfdrive/car/mazda/__init__.py index 8b13789179..e69de29bb2 100644 --- a/selfdrive/car/mazda/__init__.py +++ b/selfdrive/car/mazda/__init__.py @@ -1 +0,0 @@ - diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py index 5714bdaf0d..ecac936906 100644 --- a/selfdrive/car/mazda/carcontroller.py +++ b/selfdrive/car/mazda/carcontroller.py @@ -38,7 +38,7 @@ class CarController(): self.apply_steer_last = apply_steer - + can_sends.append(mazdacan.create_steering_control(self.packer, CS.CP.carFingerprint, frame, apply_steer, CS.cam_lkas)) return can_sends diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index a089ea13ee..86d1643c49 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -38,7 +38,7 @@ class CarState(CarStateBase): ret.leftBlinker = cp.vl["BLINK_INFO"]['LEFT_BLINK'] == 1 ret.rightBlinker = cp.vl["BLINK_INFO"]['RIGHT_BLINK'] == 1 - ret.steeringAngle = cp.vl["STEER"]['STEER_ANGLE'] + ret.steeringAngle = cp.vl["STEER"]['STEER_ANGLE'] ret.steeringTorque = cp.vl["STEER_TORQUE"]['STEER_TORQUE_SENSOR'] ret.steeringPressed = abs(ret.steeringTorque) > LKAS_LIMITS.STEER_THRESHOLD @@ -70,7 +70,7 @@ class CarState(CarStateBase): self.cruise_speed = ret.vEgoRaw ret.cruiseState.available = True - ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]['CRZ_ACTIVE'] == 1 + ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]['CRZ_ACTIVE'] == 1 ret.cruiseState.speed = self.cruise_speed if ret.cruiseState.enabled: @@ -182,4 +182,3 @@ class CarState(CarStateBase): ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) - diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 1e6b05ba02..160f531f20 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -34,7 +34,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.70 # not optimized yet if candidate in [CAR.CX5]: - ret.mass = 3655 * CV.LB_TO_KG + STD_CARGO_KG + ret.mass = 3655 * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.7 ret.steerRatio = 15.5 diff --git a/selfdrive/car/mazda/mazdacan.py b/selfdrive/car/mazda/mazdacan.py index 3fae424fa8..5728bfed93 100644 --- a/selfdrive/car/mazda/mazdacan.py +++ b/selfdrive/car/mazda/mazdacan.py @@ -17,10 +17,10 @@ def create_steering_control(packer, car_fingerprint, frame, apply_steer, lkas): b2 = int(lkas["ANGLE_ENABLED"]) tmp = steering_angle + 2048 - ahi = tmp >> 10 - amd = (tmp & 0x3FF) >> 2 - amd = (amd >> 4) | (( amd & 0xF) << 4) - alo = (tmp & 0x3) << 2 + ahi = tmp >> 10 + amd = (tmp & 0x3FF) >> 2 + amd = (amd >> 4) | (( amd & 0xF) << 4) + alo = (tmp & 0x3) << 2 ctr = frame % 16 # bytes: [ 1 ] [ 2 ] [ 3 ] [ 4 ] diff --git a/selfdrive/car/mazda/radar_interface.py b/selfdrive/car/mazda/radar_interface.py index 55f92f6326..b2f7651136 100755 --- a/selfdrive/car/mazda/radar_interface.py +++ b/selfdrive/car/mazda/radar_interface.py @@ -3,4 +3,3 @@ from selfdrive.car.interfaces import RadarInterfaceBase class RadarInterface(RadarInterfaceBase): pass - diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 2cab11d1f9..491fa72c8a 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -19,8 +19,8 @@ class CAR: class LKAS_LIMITS: STEER_THRESHOLD = 15 - DISABLE_SPEED = 45 #kph - ENABLE_SPEED = 52 #kph + DISABLE_SPEED = 45 # kph + ENABLE_SPEED = 52 # kph class Buttons: NONE = 0 diff --git a/selfdrive/car/subaru/__init__.py b/selfdrive/car/subaru/__init__.py index 8b13789179..e69de29bb2 100644 --- a/selfdrive/car/subaru/__init__.py +++ b/selfdrive/car/subaru/__init__.py @@ -1 +0,0 @@ - diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 0346801c0d..9b68c1940e 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -42,8 +42,10 @@ class CarController(): self.steer_rate_limited = False self.fake_ecus = set() - if CP.enableCamera: self.fake_ecus.add(Ecu.fwdCamera) - if CP.enableDsu: self.fake_ecus.add(Ecu.dsu) + if CP.enableCamera: + self.fake_ecus.add(Ecu.fwdCamera) + if CP.enableDsu: + self.fake_ecus.add(Ecu.dsu) self.packer = CANPacker(dbc_name) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 78c4285573..89149b6ae4 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -127,7 +127,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.82448 ret.steerRatio = 13.7 tire_stiffness_factor = 0.7933 - ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG #mean between normal and hybrid + ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] ret.lateralTuning.pid.kf = 0.00006 @@ -147,7 +147,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.78 ret.steerRatio = 16.0 tire_stiffness_factor = 0.8 - ret.mass = 4607. * CV.LB_TO_KG + STD_CARGO_KG #mean between normal and hybrid limited + ret.mass = 4607. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid limited ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.18], [0.015]] # community tuning ret.lateralTuning.pid.kf = 0.00012 # community tuning @@ -155,7 +155,7 @@ class CarInterface(CarInterfaceBase): stop_and_go = False ret.safetyParam = 73 ret.wheelbase = 2.82 - ret.steerRatio = 14.8 #Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download + ret.steerRatio = 14.8 # Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download tire_stiffness_factor = 0.7983 ret.mass = 3505. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.17], [0.03]] diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py index 12387d489f..b831b005de 100755 --- a/selfdrive/car/toyota/radar_interface.py +++ b/selfdrive/car/toyota/radar_interface.py @@ -62,7 +62,7 @@ class RadarInterface(RadarInterfaceBase): if self.trigger_msg not in self.updated_messages: return None - rr = self._update(self.updated_messages) + rr = self._update(self.updated_messages) self.updated_messages.clear() return rr diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 24305382b6..bd499c762e 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -803,7 +803,7 @@ FW_VERSIONS = { b'\x01896630852100\x00\x00\x00\x00', b'\x01896630859000\x00\x00\x00\x00', ], - (Ecu.eps, 0x7a1, None): [ + (Ecu.eps, 0x7a1, None): [ b'8965B45070\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ @@ -844,24 +844,24 @@ FW_VERSIONS = { }, CAR.LEXUS_RX: { (Ecu.engine, 0x700, None): [ - b'\x01896630E41200\x00\x00\x00\x00', - ], + b'\x01896630E41200\x00\x00\x00\x00', + ], (Ecu.esp, 0x7b0, None): [ - b'F152648473\x00\x00\x00\x00\x00\x00', - ], + b'F152648473\x00\x00\x00\x00\x00\x00', + ], (Ecu.dsu, 0x791, None): [ - b'881514810500\x00\x00\x00\x00', - ], + b'881514810500\x00\x00\x00\x00', + ], (Ecu.eps, 0x7a1, None): [ - b'8965B0E012\x00\x00\x00\x00\x00\x00', - ], + b'8965B0E012\x00\x00\x00\x00\x00\x00', + ], (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701100\x00\x00\x00\x00', - ], + b'8821F4701100\x00\x00\x00\x00', + ], (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4802001\x00\x00\x00\x00', - b'8646F4802100\x00\x00\x00\x00', - ], + b'8646F4802001\x00\x00\x00\x00', + b'8646F4802100\x00\x00\x00\x00', + ], }, CAR.LEXUS_RXH: { (Ecu.engine, 0x7e0, None): [ diff --git a/selfdrive/car/volkswagen/__init__.py b/selfdrive/car/volkswagen/__init__.py index 8b13789179..e69de29bb2 100644 --- a/selfdrive/car/volkswagen/__init__.py +++ b/selfdrive/car/volkswagen/__init__.py @@ -1 +0,0 @@ - diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index 6c90d69e78..a157805c13 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -67,7 +67,7 @@ class CarController(): self.hcaEnabledFrameCount = 0 else: self.hcaEnabledFrameCount += 1 - if self.hcaEnabledFrameCount >= 118 * (100 / P.HCA_STEP): # 118s + if self.hcaEnabledFrameCount >= 118 * (100 / P.HCA_STEP): # 118s # The Kansas I-70 Crosswind Problem: if we truly do need to steer # in one direction for > 360 seconds, we have to disable HCA for a # frame while actively steering. Testing shows we can just set the diff --git a/selfdrive/config.py b/selfdrive/config.py index 6c2296273a..0e18c31f49 100644 --- a/selfdrive/config.py +++ b/selfdrive/config.py @@ -27,4 +27,3 @@ class UIParams: car_front = 2.6924 * lidar_zoom car_back = 1.8796 * lidar_zoom car_color = 110 - diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index e3e502c1a8..55cfe1bf1e 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -223,7 +223,7 @@ class Controls: # Only allow engagement with brake pressed when stopped behind another stopped car if CS.brakePressed and self.sm['plan'].vTargetFuture >= STARTING_TARGET_SPEED \ - and not self.CP.radarOffCan and CS.vEgo < 0.3: + and not self.CP.radarOffCan and CS.vEgo < 0.3: self.events.add(EventName.noTarget) @@ -372,7 +372,7 @@ class Controls: # Send a "steering required alert" if saturation count has reached the limit if (lac_log.saturated and not CS.steeringPressed) or \ - (self.saturated_count > STEER_ANGLE_SATURATION_TIMEOUT): + (self.saturated_count > STEER_ANGLE_SATURATION_TIMEOUT): # Check if we deviated from the path left_deviation = actuators.steer > 0 and path_plan.dPoly[3] > 0.1 right_deviation = actuators.steer < 0 and path_plan.dPoly[3] < -0.1 diff --git a/selfdrive/controls/lib/driverview.py b/selfdrive/controls/lib/driverview.py index 298858bd4d..ad49fb77ec 100755 --- a/selfdrive/controls/lib/driverview.py +++ b/selfdrive/controls/lib/driverview.py @@ -71,4 +71,4 @@ def main(): is_rhd_checked = True if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/selfdrive/controls/lib/latcontrol_indi.py b/selfdrive/controls/lib/latcontrol_indi.py index 91a5e2d6ae..2b41dc6f7e 100644 --- a/selfdrive/controls/lib/latcontrol_indi.py +++ b/selfdrive/controls/lib/latcontrol_indi.py @@ -116,7 +116,7 @@ class LatControlINDI(): indi_log.delta = float(delta_u) indi_log.output = float(self.output_steer) - check_saturation = (CS.vEgo> 10.) and not CS.steeringRateLimited and not CS.steeringPressed + check_saturation = (CS.vEgo> 10.) and not CS.steeringRateLimited and not CS.steeringPressed indi_log.saturated = self._check_saturation(self.output_steer, check_saturation, steers_max) return float(self.output_steer), float(self.angle_steers_des), indi_log diff --git a/selfdrive/controls/lib/latcontrol_lqr.py b/selfdrive/controls/lib/latcontrol_lqr.py index a12aee2e93..b27f8c3e33 100644 --- a/selfdrive/controls/lib/latcontrol_lqr.py +++ b/selfdrive/controls/lib/latcontrol_lqr.py @@ -79,8 +79,8 @@ class LatControlLQR(): i = self.i_lqr + self.ki * self.i_rate * error control = lqr_output + i - if ((error >= 0 and (control <= steers_max or i < 0.0)) or \ - (error <= 0 and (control >= -steers_max or i > 0.0))): + if (error >= 0 and (control <= steers_max or i < 0.0)) or \ + (error <= 0 and (control >= -steers_max or i > 0.0)): self.i_lqr = i self.output_steer = lqr_output + self.i_lqr diff --git a/selfdrive/controls/lib/vehicle_model.py b/selfdrive/controls/lib/vehicle_model.py index 6ac5f856f4..9959f82dc8 100755 --- a/selfdrive/controls/lib/vehicle_model.py +++ b/selfdrive/controls/lib/vehicle_model.py @@ -194,4 +194,3 @@ class VehicleModel(): Yaw rate [rad/s] """ return self.calc_curvature(sa, u) * u - diff --git a/selfdrive/controls/tests/test_events.py b/selfdrive/controls/tests/test_events.py index 79662b719e..2951dcebb0 100755 --- a/selfdrive/controls/tests/test_events.py +++ b/selfdrive/controls/tests/test_events.py @@ -52,7 +52,8 @@ class TestAlerts(unittest.TestCase): continue for i, txt in enumerate([alert.alert_text_1, alert.alert_text_2]): - if i >= len(fonts[alert.alert_size]): break + if i >= len(fonts[alert.alert_size]): + break font = fonts[alert.alert_size][i] w, h = draw.textsize(txt, font) diff --git a/selfdrive/controls/tests/test_monitoring.py b/selfdrive/controls/tests/test_monitoring.py index 67e97040cd..93a3b553c5 100644 --- a/selfdrive/controls/tests/test_monitoring.py +++ b/selfdrive/controls/tests/test_monitoring.py @@ -65,7 +65,7 @@ def run_DState_seq(driver_state_msgs, driver_car_interaction, openpilot_status, for idx in range(len(driver_state_msgs)): e = Events() DS.get_pose(driver_state_msgs[idx], [0,0,0], 0, openpilot_status[idx]) - # cal_rpy and car_speed don't matter here + # cal_rpy and car_speed don't matter here # evaluate events at 10Hz for tests DS.update(e, driver_car_interaction[idx], openpilot_status[idx], car_standstill_status[idx]) diff --git a/selfdrive/crash.py b/selfdrive/crash.py index 000109dc90..a24466622e 100644 --- a/selfdrive/crash.py +++ b/selfdrive/crash.py @@ -11,10 +11,13 @@ from common.android import ANDROID if os.getenv("NOLOG") or os.getenv("NOCRASH") or not ANDROID: def capture_exception(*args, **kwargs): pass + def bind_user(**kwargs): pass + def bind_extra(**kwargs): pass + def install(): pass else: @@ -38,6 +41,7 @@ else: def install(): # installs a sys.excepthook __excepthook__ = sys.excepthook + def handle_exception(*exc_info): if exc_info[0] not in (KeyboardInterrupt, SystemExit): capture_exception() diff --git a/selfdrive/launcher.py b/selfdrive/launcher.py index 8253347d6b..dcedf07167 100644 --- a/selfdrive/launcher.py +++ b/selfdrive/launcher.py @@ -1,5 +1,5 @@ import importlib -from setproctitle import setproctitle #pylint: disable=no-name-in-module +from setproctitle import setproctitle # pylint: disable=no-name-in-module import cereal.messaging as messaging import selfdrive.crash as crash diff --git a/selfdrive/locationd/calibration_helpers.py b/selfdrive/locationd/calibration_helpers.py index f290900759..cdc0345f35 100644 --- a/selfdrive/locationd/calibration_helpers.py +++ b/selfdrive/locationd/calibration_helpers.py @@ -8,4 +8,3 @@ class Calibration: UNCALIBRATED = 0 CALIBRATED = 1 INVALID = 2 - diff --git a/selfdrive/locationd/test/ephemeris.py b/selfdrive/locationd/test/ephemeris.py index dd8155e19a..bca45c59e8 100644 --- a/selfdrive/locationd/test/ephemeris.py +++ b/selfdrive/locationd/test/ephemeris.py @@ -133,5 +133,3 @@ on of this parser self.ionoAlpha = [] self.ionoBeta = [] self.ionoCoeffsValid = False - - diff --git a/selfdrive/locationd/test/ublox.py b/selfdrive/locationd/test/ublox.py index d99e714696..b699a37211 100644 --- a/selfdrive/locationd/test/ublox.py +++ b/selfdrive/locationd/test/ublox.py @@ -12,7 +12,8 @@ for ublox version 8, not all functions may work. import struct -import time, os +import os +import time # protocol constants PREAMBLE1 = 0xb5 @@ -291,7 +292,7 @@ class UBloxDescriptor: fields = self.fields[:] for f in fields: (fieldname, alen) = ArrayParse(f) - if not fieldname in msg._fields: + if fieldname not in msg._fields: break if alen == -1: f1.append(msg._fields[fieldname]) @@ -327,7 +328,7 @@ class UBloxDescriptor: ret = self.name + ': ' for f in self.fields: (fieldname, alen) = ArrayParse(f) - if not fieldname in msg._fields: + if fieldname not in msg._fields: continue v = msg._fields[fieldname] if isinstance(v, list): @@ -591,7 +592,7 @@ class UBloxMessage: if not self.valid(): raise UBloxError('INVALID MESSAGE') type = self.msg_type() - if not type in msg_types: + if type not in msg_types: raise UBloxError('Unknown message %s length=%u' % (str(type), len(self._buf))) msg_types[type].unpack(self) return self._fields, self._recs @@ -601,7 +602,7 @@ class UBloxMessage: if not self.valid(): raise UBloxError('INVALID MESSAGE') type = self.msg_type() - if not type in msg_types: + if type not in msg_types: raise UBloxError('Unknown message %s' % str(type)) msg_types[type].pack(self) @@ -610,7 +611,7 @@ class UBloxMessage: if not self.valid(): raise UBloxError('INVALID MESSAGE') type = self.msg_type() - if not type in msg_types: + if type not in msg_types: raise UBloxError('Unknown message %s length=%u' % (str(type), len(self._buf))) return msg_types[type].name diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index 5dbe8cff45..6ba4c38a94 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -83,7 +83,7 @@ def configure_ublox(dev): def int_to_bool_list(num): # for parsing bool bytes - return [bool(num & (1<>4) + s += (c >> 4) s += c & 0xF s = 8-s s %= 0x10 @@ -45,7 +45,7 @@ def car_plant(pos, speed, grade, gas, brake): mass = 1700 aero_cd = 0.3 force_peak = mass*3. - force_brake_peak = -mass*10. #1g + force_brake_peak = -mass*10. # 1g power_peak = 100000 # 100kW speed_base = power_peak/force_peak rolling_res = 0.01 @@ -277,13 +277,13 @@ class Plant(): vls = vls_tuple( self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), - self.angle_steer, self.angle_steer_rate, 0, 0,#Steer torque sensor + self.angle_steer, self.angle_steer_rate, 0, 0, # Steer torque sensor 0, 0, # Blinkers self.gear_choice, speed != 0, self.brake_error, self.brake_error, not self.seatbelt, self.seatbelt, # Seatbelt - self.brake_pressed, 0., #Brake pressed, Brake switch + self.brake_pressed, 0., # Brake pressed, Brake switch cruise_buttons, self.esp_disabled, 0, # HUD lead @@ -339,9 +339,9 @@ class Plant(): # TODO: use the DBC if self.frame % 5 == 0: radar_state_msg = b'\x79\x00\x00\x00\x00\x00\x00\x00' - radar_msg = to_3_byte(d_rel*16.0) + \ - to_3_byte(int(lateral_pos_rel*16.0)&0x3ff) + \ - to_3s_byte(int(v_rel*32.0)) + \ + radar_msg = to_3_byte(d_rel * 16.0) + \ + to_3_byte(int(lateral_pos_rel * 16.0) & 0x3ff) + \ + to_3s_byte(int(v_rel * 32.0)) + \ b"0f00000" radar_msg = binascii.unhexlify(radar_msg) diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py index addcfa9310..985e59f87f 100755 --- a/selfdrive/test/process_replay/compare_logs.py +++ b/selfdrive/test/process_replay/compare_logs.py @@ -6,7 +6,8 @@ import numbers import dictdiffer if "CI" in os.environ: - tqdm = lambda x: x + def tqdm(x): + return x else: from tqdm import tqdm # type: ignore @@ -32,7 +33,7 @@ def remove_ignored_fields(msg, ignore): for k in keys[:-1]: try: attr = getattr(msg, k) - except: + except AttributeError: break else: v = getattr(attr, keys[-1]) @@ -46,8 +47,7 @@ def remove_ignored_fields(msg, ignore): return msg.as_reader() def compare_logs(log1, log2, ignore_fields=[], ignore_msgs=[]): - filter_msgs = lambda m: m.which() not in ignore_msgs - log1, log2 = [list(filter(filter_msgs, log)) for log in (log1, log2)] + log1, log2 = [list(filter(lambda m: m.which() not in ignore_msgs, log)) for log in (log1, log2)] assert len(log1) == len(log2), "logs are not same length: " + str(len(log1)) + " VS " + str(len(log2)) diff = [] diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 46eb5a09ef..d6fe5ef6f1 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -1,11 +1,13 @@ #!/usr/bin/env python3 +import capnp import os import sys import threading import importlib if "CI" in os.environ: - tqdm = lambda x: x + def tqdm(x): + return x else: from tqdm import tqdm # type: ignore @@ -110,7 +112,7 @@ class FakePubMaster(messaging.PubMaster): for s in services: try: data = messaging.new_message(s) - except: + except capnp.lib.capnp.KjException: data = messaging.new_message(s, 0) self.data[s] = data.as_reader() self.sock[s] = DumbSocket() diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index f9deac6713..6e4e111193 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -124,7 +124,7 @@ if __name__ == "__main__": process_replay_dir = os.path.dirname(os.path.abspath(__file__)) try: ref_commit = open(os.path.join(process_replay_dir, "ref_commit")).read().strip() - except: + except FileNotFoundError: print("couldn't find reference commit") sys.exit(1) @@ -139,7 +139,7 @@ if __name__ == "__main__": results: Any = {} for car_brand, segment in segments: if (cars_whitelisted and car_brand.upper() not in args.whitelist_cars) or \ - (not cars_whitelisted and car_brand.upper() in args.blacklist_cars): + (not cars_whitelisted and car_brand.upper() in args.blacklist_cars): continue print("***** testing route segment %s *****\n" % segment) @@ -151,7 +151,7 @@ if __name__ == "__main__": for cfg in CONFIGS: if (procs_whitelisted and cfg.proc_name not in args.whitelist_procs) or \ - (not procs_whitelisted and cfg.proc_name in args.blacklist_procs): + (not procs_whitelisted and cfg.proc_name in args.blacklist_procs): continue cmp_log_fn = os.path.join(process_replay_dir, "%s_%s_%s.bz2" % (segment, cfg.proc_name, ref_commit)) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 06d333094a..868115fb7b 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -261,7 +261,7 @@ routes = { 'enableCamera': True, 'enableDsu': False, }, - "7e34a988419b5307|2019-12-18--19-13-30": { + "7e34a988419b5307|2019-12-18--19-13-30": { 'carFingerprint': TOYOTA.RAV4H_TSS2, 'enableCamera': True, 'fingerprintSource': 'fixed' @@ -286,12 +286,12 @@ routes = { 'enableCamera': True, 'enableDsu': False, }, - "886fcd8408d570e9|2020-01-29--05-11-22": { + "886fcd8408d570e9|2020-01-29--05-11-22": { 'carFingerprint': TOYOTA.LEXUS_RX, 'enableCamera': True, 'enableDsu': True, }, - "886fcd8408d570e9|2020-01-29--02-18-55": { + "886fcd8408d570e9|2020-01-29--02-18-55": { 'carFingerprint': TOYOTA.LEXUS_RX, 'enableCamera': True, 'enableDsu': False, @@ -301,12 +301,12 @@ routes = { 'enableCamera': True, 'enableDsu': True, }, - "01b22eb2ed121565|2020-02-02--11-25-51": { + "01b22eb2ed121565|2020-02-02--11-25-51": { 'carFingerprint': TOYOTA.LEXUS_RX_TSS2, 'enableCamera': True, 'fingerprintSource': 'fixed', }, - "b74758c690a49668|2020-05-20--15-58-57": { + "b74758c690a49668|2020-05-20--15-58-57": { 'carFingerprint': TOYOTA.LEXUS_RXH_TSS2, 'enableCamera': True, 'fingerprintSource': 'fixed', diff --git a/selfdrive/test/test_leeco_alt_fan.py b/selfdrive/test/test_leeco_alt_fan.py index c14d943e2c..b1ab5c54d4 100755 --- a/selfdrive/test/test_leeco_alt_fan.py +++ b/selfdrive/test/test_leeco_alt_fan.py @@ -14,7 +14,7 @@ def setup_leon_fan(): bus.write_i2c_block_data(0x67, 0xa, [0]) else: bus.write_i2c_block_data(0x67, 0xa, [0x20]) - bus.write_i2c_block_data(0x67, 0x8, [(i-1)<<6]) + bus.write_i2c_block_data(0x67, 0x8, [(i - 1) << 6]) time.sleep(1) bus.close() diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 1d69547cd4..5d97141cb2 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -100,7 +100,7 @@ def set_eon_fan(val): else: #bus.write_i2c_block_data(0x67, 0x45, [0]) bus.write_i2c_block_data(0x67, 0xa, [0x20]) - bus.write_i2c_block_data(0x67, 0x8, [(val-1)<<6]) + bus.write_i2c_block_data(0x67, 0x8, [(val - 1) << 6]) else: bus.write_byte_data(0x21, 0x04, 0x2) bus.write_byte_data(0x21, 0x03, (val*2)+1) diff --git a/tools/carcontrols/joystick_test.py b/tools/carcontrols/joystick_test.py index 1a41d4729c..2f008af14a 100755 --- a/tools/carcontrols/joystick_test.py +++ b/tools/carcontrols/joystick_test.py @@ -51,7 +51,7 @@ pygame.joystick.init() textPrint = TextPrint() # -------- Main Program Loop ----------- -while done==False: +while not done: # EVENT PROCESSING STEP for event in pygame.event.get(): # User did something if event.type == pygame.QUIT: # If user clicked close @@ -122,4 +122,4 @@ while done==False: # Close the window and quit. # If you forget this line, the program will 'hang' # on exit if running from IDLE. -pygame.quit () +pygame.quit() diff --git a/tools/lib/route.py b/tools/lib/route.py index 2a5ab5e4ac..3060741541 100644 --- a/tools/lib/route.py +++ b/tools/lib/route.py @@ -111,10 +111,12 @@ class RouteSegment(object): self.camera_path = camera_path @property - def name(self): return str(self._name) + def name(self): + return str(self._name) @property - def canonical_name(self): return self._name + def canonical_name(self): + return self._name class RouteSegmentName(object): def __init__(self, name_str): @@ -123,6 +125,8 @@ class RouteSegmentName(object): self._num = int(num_str) @property - def segment_num(self): return self._num + def segment_num(self): + return self._num - def __str__(self): return self._segment_name_str + def __str__(self): + return self._segment_name_str diff --git a/tools/lib/route_framereader.py b/tools/lib/route_framereader.py index 47250383c5..2045a4b4c6 100644 --- a/tools/lib/route_framereader.py +++ b/tools/lib/route_framereader.py @@ -82,5 +82,8 @@ class RouteFrameReader(object): for fr in frs: fr.close() - def __enter__(self): return self - def __exit__(self, type, value, traceback): self.close() + def __enter__(self): + return self + + def __exit__(self, type, value, traceback): + self.close() diff --git a/tools/replay/lib/ui_helpers.py b/tools/replay/lib/ui_helpers.py index 78cbefddf5..44fdb2c0f9 100644 --- a/tools/replay/lib/ui_helpers.py +++ b/tools/replay/lib/ui_helpers.py @@ -73,7 +73,7 @@ def draw_path(y, x, color, img, calibration, top_down, lid_color=None): uv_model > 0, axis=1), uv_model[:, 0] < img.shape[1] - 1, uv_model[:, 1] < img.shape[0] - 1))] - for i, j in ((-1, 0), (0, -1), (0, 0), (0, 1), (1, 0)): + for i, j in ((-1, 0), (0, -1), (0, 0), (0, 1), (1, 0)): img[uv_model_dots[:, 1] + i, uv_model_dots[:, 0] + j] = color # draw lidar path point on lidar @@ -88,12 +88,12 @@ def draw_path(y, x, color, img, calibration, top_down, lid_color=None): def draw_steer_path(speed_ms, curvature, color, img, calibration, top_down, VM, lid_color=None): path_x = np.arange(101.) - path_y = np.multiply(path_x, np.tan(np.arcsin(np.clip(path_x * curvature, -0.999, 0.999)) / 2.)) + path_y = np.multiply(path_x, np.tan(np.arcsin(np.clip(path_x * curvature, -0.999, 0.999)) / 2.)) draw_path(path_y, path_x, color, img, calibration, top_down, lid_color) def draw_lead_car(closest, top_down): - if closest != None: + if closest is not None: closest_y = int(round(UP.lidar_car_y - closest * UP.lidar_zoom)) if closest_y > 0: top_down[1][int(round(UP.lidar_car_x - METER_WIDTH * 2)):int( @@ -118,12 +118,10 @@ def init_plots(arr, name_to_arr_idx, plot_xlims, plot_ylims, plot_names, plot_co "p": (0,1,1), "m": (1,0,1) } - if bigplots == True: + if bigplots: fig = plt.figure(figsize=(6.4, 7.0)) - elif bigplots == False: - fig = plt.figure() else: - fig = plt.figure(figsize=bigplots) + fig = plt.figure() fig.set_facecolor((0.2,0.2,0.2)) @@ -135,7 +133,7 @@ def init_plots(arr, name_to_arr_idx, plot_xlims, plot_ylims, plot_names, plot_co ax.patch.set_facecolor((0.4, 0.4, 0.4)) axs.append(ax) - plots = [] ;idxs = [] ;plot_select = [] + plots, idxs, plot_select = [], [], [] for i, pl_list in enumerate(plot_names): for j, item in enumerate(pl_list): plot, = axs[i].plot(arr[:, name_to_arr_idx[item]], diff --git a/tools/replay/unlogger.py b/tools/replay/unlogger.py index 3463660e86..4b71d2a148 100755 --- a/tools/replay/unlogger.py +++ b/tools/replay/unlogger.py @@ -341,15 +341,19 @@ def get_arg_parser(): parser.add_argument("route_name", type=(lambda x: x.replace("#", "|")), nargs="?", help="The route whose messages will be published.") parser.add_argument("data_dir", nargs='?', default=os.getenv('UNLOGGER_DATA_DIR'), - help="Path to directory in which log and camera files are located.") + help="Path to directory in which log and camera files are located.") parser.add_argument("--no-loop", action="store_true", help="Stop at the end of the replay.") - key_value_pair = lambda x: x.split("=") + def key_value_pair(x): + return x.split("=") + parser.add_argument("address_mapping", nargs="*", type=key_value_pair, help="Pairs = to publish on .") - comma_list = lambda x: x.split(",") + def comma_list(x): + return x.split(",") + to_mock_group = parser.add_mutually_exclusive_group() to_mock_group.add_argument("--min", action="store_true", default=os.getenv("MIN")) to_mock_group.add_argument("--enabled", default=os.getenv("ENABLED"), type=comma_list) diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index b0ea6fa7cb..3c402c4150 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -200,7 +200,7 @@ def go(q): speed = math.sqrt(vel.x**2 + vel.y**2 + vel.z**2) * 3.6 can_function(pm, speed, fake_wheel.angle, rk.frame, cruise_button=cruise_button, is_engaged=is_openpilot_engaged) - if rk.frame%1 == 0: # 20Hz? + if rk.frame % 1 == 0: # 20Hz? throttle_op, brake_op, steer_torque_op = sendcan_function(sendcan) # print(" === torq, ",steer_torque_op, " ===") if is_openpilot_engaged: diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index 9fbb2006f1..5e206e3378 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -28,8 +28,8 @@ def can_function(pm, speed, angle, idx, cruise_button=0, is_engaged=False): msg.append(packer.make_can_msg("SCM_BUTTONS", 0, {"CRUISE_BUTTONS": cruise_button}, idx)) - values = {"COUNTER_PEDAL": idx&0xF} - checksum = crc8_pedal(packer.make_can_msg("GAS_SENSOR", 0, {"COUNTER_PEDAL": idx&0xF}, -1)[2][:-1]) + values = {"COUNTER_PEDAL": idx & 0xF} + checksum = crc8_pedal(packer.make_can_msg("GAS_SENSOR", 0, {"COUNTER_PEDAL": idx & 0xF}, -1)[2][:-1]) values["CHECKSUM_PEDAL"] = checksum msg.append(packer.make_can_msg("GAS_SENSOR", 0, values, -1)) @@ -56,7 +56,7 @@ def can_function(pm, speed, angle, idx, cruise_button=0, is_engaged=False): msg.append(packer.make_can_msg("BRAKE_COMMAND", 2, {}, idx)) # radar - if idx%5 == 0: + if idx % 5 == 0: msg.append(rpacker.make_can_msg("RADAR_DIAGNOSTIC", 1, {"RADAR_STATE": 0x79}, -1)) for i in range(16): msg.append(rpacker.make_can_msg("TRACK_%d" % i, 1, {"LONG_DIST": 255.5}, -1)) diff --git a/tools/sim/lib/manual_ctrl.py b/tools/sim/lib/manual_ctrl.py index 6e7fe6e6a2..6d66097df9 100755 --- a/tools/sim/lib/manual_ctrl.py +++ b/tools/sim/lib/manual_ctrl.py @@ -1,6 +1,8 @@ #!/usr/bin/env python3 # set up wheel -import os, struct, array +import array +import os +import struct from fcntl import ioctl # Iterate over the joystick devices. diff --git a/tools/webcam/accept_terms.py b/tools/webcam/accept_terms.py index e7757511d8..a5445a5719 100755 --- a/tools/webcam/accept_terms.py +++ b/tools/webcam/accept_terms.py @@ -6,4 +6,4 @@ if __name__ == '__main__': params = Params() params.put("HasAcceptedTerms", str(terms_version, 'utf-8')) params.put("CompletedTrainingVersion", str(training_version, 'utf-8')) - print("Terms Accepted!") \ No newline at end of file + print("Terms Accepted!") From 9fc826cb5c6fc46ebd0fe5c1ecd322a472da44ef Mon Sep 17 00:00:00 2001 From: Andre Volmensky Date: Sun, 31 May 2020 12:25:32 +0900 Subject: [PATCH 150/656] Added Rogue 2019/Leaf 2019 fingerprints (#1605) * Added Rogue 2019/Leaf 2019 fingerprints * Added Rogue as new car. Updated readme * Added route to test_car_models.py. Fixed if statements to check against rogue/x-trail * Fixed paste error * Merged Leaf fingerprints * Assume Rogue is MPH until we work out the mph/kph bit --- README.md | 3 ++- selfdrive/car/nissan/carcontroller.py | 2 +- selfdrive/car/nissan/carstate.py | 14 ++++++++------ selfdrive/car/nissan/interface.py | 2 +- selfdrive/car/nissan/values.py | 9 ++++++++- selfdrive/test/test_car_models.py | 4 ++++ 6 files changed, 24 insertions(+), 10 deletions(-) diff --git a/README.md b/README.md index b1bd090e94..80c48babee 100644 --- a/README.md +++ b/README.md @@ -153,7 +153,8 @@ Community Maintained Cars and Features | Kia | Optima 20192 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Sorento 20182 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Stinger 20182 | SCC + LKAS | Stock | 0mph | 0mph | -| Nissan | Leaf 20182 | Propilot | Stock | 0mph | 0mph | +| Nissan | Leaf 2018-192 | Propilot | Stock | 0mph | 0mph | +| Nissan | Rogue 20192 | Propilot | Stock | 0mph | 0mph | | Nissan | X-Trail 20172 | Propilot | Stock | 0mph | 0mph | | Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | | Subaru | Impreza 2018-20 | EyeSight | Stock | 0mph | 0mph | diff --git a/selfdrive/car/nissan/carcontroller.py b/selfdrive/car/nissan/carcontroller.py index 56e2ae7522..5d988cb935 100644 --- a/selfdrive/car/nissan/carcontroller.py +++ b/selfdrive/car/nissan/carcontroller.py @@ -65,7 +65,7 @@ class CarController(): # send acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated cruise_cancel = 1 - if self.CP.carFingerprint == CAR.XTRAIL and cruise_cancel: + if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL] and cruise_cancel: can_sends.append(nissancan.create_acc_cancel_cmd(self.packer, CS.cruise_throttle_msg, frame)) # TODO: Find better way to cancel! diff --git a/selfdrive/car/nissan/carstate.py b/selfdrive/car/nissan/carstate.py index 849e89b731..45156a8cb9 100644 --- a/selfdrive/car/nissan/carstate.py +++ b/selfdrive/car/nissan/carstate.py @@ -17,19 +17,19 @@ class CarState(CarStateBase): def update(self, cp, cp_adas, cp_cam): ret = car.CarState.new_message() - if self.CP.carFingerprint == CAR.XTRAIL: + if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL]: ret.gas = cp.vl["GAS_PEDAL"]["GAS_PEDAL"] elif self.CP.carFingerprint == CAR.LEAF: ret.gas = cp.vl["CRUISE_THROTTLE"]["GAS_PEDAL"] ret.gasPressed = bool(ret.gas > 3) - if self.CP.carFingerprint == CAR.XTRAIL: + if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL]: ret.brakePressed = bool(cp.vl["DOORS_LIGHTS"]["USER_BRAKE_PRESSED"]) elif self.CP.carFingerprint == CAR.LEAF: ret.brakePressed = bool(cp.vl["BRAKE_PEDAL"]["BRAKE_PEDAL"] > 3) - if self.CP.carFingerprint == CAR.XTRAIL: + if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL]: ret.brakeLights = bool(cp.vl["DOORS_LIGHTS"]["BRAKE_LIGHT"]) ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FL"] * CV.KPH_TO_MS @@ -43,7 +43,7 @@ class CarState(CarStateBase): ret.standstill = ret.vEgoRaw < 0.01 ret.cruiseState.enabled = bool(cp_adas.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) - if self.CP.carFingerprint == CAR.XTRAIL: + if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL]: ret.cruiseState.available = bool(cp_cam.vl["PRO_PILOT"]["CRUISE_ON"]) elif self.CP.carFingerprint == CAR.LEAF: ret.cruiseState.available = bool(cp.vl["CRUISE_THROTTLE"]["CRUISE_AVAILABLE"]) @@ -54,6 +54,8 @@ class CarState(CarStateBase): if speed != 255: if self.CP.carFingerprint == CAR.XTRAIL: conversion = CV.KPH_TO_MS + elif self.CP.carFingerprint == CAR.ROGUE: + conversion = CV.MPH_TO_MS else: conversion = CV.MPH_TO_MS if cp.vl["HUD_SETTINGS"]["SPEED_MPH"] else CV.KPH_TO_MS speed -= 1 # Speed on HUD is always 1 lower than actually sent on can bus @@ -129,7 +131,7 @@ class CarState(CarStateBase): ("DOORS_LIGHTS", 10), ] - if CP.carFingerprint == CAR.XTRAIL: + if CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL]: signals += [ ("USER_BRAKE_PRESSED", "DOORS_LIGHTS", 1), ("BRAKE_LIGHT", "DOORS_LIGHTS", 1), @@ -271,7 +273,7 @@ class CarState(CarStateBase): @staticmethod def get_cam_can_parser(CP): signals = [] - if CP.carFingerprint == CAR.XTRAIL: + if CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL]: signals += [ ("CRUISE_ON", "PRO_PILOT", 0), ] diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index 34aeb13e65..319228da37 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -34,7 +34,7 @@ class CarInterface(CarInterfaceBase): ret.steerMaxBP = [0.] # m/s ret.steerMaxV = [1.] - if candidate == CAR.XTRAIL: + if candidate in [CAR.ROGUE, CAR.XTRAIL]: ret.mass = 1610 + STD_CARGO_KG ret.wheelbase = 2.705 ret.centerToFront = ret.wheelbase * 0.44 diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 96777e5a44..4d1d1b932c 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -5,6 +5,7 @@ STEER_THRESHOLD = 1.0 class CAR: XTRAIL = "NISSAN X-TRAIL 2017" LEAF = "NISSAN LEAF 2018" + ROGUE = "NISSAN ROGUE 2019" FINGERPRINTS = { @@ -18,12 +19,18 @@ FINGERPRINTS = { ], CAR.LEAF: [ { - 2: 5, 42: 6, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 944: 1, 976: 6, 1008: 7, 1011: 7, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8, 1856: 8, 1859: 8, 1861: 8, 1864: 8, 1874: 8, 1888: 8, 1891: 8, 1893: 8, 1906: 8, 1947: 8, 1949: 8, 1979: 8, 1981: 8, 2016: 8, 2017: 8, 2021: 8 + 2: 5, 42: 6, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 944: 1, 976: 6, 1008: 7, 1011: 7, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8, 1856: 8, 1859: 8, 1861: 8, 1864: 8, 1874: 8, 1888: 8, 1891: 8, 1893: 8, 1906: 8, 1947: 8, 1949: 8, 1979: 8, 1981: 8, 2016: 8, 2017: 8, 2021: 8, 643: 5, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8 }, ], + CAR.ROGUE: [ + { + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 634: 7, 643: 5, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1042: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1534: 7, 1821: 8, 1823: 8, 1837: 8, 1839: 8 + }, + ] } DBC = { CAR.XTRAIL: dbc_dict('nissan_x_trail_2017', None), CAR.LEAF: dbc_dict('nissan_leaf_2018', None), + CAR.ROGUE: dbc_dict('nissan_x_trail_2017', None), } diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 868115fb7b..69b376ee94 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -367,6 +367,10 @@ routes = { 'carFingerprint': MAZDA.CX5, 'enableCamera': True, }, + "059ab9162e23198e|2020-05-30--09-41-01": { + 'carFingerprint': NISSAN.ROGUE, + 'enableCamera': True, + }, } passive_routes: List[str] = [ From b08fff33a0d8e05cb0941c69ecbc0bbff89783c6 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sat, 30 May 2020 20:27:15 -0700 Subject: [PATCH 151/656] Update Nissan years in release notes --- RELEASES.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 6ff8d9e447..4f502fd4ff 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,7 +1,7 @@ Version 0.7.6 (2020-06-05) ======================== * White panda is deprecated, upgrade to comma two or black panda -* 2017 Nissan X-Trail and 2018 Nissan Leaf support thanks to avolmensky! +* 2017 Nissan X-Trail, 2018-19 Leaf and 2019 Rogue support thanks to avolmensky! * 2017 Mazda CX-5 support in dashcam mode thanks to Jafaral! * Huge CPU savings in modeld by using thneed! * Lots of code cleanup and refactors From 6051061ff8e7809960cc1f2bad9a582801d5a83e Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Sun, 31 May 2020 00:48:47 -0700 Subject: [PATCH 152/656] Flake8 E22X (#1607) * e221 * e225 * bump opendbc --- .pre-commit-config.yaml | 2 +- common/stat_live.py | 2 +- common/transformations/orientation.py | 4 +- opendbc | 2 +- selfdrive/camerad/test/frame_test.py | 2 +- selfdrive/car/chrysler/chryslercan.py | 2 +- selfdrive/car/ford/interface.py | 2 +- selfdrive/car/ford/radar_interface.py | 2 +- selfdrive/car/gm/gmcan.py | 2 +- selfdrive/car/gm/values.py | 24 +++++----- selfdrive/car/honda/values.py | 8 ++-- selfdrive/car/mazda/mazdacan.py | 8 ++-- selfdrive/car/toyota/radar_interface.py | 4 +- selfdrive/config.py | 2 +- selfdrive/controls/lib/driver_monitor.py | 6 +-- selfdrive/controls/lib/latcontrol_indi.py | 2 +- selfdrive/controls/lib/planner.py | 2 +- selfdrive/controls/tests/test_monitoring.py | 44 +++++++++---------- selfdrive/debug/mpc/live_lateral_mpc.py | 8 ++-- selfdrive/locationd/test/ubloxd.py | 2 +- .../test/longitudinal_maneuvers/plant.py | 2 +- .../test/process_replay/process_replay.py | 2 +- tools/carcontrols/joystick_test.py | 6 +-- tools/replay/unlogger.py | 14 +++--- 24 files changed, 77 insertions(+), 77 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 020c7e9e7f..33a34be665 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,7 +17,7 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E221,E225,E226,E231,E241,E251,E261,E265,E266,E302,E303,E305,E402,E501,E502,E722,E741,W504 + - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E231,E241,E251,E261,E265,E266,E302,E303,E305,E402,E501,E502,E722,E741,W504 - --statistics - repo: local hooks: diff --git a/common/stat_live.py b/common/stat_live.py index bab982888d..a91c1819bb 100644 --- a/common/stat_live.py +++ b/common/stat_live.py @@ -64,7 +64,7 @@ class RunningStatFilter(): _std_last = self.raw_stat.std() self.raw_stat.push_data(new_data) _delta_std = self.raw_stat.std() - _std_last - if _delta_std<=0: + if _delta_std <= 0: self.filtered_stat.push_data(new_data) else: pass diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py index acbd4a2bf3..ee7335d3ec 100644 --- a/common/transformations/orientation.py +++ b/common/transformations/orientation.py @@ -124,8 +124,8 @@ def rot2euler(rots): quats_from_rotations = rot2quat quat_from_rot = rot2quat rotations_from_quats = quat2rot -rot_from_quat= quat2rot -rot_from_quat= quat2rot +rot_from_quat = quat2rot +rot_from_quat = quat2rot euler_from_rot = rot2euler euler_from_quat = quat2euler rot_from_euler = euler2rot diff --git a/opendbc b/opendbc index b15edbc1b5..73685b609d 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit b15edbc1b5a68fd725ea45ba9442a6c9be875971 +Subproject commit 73685b609d25cfc8f838d53f69cf78e136c612c2 diff --git a/selfdrive/camerad/test/frame_test.py b/selfdrive/camerad/test/frame_test.py index 6b8b99ae81..095a20a7cb 100755 --- a/selfdrive/camerad/test/frame_test.py +++ b/selfdrive/camerad/test/frame_test.py @@ -6,7 +6,7 @@ from PIL import ImageFont, ImageDraw, Image font = ImageFont.truetype("arial", size=72) def get_frame(idx): img = np.zeros((874, 1164, 3), np.uint8) - img[100:400, 100:100+(idx % 10)* 100] = 255 + img[100:400, 100:100+(idx % 10) * 100] = 255 # big number im2 = Image.new("RGB", (200,200)) diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index bf9f3731f6..63d1fbe0b4 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -16,7 +16,7 @@ def create_lkas_hud(packer, gear, lkas_active, hud_alert, hud_count, lkas_car_mo lines = 1 alerts = 0 - if hud_count < (1 *4): # first 3 seconds, 4Hz + if hud_count < (1 * 4): # first 3 seconds, 4Hz alerts = 1 # CAR.PACIFICA_2018_HYBRID and CAR.PACIFICA_2019_HYBRID # had color = 1 and lines = 1 but trying 2017 hybrid style for now. diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index 4388ae7962..0c1ce863c5 100755 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -60,7 +60,7 @@ class CarInterface(CarInterfaceBase): # events events = self.create_common_events(ret) - if self.CS.lkas_state not in [2, 3] and ret.vEgo > 13.* CV.MPH_TO_MS and ret.cruiseState.enabled: + if self.CS.lkas_state not in [2, 3] and ret.vEgo > 13. * CV.MPH_TO_MS and ret.cruiseState.enabled: events.add(car.CarEvent.EventName.steerTempUnavailableMute) ret.events = events.to_msg() diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index 3733ddce7f..100855eacb 100755 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -50,7 +50,7 @@ class RadarInterface(RadarInterfaceBase): if cpt['X_Rel'] > 0.00001: self.validCnt[ii] += 1 else: - self.validCnt[ii] = max(self.validCnt[ii] -1, 0) + self.validCnt[ii] = max(self.validCnt[ii] - 1, 0) #print ii, self.validCnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] # radar point only valid if there have been enough valid measurements diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py index 67acb7c487..7b146f6804 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/selfdrive/car/gm/gmcan.py @@ -28,7 +28,7 @@ def create_gas_regen_command(packer, bus, throttle, idx, acc_engaged, at_full_st } dat = packer.make_can_msg("ASCMGasRegenCmd", bus, values)[2] - values["GasRegenChecksum"] = (((0xff -dat[1]) & 0xff) << 16) | \ + values["GasRegenChecksum"] = (((0xff - dat[1]) & 0xff) << 16) | \ (((0xff - dat[2]) & 0xff) << 8) | \ ((0x100 - dat[3] - idx) & 0xff) diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 6a35c17c9b..c2bc7e01e1 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -11,24 +11,24 @@ class CAR: BUICK_REGAL = "BUICK REGAL ESSENCE 2018" class CruiseButtons: - INIT = 0 - UNPRESS = 1 - RES_ACCEL = 2 - DECEL_SET = 3 - MAIN = 5 - CANCEL = 6 + INIT = 0 + UNPRESS = 1 + RES_ACCEL = 2 + DECEL_SET = 3 + MAIN = 5 + CANCEL = 6 class AccState: - OFF = 0 - ACTIVE = 1 - FAULTED = 3 + OFF = 0 + ACTIVE = 1 + FAULTED = 3 STANDSTILL = 4 class CanBus: POWERTRAIN = 0 - OBSTACLE = 1 - CHASSIS = 2 - SW_GMLAN = 3 + OBSTACLE = 1 + CHASSIS = 2 + SW_GMLAN = 3 def is_eps_status_ok(eps_status, car_fingerprint): return eps_status in [0, 1] diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index c9933e2a1c..af52cae087 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -6,10 +6,10 @@ VisualAlert = car.CarControl.HUDControl.VisualAlert # Car button codes class CruiseButtons: - RES_ACCEL = 4 - DECEL_SET = 3 - CANCEL = 2 - MAIN = 1 + RES_ACCEL = 4 + DECEL_SET = 3 + CANCEL = 2 + MAIN = 1 # See dbc files for info on values" VISUAL_HUD = { diff --git a/selfdrive/car/mazda/mazdacan.py b/selfdrive/car/mazda/mazdacan.py index 5728bfed93..55b9218dbd 100644 --- a/selfdrive/car/mazda/mazdacan.py +++ b/selfdrive/car/mazda/mazdacan.py @@ -9,22 +9,22 @@ def create_steering_control(packer, car_fingerprint, frame, apply_steer, lkas): b1 = int(lkas["BIT_1"]) ldw = int(lkas["LDW"]) - er1= int(lkas["ERR_BIT_1"]) + er1 = int(lkas["ERR_BIT_1"]) lnv = 0 - er2= int(lkas["ERR_BIT_2"]) + er2 = int(lkas["ERR_BIT_2"]) steering_angle = int(lkas["STEERING_ANGLE"]) b2 = int(lkas["ANGLE_ENABLED"]) tmp = steering_angle + 2048 ahi = tmp >> 10 - amd = (tmp & 0x3FF) >> 2 + amd = (tmp & 0x3FF) >> 2 amd = (amd >> 4) | (( amd & 0xF) << 4) alo = (tmp & 0x3) << 2 ctr = frame % 16 # bytes: [ 1 ] [ 2 ] [ 3 ] [ 4 ] - csum = 249 - ctr - hi - lo - (lnv << 3) - er1 - (ldw << 7) - ( er2 << 4) - (b1 << 5) + csum = 249 - ctr - hi - lo - (lnv << 3) - er1 - (ldw << 7) - ( er2 << 4) - (b1 << 5) #bytes [ 5 ] [ 6 ] [ 7 ] csum = csum - ahi - amd - alo - b2 diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py index b831b005de..3a66beed0e 100755 --- a/selfdrive/car/toyota/radar_interface.py +++ b/selfdrive/car/toyota/radar_interface.py @@ -78,12 +78,12 @@ class RadarInterface(RadarInterfaceBase): if ii in self.RADAR_A_MSGS: cpt = self.rcp.vl[ii] - if cpt['LONG_DIST'] >=255 or cpt['NEW_TRACK']: + if cpt['LONG_DIST'] >= 255 or cpt['NEW_TRACK']: self.valid_cnt[ii] = 0 # reset counter if cpt['VALID'] and cpt['LONG_DIST'] < 255: self.valid_cnt[ii] += 1 else: - self.valid_cnt[ii] = max(self.valid_cnt[ii] -1, 0) + self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) score = self.rcp.vl[ii+16]['SCORE'] # print ii, self.valid_cnt[ii], score, cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] diff --git a/selfdrive/config.py b/selfdrive/config.py index 0e18c31f49..2a89580889 100644 --- a/selfdrive/config.py +++ b/selfdrive/config.py @@ -25,5 +25,5 @@ class UIParams: lidar_car_x, lidar_car_y = lidar_x/2., lidar_y/1.1 car_hwidth = 1.7272/2 * lidar_zoom car_front = 2.6924 * lidar_zoom - car_back = 1.8796 * lidar_zoom + car_back = 1.8796 * lidar_zoom car_color = 110 diff --git a/selfdrive/controls/lib/driver_monitor.py b/selfdrive/controls/lib/driver_monitor.py index 54785df073..b6a5cee9a3 100644 --- a/selfdrive/controls/lib/driver_monitor.py +++ b/selfdrive/controls/lib/driver_monitor.py @@ -189,8 +189,8 @@ class DriverStatus(): # self.pose.roll_std = driver_state.faceOrientationStd[2] model_std_max = max(self.pose.pitch_std, self.pose.yaw_std) self.pose.low_std = model_std_max < _POSESTD_THRESHOLD - self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb>_EYE_THRESHOLD) - self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb>_EYE_THRESHOLD) + self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb > _EYE_THRESHOLD) + self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb > _EYE_THRESHOLD) self.face_detected = driver_state.faceProb > _FACE_THRESHOLD and \ abs(driver_state.facePosition[0]) <= 0.4 and abs(driver_state.facePosition[1]) <= 0.45 @@ -200,7 +200,7 @@ class DriverStatus(): # update offseter # only update when driver is actively driving the car above a certain speed - if self.face_detected and car_speed>_POSE_CALIB_MIN_SPEED and self.pose.low_std and (not op_engaged or not self.driver_distracted): + if self.face_detected and car_speed > _POSE_CALIB_MIN_SPEED and self.pose.low_std and (not op_engaged or not self.driver_distracted): self.pose.pitch_offseter.push_and_update(self.pose.pitch) self.pose.yaw_offseter.push_and_update(self.pose.yaw) diff --git a/selfdrive/controls/lib/latcontrol_indi.py b/selfdrive/controls/lib/latcontrol_indi.py index 2b41dc6f7e..8371d5ad3c 100644 --- a/selfdrive/controls/lib/latcontrol_indi.py +++ b/selfdrive/controls/lib/latcontrol_indi.py @@ -116,7 +116,7 @@ class LatControlINDI(): indi_log.delta = float(delta_u) indi_log.output = float(self.output_steer) - check_saturation = (CS.vEgo> 10.) and not CS.steeringRateLimited and not CS.steeringPressed + check_saturation = (CS.vEgo > 10.) and not CS.steeringRateLimited and not CS.steeringPressed indi_log.saturated = self._check_saturation(self.output_steer, check_saturation, steers_max) return float(self.output_steer), float(self.angle_steers_des), indi_log diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index e88a8fe11b..141de4c5df 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -23,7 +23,7 @@ AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distract # lookup tables VS speed to determine min and max accels in cruise # make sure these accelerations are smaller than mpc limits -_A_CRUISE_MIN_V = [-1.0, -.8, -.67, -.5, -.30] +_A_CRUISE_MIN_V = [-1.0, -.8, -.67, -.5, -.30] _A_CRUISE_MIN_BP = [ 0., 5., 10., 20., 40.] # need fast accel at very low speed for stop and go diff --git a/selfdrive/controls/tests/test_monitoring.py b/selfdrive/controls/tests/test_monitoring.py index 93a3b553c5..fce87af872 100644 --- a/selfdrive/controls/tests/test_monitoring.py +++ b/selfdrive/controls/tests/test_monitoring.py @@ -77,29 +77,29 @@ class TestMonitoring(unittest.TestCase): # 0. op engaged, driver is doing fine all the time def test_fully_aware_driver(self): events_output = run_DState_seq(always_attentive, always_false, always_true, always_false)[0] - self.assertTrue(np.sum([len(event) for event in events_output])==0) + self.assertTrue(np.sum([len(event) for event in events_output]) == 0) # 1. op engaged, driver is distracted and does nothing def test_fully_distracted_driver(self): events_output, d_status = run_DState_seq(always_distracted, always_false, always_true, always_false) - self.assertTrue(len(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PRE_TIME_TILL_TERMINAL)/2/DT_DMON)])==0) - self.assertEqual(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PRE_TIME_TILL_TERMINAL+\ + self.assertTrue(len(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PRE_TIME_TILL_TERMINAL)/2/DT_DMON)]) == 0) + self.assertEqual(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PRE_TIME_TILL_TERMINAL +\ ((_DISTRACTED_PRE_TIME_TILL_TERMINAL-_DISTRACTED_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0], EventName.preDriverDistracted) - self.assertEqual(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PROMPT_TIME_TILL_TERMINAL+\ + self.assertEqual(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PROMPT_TIME_TILL_TERMINAL +\ ((_DISTRACTED_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0], EventName.promptDriverDistracted) - self.assertEqual(events_output[int((_DISTRACTED_TIME+\ + self.assertEqual(events_output[int((_DISTRACTED_TIME +\ ((_TEST_TIMESPAN-10-_DISTRACTED_TIME)/2))/DT_DMON)].names[0], EventName.driverDistracted) self.assertIs(type(d_status.awareness), float) # 2. op engaged, no face detected the whole time, no action def test_fully_invisible_driver(self): events_output = run_DState_seq(always_no_face, always_false, always_true, always_false)[0] - self.assertTrue(len(events_output[int((_AWARENESS_TIME-_AWARENESS_PRE_TIME_TILL_TERMINAL)/2/DT_DMON)])==0) - self.assertEqual(events_output[int((_AWARENESS_TIME-_AWARENESS_PRE_TIME_TILL_TERMINAL+\ + self.assertTrue(len(events_output[int((_AWARENESS_TIME-_AWARENESS_PRE_TIME_TILL_TERMINAL)/2/DT_DMON)]) == 0) + self.assertEqual(events_output[int((_AWARENESS_TIME-_AWARENESS_PRE_TIME_TILL_TERMINAL +\ ((_AWARENESS_PRE_TIME_TILL_TERMINAL-_AWARENESS_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0], EventName.preDriverUnresponsive) - self.assertEqual(events_output[int((_AWARENESS_TIME-_AWARENESS_PROMPT_TIME_TILL_TERMINAL+\ + self.assertEqual(events_output[int((_AWARENESS_TIME-_AWARENESS_PROMPT_TIME_TILL_TERMINAL +\ ((_AWARENESS_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0], EventName.promptDriverUnresponsive) - self.assertEqual(events_output[int((_AWARENESS_TIME+\ + self.assertEqual(events_output[int((_AWARENESS_TIME +\ ((_TEST_TIMESPAN-10-_AWARENESS_TIME)/2))/DT_DMON)].names[0], EventName.driverUnresponsive) # 3. op engaged, down to orange, driver pays attention, back to normal; then down to orange, driver touches wheel @@ -111,11 +111,11 @@ class TestMonitoring(unittest.TestCase): interaction_vector = [car_interaction_NOT_DETECTED] * int(_DISTRACTED_SECONDS_TO_ORANGE*3/DT_DMON) + \ [car_interaction_DETECTED] * (int(_TEST_TIMESPAN/DT_DMON)-int(_DISTRACTED_SECONDS_TO_ORANGE*3/DT_DMON)) events_output = run_DState_seq(ds_vector, interaction_vector, always_true, always_false)[0] - self.assertTrue(len(events_output[int(_DISTRACTED_SECONDS_TO_ORANGE*0.5/DT_DMON)])==0) + self.assertTrue(len(events_output[int(_DISTRACTED_SECONDS_TO_ORANGE*0.5/DT_DMON)]) == 0) self.assertEqual(events_output[int((_DISTRACTED_SECONDS_TO_ORANGE-0.1)/DT_DMON)].names[0], EventName.promptDriverDistracted) - self.assertTrue(len(events_output[int(_DISTRACTED_SECONDS_TO_ORANGE*1.5/DT_DMON)])==0) + self.assertTrue(len(events_output[int(_DISTRACTED_SECONDS_TO_ORANGE*1.5/DT_DMON)]) == 0) self.assertEqual(events_output[int((_DISTRACTED_SECONDS_TO_ORANGE*3-0.1)/DT_DMON)].names[0], EventName.promptDriverDistracted) - self.assertTrue(len(events_output[int((_DISTRACTED_SECONDS_TO_ORANGE*3+0.1)/DT_DMON)])==0) + self.assertTrue(len(events_output[int((_DISTRACTED_SECONDS_TO_ORANGE*3+0.1)/DT_DMON)]) == 0) # 4. op engaged, down to orange, driver dodges camera, then comes back still distracted, down to red, \ # driver dodges, and then touches wheel to no avail, disengages and reengages @@ -133,7 +133,7 @@ class TestMonitoring(unittest.TestCase): self.assertEqual(events_output[int((_DISTRACTED_SECONDS_TO_ORANGE+0.5*_invisible_time)/DT_DMON)].names[0], EventName.promptDriverDistracted) self.assertEqual(events_output[int((_DISTRACTED_SECONDS_TO_RED+1.5*_invisible_time)/DT_DMON)].names[0], EventName.driverDistracted) self.assertEqual(events_output[int((_DISTRACTED_SECONDS_TO_RED+2*_invisible_time+1.5)/DT_DMON)].names[0], EventName.driverDistracted) - self.assertTrue(len(events_output[int((_DISTRACTED_SECONDS_TO_RED+2*_invisible_time+3.5)/DT_DMON)])==0) + self.assertTrue(len(events_output[int((_DISTRACTED_SECONDS_TO_RED+2*_invisible_time+3.5)/DT_DMON)]) == 0) # 5. op engaged, invisible driver, down to orange, driver touches wheel; then down to orange again, driver appears # - both actions should clear the alert, but momentary appearence should not @@ -145,15 +145,15 @@ class TestMonitoring(unittest.TestCase): ds_vector[int((2*_INVISIBLE_SECONDS_TO_ORANGE+1)/DT_DMON):int((2*_INVISIBLE_SECONDS_TO_ORANGE+1+_visible_time)/DT_DMON)] = [msg_ATTENTIVE] * int(_visible_time/DT_DMON) interaction_vector[int((_INVISIBLE_SECONDS_TO_ORANGE)/DT_DMON):int((_INVISIBLE_SECONDS_TO_ORANGE+1)/DT_DMON)] = [True] * int(1/DT_DMON) events_output = run_DState_seq(ds_vector, interaction_vector, 2*always_true, 2*always_false)[0] - self.assertTrue(len(events_output[int(_INVISIBLE_SECONDS_TO_ORANGE*0.5/DT_DMON)])==0) + self.assertTrue(len(events_output[int(_INVISIBLE_SECONDS_TO_ORANGE*0.5/DT_DMON)]) == 0) self.assertEqual(events_output[int((_INVISIBLE_SECONDS_TO_ORANGE-0.1)/DT_DMON)].names[0], EventName.promptDriverUnresponsive) - self.assertTrue(len(events_output[int((_INVISIBLE_SECONDS_TO_ORANGE+0.1)/DT_DMON)])==0) + self.assertTrue(len(events_output[int((_INVISIBLE_SECONDS_TO_ORANGE+0.1)/DT_DMON)]) == 0) if _visible_time == 1: self.assertEqual(events_output[int((_INVISIBLE_SECONDS_TO_ORANGE*2+1-0.1)/DT_DMON)].names[0], EventName.promptDriverUnresponsive) self.assertEqual(events_output[int((_INVISIBLE_SECONDS_TO_ORANGE*2+1+0.1+_visible_time)/DT_DMON)].names[0], EventName.preDriverUnresponsive) elif _visible_time == 10: self.assertEqual(events_output[int((_INVISIBLE_SECONDS_TO_ORANGE*2+1-0.1)/DT_DMON)].names[0], EventName.promptDriverUnresponsive) - self.assertTrue(len(events_output[int((_INVISIBLE_SECONDS_TO_ORANGE*2+1+0.1+_visible_time)/DT_DMON)])==0) + self.assertTrue(len(events_output[int((_INVISIBLE_SECONDS_TO_ORANGE*2+1+0.1+_visible_time)/DT_DMON)]) == 0) else: pass @@ -168,18 +168,18 @@ class TestMonitoring(unittest.TestCase): interaction_vector[int((_INVISIBLE_SECONDS_TO_RED+_visible_time)/DT_DMON):int((_INVISIBLE_SECONDS_TO_RED+_visible_time+1)/DT_DMON)] = [True] * int(1/DT_DMON) op_vector[int((_INVISIBLE_SECONDS_TO_RED+_visible_time+1)/DT_DMON):int((_INVISIBLE_SECONDS_TO_RED+_visible_time+0.5)/DT_DMON)] = [False] * int(0.5/DT_DMON) events_output = run_DState_seq(ds_vector, interaction_vector, op_vector, always_false)[0] - self.assertTrue(len(events_output[int(_INVISIBLE_SECONDS_TO_ORANGE*0.5/DT_DMON)])==0) + self.assertTrue(len(events_output[int(_INVISIBLE_SECONDS_TO_ORANGE*0.5/DT_DMON)]) == 0) self.assertEqual(events_output[int((_INVISIBLE_SECONDS_TO_ORANGE-0.1)/DT_DMON)].names[0], EventName.promptDriverUnresponsive) self.assertEqual(events_output[int((_INVISIBLE_SECONDS_TO_RED-0.1)/DT_DMON)].names[0], EventName.driverUnresponsive) self.assertEqual(events_output[int((_INVISIBLE_SECONDS_TO_RED+0.5*_visible_time)/DT_DMON)].names[0], EventName.driverUnresponsive) self.assertEqual(events_output[int((_INVISIBLE_SECONDS_TO_RED+_visible_time+0.5)/DT_DMON)].names[0], EventName.driverUnresponsive) - self.assertTrue(len(events_output[int((_INVISIBLE_SECONDS_TO_RED+_visible_time+1+0.1)/DT_DMON)])==0) + self.assertTrue(len(events_output[int((_INVISIBLE_SECONDS_TO_RED+_visible_time+1+0.1)/DT_DMON)]) == 0) # 7. op not engaged, always distracted driver # - dm should stay quiet when not engaged def test_pure_dashcam_user(self): events_output = run_DState_seq(always_distracted, always_false, always_false, always_false)[0] - self.assertTrue(np.sum([len(event) for event in events_output])==0) + self.assertTrue(np.sum([len(event) for event in events_output]) == 0) # 8. op engaged, car stops at traffic light, down to orange, no action, then car starts moving # - should only reach green when stopped, but continues counting down on launch @@ -201,9 +201,9 @@ class TestMonitoring(unittest.TestCase): [msg_DISTRACTED_UNCERTAIN] * (int(_TEST_TIMESPAN/DT_DMON)-int((_DISTRACTED_SECONDS_TO_ORANGE+_UNCERTAIN_SECONDS_TO_GREEN)/DT_DMON)) interaction_vector = always_false[:] events_output = run_DState_seq(ds_vector, interaction_vector, always_true, always_false)[0] - self.assertTrue(len(events_output[int(_UNCERTAIN_SECONDS_TO_GREEN*0.5/DT_DMON)])==0) + self.assertTrue(len(events_output[int(_UNCERTAIN_SECONDS_TO_GREEN*0.5/DT_DMON)]) == 0) self.assertEqual(events_output[int((_UNCERTAIN_SECONDS_TO_GREEN-0.1)/DT_DMON)].names[0], EventName.driverMonitorLowAcc) - self.assertTrue(len(events_output[int((_UNCERTAIN_SECONDS_TO_GREEN+_DISTRACTED_SECONDS_TO_ORANGE-0.5)/DT_DMON)])==0) + self.assertTrue(len(events_output[int((_UNCERTAIN_SECONDS_TO_GREEN+_DISTRACTED_SECONDS_TO_ORANGE-0.5)/DT_DMON)]) == 0) self.assertEqual(events_output[int((_TEST_TIMESPAN-5.)/DT_DMON)].names[0], EventName.driverMonitorLowAcc) # 10. op engaged, model is somehow uncertain and driver is distracted @@ -212,7 +212,7 @@ class TestMonitoring(unittest.TestCase): ds_vector = [msg_DISTRACTED_BUT_SOMEHOW_UNCERTAIN] * int(_TEST_TIMESPAN/DT_DMON) interaction_vector = always_false[:] events_output = run_DState_seq(ds_vector, interaction_vector, always_true, always_false)[0] - self.assertTrue(len(events_output[int(_UNCERTAIN_SECONDS_TO_GREEN*0.5/DT_DMON)])==0) + self.assertTrue(len(events_output[int(_UNCERTAIN_SECONDS_TO_GREEN*0.5/DT_DMON)]) == 0) self.assertEqual(events_output[int((_UNCERTAIN_SECONDS_TO_GREEN)/DT_DMON)].names[0], EventName.driverMonitorLowAcc) self.assertEqual(events_output[int((2.5*(_DISTRACTED_TIME-_DISTRACTED_PRE_TIME_TILL_TERMINAL))/DT_DMON)].names[1], EventName.preDriverDistracted) self.assertEqual(events_output[int((2.5*(_DISTRACTED_TIME-_DISTRACTED_PROMPT_TIME_TILL_TERMINAL))/DT_DMON)].names[1], EventName.promptDriverDistracted) diff --git a/selfdrive/debug/mpc/live_lateral_mpc.py b/selfdrive/debug/mpc/live_lateral_mpc.py index 48be5be9c6..d1e8276c11 100755 --- a/selfdrive/debug/mpc/live_lateral_mpc.py +++ b/selfdrive/debug/mpc/live_lateral_mpc.py @@ -81,10 +81,10 @@ def mpc_vwr_thread(addr="127.0.0.1"): lineP.set_ydata(path_x) if lMpc is not None: - mpc_path_x = list(lMpc.liveMpc.x)[1:] - mpc_path_y = list(lMpc.liveMpc.y)[1:] - mpc_steer_angle = list(lMpc.liveMpc.delta)[1:] - mpc_psi = list(lMpc.liveMpc.psi)[1:] + mpc_path_x = list(lMpc.liveMpc.x)[1:] + mpc_path_y = list(lMpc.liveMpc.y)[1:] + mpc_steer_angle = list(lMpc.liveMpc.delta)[1:] + mpc_psi = list(lMpc.liveMpc.psi)[1:] line1.set_xdata(mpc_path_y) line1.set_ydata(mpc_path_x) diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index 6ba4c38a94..927a1e2756 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -163,7 +163,7 @@ def gen_nav_data(msg, nav_frame_buffer): # parse GPS ephem gnssId = msg_meta_data['gnssId'] - if gnssId == 0: + if gnssId == 0: svId = msg_meta_data['svid'] subframeId = GET_FIELD_U(measurements[1]['dwrd'], 3, 8) words = [] diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index 0cba576fa2..acb1475afd 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -163,7 +163,7 @@ class Plant(): Plant.live_params.close() def speed_sensor(self, speed): - if speed<0.3: + if speed < 0.3: return 0 else: return speed * CV.MS_TO_KPH diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index d6fe5ef6f1..ad0b9fc6f1 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -190,7 +190,7 @@ def calibration_rcv_callback(msg, CP, cfg, fsm): # calibrationd publishes 1 calibrationData every 5 cameraOdometry packets. # should_recv always true to increment frame if msg.which() == 'carState': - if ((fsm.frame +1)% 25) == 0: + if ((fsm.frame + 1) % 25) == 0: recv_socks = ["liveCalibration"] else: recv_socks = [] diff --git a/tools/carcontrols/joystick_test.py b/tools/carcontrols/joystick_test.py index 2f008af14a..cb2309d11a 100755 --- a/tools/carcontrols/joystick_test.py +++ b/tools/carcontrols/joystick_test.py @@ -2,8 +2,8 @@ import pygame # pylint: disable=import-error # Define some colors -BLACK = ( 0, 0, 0) -WHITE = ( 255, 255, 255) +BLACK = ( 0, 0, 0) +WHITE = ( 255, 255, 255) # This is a simple class that will help us print to the screen # It has nothing to do with the joysticks, just outputting the @@ -55,7 +55,7 @@ while not done: # EVENT PROCESSING STEP for event in pygame.event.get(): # User did something if event.type == pygame.QUIT: # If user clicked close - done=True # Flag that we are done so we exit this loop + done = True # Flag that we are done so we exit this loop # Possible joystick actions: JOYAXISMOTION JOYBALLMOTION JOYBUTTONDOWN JOYBUTTONUP JOYHATMOTION if event.type == pygame.JOYBUTTONDOWN: diff --git a/tools/replay/unlogger.py b/tools/replay/unlogger.py index 4b71d2a148..c248d915a8 100755 --- a/tools/replay/unlogger.py +++ b/tools/replay/unlogger.py @@ -312,19 +312,19 @@ def keyboard_controller_thread(q, route_start_time): kb = KBHit() while 1: c = kb.getch() - if c=='m': # Move forward by 1m + if c == 'm': # Move forward by 1m q.send_pyobj(SeekRelativeTime(60)) - elif c=='M': # Move backward by 1m + elif c == 'M': # Move backward by 1m q.send_pyobj(SeekRelativeTime(-60)) - elif c=='s': # Move forward by 10s + elif c == 's': # Move forward by 10s q.send_pyobj(SeekRelativeTime(10)) - elif c=='S': # Move backward by 10s + elif c == 'S': # Move backward by 10s q.send_pyobj(SeekRelativeTime(-10)) - elif c=='G': # Move backward by 10s + elif c == 'G': # Move backward by 10s q.send_pyobj(SeekAbsoluteTime(0.)) - elif c=="\x20": # Space bar. + elif c == "\x20": # Space bar. q.send_pyobj(TogglePause()) - elif c=="\n": + elif c == "\n": try: seek_time_input = input('time: ') seek_time = absolute_time_str(seek_time_input, route_start_time) From ddcc78d2d5e83f4355533164a00036dea112b080 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 31 May 2020 12:09:11 -0700 Subject: [PATCH 153/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index b8267341a1..49ffbe99f6 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit b8267341a15feed3308870b91255a5d4de842df9 +Subproject commit 49ffbe99f65e64d23d27d9d3e37f68bc2368dccd From efd5dffb1e727c70065fdbe7499ec9e009dfd282 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 31 May 2020 12:37:52 -0700 Subject: [PATCH 154/656] enable flake8 E231: missing whitespace after comma --- .pre-commit-config.yaml | 2 +- common/android.py | 2 +- common/apk.py | 2 +- common/transformations/camera.py | 24 ++--- common/transformations/coordinates.py | 6 +- common/transformations/model.py | 4 +- common/transformations/orientation.py | 18 ++-- .../transformations/tests/test_coordinates.py | 14 +-- common/window.py | 10 +- opendbc | 2 +- scripts/waste.py | 4 +- selfdrive/boardd/tests/boardd_old.py | 2 +- selfdrive/camerad/snapshot/visionipc.py | 2 +- selfdrive/camerad/test/frame_test.py | 4 +- selfdrive/car/chrysler/interface.py | 2 +- selfdrive/car/chrysler/values.py | 4 +- selfdrive/car/ford/fordcan.py | 2 +- selfdrive/car/honda/values.py | 2 +- selfdrive/car/hyundai/carstate.py | 6 +- selfdrive/car/hyundai/values.py | 2 +- selfdrive/car/mazda/carstate.py | 8 +- selfdrive/car/nissan/interface.py | 2 +- selfdrive/car/nissan/values.py | 4 +- selfdrive/car/toyota/values.py | 100 +++++++++--------- selfdrive/car/volkswagen/carstate.py | 8 +- selfdrive/controls/dmonitoringd.py | 2 +- selfdrive/controls/lib/latcontrol_lqr.py | 10 +- selfdrive/controls/tests/test_monitoring.py | 12 +-- selfdrive/debug/can_printer.py | 4 +- selfdrive/debug/cpu_usage_stat.py | 2 +- .../debug/internal/sensor_test_bootloop.py | 2 +- selfdrive/locationd/calibrationd.py | 8 +- selfdrive/locationd/locationd.py | 2 +- selfdrive/locationd/models/live_kf.py | 2 +- selfdrive/locationd/models/loc_kf.py | 6 +- selfdrive/locationd/test/ublox.py | 2 +- selfdrive/locationd/test/ubloxd.py | 6 +- selfdrive/loggerd/tests/test_uploader.py | 8 +- selfdrive/manager.py | 2 +- selfdrive/modeld/runners/keras_runner.py | 2 +- selfdrive/registration.py | 2 +- .../test/longitudinal_maneuvers/plant.py | 2 +- .../test_longitudinal.py | 6 +- selfdrive/test/process_replay/inject_model.py | 2 +- selfdrive/test/test_leeco_alt_fan.py | 2 +- tools/carcontrols/joystick_test.py | 2 +- tools/lib/framereader.py | 2 +- tools/lib/kbhit.py | 2 +- tools/livedm/helpers.py | 32 +++--- tools/livedm/livedm.py | 22 ++-- tools/nui/get_files_comma_api.py | 4 +- tools/replay/lib/ui_helpers.py | 20 ++-- tools/replay/sensorium.py | 2 +- tools/replay/ui.py | 16 +-- tools/sim/bridge.py | 4 +- tools/sim/lib/can.py | 4 +- tools/sim/lib/manual_ctrl.py | 8 +- tools/streamer/streamerd.py | 6 +- tools/webcam/front_mount_helper.py | 6 +- tools/webcam/warp_vis.py | 6 +- 60 files changed, 228 insertions(+), 228 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 33a34be665..84aba5d599 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,7 +17,7 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E231,E241,E251,E261,E265,E266,E302,E303,E305,E402,E501,E502,E722,E741,W504 + - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E251,E261,E265,E266,E302,E303,E305,E402,E501,E502,E722,E741,W504 - --statistics - repo: local hooks: diff --git a/common/android.py b/common/android.py index cb6a7748d2..9b140c9143 100644 --- a/common/android.py +++ b/common/android.py @@ -22,7 +22,7 @@ def get_imei(slot): if slot not in ("0", "1"): raise ValueError("SIM slot must be 0 or 1") - ret = parse_service_call_string(service_call(["iphonesubinfo", "3" ,"i32", str(slot)])) + ret = parse_service_call_string(service_call(["iphonesubinfo", "3" , "i32", str(slot)])) if not ret: # allow non android to be identified differently ret = "%015d" % random.randint(0, 1 << 32) diff --git a/common/apk.py b/common/apk.py index 5716ed452a..c04c19aa5f 100644 --- a/common/apk.py +++ b/common/apk.py @@ -13,7 +13,7 @@ def get_installed_apks(): ret = {} for x in dat: if x.startswith("package:"): - v,k = x.split("package:")[1].split("=") + v, k = x.split("package:")[1].split("=") ret[k] = v return ret diff --git a/common/transformations/camera.py b/common/transformations/camera.py index 3e8ee16e37..e56a6f34bf 100644 --- a/common/transformations/camera.py +++ b/common/transformations/camera.py @@ -59,7 +59,7 @@ def vp_from_ke(m): The vanishing point is defined as lim x->infinity C (x, 0, 0, 1).T """ - return (m[0, 0]/m[2,0], m[1,0]/m[2,0]) + return (m[0, 0]/m[2, 0], m[1, 0]/m[2, 0]) def vp_from_rpy(rpy): @@ -81,10 +81,10 @@ def normalize(img_pts, intrinsics=eon_intrinsics): img_pts = np.array(img_pts) input_shape = img_pts.shape img_pts = np.atleast_2d(img_pts) - img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0],1)))) + img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0], 1)))) img_pts_normalized = img_pts.dot(intrinsics_inv.T) img_pts_normalized[(img_pts < 0).any(axis=1)] = np.nan - return img_pts_normalized[:,:2].reshape(input_shape) + return img_pts_normalized[:, :2].reshape(input_shape) def denormalize(img_pts, intrinsics=eon_intrinsics): @@ -93,13 +93,13 @@ def denormalize(img_pts, intrinsics=eon_intrinsics): img_pts = np.array(img_pts) input_shape = img_pts.shape img_pts = np.atleast_2d(img_pts) - img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0],1)))) + img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0], 1)))) img_pts_denormalized = img_pts.dot(intrinsics.T) - img_pts_denormalized[img_pts_denormalized[:,0] > W] = np.nan - img_pts_denormalized[img_pts_denormalized[:,0] < 0] = np.nan - img_pts_denormalized[img_pts_denormalized[:,1] > H] = np.nan - img_pts_denormalized[img_pts_denormalized[:,1] < 0] = np.nan - return img_pts_denormalized[:,:2].reshape(input_shape) + img_pts_denormalized[img_pts_denormalized[:, 0] > W] = np.nan + img_pts_denormalized[img_pts_denormalized[:, 0] < 0] = np.nan + img_pts_denormalized[img_pts_denormalized[:, 1] > H] = np.nan + img_pts_denormalized[img_pts_denormalized[:, 1] < 0] = np.nan + return img_pts_denormalized[:, :2].reshape(input_shape) def device_from_ecef(pos_ecef, orientation_ecef, pt_ecef): @@ -124,10 +124,10 @@ def img_from_device(pt_device): pt_view = np.einsum('jk,ik->ij', view_frame_from_device_frame, pt_device) # This function should never return negative depths - pt_view[pt_view[:,2] < 0] = np.nan + pt_view[pt_view[:, 2] < 0] = np.nan - pt_img = pt_view/pt_view[:,2:3] - return pt_img.reshape(input_shape)[:,:2] + pt_img = pt_view/pt_view[:, 2:3] + return pt_img.reshape(input_shape)[:, :2] def get_camera_frame_from_calib_frame(camera_frame_from_road_frame): diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index 3f9ba23f29..4f15f92777 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -18,9 +18,9 @@ def geodetic2ecef(geodetic, radians=False): geodetic = np.atleast_2d(geodetic) ratio = 1.0 if radians else (np.pi / 180.0) - lat = ratio*geodetic[:,0] - lon = ratio*geodetic[:,1] - alt = geodetic[:,2] + lat = ratio*geodetic[:, 0] + lon = ratio*geodetic[:, 1] + alt = geodetic[:, 2] xi = np.sqrt(1 - esq * np.sin(lat)**2) x = (a / xi + alt) * np.cos(lat) * np.cos(lon) diff --git a/common/transformations/model.py b/common/transformations/model.py index c47c9e987f..a7edacf9b5 100644 --- a/common/transformations/model.py +++ b/common/transformations/model.py @@ -130,9 +130,9 @@ def get_camera_frame_from_bigmodel_frame(camera_frame_from_road_frame): def get_model_frame(snu_full, camera_frame_from_model_frame, size): idxs = camera_frame_from_model_frame.dot(np.column_stack([np.tile(np.arange(size[0]), size[1]), - np.tile(np.arange(size[1]), (size[0],1)).T.flatten(), + np.tile(np.arange(size[1]), (size[0], 1)).T.flatten(), np.ones(size[0] * size[1])]).T).T.astype(int) - calib_flat = snu_full[idxs[:,1], idxs[:,0]] + calib_flat = snu_full[idxs[:, 1], idxs[:, 0]] if len(snu_full.shape) == 3: calib = calib_flat.reshape((size[1], size[0], 3)) elif len(snu_full.shape) == 2: diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py index ee7335d3ec..0a28524a67 100644 --- a/common/transformations/orientation.py +++ b/common/transformations/orientation.py @@ -13,11 +13,11 @@ Supports both x2y and y_from_x format (y_from_x preferred!). def euler2quat(eulers): eulers = array(eulers) if len(eulers.shape) > 1: - output_shape = (-1,4) + output_shape = (-1, 4) else: output_shape = (4,) eulers = np.atleast_2d(eulers) - gamma, theta, psi = eulers[:,0], eulers[:,1], eulers[:,2] + gamma, theta, psi = eulers[:, 0], eulers[:, 1], eulers[:, 2] q0 = np.cos(gamma / 2) * np.cos(theta / 2) * np.cos(psi / 2) + \ np.sin(gamma / 2) * np.sin(theta / 2) * np.sin(psi / 2) @@ -30,7 +30,7 @@ def euler2quat(eulers): quats = array([q0, q1, q2, q3]).T for i in range(len(quats)): - if quats[i,0] < 0: + if quats[i, 0] < 0: quats[i] = -quats[i] return quats.reshape(output_shape) @@ -38,11 +38,11 @@ def euler2quat(eulers): def quat2euler(quats): quats = array(quats) if len(quats.shape) > 1: - output_shape = (-1,3) + output_shape = (-1, 3) else: output_shape = (3,) quats = np.atleast_2d(quats) - q0, q1, q2, q3 = quats[:,0], quats[:,1], quats[:,2], quats[:,3] + q0, q1, q2, q3 = quats[:, 0], quats[:, 1], quats[:, 2], quats[:, 3] gamma = np.arctan2(2 * (q0 * q1 + q2 * q3), 1 - 2 * (q1**2 + q2**2)) theta = np.arcsin(2 * (q0 * q2 - q3 * q1)) @@ -101,7 +101,7 @@ def rot2quat(rots): q = np.empty((len(rots), 4)) for i in range(len(rots)): _, eigvecs = linalg.eigh(K3[i].T) - eigvecs = eigvecs[:,3:] + eigvecs = eigvecs[:, 3:] q[i, 0] = eigvecs[-1] q[i, 1:] = -eigvecs[:-1].flatten() if q[i, 0] < 0: @@ -154,9 +154,9 @@ def rot_matrix(roll, pitch, yaw): cr, sr = np.cos(roll), np.sin(roll) cp, sp = np.cos(pitch), np.sin(pitch) cy, sy = np.cos(yaw), np.sin(yaw) - rr = array([[1,0,0],[0, cr,-sr],[0, sr, cr]]) - rp = array([[cp,0,sp],[0, 1,0],[-sp, 0, cp]]) - ry = array([[cy,-sy,0],[sy, cy,0],[0, 0, 1]]) + rr = array([[1, 0, 0], [0, cr, -sr], [0, sr, cr]]) + rp = array([[cp, 0, sp], [0, 1, 0], [-sp, 0, cp]]) + ry = array([[cy, -sy, 0], [sy, cy, 0], [0, 0, 1]]) return ry.dot(rp.dot(rr)) diff --git a/common/transformations/tests/test_coordinates.py b/common/transformations/tests/test_coordinates.py index 82fdc35fbe..b0cbcd79d6 100755 --- a/common/transformations/tests/test_coordinates.py +++ b/common/transformations/tests/test_coordinates.py @@ -72,16 +72,16 @@ class TestNED(unittest.TestCase): def test_ecef_geodetic(self): # testing single np.testing.assert_allclose(ecef_positions[0], coord.geodetic2ecef(geodetic_positions[0]), rtol=1e-9) - np.testing.assert_allclose(geodetic_positions[0,:2], coord.ecef2geodetic(ecef_positions[0])[:2], rtol=1e-9) - np.testing.assert_allclose(geodetic_positions[0,2], coord.ecef2geodetic(ecef_positions[0])[2], rtol=1e-9, atol=1e-4) + np.testing.assert_allclose(geodetic_positions[0, :2], coord.ecef2geodetic(ecef_positions[0])[:2], rtol=1e-9) + np.testing.assert_allclose(geodetic_positions[0, 2], coord.ecef2geodetic(ecef_positions[0])[2], rtol=1e-9, atol=1e-4) - np.testing.assert_allclose(geodetic_positions[:,:2], coord.ecef2geodetic(ecef_positions)[:,:2], rtol=1e-9) - np.testing.assert_allclose(geodetic_positions[:,2], coord.ecef2geodetic(ecef_positions)[:,2], rtol=1e-9, atol=1e-4) + np.testing.assert_allclose(geodetic_positions[:, :2], coord.ecef2geodetic(ecef_positions)[:, :2], rtol=1e-9) + np.testing.assert_allclose(geodetic_positions[:, 2], coord.ecef2geodetic(ecef_positions)[:, 2], rtol=1e-9, atol=1e-4) np.testing.assert_allclose(ecef_positions, coord.geodetic2ecef(geodetic_positions), rtol=1e-9) np.testing.assert_allclose(geodetic_positions_radians[0], coord.ecef2geodetic(ecef_positions[0], radians=True), rtol=1e-5) - np.testing.assert_allclose(geodetic_positions_radians[:,:2], coord.ecef2geodetic(ecef_positions, radians=True)[:,:2], rtol=1e-7) - np.testing.assert_allclose(geodetic_positions_radians[:,2], coord.ecef2geodetic(ecef_positions, radians=True)[:,2], rtol=1e-7, atol=1e-4) + np.testing.assert_allclose(geodetic_positions_radians[:, :2], coord.ecef2geodetic(ecef_positions, radians=True)[:, :2], rtol=1e-7) + np.testing.assert_allclose(geodetic_positions_radians[:, 2], coord.ecef2geodetic(ecef_positions, radians=True)[:, 2], rtol=1e-7, atol=1e-4) @@ -95,7 +95,7 @@ class TestNED(unittest.TestCase): for geo_pos in geodetic_positions: converter = coord.LocalCoord.from_geodetic(geo_pos) geo_pos_moved = geo_pos + np.array([0, 0, 10]) - geo_pos_double_converted_moved = converter.ned2geodetic(converter.geodetic2ned(geo_pos) + np.array([0,0,-10])) + geo_pos_double_converted_moved = converter.ned2geodetic(converter.geodetic2ned(geo_pos) + np.array([0, 0, -10])) np.testing.assert_allclose(geo_pos_moved[:2], geo_pos_double_converted_moved[:2], rtol=1e-9, atol=1e-6) np.testing.assert_allclose(geo_pos_moved[2], geo_pos_double_converted_moved[2], rtol=1e-9, atol=1e-4) diff --git a/common/window.py b/common/window.py index 8c36fa5432..6fc36d06bf 100644 --- a/common/window.py +++ b/common/window.py @@ -10,17 +10,17 @@ class Window(): pygame.display.set_caption(caption) self.double = double if self.double: - self.screen = pygame.display.set_mode((w*2,h*2)) + self.screen = pygame.display.set_mode((w*2, h*2)) else: - self.screen = pygame.display.set_mode((w,h)) + self.screen = pygame.display.set_mode((w, h)) def draw(self, out): pygame.event.pump() if self.double: out2 = cv2.resize(out, (self.w*2, self.h*2)) - pygame.surfarray.blit_array(self.screen, out2.swapaxes(0,1)) + pygame.surfarray.blit_array(self.screen, out2.swapaxes(0, 1)) else: - pygame.surfarray.blit_array(self.screen, out.swapaxes(0,1)) + pygame.surfarray.blit_array(self.screen, out.swapaxes(0, 1)) pygame.display.flip() @@ -42,7 +42,7 @@ class Window(): if __name__ == "__main__": import numpy as np win = Window(200, 200, double=True) - img = np.zeros((200,200,3), np.uint8) + img = np.zeros((200, 200, 3), np.uint8) while 1: print("draw") img += 1 diff --git a/opendbc b/opendbc index 73685b609d..e92e74311a 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 73685b609d25cfc8f838d53f69cf78e136c612c2 +Subproject commit e92e74311a7ed66922629bec4b8cee7c8db1b9f0 diff --git a/scripts/waste.py b/scripts/waste.py index 2834dea191..48600253d3 100755 --- a/scripts/waste.py +++ b/scripts/waste.py @@ -9,8 +9,8 @@ def waste(pid): # set affinity os.system("taskset -p %d %d" % (1 << pid, os.getpid())) - m1 = np.zeros((200,200)) + 0.8 - m2 = np.zeros((200,200)) + 1.2 + m1 = np.zeros((200, 200)) + 0.8 + m2 = np.zeros((200, 200)) + 1.2 i = 1 st = sec_since_boot() diff --git a/selfdrive/boardd/tests/boardd_old.py b/selfdrive/boardd/tests/boardd_old.py index c5ff9263b5..4c62e94883 100755 --- a/selfdrive/boardd/tests/boardd_old.py +++ b/selfdrive/boardd/tests/boardd_old.py @@ -138,7 +138,7 @@ def boardd_test_loop(): can_init() cnt = 0 while 1: - can_send_many([[0xbb,0,"\xaa\xaa\xaa\xaa",0], [0xaa,0,"\xaa\xaa\xaa\xaa"+struct.pack("!I", cnt),1]]) + can_send_many([[0xbb, 0, "\xaa\xaa\xaa\xaa", 0], [0xaa, 0, "\xaa\xaa\xaa\xaa"+struct.pack("!I", cnt), 1]]) #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",0]]) #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",1]]) # recv @ 100hz diff --git a/selfdrive/camerad/snapshot/visionipc.py b/selfdrive/camerad/snapshot/visionipc.py index 816db41208..4df79e2cc2 100644 --- a/selfdrive/camerad/snapshot/visionipc.py +++ b/selfdrive/camerad/snapshot/visionipc.py @@ -90,4 +90,4 @@ class VisionIPC(): buf = self.clib.visionstream_get(self.s, ffi.NULL) pbuf = ffi.buffer(buf.addr, buf.len) ret = np.frombuffer(pbuf, dtype=np.uint8).reshape((-1, self.buf_info.stride//3, 3)) - return ret[:self.buf_info.height, :self.buf_info.width, [2,1,0]] + return ret[:self.buf_info.height, :self.buf_info.width, [2, 1, 0]] diff --git a/selfdrive/camerad/test/frame_test.py b/selfdrive/camerad/test/frame_test.py index 095a20a7cb..36e6733654 100755 --- a/selfdrive/camerad/test/frame_test.py +++ b/selfdrive/camerad/test/frame_test.py @@ -9,10 +9,10 @@ def get_frame(idx): img[100:400, 100:100+(idx % 10) * 100] = 255 # big number - im2 = Image.new("RGB", (200,200)) + im2 = Image.new("RGB", (200, 200)) draw = ImageDraw.Draw(im2) draw.text((10, 100), "%02d" % idx, font=font) - img[400:600, 400:600] = np.array(im2.getdata()).reshape((200,200,3)) + img[400:600, 400:600] = np.array(im2.getdata()).reshape((200, 200, 3)) return img.tostring() if __name__ == "__main__": diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 66ba7159fb..a62d06d0ab 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -24,7 +24,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.2 # Pacifica Hybrid 2017 ret.mass = 2858. + STD_CARGO_KG # kg curb weight Pacifica Hybrid 2017 ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15,0.30], [0.03,0.05]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] ret.lateralTuning.pid.kf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 ret.steerActuatorDelay = 0.1 ret.steerRateCost = 0.7 diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 1043f7f00b..03c6dab93c 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -41,7 +41,7 @@ FINGERPRINTS = { ], CAR.PACIFICA_2020: [ { - 55: 8, 179: 8, 181: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 650: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 926: 3, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 7, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1284: 8, 1568: 8, 1570:8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 2016: 8, 2024: 8 + 55: 8, 179: 8, 181: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 650: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 926: 3, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 7, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1284: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 2016: 8, 2024: 8 } ], CAR.PACIFICA_2018_HYBRID: [ @@ -50,7 +50,7 @@ FINGERPRINTS = { {168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1258: 8, 1259: 8, 1260: 8, 1262: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 1899: 8, 1900: 8, 1902: 8, 2016: 8, 2018: 8, 2019: 8, 2020: 8, 2023: 8, 2024: 8, 2026: 8, 2027: 8, 2028: 8, 2031: 8}, ], CAR.PACIFICA_2019_HYBRID: [ - {168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770:8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1538: 8}, + {168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1538: 8}, # Based on 0607d2516fc2148f|2019-02-13--23-03-16 { 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1537: 8 diff --git a/selfdrive/car/ford/fordcan.py b/selfdrive/car/ford/fordcan.py index f2ebb9100b..e98dec584b 100644 --- a/selfdrive/car/ford/fordcan.py +++ b/selfdrive/car/ford/fordcan.py @@ -6,7 +6,7 @@ def create_steer_command(packer, angle_cmd, enabled, lkas_state, angle_steers, c """Creates a CAN message for the Ford Steer Command.""" #if enabled and lkas available: - if enabled and lkas_state in [2,3]: # and (frame % 500) >= 3: + if enabled and lkas_state in [2, 3]: # and (frame % 500) >= 3: action = lkas_action else: action = 0xf diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index af52cae087..1901eaf579 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -126,7 +126,7 @@ FINGERPRINTS = { }, # 2019 Ridgeline { - 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422:8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 512: 6, 513: 6, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 871: 8, 882: 2, 884: 7, 892: 8, 923: 2, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 424: 5, 1613: 5, 1616: 5, 1618: 5, 1623: 5, 1668: 5 + 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 512: 6, 513: 6, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 871: 8, 882: 2, 884: 7, 892: 8, 923: 2, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 424: 5, 1613: 5, 1616: 5, 1618: 5, 1623: 5, 1668: 5 }], # 2019 Insight CAR.INSIGHT: [{ diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index c108bd5838..9c36804c3d 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -11,7 +11,7 @@ class CarState(CarStateBase): def update(self, cp, cp_cam): ret = car.CarState.new_message() - ret.doorOpen = any([cp.vl["CGW1"]['CF_Gway_DrvDrSw'],cp.vl["CGW1"]['CF_Gway_AstDrSw'], + ret.doorOpen = any([cp.vl["CGW1"]['CF_Gway_DrvDrSw'], cp.vl["CGW1"]['CF_Gway_AstDrSw'], cp.vl["CGW2"]['CF_Gway_RLDrSw'], cp.vl["CGW2"]['CF_Gway_RRDrSw']]) ret.seatbeltUnlatched = cp.vl["CGW1"]['CF_Gway_DrvSeatBeltSw'] == 0 @@ -212,7 +212,7 @@ class CarState(CarStateBase): ] elif CP.carFingerprint in FEATURES["use_tcu_gears"]: signals += [ - ("CUR_GR", "TCU12",0) + ("CUR_GR", "TCU12", 0) ] checks += [ ("TCU12", 100) @@ -222,7 +222,7 @@ class CarState(CarStateBase): checks += [("ELECT_GEAR", 20)] else: signals += [ - ("CF_Lvr_Gear","LVR12",0) + ("CF_Lvr_Gear", "LVR12", 0) ] checks += [ ("LVR12", 100) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 307e1a4293..1fbb9b43c5 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -108,7 +108,7 @@ FINGERPRINTS = { 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1162: 4, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2003: 8, 2004: 8, 2005: 8, 2008: 8, 2011: 8, 2012: 8, 2013: 8 }], CAR.KONA: [{ - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 909: 8, 916: 8, 1040: 8, 1078: 4, 1107: 5, 1136: 8, 1156: 8, 1170: 8, 1173: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8,1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 2004: 8, 2009: 8, 2012: 8 + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 909: 8, 916: 8, 1040: 8, 1078: 4, 1107: 5, 1136: 8, 1156: 8, 1170: 8, 1173: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 2004: 8, 2009: 8, 2012: 8 }], CAR.KONA_EV: [{ 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 549: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1307: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1378: 4, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8 diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index 86d1643c49..ffa99dadac 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -125,10 +125,10 @@ class CarState(CarStateBase): ("LKAS_TRACK_STATE", "STEER_RATE", 0), ("HANDS_OFF_5_SECONDS", "STEER_RATE", 0), ("CRZ_ACTIVE", "CRZ_CTRL", 0), - ("STANDSTILL","PEDALS", 0), - ("BRAKE_ON","PEDALS", 0), - ("BRAKE_PRESSURE","BRAKE", 0), - ("GEAR","GEAR", 0), + ("STANDSTILL", "PEDALS", 0), + ("BRAKE_ON", "PEDALS", 0), + ("BRAKE_PRESSURE", "BRAKE", 0), + ("GEAR", "GEAR", 0), ("DRIVER_SEATBELT", "SEATBELT", 0), ("FL", "DOORS", 0), ("FR", "DOORS", 0), diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index 319228da37..dc2e757990 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -86,7 +86,7 @@ class CarInterface(CarInterfaceBase): def apply(self, c): can_sends = self.CC.update(c.enabled, self.CS, self.frame, c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert, - c.hudControl.leftLaneVisible,c.hudControl.rightLaneVisible, + c.hudControl.leftLaneVisible, c.hudControl.rightLaneVisible, c.hudControl.leftLaneDepart, c.hudControl.rightLaneDepart) self.frame += 1 return can_sends diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 4d1d1b932c..ccd88954cc 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -11,10 +11,10 @@ class CAR: FINGERPRINTS = { CAR.XTRAIL: [ { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 2, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1821: 8, 1823: 8, 1837:8, 2015: 8, 2016: 8, 2024: 8 + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 2, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1821: 8, 1823: 8, 1837: 8, 2015: 8, 2016: 8, 2024: 8 }, { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 527: 1, 548: 8, 637: 4, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 8, 1497: 3,1534: 6, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 527: 1, 548: 8, 637: 4, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 8, 1497: 3, 1534: 6, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 }, ], CAR.LEAF: [ diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index bd499c762e..7ff2265eb7 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -69,70 +69,70 @@ ECU_FINGERPRINT = { FINGERPRINTS = { CAR.RAV4: [{ - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 547: 8, 548: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767:4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2024: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 547: 8, 548: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2024: 8 }], CAR.RAV4H: [{ - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 296: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 550: 8, 552: 4, 560: 7, 562: 4, 581: 5, 608: 8, 610: 5, 643: 7, 705: 8, 713: 8, 725: 2, 740: 5, 767:4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1212: 8, 1227: 8, 1228: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 296: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 550: 8, 552: 4, 560: 7, 562: 4, 581: 5, 608: 8, 610: 5, 643: 7, 705: 8, 713: 8, 725: 2, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1212: 8, 1227: 8, 1228: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, # Chinese RAV4 { - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 547: 8, 548: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 742: 8, 743: 8, 767:4, 800: 8, 830: 7, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1207: 8, 1227: 8, 1235: 8, 1263: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 547: 8, 548: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 830: 7, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1207: 8, 1227: 8, 1235: 8, 1263: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8 }], CAR.PRIUS: [{ - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2,898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, #2019 LE { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, # 2020 Prius Prime LE { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 740: 5, 742: 8, 743: 8, 764: 8, 767:4, 800: 8, 810: 2, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 740: 5, 742: 8, 743: 8, 764: 8, 767: 4, 800: 8, 810: 2, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, #2020 Prius Prime Limited { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2024: 8, 2026: 8, 2027: 8, 2029: 8, 2030: 8, 2031: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2024: 8, 2026: 8, 2027: 8, 2029: 8, 2030: 8, 2031: 8 }, #2020 Central Europe Prime { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 740: 5, 742: 8, 743: 8, 764: 8, 767:4, 800: 8, 810: 2, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 8, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 740: 5, 742: 8, 743: 8, 764: 8, 767: 4, 800: 8, 810: 2, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 8, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8 }, #2017 German Prius { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296:8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8,740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1792: 8, 1767:4, 1863:8, 1904: 8, 1912: 8, 1984: 8, 1988: 8, 1990: 8, 1992: 8, 1996:8, 1998: 8, 2002: 8, 2010: 8, 2015: 8, 2016: 8, 2018: 8, 2024: 8, 2026: 8, 2030: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1792: 8, 1767: 4, 1863: 8, 1904: 8, 1912: 8, 1984: 8, 1988: 8, 1990: 8, 1992: 8, 1996: 8, 1998: 8, 2002: 8, 2010: 8, 2015: 8, 2016: 8, 2018: 8, 2024: 8, 2026: 8, 2030: 8 }], #Corolla w/ added Pedal Support (512L and 513L) CAR.COROLLA: [{ - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 547: 8, 548: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767:4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 2, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1196: 8, 1227: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2021: 8, 2022: 8, 2023: 8, 2024: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 547: 8, 548: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 2, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1196: 8, 1227: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2021: 8, 2022: 8, 2023: 8, 2024: 8 }], CAR.LEXUS_RX: [{ # 2016 Lexus RX 350 - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 812: 3, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 }, # 2017 Lexus RX 350 { - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 658: 8, 705: 8, 740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 658: 8, 705: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }], CAR.LEXUS_RXH: [{ - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513:6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1956: 8, 1960: 8, 1964: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1956: 8, 1960: 8, 1964: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8 }, # RX450HL # TODO: get proper fingerprint in stock mode { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, # RX540H 2019 with color hud { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1952: 8, 1960: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1952: 8, 1960: 8, 1990: 8, 1998: 8 }, # 2017 RX 450h { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 744: 8, 767:4, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1745: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 744: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1745: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 }], CAR.LEXUS_RX_TSS2: [ # 2020 Lexus RX 350 { - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 740: 5, 742: 8, 743: 8, 764: 8, 765: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8,1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594:8, 1595: 8, 1600: 8, 1649: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 740: 5, 742: 8, 743: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1600: 8, 1649: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 }], CAR.LEXUS_RXH_TSS2: [ # 2020 Lexus RX 450h @@ -140,122 +140,122 @@ FINGERPRINTS = { 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 744: 8, 764: 8, 765: 8, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 942: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 987: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1600: 8, 1649: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1792: 8, 1808: 8, 1809: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1937: 8, 1940: 8, 1941: 8, 1945: 8, 1948: 8, 1949: 8, 1952: 8, 1953: 8, 1956: 8, 1960: 8, 1961: 8, 1968: 8, 1976: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8, 2015: 8, 2016: 8, 2024: 8 }], CAR.CHR: [{ - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 705: 8, 740: 5, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 913: 8, 918: 8, 921: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 705: 8, 740: 5, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 913: 8, 918: 8, 921: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8 }], CAR.CHRH: [{ - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }], CAR.CAMRY: [ #XLE and LE { - 36: 8, 37: 8, 119: 6, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 891: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 119: 6, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 891: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, #XSE and SE # TODO: get proper fingerprint in stock mode { - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 888: 8, 889: 8, 891: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 888: 8, 889: 8, 891: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, { # 2019 XSE - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 942: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1792: 8, 1767:4, 1808: 8, 1816: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1937: 8, 1945: 8, 1953: 8, 1961: 8, 1968: 8, 1976: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 942: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1792: 8, 1767: 4, 1808: 8, 1816: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1937: 8, 1945: 8, 1953: 8, 1961: 8, 1968: 8, 1976: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 }], CAR.CAMRYH: [ #SE, LE and LE with Blindspot Monitor { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767:4, 800: 8, 810: 2, 812: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 983: 8, 984: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767: 4, 800: 8, 810: 2, 812: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 983: 8, 984: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, #SL { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767:4, 800: 8, 810: 2, 812: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767: 4, 800: 8, 810: 2, 812: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, #XLE { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 983: 8, 984: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 983: 8, 984: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }], CAR.HIGHLANDER: [{ - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767:4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1984: 8, 1988: 8, 1992: 8, 1996: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1984: 8, 1988: 8, 1992: 8, 1996: 8, 1990: 8, 1998: 8 }, # 2019 Highlander XLE { - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767:4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, # 2017 Highlander Limited { - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767:4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, # 2018 Highlander Limited Platinum { - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767:4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1263: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1585: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1988: 8, 1990: 8, 1996: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1263: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1585: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1988: 8, 1990: 8, 1996: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 }], CAR.HIGHLANDER_TSS2: [{ # 2020 highlander limited - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 355: 5, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 765: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1952: 8, 1960: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 355: 5, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1952: 8, 1960: 8, 1990: 8, 1998: 8 }], CAR.HIGHLANDERH: [{ - 36: 8, 37: 8, 170: 8, 180: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767:4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, { # 2019 Highlander Hybrid Limited Platinum - 36: 8, 37: 8, 170: 8, 180: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767:4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1076: 8, 1077: 8, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1076: 8, 1077: 8, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }], CAR.HIGHLANDERH_TSS2: [{ 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 761: 8, 765: 8, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 881: 8, 885: 8, 891: 8, 896: 8, 898: 8, 918: 8, 942: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 971: 7, 975: 5, 987: 8, 993: 8, 1014: 8, 1017: 8, 1020: 8, 1059: 1, 1063: 8, 1071: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1552: 8, 1553: 8, 1556: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1745: 8 }], CAR.AVALON: [{ - 36: 8, 37: 8, 170: 8, 180: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767:4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 905: 8, 911: 1, 916: 2, 921: 8, 933: 6, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 1005: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1206: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1558: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 905: 8, 911: 1, 916: 2, 921: 8, 933: 6, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 1005: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1206: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1558: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }], CAR.RAV4_TSS2: [ # LE { - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 355: 5, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767:4, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8,1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553:8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 355: 5, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, # XLE, Limited, and AWD { - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 }], CAR.COROLLA_TSS2: [ # hatch 2019+ and sedan 2020+ { - 36: 8, 37: 8, 114: 5, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767:4, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1235: 8, 1237: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1649: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1809: 8, 1816: 8, 1817: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1960: 8, 1981: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8 + 36: 8, 37: 8, 114: 5, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1235: 8, 1237: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1649: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1809: 8, 1816: 8, 1817: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1960: 8, 1981: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8 }], CAR.COROLLAH_TSS2: [ # 2019 Taiwan Altis Hybrid { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 765: 8, 767:4, 800: 8, 810: 2, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 885: 8, 896: 8, 898: 8, 918: 7, 921: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 987: 8, 993: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1082: 8, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1172: 8, 1235: 8, 1237: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1745: 8, 1775: 8, 1779: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 765: 8, 767: 4, 800: 8, 810: 2, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 885: 8, 896: 8, 898: 8, 918: 7, 921: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 987: 8, 993: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1082: 8, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1172: 8, 1235: 8, 1237: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1745: 8, 1775: 8, 1779: 8 }, # 2019 Chinese Levin Hybrid { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 765: 8, 767:4, 800: 8, 810: 2, 812: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 885: 8, 896: 8, 898: 8, 921: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1172: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1600: 8, 1649: 8, 1745: 8, 1775: 8, 1779: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 885: 8, 896: 8, 898: 8, 921: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1172: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1600: 8, 1649: 8, 1745: 8, 1775: 8, 1779: 8 } ], CAR.LEXUS_ES_TSS2: [{ - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 765: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, }], CAR.LEXUS_ESH_TSS2: [ { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 744: 8, 761: 8, 764: 8, 765: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 987: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 744: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 987: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }], CAR.SIENNA: [ { - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 548: 8, 550: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 764: 8, 767:4, 800: 8, 824: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 888: 8, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 1, 918: 7, 921: 8, 933: 8, 944: 6, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1160: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1212: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1656: 8, 1664: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 548: 8, 550: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 764: 8, 767: 4, 800: 8, 824: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 888: 8, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 1, 918: 7, 921: 8, 933: 8, 944: 6, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1160: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1212: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1656: 8, 1664: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, # XLE AWD 2018 { - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 548: 8, 550: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 764: 8, 767:4, 800: 8, 824: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 1, 921: 8, 933: 8, 944: 6, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1160: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1656: 8, 1664: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 548: 8, 550: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 764: 8, 767: 4, 800: 8, 824: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 1, 921: 8, 933: 8, 944: 6, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1160: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1656: 8, 1664: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }], CAR.LEXUS_IS: [ # IS300 2018 { - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 400: 6, 426: 6, 452: 8, 464: 8, 466: 8, 467: 5, 544: 4, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767:4, 800: 8, 836: 8, 845: 5, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 913: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1009: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1168: 1, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1184: 8, 1185: 8, 1186: 8, 1187: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1208: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1590: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1648: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 400: 6, 426: 6, 452: 8, 464: 8, 466: 8, 467: 5, 544: 4, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767: 4, 800: 8, 836: 8, 845: 5, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 913: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1009: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1168: 1, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1184: 8, 1185: 8, 1186: 8, 1187: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1208: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1590: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1648: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, # IS300H 2017 { - 36: 8, 37: 8, 170: 8, 180: 8, 295: 8, 296: 8, 400: 6, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767:4, 800: 8, 836: 8, 845: 5, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 913: 8, 916: 3, 918: 7, 921: 7, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1009: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1168: 1, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1187: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1208: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 295: 8, 296: 8, 400: 6, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767: 4, 800: 8, 836: 8, 845: 5, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 913: 8, 916: 3, 918: 7, 921: 7, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1009: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1168: 1, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1187: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1208: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }], CAR.RAV4H_TSS2: [ #Hybrid Limited { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913:8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 987: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 987: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }, ], CAR.LEXUS_CTH: [{ @@ -552,11 +552,11 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x750, 0x6d): [b'8646F0E01200\x00\x00\x00\x00'], }, CAR.HIGHLANDERH_TSS2: { - (Ecu.eps, 0x7a1, None): [b'8965B48241\x00\x00\x00\x00\x00\x00',], - (Ecu.esp, 0x7b0, None): [b'\x01F15264872300\x00\x00\x00\x00',], - (Ecu.engine, 0x700, None): [b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',], - (Ecu.fwdRadar, 0x750, 0xf): [b'\x018821F3301400\x00\x00\x00\x00',], - (Ecu.fwdCamera, 0x750, 0x6d): [b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',], + (Ecu.eps, 0x7a1, None): [b'8965B48241\x00\x00\x00\x00\x00\x00', ], + (Ecu.esp, 0x7b0, None): [b'\x01F15264872300\x00\x00\x00\x00', ], + (Ecu.engine, 0x700, None): [b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', ], + (Ecu.fwdRadar, 0x750, 0xf): [b'\x018821F3301400\x00\x00\x00\x00', ], + (Ecu.fwdCamera, 0x750, 0x6d): [b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', ], }, CAR.LEXUS_IS: { (Ecu.engine, 0x700, None): [b'\x018966353Q2300\x00\x00\x00\x00'], diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index 91b24dc4ff..1bec834969 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -28,11 +28,11 @@ class CarState(CarStateBase): # Update steering angle, rate, yaw rate, and driver input torque. VW send # the sign/direction in a separate signal so they must be recombined. - ret.steeringAngle = pt_cp.vl["LWI_01"]['LWI_Lenkradwinkel'] * (1,-1)[int(pt_cp.vl["LWI_01"]['LWI_VZ_Lenkradwinkel'])] - ret.steeringRate = pt_cp.vl["LWI_01"]['LWI_Lenkradw_Geschw'] * (1,-1)[int(pt_cp.vl["LWI_01"]['LWI_VZ_Lenkradwinkel'])] - ret.steeringTorque = pt_cp.vl["EPS_01"]['Driver_Strain'] * (1,-1)[int(pt_cp.vl["EPS_01"]['Driver_Strain_VZ'])] + ret.steeringAngle = pt_cp.vl["LWI_01"]['LWI_Lenkradwinkel'] * (1, -1)[int(pt_cp.vl["LWI_01"]['LWI_VZ_Lenkradwinkel'])] + ret.steeringRate = pt_cp.vl["LWI_01"]['LWI_Lenkradw_Geschw'] * (1, -1)[int(pt_cp.vl["LWI_01"]['LWI_VZ_Lenkradwinkel'])] + ret.steeringTorque = pt_cp.vl["EPS_01"]['Driver_Strain'] * (1, -1)[int(pt_cp.vl["EPS_01"]['Driver_Strain_VZ'])] ret.steeringPressed = abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE - ret.yawRate = pt_cp.vl["ESP_02"]['ESP_Gierrate'] * (1,-1)[int(pt_cp.vl["ESP_02"]['ESP_VZ_Gierrate'])] * CV.DEG_TO_RAD + ret.yawRate = pt_cp.vl["ESP_02"]['ESP_Gierrate'] * (1, -1)[int(pt_cp.vl["ESP_02"]['ESP_VZ_Gierrate'])] * CV.DEG_TO_RAD # Update gas, brakes, and gearshift. ret.gas = pt_cp.vl["Motor_20"]['MO_Fahrpedalrohwert_01'] / 100.0 diff --git a/selfdrive/controls/dmonitoringd.py b/selfdrive/controls/dmonitoringd.py index 06cf556005..0f949c2e89 100755 --- a/selfdrive/controls/dmonitoringd.py +++ b/selfdrive/controls/dmonitoringd.py @@ -37,7 +37,7 @@ def dmonitoringd_thread(sm=None, pm=None): sm['carState'].steeringPressed = False sm['carState'].standstill = True - cal_rpy = [0,0,0] + cal_rpy = [0, 0, 0] v_cruise_last = 0 driver_engaged = False diff --git a/selfdrive/controls/lib/latcontrol_lqr.py b/selfdrive/controls/lib/latcontrol_lqr.py index b27f8c3e33..cb54e52ebd 100644 --- a/selfdrive/controls/lib/latcontrol_lqr.py +++ b/selfdrive/controls/lib/latcontrol_lqr.py @@ -10,11 +10,11 @@ class LatControlLQR(): self.scale = CP.lateralTuning.lqr.scale self.ki = CP.lateralTuning.lqr.ki - self.A = np.array(CP.lateralTuning.lqr.a).reshape((2,2)) - self.B = np.array(CP.lateralTuning.lqr.b).reshape((2,1)) - self.C = np.array(CP.lateralTuning.lqr.c).reshape((1,2)) - self.K = np.array(CP.lateralTuning.lqr.k).reshape((1,2)) - self.L = np.array(CP.lateralTuning.lqr.l).reshape((2,1)) + self.A = np.array(CP.lateralTuning.lqr.a).reshape((2, 2)) + self.B = np.array(CP.lateralTuning.lqr.b).reshape((2, 1)) + self.C = np.array(CP.lateralTuning.lqr.c).reshape((1, 2)) + self.K = np.array(CP.lateralTuning.lqr.k).reshape((1, 2)) + self.L = np.array(CP.lateralTuning.lqr.l).reshape((2, 1)) self.dc_gain = CP.lateralTuning.lqr.dcGain self.x_hat = np.array([[0], [0]]) diff --git a/selfdrive/controls/tests/test_monitoring.py b/selfdrive/controls/tests/test_monitoring.py index fce87af872..c0f5fd8066 100644 --- a/selfdrive/controls/tests/test_monitoring.py +++ b/selfdrive/controls/tests/test_monitoring.py @@ -20,15 +20,15 @@ _UNCERTAIN_SECONDS_TO_GREEN = _HI_STD_TIMEOUT + 0.5 class fake_DM_msg(): def __init__(self, is_face_detected, is_distracted=False, is_model_uncertain=False): - self.faceOrientation = [0.,0.,0.] - self.facePosition = [0.,0.] + self.faceOrientation = [0., 0., 0.] + self.facePosition = [0., 0.] self.faceProb = 1. * is_face_detected self.leftEyeProb = 1. self.rightEyeProb = 1. self.leftBlinkProb = 1. * is_distracted self.rightBlinkProb = 1. * is_distracted - self.faceOrientationStd = [1.*is_model_uncertain,1.*is_model_uncertain,1.*is_model_uncertain] - self.facePositionStd = [1.*is_model_uncertain,1.*is_model_uncertain] + self.faceOrientationStd = [1.*is_model_uncertain, 1.*is_model_uncertain, 1.*is_model_uncertain] + self.facePositionStd = [1.*is_model_uncertain, 1.*is_model_uncertain] # driver state from neural net, 10Hz @@ -64,7 +64,7 @@ def run_DState_seq(driver_state_msgs, driver_car_interaction, openpilot_status, events_from_DM = [] for idx in range(len(driver_state_msgs)): e = Events() - DS.get_pose(driver_state_msgs[idx], [0,0,0], 0, openpilot_status[idx]) + DS.get_pose(driver_state_msgs[idx], [0, 0, 0], 0, openpilot_status[idx]) # cal_rpy and car_speed don't matter here # evaluate events at 10Hz for tests @@ -138,7 +138,7 @@ class TestMonitoring(unittest.TestCase): # 5. op engaged, invisible driver, down to orange, driver touches wheel; then down to orange again, driver appears # - both actions should clear the alert, but momentary appearence should not def test_sometimes_transparent_commuter(self): - _visible_time = np.random.choice([1,10]) # seconds + _visible_time = np.random.choice([1, 10]) # seconds # print _visible_time ds_vector = always_no_face[:]*2 interaction_vector = always_false[:]*2 diff --git a/selfdrive/debug/can_printer.py b/selfdrive/debug/can_printer.py index f06db79545..7ea26d62fc 100755 --- a/selfdrive/debug/can_printer.py +++ b/selfdrive/debug/can_printer.py @@ -25,9 +25,9 @@ def can_printer(bus=0, max_msg=None, addr="127.0.0.1"): if sec_since_boot() - lp > 0.1: dd = chr(27) + "[2J" dd += "%5.2f\n" % (sec_since_boot() - start) - for k,v in sorted(zip(msgs.keys(), map(lambda x: binascii.hexlify(x[-1]), msgs.values()))): + for k, v in sorted(zip(msgs.keys(), map(lambda x: binascii.hexlify(x[-1]), msgs.values()))): if max_msg is None or k < max_msg: - dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v.decode('ascii')) + dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k, k), len(msgs[k]), v.decode('ascii')) print(dd) lp = sec_since_boot() diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index c3f54f9439..1dcc4996b2 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -69,7 +69,7 @@ if __name__ == "__main__": k = ' '.join(p.cmdline()) print('Add monitored proc:', k) stats[k] = {'cpu_samples': defaultdict(list), 'min': defaultdict(lambda: None), 'max': defaultdict(lambda: None), - 'avg': defaultdict(lambda: 0.0), 'last_cpu_times': None, 'last_sys_time':None} + 'avg': defaultdict(lambda: 0.0), 'last_cpu_times': None, 'last_sys_time': None} stats[k]['last_sys_time'] = timer() stats[k]['last_cpu_times'] = p.cpu_times() monitored_procs.append(p) diff --git a/selfdrive/debug/internal/sensor_test_bootloop.py b/selfdrive/debug/internal/sensor_test_bootloop.py index 041905544e..5d0208d298 100755 --- a/selfdrive/debug/internal/sensor_test_bootloop.py +++ b/selfdrive/debug/internal/sensor_test_bootloop.py @@ -45,7 +45,7 @@ else: with open('/tmp/dmesg-' + timestr + '.log', 'w') as dmesg_out: subprocess.call('dmesg', stdout=dmesg_out, shell=False) with open("/tmp/logcat-" + timestr + '.log', 'w') as logcat_out: - subprocess.call(['logcat','-d'], stdout=logcat_out, shell=False) + subprocess.call(['logcat', '-d'], stdout=logcat_out, shell=False) text += "Sensor pass history: " + str(data['sensor-pass']) + "\n" text += "Sensor fail history: " + str(data['sensor-fail']) + "\n" diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 7d8e440b84..14754f75b2 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -30,15 +30,15 @@ DEBUG = os.getenv("DEBUG") is not None def is_calibration_valid(vp): - return vp[0] > VP_VALIDITY_CORNERS[0,0] and vp[0] < VP_VALIDITY_CORNERS[1,0] and \ - vp[1] > VP_VALIDITY_CORNERS[0,1] and vp[1] < VP_VALIDITY_CORNERS[1,1] + return vp[0] > VP_VALIDITY_CORNERS[0, 0] and vp[0] < VP_VALIDITY_CORNERS[1, 0] and \ + vp[1] > VP_VALIDITY_CORNERS[0, 1] and vp[1] < VP_VALIDITY_CORNERS[1, 1] def sanity_clip(vp): if np.isnan(vp).any(): vp = VP_INIT - return np.array([np.clip(vp[0], VP_VALIDITY_CORNERS[0,0] - 5, VP_VALIDITY_CORNERS[1,0] + 5), - np.clip(vp[1], VP_VALIDITY_CORNERS[0,1] - 5, VP_VALIDITY_CORNERS[1,1] + 5)]) + return np.array([np.clip(vp[0], VP_VALIDITY_CORNERS[0, 0] - 5, VP_VALIDITY_CORNERS[1, 0] + 5), + np.clip(vp[1], VP_VALIDITY_CORNERS[0, 1] - 5, VP_VALIDITY_CORNERS[1, 1] + 5)]) def intrinsics_from_vp(vp): diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index bc5cd97c3f..ad84550601 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -93,7 +93,7 @@ class Localizer(): vel_device = device_from_ecef.dot(vel_ecef) device_from_ecef_eul = euler_from_quat(predicted_state[States.ECEF_ORIENTATION]).T idxs = list(range(States.ECEF_ORIENTATION_ERR.start, States.ECEF_ORIENTATION_ERR.stop)) + list(range(States.ECEF_VELOCITY_ERR.start, States.ECEF_VELOCITY_ERR.stop)) - condensed_cov = predicted_cov[idxs][:,idxs] + condensed_cov = predicted_cov[idxs][:, idxs] HH = H(*list(np.concatenate([device_from_ecef_eul, vel_ecef]))) vel_device_cov = HH.dot(condensed_cov).dot(HH.T) vel_device_std = np.sqrt(np.diagonal(vel_device_cov)) diff --git a/selfdrive/locationd/models/live_kf.py b/selfdrive/locationd/models/live_kf.py index 71d4d31fbe..a6a6eaf0b1 100755 --- a/selfdrive/locationd/models/live_kf.py +++ b/selfdrive/locationd/models/live_kf.py @@ -80,7 +80,7 @@ class LiveKalman(): omega = state[States.ANGULAR_VELOCITY, :] vroll, vpitch, vyaw = omega roll_bias, pitch_bias, yaw_bias = state[States.GYRO_BIAS, :] - odo_scale = state[States.ODO_SCALE, :][0,:] + odo_scale = state[States.ODO_SCALE, :][0, :] acceleration = state[States.ACCELERATION, :] imu_angles = state[States.IMU_OFFSET, :] diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index 06e16045d6..9b1329511d 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -176,7 +176,7 @@ class LocKalman(): state_dot[13, 0] = cd state_dot[14, 0] = ca #state_dot[States.CLOCK_BIAS, 0][0,0] = cd - state_dot[States.CLOCK_DRIFT, 0][0,0] = ca + state_dot[States.CLOCK_DRIFT, 0][0, 0] = ca # Basic descretization, 1st order intergrator # Can be pretty bad if dt is big @@ -201,8 +201,8 @@ class LocKalman(): state_err_dot[States.ECEF_VELOCITY_ERR, :] = quat_err_matrix * quat_rot * (acceleration + acceleration_err) #state_err_dot[States.CLOCK_BIAS_ERR, :][0,:] = cd_err #state_err_dot[States.CLOCK_DRIFT_ERR, :][0,:] = ca_err - state_err_dot[12, :][0,:] = cd_err - state_err_dot[13, :][0,:] = ca_err + state_err_dot[12, :][0, :] = cd_err + state_err_dot[13, :][0, :] = ca_err f_err_sym = state_err + dt * state_err_dot # convenient indexing diff --git a/selfdrive/locationd/test/ublox.py b/selfdrive/locationd/test/ublox.py index b699a37211..cfb32ed816 100644 --- a/selfdrive/locationd/test/ublox.py +++ b/selfdrive/locationd/test/ublox.py @@ -717,7 +717,7 @@ class UBlox: self.dev = PandaSerial(self.panda, 1, self.baudrate) self.baudrate = 460800 - print("upping baud:",self.baudrate) + print("upping baud:", self.baudrate) self.send_nmea("$PUBX,41,1,0007,0003,%u,0" % self.baudrate) time.sleep(0.1) diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index 927a1e2756..570e9d0a1c 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -21,7 +21,7 @@ print_dB = os.getenv("PRINT_DB") is not None # print antenna dB timeout = 1 dyn_model = 4 # auto model baudrate = 460800 -ports = ["/dev/ttyACM0","/dev/ttyACM1"] +ports = ["/dev/ttyACM0", "/dev/ttyACM1"] rate = 100 # send new data every 100ms # which SV IDs we have seen and when we got iono @@ -135,7 +135,7 @@ def gen_solution(msg): msg_data['hour'], msg_data['min'], msg_data['sec']) - - datetime.datetime(1970,1,1)).total_seconds())*1e+03 + + datetime.datetime(1970, 1, 1)).total_seconds())*1e+03 + msg_data['nano']*1e-06) gps_fix = {'bearing': msg_data['headMot']*1e-05, # heading of motion in degrees 'altitude': msg_data['height']*1e-03, # altitude above ellipsoid @@ -281,7 +281,7 @@ def main(): global gpsLocationExternal, ubloxGnss nav_frame_buffer = {} nav_frame_buffer[0] = {} - for i in range(1,33): + for i in range(1, 33): nav_frame_buffer[0][i] = {} diff --git a/selfdrive/loggerd/tests/test_uploader.py b/selfdrive/loggerd/tests/test_uploader.py index 96f449b03b..3df3d937ac 100644 --- a/selfdrive/loggerd/tests/test_uploader.py +++ b/selfdrive/loggerd/tests/test_uploader.py @@ -61,9 +61,9 @@ class TestUploader(UploaderTestCase): keys = [f"{self.seg_format.format(i)}/qlog.bz2" for i in seg1] keys += [f"{self.seg_format2.format(i)}/qlog.bz2" for i in seg2] for i in seg1: - keys += [f"{self.seg_format.format(i)}/{f}" for f in ['rlog.bz2','fcamera.hevc','dcamera.hevc']] + keys += [f"{self.seg_format.format(i)}/{f}" for f in ['rlog.bz2', 'fcamera.hevc', 'dcamera.hevc']] for i in seg2: - keys += [f"{self.seg_format2.format(i)}/{f}" for f in ['rlog.bz2','fcamera.hevc','dcamera.hevc']] + keys += [f"{self.seg_format2.format(i)}/{f}" for f in ['rlog.bz2', 'fcamera.hevc', 'dcamera.hevc']] keys += [f"{self.seg_format.format(i)}/bootlog.bz2" for i in seg1] keys += [f"{self.seg_format2.format(i)}/bootlog.bz2" for i in seg2] return keys @@ -103,11 +103,11 @@ class TestUploader(UploaderTestCase): def test_upload_files_in_create_order(self): f_paths = list() - seg1_nums = [0,1,2,10,20] + seg1_nums = [0, 1, 2, 10, 20] for i in seg1_nums: self.seg_dir = self.seg_format.format(i) f_paths += self.gen_files() - seg2_nums = [5,50,51] + seg2_nums = [5, 50, 51] for i in seg2_nums: self.seg_dir = self.seg_format2.format(i) f_paths += self.gen_files() diff --git a/selfdrive/manager.py b/selfdrive/manager.py index bf237ee76c..d849c7f865 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -124,7 +124,7 @@ if not prebuilt: if retry: print("scons build failed, cleaning in") - for i in range(3,-1,-1): + for i in range(3, -1, -1): print("....%d" % i) time.sleep(1) subprocess.check_call(["scons", "-c"], cwd=BASEDIR, env=env) diff --git a/selfdrive/modeld/runners/keras_runner.py b/selfdrive/modeld/runners/keras_runner.py index 5ed0e6d79c..08b098feee 100755 --- a/selfdrive/modeld/runners/keras_runner.py +++ b/selfdrive/modeld/runners/keras_runner.py @@ -48,7 +48,7 @@ if __name__ == "__main__": acc = 0 for i, ii in enumerate(m.inputs): print(ii, file=sys.stderr) - ti = keras.layers.Lambda(lambda x: x[:,acc:acc+bs[i]], output_shape=(1, bs[i]))(ri) + ti = keras.layers.Lambda(lambda x: x[:, acc:acc+bs[i]], output_shape=(1, bs[i]))(ri) acc += bs[i] tr = keras.layers.Reshape(ii.shape[1:])(ti) tii.append(tr) diff --git a/selfdrive/registration.py b/selfdrive/registration.py index dbedcc9ebc..6e1596f35a 100644 --- a/selfdrive/registration.py +++ b/selfdrive/registration.py @@ -45,7 +45,7 @@ def register(): # late import import jwt - register_token = jwt.encode({'register':True, 'exp': datetime.utcnow() + timedelta(hours=1)}, private_key, algorithm='RS256') + register_token = jwt.encode({'register': True, 'exp': datetime.utcnow() + timedelta(hours=1)}, private_key, algorithm='RS256') try: cloudlog.info("getting pilotauth") diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index acb1475afd..faf00233d9 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -129,7 +129,7 @@ class Plant(): self.esp_disabled = 0 self.main_on = 1 self.user_gas = 0 - self.computer_brake,self.user_brake = 0,0 + self.computer_brake, self.user_brake = 0, 0 self.brake_pressed = 0 self.angle_steer_rate = 0 self.distance, self.distance_prev = 0., 0. diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py index 02e4e63ca0..08b6cd047d 100755 --- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py +++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py @@ -151,8 +151,8 @@ maneuvers = [ 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.], + 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)], @@ -164,7 +164,7 @@ maneuvers = [ initial_speed=10., lead_relevancy=True, initial_distance_lead=20., - speed_lead_values=[10., 0., 0., 10., 0.,10.], + 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), diff --git a/selfdrive/test/process_replay/inject_model.py b/selfdrive/test/process_replay/inject_model.py index 98a6794d7e..aaba744419 100755 --- a/selfdrive/test/process_replay/inject_model.py +++ b/selfdrive/test/process_replay/inject_model.py @@ -28,7 +28,7 @@ def regen_model(msgs, pm, frame_reader, model_sock): if w == 'frame': msg = msg.as_builder() - img = frame_reader.get(fidx, pix_fmt="rgb24")[0][:,::-1] + img = frame_reader.get(fidx, pix_fmt="rgb24")[0][:, ::-1] msg.frame.image = img.flatten().tobytes() diff --git a/selfdrive/test/test_leeco_alt_fan.py b/selfdrive/test/test_leeco_alt_fan.py index b1ab5c54d4..0a51e94064 100755 --- a/selfdrive/test/test_leeco_alt_fan.py +++ b/selfdrive/test/test_leeco_alt_fan.py @@ -8,7 +8,7 @@ def setup_leon_fan(): bus = SMBus(7, force=True) # http://www.ti.com/lit/ds/symlink/tusb320.pdf - for i in [0,1,2,3]: + for i in [0, 1, 2, 3]: print("FAN SPEED", i) if i == 0: bus.write_i2c_block_data(0x67, 0xa, [0]) diff --git a/tools/carcontrols/joystick_test.py b/tools/carcontrols/joystick_test.py index cb2309d11a..64bb1b37f8 100755 --- a/tools/carcontrols/joystick_test.py +++ b/tools/carcontrols/joystick_test.py @@ -104,7 +104,7 @@ while not done: for i in range( buttons ): button = joystick.get_button( i ) - textPrint.printf(screen, "Button {:>2} value: {}".format(i,button) ) + textPrint.printf(screen, "Button {:>2} value: {}".format(i, button) ) textPrint.unindent() diff --git a/tools/lib/framereader.py b/tools/lib/framereader.py index 5a1403591c..98a292fdc9 100644 --- a/tools/lib/framereader.py +++ b/tools/lib/framereader.py @@ -207,7 +207,7 @@ def rgb24toyuv420(rgb): yuv420[y_len:y_len + uv_len] = us.reshape(-1) yuv420[y_len + uv_len:y_len + 2 * uv_len] = vs.reshape(-1) - return yuv420.clip(0,255).astype('uint8') + return yuv420.clip(0, 255).astype('uint8') def decompress_video_data(rawdat, vid_fmt, w, h, pix_fmt): diff --git a/tools/lib/kbhit.py b/tools/lib/kbhit.py index 99b88bfbcc..d640cf54c2 100644 --- a/tools/lib/kbhit.py +++ b/tools/lib/kbhit.py @@ -57,7 +57,7 @@ class KBHit: def kbhit(self): ''' Returns True if keyboard character was hit, False otherwise. ''' - dr,dw,de = select([sys.stdin], [], [], 0) + dr, dw, de = select([sys.stdin], [], [], 0) return dr != [] diff --git a/tools/livedm/helpers.py b/tools/livedm/helpers.py index df392bfd9b..023174e171 100644 --- a/tools/livedm/helpers.py +++ b/tools/livedm/helpers.py @@ -5,25 +5,25 @@ def rot_matrix(roll, pitch, yaw): cr, sr = np.cos(roll), np.sin(roll) cp, sp = np.cos(pitch), np.sin(pitch) cy, sy = np.cos(yaw), np.sin(yaw) - rr = np.array([[1,0,0],[0, cr,-sr],[0, sr, cr]]) - rp = np.array([[cp,0,sp],[0, 1,0],[-sp, 0, cp]]) - ry = np.array([[cy,-sy,0],[sy, cy,0],[0, 0, 1]]) + rr = np.array([[1, 0, 0], [0, cr, -sr], [0, sr, cr]]) + rp = np.array([[cp, 0, sp], [0, 1, 0], [-sp, 0, cp]]) + ry = np.array([[cy, -sy, 0], [sy, cy, 0], [0, 0, 1]]) return ry.dot(rp.dot(rr)) -def draw_pose(img, pose, loc, W=160, H=320, xyoffset=(0,0), faceprob=0): - rcmat = np.zeros((3,4)) - rcmat[:,:3] = rot_matrix(*pose[0:3]) * 0.5 - rcmat[0,3] = (loc[0]+0.5) * W - rcmat[1,3] = (loc[1]+0.5) * H - rcmat[2,3] = 1.0 +def draw_pose(img, pose, loc, W=160, H=320, xyoffset=(0, 0), faceprob=0): + rcmat = np.zeros((3, 4)) + rcmat[:, :3] = rot_matrix(*pose[0:3]) * 0.5 + rcmat[0, 3] = (loc[0]+0.5) * W + rcmat[1, 3] = (loc[1]+0.5) * H + rcmat[2, 3] = 1.0 # draw nose - p1 = np.dot(rcmat, [0,0,0,1])[0:2] - p2 = np.dot(rcmat, [0,0,100,1])[0:2] - tr = tuple([int(round(x + xyoffset[i])) for i,x in enumerate(p1)]) - pr = tuple([int(round(x + xyoffset[i])) for i,x in enumerate(p2)]) + p1 = np.dot(rcmat, [0, 0, 0, 1])[0:2] + p2 = np.dot(rcmat, [0, 0, 100, 1])[0:2] + tr = tuple([int(round(x + xyoffset[i])) for i, x in enumerate(p1)]) + pr = tuple([int(round(x + xyoffset[i])) for i, x in enumerate(p2)]) if faceprob > 0.4: - color = (255,255,0) - cv2.line(img, tr, pr, color=(255,255,0), thickness=3) + color = (255, 255, 0) + cv2.line(img, tr, pr, color=(255, 255, 0), thickness=3) else: - color = (64,64,64) + color = (64, 64, 64) cv2.circle(img, tr, 7, color=color) diff --git a/tools/livedm/livedm.py b/tools/livedm/livedm.py index 360aaee602..906a1da664 100644 --- a/tools/livedm/livedm.py +++ b/tools/livedm/livedm.py @@ -27,8 +27,8 @@ if __name__ == "__main__": pygame.init() pygame.display.set_caption('livedm') - screen = pygame.display.set_mode((320,640), pygame.DOUBLEBUF) - camera_surface = pygame.surface.Surface((160,320), 0, 24).convert() + screen = pygame.display.set_mode((320, 640), pygame.DOUBLEBUF) + camera_surface = pygame.surface.Surface((160, 320), 0, 24).convert() while 1: polld = poller.poll(1000) @@ -46,34 +46,34 @@ if __name__ == "__main__": faceOrientation[1] *= -1 facePosition[0] *= -1 - img = np.zeros((320,160,3)) + img = np.zeros((320, 160, 3)) if faceProb > 0.4: - cv2.putText(img, 'you', (int(facePosition[0]*160+40), int(facePosition[1]*320+110)), cv2.FONT_ITALIC, 0.5, (255,255,0)) + cv2.putText(img, 'you', (int(facePosition[0]*160+40), int(facePosition[1]*320+110)), cv2.FONT_ITALIC, 0.5, (255, 255, 0)) cv2.rectangle(img, (int(facePosition[0]*160+40), int(facePosition[1]*320+120)),\ - (int(facePosition[0]*160+120), int(facePosition[1]*320+200)), (255,255,0), 1) + (int(facePosition[0]*160+120), int(facePosition[1]*320+200)), (255, 255, 0), 1) not_blink = evt.driverMonitoring.leftBlinkProb + evt.driverMonitoring.rightBlinkProb < 1 if evt.driverMonitoring.leftEyeProb > 0.6: cv2.line(img, (int(facePosition[0]*160+95), int(facePosition[1]*320+140)),\ - (int(facePosition[0]*160+105), int(facePosition[1]*320+140)), (255,255,0), 2) + (int(facePosition[0]*160+105), int(facePosition[1]*320+140)), (255, 255, 0), 2) if not_blink: cv2.line(img, (int(facePosition[0]*160+99), int(facePosition[1]*320+143)),\ - (int(facePosition[0]*160+101), int(facePosition[1]*320+143)), (255,255,0), 2) + (int(facePosition[0]*160+101), int(facePosition[1]*320+143)), (255, 255, 0), 2) if evt.driverMonitoring.rightEyeProb > 0.6: cv2.line(img, (int(facePosition[0]*160+55), int(facePosition[1]*320+140)),\ - (int(facePosition[0]*160+65), int(facePosition[1]*320+140)), (255,255,0), 2) + (int(facePosition[0]*160+65), int(facePosition[1]*320+140)), (255, 255, 0), 2) if not_blink: cv2.line(img, (int(facePosition[0]*160+59), int(facePosition[1]*320+143)),\ - (int(facePosition[0]*160+61), int(facePosition[1]*320+143)), (255,255,0), 2) + (int(facePosition[0]*160+61), int(facePosition[1]*320+143)), (255, 255, 0), 2) else: - cv2.putText(img, 'you not found', (int(facePosition[0]*160+40), int(facePosition[1]*320+110)), cv2.FONT_ITALIC, 0.5, (64,64,64)) + cv2.putText(img, 'you not found', (int(facePosition[0]*160+40), int(facePosition[1]*320+110)), cv2.FONT_ITALIC, 0.5, (64, 64, 64)) draw_pose(img, faceOrientation, facePosition, W = 160, H = 320, xyoffset = (0, 0), faceprob=faceProb) - pygame.surfarray.blit_array(camera_surface, img.swapaxes(0,1)) + pygame.surfarray.blit_array(camera_surface, img.swapaxes(0, 1)) camera_surface_2x = pygame.transform.scale2x(camera_surface) screen.blit(camera_surface_2x, (0, 0)) pygame.display.flip() diff --git a/tools/nui/get_files_comma_api.py b/tools/nui/get_files_comma_api.py index 55b7788b36..515f0efd86 100644 --- a/tools/nui/get_files_comma_api.py +++ b/tools/nui/get_files_comma_api.py @@ -6,8 +6,8 @@ from tools.lib.route import Route route_name = sys.argv[1] routes = Route(route_name) data_dump = { - "camera":routes.camera_paths(), - "logs":routes.log_paths() + "camera": routes.camera_paths(), + "logs": routes.log_paths() } json.dump(data_dump, open("routes.json", "w")) diff --git a/tools/replay/lib/ui_helpers.py b/tools/replay/lib/ui_helpers.py index 44fdb2c0f9..277792f54e 100644 --- a/tools/replay/lib/ui_helpers.py +++ b/tools/replay/lib/ui_helpers.py @@ -23,7 +23,7 @@ _PATH_X = np.arange(192.) _PATH_XD = np.arange(192.) _PATH_PINV = compute_path_pinv(50) #_BB_OFFSET = 290, 332 -_BB_OFFSET = 0,0 +_BB_OFFSET = 0, 0 _BB_SCALE = 1164/640. _BB_TO_FULL_FRAME = np.asarray([ [_BB_SCALE, 0., _BB_OFFSET[0]], @@ -110,24 +110,24 @@ def draw_lead_on(img, closest_x_m, closest_y_m, calibration, color, sz=10, img_o def init_plots(arr, name_to_arr_idx, plot_xlims, plot_ylims, plot_names, plot_colors, plot_styles, bigplots=False): - color_palette = { "r": (1,0,0), - "g": (0,1,0), - "b": (0,0,1), - "k": (0,0,0), - "y": (1,1,0), - "p": (0,1,1), - "m": (1,0,1) } + color_palette = { "r": (1, 0, 0), + "g": (0, 1, 0), + "b": (0, 0, 1), + "k": (0, 0, 0), + "y": (1, 1, 0), + "p": (0, 1, 1), + "m": (1, 0, 1) } if bigplots: fig = plt.figure(figsize=(6.4, 7.0)) else: fig = plt.figure() - fig.set_facecolor((0.2,0.2,0.2)) + fig.set_facecolor((0.2, 0.2, 0.2)) axs = [] for pn in range(len(plot_ylims)): - ax = fig.add_subplot(len(plot_ylims),1,len(axs)+1) + ax = fig.add_subplot(len(plot_ylims), 1, len(axs)+1) ax.set_xlim(plot_xlims[pn][0], plot_xlims[pn][1]) ax.set_ylim(plot_ylims[pn][0], plot_ylims[pn][1]) ax.patch.set_facecolor((0.4, 0.4, 0.4)) diff --git a/tools/replay/sensorium.py b/tools/replay/sensorium.py index a7d9ee6819..fdc24baf87 100755 --- a/tools/replay/sensorium.py +++ b/tools/replay/sensorium.py @@ -35,7 +35,7 @@ if __name__ == "__main__": if sm.updated['liveCalibration']: intrinsic_matrix = eon_intrinsics - img_transform = np.array(fpkt.frame.transform).reshape(3,3) + img_transform = np.array(fpkt.frame.transform).reshape(3, 3) extrinsic_matrix = np.asarray(sm['liveCalibration'].extrinsicMatrix).reshape(3, 4) ke = intrinsic_matrix.dot(extrinsic_matrix) warp_matrix = get_camera_frame_from_medmodel_frame(ke) diff --git a/tools/replay/ui.py b/tools/replay/ui.py index 9d30c38522..1bd8cd3a85 100755 --- a/tools/replay/ui.py +++ b/tools/replay/ui.py @@ -63,7 +63,7 @@ def ui_thread(addr, frame_address): camera_surface = pygame.surface.Surface((640, 480), 0, 24).convert() cameraw_surface = pygame.surface.Surface(MODEL_INPUT_SIZE, 0, 24).convert() - top_down_surface = pygame.surface.Surface((UP.lidar_x, UP.lidar_y),0,8) + top_down_surface = pygame.surface.Surface((UP.lidar_x, UP.lidar_y), 0, 8) frame = messaging.sub_sock('frame', addr=addr, conflate=True) sm = messaging.SubMaster(['carState', 'plan', 'carControl', 'radarState', 'liveCalibration', 'controlsState', 'liveTracks', 'model', 'liveMpc', 'liveParameters', 'pathPlan'], addr=addr) @@ -113,7 +113,7 @@ def ui_thread(addr, frame_address): while 1: list(pygame.event.get()) - screen.fill((64,64,64)) + screen.fill((64, 64, 64)) lid_overlay = lid_overlay_blank.copy() top_down = top_down_surface, lid_overlay @@ -122,7 +122,7 @@ def ui_thread(addr, frame_address): rgb_img_raw = fpkt.frame.image if fpkt.frame.transform: - img_transform = np.array(fpkt.frame.transform).reshape(3,3) + img_transform = np.array(fpkt.frame.transform).reshape(3, 3) else: # assume frame is flipped img_transform = np.array([ @@ -200,17 +200,17 @@ def ui_thread(addr, frame_address): for lead in [sm['radarState'].leadOne, sm['radarState'].leadTwo]: if lead.status: if calibration is not None: - draw_lead_on(img, lead.dRel, lead.yRel, calibration, color=(192,0,0)) + draw_lead_on(img, lead.dRel, lead.yRel, calibration, color=(192, 0, 0)) draw_lead_car(lead.dRel, top_down) # *** blits *** - pygame.surfarray.blit_array(camera_surface, img.swapaxes(0,1)) + pygame.surfarray.blit_array(camera_surface, img.swapaxes(0, 1)) screen.blit(camera_surface, (0, 0)) # display alerts - alert_line1 = alert1_font.render(sm['controlsState'].alertText1, True, (255,0,0)) - alert_line2 = alert2_font.render(sm['controlsState'].alertText2, True, (255,0,0)) + alert_line1 = alert1_font.render(sm['controlsState'].alertText1, True, (255, 0, 0)) + alert_line2 = alert2_font.render(sm['controlsState'].alertText2, True, (255, 0, 0)) screen.blit(alert_line1, (180, 150)) screen.blit(alert_line2, (180, 190)) @@ -229,7 +229,7 @@ def ui_thread(addr, frame_address): screen.blit(cameraw_surface, (320, 480)) pygame.surfarray.blit_array(*top_down) - screen.blit(top_down[0], (640,0)) + screen.blit(top_down[0], (640, 0)) i = 0 SPACING = 25 diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index 3c402c4150..dd11cd942f 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -22,12 +22,12 @@ args = parser.parse_args() pm = messaging.PubMaster(['frame', 'sensorEvents', 'can']) -W,H = 1164, 874 +W, H = 1164, 874 def cam_callback(image): img = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) img = np.reshape(img, (H, W, 4)) - img = img[:, :, [0,1,2]].copy() + img = img[:, :, [0, 1, 2]].copy() dat = messaging.new_message('frame') dat.frame = { diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index 5e206e3378..9bb205a126 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -37,7 +37,7 @@ def can_function(pm, speed, angle, idx, cruise_button=0, is_engaged=False): msg.append(packer.make_can_msg("GAS_PEDAL_2", 0, {}, idx)) msg.append(packer.make_can_msg("SEATBELT_STATUS", 0, {"SEATBELT_DRIVER_LATCHED": 1}, idx)) msg.append(packer.make_can_msg("STEER_STATUS", 0, {}, idx)) - msg.append(packer.make_can_msg("STEERING_SENSORS", 0, {"STEER_ANGLE":angle_to_sangle(angle)}, idx)) + msg.append(packer.make_can_msg("STEERING_SENSORS", 0, {"STEER_ANGLE": angle_to_sangle(angle)}, idx)) msg.append(packer.make_can_msg("POWERTRAIN_DATA", 0, {}, idx)) msg.append(packer.make_can_msg("VSA_STATUS", 0, {}, idx)) msg.append(packer.make_can_msg("STANDSTILL", 0, {}, idx)) @@ -63,7 +63,7 @@ def can_function(pm, speed, angle, idx, cruise_button=0, is_engaged=False): # fill in the rest for fingerprint done = set([x[0] for x in msg]) - for k,v in FINGERPRINTS[CAR.CIVIC][0].items(): + for k, v in FINGERPRINTS[CAR.CIVIC][0].items(): if k not in done and k not in [0xE4, 0x194]: msg.append([k, 0, b'\x00'*v, 0]) pm.send('can', can_list_to_can_capnp(msg)) diff --git a/tools/sim/lib/manual_ctrl.py b/tools/sim/lib/manual_ctrl.py index 6d66097df9..16cf42af46 100755 --- a/tools/sim/lib/manual_ctrl.py +++ b/tools/sim/lib/manual_ctrl.py @@ -167,19 +167,19 @@ def wheel_poll_thread(q): q.put(str("steer_%f" % normalized)) if mtype & 0x01: # buttons - if number in [0,19]: # X + if number in [0, 19]: # X if value == 1: # press down q.put(str("cruise_down")) - if number in [3,18]: # triangle + if number in [3, 18]: # triangle if value == 1: # press down q.put(str("cruise_up")) - if number in [1,6]: # square + if number in [1, 6]: # square if value == 1: # press down q.put(str("cruise_cancel")) - if number in [10,21]: # R3 + if number in [10, 21]: # R3 if value == 1: # press down q.put(str("reverse_switch")) diff --git a/tools/streamer/streamerd.py b/tools/streamer/streamerd.py index 9cbb2f064b..7bfaeb38d5 100755 --- a/tools/streamer/streamerd.py +++ b/tools/streamer/streamerd.py @@ -26,8 +26,8 @@ def receiver_thread(): if PYGAME: pygame.init() pygame.display.set_caption("vnet debug UI") - screen = pygame.display.set_mode((1164,874), pygame.DOUBLEBUF) - camera_surface = pygame.surface.Surface((1164,874), 0, 24).convert() + screen = pygame.display.set_mode((1164, 874), pygame.DOUBLEBUF) + camera_surface = pygame.surface.Surface((1164, 874), 0, 24).convert() addr = "192.168.5.11" if len(sys.argv) >= 2: @@ -77,7 +77,7 @@ def receiver_thread(): #scipy.misc.imsave("tmp.png", imgff) - pygame.surfarray.blit_array(camera_surface, imgff.swapaxes(0,1)) + pygame.surfarray.blit_array(camera_surface, imgff.swapaxes(0, 1)) screen.blit(camera_surface, (0, 0)) pygame.display.flip() diff --git a/tools/webcam/front_mount_helper.py b/tools/webcam/front_mount_helper.py index 78b707950e..73f446582c 100755 --- a/tools/webcam/front_mount_helper.py +++ b/tools/webcam/front_mount_helper.py @@ -20,7 +20,7 @@ cam_id = 2 if __name__ == "__main__": import cv2 # pylint: disable=import-error - trans_webcam_to_eon_front = np.dot(eon_dcam_intrinsics,np.linalg.inv(webcam_intrinsics)) + trans_webcam_to_eon_front = np.dot(eon_dcam_intrinsics, np.linalg.inv(webcam_intrinsics)) cap = cv2.VideoCapture(cam_id) cap.set(cv2.CAP_PROP_FRAME_WIDTH, 1280) @@ -29,7 +29,7 @@ if __name__ == "__main__": while (True): ret, img = cap.read() if ret: - img = cv2.warpPerspective(img, trans_webcam_to_eon_front, (1152,864), borderMode=cv2.BORDER_CONSTANT, borderValue=0) - img = img[:,-864//2:,:] + img = cv2.warpPerspective(img, trans_webcam_to_eon_front, (1152, 864), borderMode=cv2.BORDER_CONSTANT, borderValue=0) + img = img[:, -864//2:, :] cv2.imshow('preview', img) cv2.waitKey(10) diff --git a/tools/webcam/warp_vis.py b/tools/webcam/warp_vis.py index a1cb3e7e45..3daec95fbe 100755 --- a/tools/webcam/warp_vis.py +++ b/tools/webcam/warp_vis.py @@ -24,8 +24,8 @@ webcam_intrinsics = np.array([ if __name__ == "__main__": import cv2 # pylint: disable=import-error - trans_webcam_to_eon_rear = np.dot(eon_intrinsics,np.linalg.inv(webcam_intrinsics)) - trans_webcam_to_eon_front = np.dot(eon_dcam_intrinsics,np.linalg.inv(webcam_intrinsics)) + trans_webcam_to_eon_rear = np.dot(eon_intrinsics, np.linalg.inv(webcam_intrinsics)) + trans_webcam_to_eon_front = np.dot(eon_dcam_intrinsics, np.linalg.inv(webcam_intrinsics)) print("trans_webcam_to_eon_rear:\n", trans_webcam_to_eon_rear) print("trans_webcam_to_eon_front:\n", trans_webcam_to_eon_front) @@ -37,7 +37,7 @@ if __name__ == "__main__": ret, img = cap.read() if ret: # img = cv2.warpPerspective(img, trans_webcam_to_eon_rear, (1164,874), borderMode=cv2.BORDER_CONSTANT, borderValue=0) - img = cv2.warpPerspective(img, trans_webcam_to_eon_front, (1164,874), borderMode=cv2.BORDER_CONSTANT, borderValue=0) + img = cv2.warpPerspective(img, trans_webcam_to_eon_front, (1164, 874), borderMode=cv2.BORDER_CONSTANT, borderValue=0) print(img.shape, end='\r') cv2.imshow('preview', img) cv2.waitKey(10) From 0e7d50941551d27c8f12e618fac0c03a96109f07 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sun, 31 May 2020 12:50:13 -0700 Subject: [PATCH 155/656] fake text window has no close --- common/text_window.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/common/text_window.py b/common/text_window.py index 50fdcb6440..7bcad25094 100755 --- a/common/text_window.py +++ b/common/text_window.py @@ -59,6 +59,9 @@ class FakeTextWindow(TextWindow): def update(self, _): pass + def close(self): + pass + def __exit__(self, type, value, traceback): pass From 775acd11ba2e0a8c2f5a5655338718d796491b36 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sun, 31 May 2020 13:20:56 -0700 Subject: [PATCH 156/656] Temporarily disable openpilot run in jenkins test until testing stuff is back up --- release/build_devel.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/release/build_devel.sh b/release/build_devel.sh index c3028d5520..eb39f77810 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -109,7 +109,7 @@ echo -n "1" > /data/params/d/HasCompletedSetup echo -n "1" > /data/params/d/CommunityFeaturesToggle PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" nosetests -s selfdrive/test/test_openpilot.py -PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" GET_CPU_USAGE=1 selfdrive/manager.py +#PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" GET_CPU_USAGE=1 selfdrive/manager.py echo "[-] testing panda build T=$SECONDS" pushd panda/board/ From ea74edf71be344b09eb9c5802405ef9aefc6b614 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sun, 31 May 2020 13:31:44 -0700 Subject: [PATCH 157/656] Bump version to 0.8.0 --- selfdrive/common/version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index d6131d2de7..6787344481 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.7.6" +#define COMMA_VERSION "0.8.0" From 106cddb49a3c60449a0413ff28dbbe50479c43bf Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sun, 31 May 2020 13:33:56 -0700 Subject: [PATCH 158/656] White panda no longer supported --- RELEASES.md | 4 ++++ selfdrive/car/car_helpers.py | 2 -- selfdrive/common/version.h | 2 +- selfdrive/controls/controlsd.py | 4 ++-- 4 files changed, 7 insertions(+), 5 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index 4f502fd4ff..e3da108f30 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,7 @@ +Version 0.8 (2020-xx-xx) +======================== + * White panda is no longer supported, upgrade to comma two or black panda + Version 0.7.6 (2020-06-05) ======================== * White panda is deprecated, upgrade to comma two or black panda diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 23cbd1abf5..573bd6f962 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -22,8 +22,6 @@ def get_startup_event(car_recognized, controller_available, hw_type): event = EventName.startupNoCar elif car_recognized and not controller_available: event = EventName.startupNoControl - elif hw_type == HwType.whitePanda: - event = EventName.startupWhitePanda return event diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index 6787344481..f9b22edef6 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.8.0" +#define COMMA_VERSION "0.8" diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 55cfe1bf1e..46a657f3fc 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -139,8 +139,8 @@ class Controls: self.events.add(EventName.communityFeatureDisallowed, static=True) if self.read_only and not passive: self.events.add(EventName.carUnrecognized, static=True) - # if hw_type == HwType.whitePanda: - # self.events.add(EventName.whitePandaUnsupported, static=True) + if hw_type == HwType.whitePanda: + self.events.add(EventName.whitePandaUnsupported, static=True) # controlsd is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) From a0adc4482108a3b89b6e4cb3fe27b8f51291bc08 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sun, 31 May 2020 13:36:27 -0700 Subject: [PATCH 159/656] Enable new params learner for improved vehicle model estimation --- RELEASES.md | 1 + common/manager_helpers.py | 2 +- selfdrive/manager.py | 2 +- 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index e3da108f30..17989d1d85 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,6 +1,7 @@ Version 0.8 (2020-xx-xx) ======================== * White panda is no longer supported, upgrade to comma two or black panda + * Improved vehicle model estimation using high precision localizer Version 0.7.6 (2020-06-05) ======================== diff --git a/common/manager_helpers.py b/common/manager_helpers.py index 4aaf4dd213..e2a88b4f90 100644 --- a/common/manager_helpers.py +++ b/common/manager_helpers.py @@ -13,13 +13,13 @@ def print_cpu_usage(first_proc, last_proc): ("./_ui", 9.54), ("./camerad", 7.07), ("selfdrive.locationd.locationd", 27.46), + ("selfdrive.locationd.paramsd", 10.0), ("./_sensord", 6.17), ("selfdrive.controls.dmonitoringd", 5.48), ("./boardd", 3.63), ("./_dmonitoringmodeld", 2.67), ("selfdrive.logmessaged", 2.71), ("selfdrive.thermald", 2.41), - ("./paramsd", 2.18), ("selfdrive.locationd.calibrationd", 1.76), ("./proclogd", 1.54), ("./_gpsd", 0.09), diff --git a/selfdrive/manager.py b/selfdrive/manager.py index d849c7f865..8496b0d27f 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -181,7 +181,7 @@ managed_processes = { "pandad": "selfdrive.pandad", "ui": ("selfdrive/ui", ["./ui"]), "calibrationd": "selfdrive.locationd.calibrationd", - "paramsd": ("selfdrive/locationd", ["./paramsd"]), + "paramsd": "selfdrive.locationd.paramsd", "camerad": ("selfdrive/camerad", ["./camerad"]), "sensord": ("selfdrive/sensord", ["./sensord"]), "clocksd": ("selfdrive/clocksd", ["./clocksd"]), From 02c130731c2c041cbe95cef8717a93a0b6d67b48 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sun, 31 May 2020 13:37:55 -0700 Subject: [PATCH 160/656] Add alternate Accord tuning --- selfdrive/car/honda/interface.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 0edae57dd9..18df552032 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -200,12 +200,16 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.33 # 11.82 is spec end-to-end ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.8467 - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] ret.longitudinalTuning.kpBP = [0., 5., 35.] ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5] ret.longitudinalTuning.kiBP = [0., 35.] ret.longitudinalTuning.kiV = [0.18, 0.12] + if eps_modified: + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] + else: + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] + elif candidate == CAR.ACURA_ILX: stop_and_go = False ret.mass = 3095. * CV.LB_TO_KG + STD_CARGO_KG From 27754a277c36b82ef4040e536cc918ba8ad77bec Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 31 May 2020 14:03:22 -0700 Subject: [PATCH 161/656] enable E261 in flake8: two spaces before inline comment --- .pre-commit-config.yaml | 2 +- cereal | 2 +- common/android.py | 8 ++--- common/transformations/model.py | 2 +- external/simpleperf/utils.py | 2 +- laika_repo | 2 +- opendbc | 2 +- panda | 2 +- release/remote_build.py | 2 +- selfdrive/boardd/tests/replay_many.py | 2 +- .../boardd/tests/test_boardd_loopback.py | 6 ++-- selfdrive/car/chrysler/carstate.py | 2 +- selfdrive/car/chrysler/interface.py | 4 +-- selfdrive/car/fw_versions.py | 4 +-- selfdrive/car/gm/carcontroller.py | 2 +- selfdrive/car/gm/gmcan.py | 2 +- selfdrive/car/gm/interface.py | 12 +++---- selfdrive/car/gm/radar_interface.py | 2 +- selfdrive/car/honda/carstate.py | 4 +-- selfdrive/car/honda/interface.py | 36 +++++++++---------- selfdrive/car/hyundai/carstate.py | 6 ++-- selfdrive/car/hyundai/values.py | 2 +- selfdrive/car/interfaces.py | 2 +- selfdrive/car/mock/interface.py | 4 +-- selfdrive/car/nissan/interface.py | 2 +- selfdrive/car/toyota/carcontroller.py | 2 +- selfdrive/car/toyota/interface.py | 6 ++-- selfdrive/car/volkswagen/carstate.py | 6 ++-- selfdrive/car/volkswagen/volkswagencan.py | 2 +- selfdrive/controls/lib/driver_monitor.py | 30 ++++++++-------- selfdrive/controls/lib/pid.py | 4 +-- selfdrive/controls/lib/planner.py | 2 +- selfdrive/controls/lib/speed_smoother.py | 2 +- selfdrive/controls/tests/test_events.py | 4 +-- selfdrive/controls/tests/test_monitoring.py | 12 +++---- selfdrive/debug/internal/design_lqr.py | 2 +- selfdrive/debug/internal/power_monitor.py | 2 +- selfdrive/locationd/calibration_helpers.py | 4 +-- .../locationd/test/test_params_learner.py | 2 +- selfdrive/locationd/test/ubloxd.py | 20 +++++------ selfdrive/loggerd/uploader.py | 2 +- selfdrive/manager.py | 2 +- selfdrive/modeld/runners/keras_runner.py | 6 ++-- selfdrive/modeld/visiontest.py | 2 +- .../test/longitudinal_maneuvers/plant.py | 4 +-- .../test/process_replay/test_processes.py | 2 +- selfdrive/test/test_car_models.py | 2 +- selfdrive/test/update_ci_routes.py | 2 +- tools/carcontrols/joystick_test.py | 6 ++-- tools/carcontrols/joystickd.py | 4 +-- tools/lib/framereader.py | 2 +- tools/lib/kbhit.py | 2 +- tools/replay/camera.py | 2 +- tools/replay/sensorium.py | 2 +- tools/replay/ui.py | 2 +- tools/replay/unlogger.py | 16 ++++----- tools/sim/bridge.py | 4 +-- tools/sim/lib/helpers.py | 6 ++-- tools/sim/lib/manual_ctrl.py | 36 +++++++++---------- tools/webcam/front_mount_helper.py | 4 +-- tools/webcam/warp_vis.py | 6 ++-- 61 files changed, 165 insertions(+), 165 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 84aba5d599..27a258b0a0 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,7 +17,7 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E251,E261,E265,E266,E302,E303,E305,E402,E501,E502,E722,E741,W504 + - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E251,E265,E266,E302,E303,E305,E402,E501,E502,E722,E741,W504 - --statistics - repo: local hooks: diff --git a/cereal b/cereal index 0adfc7e77e..76eb23e062 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 0adfc7e77efbf1ebc21bf2629a85d165b319b23e +Subproject commit 76eb23e062679058025369204f4e9a81ea7d479b diff --git a/common/android.py b/common/android.py index 9b140c9143..e1b1098d39 100644 --- a/common/android.py +++ b/common/android.py @@ -47,10 +47,10 @@ def reboot(reason=None): reason_args = ["s16", reason] subprocess.check_output([ - "service", "call", "power", "16", # IPowerManager.reboot - "i32", "0", # no confirmation, + "service", "call", "power", "16", # IPowerManager.reboot + "i32", "0", # no confirmation, *reason_args, - "i32", "1" # wait + "i32", "1" # wait ]) def service_call(call): @@ -71,7 +71,7 @@ def parse_service_call_unpack(r, fmt): def parse_service_call_string(r): try: - r = r[8:] # Cut off length field + r = r[8:] # Cut off length field r = r.decode('utf_16_be') # All pairs of two characters seem to be swapped. Not sure why diff --git a/common/transformations/model.py b/common/transformations/model.py index a7edacf9b5..1be827889d 100644 --- a/common/transformations/model.py +++ b/common/transformations/model.py @@ -100,7 +100,7 @@ def get_camera_frame_from_model_frame(camera_frame_from_road_frame, height=model # This function is super slow, so skip it if height is very close to canonical # TODO: speed it up! - if abs(height - model_height) > 0.001: # + if abs(height - model_height) > 0.001: camera_from_model_camera = get_model_height_transform(camera_frame_from_road_frame, height) else: camera_from_model_camera = np.eye(3) diff --git a/external/simpleperf/utils.py b/external/simpleperf/utils.py index 843e61212d..4534477043 100644 --- a/external/simpleperf/utils.py +++ b/external/simpleperf/utils.py @@ -101,7 +101,7 @@ def get_host_binary_path(binary_name): elif '.' not in binary_name: binary_name += '.exe' dir = os.path.join(dir, 'windows') - elif sys.platform == 'darwin': # OSX + elif sys.platform == 'darwin': # OSX if binary_name.endswith('.so'): binary_name = binary_name[0:-3] + '.dylib' dir = os.path.join(dir, 'darwin') diff --git a/laika_repo b/laika_repo index 90b4c98502..d0872aa161 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 90b4c98502ade83df62fb215ee44375eee46b3d5 +Subproject commit d0872aa16155e8f73961d52952c8cef41d5702d4 diff --git a/opendbc b/opendbc index e92e74311a..4c59163aa3 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit e92e74311a7ed66922629bec4b8cee7c8db1b9f0 +Subproject commit 4c59163aa31b58436fad2f8cbadeacd564887276 diff --git a/panda b/panda index 49ffbe99f6..9102c16118 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 49ffbe99f65e64d23d27d9d3e37f68bc2368dccd +Subproject commit 9102c16118171597abf6cb7b9dee99b557f7eee7 diff --git a/release/remote_build.py b/release/remote_build.py index d9785e0b6f..7db14b3892 100755 --- a/release/remote_build.py +++ b/release/remote_build.py @@ -1,5 +1,5 @@ #!/usr/bin/env python2 -import paramiko # pylint: disable=import-error +import paramiko # pylint: disable=import-error import os import sys import re diff --git a/selfdrive/boardd/tests/replay_many.py b/selfdrive/boardd/tests/replay_many.py index 7596b47a14..41e86f4124 100755 --- a/selfdrive/boardd/tests/replay_many.py +++ b/selfdrive/boardd/tests/replay_many.py @@ -10,7 +10,7 @@ from multiprocessing import Pool jungle = "JUNGLE" in os.environ if jungle: - from panda_jungle import PandaJungle # pylint: disable=import-error + from panda_jungle import PandaJungle # pylint: disable=import-error import cereal.messaging as messaging from selfdrive.boardd.boardd import can_capnp_to_can_list diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py index cb88776a0a..c3a636e476 100755 --- a/selfdrive/boardd/tests/test_boardd_loopback.py +++ b/selfdrive/boardd/tests/test_boardd_loopback.py @@ -14,9 +14,9 @@ def get_test_string(): BUS = 0 def main(): - rcv = sub_sock('can') # port 8006 - snd = pub_sock('sendcan') # port 8017 - time.sleep(0.3) # wait to bind before send/recv + rcv = sub_sock('can') # port 8006 + snd = pub_sock('sendcan') # port 8017 + time.sleep(0.3) # wait to bind before send/recv for i in range(10): print("Loop %d" % i) diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 1a4b1e659e..d935e8eaa0 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -24,7 +24,7 @@ class CarState(CarStateBase): cp.vl["DOORS"]['DOOR_OPEN_RR']]) ret.seatbeltUnlatched = cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_UNLATCHED'] == 1 - ret.brakePressed = cp.vl["BRAKE_2"]['BRAKE_PRESSED_2'] == 5 # human-only + ret.brakePressed = cp.vl["BRAKE_2"]['BRAKE_PRESSED_2'] == 5 # human-only ret.brake = 0 ret.brakeLights = ret.brakePressed ret.gas = cp.vl["ACCEL_GAS_134"]['ACCEL_134'] diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index a62d06d0ab..381174e59d 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -21,7 +21,7 @@ class CarInterface(CarInterfaceBase): # Speed conversion: 20, 45 mph ret.wheelbase = 3.089 # in meters for Pacifica Hybrid 2017 - ret.steerRatio = 16.2 # Pacifica Hybrid 2017 + ret.steerRatio = 16.2 # Pacifica Hybrid 2017 ret.mass = 2858. + STD_CARGO_KG # kg curb weight Pacifica Hybrid 2017 ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] @@ -88,7 +88,7 @@ class CarInterface(CarInterfaceBase): def apply(self, c): if (self.CS.frame == -1): - return [] # if we haven't seen a frame 220, then do not update. + return [] # if we haven't seen a frame 220, then do not update. can_sends = self.CC.update(c.enabled, self.CS, c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index f42e1c09d8..ca53460520 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -42,9 +42,9 @@ UDS_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) HYUNDAI_VERSION_REQUEST_SHORT = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf1a0) # 4 Byte version number + p16(0xf1a0) # 4 Byte version number HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf100) # Long description + p16(0xf100) # Long description HYUNDAI_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + \ diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 06f87113ae..9b4961272b 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -20,7 +20,7 @@ class CarControllerParams(): self.STEER_DRIVER_ALLOWANCE = 50 # allowed driver torque before start limiting self.STEER_DRIVER_MULTIPLIER = 4 # weight driver torque heavily self.STEER_DRIVER_FACTOR = 100 # from dbc - self.NEAR_STOP_BRAKE_PHASE = 0.5 # m/s, more aggressive braking near full stop + self.NEAR_STOP_BRAKE_PHASE = 0.5 # m/s, more aggressive braking near full stop # Takes case of "Service Adaptive Cruise" and "Service Front Camera" # dashboard messages. diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py index 7b146f6804..5cd81ead11 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/selfdrive/car/gm/gmcan.py @@ -68,7 +68,7 @@ def create_acc_dashboard_command(packer, bus, acc_engaged, target_speed_kph, lea "ACCAlwaysOne" : 1, "ACCResumeButton" : 0, "ACCSpeedSetpoint" : target_speed, - "ACCGapLevel" : 3 * acc_engaged, # 3 "far", 0 "inactive" + "ACCGapLevel" : 3 * acc_engaged, # 3 "far", 0 "inactive" "ACCCmdActive" : acc_engaged, "ACCAlwaysOne2" : 1, "ACCLeadCar" : lead_car_in_sight, diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 18baf8886d..c5ffb127b1 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -47,7 +47,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.69 ret.steerRatio = 15.7 ret.steerRatioRear = 0. - ret.centerToFront = ret.wheelbase * 0.4 # wild guess + ret.centerToFront = ret.wheelbase * 0.4 # wild guess elif candidate == CAR.MALIBU: # supports stop and go, but initial engage must be above 18mph (which include conservatism) @@ -56,7 +56,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.83 ret.steerRatio = 15.8 ret.steerRatioRear = 0. - ret.centerToFront = ret.wheelbase * 0.4 # wild guess + ret.centerToFront = ret.wheelbase * 0.4 # wild guess elif candidate == CAR.HOLDEN_ASTRA: ret.mass = 1363. + STD_CARGO_KG @@ -68,7 +68,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatioRear = 0. elif candidate == CAR.ACADIA: - ret.minEnableSpeed = -1. # engage speed is decided by pcm + ret.minEnableSpeed = -1. # engage speed is decided by pcm ret.mass = 4353. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.86 ret.steerRatio = 14.4 # end to end is 13.46 @@ -77,11 +77,11 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.BUICK_REGAL: ret.minEnableSpeed = 18 * CV.MPH_TO_MS - ret.mass = 3779. * CV.LB_TO_KG + STD_CARGO_KG # (3849+3708)/2 + ret.mass = 3779. * CV.LB_TO_KG + STD_CARGO_KG # (3849+3708)/2 ret.wheelbase = 2.83 # 111.4 inches in meters ret.steerRatio = 14.4 # guess for tourx ret.steerRatioRear = 0. - ret.centerToFront = ret.wheelbase * 0.4 # guess for tourx + ret.centerToFront = ret.wheelbase * 0.4 # guess for tourx elif candidate == CAR.CADILLAC_ATS: ret.minEnableSpeed = 18 * CV.MPH_TO_MS @@ -135,7 +135,7 @@ class CarInterface(CarInterfaceBase): but = self.CS.prev_cruise_buttons if but == CruiseButtons.RES_ACCEL: if not (ret.cruiseState.enabled and ret.standstill): - be.type = ButtonType.accelCruise # Suppress resume button if we're resuming from stop so we don't adjust speed. + be.type = ButtonType.accelCruise # Suppress resume button if we're resuming from stop so we don't adjust speed. elif but == CruiseButtons.DECEL_SET: be.type = ButtonType.decelCruise elif but == CruiseButtons.CANCEL: diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py index b63acaddc9..f2f8c3cec9 100755 --- a/selfdrive/car/gm/radar_interface.py +++ b/selfdrive/car/gm/radar_interface.py @@ -95,7 +95,7 @@ class RadarInterface(RadarInterfaceBase): self.pts[targetId] = car.RadarData.RadarPoint.new_message() self.pts[targetId].trackId = targetId distance = cpt['TrkRange'] - self.pts[targetId].dRel = distance # from front of car + self.pts[targetId].dRel = distance # from front of car # From driver's pov, left is positive self.pts[targetId].yRel = math.sin(cpt['TrkAzimuth'] * CV.DEG_TO_RAD) * distance self.pts[targetId].vRel = cpt['TrkRangeRate'] diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 71c0299dd6..38f7efb4f4 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -179,7 +179,7 @@ class CarState(CarStateBase): self.prev_cruise_setting = self.cruise_setting # ******************* parse out can ******************* - if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT): # TODO: find wheels moving bit in dbc + if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT): # TODO: find wheels moving bit in dbc ret.standstill = cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] < 0.1 ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]['DRIVERS_DOOR_OPEN']) elif self.CP.carFingerprint == CAR.ODYSSEY_CHN: @@ -252,7 +252,7 @@ class CarState(CarStateBase): # TODO: Replace tests by toyota so this can go away if self.CP.enableGasInterceptor: self.user_gas = (cp.vl["GAS_SENSOR"]['INTERCEPTOR_GAS'] + cp.vl["GAS_SENSOR"]['INTERCEPTOR_GAS2']) / 2. - self.user_gas_pressed = self.user_gas > 1e-5 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change + self.user_gas_pressed = self.user_gas > 1e-5 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change ret.gasPressed = self.user_gas_pressed else: ret.gasPressed = self.pedal_gas > 1e-5 diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 18df552032..1cb11bd119 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -87,7 +87,7 @@ class CarInterface(CarInterfaceBase): # normalized max accel. Allowing max accel at low speed causes speed overshoots max_accel_bp = [10, 20] # m/s - max_accel_v = [0.714, 1.0] # unit of max accel + max_accel_v = [0.714, 1.0] # unit of max accel max_accel = interp(v_ego, max_accel_bp, max_accel_v) # limit the pcm accel cmd if: @@ -144,7 +144,7 @@ class CarInterface(CarInterfaceBase): # For modeling details, see p.198-200 in "The Science of Vehicle Dynamics (2014), M. Guiggiani" ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0], [0]] ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kf = 0.00006 # conservative feed-forward + ret.lateralTuning.pid.kf = 0.00006 # conservative feed-forward eps_modified = False for fw in car_fw: @@ -182,7 +182,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = CivicParams.WHEELBASE ret.centerToFront = CivicParams.CENTER_TO_FRONT ret.steerRatio = 15.38 # 10.93 is end-to-end spec - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 1. ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -192,13 +192,13 @@ class CarInterface(CarInterfaceBase): elif candidate in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH): stop_and_go = True - if not candidate == CAR.ACCORDH: # Hybrid uses same brake msg as hatch + if not candidate == CAR.ACCORDH: # Hybrid uses same brake msg as hatch ret.safetyParam = 1 # Accord and CRV 5G use an alternate user brake msg ret.mass = 3279. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.83 ret.centerToFront = ret.wheelbase * 0.39 ret.steerRatio = 16.33 # 11.82 is spec end-to-end - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.8467 ret.longitudinalTuning.kpBP = [0., 5., 35.] ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5] @@ -216,7 +216,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.67 ret.centerToFront = ret.wheelbase * 0.37 ret.steerRatio = 18.61 # 15.3 is spec end-to-end - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.72 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -230,7 +230,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.62 ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 16.89 # as spec - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -263,11 +263,11 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.CRV_HYBRID: stop_and_go = True ret.safetyParam = 1 # Accord and CRV 5G use an alternate user brake msg - ret.mass = 1667. + STD_CARGO_KG # mean of 4 models in kg + ret.mass = 1667. + STD_CARGO_KG # mean of 4 models in kg ret.wheelbase = 2.66 ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 16.0 # 12.3 is spec end-to-end - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.677 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -281,7 +281,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.53 ret.centerToFront = ret.wheelbase * 0.39 ret.steerRatio = 13.06 - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.75 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.06]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -309,7 +309,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.68 ret.centerToFront = ret.wheelbase * 0.38 ret.steerRatio = 15.0 # as spec - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -323,7 +323,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 3.00 ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 14.35 # as spec - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.45], [0.135]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -337,7 +337,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.90 ret.centerToFront = ret.wheelbase * 0.41 # from CAR.ODYSSEY ret.steerRatio = 14.35 - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.45], [0.135]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -347,11 +347,11 @@ class CarInterface(CarInterfaceBase): elif candidate in (CAR.PILOT, CAR.PILOT_2019): stop_and_go = False - ret.mass = 4204. * CV.LB_TO_KG + STD_CARGO_KG # average weight + ret.mass = 4204. * CV.LB_TO_KG + STD_CARGO_KG # average weight ret.wheelbase = 2.82 ret.centerToFront = ret.wheelbase * 0.428 ret.steerRatio = 17.25 # as spec - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -365,7 +365,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 3.18 ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 15.59 # as spec - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -379,7 +379,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.7 ret.centerToFront = ret.wheelbase * 0.39 ret.steerRatio = 15.0 # 12.58 is spec end-to-end - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] ret.longitudinalTuning.kpBP = [0., 5., 35.] @@ -406,7 +406,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor=tire_stiffness_factor) ret.gasMaxBP = [0.] # m/s - ret.gasMaxV = [0.6] if ret.enableGasInterceptor else [0.] # max gas allowed + ret.gasMaxV = [0.6] if ret.enableGasInterceptor else [0.] # max gas allowed ret.brakeMaxBP = [5., 20.] # m/s ret.brakeMaxV = [1., 0.8] # max brake allowed diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 9c36804c3d..57435eadbe 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -85,7 +85,7 @@ class CarState(CarStateBase): # Gear Selecton - This is only compatible with optima hybrid 2017 elif self.CP.carFingerprint in FEATURES["use_elect_gears"]: gear = cp.vl["ELECT_GEAR"]["Elect_Gear_Shifter"] - if gear in (5, 8): # 5: D, 8: sport mode + if gear in (5, 8): # 5: D, 8: sport mode ret.gearShifter = GearShifter.drive elif gear == 6: ret.gearShifter = GearShifter.neutral @@ -98,7 +98,7 @@ class CarState(CarStateBase): # Gear Selecton - This is not compatible with all Kia/Hyundai's, But is the best way for those it is compatible with else: gear = cp.vl["LVR12"]["CF_Lvr_Gear"] - if gear in (5, 8): # 5: D, 8: sport mode + if gear in (5, 8): # 5: D, 8: sport mode ret.gearShifter = GearShifter.drive elif gear == 6: ret.gearShifter = GearShifter.neutral @@ -113,7 +113,7 @@ class CarState(CarStateBase): self.lkas11 = cp_cam.vl["LKAS11"] self.clu11 = cp.vl["CLU11"] self.park_brake = cp.vl["CGW1"]['CF_Gway_ParkBrakeSw'] - self.steer_state = cp.vl["MDPS12"]['CF_Mdps_ToiActive'] # 0 NOT ACTIVE, 1 ACTIVE + self.steer_state = cp.vl["MDPS12"]['CF_Mdps_ToiActive'] # 0 NOT ACTIVE, 1 ACTIVE self.lead_distance = cp.vl["SCC11"]['ACC_ObjDist'] return ret diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 1fbb9b43c5..777ddb39d4 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -150,7 +150,7 @@ CHECKSUM = { FEATURES = { "use_cluster_gears": [CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30], # Use Cluster for Gear Selection, rather than Transmission "use_tcu_gears": [CAR.KIA_OPTIMA, CAR.SONATA_2019], # Use TCU Message for Gear Selection - "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.KONA_EV], # Use TCU Message for Gear Selection + "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.KONA_EV], # Use TCU Message for Gear Selection } DBC = { diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 3639b2836e..a72024a138 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -11,7 +11,7 @@ from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX GearShifter = car.CarState.GearShifter EventName = car.CarEvent.EventName -MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS # 144 + 4 = 92 mph +MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS # 144 + 4 = 92 mph # generic car and radar interfaces diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index 69b3862df4..b0474f8ce8 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -8,7 +8,7 @@ from selfdrive.car.interfaces import CarInterfaceBase # mocked car interface to work with chffrplus TS = 0.01 # 100Hz -YAW_FR = 0.2 # ~0.8s time constant on yaw rate filter +YAW_FR = 0.2 # ~0.8s time constant on yaw rate filter # low pass gain LPG = 2 * 3.1415 * YAW_FR * TS / (1 + 2 * 3.1415 * YAW_FR * TS) @@ -41,7 +41,7 @@ class CarInterface(CarInterfaceBase): ret.rotationalInertia = 2500. ret.wheelbase = 2.70 ret.centerToFront = ret.wheelbase * 0.5 - ret.steerRatio = 13. # reasonable + ret.steerRatio = 13. # reasonable ret.tireStiffnessFront = 1e6 # very stiff to neglect slip ret.tireStiffnessRear = 1e6 # very stiff to neglect slip diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index dc2e757990..ebcfd573e7 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -31,7 +31,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kf = 0.00006 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.0], [0.0]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01], [0.005]] - ret.steerMaxBP = [0.] # m/s + ret.steerMaxBP = [0.] # m/s ret.steerMaxV = [1.] if candidate in [CAR.ROGUE, CAR.XTRAIL]: diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 9b68c1940e..96e25013ea 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -12,7 +12,7 @@ VisualAlert = car.CarControl.HUDControl.VisualAlert # Accel limits ACCEL_HYST_GAP = 0.02 # don't change accel command for small oscilalitons within this value ACCEL_MAX = 1.5 # 1.5 m/s2 -ACCEL_MIN = -3.0 # 3 m/s2 +ACCEL_MIN = -3.0 # 3 m/s2 ACCEL_SCALE = max(ACCEL_MAX, -ACCEL_MIN) def accel_hysteresis(accel, accel_steady, enabled): diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 89149b6ae4..93bed7e989 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -23,7 +23,7 @@ class CarInterface(CarInterfaceBase): ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay ret.steerLimitTimer = 0.4 - if candidate not in [CAR.PRIUS, CAR.RAV4, CAR.RAV4H]: # These cars use LQR/INDI + if candidate not in [CAR.PRIUS, CAR.RAV4, CAR.RAV4H]: # These cars use LQR/INDI ret.lateralTuning.init('pid') ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] @@ -207,7 +207,7 @@ class CarInterface(CarInterfaceBase): stop_and_go = True ret.safetyParam = 73 ret.wheelbase = 2.8702 - ret.steerRatio = 16.0 # not optimized + ret.steerRatio = 16.0 # not optimized tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 3704. * CV.LB_TO_KG + STD_CARGO_KG ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] @@ -248,7 +248,7 @@ class CarInterface(CarInterfaceBase): ret.safetyParam = 73 ret.wheelbase = 2.66 ret.steerRatio = 14.7 - tire_stiffness_factor = 0.444 # not optimized yet + tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 4070 * CV.LB_TO_KG + STD_CARGO_KG ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] ret.lateralTuning.pid.kf = 0.00006 diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index 1bec834969..0ee8ce50e5 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -37,7 +37,7 @@ class CarState(CarStateBase): # Update gas, brakes, and gearshift. ret.gas = pt_cp.vl["Motor_20"]['MO_Fahrpedalrohwert_01'] / 100.0 ret.gasPressed = ret.gas > 0 - ret.brake = pt_cp.vl["ESP_05"]['ESP_Bremsdruck'] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects + ret.brake = pt_cp.vl["ESP_05"]['ESP_Bremsdruck'] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects ret.brakePressed = bool(pt_cp.vl["ESP_05"]['ESP_Fahrer_bremst']) ret.brakeLights = bool(pt_cp.vl["ESP_05"]['ESP_Status_Bremsdruck']) @@ -107,7 +107,7 @@ class CarState(CarStateBase): self.steeringFault = not pt_cp.vl["EPS_01"]["HCA_Ready"] # Additional safety checks performed in CarInterface. - self.parkingBrakeSet = bool(pt_cp.vl["Kombi_01"]['KBI_Handbremse']) # FIXME: need to include an EPB check as well + self.parkingBrakeSet = bool(pt_cp.vl["Kombi_01"]['KBI_Handbremse']) # FIXME: need to include an EPB check as well ret.espDisabled = pt_cp.vl["ESP_21"]['ESP_Tastung_passiv'] != 0 return ret @@ -159,7 +159,7 @@ class CarState(CarStateBase): ("GRA_Tip_Hoch", "GRA_ACC_01", 0), # ACC button, increase or accel ("GRA_Tip_Runter", "GRA_ACC_01", 0), # ACC button, decrease or decel ("GRA_Tip_Wiederaufnahme", "GRA_ACC_01", 0), # ACC button, resume - ("GRA_Verstellung_Zeitluecke", "GRA_ACC_01", 0), # ACC button, time gap adj + ("GRA_Verstellung_Zeitluecke", "GRA_ACC_01", 0), # ACC button, time gap adj ("GRA_Typ_Hauptschalter", "GRA_ACC_01", 0), # ACC main button type ("GRA_Tip_Stufe_2", "GRA_ACC_01", 0), # unknown related to stalk type ("GRA_ButtonTypeInfo", "GRA_ACC_01", 0), # unknown related to stalk type diff --git a/selfdrive/car/volkswagen/volkswagencan.py b/selfdrive/car/volkswagen/volkswagencan.py index 34f19003d8..694673ea6b 100644 --- a/selfdrive/car/volkswagen/volkswagencan.py +++ b/selfdrive/car/volkswagen/volkswagencan.py @@ -25,7 +25,7 @@ def create_mqb_hud_control(packer, bus, hca_enabled, steering_pressed, hud_alert rightlanehud = 2 if rightLaneVisible else 1 values = { - "LDW_Unknown": 2, # FIXME: possible speed or attention relationship + "LDW_Unknown": 2, # FIXME: possible speed or attention relationship "Kombi_Lamp_Orange": 1 if hca_enabled and steering_pressed else 0, "Kombi_Lamp_Green": 1 if hca_enabled and not steering_pressed else 0, "Left_Lane_Status": leftlanehud, diff --git a/selfdrive/controls/lib/driver_monitor.py b/selfdrive/controls/lib/driver_monitor.py index b6a5cee9a3..7cacd770ce 100644 --- a/selfdrive/controls/lib/driver_monitor.py +++ b/selfdrive/controls/lib/driver_monitor.py @@ -23,31 +23,31 @@ _DISTRACTED_PROMPT_TIME_TILL_TERMINAL = 6. _FACE_THRESHOLD = 0.4 _EYE_THRESHOLD = 0.6 -_BLINK_THRESHOLD = 0.5 # 0.225 +_BLINK_THRESHOLD = 0.5 # 0.225 _BLINK_THRESHOLD_SLACK = 0.65 _BLINK_THRESHOLD_STRICT = 0.5 -_PITCH_WEIGHT = 1.35 # 1.5 # pitch matters a lot more +_PITCH_WEIGHT = 1.35 # 1.5 # pitch matters a lot more _POSESTD_THRESHOLD = 0.14 _METRIC_THRESHOLD = 0.4 _METRIC_THRESHOLD_SLACK = 0.55 _METRIC_THRESHOLD_STRICT = 0.4 -_PITCH_POS_ALLOWANCE = 0.12 # rad, to not be too sensitive on positive pitch -_PITCH_NATURAL_OFFSET = 0.02 # people don't seem to look straight when they drive relaxed, rather a bit up -_YAW_NATURAL_OFFSET = 0.08 # people don't seem to look straight when they drive relaxed, rather a bit to the right (center of car) +_PITCH_POS_ALLOWANCE = 0.12 # rad, to not be too sensitive on positive pitch +_PITCH_NATURAL_OFFSET = 0.02 # people don't seem to look straight when they drive relaxed, rather a bit up +_YAW_NATURAL_OFFSET = 0.08 # people don't seem to look straight when they drive relaxed, rather a bit to the right (center of car) _HI_STD_TIMEOUT = 5 -_HI_STD_FALLBACK_TIME = 10 # fall back to wheel touch if model is uncertain for a long time +_HI_STD_FALLBACK_TIME = 10 # fall back to wheel touch if model is uncertain for a long time _DISTRACTED_FILTER_TS = 0.25 # 0.6Hz -_POSE_CALIB_MIN_SPEED = 13 # 30 mph -_POSE_OFFSET_MIN_COUNT = 600 # valid data counts before calibration completes, 1 seg is 600 counts -_POSE_OFFSET_MAX_COUNT = 3600 # stop deweighting new data after 6 min, aka "short term memory" +_POSE_CALIB_MIN_SPEED = 13 # 30 mph +_POSE_OFFSET_MIN_COUNT = 600 # valid data counts before calibration completes, 1 seg is 600 counts +_POSE_OFFSET_MAX_COUNT = 3600 # stop deweighting new data after 6 min, aka "short term memory" -_RECOVERY_FACTOR_MAX = 5. # relative to minus step change -_RECOVERY_FACTOR_MIN = 1.25 # relative to minus step change +_RECOVERY_FACTOR_MAX = 5. # relative to minus step change +_RECOVERY_FACTOR_MIN = 1.25 # relative to minus step change -MAX_TERMINAL_ALERTS = 3 # not allowed to engage after 3 terminal alerts -MAX_TERMINAL_DURATION = 300 # 30s +MAX_TERMINAL_ALERTS = 3 # not allowed to engage after 3 terminal alerts +MAX_TERMINAL_DURATION = 300 # 30s # model output refers to center of cropped image, so need to apply the x displacement offset RESIZED_FOCAL = 320.0 @@ -76,7 +76,7 @@ def face_orientation_from_net(angles_desc, pos_desc, rpy_calib, is_rhd): # no calib for roll pitch -= rpy_calib[1] - yaw -= rpy_calib[2] * (1 - 2 * int(is_rhd)) # lhd -> -=, rhd -> += + yaw -= rpy_calib[2] * (1 - 2 * int(is_rhd)) # lhd -> -=, rhd -> += return roll, pitch, yaw class DriverPose(): @@ -128,7 +128,7 @@ class DriverStatus(): self.step_change = DT_DMON / _DISTRACTED_TIME else: self.step_change = 0. - return # no exploit after orange alert + return # no exploit after orange alert elif self.awareness <= 0.: return diff --git a/selfdrive/controls/lib/pid.py b/selfdrive/controls/lib/pid.py index fbd3885304..d374619c19 100644 --- a/selfdrive/controls/lib/pid.py +++ b/selfdrive/controls/lib/pid.py @@ -12,8 +12,8 @@ def apply_deadzone(error, deadzone): class PIController(): def __init__(self, k_p, k_i, k_f=1., pos_limit=None, neg_limit=None, rate=100, sat_limit=0.8, convert=None): - self._k_p = k_p # proportional gain - self._k_i = k_i # integral gain + self._k_p = k_p # proportional gain + self._k_i = k_i # integral gain self.k_f = k_f # feedforward gain self.pos_limit = pos_limit diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index 141de4c5df..ea87adae55 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -147,7 +147,7 @@ class Planner(): a_y_max = 2.975 - v_ego * 0.0375 # ~1.85 @ 75mph, ~2.6 @ 25mph v_curvature = np.sqrt(a_y_max / np.clip(np.abs(curv), 1e-4, None)) model_speed = np.min(v_curvature) - model_speed = max(20.0 * CV.MPH_TO_MS, model_speed) # Don't slow down below 20mph + model_speed = max(20.0 * CV.MPH_TO_MS, model_speed) # Don't slow down below 20mph else: model_speed = MAX_SPEED diff --git a/selfdrive/controls/lib/speed_smoother.py b/selfdrive/controls/lib/speed_smoother.py index 1ee7ec6b18..431822dd9f 100644 --- a/selfdrive/controls/lib/speed_smoother.py +++ b/selfdrive/controls/lib/speed_smoother.py @@ -67,7 +67,7 @@ def speed_smoother(vEgo, aEgo, vT, aMax, aMin, jMax, jMin, ts): if aPeak > aMax: aPeak = aMax t1 = (aPeak - aEgo) / jMax - if aPeak <= 0: # there is no solution, so stop after t1 + if aPeak <= 0: # there is no solution, so stop after t1 t2 = t1 + ts + 1e-9 t3 = t2 else: diff --git a/selfdrive/controls/tests/test_events.py b/selfdrive/controls/tests/test_events.py index 2951dcebb0..3c5bc9d34b 100755 --- a/selfdrive/controls/tests/test_events.py +++ b/selfdrive/controls/tests/test_events.py @@ -27,9 +27,9 @@ class TestAlerts(unittest.TestCase): bold_font_path = os.path.join(font_path, "opensans_semibold.ttf") semibold_font_path = os.path.join(font_path, "opensans_semibold.ttf") - max_text_width = 1920 - 300 # full screen width is useable, minus sidebar + max_text_width = 1920 - 300 # full screen width is useable, minus sidebar # TODO: get exact scale factor. found this empirically, works well enough - font_scale_factor = 1.85 # factor to scale from nanovg units to PIL + font_scale_factor = 1.85 # factor to scale from nanovg units to PIL draw = ImageDraw.Draw(Image.new('RGB', (0, 0))) diff --git a/selfdrive/controls/tests/test_monitoring.py b/selfdrive/controls/tests/test_monitoring.py index c0f5fd8066..2cf8f0fdda 100644 --- a/selfdrive/controls/tests/test_monitoring.py +++ b/selfdrive/controls/tests/test_monitoring.py @@ -11,7 +11,7 @@ from selfdrive.controls.lib.driver_monitor import DriverStatus, MAX_TERMINAL_ALE EventName = car.CarEvent.EventName -_TEST_TIMESPAN = 120 # seconds +_TEST_TIMESPAN = 120 # seconds _DISTRACTED_SECONDS_TO_ORANGE = _DISTRACTED_TIME - _DISTRACTED_PROMPT_TIME_TILL_TERMINAL + 1 _DISTRACTED_SECONDS_TO_RED = _DISTRACTED_TIME + 1 _INVISIBLE_SECONDS_TO_ORANGE = _AWARENESS_TIME - _AWARENESS_PROMPT_TIME_TILL_TERMINAL + 1 @@ -121,7 +121,7 @@ class TestMonitoring(unittest.TestCase): # driver dodges, and then touches wheel to no avail, disengages and reengages # - orange/red alert should remain after disappearance, and only disengaging clears red def test_biggest_comma_fan(self): - _invisible_time = 2 # seconds + _invisible_time = 2 # seconds ds_vector = always_distracted[:] interaction_vector = always_false[:] op_vector = always_true[:] @@ -138,7 +138,7 @@ class TestMonitoring(unittest.TestCase): # 5. op engaged, invisible driver, down to orange, driver touches wheel; then down to orange again, driver appears # - both actions should clear the alert, but momentary appearence should not def test_sometimes_transparent_commuter(self): - _visible_time = np.random.choice([1, 10]) # seconds + _visible_time = np.random.choice([1, 10]) # seconds # print _visible_time ds_vector = always_no_face[:]*2 interaction_vector = always_false[:]*2 @@ -160,7 +160,7 @@ class TestMonitoring(unittest.TestCase): # 6. op engaged, invisible driver, down to red, driver appears and then touches wheel, then disengages/reengages # - only disengage will clear the alert def test_last_second_responder(self): - _visible_time = 2 # seconds + _visible_time = 2 # seconds ds_vector = always_no_face[:] interaction_vector = always_false[:] op_vector = always_true[:] @@ -184,7 +184,7 @@ class TestMonitoring(unittest.TestCase): # 8. op engaged, car stops at traffic light, down to orange, no action, then car starts moving # - should only reach green when stopped, but continues counting down on launch def test_long_traffic_light_victim(self): - _redlight_time = 60 # seconds + _redlight_time = 60 # seconds standstill_vector = always_true[:] standstill_vector[int(_redlight_time/DT_DMON):] = [False] * int((_TEST_TIMESPAN-_redlight_time)/DT_DMON) events_output = run_DState_seq(always_distracted, always_false, always_true, standstill_vector)[0] @@ -217,7 +217,7 @@ class TestMonitoring(unittest.TestCase): self.assertEqual(events_output[int((2.5*(_DISTRACTED_TIME-_DISTRACTED_PRE_TIME_TILL_TERMINAL))/DT_DMON)].names[1], EventName.preDriverDistracted) self.assertEqual(events_output[int((2.5*(_DISTRACTED_TIME-_DISTRACTED_PROMPT_TIME_TILL_TERMINAL))/DT_DMON)].names[1], EventName.promptDriverDistracted) self.assertEqual(events_output[int((_DISTRACTED_TIME+1)/DT_DMON)].names[1], EventName.promptDriverDistracted) - self.assertEqual(events_output[int((_DISTRACTED_TIME*2.5)/DT_DMON)].names[1], EventName.promptDriverDistracted) # set_timer blocked + self.assertEqual(events_output[int((_DISTRACTED_TIME*2.5)/DT_DMON)].names[1], EventName.promptDriverDistracted) # set_timer blocked if __name__ == "__main__": print('MAX_TERMINAL_ALERTS', MAX_TERMINAL_ALERTS) diff --git a/selfdrive/debug/internal/design_lqr.py b/selfdrive/debug/internal/design_lqr.py index fcc2524f2c..e86926f607 100755 --- a/selfdrive/debug/internal/design_lqr.py +++ b/selfdrive/debug/internal/design_lqr.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 import numpy as np -import control # pylint: disable=import-error +import control # pylint: disable=import-error dt = 0.01 A = np.array([[ 0. , 1. ], [-0.78823806, 1.78060701]]) diff --git a/selfdrive/debug/internal/power_monitor.py b/selfdrive/debug/internal/power_monitor.py index 74a7e2ba0d..3377088f8b 100755 --- a/selfdrive/debug/internal/power_monitor.py +++ b/selfdrive/debug/internal/power_monitor.py @@ -17,7 +17,7 @@ if __name__ == '__main__': print("disabling charging") os.system('echo "0" > /sys/class/power_supply/battery/charging_enabled') - voltage_average = (0., 0) # average, count + voltage_average = (0., 0) # average, count current_average = (0., 0) power_average = (0., 0) capacity_average = (0., 0) diff --git a/selfdrive/locationd/calibration_helpers.py b/selfdrive/locationd/calibration_helpers.py index cdc0345f35..c7886d3019 100644 --- a/selfdrive/locationd/calibration_helpers.py +++ b/selfdrive/locationd/calibration_helpers.py @@ -1,8 +1,8 @@ import math class Filter: - MIN_SPEED = 7 # m/s (~15.5mph) - MAX_YAW_RATE = math.radians(3) # per second + MIN_SPEED = 7 # m/s (~15.5mph) + MAX_YAW_RATE = math.radians(3) # per second class Calibration: UNCALIBRATED = 0 diff --git a/selfdrive/locationd/test/test_params_learner.py b/selfdrive/locationd/test/test_params_learner.py index a3c8487858..c1b75c5af9 100755 --- a/selfdrive/locationd/test/test_params_learner.py +++ b/selfdrive/locationd/test/test_params_learner.py @@ -6,7 +6,7 @@ import unittest from selfdrive.car.honda.interface import CarInterface from selfdrive.car.honda.values import CAR from selfdrive.controls.lib.vehicle_model import VehicleModel -from selfdrive.locationd.liblocationd_py import liblocationd # pylint: disable=no-name-in-module, import-error +from selfdrive.locationd.liblocationd_py import liblocationd # pylint: disable=no-name-in-module, import-error class TestParamsLearner(unittest.TestCase): diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index 570e9d0a1c..c5e48a8633 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -19,10 +19,10 @@ debug = os.getenv("DEBUG") is not None # debug prints print_dB = os.getenv("PRINT_DB") is not None # print antenna dB timeout = 1 -dyn_model = 4 # auto model +dyn_model = 4 # auto model baudrate = 460800 ports = ["/dev/ttyACM0", "/dev/ttyACM1"] -rate = 100 # send new data every 100ms +rate = 100 # send new data every 100ms # which SV IDs we have seen and when we got iono svid_seen = {} @@ -32,17 +32,17 @@ iono_seen = 0 def configure_ublox(dev): # configure ports and solution parameters and rate # TODO: configure constellations and channels to allow for 10Hz and high precision - dev.configure_port(port=ublox.PORT_USB, inMask=1, outMask=1) # enable only UBX on USB - dev.configure_port(port=0, inMask=0, outMask=0) # disable DDC + dev.configure_port(port=ublox.PORT_USB, inMask=1, outMask=1) # enable only UBX on USB + dev.configure_port(port=0, inMask=0, outMask=0) # disable DDC if panda: payload = struct.pack(' 0 and lag < 30: # a large jump is OK, likely due to an out of order segment + if lag > 0 and lag < 30: # a large jump is OK, likely due to an out of order segment if lag > 1: print("sleeping for", lag) time.sleep(lag) @@ -312,17 +312,17 @@ def keyboard_controller_thread(q, route_start_time): kb = KBHit() while 1: c = kb.getch() - if c == 'm': # Move forward by 1m + if c == 'm': # Move forward by 1m q.send_pyobj(SeekRelativeTime(60)) - elif c == 'M': # Move backward by 1m + elif c == 'M': # Move backward by 1m q.send_pyobj(SeekRelativeTime(-60)) - elif c == 's': # Move forward by 10s + elif c == 's': # Move forward by 10s q.send_pyobj(SeekRelativeTime(10)) - elif c == 'S': # Move backward by 10s + elif c == 'S': # Move backward by 10s q.send_pyobj(SeekRelativeTime(-10)) - elif c == 'G': # Move backward by 10s + elif c == 'G': # Move backward by 10s q.send_pyobj(SeekAbsoluteTime(0.)) - elif c == "\x20": # Space bar. + elif c == "\x20": # Space bar. q.send_pyobj(TogglePause()) elif c == "\n": try: diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index dd11cd942f..b5a63c3056 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -169,7 +169,7 @@ def go(q): m = message.split('_') if m[0] == "steer": steer_angle_out = float(m[1]) - fake_wheel.set_angle(steer_angle_out) # touching the wheel overrides fake wheel angle + fake_wheel.set_angle(steer_angle_out) # touching the wheel overrides fake wheel angle # print(" === steering overriden === ") if m[0] == "throttle": throttle_out = float(m[1]) / 100. @@ -200,7 +200,7 @@ def go(q): speed = math.sqrt(vel.x**2 + vel.y**2 + vel.z**2) * 3.6 can_function(pm, speed, fake_wheel.angle, rk.frame, cruise_button=cruise_button, is_engaged=is_openpilot_engaged) - if rk.frame % 1 == 0: # 20Hz? + if rk.frame % 1 == 0: # 20Hz? throttle_op, brake_op, steer_torque_op = sendcan_function(sendcan) # print(" === torq, ",steer_torque_op, " ===") if is_openpilot_engaged: diff --git a/tools/sim/lib/helpers.py b/tools/sim/lib/helpers.py index 104d5e3633..f6bb4b8173 100644 --- a/tools/sim/lib/helpers.py +++ b/tools/sim/lib/helpers.py @@ -1,7 +1,7 @@ class FakeSteeringWheel(): def __init__(self, dt=0.01): # physical params - self.DAC = 4. / 0.625 # convert torque value from can to Nm + self.DAC = 4. / 0.625 # convert torque value from can to Nm self.k = 0.035 self.centering_k = 4.1 * 0.9 self.b = 0.1 * 0.8 @@ -9,7 +9,7 @@ class FakeSteeringWheel(): self.dt = dt # ... - self.angle = 0. # start centered + self.angle = 0. # start centered # self.omega = 0. def response(self, torque, vego=0): @@ -19,7 +19,7 @@ class FakeSteeringWheel(): # self.omega += self.dt * (exerted_torque + centering_torque + damping_torque) / self.I # self.omega = np.clip(self.omega, -1.1, 1.1) # self.angle += self.dt * self.omega - self.angle += self.dt * self.k * exerted_torque # aristotle + self.angle += self.dt * self.k * exerted_torque # aristotle # print(" ========== ") # print("angle,", self.angle) diff --git a/tools/sim/lib/manual_ctrl.py b/tools/sim/lib/manual_ctrl.py index 16cf42af46..bdc0778ec9 100755 --- a/tools/sim/lib/manual_ctrl.py +++ b/tools/sim/lib/manual_ctrl.py @@ -99,22 +99,22 @@ def wheel_poll_thread(q): # Get the device name. #buf = bytearray(63) buf = array.array('B', [0] * 64) - ioctl(jsdev, 0x80006a13 + (0x10000 * len(buf)), buf) # JSIOCGNAME(len) + ioctl(jsdev, 0x80006a13 + (0x10000 * len(buf)), buf) # JSIOCGNAME(len) js_name = buf.tobytes().rstrip(b'\x00').decode('utf-8') print('Device name: %s' % js_name) # Get number of axes and buttons. buf = array.array('B', [0]) - ioctl(jsdev, 0x80016a11, buf) # JSIOCGAXES + ioctl(jsdev, 0x80016a11, buf) # JSIOCGAXES num_axes = buf[0] buf = array.array('B', [0]) - ioctl(jsdev, 0x80016a12, buf) # JSIOCGBUTTONS + ioctl(jsdev, 0x80016a12, buf) # JSIOCGBUTTONS num_buttons = buf[0] # Get the axis map. buf = array.array('B', [0] * 0x40) - ioctl(jsdev, 0x80406a32, buf) # JSIOCGAXMAP + ioctl(jsdev, 0x80406a32, buf) # JSIOCGAXMAP for axis in buf[:num_axes]: axis_name = axis_names.get(axis, 'unknown(0x%02x)' % axis) @@ -123,7 +123,7 @@ def wheel_poll_thread(q): # Get the button map. buf = array.array('H', [0] * 200) - ioctl(jsdev, 0x80406a34, buf) # JSIOCGBTNMAP + ioctl(jsdev, 0x80406a34, buf) # JSIOCGBTNMAP for btn in buf[:num_buttons]: btn_name = button_names.get(btn, 'unknown(0x%03x)' % btn) @@ -145,42 +145,42 @@ def wheel_poll_thread(q): evbuf = jsdev.read(8) time, value, mtype, number = struct.unpack('IhBB', evbuf) # print(mtype, number, value) - if mtype & 0x02: # wheel & paddles + if mtype & 0x02: # wheel & paddles axis = axis_map[number] - if axis == "z": # gas + if axis == "z": # gas fvalue = value / 32767.0 axis_states[axis] = fvalue normalized = (1 - fvalue) * 50 q.put(str("throttle_%f" % normalized)) - if axis == "rz": # brake + if axis == "rz": # brake fvalue = value / 32767.0 axis_states[axis] = fvalue normalized = (1 - fvalue) * 50 q.put(str("brake_%f" % normalized)) - if axis == "x": # steer angle + if axis == "x": # steer angle fvalue = value / 32767.0 axis_states[axis] = fvalue normalized = fvalue q.put(str("steer_%f" % normalized)) - if mtype & 0x01: # buttons - if number in [0, 19]: # X - if value == 1: # press down + if mtype & 0x01: # buttons + if number in [0, 19]: # X + if value == 1: # press down q.put(str("cruise_down")) - if number in [3, 18]: # triangle - if value == 1: # press down + if number in [3, 18]: # triangle + if value == 1: # press down q.put(str("cruise_up")) - if number in [1, 6]: # square - if value == 1: # press down + if number in [1, 6]: # square + if value == 1: # press down q.put(str("cruise_cancel")) - if number in [10, 21]: # R3 - if value == 1: # press down + if number in [10, 21]: # R3 + if value == 1: # press down q.put(str("reverse_switch")) if __name__ == '__main__': diff --git a/tools/webcam/front_mount_helper.py b/tools/webcam/front_mount_helper.py index 73f446582c..2ae35992ec 100755 --- a/tools/webcam/front_mount_helper.py +++ b/tools/webcam/front_mount_helper.py @@ -2,8 +2,8 @@ import numpy as np # copied from common.transformations/camera.py -eon_dcam_focal_length = 860.0 # pixels -webcam_focal_length = 908.0 # pixels +eon_dcam_focal_length = 860.0 # pixels +webcam_focal_length = 908.0 # pixels eon_dcam_intrinsics = np.array([ [eon_dcam_focal_length, 0, 1152/2.], diff --git a/tools/webcam/warp_vis.py b/tools/webcam/warp_vis.py index 3daec95fbe..4331614acf 100755 --- a/tools/webcam/warp_vis.py +++ b/tools/webcam/warp_vis.py @@ -2,10 +2,10 @@ import numpy as np # copied from common.transformations/camera.py -eon_focal_length = 910.0 # pixels -eon_dcam_focal_length = 860.0 # pixels +eon_focal_length = 910.0 # pixels +eon_dcam_focal_length = 860.0 # pixels -webcam_focal_length = -908.0/1.5 # pixels +webcam_focal_length = -908.0/1.5 # pixels eon_intrinsics = np.array([ [eon_focal_length, 0., 1164/2.], From 35663f2fbca2f055d618fd4cc4a93025de578aa4 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sun, 31 May 2020 14:37:10 -0700 Subject: [PATCH 162/656] bump submodules --- cereal | 2 +- opendbc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 76eb23e062..286b7e58b5 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 76eb23e062679058025369204f4e9a81ea7d479b +Subproject commit 286b7e58b5e7ede697370acc77fc7cca21d69764 diff --git a/opendbc b/opendbc index 4c59163aa3..e92e74311a 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 4c59163aa31b58436fad2f8cbadeacd564887276 +Subproject commit e92e74311a7ed66922629bec4b8cee7c8db1b9f0 From b86460c28e4c14256fc8c6f46e1787d50e08e834 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 31 May 2020 14:44:42 -0700 Subject: [PATCH 163/656] bump again --- cereal | 2 +- opendbc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 286b7e58b5..76eb23e062 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 286b7e58b5e7ede697370acc77fc7cca21d69764 +Subproject commit 76eb23e062679058025369204f4e9a81ea7d479b diff --git a/opendbc b/opendbc index e92e74311a..4c59163aa3 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit e92e74311a7ed66922629bec4b8cee7c8db1b9f0 +Subproject commit 4c59163aa31b58436fad2f8cbadeacd564887276 From f3dcf861c73b47c52b5dd77a8f1f8858005ae18b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 31 May 2020 17:18:08 -0700 Subject: [PATCH 164/656] enable flake8 E303: too many blank lines --- .pre-commit-config.yaml | 2 +- cereal | 2 +- common/kalman/tests/test_simple_kalman.py | 1 - common/transformations/coordinates.py | 2 -- common/transformations/orientation.py | 4 ---- common/transformations/tests/test_coordinates.py | 4 ---- common/transformations/tests/test_orientation.py | 1 - common/url_file.py | 1 - common/window.py | 1 - external/simpleperf/utils.py | 7 ------- laika_repo | 2 +- panda | 2 +- selfdrive/boardd/tests/replay_many.py | 1 - selfdrive/car/chrysler/carcontroller.py | 1 - selfdrive/car/chrysler/test_chryslercan.py | 1 - selfdrive/car/chrysler/values.py | 1 - selfdrive/car/ford/radar_interface.py | 1 - selfdrive/car/honda/carstate.py | 1 - selfdrive/car/honda/interface.py | 1 - selfdrive/car/honda/radar_interface.py | 1 - selfdrive/car/hyundai/carcontroller.py | 1 - selfdrive/car/mazda/carcontroller.py | 1 - selfdrive/car/mazda/carstate.py | 2 -- selfdrive/car/mazda/interface.py | 1 - selfdrive/car/subaru/carcontroller.py | 1 - selfdrive/car/toyota/carstate.py | 1 - selfdrive/controls/controlsd.py | 5 ----- selfdrive/controls/radard.py | 1 - selfdrive/debug/internal/check_alive_valid.py | 2 -- selfdrive/debug/mpc/live_lateral_mpc.py | 1 - selfdrive/debug/mpc/live_longitudinal_mpc.py | 2 -- selfdrive/debug/mpc/tune_lateral.py | 1 - selfdrive/locationd/calibrationd.py | 1 - selfdrive/locationd/locationd.py | 1 - selfdrive/locationd/models/constants.py | 1 - selfdrive/locationd/test/test_params_learner.py | 3 --- selfdrive/locationd/test/ublox.py | 1 - selfdrive/locationd/test/ubloxd.py | 4 ---- selfdrive/modeld/visiontest.py | 1 - selfdrive/test/longitudinal_maneuvers/maneuverplots.py | 1 - selfdrive/test/longitudinal_maneuvers/plant.py | 1 - selfdrive/test/process_replay/inject_model.py | 1 - selfdrive/test/process_replay/process_replay.py | 1 - selfdrive/test/update_ci_routes.py | 1 - tools/carcontrols/joystick_test.py | 3 --- tools/lib/kbhit.py | 3 --- tools/lib/route_framereader.py | 1 - tools/lib/tests/test_readers.py | 3 --- tools/replay/camera.py | 1 - tools/replay/lib/ui_helpers.py | 1 - tools/replay/sensorium.py | 1 - tools/replay/ui.py | 2 -- 52 files changed, 4 insertions(+), 84 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 27a258b0a0..7b77f3f5ba 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,7 +17,7 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E251,E265,E266,E302,E303,E305,E402,E501,E502,E722,E741,W504 + - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E251,E265,E266,E302,E305,E402,E501,E502,E722,E741,W504 - --statistics - repo: local hooks: diff --git a/cereal b/cereal index 76eb23e062..b25a7d6f6e 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 76eb23e062679058025369204f4e9a81ea7d479b +Subproject commit b25a7d6f6e4dc923f1ee1fd5ea13d6e12100341e diff --git a/common/kalman/tests/test_simple_kalman.py b/common/kalman/tests/test_simple_kalman.py index c1f9f7b03c..9b947a4320 100644 --- a/common/kalman/tests/test_simple_kalman.py +++ b/common/kalman/tests/test_simple_kalman.py @@ -50,7 +50,6 @@ class TestSimpleKalman(unittest.TestCase): self.assertAlmostEqual(x_old[0], x[0]) self.assertAlmostEqual(x_old[1], x[1]) - def test_new_is_faster(self): setup = """ import numpy as np diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index 4f15f92777..a0d179c353 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -5,7 +5,6 @@ with each row as a position. """ - a = 6378137 b = 6356752.3142 esq = 6.69437999014 * 0.001 @@ -91,7 +90,6 @@ class LocalCoord(): init_geodetic = ecef2geodetic(init_ecef) return LocalCoord(init_geodetic, init_ecef) - def ecef2ned(self, ecef): ecef = np.array(ecef) return np.dot(self.ecef2ned_matrix, (ecef - self.init_ecef).T).T diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py index 0a28524a67..f594f05678 100644 --- a/common/transformations/orientation.py +++ b/common/transformations/orientation.py @@ -132,10 +132,6 @@ rot_from_euler = euler2rot quat_from_euler = euler2quat - - - - ''' Random helpers below ''' diff --git a/common/transformations/tests/test_coordinates.py b/common/transformations/tests/test_coordinates.py index b0cbcd79d6..a7fbfcde34 100755 --- a/common/transformations/tests/test_coordinates.py +++ b/common/transformations/tests/test_coordinates.py @@ -50,7 +50,6 @@ ned_offsets_batch = np.array([[ 53.88103168, 43.83445935, -46.27488057], [ 78.56272609, 18.53100158, -43.25290759]]) - class TestNED(unittest.TestCase): def test_small_distances(self): start_geodetic = np.array([33.8042184, -117.888593, 0.0]) @@ -83,8 +82,6 @@ class TestNED(unittest.TestCase): np.testing.assert_allclose(geodetic_positions_radians[:, :2], coord.ecef2geodetic(ecef_positions, radians=True)[:, :2], rtol=1e-7) np.testing.assert_allclose(geodetic_positions_radians[:, 2], coord.ecef2geodetic(ecef_positions, radians=True)[:, 2], rtol=1e-7, atol=1e-4) - - def test_ned(self): for ecef_pos in ecef_positions: converter = coord.LocalCoord.from_ecef(ecef_pos) @@ -99,7 +96,6 @@ class TestNED(unittest.TestCase): np.testing.assert_allclose(geo_pos_moved[:2], geo_pos_double_converted_moved[:2], rtol=1e-9, atol=1e-6) np.testing.assert_allclose(geo_pos_moved[2], geo_pos_double_converted_moved[2], rtol=1e-9, atol=1e-4) - def test_ned_saved_results(self): for i, ecef_pos in enumerate(ecef_positions): converter = coord.LocalCoord.from_ecef(ecef_pos) diff --git a/common/transformations/tests/test_orientation.py b/common/transformations/tests/test_orientation.py index 1e85c81a0a..906389757b 100755 --- a/common/transformations/tests/test_orientation.py +++ b/common/transformations/tests/test_orientation.py @@ -64,6 +64,5 @@ class TestOrientation(unittest.TestCase): np.testing.assert_allclose(ned_eulers, ned_euler_from_ecef(ecef_positions, eulers), rtol=1e-7) - if __name__ == "__main__": unittest.main() diff --git a/common/url_file.py b/common/url_file.py index 4ba8192049..343e7537be 100644 --- a/common/url_file.py +++ b/common/url_file.py @@ -77,7 +77,6 @@ class URLFile(object): if response_code != 206 and response_code != 200: raise Exception("Error {} ({}): {}".format(response_code, self._url, repr(dats.getvalue())[:500])) - ret = dats.getvalue() self._pos += len(ret) return ret diff --git a/common/window.py b/common/window.py index 6fc36d06bf..fada132b81 100644 --- a/common/window.py +++ b/common/window.py @@ -23,7 +23,6 @@ class Window(): pygame.surfarray.blit_array(self.screen, out.swapaxes(0, 1)) pygame.display.flip() - def getkey(self): while 1: event = pygame.event.wait() diff --git a/external/simpleperf/utils.py b/external/simpleperf/utils.py index 4534477043..4077039846 100644 --- a/external/simpleperf/utils.py +++ b/external/simpleperf/utils.py @@ -220,11 +220,9 @@ class AdbHelper(object): self.adb_path = adb_path self.enable_switch_to_root = enable_switch_to_root - def run(self, adb_args): return self.run_and_return_output(adb_args)[0] - def run_and_return_output(self, adb_args, stdout_file=None, log_output=True): adb_args = [self.adb_path] + adb_args log_debug('run adb cmd: %s' % adb_args) @@ -247,14 +245,12 @@ class AdbHelper(object): def check_run(self, adb_args): self.check_run_and_return_output(adb_args) - def check_run_and_return_output(self, adb_args, stdout_file=None, log_output=True): result, stdoutdata = self.run_and_return_output(adb_args, stdout_file, log_output) if not result: log_exit('run "adb %s" failed' % adb_args) return stdoutdata - def _unroot(self): result, stdoutdata = self.run_and_return_output(['shell', 'whoami']) if not result: @@ -266,7 +262,6 @@ class AdbHelper(object): self.run(['wait-for-device']) time.sleep(1) - def switch_to_root(self): if not self.enable_switch_to_root: self._unroot() @@ -292,7 +287,6 @@ class AdbHelper(object): def set_property(self, name, value): return self.run(['shell', 'setprop', name, value]) - def get_device_arch(self): output = self.check_run_and_return_output(['shell', 'uname', '-m']) if 'aarch64' in output: @@ -305,7 +299,6 @@ class AdbHelper(object): return 'x86' log_fatal('unsupported architecture: %s' % output.strip()) - def get_android_version(self): build_version = self.get_property('ro.build.version.release') android_version = 0 diff --git a/laika_repo b/laika_repo index d0872aa161..4d9df5eb09 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit d0872aa16155e8f73961d52952c8cef41d5702d4 +Subproject commit 4d9df5eb0994523d8061358e0210ca6e6a473e48 diff --git a/panda b/panda index 9102c16118..275e76c2b2 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 9102c16118171597abf6cb7b9dee99b557f7eee7 +Subproject commit 275e76c2b2f9206c82990fe7ba0a6a96ecb8a0bc diff --git a/selfdrive/boardd/tests/replay_many.py b/selfdrive/boardd/tests/replay_many.py index 41e86f4124..71db229a21 100755 --- a/selfdrive/boardd/tests/replay_many.py +++ b/selfdrive/boardd/tests/replay_many.py @@ -56,7 +56,6 @@ if __name__ == "__main__": serials = Panda.list() num_senders = len(serials) - if num_senders == 0: print("No senders found. Exiting") sys.exit(1) diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index c4db730368..f25cc69f7c 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -17,7 +17,6 @@ class CarController(): self.packer = CANPacker(dbc_name) - def update(self, enabled, CS, actuators, pcm_cancel_cmd, hud_alert): # this seems needed to avoid steering faults and to force the sync with the EPS counter frame = CS.lkas_counter diff --git a/selfdrive/car/chrysler/test_chryslercan.py b/selfdrive/car/chrysler/test_chryslercan.py index 5b15666c04..a172526189 100644 --- a/selfdrive/car/chrysler/test_chryslercan.py +++ b/selfdrive/car/chrysler/test_chryslercan.py @@ -8,7 +8,6 @@ VisualAlert = car.CarControl.HUDControl.VisualAlert GearShifter = car.CarState.GearShifter - class TestChryslerCan(unittest.TestCase): def test_hud(self): diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 03c6dab93c..9af22c07a1 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -10,7 +10,6 @@ class SteerLimitParams: STEER_ERROR_MAX = 80 - class CAR: PACIFICA_2017_HYBRID = "CHRYSLER PACIFICA HYBRID 2017" PACIFICA_2018_HYBRID = "CHRYSLER PACIFICA HYBRID 2018" diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index 100855eacb..b01814bca6 100755 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -34,7 +34,6 @@ class RadarInterface(RadarInterfaceBase): if self.trigger_msg not in self.updated_messages: return None - ret = car.RadarData.new_message() errors = [] if not self.rcp.can_valid: diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 38f7efb4f4..65f80187db 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -339,7 +339,6 @@ class CarState(CarStateBase): ("FCM_PROBLEM", "ACC_HUD", 0), ("ICONS", "ACC_HUD", 0)] - # all hondas except CRV, RDX and 2019 Odyssey@China use 0xe4 for steering checks = [(0xe4, 100)] if CP.carFingerprint in [CAR.CRV, CAR.CRV_EU, CAR.ACURA_RDX, CAR.ODYSSEY_CHN]: diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 1cb11bd119..56f216fc4e 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -387,7 +387,6 @@ class CarInterface(CarInterfaceBase): ret.longitudinalTuning.kiBP = [0., 35.] ret.longitudinalTuning.kiV = [0.18, 0.12] - else: raise ValueError("unsupported car %s" % candidate) diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py index b1606e64ad..a921534c5a 100755 --- a/selfdrive/car/honda/radar_interface.py +++ b/selfdrive/car/honda/radar_interface.py @@ -52,7 +52,6 @@ class RadarInterface(RadarInterfaceBase): self.updated_messages.clear() return rr - def _update(self, updated_messages): ret = car.RadarData.new_message() diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index e31a0bcea7..dfd07d581c 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -94,7 +94,6 @@ class CarController(): elif self.last_lead_distance != 0: self.last_lead_distance = 0 - # 20 Hz LFA MFA message if frame % 5 == 0 and self.car_fingerprint in [CAR.SONATA, CAR.PALISADE]: can_sends.append(create_lfa_mfa(self.packer, frame, enabled)) diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py index ecac936906..ce31cd2c0b 100644 --- a/selfdrive/car/mazda/carcontroller.py +++ b/selfdrive/car/mazda/carcontroller.py @@ -36,7 +36,6 @@ class CarController(): # Match stock message rate which is sent at 10hz can_sends.append(mazdacan.create_button_cmd(self.packer, CS.CP.carFingerprint, Buttons.CANCEL)) - self.apply_steer_last = apply_steer can_sends.append(mazdacan.create_steering_control(self.packer, CS.CP.carFingerprint, diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index ffa99dadac..e1c9030a04 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -56,7 +56,6 @@ class CarState(CarStateBase): ret.gas = cp.vl["ENGINE_DATA"]['PEDAL_GAS'] ret.gasPressed = ret.gas > 0 - # LKAS is enabled at 52kph going up and disabled at 45kph going down if speed_kph > LKAS_LIMITS.ENABLE_SPEED: self.lkas_allowed = True @@ -155,7 +154,6 @@ class CarState(CarStateBase): return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) - @staticmethod def get_cam_can_parser(CP): signals = [ ] diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 160f531f20..f4af318945 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -46,7 +46,6 @@ class CarInterface(CarInterfaceBase): # No steer below disable speed ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS - ret.centerToFront = ret.wheelbase * 0.41 # TODO: get actual value, for now starting with reasonable value for diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py index 7f3fc3d84b..0997b1200c 100644 --- a/selfdrive/car/subaru/carcontroller.py +++ b/selfdrive/car/subaru/carcontroller.py @@ -16,7 +16,6 @@ class CarControllerParams(): self.STEER_DRIVER_FACTOR = 1 # from dbc - class CarController(): def __init__(self, dbc_name, CP, VM): self.lkas_active = False diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index c9970beadb..1c8c3735d7 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -160,7 +160,6 @@ class CarState(CarStateBase): signals.append(("LOW_SPEED_LOCKOUT", "PCM_CRUISE_2", 0)) checks.append(("PCM_CRUISE_2", 33)) - if CP.carFingerprint == CAR.PRIUS: signals += [("STATE", "AUTOPARK_STATUS", 0)] diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 46a657f3fc..ae421892f8 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -146,7 +146,6 @@ class Controls: self.rk = Ratekeeper(100, print_delay_threshold=None) self.prof = Profiler(False) # off by default - def update_events(self, CS): """Compute carEvents from carState""" @@ -226,7 +225,6 @@ class Controls: and not self.CP.radarOffCan and CS.vEgo < 0.3: self.events.add(EventName.noTarget) - def data_sample(self): """Receive data from sockets and update carState""" @@ -255,7 +253,6 @@ class Controls: return CS - def state_transition(self, CS): """Compute conditional state transitions and execute actions on state transitions""" @@ -331,7 +328,6 @@ class Controls: # Check if openpilot is engaged self.enabled = self.active or self.state == State.preEnabled - def state_control(self, CS): """Given the state, this function returns an actuators packet""" @@ -382,7 +378,6 @@ class Controls: return actuators, v_acc_sol, a_acc_sol, lac_log - def publish_logs(self, CS, start_time, actuators, v_acc, a_acc, lac_log): """Send actuators and hud commands to the car, send controlsstate and MPC logging""" diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index e4d6f97234..3ae766281b 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -133,7 +133,6 @@ class RadarD(): idens = list(sorted(self.tracks.keys())) track_pts = list([self.tracks[iden].get_key_for_cluster() for iden in idens]) - # If we have multiple points, cluster them if len(track_pts) > 1: cluster_idxs = cluster_points_centroid(track_pts, 2.5) diff --git a/selfdrive/debug/internal/check_alive_valid.py b/selfdrive/debug/internal/check_alive_valid.py index cee03d6a37..cd8a2463eb 100755 --- a/selfdrive/debug/internal/check_alive_valid.py +++ b/selfdrive/debug/internal/check_alive_valid.py @@ -6,12 +6,10 @@ import cereal.messaging as messaging if __name__ == "__main__": sm = messaging.SubMaster(['thermal', 'health', 'model', 'liveCalibration', 'dMonitoringState', 'plan', 'pathPlan']) - i = 0 while True: sm.update(0) - i += 1 if i % 100 == 0: print() diff --git a/selfdrive/debug/mpc/live_lateral_mpc.py b/selfdrive/debug/mpc/live_lateral_mpc.py index d1e8276c11..7cd5c677a2 100755 --- a/selfdrive/debug/mpc/live_lateral_mpc.py +++ b/selfdrive/debug/mpc/live_lateral_mpc.py @@ -55,7 +55,6 @@ def mpc_vwr_thread(addr="127.0.0.1"): aa.invert_xaxis() plt.show() - # *** log *** livempc = messaging.sub_sock('liveMpc', addr=addr) model = messaging.sub_sock('model', addr=addr) diff --git a/selfdrive/debug/mpc/live_longitudinal_mpc.py b/selfdrive/debug/mpc/live_longitudinal_mpc.py index b5b4361e13..4861a03ede 100755 --- a/selfdrive/debug/mpc/live_longitudinal_mpc.py +++ b/selfdrive/debug/mpc/live_longitudinal_mpc.py @@ -97,8 +97,6 @@ def plot_longitudinal_mpc(addr="127.0.0.1"): fig.canvas.flush_events() - - if __name__ == "__main__": if len(sys.argv) > 1: plot_longitudinal_mpc(sys.argv[1]) diff --git a/selfdrive/debug/mpc/tune_lateral.py b/selfdrive/debug/mpc/tune_lateral.py index 95bf6023bc..f01865574b 100755 --- a/selfdrive/debug/mpc/tune_lateral.py +++ b/selfdrive/debug/mpc/tune_lateral.py @@ -151,7 +151,6 @@ ys.append(sol_y) deltas.append(delta) - plt.figure() for i in range(len(xs)): diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 14754f75b2..cb35763cd5 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -167,7 +167,6 @@ def calibrationd_thread(sm=None, pm=None): sm['cameraOdometry'].transStd, sm['cameraOdometry'].rotStd) - if DEBUG and new_vp is not None: print('got new vp', new_vp) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index ad84550601..3798b3a456 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -194,7 +194,6 @@ class Localizer(): ecef_pos_R = np.diag([(3*log.verticalAccuracy)**2]*3) ecef_vel_R = np.diag([(log.speedAccuracy)**2]*3) - #self.time = GPSTime.from_datetime(datetime.utcfromtimestamp(log.timestamp*1e-3)) self.unix_timestamp_millis = log.timestamp gps_est_error = np.sqrt((self.kf.x[0] - ecef_pos[0])**2 + diff --git a/selfdrive/locationd/models/constants.py b/selfdrive/locationd/models/constants.py index f0096aadb8..ebe83186e4 100644 --- a/selfdrive/locationd/models/constants.py +++ b/selfdrive/locationd/models/constants.py @@ -38,7 +38,6 @@ class ObservationKind: STEER_RATIO = 29 # [-] ROAD_FRAME_X_SPEED = 30 # (x) [m/s] - names = [ 'Unknown', 'No observation', diff --git a/selfdrive/locationd/test/test_params_learner.py b/selfdrive/locationd/test/test_params_learner.py index c1b75c5af9..bd2399b24b 100755 --- a/selfdrive/locationd/test/test_params_learner.py +++ b/selfdrive/locationd/test/test_params_learner.py @@ -46,8 +46,5 @@ class TestParamsLearner(unittest.TestCase): self.assertAlmostEqual(sr_target, sr, places=1) - - - if __name__ == "__main__": unittest.main() diff --git a/selfdrive/locationd/test/ublox.py b/selfdrive/locationd/test/ublox.py index cfb32ed816..8120f70fd2 100644 --- a/selfdrive/locationd/test/ublox.py +++ b/selfdrive/locationd/test/ublox.py @@ -737,7 +737,6 @@ class UBlox: self.buf = self.buf[n:] return ret - def write(self, dat): pass diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index c5e48a8633..6d858c9ecf 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -80,7 +80,6 @@ def configure_ublox(dev): dev.configure_message_rate(ublox.CLASS_MON, ublox.MSG_MON_HW, 1) - def int_to_bool_list(num): # for parsing bool bytes return [bool(num & (1 << n)) for n in range(8)] @@ -181,8 +180,6 @@ def gen_nav_data(msg, nav_frame_buffer): return gen_ephemeris(ephem_data) - - def gen_raw(msg): # meta data is in first part of tuple # list of measurements is in second part @@ -284,7 +281,6 @@ def main(): for i in range(1, 33): nav_frame_buffer[0][i] = {} - gpsLocationExternal = messaging.pub_sock('gpsLocationExternal') ubloxGnss = messaging.pub_sock('ubloxGnss') diff --git a/selfdrive/modeld/visiontest.py b/selfdrive/modeld/visiontest.py index aead045bc8..72dbe59acc 100644 --- a/selfdrive/modeld/visiontest.py +++ b/selfdrive/modeld/visiontest.py @@ -103,7 +103,6 @@ class VisionTest(): transform) return result - def transform_output_buffer(self, yuv_data, y_out, u_out, v_out, transform): assert len(yuv_data) == self.input_size[0] * self.input_size[1] * 3/2 diff --git a/selfdrive/test/longitudinal_maneuvers/maneuverplots.py b/selfdrive/test/longitudinal_maneuvers/maneuverplots.py index eb038c33af..9a5ea61559 100644 --- a/selfdrive/test/longitudinal_maneuvers/maneuverplots.py +++ b/selfdrive/test/longitudinal_maneuvers/maneuverplots.py @@ -61,7 +61,6 @@ class ManeuverPlot(): self.a_target_array.append(a_target) self.fcw_array.append(fcw) - def write_plot(self, path, maneuver_name): # title = self.title or maneuver_name # TODO: Missing plots from the old one: diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index f45ccda75f..45a4a01f5b 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -355,7 +355,6 @@ class Plant(): msg_data = fix(msg_data, 0xe4) can_msgs.append([0xe4, 0, msg_data, 2]) - # Fake sockets that controlsd subscribes to live_parameters = messaging.new_message('liveParameters') live_parameters.liveParameters.valid = True diff --git a/selfdrive/test/process_replay/inject_model.py b/selfdrive/test/process_replay/inject_model.py index aaba744419..ee16846751 100755 --- a/selfdrive/test/process_replay/inject_model.py +++ b/selfdrive/test/process_replay/inject_model.py @@ -65,7 +65,6 @@ def inject_model(msgs, segment_name): time.sleep(2) manager.kill_managed_process('camerad') - new_msgs = [] midx = 0 for msg in msgs: diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index ad0b9fc6f1..ca438ed666 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -94,7 +94,6 @@ class FakeSubMaster(messaging.SubMaster): wait_for_event(self.update_ready) self.update_ready.clear() - def update_msgs(self, cur_time, msgs): wait_for_event(self.update_called) self.update_called.clear() diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py index 8fc4205cd9..7e5217738f 100755 --- a/selfdrive/test/update_ci_routes.py +++ b/selfdrive/test/update_ci_routes.py @@ -65,7 +65,6 @@ if __name__ == "__main__": if not sync_to_ci_public(r): failed_routes.append(r) - if len(failed_routes): print("failed routes:") print(failed_routes) diff --git a/tools/carcontrols/joystick_test.py b/tools/carcontrols/joystick_test.py index acf01c7fd0..0d92c70423 100755 --- a/tools/carcontrols/joystick_test.py +++ b/tools/carcontrols/joystick_test.py @@ -63,7 +63,6 @@ while not done: if event.type == pygame.JOYBUTTONUP: print("Joystick button released.") - # DRAWING STEP # First, clear the screen to white. Don't put other drawing commands # above this, or they will be erased with this command. @@ -107,10 +106,8 @@ while not done: textPrint.printf(screen, "Button {:>2} value: {}".format(i, button) ) textPrint.unindent() - textPrint.unindent() - # ALL CODE TO DRAW SHOULD GO ABOVE THIS COMMENT # Go ahead and update the screen with what we've drawn. diff --git a/tools/lib/kbhit.py b/tools/lib/kbhit.py index 57958e3ba8..fcb29c16a5 100644 --- a/tools/lib/kbhit.py +++ b/tools/lib/kbhit.py @@ -31,14 +31,12 @@ class KBHit: termios.tcsetattr(self.fd, termios.TCSAFLUSH, self.old_term) - def getch(self): ''' Returns a keyboard character after kbhit() has been called. Should not be called in the same program as getarrow(). ''' return sys.stdin.read(1) - def getarrow(self): ''' Returns an arrow-key code after kbhit() has been called. Codes are 0 : up @@ -53,7 +51,6 @@ class KBHit: return vals.index(ord(c.decode('utf-8'))) - def kbhit(self): ''' Returns True if keyboard character was hit, False otherwise. ''' diff --git a/tools/lib/route_framereader.py b/tools/lib/route_framereader.py index 2045a4b4c6..a60547cc02 100644 --- a/tools/lib/route_framereader.py +++ b/tools/lib/route_framereader.py @@ -75,7 +75,6 @@ class RouteFrameReader(object): return self._frame_readers[segment_num].get(segment_id, **kwargs)[0] - def close(self): frs = self._frame_readers self._frame_readers.clear() diff --git a/tools/lib/tests/test_readers.py b/tools/lib/tests/test_readers.py index c8688a4d85..cb6ba3e11a 100755 --- a/tools/lib/tests/test_readers.py +++ b/tools/lib/tests/test_readers.py @@ -18,7 +18,6 @@ class TestReaders(unittest.TestCase): self.assertEqual(hist['carControl'], 6000) self.assertEqual(hist['logMessage'], 6857) - with tempfile.NamedTemporaryFile(suffix=".bz2") as fp: r = requests.get("https://github.com/commaai/comma2k19/blob/master/Example_1/b0c9d2329ad1606b%7C2018-08-02--08-34-47/40/raw_log.bz2?raw=true") fp.write(r.content) @@ -36,11 +35,9 @@ class TestReaders(unittest.TestCase): self.assertEqual(f.w, 1164) self.assertEqual(f.h, 874) - frame_first_30 = f.get(0, 30) self.assertEqual(len(frame_first_30), 30) - print(frame_first_30[15]) print("frame_0") diff --git a/tools/replay/camera.py b/tools/replay/camera.py index a726c27da5..e1869048ec 100755 --- a/tools/replay/camera.py +++ b/tools/replay/camera.py @@ -19,7 +19,6 @@ _FULL_FRAME_TO_BB = np.linalg.inv(_BB_TO_FULL_FRAME) _FULL_FRAME_SIZE = 1164, 874 - def pygame_modules_have_loaded(): return pygame.display.get_init() and pygame.font.get_init() diff --git a/tools/replay/lib/ui_helpers.py b/tools/replay/lib/ui_helpers.py index 277792f54e..b95c8f63e4 100644 --- a/tools/replay/lib/ui_helpers.py +++ b/tools/replay/lib/ui_helpers.py @@ -187,7 +187,6 @@ def draw_mpc(liveMpc, top_down): top_down[1][px, py] = mpc_color - class CalibrationTransformsForWarpMatrix(object): def __init__(self, model_to_full_frame, K, E): self._model_to_full_frame = model_to_full_frame diff --git a/tools/replay/sensorium.py b/tools/replay/sensorium.py index ea4a90996e..10b2a960d1 100755 --- a/tools/replay/sensorium.py +++ b/tools/replay/sensorium.py @@ -42,7 +42,6 @@ if __name__ == "__main__": calibration = CalibrationTransformsForWarpMatrix(warp_matrix, intrinsic_matrix, extrinsic_matrix) transform = np.dot(img_transform, calibration.model_to_full_frame) - if calibration is not None: imgw = cv2.warpAffine(imgff, transform[:2], (MEDMODEL_INPUT_SIZE[0], MEDMODEL_INPUT_SIZE[1]), diff --git a/tools/replay/ui.py b/tools/replay/ui.py index 5b7bf7b294..438f86f918 100755 --- a/tools/replay/ui.py +++ b/tools/replay/ui.py @@ -131,7 +131,6 @@ def ui_thread(addr, frame_address): [ 0.0, 0.0, 1.0] ]) - if rgb_img_raw and len(rgb_img_raw) == FULL_FRAME_SIZE[0] * FULL_FRAME_SIZE[1] * 3: imgff = np.frombuffer(rgb_img_raw, dtype=np.uint8).reshape((FULL_FRAME_SIZE[1], FULL_FRAME_SIZE[0], 3)) imgff = imgff[:, :, ::-1] # Convert BGR to RGB @@ -189,7 +188,6 @@ def ui_thread(addr, frame_address): # draw all radar points maybe_update_radar_points(sm['liveTracks'], top_down[1]) - if sm.updated['liveCalibration']: extrinsic_matrix = np.asarray(sm['liveCalibration'].extrinsicMatrix).reshape(3, 4) ke = intrinsic_matrix.dot(extrinsic_matrix) From ebed2d1dcc53f092696b61fd1e004045c9bde893 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 31 May 2020 17:34:16 -0700 Subject: [PATCH 165/656] enable flake8 E251: unexpected spaces around keyword / parameter equals --- .pre-commit-config.yaml | 2 +- common/api/__init__.py | 2 +- panda | 2 +- selfdrive/debug/cpu_usage_stat.py | 2 +- .../test/longitudinal_maneuvers/maneuver.py | 6 +- .../longitudinal_maneuvers/maneuverplots.py | 2 +- .../test/longitudinal_maneuvers/plant.py | 2 +- .../test_longitudinal.py | 92 +++++++++---------- tools/livedm/livedm.py | 2 +- 9 files changed, 56 insertions(+), 56 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 7b77f3f5ba..1c31c08fcd 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,7 +17,7 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E251,E265,E266,E302,E305,E402,E501,E502,E722,E741,W504 + - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E265,E266,E302,E305,E402,E501,E502,E722,E741,W504 - --statistics - repo: local hooks: diff --git a/common/api/__init__.py b/common/api/__init__.py index f44e48f963..b030c33334 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -38,4 +38,4 @@ def api_get(endpoint, method='GET', timeout=None, access_token=None, **params): headers['User-Agent'] = "openpilot-" + version - return requests.request(method, backend+endpoint, timeout=timeout, headers = headers, params=params) + return requests.request(method, backend+endpoint, timeout=timeout, headers=headers, params=params) diff --git a/panda b/panda index 275e76c2b2..8039638482 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 275e76c2b2f9206c82990fe7ba0a6a96ecb8a0bc +Subproject commit 8039638482ebedb9cd10cb1eac083631919ac95e diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index 1dcc4996b2..b18199885e 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -113,7 +113,7 @@ if __name__ == "__main__": for stat_type in ['avg', 'min', 'max']: msg += '\n {}: {}'.format(stat_type, [name + ':' + str(round(stat[stat_type][name]*100, 2)) for name in cpu_time_names]) l.append((os.path.basename(k), stat['avg']['total'], msg)) - l.sort(key= lambda x: -x[1]) + l.sort(key=lambda x: -x[1]) for x in l: print(x[2]) print('avg sum: {0:.2%} over {1} samples {2} seconds\n'.format( diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py index e79cf61d26..d60dcc4e31 100644 --- a/selfdrive/test/longitudinal_maneuvers/maneuver.py +++ b/selfdrive/test/longitudinal_maneuvers/maneuver.py @@ -25,9 +25,9 @@ class Maneuver(): def evaluate(self): """runs the plant sim and returns (score, run_data)""" plant = Plant( - lead_relevancy = self.lead_relevancy, - speed = self.speed, - distance_lead = self.distance_lead + lead_relevancy=self.lead_relevancy, + speed=self.speed, + distance_lead=self.distance_lead ) logs = defaultdict(list) diff --git a/selfdrive/test/longitudinal_maneuvers/maneuverplots.py b/selfdrive/test/longitudinal_maneuvers/maneuverplots.py index 9a5ea61559..503c184456 100644 --- a/selfdrive/test/longitudinal_maneuvers/maneuverplots.py +++ b/selfdrive/test/longitudinal_maneuvers/maneuverplots.py @@ -7,7 +7,7 @@ import pylab from selfdrive.config import Conversions as CV class ManeuverPlot(): - def __init__(self, title = None): + def __init__(self, title=None): self.time_array = [] self.gas_array = [] diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index 45a4a01f5b..8ac65d855d 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -171,7 +171,7 @@ class Plant(): def current_time(self): return float(self.rk.frame) / self.rate - def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True): + def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model=True): gen_signals, gen_checks = get_can_signals(CP) sgs = [s[0] for s in gen_signals] msgs = [s[1] for s in gen_signals] diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py index 08b6cd047d..a7fb64b224 100755 --- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py +++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py @@ -34,8 +34,8 @@ 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), + 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)], checks=[check_engaged], @@ -44,7 +44,7 @@ maneuvers = [ '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), + 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)], checks=[check_engaged], @@ -53,93 +53,93 @@ maneuvers = [ '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.], + cruise_button_presses=[(CB.DECEL_SET, 1.2), (0, 1.3)], + grade_values=[0., 0., 1.0], + grade_breakpoints=[0., 10., 11.], checks=[check_engaged], ), 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.], + cruise_button_presses=[(CB.DECEL_SET, 1.2), (0, 1.3)], + grade_values=[0., 0., -1.0], + grade_breakpoints=[0., 10., 11.], checks=[check_engaged], ), Maneuver( 'approaching a 40mph car while cruising at 60mph from 100m away', duration=30., - initial_speed = 60. * CV.MPH_TO_MS, + 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)], + 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)], checks=[check_engaged, check_no_collision], ), Maneuver( 'approaching a 0mph car while cruising at 40mph from 150m away', duration=30., - initial_speed = 40. * CV.MPH_TO_MS, + 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)], + 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)], checks=[check_engaged, check_no_collision], ), Maneuver( 'steady state following a car at 20m/s, then lead decel to 0mph at 1m/s^2', duration=50., - initial_speed = 20., + initial_speed=20., lead_relevancy=True, initial_distance_lead=35., - speed_lead_values = [20., 20., 0.], - speed_lead_breakpoints = [0., 15., 35.0], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)], + speed_lead_values=[20., 20., 0.], + speed_lead_breakpoints=[0., 15., 35.0], + cruise_button_presses=[(CB.DECEL_SET, 1.2), (0, 1.3)], checks=[check_engaged, check_no_collision], ), Maneuver( 'steady state following a car at 20m/s, then lead decel to 0mph at 2m/s^2', duration=50., - initial_speed = 20., + initial_speed=20., lead_relevancy=True, initial_distance_lead=35., - speed_lead_values = [20., 20., 0.], - speed_lead_breakpoints = [0., 15., 25.0], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)], + speed_lead_values=[20., 20., 0.], + speed_lead_breakpoints=[0., 15., 25.0], + cruise_button_presses=[(CB.DECEL_SET, 1.2), (0, 1.3)], checks=[check_engaged, check_no_collision], ), Maneuver( 'steady state following a car at 20m/s, then lead decel to 0mph at 3m/s^2', duration=50., - initial_speed = 20., + initial_speed=20., lead_relevancy=True, initial_distance_lead=35., - speed_lead_values = [20., 20., 0.], - speed_lead_breakpoints = [0., 15., 21.66], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)], + speed_lead_values=[20., 20., 0.], + speed_lead_breakpoints=[0., 15., 21.66], + cruise_button_presses=[(CB.DECEL_SET, 1.2), (0, 1.3)], checks=[check_engaged, check_fcw], ), Maneuver( 'steady state following a car at 20m/s, then lead decel to 0mph at 5m/s^2', duration=40., - initial_speed = 20., + initial_speed=20., lead_relevancy=True, initial_distance_lead=35., - speed_lead_values = [20., 20., 0.], - speed_lead_breakpoints = [0., 15., 19.], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)], + speed_lead_values=[20., 20., 0.], + speed_lead_breakpoints=[0., 15., 19.], + cruise_button_presses=[(CB.DECEL_SET, 1.2), (0, 1.3)], checks=[check_engaged, check_fcw], ), Maneuver( 'starting at 0mph, approaching a stopped car 100m away', duration=30., - initial_speed = 0., + initial_speed=0., lead_relevancy=True, initial_distance_lead=100., - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + 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)], @@ -153,7 +153,7 @@ maneuvers = [ 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), + 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)], checks=[check_engaged, check_no_collision], @@ -166,7 +166,7 @@ maneuvers = [ 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), + 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)], checks=[check_engaged, check_no_collision], @@ -179,7 +179,7 @@ maneuvers = [ 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), + 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), @@ -195,7 +195,7 @@ maneuvers = [ 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), + 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)], checks=[check_engaged, check_no_collision], @@ -208,7 +208,7 @@ maneuvers = [ initial_distance_lead=20., speed_lead_values=[10., 0., 0., 10., 0., 0.] , speed_lead_breakpoints=[10., 13., 26., 33., 36., 45.], - cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + 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)], checks=[check_engaged, check_no_collision], @@ -221,7 +221,7 @@ maneuvers = [ 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), + 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), @@ -237,7 +237,7 @@ maneuvers = [ 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), + 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), @@ -253,7 +253,7 @@ maneuvers = [ initial_distance_lead=100., speed_lead_values=[20.], speed_lead_breakpoints=[1.], - cruise_button_presses = [], + cruise_button_presses=[], checks=[check_fcw], ), Maneuver( @@ -264,7 +264,7 @@ maneuvers = [ initial_distance_lead=35., speed_lead_values=[20., 0.], speed_lead_breakpoints=[3., 23.], - cruise_button_presses = [], + cruise_button_presses=[], checks=[check_fcw], ), Maneuver( @@ -275,7 +275,7 @@ maneuvers = [ initial_distance_lead=35., speed_lead_values=[20., 0.], speed_lead_breakpoints=[3., 9.6], - cruise_button_presses = [], + cruise_button_presses=[], checks=[check_fcw], ), Maneuver( @@ -286,7 +286,7 @@ maneuvers = [ initial_distance_lead=35., speed_lead_values=[20., 0.], speed_lead_breakpoints=[3., 7.], - cruise_button_presses = [], + cruise_button_presses=[], checks=[check_fcw], ) ] diff --git a/tools/livedm/livedm.py b/tools/livedm/livedm.py index 906a1da664..bb44cf56d3 100644 --- a/tools/livedm/livedm.py +++ b/tools/livedm/livedm.py @@ -71,7 +71,7 @@ if __name__ == "__main__": else: cv2.putText(img, 'you not found', (int(facePosition[0]*160+40), int(facePosition[1]*320+110)), cv2.FONT_ITALIC, 0.5, (64, 64, 64)) draw_pose(img, faceOrientation, facePosition, - W = 160, H = 320, xyoffset = (0, 0), faceprob=faceProb) + W=160, H=320, xyoffset=(0, 0), faceprob=faceProb) pygame.surfarray.blit_array(camera_surface, img.swapaxes(0, 1)) camera_surface_2x = pygame.transform.scale2x(camera_surface) From 6466ec982aa47bcbbc7c6a3a7cf60cec0163be84 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 31 May 2020 17:41:18 -0700 Subject: [PATCH 166/656] enable flake8 E502: backslash is redundant between brackets --- .pre-commit-config.yaml | 2 +- common/transformations/coordinates.py | 2 +- panda | 2 +- selfdrive/car/chrysler/interface.py | 2 +- selfdrive/car/gm/carcontroller.py | 2 +- selfdrive/car/gm/interface.py | 4 ++-- selfdrive/car/honda/carcontroller.py | 4 ++-- selfdrive/car/honda/carstate.py | 2 +- selfdrive/controls/controlsd.py | 10 +++++----- selfdrive/controls/lib/longcontrol.py | 2 +- selfdrive/controls/lib/pathplanner.py | 2 +- selfdrive/controls/lib/pid.py | 2 +- selfdrive/controls/tests/test_monitoring.py | 12 ++++++------ tools/livedm/livedm.py | 10 +++++----- 14 files changed, 29 insertions(+), 29 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 1c31c08fcd..e0a1755d10 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,7 +17,7 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E265,E266,E302,E305,E402,E501,E502,E722,E741,W504 + - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E265,E266,E302,E305,E402,E501,E722,E741,W504 - --statistics - repo: local hooks: diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index a0d179c353..f619e55cfb 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -51,7 +51,7 @@ def ecef2geodetic(ecef, radians=False): S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C)) P = F / (3 * pow((S + 1 / S + 1), 2) * G * G) Q = np.sqrt(1 + 2 * esq * esq * P) - r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \ + r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r) U = np.sqrt(pow((r - esq * r_0), 2) + z * z) V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z) diff --git a/panda b/panda index 8039638482..eba113cb67 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 8039638482ebedb9cd10cb1eac083631919ac95e +Subproject commit eba113cb677b53b868f166dd2437347698b1341e diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 381174e59d..85ad43af14 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -70,7 +70,7 @@ class CarInterface(CarInterfaceBase): ret.buttonEvents = [] # events - events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low], \ + events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low], gas_resume_speed=2.) if ret.vEgo < self.CP.minSteerSpeed: diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 9b4961272b..c304081c0a 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -67,7 +67,7 @@ class CarController(): self.packer_pt = CANPacker(DBC[CP.carFingerprint]['pt']) self.packer_ch = CANPacker(DBC[CP.carFingerprint]['chassis']) - def update(self, enabled, CS, frame, actuators, \ + def update(self, enabled, CS, frame, actuators, hud_v_cruise, hud_show_lanes, hud_show_car, hud_alert): P = self.params diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index c5ffb127b1..4dffa73c2b 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -182,9 +182,9 @@ class CarInterface(CarInterfaceBase): # In GM, PCM faults out if ACC command overlaps user gas. enabled = c.enabled and not self.CS.out.gasPressed - can_sends = self.CC.update(enabled, self.CS, self.frame, \ + can_sends = self.CC.update(enabled, self.CS, self.frame, c.actuators, - hud_v_cruise, c.hudControl.lanesVisible, \ + hud_v_cruise, c.hudControl.lanesVisible, c.hudControl.leadVisible, c.hudControl.visualAlert) self.frame += 1 diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index a09dffce30..0438dd76a0 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -96,8 +96,8 @@ class CarController(): self.params = CarControllerParams(CP) - def update(self, enabled, CS, frame, actuators, \ - pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \ + def update(self, enabled, CS, frame, actuators, + pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, hud_v_cruise, hud_show_lanes, hud_show_car, hud_alert): P = self.params diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 65f80187db..1adbfdf896 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -269,7 +269,7 @@ class CarState(CarStateBase): ret.cruiseState.speedOffset = calc_cruise_offset(0, ret.vEgo) if self.CP.carFingerprint in (CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.ACCORDH, CAR.CRV_HYBRID, CAR.INSIGHT): ret.brakePressed = cp.vl["POWERTRAIN_DATA"]['BRAKE_PRESSED'] != 0 or \ - (self.brake_switch and self.brake_switch_prev and \ + (self.brake_switch and self.brake_switch_prev and cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] != self.brake_switch_ts) self.brake_switch_prev = self.brake_switch self.brake_switch_ts = cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index ae421892f8..7d4591626d 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -44,12 +44,12 @@ class Controls: # Setup sockets self.pm = pm if self.pm is None: - self.pm = messaging.PubMaster(['sendcan', 'controlsState', 'carState', \ + self.pm = messaging.PubMaster(['sendcan', 'controlsState', 'carState', 'carControl', 'carEvents', 'carParams']) self.sm = sm if self.sm is None: - self.sm = messaging.SubMaster(['thermal', 'health', 'model', 'liveCalibration', \ + self.sm = messaging.SubMaster(['thermal', 'health', 'model', 'liveCalibration', 'dMonitoringState', 'plan', 'pathPlan', 'liveLocationKalman']) self.can_sock = can_sock @@ -76,8 +76,8 @@ class Controls: internet_needed or not openpilot_enabled_toggle # detect sound card presence and ensure successful init - sounds_available = not os.path.isfile('/EON') or (os.path.isfile('/proc/asound/card0/state') \ - and open('/proc/asound/card0/state').read().strip() == 'ONLINE') + sounds_available = (not os.path.isfile('/EON') or (os.path.isfile('/proc/asound/card0/state') and + open('/proc/asound/card0/state').read().strip() == 'ONLINE')) car_recognized = self.CP.carName != 'mock' # If stock camera is disconnected, we loaded car controls and it's not dashcam mode @@ -184,7 +184,7 @@ class Controls: self.events.add(EventName.preLaneChangeLeft) else: self.events.add(EventName.preLaneChangeRight) - elif self.sm['pathPlan'].laneChangeState in [LaneChangeState.laneChangeStarting, \ + elif self.sm['pathPlan'].laneChangeState in [LaneChangeState.laneChangeStarting, LaneChangeState.laneChangeFinishing]: self.events.add(EventName.laneChange) diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index 2b4db2e7af..d75f9db383 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -24,7 +24,7 @@ def long_control_state_trans(active, long_control_state, v_ego, v_target, v_pid, output_gb, brake_pressed, cruise_standstill): """Update longitudinal control state machine""" stopping_condition = (v_ego < 2.0 and cruise_standstill) or \ - (v_ego < STOPPING_EGO_SPEED and \ + (v_ego < STOPPING_EGO_SPEED and ((v_pid < STOPPING_TARGET_SPEED and v_target < STOPPING_TARGET_SPEED) or brake_pressed)) diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index a92efa1ade..48ae4baca0 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -106,7 +106,7 @@ class PathPlanner(): self.lane_change_direction = LaneChangeDirection.none else: torque_applied = sm['carState'].steeringPressed and \ - ((sm['carState'].steeringTorque > 0 and self.lane_change_direction == LaneChangeDirection.left) or \ + ((sm['carState'].steeringTorque > 0 and self.lane_change_direction == LaneChangeDirection.left) or (sm['carState'].steeringTorque < 0 and self.lane_change_direction == LaneChangeDirection.right)) lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob diff --git a/selfdrive/controls/lib/pid.py b/selfdrive/controls/lib/pid.py index d374619c19..916b95c9ea 100644 --- a/selfdrive/controls/lib/pid.py +++ b/selfdrive/controls/lib/pid.py @@ -73,7 +73,7 @@ class PIController(): # 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 \ + if ((error >= 0 and (control <= self.pos_limit or i < 0.0)) or (error <= 0 and (control >= self.neg_limit or i > 0.0))) and \ not freeze_integrator: self.i = i diff --git a/selfdrive/controls/tests/test_monitoring.py b/selfdrive/controls/tests/test_monitoring.py index 2cf8f0fdda..0753300bf6 100644 --- a/selfdrive/controls/tests/test_monitoring.py +++ b/selfdrive/controls/tests/test_monitoring.py @@ -83,11 +83,11 @@ class TestMonitoring(unittest.TestCase): def test_fully_distracted_driver(self): events_output, d_status = run_DState_seq(always_distracted, always_false, always_true, always_false) self.assertTrue(len(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PRE_TIME_TILL_TERMINAL)/2/DT_DMON)]) == 0) - self.assertEqual(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PRE_TIME_TILL_TERMINAL +\ + self.assertEqual(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PRE_TIME_TILL_TERMINAL + ((_DISTRACTED_PRE_TIME_TILL_TERMINAL-_DISTRACTED_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0], EventName.preDriverDistracted) - self.assertEqual(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PROMPT_TIME_TILL_TERMINAL +\ + self.assertEqual(events_output[int((_DISTRACTED_TIME-_DISTRACTED_PROMPT_TIME_TILL_TERMINAL + ((_DISTRACTED_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0], EventName.promptDriverDistracted) - self.assertEqual(events_output[int((_DISTRACTED_TIME +\ + self.assertEqual(events_output[int((_DISTRACTED_TIME + ((_TEST_TIMESPAN-10-_DISTRACTED_TIME)/2))/DT_DMON)].names[0], EventName.driverDistracted) self.assertIs(type(d_status.awareness), float) @@ -95,11 +95,11 @@ class TestMonitoring(unittest.TestCase): def test_fully_invisible_driver(self): events_output = run_DState_seq(always_no_face, always_false, always_true, always_false)[0] self.assertTrue(len(events_output[int((_AWARENESS_TIME-_AWARENESS_PRE_TIME_TILL_TERMINAL)/2/DT_DMON)]) == 0) - self.assertEqual(events_output[int((_AWARENESS_TIME-_AWARENESS_PRE_TIME_TILL_TERMINAL +\ + self.assertEqual(events_output[int((_AWARENESS_TIME-_AWARENESS_PRE_TIME_TILL_TERMINAL + ((_AWARENESS_PRE_TIME_TILL_TERMINAL-_AWARENESS_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0], EventName.preDriverUnresponsive) - self.assertEqual(events_output[int((_AWARENESS_TIME-_AWARENESS_PROMPT_TIME_TILL_TERMINAL +\ + self.assertEqual(events_output[int((_AWARENESS_TIME-_AWARENESS_PROMPT_TIME_TILL_TERMINAL + ((_AWARENESS_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0], EventName.promptDriverUnresponsive) - self.assertEqual(events_output[int((_AWARENESS_TIME +\ + self.assertEqual(events_output[int((_AWARENESS_TIME + ((_TEST_TIMESPAN-10-_AWARENESS_TIME)/2))/DT_DMON)].names[0], EventName.driverUnresponsive) # 3. op engaged, down to orange, driver pays attention, back to normal; then down to orange, driver touches wheel diff --git a/tools/livedm/livedm.py b/tools/livedm/livedm.py index bb44cf56d3..d54b353680 100644 --- a/tools/livedm/livedm.py +++ b/tools/livedm/livedm.py @@ -49,23 +49,23 @@ if __name__ == "__main__": img = np.zeros((320, 160, 3)) if faceProb > 0.4: cv2.putText(img, 'you', (int(facePosition[0]*160+40), int(facePosition[1]*320+110)), cv2.FONT_ITALIC, 0.5, (255, 255, 0)) - cv2.rectangle(img, (int(facePosition[0]*160+40), int(facePosition[1]*320+120)),\ + cv2.rectangle(img, (int(facePosition[0]*160+40), int(facePosition[1]*320+120)), (int(facePosition[0]*160+120), int(facePosition[1]*320+200)), (255, 255, 0), 1) not_blink = evt.driverMonitoring.leftBlinkProb + evt.driverMonitoring.rightBlinkProb < 1 if evt.driverMonitoring.leftEyeProb > 0.6: - cv2.line(img, (int(facePosition[0]*160+95), int(facePosition[1]*320+140)),\ + cv2.line(img, (int(facePosition[0]*160+95), int(facePosition[1]*320+140)), (int(facePosition[0]*160+105), int(facePosition[1]*320+140)), (255, 255, 0), 2) if not_blink: - cv2.line(img, (int(facePosition[0]*160+99), int(facePosition[1]*320+143)),\ + cv2.line(img, (int(facePosition[0]*160+99), int(facePosition[1]*320+143)), (int(facePosition[0]*160+101), int(facePosition[1]*320+143)), (255, 255, 0), 2) if evt.driverMonitoring.rightEyeProb > 0.6: - cv2.line(img, (int(facePosition[0]*160+55), int(facePosition[1]*320+140)),\ + cv2.line(img, (int(facePosition[0]*160+55), int(facePosition[1]*320+140)), (int(facePosition[0]*160+65), int(facePosition[1]*320+140)), (255, 255, 0), 2) if not_blink: - cv2.line(img, (int(facePosition[0]*160+59), int(facePosition[1]*320+143)),\ + cv2.line(img, (int(facePosition[0]*160+59), int(facePosition[1]*320+143)), (int(facePosition[0]*160+61), int(facePosition[1]*320+143)), (255, 255, 0), 2) else: From 5aad365fc0fb983cc4e58babf3c7f3d90bb6852b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 31 May 2020 18:18:59 -0700 Subject: [PATCH 167/656] bump submodules --- cereal | 2 +- panda | 2 +- rednose_repo | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/cereal b/cereal index b25a7d6f6e..58878bfd26 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit b25a7d6f6e4dc923f1ee1fd5ea13d6e12100341e +Subproject commit 58878bfd264d09c3c19f0a1bedbc0c2248019a8d diff --git a/panda b/panda index eba113cb67..f70ef291f9 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit eba113cb677b53b868f166dd2437347698b1341e +Subproject commit f70ef291f9e27c545de76bd3e57b15a5daabd8a9 diff --git a/rednose_repo b/rednose_repo index ffab6b4a36..6938fea39b 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit ffab6b4a369f809cc2058155d8316dfef75de2a9 +Subproject commit 6938fea39b78233eb6b7160ba8dabd7f505274d1 From cc7bc6785ff0932efd5a02c67a712a3e99d847ce Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 1 Jun 2020 01:49:55 -0700 Subject: [PATCH 168/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index f70ef291f9..d7f7b14118 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit f70ef291f9e27c545de76bd3e57b15a5daabd8a9 +Subproject commit d7f7b141181c290e8ceb982a69e0f5729532c67f From 5b431d41a8c7cd682be8fccf6dccb1c3d28b2a37 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 1 Jun 2020 01:55:56 -0700 Subject: [PATCH 169/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 58878bfd26..3ad1ac096b 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 58878bfd264d09c3c19f0a1bedbc0c2248019a8d +Subproject commit 3ad1ac096b8be6c598fd8352e0962019cd032545 From 3e3656e62b3f2273a143acc727489a7d8b986034 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 1 Jun 2020 02:03:24 -0700 Subject: [PATCH 170/656] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index 4c59163aa3..1f1ff225bd 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 4c59163aa31b58436fad2f8cbadeacd564887276 +Subproject commit 1f1ff225bd03b273a4861a67d96d4e53d7ce542c From 41fbce59067569d370b38f40cd1ef09b61c08df2 Mon Sep 17 00:00:00 2001 From: Jafar Al-Gharaibeh Date: Mon, 1 Jun 2020 04:04:47 -0500 Subject: [PATCH 171/656] Mazda: Slower rate for ACC cancel msg to avoid cruise disable (#1615) * Slower rate for ACC cancel msg to avoid cruise disable Sending ACC cancel message at 10hz may end up disabling main cruise state. That is because stoc ACC use the same signal for both functions. If cruise is already enabled the signal canceles it, otherwise cruise is disabled. 10hz seems to be still fast in some cases not allowing the state to sync up between OP and the Stock state. 5hz avoids that issue. Also, the resume message was also updated to 5hz as that seems to work better as well. Signed-off-by: Jafar Al-Gharaibeh * Round up 27.96 to 28mph Signed-off-by: Jafar Al-Gharaibeh --- selfdrive/car/mazda/carcontroller.py | 8 ++++---- selfdrive/car/mazda/interface.py | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py index ce31cd2c0b..20d80e519a 100644 --- a/selfdrive/car/mazda/carcontroller.py +++ b/selfdrive/car/mazda/carcontroller.py @@ -23,17 +23,17 @@ class CarController(): CS.out.steeringTorque, SteerLimitParams) self.steer_rate_limited = new_steer != apply_steer - if CS.out.standstill and frame % 50 == 0: + if CS.out.standstill and frame % 20 == 0: # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds - # Send Resume button at 2hz if we're engaged at standstill to support full stop and go! + # Send Resume button at 5hz if we're engaged at standstill to support full stop and go! # TODO: improve the resume trigger logic by looking at actual radar data can_sends.append(mazdacan.create_button_cmd(self.packer, CS.CP.carFingerprint, Buttons.RESUME)) else: apply_steer = 0 self.steer_rate_limited = False - if CS.out.cruiseState.enabled and frame % 10 == 0: + if CS.out.cruiseState.enabled and frame % 20 == 0: # Cancel Stock ACC if it's enabled while OP is disengaged - # Match stock message rate which is sent at 10hz + # Send at a rate of 5hz until we sync with stock ACC state can_sends.append(mazdacan.create_button_cmd(self.packer, CS.CP.carFingerprint, Buttons.CANCEL)) self.apply_steer_last = apply_steer diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index f4af318945..2cd286b6ed 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -44,7 +44,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kf = 0.00006 # No steer below disable speed - ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS + ret.minSteerSpeed = round(LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS) ret.centerToFront = ret.wheelbase * 0.41 From f575a9ec12990ac2a764a5f416795d1c618f4609 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 10:14:11 -0700 Subject: [PATCH 172/656] Fix low speed engage on stop and go Hondas (#1613) * fix low speed engage on stop and go Hondas * update ref commit --- selfdrive/car/honda/interface.py | 5 +++-- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 56f216fc4e..b18252d579 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -483,8 +483,9 @@ class CarInterface(CarInterfaceBase): # 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 - if self.CP.enableCruise and not ret.cruiseState.enabled and (c.actuators.brake <= 0. or not self.CP.openpilotLongitudinalControl): - # non loud alert if cruise disbales below 25mph as expected (+ a little margin) + if self.CP.enableCruise and not ret.cruiseState.enabled \ + and (c.actuators.brake <= 0. or not self.CP.openpilotLongitudinalControl) and (self.CP.minEnableSpeed > 0): + # non loud alert if cruise disables below 25mph as expected (+ a little margin) if ret.vEgo < self.CP.minEnableSpeed + 2.: events.add(EventName.speedTooLow) else: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 7e5f01eb3d..bdcc7b799f 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -d50cc2d81fd73dcfccfe1a8e2726879941ec5327 \ No newline at end of file +5bad0192bf35d8f08f26dd5ac72b3c1d62a57569 \ No newline at end of file From 56e155d41cc84f480f3b72c68476fddbf786c6e2 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Mon, 1 Jun 2020 12:09:00 -0700 Subject: [PATCH 173/656] better name --- common/transformations/coordinates.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index f619e55cfb..4f8445145c 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -64,6 +64,11 @@ def ecef2geodetic(ecef, radians=False): geodetic = np.column_stack((lat, lon, h)) return geodetic.reshape(input_shape) + +geodetic_from_ecef = ecef2geodetic +ecef_from_geodetic = geodetic2ecef + + class LocalCoord(): """ Allows conversions to local frames. In this case NED. From a108e7f211e4af4b4e0ac334686c11cdb7a26f2e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 13:39:53 -0700 Subject: [PATCH 174/656] paramsd output at 20 Hz instead of 100 Hz --- selfdrive/locationd/paramsd.py | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index 29d7c73f39..70ffd4795c 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -103,7 +103,6 @@ def main(sm=None, pm=None): learner = ParamsLearner(CP, params['steerRatio'], params['stiffnessFactor'], math.radians(params['angleOffsetAverage'])) min_sr, max_sr = 0.5 * CP.steerRatio, 2.0 * CP.steerRatio - i = 0 while True: sm.update() @@ -113,14 +112,10 @@ def main(sm=None, pm=None): t = sm.logMonoTime[which] * 1e-9 learner.handle_log(t, which, sm[which]) - # TODO: set valid to false when locationd stops sending - # TODO: make sure controlsd knows when there is no gyro - - if sm.updated['carState']: + if sm.updated['carState'] and (learner.carstate_counter % CARSTATE_DECIMATION == 0): msg = messaging.new_message('liveParameters') msg.logMonoTime = sm.logMonoTime['carState'] - msg.liveParameters.valid = True # TODO: Check if learned values are sane msg.liveParameters.posenetValid = True msg.liveParameters.sensorValid = True @@ -136,8 +131,7 @@ def main(sm=None, pm=None): min_sr <= msg.liveParameters.steerRatio <= max_sr, )) - i += 1 - if i % 6000 == 0: # once a minute + if learner.carstate_counter % 6000 == 0: # once a minute params = { 'carFingerprint': CP.carFingerprint, 'steerRatio': msg.liveParameters.steerRatio, From a2ca743f66dd68d6d7ee3c4047e7d8ca2d3e6bd8 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 13:45:06 -0700 Subject: [PATCH 175/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 3ad1ac096b..a4beeb99ff 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 3ad1ac096b8be6c598fd8352e0962019cd032545 +Subproject commit a4beeb99ff8a2d553c29249d55e95ecee8ec8b47 From fab8425f2f5277f3e767e29f01942448674428b0 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 13:58:54 -0700 Subject: [PATCH 176/656] Make driverview not pin two cores at 100% --- selfdrive/controls/lib/driverview.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/selfdrive/controls/lib/driverview.py b/selfdrive/controls/lib/driverview.py index ad49fb77ec..4581a06549 100755 --- a/selfdrive/controls/lib/driverview.py +++ b/selfdrive/controls/lib/driverview.py @@ -12,6 +12,7 @@ from common.basedir import BASEDIR KILL_TIMEOUT = 15 + def send_controls_packet(pm): while True: dat = messaging.new_message('controlsState') @@ -19,6 +20,8 @@ def send_controls_packet(pm): "rearViewCam": True, } pm.send('controlsState', dat) + time.sleep(0.01) + def send_dmon_packet(pm, d): dat = messaging.new_message('dMonitoringState') @@ -29,6 +32,7 @@ def send_dmon_packet(pm, d): } pm.send('dMonitoringState', dat) + def main(): pm = messaging.PubMaster(['controlsState', 'dMonitoringState']) controls_sender = multiprocessing.Process(target=send_controls_packet, args=[pm]) @@ -70,5 +74,8 @@ def main(): is_rhd = params.get("IsRHD") == b"1" is_rhd_checked = True + time.sleep(0.01) + + if __name__ == '__main__': main() From cdb48cc180bd22fbad75785d07a7f47da959880c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 2 Jun 2020 05:00:43 +0800 Subject: [PATCH 177/656] dmonitoring : use memory cache to avoid malloc/free on every frame (#1599) * use memory cache * use template function to return buffer * inline function * const size_t * use std::vector instead of kj::array --- selfdrive/modeld/models/dmonitoring.cc | 23 ++++++++++++----------- selfdrive/modeld/models/dmonitoring.h | 11 ++++++----- 2 files changed, 18 insertions(+), 16 deletions(-) diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 21fac61c28..6dc90718d1 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -26,6 +26,14 @@ void dmonitoring_init(DMonitoringModelState* s) { s->is_rhd_checked = false; } +template +static inline T *get_buffer(std::vector &buf, const size_t size) { + if (buf.size() < size) { + buf.resize(size); + } + return buf.data(); +} + DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height) { uint8_t *raw_buf = (uint8_t*) stream_buf; @@ -39,8 +47,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ int resized_width = MODEL_WIDTH; int resized_height = MODEL_HEIGHT; - uint8_t *cropped_buf = new uint8_t[cropped_width*cropped_height*3/2]; - uint8_t *cropped_y_buf = cropped_buf; + uint8_t *cropped_y_buf = get_buffer(s->cropped_buf, cropped_width*cropped_height*3/2); uint8_t *cropped_u_buf = cropped_y_buf + (cropped_width * cropped_height); uint8_t *cropped_v_buf = cropped_u_buf + ((cropped_width/2) * (cropped_height/2)); @@ -53,8 +60,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ } } else { // not tested - uint8_t *premirror_cropped_buf = new uint8_t[cropped_width*cropped_height*3/2]; - uint8_t *premirror_cropped_y_buf = premirror_cropped_buf; + uint8_t *premirror_cropped_y_buf = get_buffer(s->premirror_cropped_buf, cropped_width*cropped_height*3/2); uint8_t *premirror_cropped_u_buf = premirror_cropped_y_buf + (cropped_width * cropped_height); uint8_t *premirror_cropped_v_buf = premirror_cropped_u_buf + ((cropped_width/2) * (cropped_height/2)); for (int r = 0; r < height/2; r++) { @@ -70,10 +76,9 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ cropped_u_buf, cropped_width/2, cropped_v_buf, cropped_width/2, cropped_width, cropped_height); - delete[] premirror_cropped_buf; } - uint8_t *resized_buf = new uint8_t[resized_width*resized_height*3/2]; + uint8_t *resized_buf = get_buffer(s->resized_buf, resized_width*resized_height*3/2); uint8_t *resized_y_buf = resized_buf; uint8_t *resized_u_buf = resized_y_buf + (resized_width * resized_height); uint8_t *resized_v_buf = resized_u_buf + ((resized_width/2) * (resized_height/2)); @@ -90,8 +95,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ mode); int yuv_buf_len = (MODEL_WIDTH/2) * (MODEL_HEIGHT/2) * 6; // Y|u|v -> y|y|y|y|u|v - - float *net_input_buf = new float[yuv_buf_len]; + float *net_input_buf = get_buffer(s->net_input_buf, yuv_buf_len); // one shot conversion, O(n) anyway // yuvframe2tensor, normalize for (int r = 0; r < MODEL_HEIGHT/2; r++) { @@ -120,10 +124,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ //fwrite(net_input_buf, MODEL_HEIGHT*MODEL_WIDTH*3/2, sizeof(float), dump_yuv_file2); //fclose(dump_yuv_file2); - delete[] cropped_buf; - delete[] resized_buf; s->m->execute(net_input_buf, yuv_buf_len); - delete[] net_input_buf; DMonitoringResult ret = {0}; memcpy(&ret.face_orientation, &s->output[0], sizeof ret.face_orientation); diff --git a/selfdrive/modeld/models/dmonitoring.h b/selfdrive/modeld/models/dmonitoring.h index e8a496dee9..c0a0cf4463 100644 --- a/selfdrive/modeld/models/dmonitoring.h +++ b/selfdrive/modeld/models/dmonitoring.h @@ -1,10 +1,8 @@ -#ifndef DMONITORING_H -#define DMONITORING_H - +#pragma once +#include #include "common/util.h" #include "commonmodel.h" #include "runners/run.h" - #include "messaging.hpp" #ifdef __cplusplus @@ -31,6 +29,10 @@ typedef struct DMonitoringModelState { bool is_rhd; bool is_rhd_checked; float output[OUTPUT_SIZE]; + std::vector resized_buf; + std::vector cropped_buf; + std::vector premirror_cropped_buf; + std::vector net_input_buf; } DMonitoringModelState; void dmonitoring_init(DMonitoringModelState* s); @@ -42,4 +44,3 @@ void dmonitoring_free(DMonitoringModelState* s); } #endif -#endif From d00cdf1e0c7bf7fc8bb7726bafb93e8e6f946574 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 14:24:48 -0700 Subject: [PATCH 178/656] longitudinal test should broadcast liveLocationKalman --- selfdrive/test/longitudinal_maneuvers/plant.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index 8ac65d855d..f8c265d07f 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -113,6 +113,7 @@ class Plant(): Plant.sendcan = messaging.sub_sock('sendcan') Plant.model = messaging.pub_sock('model') Plant.live_params = messaging.pub_sock('liveParameters') + Plant.live_location_kalman = messaging.pub_sock('liveLocationKalman') Plant.health = messaging.pub_sock('health') Plant.thermal = messaging.pub_sock('thermal') Plant.driverState = messaging.pub_sock('driverState') @@ -161,6 +162,7 @@ class Plant(): Plant.logcan.close() Plant.model.close() Plant.live_params.close() + Plant.live_location_kalman.close() def speed_sensor(self, speed): if speed < 0.3: @@ -378,6 +380,11 @@ class Plant(): thermal.thermal.batteryPercent = 100 Plant.thermal.send(thermal.to_bytes()) + live_location_kalman = messaging.new_message('liveLocationKalman') + live_location_kalman.liveLocationKalman.inputsOK = True + live_location_kalman.liveLocationKalman.gpsOK = True + Plant.live_location_kalman.send(live_location_kalman.to_bytes()) + # ******** publish a fake model going straight and fake calibration ******** # note that this is worst case for MPC, since model will delay long mpc by one time step if publish_model and self.frame % 5 == 0: From c9dbaf821c5654019dec0ac814c56ed54c3cacf3 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 2 Jun 2020 05:30:53 +0800 Subject: [PATCH 179/656] Template version of read_param (#1593) --- selfdrive/ui/ui.cc | 78 ++++++++++++++-------------------------------- 1 file changed, 23 insertions(+), 55 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index e70197b268..31f6c17179 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -4,6 +4,7 @@ #include #include #include +#include #include #include #include "common/util.h" @@ -135,61 +136,28 @@ static void set_do_exit(int sig) { do_exit = 1; } -static void read_param_bool(bool* param, const char* param_name, bool persistent_param = false) { +template +static int read_param(T* param, const char *param_name, bool persistent_param = false){ char *s; - const int result = read_db_value(param_name, &s, NULL, persistent_param); - if (result == 0) { - *param = s[0] == '1'; - free(s); - } -} - -static int read_param_float(float* param, const char* param_name, bool persistent_param = false) { - char *s; - const int result = read_db_value(param_name, &s, NULL, persistent_param); - if (result == 0) { - *param = strtod(s, NULL); + int result = read_db_value(param_name, &s, NULL, persistent_param); + if (result == 0){ + std::istringstream iss(s); + iss >> *param; free(s); } return result; } -static int read_param_uint64(uint64_t* dest, const char* param_name, bool persistent_param = false) { - char *s; - const int result = read_db_value(param_name, &s, NULL, persistent_param); - if (result == 0) { - *dest = strtoull(s, NULL, 0); - free(s); - } - return result; -} - -static void read_param_bool_timeout(bool* param, const char* param_name, int* timeout, bool persistent_param = false) { - if (*timeout > 0){ - (*timeout)--; - } else { - read_param_bool(param, param_name, persistent_param); - *timeout = 2 * UI_FREQ; // 0.5Hz - } -} - -static void read_param_float_timeout(float* param, const char* param_name, int* timeout, bool persistent_param = false) { +template +static int read_param_timeout(T* param, const char* param_name, int* timeout, bool persistent_param = false) { + int result = -1; if (*timeout > 0){ (*timeout)--; } else { - read_param_float(param, param_name, persistent_param); *timeout = 2 * UI_FREQ; // 0.5Hz + result = read_param(param, param_name, persistent_param); } -} - -static int read_param_uint64_timeout(uint64_t* dest, const char* param_name, int* timeout, bool persistent_param = false) { - if (*timeout > 0){ - (*timeout)--; - return -1; - } else { - *timeout = 2 * UI_FREQ; // 0.5Hz - return read_param_uint64(dest, param_name, persistent_param); - } + return result; } static int write_param_float(float param, const char* param_name, bool persistent_param = false) { @@ -277,10 +245,10 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, 0.0f, 0.0f, 0.0f, 1.0f, }}; - read_param_float(&s->speed_lim_off, "SpeedLimitOffset"); - read_param_bool(&s->is_metric, "IsMetric"); - read_param_bool(&s->longitudinal_control, "LongitudinalControl"); - read_param_bool(&s->limit_set_speed, "LimitSetSpeed"); + read_param(&s->speed_lim_off, "SpeedLimitOffset"); + read_param(&s->is_metric, "IsMetric"); + read_param(&s->longitudinal_control, "LongitudinalControl"); + read_param(&s->limit_set_speed, "LimitSetSpeed"); // Set offsets so params don't get read at the same time s->longitudinal_control_timeout = UI_FREQ / 3; @@ -829,8 +797,8 @@ int main(int argc, char* argv[]) { const int LEON = is_leon(); float brightness_b, brightness_m; - int result = read_param_float(&brightness_b, "BRIGHTNESS_B", true); - result += read_param_float(&brightness_m, "BRIGHTNESS_M", true); + int result = read_param(&brightness_b, "BRIGHTNESS_B", true); + result += read_param(&brightness_m, "BRIGHTNESS_M", true); if(result != 0){ brightness_b = LEON ? 10.0 : 5.0; @@ -965,11 +933,11 @@ int main(int argc, char* argv[]) { s->alert_sound = cereal::CarControl::HUDControl::AudibleAlert::NONE; } - read_param_bool_timeout(&s->is_metric, "IsMetric", &s->is_metric_timeout); - read_param_bool_timeout(&s->longitudinal_control, "LongitudinalControl", &s->longitudinal_control_timeout); - read_param_bool_timeout(&s->limit_set_speed, "LimitSetSpeed", &s->limit_set_speed_timeout); - read_param_float_timeout(&s->speed_lim_off, "SpeedLimitOffset", &s->limit_set_speed_timeout); - int param_read = read_param_uint64_timeout(&s->last_athena_ping, "LastAthenaPingTime", &s->last_athena_ping_timeout); + read_param_timeout(&s->is_metric, "IsMetric", &s->is_metric_timeout); + read_param_timeout(&s->longitudinal_control, "LongitudinalControl", &s->longitudinal_control_timeout); + read_param_timeout(&s->limit_set_speed, "LimitSetSpeed", &s->limit_set_speed_timeout); + read_param_timeout(&s->speed_lim_off, "SpeedLimitOffset", &s->limit_set_speed_timeout); + int param_read = read_param_timeout(&s->last_athena_ping, "LastAthenaPingTime", &s->last_athena_ping_timeout); if (param_read != -1) { // Param was updated this loop if (param_read != 0) { // Failed to read param s->scene.athenaStatus = NET_DISCONNECTED; From 843b2940c5b35a92cc3f9f7d0f4310a420a8ad94 Mon Sep 17 00:00:00 2001 From: Andre Volmensky Date: Tue, 2 Jun 2020 06:38:20 +0900 Subject: [PATCH 180/656] Nissan mph bit (#1609) * Added MPH bit for Rogue/XTrail * Init seatbeltUnlatched as True --- selfdrive/car/nissan/carstate.py | 20 +++++++++----------- 1 file changed, 9 insertions(+), 11 deletions(-) diff --git a/selfdrive/car/nissan/carstate.py b/selfdrive/car/nissan/carstate.py index 45156a8cb9..c56e047331 100644 --- a/selfdrive/car/nissan/carstate.py +++ b/selfdrive/car/nissan/carstate.py @@ -11,6 +11,7 @@ class CarState(CarStateBase): def __init__(self, CP): super().__init__(CP) can_define = CANDefine(DBC[CP.carFingerprint]['pt']) + self.seatbeltUnlatched = True self.shifter_values = can_define.dv["GEARBOX"]["GEAR_SHIFTER"] @@ -44,20 +45,18 @@ class CarState(CarStateBase): ret.cruiseState.enabled = bool(cp_adas.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL]: + ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 ret.cruiseState.available = bool(cp_cam.vl["PRO_PILOT"]["CRUISE_ON"]) elif self.CP.carFingerprint == CAR.LEAF: + ret.seatbeltUnlatched = cp.vl["SEATBELT"]["SEATBELT_DRIVER_LATCHED"] == 0 ret.cruiseState.available = bool(cp.vl["CRUISE_THROTTLE"]["CRUISE_AVAILABLE"]) - # TODO: Find mph/kph bit on XTRAIL until then, assume xtrail is kph. - # Unable to change kph to mph on the xtrail, need a rogue to test it on speed = cp_adas.vl["PROPILOT_HUD"]["SET_SPEED"] if speed != 255: - if self.CP.carFingerprint == CAR.XTRAIL: - conversion = CV.KPH_TO_MS - elif self.CP.carFingerprint == CAR.ROGUE: - conversion = CV.MPH_TO_MS - else: + if self.CP.carFingerprint == CAR.LEAF: conversion = CV.MPH_TO_MS if cp.vl["HUD_SETTINGS"]["SPEED_MPH"] else CV.KPH_TO_MS + else: + conversion = CV.MPH_TO_MS if cp.vl["HUD"]["SPEED_MPH"] else CV.KPH_TO_MS speed -= 1 # Speed on HUD is always 1 lower than actually sent on can bus ret.cruiseState.speed = speed * conversion @@ -74,8 +73,6 @@ class CarState(CarStateBase): cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FR"], cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FL"]]) - ret.seatbeltUnlatched = cp.vl["SEATBELT"]["SEATBELT_DRIVER_LATCHED"] == 0 - ret.espDisabled = bool(cp.vl["ESP"]["ESP_DISABLED"]) can_gear = int(cp.vl["GEARBOX"]["GEAR_SHIFTER"]) @@ -115,8 +112,6 @@ class CarState(CarStateBase): ("RIGHT_BLINKER", "LIGHTS", 0), ("LEFT_BLINKER", "LIGHTS", 0), - ("SEATBELT_DRIVER_LATCHED", "SEATBELT", 0), - ("ESP_DISABLED", "ESP", 0), ("GEAR_SHIFTER", "GEARBOX", 0), @@ -137,6 +132,8 @@ class CarState(CarStateBase): ("BRAKE_LIGHT", "DOORS_LIGHTS", 1), ("GAS_PEDAL", "GAS_PEDAL", 0), + ("SEATBELT_DRIVER_LATCHED", "HUD", 0), + ("SPEED_MPH", "HUD", 0), ("PROPILOT_BUTTON", "CRUISE_THROTTLE", 0), ("CANCEL_BUTTON", "CRUISE_THROTTLE", 0), @@ -165,6 +162,7 @@ class CarState(CarStateBase): ("GAS_PEDAL", "CRUISE_THROTTLE", 0), ("CRUISE_AVAILABLE", "CRUISE_THROTTLE", 0), ("SPEED_MPH", "HUD_SETTINGS", 0), + ("SEATBELT_DRIVER_LATCHED", "SEATBELT", 0), # Copy other values, we use this to cancel ("CANCEL_SEATBELT", "CANCEL_MSG", 0), From 7316872607c79e6600d0ea8913357902f1bea314 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 14:38:55 -0700 Subject: [PATCH 181/656] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index 1f1ff225bd..c25b757ac6 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 1f1ff225bd03b273a4861a67d96d4e53d7ce542c +Subproject commit c25b757ac66bbe26148174bac9d2db86346963d4 From fa7d8f6e1b6c8a27dacff2bbff89b3cbe79c5609 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 14:39:06 -0700 Subject: [PATCH 182/656] remove unused line in nissan carstate --- selfdrive/car/nissan/carstate.py | 1 - 1 file changed, 1 deletion(-) diff --git a/selfdrive/car/nissan/carstate.py b/selfdrive/car/nissan/carstate.py index c56e047331..d43db51b6b 100644 --- a/selfdrive/car/nissan/carstate.py +++ b/selfdrive/car/nissan/carstate.py @@ -11,7 +11,6 @@ class CarState(CarStateBase): def __init__(self, CP): super().__init__(CP) can_define = CANDefine(DBC[CP.carFingerprint]['pt']) - self.seatbeltUnlatched = True self.shifter_values = can_define.dv["GEARBOX"]["GEAR_SHIFTER"] From afaa2b917c249872f59b5ab1a03a93c02d7a3789 Mon Sep 17 00:00:00 2001 From: cowanhmoore Date: Mon, 1 Jun 2020 18:26:47 -0400 Subject: [PATCH 183/656] HRV fix gas pedal signal (#1582) Seperate CAR.HRV from CAR.FIT HRV used GAS_PEDAL, not GAS_PEDAL_2 for FIT --- selfdrive/car/honda/carstate.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 1adbfdf896..a105b19eda 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -128,10 +128,14 @@ def get_can_signals(CP): ("MAIN_ON", "SCM_BUTTONS", 0)] elif CP.carFingerprint in (CAR.CRV, CAR.CRV_EU, CAR.ACURA_RDX, CAR.PILOT_2019, CAR.RIDGELINE): signals += [("MAIN_ON", "SCM_BUTTONS", 0)] - elif CP.carFingerprint in (CAR.FIT, CAR.HRV): + elif CP.carFingerprint == CAR.FIT: signals += [("CAR_GAS", "GAS_PEDAL_2", 0), ("MAIN_ON", "SCM_BUTTONS", 0), ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] + elif CP.carFingerprint == CAR.HRV: + signals += [("CAR_GAS", "GAS_PEDAL",0), + ("MAIN_ON", "SCM_BUTTONS", 0), + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] elif CP.carFingerprint == CAR.ODYSSEY: signals += [("MAIN_ON", "SCM_FEEDBACK", 0), ("EPB_STATE", "EPB_STATUS", 0)] @@ -243,7 +247,7 @@ class CarState(CarStateBase): self.pedal_gas = cp.vl["POWERTRAIN_DATA"]['PEDAL_GAS'] # crv doesn't include cruise control - if self.CP.carFingerprint in (CAR.CRV, CAR.CRV_EU, CAR.ODYSSEY, CAR.ACURA_RDX, CAR.RIDGELINE, CAR.PILOT_2019, CAR.ODYSSEY_CHN): + if self.CP.carFingerprint in (CAR.CRV, CAR.CRV_EU, CAR.HRV, CAR.ODYSSEY, CAR.ACURA_RDX, CAR.RIDGELINE, CAR.PILOT_2019, CAR.ODYSSEY_CHN): ret.gas = self.pedal_gas / 256. else: ret.gas = cp.vl["GAS_PEDAL_2"]['CAR_GAS'] / 256. From 5b8f025fb046c0f3e19bfdad03ac72fe5df30243 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 15:28:34 -0700 Subject: [PATCH 184/656] bump opendbc with hrv gas signal --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index c25b757ac6..daf3bc988f 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit c25b757ac66bbe26148174bac9d2db86346963d4 +Subproject commit daf3bc988f91703293784099e57ae78b8d593a8d From 0a5bb88ca293a690d947ea5d98e915f3f3c8eca9 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 15:28:47 -0700 Subject: [PATCH 185/656] fix flake8 error in honda carstate --- selfdrive/car/honda/carstate.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index a105b19eda..8635831db1 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -133,9 +133,10 @@ def get_can_signals(CP): ("MAIN_ON", "SCM_BUTTONS", 0), ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] elif CP.carFingerprint == CAR.HRV: - signals += [("CAR_GAS", "GAS_PEDAL",0), + signals += [("CAR_GAS", "GAS_PEDAL", 0), ("MAIN_ON", "SCM_BUTTONS", 0), - ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] + elif CP.carFingerprint == CAR.ODYSSEY: signals += [("MAIN_ON", "SCM_FEEDBACK", 0), ("EPB_STATE", "EPB_STATUS", 0)] From 205cb04ee95f51c0d96f20d71564ef6d1c530d85 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 15:53:41 -0700 Subject: [PATCH 186/656] speedTooHigh should not be an immediate disable --- selfdrive/controls/lib/events.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index bf2dcaf049..2b21cd7171 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -681,7 +681,7 @@ EVENTS = { }, EventName.speedTooHigh: { - ET.IMMEDIATE_DISABLE: Alert( + ET.WARNING: Alert( "Speed Too High", "Slow down to resume operation", AlertStatus.normal, AlertSize.mid, From 884b327374890358424c90d1fc20b459f599987e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 16:41:04 -0700 Subject: [PATCH 187/656] ui.cc: read_db_value is not null terminated --- selfdrive/ui/ui.cc | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 31f6c17179..cd76ebe7c3 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -4,6 +4,7 @@ #include #include #include +#include #include #include #include @@ -138,12 +139,24 @@ static void set_do_exit(int sig) { template static int read_param(T* param, const char *param_name, bool persistent_param = false){ - char *s; - int result = read_db_value(param_name, &s, NULL, persistent_param); + T param_orig = *param; + char *value; + size_t sz; + + int result = read_db_value(param_name, &value, &sz, persistent_param); if (result == 0){ + std::string s = std::string(value, sz); // value is not null terminated + free(value); + + // Parse result std::istringstream iss(s); iss >> *param; - free(s); + + // Restore original value if parsing failed + if (iss.fail()) { + *param = param_orig; + result = -1; + } } return result; } From 68040408da9809a480f224bbe4d09e8c3be40608 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Mon, 1 Jun 2020 18:35:28 -0700 Subject: [PATCH 188/656] Add Putty key --- tools/ssh/key/id_rsa.ppk | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) create mode 100644 tools/ssh/key/id_rsa.ppk diff --git a/tools/ssh/key/id_rsa.ppk b/tools/ssh/key/id_rsa.ppk new file mode 100644 index 0000000000..7183e69dd0 --- /dev/null +++ b/tools/ssh/key/id_rsa.ppk @@ -0,0 +1,26 @@ +PuTTY-User-Key-File-2: ssh-rsa +Encryption: none +Comment: imported-openssh-key +Public-Lines: 6 +AAAAB3NzaC1yc2EAAAADAQABAAABAQC+iXXq30Tq+J5NKat3KWHCzcmwZ55nGh6W +ggAqECa5CasBlM9VeROpVu3beA+5h0MibRgbD4DMtVXBt6gEvZ8nd04E7eLA9LTZ +yFDZ7SkSOVj4oXOQsT0GnJmKrASW5KslTWqVzTfo2XCtZ+004ikLxmyFeBO8NOcE +rW1pa8gFdQDToH9FrA7kgysic/XVESTOoe7XlzRoe/eZacEQ+jtnmFd21A4aEADk +k00Ahjr0uKaJiLUAPatxs2icIXWpgYtfqqtaKF23wSt61OTu6cAwXbOWr3m+IUSR +UO0IRzEIQS3z1jfd1svgzSgSSwZ1Lhj4AoKxIEAIc8qJrO4uymCJ +Private-Lines: 14 +AAABAQCEhXr8RxnaC92ecZMOqDuUkCjthsRHlYUczYJrvxwPqsfDq8qg+jtQlmON +N+5H7eolsZcIizncJ2tj9ubnlTNy8anUB9ikuA5pQsfpKuhcAoL9Ot30DzIQvS6V +opr2kEjxAu1VD40JaOLT2OrE02AVDodANYoUZv8e47irkAlosQqvAvw1ZwdV+Jho +/lt5yXOU8FSbYCW24ga6uj1q4bwf96ppMR0S+3VNkgW9ojURdSy2N9HScf3A+91A +yjR65a7I5N1CXNvTKePzJWnSr1JEajcJWMUrgLSVdJ2d/ohZC7N2nUkx3SaQpUHq ++OUedaxQ5VbA89mQaW/4UTUaBg7hAAAAgQDoDUSLEurtBg6HdxteHKHdbiSlW8D8 +U98ofU4zLc404P9j05r4z/C2FbXBKhEvaf664hbk4CFMi8gSK+PpsBmxNPe3Cu86 +u9i72vH1qWfinwGHK92N5biRLtPwU/miXoug63axM/dPUs64k865C86OUo8ogyHd +zdEU1ZOcbMw9rQAAAIEA0jNiPLxP3A2nrX0keKDI+VHuvOY88gdh0W5BuLMLovOI +Dk9aQFIbBbMuW1OTjHKv9NK+Lrw+YbCFqOGf1dU/UN5gSyE8lX/QFsUGUqUZx574 +nJZnOIcy3ONOnQLcvHAQToLFAGUd7PWgP3CtHkt9hEv2koUwL4voikTP1u9Gkc0A +AACAPLxtzP7rcHi76uESO5e1O2/otgWo3ytjpszYv8boH3i42OpNrX0Bkbr+qaU4 +3obY4trr4A1pIIyVID32aYq9yEbFTFIhYJaFhhxEzstEL3OQMLakyRS0w9Vs2trg +YpUlSBLIOmPNxonJIfnozphLGOnKNe0RWgGR8BnwhRYzu+k= +Private-MAC: 2af7f5a599fa35e22392b7770a2eb7a0be8718b7 \ No newline at end of file From 73b6eb48290596e3310a7a1f0af24dc48b07af90 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Mon, 1 Jun 2020 18:45:54 -0700 Subject: [PATCH 189/656] new laika --- laika_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/laika_repo b/laika_repo index 4d9df5eb09..fd77ad9ecc 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 4d9df5eb0994523d8061358e0210ca6e6a473e48 +Subproject commit fd77ad9eccf6b62bae587bd2f2ac09352712e23f From b042ac034e539df09a7040dd4f28b2afc2429f55 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 1 Jun 2020 18:57:04 -0700 Subject: [PATCH 190/656] Turn Jenkins CPU test back on (#1617) * run cpu test again * Update cpu values * Locationd can be more too * Give some updater allowance * Just remove updated --- common/manager_helpers.py | 9 ++++----- release/build_devel.sh | 2 +- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/common/manager_helpers.py b/common/manager_helpers.py index e2a88b4f90..5f1c859648 100644 --- a/common/manager_helpers.py +++ b/common/manager_helpers.py @@ -6,28 +6,27 @@ def print_cpu_usage(first_proc, last_proc): r = 0 procs = [ ("selfdrive.controls.controlsd", 59.46), - ("./_modeld", 6.75), + ("./_modeld", 12.74), ("./loggerd", 28.49), ("selfdrive.controls.plannerd", 19.77), ("selfdrive.controls.radard", 9.54), ("./_ui", 9.54), ("./camerad", 7.07), - ("selfdrive.locationd.locationd", 27.46), - ("selfdrive.locationd.paramsd", 10.0), + ("selfdrive.locationd.locationd", 34.38), + ("selfdrive.locationd.paramsd", 11.53), ("./_sensord", 6.17), ("selfdrive.controls.dmonitoringd", 5.48), ("./boardd", 3.63), ("./_dmonitoringmodeld", 2.67), ("selfdrive.logmessaged", 2.71), ("selfdrive.thermald", 2.41), - ("selfdrive.locationd.calibrationd", 1.76), + ("selfdrive.locationd.calibrationd", 6.81), ("./proclogd", 1.54), ("./_gpsd", 0.09), ("./clocksd", 0.02), ("./ubloxd", 0.02), ("selfdrive.tombstoned", 0), ("./logcatd", 0), - ("selfdrive.updated", 0), ] dt = (last_proc.logMonoTime - first_proc.logMonoTime) / 1e9 diff --git a/release/build_devel.sh b/release/build_devel.sh index eb39f77810..c3028d5520 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -109,7 +109,7 @@ echo -n "1" > /data/params/d/HasCompletedSetup echo -n "1" > /data/params/d/CommunityFeaturesToggle PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" nosetests -s selfdrive/test/test_openpilot.py -#PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" GET_CPU_USAGE=1 selfdrive/manager.py +PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" GET_CPU_USAGE=1 selfdrive/manager.py echo "[-] testing panda build T=$SECONDS" pushd panda/board/ From 8fa6846c75a78b79e69f350e1094582acb8e461a Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 2 Jun 2020 15:21:26 -0700 Subject: [PATCH 191/656] bump opendbc + rednose --- opendbc | 2 +- rednose_repo | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/opendbc b/opendbc index daf3bc988f..b875f970fc 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit daf3bc988f91703293784099e57ae78b8d593a8d +Subproject commit b875f970fc6ddad5befe2f6831f4bcda354d8bea diff --git a/rednose_repo b/rednose_repo index 6938fea39b..40f9d48c63 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit 6938fea39b78233eb6b7160ba8dabd7f505274d1 +Subproject commit 40f9d48c63f49e24a1ff56181434af747a503fc2 From 676d0901e5496f3c81d32e2716149544731f688e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 2 Jun 2020 15:41:41 -0700 Subject: [PATCH 192/656] clean up release files --- release/files_common | 3 --- 1 file changed, 3 deletions(-) diff --git a/release/files_common b/release/files_common index cb760dcc8f..2ef07b565e 100644 --- a/release/files_common +++ b/release/files_common @@ -326,7 +326,6 @@ selfdrive/test/longitudinal_maneuvers/*.py selfdrive/test/test_openpilot.py selfdrive/test/test_fingerprints.py selfdrive/test/test_car_models.py -selfdrive/test/openpilotci_upload.py selfdrive/test/process_replay/.gitignore selfdrive/test/process_replay/__init__.py @@ -413,9 +412,7 @@ phonelibs/nanovg/*.h phonelibs/libgralloc/** phonelibs/linux/** phonelibs/opencl/** -phonelibs/curl/* phonelibs/zlib/* -phonelibs/boringssl/* phonelibs/bzip2/* phonelibs/openmax/** From 843a64c72fb94397a1edf814fa66044c8d92acbf Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 2 Jun 2020 16:29:32 -0700 Subject: [PATCH 193/656] Make pylint more strict (#1626) * make pylint more strict * cleanup in progress * done cleaning up * no opendbc --- .pre-commit-config.yaml | 6 +- .pylintrc | 116 +----------------- common/file_helpers.py | 15 ++- common/logging_extra.py | 4 +- common/params.py | 17 ++- common/spinner.py | 6 +- common/text_window.py | 6 +- common/transformations/coordinates.py | 2 +- common/transformations/orientation.py | 10 +- common/url_file.py | 11 +- selfdrive/athena/athenad.py | 34 ++++- selfdrive/athena/test_helpers.py | 9 +- selfdrive/boardd/tests/boardd_old.py | 1 + selfdrive/boardd/tests/test_boardd_api.py | 8 +- selfdrive/car/__init__.py | 13 +- selfdrive/car/chrysler/interface.py | 7 +- selfdrive/car/ford/interface.py | 2 +- selfdrive/car/gm/carcontroller.py | 29 +---- selfdrive/car/gm/interface.py | 2 +- selfdrive/car/honda/interface.py | 7 +- selfdrive/car/hyundai/interface.py | 2 +- selfdrive/car/interfaces.py | 4 +- selfdrive/car/mazda/interface.py | 2 +- selfdrive/car/mock/interface.py | 2 +- selfdrive/car/nissan/interface.py | 2 +- selfdrive/car/subaru/interface.py | 2 +- selfdrive/car/toyota/interface.py | 2 +- selfdrive/car/volkswagen/interface.py | 2 +- selfdrive/controls/lib/events.py | 5 +- selfdrive/controls/lib/vehicle_model.py | 5 +- selfdrive/controls/tests/test_events.py | 11 +- selfdrive/crash.py | 12 +- selfdrive/debug/cpu_usage_stat.py | 23 ++-- .../debug/internal/sensor_test_bootloop.py | 2 +- selfdrive/locationd/locationd.py | 11 +- selfdrive/locationd/models/car_kf.py | 7 +- selfdrive/locationd/models/gnss_kf.py | 8 +- selfdrive/locationd/models/loc_kf.py | 10 +- selfdrive/locationd/test/ephemeris.py | 61 ++++----- .../locationd/test/test_params_learner.py | 2 +- selfdrive/locationd/test/ublox.py | 1 + selfdrive/locationd/test/ubloxd.py | 1 + selfdrive/loggerd/tests/test_deleter.py | 3 - selfdrive/loggerd/tests/test_uploader.py | 3 - selfdrive/loggerd/uploader.py | 2 +- selfdrive/manager.py | 12 +- selfdrive/modeld/runners/keras_runner.py | 10 +- selfdrive/modeld/visiontest.py | 9 +- .../test_longitudinal.py | 80 ++++++------ selfdrive/test/process_replay/compare_logs.py | 11 +- .../test/process_replay/process_replay.py | 7 +- .../test/process_replay/test_processes.py | 6 +- selfdrive/test/profiling/lib.py | 4 +- selfdrive/test/test_car_models.py | 5 +- selfdrive/test/test_openpilot.py | 1 - selfdrive/thermald/power_monitoring.py | 2 +- selfdrive/tombstoned.py | 2 +- selfdrive/updated.py | 2 +- tools/lib/auth.py | 2 +- tools/lib/kbhit.py | 2 +- tools/lib/route_framereader.py | 5 +- tools/replay/camera.py | 2 +- tools/replay/unlogger.py | 10 +- tools/sim/bridge.py | 8 +- tools/sim/lib/manual_ctrl.py | 2 +- 65 files changed, 313 insertions(+), 359 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index e0a1755d10..d65b68b13d 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -10,12 +10,12 @@ repos: rev: master hooks: - id: mypy - exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' + exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(opendbc)|(laika_repo)|(rednose_repo)/' - repo: https://github.com/PyCQA/flake8 rev: master hooks: - id: flake8 - exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' + exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(opendbc)|(laika_repo)|(rednose_repo)/' args: - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E265,E266,E302,E305,E402,E501,E722,E741,W504 - --statistics @@ -27,5 +27,3 @@ repos: language: system types: [python] exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' - args: - - --disable=R,C,W diff --git a/.pylintrc b/.pylintrc index 9a55710c45..be7701c906 100644 --- a/.pylintrc +++ b/.pylintrc @@ -54,121 +54,7 @@ confidence= # --enable=similarities". If you want to run only the classes checker, but have # no Warning level messages displayed, use"--disable=all --enable=classes # --disable=W" -disable=print-statement, - parameter-unpacking, - unpacking-in-except, - old-raise-syntax, - backtick, - long-suffix, - old-ne-operator, - old-octal-literal, - import-star-module-level, - non-ascii-bytes-literal, - raw-checker-failed, - bad-inline-option, - locally-disabled, - locally-enabled, - file-ignored, - suppressed-message, - useless-suppression, - deprecated-pragma, - apply-builtin, - basestring-builtin, - buffer-builtin, - cmp-builtin, - coerce-builtin, - execfile-builtin, - file-builtin, - long-builtin, - raw_input-builtin, - reduce-builtin, - standarderror-builtin, - unicode-builtin, - xrange-builtin, - coerce-method, - delslice-method, - getslice-method, - setslice-method, - no-absolute-import, - old-division, - dict-iter-method, - dict-view-method, - next-method-called, - metaclass-assignment, - indexing-exception, - raising-string, - reload-builtin, - oct-method, - hex-method, - nonzero-method, - cmp-method, - input-builtin, - round-builtin, - intern-builtin, - unichr-builtin, - map-builtin-not-iterating, - zip-builtin-not-iterating, - range-builtin-not-iterating, - filter-builtin-not-iterating, - using-cmp-argument, - eq-without-hash, - div-method, - idiv-method, - rdiv-method, - exception-message-attribute, - invalid-str-codec, - sys-max-int, - bad-python3-import, - deprecated-string-function, - deprecated-str-translate-call, - deprecated-itertools-function, - deprecated-types-field, - next-method-defined, - dict-items-not-iterating, - dict-keys-not-iterating, - dict-values-not-iterating, - bad-indentation, - line-too-long, - missing-docstring, - multiple-statements, - bad-continuation, - invalid-name, - too-many-arguments, - too-many-locals, - superfluous-parens, - bad-whitespace, - too-many-instance-attributes, - wrong-import-position, - ungrouped-imports, - wrong-import-order, - protected-access, - trailing-whitespace, - too-many-branches, - too-few-public-methods, - too-many-statements, - trailing-newlines, - attribute-defined-outside-init, - too-many-return-statements, - too-many-public-methods, - unused-argument, - old-style-class, - no-init, - len-as-condition, - unneeded-not, - no-self-use, - multiple-imports, - no-else-return, - logging-not-lazy, - fixme, - redefined-outer-name, - unused-variable, - unsubscriptable-object, - expression-not-assigned, - too-many-boolean-expressions, - consider-using-ternary, - invalid-unary-operand-type, - relative-import, - deprecated-lambda +disable=C,R,W0613,W0511,W0212,W0201,W0311,W0106,W0603,W0621,W0703,E1136 # Enable the message, report, category or checker with the given id(s). You can diff --git a/common/file_helpers.py b/common/file_helpers.py index 187f0f9ac6..c33ebac6f6 100644 --- a/common/file_helpers.py +++ b/common/file_helpers.py @@ -3,6 +3,7 @@ import shutil import tempfile from atomicwrites import AtomicWriter + def mkdirs_exists_ok(path): try: os.makedirs(path) @@ -10,6 +11,7 @@ def mkdirs_exists_ok(path): if not os.path.isdir(path): raise + def rm_not_exists_ok(path): try: os.remove(path) @@ -17,12 +19,14 @@ def rm_not_exists_ok(path): if os.path.exists(path): raise + def rm_tree_or_link(path): if os.path.islink(path): os.unlink(path) elif os.path.isdir(path): shutil.rmtree(path) + def get_tmpdir_on_same_filesystem(path): normpath = os.path.normpath(path) parts = normpath.split("/") @@ -32,6 +36,7 @@ def get_tmpdir_on_same_filesystem(path): return "/{}/runner/tmp".format(parts[1]) return "/tmp" + class AutoMoveTempdir(): def __init__(self, target_path, temp_dir=None): self._target_path = target_path @@ -47,12 +52,13 @@ class AutoMoveTempdir(): def __enter__(self): return self - def __exit__(self, type, value, traceback): - if type is None: + def __exit__(self, exc_type, exc_value, traceback): + if exc_type is None: self.close() else: shutil.rmtree(self._path) + class NamedTemporaryDir(): def __init__(self, temp_dir=None): self._path = tempfile.mkdtemp(dir=temp_dir) @@ -67,9 +73,10 @@ class NamedTemporaryDir(): def __enter__(self): return self - def __exit__(self, type, value, traceback): + def __exit__(self, exc_type, exc_value, traceback): self.close() + def _get_fileobject_func(writer, temp_dir): def _get_fileobject(): file_obj = writer.get_fileobject(dir=temp_dir) @@ -77,6 +84,7 @@ def _get_fileobject_func(writer, temp_dir): return file_obj return _get_fileobject + def atomic_write_on_fs_tmp(path, **kwargs): """Creates an atomic writer using a temporary file in a temporary directory on the same filesystem as path. @@ -94,6 +102,7 @@ def atomic_write_in_dir(path, **kwargs): writer = AtomicWriter(path, **kwargs) return writer._open(_get_fileobject_func(writer, os.path.dirname(path))) + def atomic_write_in_dir_neos(path, contents, mode=None): """ Atomically writes contents to path using a temporary file in the same directory diff --git a/common/logging_extra.py b/common/logging_extra.py index 2c49561fb9..7d9bcd7b6e 100644 --- a/common/logging_extra.py +++ b/common/logging_extra.py @@ -143,7 +143,9 @@ class SwagLogger(logging.Logger): while hasattr(f, "f_code"): co = f.f_code filename = os.path.normcase(co.co_filename) - if filename == _srcfile: + + # TODO: is this pylint exception correct? + if filename == _srcfile: # pylint: disable=comparison-with-callable f = f.f_back continue sinfo = None diff --git a/common/params.py b/common/params.py index b92f17ca26..ddaf56ae51 100755 --- a/common/params.py +++ b/common/params.py @@ -30,6 +30,7 @@ import threading from enum import Enum from common.basedir import PARAMS + def mkdirs_exists_ok(path): try: os.makedirs(path) @@ -143,6 +144,10 @@ class DBAccessor(): def get(self, key): self._check_entered() + + if self._vals is None: + return None + try: return self._vals[key] except KeyError: @@ -195,7 +200,7 @@ class DBReader(DBAccessor): finally: lock.release() - def __exit__(self, type, value, traceback): + def __exit__(self, exc_type, exc_value, traceback): pass @@ -221,14 +226,14 @@ class DBWriter(DBAccessor): os.chmod(self._path, 0o777) self._lock = self._get_lock(True) self._vals = self._read_values_locked() - except: + except Exception: os.umask(self._prev_umask) self._prev_umask = None raise return self - def __exit__(self, type, value, traceback): + def __exit__(self, exc_type, exc_value, traceback): self._check_entered() try: @@ -302,12 +307,13 @@ def read_db(params_path, key): except IOError: return None + def write_db(params_path, key, value): if isinstance(value, str): value = value.encode('utf8') prev_umask = os.umask(0) - lock = FileLock(params_path+"/.lock", True) + lock = FileLock(params_path + "/.lock", True) lock.acquire() try: @@ -324,12 +330,13 @@ def write_db(params_path, key, value): os.umask(prev_umask) lock.release() + class Params(): def __init__(self, db=PARAMS): self.db = db # create the database if it doesn't exist... - if not os.path.exists(self.db+"/d"): + if not os.path.exists(self.db + "/d"): with self.transaction(write=True): pass diff --git a/common/spinner.py b/common/spinner.py index 370d54c815..c49b124c98 100644 --- a/common/spinner.py +++ b/common/spinner.py @@ -36,12 +36,12 @@ class Spinner(): def __del__(self): self.close() - def __exit__(self, type, value, traceback): + def __exit__(self, exc_type, exc_value, traceback): self.close() class FakeSpinner(Spinner): - def __init__(self): + def __init__(self): # pylint: disable=super-init-not-called pass def __enter__(self): @@ -53,7 +53,7 @@ class FakeSpinner(Spinner): def close(self): pass - def __exit__(self, type, value, traceback): + def __exit__(self, exc_type, exc_value, traceback): pass diff --git a/common/text_window.py b/common/text_window.py index 7bcad25094..88da8e53f5 100755 --- a/common/text_window.py +++ b/common/text_window.py @@ -39,12 +39,12 @@ class TextWindow(): def __del__(self): self.close() - def __exit__(self, type, value, traceback): + def __exit__(self, exc_type, exc_value, traceback): self.close() class FakeTextWindow(TextWindow): - def __init__(self, s): + def __init__(self, s): # pylint: disable=super-init-not-called pass def get_status(self): @@ -62,7 +62,7 @@ class FakeTextWindow(TextWindow): def close(self): pass - def __exit__(self, type, value, traceback): + def __exit__(self, exc_type, exc_value, traceback): pass diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index 4f8445145c..e39ad697aa 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -1,8 +1,8 @@ -import numpy as np """ Coordinate transformation module. All methods accept arrays as input with each row as a position. """ +import numpy as np a = 6378137 diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py index f594f05678..e6161ea28d 100644 --- a/common/transformations/orientation.py +++ b/common/transformations/orientation.py @@ -1,8 +1,3 @@ -import numpy as np -from numpy import dot, inner, array, linalg -from common.transformations.coordinates import LocalCoord - - ''' Vectorized functions that transform between rotation matrices, euler angles and quaternions. @@ -10,6 +5,11 @@ All support lists, array or array of arrays as inputs. Supports both x2y and y_from_x format (y_from_x preferred!). ''' +import numpy as np +from numpy import dot, inner, array, linalg +from common.transformations.coordinates import LocalCoord + + def euler2quat(eulers): eulers = array(eulers) if len(eulers.shape) > 1: diff --git a/common/url_file.py b/common/url_file.py index 343e7537be..38637d90cc 100644 --- a/common/url_file.py +++ b/common/url_file.py @@ -9,6 +9,7 @@ import pycurl from io import BytesIO from tenacity import retry, wait_random_exponential, stop_after_attempt + class URLFile(object): _tlocal = threading.local() @@ -26,7 +27,7 @@ class URLFile(object): def __enter__(self): return self - def __exit__(self, type, value, traceback): + def __exit__(self, exc_type, exc_value, traceback): if self._local_file is not None: os.remove(self._local_file.name) self._local_file.close() @@ -37,7 +38,7 @@ class URLFile(object): if ll is None: trange = 'bytes=%d-' % self._pos else: - trange = 'bytes=%d-%d' % (self._pos, self._pos+ll-1) + trange = 'bytes=%d-%d' % (self._pos, self._pos + ll - 1) dats = BytesIO() c = self._curl @@ -68,8 +69,8 @@ class URLFile(object): if self._debug: t2 = time.time() - if t2-t1 > 0.1: - print("get %s %r %.f slow" % (self._url, trange, t2-t1)) + if t2 - t1 > 0.1: + print("get %s %r %.f slow" % (self._url, trange, t2 - t1)) response_code = c.getinfo(pycurl.RESPONSE_CODE) if response_code == 416: # Requested Range Not Satisfiable @@ -96,7 +97,7 @@ class URLFile(object): try: os.write(local_fd, self.read()) local_file = open(local_path, "rb") - except: + except Exception: os.remove(local_path) raise finally: diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index cbebb08e56..72e81a58bb 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -29,7 +29,7 @@ from selfdrive.loggerd.config import ROOT from selfdrive.swaglog import cloudlog ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') -HANDLER_THREADS = os.getenv('HANDLER_THREADS', 4) +HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4")) LOCAL_PORT_WHITELIST = set([8022]) dispatcher["echo"] = lambda s: s @@ -39,6 +39,7 @@ upload_queue: Any = queue.Queue() cancelled_uploads: Any = set() UploadItem = namedtuple('UploadItem', ['path', 'url', 'headers', 'created_at', 'id']) + def handle_long_poll(ws): end_event = threading.Event() @@ -60,9 +61,10 @@ def handle_long_poll(ws): end_event.set() raise finally: - for i, thread in enumerate(threads): + for thread in threads: thread.join() + def jsonrpc_handler(end_event): dispatcher["startLocalProxy"] = partial(startLocalProxy, end_event) while not end_event.is_set(): @@ -76,6 +78,7 @@ def jsonrpc_handler(end_event): cloudlog.exception("athena jsonrpc handler failed") response_queue.put_nowait(json.dumps({"error": str(e)})) + def upload_handler(end_event): while not end_event.is_set(): try: @@ -89,6 +92,7 @@ def upload_handler(end_event): except Exception: cloudlog.exception("athena.upload_handler.exception") + def _do_upload(upload_item): with open(upload_item.path, "rb") as f: size = os.fstat(f.fileno()).st_size @@ -97,6 +101,7 @@ def _do_upload(upload_item): headers={**upload_item.headers, 'Content-Length': str(size)}, timeout=10) + # security: user should be able to request any message from their car @dispatcher.add_method def getMessage(service=None, timeout=1000): @@ -111,11 +116,13 @@ def getMessage(service=None, timeout=1000): return ret.to_dict() + @dispatcher.add_method def listDataDirectory(): files = [os.path.relpath(os.path.join(dp, f), ROOT) for dp, dn, fn in os.walk(ROOT) for f in fn] return files + @dispatcher.add_method def reboot(): thermal_sock = messaging.sub_sock("thermal", timeout=1000) @@ -131,6 +138,7 @@ def reboot(): return {"success": 1} + @dispatcher.add_method def uploadFileToUrl(fn, url, headers): if len(fn) == 0 or fn[0] == '/' or '..' in fn: @@ -139,7 +147,7 @@ def uploadFileToUrl(fn, url, headers): if not os.path.exists(path): return 404 - item = UploadItem(path=path, url=url, headers=headers, created_at=int(time.time()*1000), id=None) + item = UploadItem(path=path, url=url, headers=headers, created_at=int(time.time() * 1000), id=None) upload_id = hashlib.sha1(str(item).encode()).hexdigest() item = item._replace(id=upload_id) @@ -147,10 +155,12 @@ def uploadFileToUrl(fn, url, headers): return {"enqueued": 1, "item": item._asdict()} + @dispatcher.add_method def listUploadQueue(): return [item._asdict() for item in list(upload_queue.queue)] + @dispatcher.add_method def cancelUpload(upload_id): upload_ids = set(item.id for item in list(upload_queue.queue)) @@ -160,6 +170,7 @@ def cancelUpload(upload_id): cancelled_uploads.add(upload_id) return {"success": 1} + def startLocalProxy(global_end_event, remote_ws_uri, local_port): try: if local_port not in LOCAL_PORT_WHITELIST: @@ -190,18 +201,21 @@ def startLocalProxy(global_end_event, remote_ws_uri, local_port): cloudlog.exception("athenad.startLocalProxy.exception") raise e + @dispatcher.add_method def getPublicKey(): - if not os.path.isfile(PERSIST+'/comma/id_rsa.pub'): + if not os.path.isfile(PERSIST + '/comma/id_rsa.pub'): return None - with open(PERSIST+'/comma/id_rsa.pub', 'r') as f: + with open(PERSIST + '/comma/id_rsa.pub', 'r') as f: return f.read() + @dispatcher.add_method def getSshAuthorizedKeys(): return Params().get("GithubSshKeys", encoding='utf8') or '' + @dispatcher.add_method def getSimInfo(): sim_state = android.getprop("gsm.sim.state").split(",") @@ -220,6 +234,7 @@ def getSimInfo(): 'data_connected': cell_data_connected } + @dispatcher.add_method def takeSnapshot(): from selfdrive.camerad.snapshot.snapshot import snapshot, jpeg_write @@ -237,6 +252,7 @@ def takeSnapshot(): else: raise Exception("not available while camerad is started") + def ws_proxy_recv(ws, local_sock, ssock, end_event, global_end_event): while not (end_event.is_set() or global_end_event.is_set()): try: @@ -252,6 +268,7 @@ def ws_proxy_recv(ws, local_sock, ssock, end_event, global_end_event): local_sock.close() end_event.set() + def ws_proxy_send(ws, local_sock, signal_sock, end_event): while not end_event.is_set(): try: @@ -272,6 +289,7 @@ def ws_proxy_send(ws, local_sock, signal_sock, end_event): cloudlog.exception("athenad.ws_proxy_send.exception") end_event.set() + def ws_recv(ws, end_event): while not end_event.is_set(): try: @@ -281,13 +299,14 @@ def ws_recv(ws, end_event): data = data.decode("utf-8") payload_queue.put_nowait(data) elif opcode == ABNF.OPCODE_PING: - Params().put("LastAthenaPingTime", str(int(sec_since_boot()*1e9))) + Params().put("LastAthenaPingTime", str(int(sec_since_boot() * 1e9))) except WebSocketTimeoutException: pass except Exception: cloudlog.exception("athenad.ws_recv.exception") end_event.set() + def ws_send(ws, end_event): while not end_event.is_set(): try: @@ -299,9 +318,11 @@ def ws_send(ws, end_event): cloudlog.exception("athenad.ws_send.exception") end_event.set() + def backoff(retries): return random.randrange(0, min(128, int(2 ** retries))) + def main(): params = Params() dongle_id = params.get("DongleId").decode('utf-8') @@ -328,5 +349,6 @@ def main(): time.sleep(backoff(conn_retries)) + if __name__ == "__main__": main() diff --git a/selfdrive/athena/test_helpers.py b/selfdrive/athena/test_helpers.py index 2335ce89c5..2919de6637 100644 --- a/selfdrive/athena/test_helpers.py +++ b/selfdrive/athena/test_helpers.py @@ -8,6 +8,7 @@ import time from functools import wraps from multiprocessing import Process + class EchoSocket(): def __init__(self, port): self.socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) @@ -15,7 +16,7 @@ class EchoSocket(): self.socket.listen(1) def run(self): - conn, client_address = self.socket.accept() + conn, _ = self.socket.accept() conn.settimeout(5.0) try: @@ -32,6 +33,7 @@ class EchoSocket(): self.socket.shutdown(0) self.socket.close() + class MockApi(): def __init__(self, dongle_id): pass @@ -39,6 +41,7 @@ class MockApi(): def get_token(self): return "fake-token" + class MockParams(): def __init__(self): self.params = { @@ -52,6 +55,7 @@ class MockParams(): ret = ret.decode(encoding) return ret + class MockWebsocket(): def __init__(self, recv_queue, send_queue): self.recv_queue = recv_queue @@ -66,6 +70,7 @@ class MockWebsocket(): def send(self, data, opcode): self.send_queue.put_nowait((data, opcode)) + class HTTPRequestHandler(http.server.SimpleHTTPRequestHandler): def do_PUT(self): length = int(self.headers['Content-Length']) @@ -73,6 +78,7 @@ class HTTPRequestHandler(http.server.SimpleHTTPRequestHandler): self.send_response(201, "Created") self.end_headers() + def http_server(port_queue, **kwargs): while 1: try: @@ -83,6 +89,7 @@ def http_server(port_queue, **kwargs): if e.errno == 98: continue + def with_http_server(func): @wraps(func) def inner(*args, **kwargs): diff --git a/selfdrive/boardd/tests/boardd_old.py b/selfdrive/boardd/tests/boardd_old.py index 4c62e94883..87e579023d 100755 --- a/selfdrive/boardd/tests/boardd_old.py +++ b/selfdrive/boardd/tests/boardd_old.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +# pylint: skip-file # This file is not used by OpenPilot. Only boardd.cc is used. # The python version is slower, but has more options for development. diff --git a/selfdrive/boardd/tests/test_boardd_api.py b/selfdrive/boardd/tests/test_boardd_api.py index f41e1e3571..9386c7845e 100644 --- a/selfdrive/boardd/tests/test_boardd_api.py +++ b/selfdrive/boardd/tests/test_boardd_api.py @@ -12,7 +12,7 @@ import unittest def generate_random_can_data_list(): can_list = [] cnt = random.randint(1, 64) - for j in range(cnt): + for _ in range(cnt): can_data = np.random.bytes(random.randint(1, 8)) can_list.append([random.randint(0, 128), random.randint(0, 128), can_data, random.randint(0, 128)]) return can_list, cnt @@ -54,18 +54,18 @@ class TestBoarddApiMethods(unittest.TestCase): self.assertEqual(getattr(ev.can[i], attr, 'new'), getattr(ev_old.can[i], attr, 'old')) def test_performance(self): - can_list, cnt = generate_random_can_data_list() + can_list, _ = generate_random_can_data_list() recursions = 1000 n1 = sec_since_boot() - for i in range(recursions): + for _ in range(recursions): boardd_old.can_list_to_can_capnp(can_list, 'sendcan').to_bytes() n2 = sec_since_boot() elapsed_old = n2 - n1 # print('Old API, elapsed time: {} secs'.format(elapsed_old)) n1 = sec_since_boot() - for i in range(recursions): + for _ in range(recursions): boardd.can_list_to_can_capnp(can_list) n2 = sec_since_boot() elapsed_new = n2 - n1 diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 1d579543a6..09edb03156 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -4,9 +4,11 @@ from common.numpy_fast import clip # kg of standard extra cargo to count for drive, gas, etc... STD_CARGO_KG = 136. + def gen_empty_fingerprint(): return {i: {} for i in range(0, 4)} + # FIXME: hardcoding honda civic 2016 touring params so they can be used to # scale unknown params for other cars class CivicParams: @@ -18,11 +20,13 @@ class CivicParams: TIRE_STIFFNESS_FRONT = 192150 TIRE_STIFFNESS_REAR = 202500 + # TODO: get actual value, for now starting with reasonable value for # civic and scaling by mass and wheelbase def scale_rot_inertia(mass, wheelbase): return CivicParams.ROTATIONAL_INERTIA * mass * wheelbase ** 2 / (CivicParams.MASS * CivicParams.WHEELBASE ** 2) + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by # mass and CG position, so all cars will have approximately similar dyn behaviors def scale_tire_stiffness(mass, wheelbase, center_to_front, tire_stiffness_factor=1.0): @@ -35,6 +39,7 @@ def scale_tire_stiffness(mass, wheelbase, center_to_front, tire_stiffness_factor return tire_stiffness_front, tire_stiffness_rear + def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None): return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc} @@ -51,10 +56,10 @@ def apply_std_steer_torque_limits(apply_torque, apply_torque_last, driver_torque # slow rate if steer torque increases in magnitude if apply_torque_last > 0: apply_torque = clip(apply_torque, max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP), - apply_torque_last + LIMITS.STEER_DELTA_UP) + apply_torque_last + LIMITS.STEER_DELTA_UP) else: apply_torque = clip(apply_torque, apply_torque_last - LIMITS.STEER_DELTA_UP, - min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP)) + min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP)) return int(round(float(apply_torque))) @@ -83,9 +88,9 @@ def crc8_pedal(data): crc = 0xFF # standard init value poly = 0xD5 # standard crc8: x8+x7+x6+x4+x2+1 size = len(data) - for i in range(size-1, -1, -1): + for i in range(size - 1, -1, -1): crc ^= data[i] - for j in range(8): + for _ in range(8): if ((crc & 0x80) != 0): crc = ((crc << 1) ^ poly) & 0xFF else: diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 85ad43af14..294b96c5ea 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -11,7 +11,12 @@ class CarInterface(CarInterfaceBase): return float(accel) / 3.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=None, has_relay=False, car_fw=None): + if fingerprint is None: + fingerprint = gen_empty_fingerprint() + if car_fw is None: + car_fw = [] + ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "chrysler" ret.safetyModel = car.CarParams.SafetyModel.chrysler diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index 0c1ce863c5..59e6191420 100755 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -14,7 +14,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 3.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "ford" ret.safetyModel = car.CarParams.SafetyModel.ford diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index c304081c0a..2018d73306 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -38,24 +38,8 @@ class CarControllerParams(): self.BRAKE_LOOKUP_V = [MAX_BRAKE, 0] -def actuator_hystereses(final_pedal, pedal_steady): - # hyst params... TODO: move these to VehicleParams - pedal_hyst_gap = 0.01 # don't change pedal command for small oscillations within this value - - # for small pedal oscillations within pedal_hyst_gap, don't change the pedal command - if final_pedal == 0.: - pedal_steady = 0. - elif final_pedal > pedal_steady + pedal_hyst_gap: - pedal_steady = final_pedal - pedal_hyst_gap - elif final_pedal < pedal_steady - pedal_hyst_gap: - pedal_steady = final_pedal + pedal_hyst_gap - final_pedal = pedal_steady - - return final_pedal, pedal_steady - class CarController(): def __init__(self, dbc_name, CP, VM): - self.pedal_steady = 0. self.start_time = 0. self.apply_steer_last = 0 self.lka_icon_status_last = (False, False) @@ -79,8 +63,7 @@ class CarController(): if hud_alert == VisualAlert.fcw: self.fcw_frames = 100 - ### STEER ### - + # STEER if (frame % P.STEER_STEP) == 0: lkas_enabled = enabled and not CS.out.steerWarning and CS.out.vEgo > P.MIN_STEER_SPEED if lkas_enabled: @@ -93,19 +76,13 @@ class CarController(): self.apply_steer_last = apply_steer idx = (frame // P.STEER_STEP) % 4 - can_sends.append(gmcan.create_steering_control(self.packer_pt, - CanBus.POWERTRAIN, apply_steer, idx, lkas_enabled)) - - ### GAS/BRAKE ### + can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, lkas_enabled)) + # GAS/BRAKE # no output if not enabled, but keep sending keepalive messages # treat pedals as one final_pedal = actuators.gas - actuators.brake - # *** apply pedal hysteresis *** - final_brake, self.brake_steady = actuator_hystereses( - final_pedal, self.pedal_steady) - if not enabled: # Stock ECU sends max regen when not enabled. apply_gas = P.MAX_ACC_REGEN diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 4dffa73c2b..6dda4f3a0a 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -16,7 +16,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "gm" ret.safetyModel = car.CarParams.SafetyModel.gm # default to gm diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index b18252d579..aa315afd52 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -82,6 +82,10 @@ class CarInterface(CarInterfaceBase): else: self.compute_gb = compute_gb_honda + @staticmethod + def compute_gb(accel, speed): + raise NotImplementedError + @staticmethod def calc_accel_override(a_ego, a_target, v_ego, v_target): @@ -115,8 +119,7 @@ class CarInterface(CarInterfaceBase): return float(max(max_accel, a_target / A_ACC_MAX)) * min(speedLimiter, accelLimiter) @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): - + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "honda" diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 5b28d573b1..c38f54923d 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -12,7 +12,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 3.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "hyundai" diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index a72024a138..db6b75319a 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -41,7 +41,7 @@ class CarInterfaceBase(): raise NotImplementedError @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value raise NotImplementedError # returns a set of default params to avoid repetition in car specific params @@ -84,7 +84,7 @@ class CarInterfaceBase(): def apply(self, c): raise NotImplementedError - def create_common_events(self, cs_out, extra_gears=[], gas_resume_speed=-1, pcm_enable=True): + def create_common_events(self, cs_out, extra_gears=[], gas_resume_speed=-1, pcm_enable=True): # pylint: disable=dangerous-default-value events = Events() if cs_out.doorOpen: diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 2cd286b6ed..037b84e107 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -15,7 +15,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "mazda" diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index b0474f8ce8..617f7e23d2 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -33,7 +33,7 @@ class CarInterface(CarInterfaceBase): return accel @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "mock" ret.safetyModel = car.CarParams.SafetyModel.noOutput diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index ebcfd573e7..cc9547aedd 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -14,7 +14,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "nissan" diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index 328666d79c..a0cfdd0102 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -11,7 +11,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "subaru" diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 93bed7e989..9b9b46cf39 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -14,7 +14,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 3.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "toyota" diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 3632b7b0c9..3ec4b07000 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -19,7 +19,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) # VW port is a community feature, since we don't own one to test diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 2b21cd7171..413a402407 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -59,7 +59,10 @@ class Events: return True return False - def create_alerts(self, event_types, callback_args=[]): + def create_alerts(self, event_types, callback_args=None): + if callback_args is None: + callback_args = [] + ret = [] for e in self.events: types = EVENTS[e].keys() diff --git a/selfdrive/controls/lib/vehicle_model.py b/selfdrive/controls/lib/vehicle_model.py index 9959f82dc8..85acca54d9 100755 --- a/selfdrive/controls/lib/vehicle_model.py +++ b/selfdrive/controls/lib/vehicle_model.py @@ -1,7 +1,4 @@ #!/usr/bin/env python3 -import numpy as np -from numpy.linalg import solve - """ Dynamic bycicle model from "The Science of Vehicle Dynamics (2014), M. Guiggiani" @@ -15,6 +12,8 @@ x_dot = A*x + B*u A depends on longitudinal speed, u [m/s], and vehicle parameters CP """ +import numpy as np +from numpy.linalg import solve def create_dyn_state_matrices(u, VM): diff --git a/selfdrive/controls/tests/test_events.py b/selfdrive/controls/tests/test_events.py index 3c5bc9d34b..ef41eea91e 100755 --- a/selfdrive/controls/tests/test_events.py +++ b/selfdrive/controls/tests/test_events.py @@ -9,8 +9,8 @@ from selfdrive.controls.lib.events import Alert, EVENTS AlertSize = log.ControlsState.AlertSize -class TestAlerts(unittest.TestCase): +class TestAlerts(unittest.TestCase): def test_events_defined(self): # Ensure all events in capnp schema are defined in events.py events = car.CarEvent.EventName.schema.enumerants @@ -34,9 +34,9 @@ class TestAlerts(unittest.TestCase): draw = ImageDraw.Draw(Image.new('RGB', (0, 0))) fonts = { - AlertSize.small: [ImageFont.truetype(semibold_font_path, int(40*font_scale_factor))], - AlertSize.mid: [ImageFont.truetype(bold_font_path, int(48*font_scale_factor)), - ImageFont.truetype(regular_font_path, int(36*font_scale_factor))], + AlertSize.small: [ImageFont.truetype(semibold_font_path, int(40 * font_scale_factor))], + AlertSize.mid: [ImageFont.truetype(bold_font_path, int(48 * font_scale_factor)), + ImageFont.truetype(regular_font_path, int(36 * font_scale_factor))], } alerts = [] @@ -56,9 +56,10 @@ class TestAlerts(unittest.TestCase): break font = fonts[alert.alert_size][i] - w, h = draw.textsize(txt, font) + w, _ = draw.textsize(txt, font) msg = "type: %s msg: %s" % (alert.alert_type, txt) self.assertLessEqual(w, max_text_width, msg=msg) + if __name__ == "__main__": unittest.main() diff --git a/selfdrive/crash.py b/selfdrive/crash.py index a24466622e..7459f71668 100644 --- a/selfdrive/crash.py +++ b/selfdrive/crash.py @@ -39,6 +39,12 @@ else: client.extra_context(kwargs) def install(): + """ + Workaround for `sys.excepthook` thread bug from: + http://bugs.python.org/issue1230540 + Call once from the main thread before creating any threads. + Source: https://stackoverflow.com/a/31622038 + """ # installs a sys.excepthook __excepthook__ = sys.excepthook @@ -48,12 +54,6 @@ else: __excepthook__(*exc_info) sys.excepthook = handle_exception - """ - Workaround for `sys.excepthook` thread bug from: - http://bugs.python.org/issue1230540 - Call once from the main thread before creating any threads. - Source: https://stackoverflow.com/a/31622038 - """ init_original = threading.Thread.__init__ def init(self, *args, **kwargs): diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index b18199885e..50307c228c 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -1,14 +1,5 @@ #!/usr/bin/env python3 # type: ignore -import psutil -import time -import os -import sys -import numpy as np -import argparse -import re -from collections import defaultdict - ''' System tools like top/htop can only show current cpu usage values, so I write this script to do statistics jobs. Features: @@ -24,18 +15,28 @@ System tools like top/htop can only show current cpu usage values, so I write th boardd: 1.96%, min: 1.96%, max: 1.96%, acc: 1.96% ubloxd.py: 0.39%, min: 0.39%, max: 0.39%, acc: 0.39% ''' +import psutil +import time +import os +import sys +import numpy as np +import argparse +import re +from collections import defaultdict + # Do statistics every 5 seconds PRINT_INTERVAL = 5 SLEEP_INTERVAL = 0.2 monitored_proc_names = [ - 'ubloxd', 'thermald', 'uploader', 'deleter', 'controlsd', 'plannerd', 'radard', 'mapd', 'loggerd' , 'logmessaged', 'tombstoned', - 'logcatd', 'proclogd', 'boardd', 'pandad', './ui', 'ui', 'calibrationd', 'params_learner', 'modeld', 'dmonitoringmodeld', 'camerad', 'sensord', 'updated', 'gpsd', 'athena'] + 'ubloxd', 'thermald', 'uploader', 'deleter', 'controlsd', 'plannerd', 'radard', 'mapd', 'loggerd', 'logmessaged', 'tombstoned', + 'logcatd', 'proclogd', 'boardd', 'pandad', './ui', 'ui', 'calibrationd', 'params_learner', 'modeld', 'dmonitoringmodeld', 'camerad', 'sensord', 'updated', 'gpsd', 'athena'] cpu_time_names = ['user', 'system', 'children_user', 'children_system'] timer = getattr(time, 'monotonic', time.time) + def get_arg_parser(): parser = argparse.ArgumentParser( description="Unlogger and UI", diff --git a/selfdrive/debug/internal/sensor_test_bootloop.py b/selfdrive/debug/internal/sensor_test_bootloop.py index 5d0208d298..9e89add6bb 100755 --- a/selfdrive/debug/internal/sensor_test_bootloop.py +++ b/selfdrive/debug/internal/sensor_test_bootloop.py @@ -32,7 +32,7 @@ except Exception: sys.exit(-1) sensord_env = {**os.environ, 'SENSOR_TEST': '1'} -process = subprocess.run("./sensord", cwd="/data/openpilot/selfdrive/sensord", env=sensord_env) +process = subprocess.run("./sensord", cwd="/data/openpilot/selfdrive/sensord", env=sensord_env) # pylint: disable=subprocess-run-check if process.returncode == 40: text = "Current run: SUCCESS\n" diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 3798b3a456..959684e1b6 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -47,7 +47,10 @@ def get_H(): class Localizer(): - def __init__(self, disabled_logs=[], dog=None): + def __init__(self, disabled_logs=None, dog=None): + if disabled_logs is None: + disabled_logs = [] + self.kf = LiveKalman(GENERATED_DIR) self.reset_kalman() self.max_age = .2 # seconds @@ -279,7 +282,11 @@ class Localizer(): self.speed_counter = 0 self.cam_counter = 0 -def locationd_thread(sm, pm, disabled_logs=[]): + +def locationd_thread(sm, pm, disabled_logs=None): + if disabled_logs is None: + disabled_logs = [] + if sm is None: socks = ['gpsLocationExternal', 'sensorEvents', 'cameraOdometry', 'liveCalibration', 'carState'] sm = messaging.SubMaster(socks, ignore_alive=['gpsLocationExternal']) diff --git a/selfdrive/locationd/models/car_kf.py b/selfdrive/locationd/models/car_kf.py index dda5cea1b2..ee409ecebc 100755 --- a/selfdrive/locationd/models/car_kf.py +++ b/selfdrive/locationd/models/car_kf.py @@ -12,6 +12,7 @@ from selfdrive.locationd.models.constants import ObservationKind i = 0 + def _slice(n): global i s = slice(i, i + n) @@ -48,7 +49,7 @@ class CarKalman(KalmanFilter): # process noise Q = np.diag([ - (.05/100)**2, + (.05 / 100)**2, .01**2, math.radians(0.02)**2, math.radians(0.25)**2, @@ -59,7 +60,7 @@ class CarKalman(KalmanFilter): ]) P_initial = Q.copy() - obs_noise : Dict[int, Any] = { + obs_noise: Dict[int, Any] = { ObservationKind.STEER_ANGLE: np.atleast_2d(math.radians(0.01)**2), ObservationKind.ANGLE_OFFSET_FAST: np.atleast_2d(math.radians(10.0)**2), ObservationKind.STEER_RATIO: np.atleast_2d(5.0**2), @@ -138,7 +139,7 @@ class CarKalman(KalmanFilter): gen_code(generated_dir, name, f_sym, dt, state_sym, obs_eqs, dim_state, dim_state, global_vars=CarKalman.global_vars) - def __init__(self, generated_dir, steer_ratio=15, stiffness_factor=1, angle_offset=0): + def __init__(self, generated_dir, steer_ratio=15, stiffness_factor=1, angle_offset=0): # pylint: disable=super-init-not-called dim_state = self.initial_x.shape[0] dim_state_err = self.P_initial.shape[0] x_init = self.initial_x diff --git a/selfdrive/locationd/models/gnss_kf.py b/selfdrive/locationd/models/gnss_kf.py index 59c3877e44..db1a7e81a5 100755 --- a/selfdrive/locationd/models/gnss_kf.py +++ b/selfdrive/locationd/models/gnss_kf.py @@ -76,14 +76,14 @@ class GNSSKalman(): # extra args sat_pos_freq_sym = sp.MatrixSymbol('sat_pos', 4, 1) sat_pos_vel_sym = sp.MatrixSymbol('sat_pos_vel', 6, 1) - sat_los_sym = sp.MatrixSymbol('sat_los', 3, 1) - orb_epos_sym = sp.MatrixSymbol('orb_epos_sym', 3, 1) + # sat_los_sym = sp.MatrixSymbol('sat_los', 3, 1) + # orb_epos_sym = sp.MatrixSymbol('orb_epos_sym', 3, 1) # expand extra args sat_x, sat_y, sat_z, glonass_freq = sat_pos_freq_sym sat_vx, sat_vy, sat_vz = sat_pos_vel_sym[3:] - los_x, los_y, los_z = sat_los_sym - orb_x, orb_y, orb_z = orb_epos_sym + # los_x, los_y, los_z = sat_los_sym + # orb_x, orb_y, orb_z = orb_epos_sym h_pseudorange_sym = sp.Matrix([ sp.sqrt( diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index 9b1329511d..421b0a64f9 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -252,13 +252,13 @@ class LocKalman(): # extra args sat_pos_freq_sym = sp.MatrixSymbol('sat_pos', 4, 1) sat_pos_vel_sym = sp.MatrixSymbol('sat_pos_vel', 6, 1) - sat_los_sym = sp.MatrixSymbol('sat_los', 3, 1) + # sat_los_sym = sp.MatrixSymbol('sat_los', 3, 1) orb_epos_sym = sp.MatrixSymbol('orb_epos_sym', 3, 1) # expand extra args sat_x, sat_y, sat_z, glonass_freq = sat_pos_freq_sym sat_vx, sat_vy, sat_vz = sat_pos_vel_sym[3:] - los_x, los_y, los_z = sat_los_sym + # los_x, los_y, los_z = sat_los_sym orb_x, orb_y, orb_z = orb_epos_sym h_pseudorange_sym = sp.Matrix([ @@ -377,7 +377,7 @@ class LocKalman(): self.dim_state_err = self.dim_main_err + self.dim_augment_err * self.N if self.N > 0: - x_initial, P_initial, Q = self.pad_augmented(self.x_initial, self.P_initial, self.Q) + x_initial, P_initial, Q = self.pad_augmented(self.x_initial, self.P_initial, self.Q) # pylint: disable=unbalanced-tuple-unpacking self.computer = LstSqComputer(generated_dir, N) self.max_tracks = max_tracks @@ -569,14 +569,14 @@ class LocKalman(): def maha_test_pseudorange(self, x, P, meas, kind, maha_thresh=.3): bools = [] - for i, m in enumerate(meas): + for m in meas: z, R, sat_pos_freq = parse_pr(m) bools.append(self.filter.maha_test(x, P, kind, z, R, extra_args=sat_pos_freq, maha_thresh=maha_thresh)) return np.array(bools) def maha_test_pseudorange_rate(self, x, P, meas, kind, maha_thresh=.999): bools = [] - for i, m in enumerate(meas): + for m in meas: z, R, sat_pos_vel = parse_prr(m) bools.append(self.filter.maha_test(x, P, kind, z, R, extra_args=sat_pos_vel, maha_thresh=maha_thresh)) return np.array(bools) diff --git a/selfdrive/locationd/test/ephemeris.py b/selfdrive/locationd/test/ephemeris.py index bca45c59e8..2793e3c62a 100644 --- a/selfdrive/locationd/test/ephemeris.py +++ b/selfdrive/locationd/test/ephemeris.py @@ -1,3 +1,5 @@ +import math + def GET_FIELD_U(w, nb, pos): return (((w) >> (pos)) & ((1 << (nb)) - 1)) @@ -35,7 +37,6 @@ on of this parser ''' def __init__(self, svId, subframes): - from math import pow self.svId = svId week_no = GET_FIELD_U(subframes[1][2+0], 10, 20) # code_on_l2 = GET_FIELD_U(subframes[1][0], 2, 12) @@ -84,30 +85,30 @@ on of this parser gpsPi = 3.1415926535898 # now form variables in radians, meters and seconds etc - self.Tgd = t_gd * pow(2, -31) - self.A = pow(a_powhalf * pow(2, -19), 2.0) - self.cic = c_ic * pow(2, -29) - self.cis = c_is * pow(2, -29) - self.crc = c_rc * pow(2, -5) - self.crs = c_rs * pow(2, -5) - self.cuc = c_uc * pow(2, -29) - self.cus = c_us * pow(2, -29) - self.deltaN = delta_n * pow(2, -43) * gpsPi - self.ecc = e * pow(2, -33) - self.i0 = i_0 * pow(2, -31) * gpsPi - self.idot = idot * pow(2, -43) * gpsPi - self.M0 = m_0 * pow(2, -31) * gpsPi - self.omega = w * pow(2, -31) * gpsPi - self.omega_dot = omega_dot * pow(2, -43) * gpsPi - self.omega0 = omega_0 * pow(2, -31) * gpsPi - self.toe = t_oe * pow(2, 4) + self.Tgd = t_gd * math.pow(2, -31) + self.A = math.pow(a_powhalf * math.pow(2, -19), 2.0) + self.cic = c_ic * math.pow(2, -29) + self.cis = c_is * math.pow(2, -29) + self.crc = c_rc * math.pow(2, -5) + self.crs = c_rs * math.pow(2, -5) + self.cuc = c_uc * math.pow(2, -29) + self.cus = c_us * math.pow(2, -29) + self.deltaN = delta_n * math.pow(2, -43) * gpsPi + self.ecc = e * math.pow(2, -33) + self.i0 = i_0 * math.pow(2, -31) * gpsPi + self.idot = idot * math.pow(2, -43) * gpsPi + self.M0 = m_0 * math.pow(2, -31) * gpsPi + self.omega = w * math.pow(2, -31) * gpsPi + self.omega_dot = omega_dot * math.pow(2, -43) * gpsPi + self.omega0 = omega_0 * math.pow(2, -31) * gpsPi + self.toe = t_oe * math.pow(2, 4) # clock correction information - self.toc = t_oc * pow(2, 4) + self.toc = t_oc * math.pow(2, 4) self.gpsWeek = week_no - self.af0 = a_f0 * pow(2, -31) - self.af1 = a_f1 * pow(2, -43) - self.af2 = a_f2 * pow(2, -55) + self.af0 = a_f0 * math.pow(2, -31) + self.af1 = a_f1 * math.pow(2, -43) + self.af2 = a_f2 * math.pow(2, -55) iode1 = GET_FIELD_U(subframes[2][2+0], 8, 22) iode2 = GET_FIELD_U(subframes[3][2+7], 8, 22) @@ -117,14 +118,14 @@ on of this parser if GET_FIELD_U(subframes[4][2+0], 6, 22) == 56 and \ GET_FIELD_U(subframes[4][2+0], 2, 28) == 1 and \ GET_FIELD_U(subframes[5][2+0], 2, 28) == 1: - a0 = GET_FIELD_S(subframes[4][2], 8, 14) * pow(2, -30) - a1 = GET_FIELD_S(subframes[4][2], 8, 6) * pow(2, -27) - a2 = GET_FIELD_S(subframes[4][3], 8, 22) * pow(2, -24) - a3 = GET_FIELD_S(subframes[4][3], 8, 14) * pow(2, -24) - b0 = GET_FIELD_S(subframes[4][3], 8, 6) * pow(2, 11) - b1 = GET_FIELD_S(subframes[4][4], 8, 22) * pow(2, 14) - b2 = GET_FIELD_S(subframes[4][4], 8, 14) * pow(2, 16) - b3 = GET_FIELD_S(subframes[4][4], 8, 6) * pow(2, 16) + a0 = GET_FIELD_S(subframes[4][2], 8, 14) * math.pow(2, -30) + a1 = GET_FIELD_S(subframes[4][2], 8, 6) * math.pow(2, -27) + a2 = GET_FIELD_S(subframes[4][3], 8, 22) * math.pow(2, -24) + a3 = GET_FIELD_S(subframes[4][3], 8, 14) * math.pow(2, -24) + b0 = GET_FIELD_S(subframes[4][3], 8, 6) * math.pow(2, 11) + b1 = GET_FIELD_S(subframes[4][4], 8, 22) * math.pow(2, 14) + b2 = GET_FIELD_S(subframes[4][4], 8, 14) * math.pow(2, 16) + b3 = GET_FIELD_S(subframes[4][4], 8, 6) * math.pow(2, 16) self.ionoAlpha = [a0, a1, a2, a3] self.ionoBeta = [b0, b1, b2, b3] diff --git a/selfdrive/locationd/test/test_params_learner.py b/selfdrive/locationd/test/test_params_learner.py index bd2399b24b..df0e851cd7 100755 --- a/selfdrive/locationd/test/test_params_learner.py +++ b/selfdrive/locationd/test/test_params_learner.py @@ -31,7 +31,7 @@ class TestParamsLearner(unittest.TestCase): steering_angles = np.radians(10 * np.sin(2 * np.pi * times / 100.)) + angle_offset speeds = 10 * np.sin(2 * np.pi * times / 1000.) + 25 - for i, t in enumerate(times): + for i, _ in enumerate(times): u = speeds[i] sa = steering_angles[i] psi = VM_sim.yaw_rate(sa - angle_offset, u) diff --git a/selfdrive/locationd/test/ublox.py b/selfdrive/locationd/test/ublox.py index 8120f70fd2..6a28edb1aa 100644 --- a/selfdrive/locationd/test/ublox.py +++ b/selfdrive/locationd/test/ublox.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +# pylint: skip-file ''' UBlox binary protocol handling diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index 6d858c9ecf..314c80237f 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 # type: ignore +# pylint: skip-file import os import serial diff --git a/selfdrive/loggerd/tests/test_deleter.py b/selfdrive/loggerd/tests/test_deleter.py index f06946b2fe..89904e694a 100644 --- a/selfdrive/loggerd/tests/test_deleter.py +++ b/selfdrive/loggerd/tests/test_deleter.py @@ -23,9 +23,6 @@ class TestDeleter(UploaderTestCase): deleter.os.statvfs = self.fake_statvfs deleter.ROOT = self.root - def tearDown(self): - super(TestDeleter, self).tearDown() - def start_thread(self): self.end_event = threading.Event() self.del_thread = threading.Thread(target=deleter.deleter_thread, args=[self.end_event]) diff --git a/selfdrive/loggerd/tests/test_uploader.py b/selfdrive/loggerd/tests/test_uploader.py index 3df3d937ac..4a44f80b5c 100644 --- a/selfdrive/loggerd/tests/test_uploader.py +++ b/selfdrive/loggerd/tests/test_uploader.py @@ -38,9 +38,6 @@ class TestUploader(UploaderTestCase): super(TestUploader, self).setUp() log_handler.reset() - def tearDown(self): - super(TestUploader, self).tearDown() - def start_thread(self): self.end_event = threading.Event() self.up_thread = threading.Thread(target=uploader.uploader_fn, args=[self.end_event]) diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index b3b25a2610..b479574b02 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -25,6 +25,7 @@ UPLOAD_ATTR_VALUE = b'1' fake_upload = os.getenv("FAKEUPLOAD") is not None def raise_on_thread(t, exctype): + '''Raises an exception in the threads with id tid''' for ctid, tobj in threading._active.items(): if tobj is t: tid = ctid @@ -32,7 +33,6 @@ def raise_on_thread(t, exctype): else: raise Exception("Could not find thread") - '''Raises an exception in the threads with id tid''' if not inspect.isclass(exctype): raise TypeError("Only types can be raised (not instances)") diff --git a/selfdrive/manager.py b/selfdrive/manager.py index c3ca373372..bee1dacb4c 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -305,11 +305,11 @@ def start_daemon_process(name): pass cloudlog.info("starting daemon %s" % name) - proc = subprocess.Popen(['python', '-m', proc], - stdin=open('/dev/null', 'r'), - stdout=open('/dev/null', 'w'), - stderr=open('/dev/null', 'w'), - preexec_fn=os.setpgrp) + proc = subprocess.Popen(['python', '-m', proc], # pylint: disable=subprocess-popen-preexec-fn + stdin=open('/dev/null', 'r'), + stdout=open('/dev/null', 'w'), + stderr=open('/dev/null', 'w'), + preexec_fn=os.setpgrp) params.put(pid_param, str(proc.pid)) @@ -590,8 +590,6 @@ def main(): try: manager_thread() - except SystemExit: - raise except Exception: traceback.print_exc() crash.capture_exception() diff --git a/selfdrive/modeld/runners/keras_runner.py b/selfdrive/modeld/runners/keras_runner.py index 33d4322732..c692ac5988 100755 --- a/selfdrive/modeld/runners/keras_runner.py +++ b/selfdrive/modeld/runners/keras_runner.py @@ -10,19 +10,22 @@ import numpy as np from tensorflow.keras.models import Model # pylint: disable=import-error from tensorflow.keras.models import load_model # pylint: disable=import-error + def read(sz): dd = [] gt = 0 - while gt < sz*4: - st = os.read(0, sz*4 - gt) + while gt < sz * 4: + st = os.read(0, sz * 4 - gt) assert(len(st) > 0) dd.append(st) gt += len(st) return np.fromstring(b''.join(dd), dtype=np.float32) + def write(d): os.write(1, d.tobytes()) + def run_loop(m): isize = m.inputs[0].shape[1] osize = m.outputs[0].shape[1] @@ -32,6 +35,7 @@ def run_loop(m): ret = m.predict_on_batch(idata) write(ret) + if __name__ == "__main__": print(tf.__version__, file=sys.stderr) # limit gram alloc @@ -48,7 +52,7 @@ if __name__ == "__main__": acc = 0 for i, ii in enumerate(m.inputs): print(ii, file=sys.stderr) - ti = keras.layers.Lambda(lambda x: x[:, acc:acc+bs[i]], output_shape=(1, bs[i]))(ri) + ti = keras.layers.Lambda(lambda x, i=i: x[:, acc:acc + bs[i]], output_shape=(1, bs[i]))(ri) acc += bs[i] tr = keras.layers.Reshape(ii.shape[1:])(ti) tii.append(tr) diff --git a/selfdrive/modeld/visiontest.py b/selfdrive/modeld/visiontest.py index 72dbe59acc..6f97684244 100644 --- a/selfdrive/modeld/visiontest.py +++ b/selfdrive/modeld/visiontest.py @@ -8,11 +8,12 @@ _visiond_dir = os.path.dirname(os.path.abspath(__file__)) _libvisiontest = "libvisiontest.so" try: # bacause this crashes somtimes when running pipeline subprocess.check_output(["make", "-C", _visiond_dir, "-f", - os.path.join(_visiond_dir, "visiontest.mk"), - _libvisiontest]) + os.path.join(_visiond_dir, "visiontest.mk"), + _libvisiontest]) except Exception: pass + class VisionTest(): """A version of the vision model that can be run on a desktop. @@ -105,7 +106,7 @@ class VisionTest(): def transform_output_buffer(self, yuv_data, y_out, u_out, v_out, transform): - assert len(yuv_data) == self.input_size[0] * self.input_size[1] * 3/2 + assert len(yuv_data) == self.input_size[0] * self.input_size[1] * 3 / 2 cast = self.ffi.cast from_buffer = self.ffi.from_buffer @@ -126,7 +127,7 @@ class VisionTest(): def __enter__(self): return self - def __exit__(self, type, value, traceback): + def __exit__(self, exc_type, exc_value, traceback): self.close() diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py index a7fb64b224..24f5015bd2 100755 --- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py +++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py @@ -24,20 +24,23 @@ def create_dir(path): def check_no_collision(log): return min(log['d_rel']) > 0 + def check_fcw(log): return any(log['fcw']) + def check_engaged(log): return log['controls_state_msgs'][-1][-1].active + 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)], + (CB.RES_ACCEL, 10.), (0, 10.1), + (CB.RES_ACCEL, 10.2), (0, 10.3)], checks=[check_engaged], ), Maneuver( @@ -45,8 +48,8 @@ maneuvers = [ 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)], + (CB.DECEL_SET, 10.), (0, 10.1), + (CB.DECEL_SET, 10.2), (0, 10.3)], checks=[check_engaged], ), Maneuver( @@ -73,7 +76,7 @@ maneuvers = [ 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_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)], checks=[check_engaged, check_no_collision], @@ -84,7 +87,7 @@ maneuvers = [ 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_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)], checks=[check_engaged, check_no_collision], @@ -140,9 +143,9 @@ maneuvers = [ 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)], + (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)], checks=[check_engaged, check_no_collision], ), Maneuver( @@ -154,8 +157,8 @@ maneuvers = [ 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)], + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)], checks=[check_engaged, check_no_collision], ), Maneuver( @@ -167,8 +170,8 @@ maneuvers = [ 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)], + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)], checks=[check_engaged, check_no_collision], ), Maneuver( @@ -177,14 +180,14 @@ maneuvers = [ initial_speed=0., lead_relevancy=True, initial_distance_lead=4., - speed_lead_values=[0, 0 , 45], + 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)], + (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)], checks=[check_engaged, check_no_collision], ), Maneuver( @@ -193,11 +196,11 @@ maneuvers = [ initial_speed=0., lead_relevancy=True, initial_distance_lead=20., - speed_lead_values=[10., 0., 0., 10., 0., 0.] , + 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)], + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)], checks=[check_engaged, check_no_collision], ), Maneuver( @@ -206,11 +209,11 @@ maneuvers = [ initial_speed=0., lead_relevancy=True, initial_distance_lead=20., - speed_lead_values=[10., 0., 0., 10., 0., 0.] , + speed_lead_values=[10., 0., 0., 10., 0., 0.], speed_lead_breakpoints=[10., 13., 26., 33., 36., 45.], 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.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)], checks=[check_engaged, check_no_collision], ), Maneuver( @@ -222,11 +225,11 @@ maneuvers = [ 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)], + (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)], checks=[check_engaged, check_no_collision], ), Maneuver( @@ -238,11 +241,11 @@ maneuvers = [ 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)], + (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)], checks=[check_engaged, check_no_collision], ), Maneuver( @@ -291,8 +294,6 @@ maneuvers = [ ) ] -# maneuvers = [maneuvers[-11]] -# maneuvers = [maneuvers[6]] def setup_output(): output_dir = os.path.join(os.getcwd(), 'out/longitudinal') @@ -313,13 +314,14 @@ def setup_output(): 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 += "" % (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): @@ -355,7 +357,7 @@ def run_maneuver_worker(k): print(man.title) valid = False - for retries in range(3): + for _ in range(3): manager.start_managed_process('radard') manager.start_managed_process('controlsd') manager.start_managed_process('plannerd') diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py index 985e59f87f..10f5231df0 100755 --- a/selfdrive/test/process_replay/compare_logs.py +++ b/selfdrive/test/process_replay/compare_logs.py @@ -13,6 +13,7 @@ else: from tools.lib.logreader import LogReader + def save_log(dest, log_msgs): dat = b"" for msg in tqdm(log_msgs): @@ -22,6 +23,7 @@ def save_log(dest, log_msgs): with open(dest, "wb") as f: f.write(dat) + def remove_ignored_fields(msg, ignore): msg = msg.as_builder() for key in ignore: @@ -46,7 +48,13 @@ def remove_ignored_fields(msg, ignore): setattr(attr, keys[-1], val) return msg.as_reader() -def compare_logs(log1, log2, ignore_fields=[], ignore_msgs=[]): + +def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None): + if ignore_fields is None: + ignore_fields = [] + + if ignore_msgs is None: + ignore_msgs = [] log1, log2 = [list(filter(lambda m: m.which() not in ignore_msgs, log)) for log in (log1, log2)] assert len(log1) == len(log2), "logs are not same length: " + str(len(log1)) + " VS " + str(len(log2)) @@ -66,6 +74,7 @@ def compare_logs(log1, log2, ignore_fields=[], ignore_msgs=[]): diff.extend(dd) return diff + if __name__ == "__main__": log1 = list(LogReader(sys.argv[1])) log2 = list(LogReader(sys.argv[2])) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index ca438ed666..b42fefea26 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -21,6 +21,7 @@ from collections import namedtuple ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'init_callback', 'should_recv_callback']) + def wait_for_event(evt): if not evt.wait(15): if threading.currentThread().getName() == "MainThread": @@ -30,6 +31,7 @@ def wait_for_event(evt): # done testing this process, let it die sys.exit(0) + class FakeSocket: def __init__(self, wait=True): self.data = [] @@ -60,6 +62,7 @@ class FakeSocket: def wait_for_recv(self): wait_for_event(self.recv_called) + class DumbSocket: def __init__(self, s=None): if s is not None: @@ -72,6 +75,7 @@ class DumbSocket: def send(self, dat): pass + class FakeSubMaster(messaging.SubMaster): def __init__(self, services): super(FakeSubMaster, self).__init__(services, addr=None) @@ -103,8 +107,9 @@ class FakeSubMaster(messaging.SubMaster): def wait_for_update(self): wait_for_event(self.update_called) + class FakePubMaster(messaging.PubMaster): - def __init__(self, services): + def __init__(self, services): # pylint: disable=super-init-not-called self.data = {} self.sock = {} self.last_updated = None diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index b1a28a700f..c40604aa00 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -49,7 +49,11 @@ def get_segment(segment_name, original=True): return rlog_url -def test_process(cfg, lr, cmp_log_fn, ignore_fields=[], ignore_msgs=[]): +def test_process(cfg, lr, cmp_log_fn, ignore_fields=None, ignore_msgs=None): + if ignore_fields is None: + ignore_fields = [] + if ignore_msgs is None: + ignore_msgs = [] url = BASE_URL + os.path.basename(cmp_log_fn) cmp_log_msgs = list(LogReader(url)) diff --git a/selfdrive/test/profiling/lib.py b/selfdrive/test/profiling/lib.py index eb9b9b8e56..0495be80c3 100644 --- a/selfdrive/test/profiling/lib.py +++ b/selfdrive/test/profiling/lib.py @@ -36,7 +36,7 @@ class PubSocket(): class SubMaster(messaging.SubMaster): - def __init__(self, msgs, trigger, services): + def __init__(self, msgs, trigger, services): # pylint: disable=super-init-not-called self.max_i = len(msgs) - 1 self.i = 0 self.frame = 0 @@ -88,5 +88,5 @@ class SubMaster(messaging.SubMaster): class PubMaster(messaging.PubMaster): - def __init__(self): + def __init__(self): # pylint: disable=super-init-not-called self.sock = defaultdict(PubSocket) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index ad539fff7b..eb01c41bc9 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -40,6 +40,7 @@ def wait_for_sockets(socks, timeout=10.0): recvd.append(s) return recvd + def get_route_log(route_name): log_path = os.path.join("/tmp", "%s--0--%s" % (route_name.replace("|", "_"), "rlog.bz2")) @@ -49,7 +50,7 @@ def get_route_log(route_name): # if request fails, try again once and let it throw exception if fails again try: r = requests.get(log_url, timeout=15) - except: + except Exception: r = requests.get(log_url, timeout=15) if r.status_code == 200: @@ -460,7 +461,7 @@ if __name__ == "__main__": # Start unlogger print("Start unlogger") unlogger_cmd = [os.path.join(BASEDIR, 'tools/replay/unlogger.py'), route, '/tmp'] - unlogger = subprocess.Popen(unlogger_cmd + ['--disable', 'frame,encodeIdx,plan,pathPlan,liveLongitudinalMpc,radarState,controlsState,liveTracks,liveMpc,sendcan,carState,carControl,carEvents,carParams', '--no-interactive'], preexec_fn=os.setsid) + unlogger = subprocess.Popen(unlogger_cmd + ['--disable', 'frame,encodeIdx,plan,pathPlan,liveLongitudinalMpc,radarState,controlsState,liveTracks,liveMpc,sendcan,carState,carControl,carEvents,carParams', '--no-interactive'], preexec_fn=os.setsid) # pylint: disable=subprocess-popen-preexec-fn print("Check sockets") extra_socks = [] diff --git a/selfdrive/test/test_openpilot.py b/selfdrive/test/test_openpilot.py index 624524de77..c03a2e41ff 100644 --- a/selfdrive/test/test_openpilot.py +++ b/selfdrive/test/test_openpilot.py @@ -15,7 +15,6 @@ import requests import signal import subprocess import time -from datetime import datetime, timedelta DID_INIT = False diff --git a/selfdrive/thermald/power_monitoring.py b/selfdrive/thermald/power_monitoring.py index 378bee6f91..0801cea559 100644 --- a/selfdrive/thermald/power_monitoring.py +++ b/selfdrive/thermald/power_monitoring.py @@ -114,7 +114,7 @@ class PowerMonitoring: # Measure for a few sec to get a good average voltages = [] currents = [] - for i in range(6): + for _ in range(6): voltages.append(get_battery_voltage()) currents.append(get_battery_current()) time.sleep(1) diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py index 022f9fdfcf..4dc969b5c7 100755 --- a/selfdrive/tombstoned.py +++ b/selfdrive/tombstoned.py @@ -61,7 +61,7 @@ def main(): while True: now_tombstones = set(get_tombstones()) - for fn, ctime in (now_tombstones - initial_tombstones): + for fn, _ in (now_tombstones - initial_tombstones): try: cloudlog.info(f"reporting new tombstone {fn}") report_tombstone(fn, client) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index c31ab9560f..9775df027e 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -195,7 +195,7 @@ def inodes_in_tree(search_dir): """Given a search root, produce a dictionary mapping of inodes to relative pathnames of regular files (no directories, symlinks, or special files).""" inode_map = {} - for root, dirs, files in os.walk(search_dir, topdown=True): + for root, _, files in os.walk(search_dir, topdown=True): for file_name in files: full_path_name = os.path.join(root, file_name) st = os.lstat(full_path_name) diff --git a/tools/lib/auth.py b/tools/lib/auth.py index 870eb6b0bc..b91eb3f7b0 100755 --- a/tools/lib/auth.py +++ b/tools/lib/auth.py @@ -25,7 +25,7 @@ class ClientRedirectHandler(BaseHTTPRequestHandler): self.end_headers() self.wfile.write(b'Return to the CLI to continue') - def log_message(self, format, *args): + def log_message(self, format, *args): # pylint: disable=redefined-builtin pass # this prevent http server from dumping messages to stdout def auth_redirect_link(port): diff --git a/tools/lib/kbhit.py b/tools/lib/kbhit.py index fcb29c16a5..69f61d7a26 100644 --- a/tools/lib/kbhit.py +++ b/tools/lib/kbhit.py @@ -54,7 +54,7 @@ class KBHit: def kbhit(self): ''' Returns True if keyboard character was hit, False otherwise. ''' - dr, dw, de = select([sys.stdin], [], [], 0) + dr, _, _ = select([sys.stdin], [], [], 0) return dr != [] diff --git a/tools/lib/route_framereader.py b/tools/lib/route_framereader.py index a60547cc02..b228275efc 100644 --- a/tools/lib/route_framereader.py +++ b/tools/lib/route_framereader.py @@ -1,6 +1,7 @@ """RouteFrameReader indexes and reads frames across routes, by frameId or segment indices.""" from tools.lib.framereader import FrameReader + class _FrameReaderDict(dict): def __init__(self, camera_paths, cache_paths, framereader_kwargs, *args, **kwargs): super(_FrameReaderDict, self).__init__(*args, **kwargs) @@ -8,7 +9,7 @@ class _FrameReaderDict(dict): if cache_paths is None: cache_paths = {} if not isinstance(cache_paths, dict): - cache_paths = { k: v for k, v in enumerate(cache_paths) } + cache_paths = {k: v for k, v in enumerate(cache_paths)} self._camera_paths = camera_paths self._cache_paths = cache_paths @@ -84,5 +85,5 @@ class RouteFrameReader(object): def __enter__(self): return self - def __exit__(self, type, value, traceback): + def __exit__(self, exc_type, exc_value, traceback): self.close() diff --git a/tools/replay/camera.py b/tools/replay/camera.py index e1869048ec..ad6db041d2 100755 --- a/tools/replay/camera.py +++ b/tools/replay/camera.py @@ -3,7 +3,7 @@ import os from common.basedir import BASEDIR os.environ['BASEDIR'] = BASEDIR -SCALE = float(os.getenv("SCALE", 1.0)) +SCALE = float(os.getenv("SCALE", "1")) import argparse import pygame # pylint: disable=import-error diff --git a/tools/replay/unlogger.py b/tools/replay/unlogger.py index 3744832b6b..eebfe28203 100755 --- a/tools/replay/unlogger.py +++ b/tools/replay/unlogger.py @@ -5,10 +5,10 @@ import sys import zmq import time import signal +import multiprocessing from uuid import uuid4 from collections import namedtuple from collections import deque -from multiprocessing import Process, TimeoutError from datetime import datetime # strat 1: script to copy files @@ -404,11 +404,11 @@ def main(argv): subprocesses = {} try: - subprocesses["data"] = Process( + subprocesses["data"] = multiprocessing.Process( target=UnloggerWorker().run, args=(forward_commands_address, data_address, address_mapping.copy())) - subprocesses["control"] = Process( + subprocesses["control"] = multiprocessing.Process( target=unlogger_thread, args=(command_address, forward_commands_address, data_address, args.realtime, _get_address_mapping(args), args.publish_time_length, args.bind_early, args.no_loop)) @@ -421,7 +421,7 @@ def main(argv): # Exit if any of the children die. def exit_if_children_dead(*_): - for name, p in subprocesses.items(): + for _, p in subprocesses.items(): if not p.is_alive(): [p.terminate() for p in subprocesses.values()] exit() @@ -439,7 +439,7 @@ def main(argv): if p.is_alive(): try: p.join(3.) - except TimeoutError: + except multiprocessing.TimeoutError: p.terminate() continue return 0 diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index b5a63c3056..9ffdc8c827 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -97,11 +97,9 @@ def go(q): world.set_weather(weather) blueprint_library = world.get_blueprint_library() - """ - for blueprint in blueprint_library.filter('sensor.*'): - print(blueprint.id) - exit(0) - """ + # for blueprint in blueprint_library.filter('sensor.*'): + # print(blueprint.id) + # exit(0) world_map = world.get_map() vehicle_bp = random.choice(blueprint_library.filter('vehicle.tesla.*')) diff --git a/tools/sim/lib/manual_ctrl.py b/tools/sim/lib/manual_ctrl.py index bdc0778ec9..d943bdf1d9 100755 --- a/tools/sim/lib/manual_ctrl.py +++ b/tools/sim/lib/manual_ctrl.py @@ -143,7 +143,7 @@ def wheel_poll_thread(q): while True: evbuf = jsdev.read(8) - time, value, mtype, number = struct.unpack('IhBB', evbuf) + _, value, mtype, number = struct.unpack('IhBB', evbuf) # print(mtype, number, value) if mtype & 0x02: # wheel & paddles axis = axis_map[number] From 60620fe773dc000a6cd8dfef66293d164631316f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 2 Jun 2020 16:29:50 -0700 Subject: [PATCH 194/656] bump submodules --- cereal | 2 +- panda | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index a4beeb99ff..978ffda405 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit a4beeb99ff8a2d553c29249d55e95ecee8ec8b47 +Subproject commit 978ffda4057542514b233a4b540690a964651dca diff --git a/panda b/panda index d7f7b14118..e0a706e4f0 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit d7f7b141181c290e8ceb982a69e0f5729532c67f +Subproject commit e0a706e4f013b69253f300eeeda3a60915e10adf From 165bcf1f31ffc34b56c84cf8e71f41ce224dd7e3 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Tue, 2 Jun 2020 17:31:59 -0700 Subject: [PATCH 195/656] Fix speed too low (#1627) * fix speed too low * bump ref Co-authored-by: Willem Melching --- cereal | 2 +- selfdrive/car/gm/interface.py | 2 +- selfdrive/car/honda/interface.py | 4 ++-- selfdrive/car/mazda/interface.py | 2 +- selfdrive/car/toyota/interface.py | 2 +- selfdrive/controls/lib/events.py | 5 ++++- selfdrive/test/process_replay/ref_commit | 2 +- 7 files changed, 11 insertions(+), 8 deletions(-) diff --git a/cereal b/cereal index 978ffda405..cc14179697 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 978ffda4057542514b233a4b540690a964651dca +Subproject commit cc14179697fac4757daeaa7968ac29d490204693 diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 6dda4f3a0a..f63f8d7741 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -149,7 +149,7 @@ class CarInterface(CarInterfaceBase): events = self.create_common_events(ret, pcm_enable=False) if ret.vEgo < self.CP.minEnableSpeed: - events.add(EventName.speedTooLow) + events.add(EventName.belowEngageSpeed) if self.CS.park_brake: events.add(EventName.parkBrake) if ret.cruiseState.standstill: diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index aa315afd52..7e5c46c895 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -482,12 +482,12 @@ class CarInterface(CarInterfaceBase): events.add(EventName.parkBrake) if self.CP.enableCruise and ret.vEgo < self.CP.minEnableSpeed: - events.add(EventName.speedTooLow) + events.add(EventName.belowEngageSpeed) # 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 if self.CP.enableCruise and not ret.cruiseState.enabled \ - and (c.actuators.brake <= 0. or not self.CP.openpilotLongitudinalControl) and (self.CP.minEnableSpeed > 0): + and (c.actuators.brake <= 0. or not self.CP.openpilotLongitudinalControl): # non loud alert if cruise disables below 25mph as expected (+ a little margin) if ret.vEgo < self.CP.minEnableSpeed + 2.: events.add(EventName.speedTooLow) diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 037b84e107..20ddf5ae94 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -77,7 +77,7 @@ class CarInterface(CarInterfaceBase): events = self.create_common_events(ret) if self.CS.low_speed_lockout: - events.add(EventName.speedTooLow) + events.add(EventName.belowEngageSpeed) if self.CS.low_speed_alert: events.add(EventName.belowSteerSpeed) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 9b9b46cf39..7720e627f7 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -323,7 +323,7 @@ class CarInterface(CarInterfaceBase): if self.CS.low_speed_lockout and self.CP.openpilotLongitudinalControl: events.add(EventName.lowSpeedLockout) if ret.vEgo < self.CP.minEnableSpeed and self.CP.openpilotLongitudinalControl: - events.add(EventName.speedTooLow) + events.add(EventName.belowEngageSpeed) if c.actuators.gas > 0.1: # some margin on the actuator to not false trigger cancellation while stopping events.add(EventName.speedTooLow) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 413a402407..ff97a6bbd5 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -506,6 +506,10 @@ EVENTS = { duration_hud_alert=0.), }, + EventName.belowEngageSpeed: { + ET.NO_ENTRY: NoEntryAlert("Speed Too Low"), + }, + EventName.sensorDataInvalid: { ET.PERMANENT: Alert( "No Data from Device Sensors", @@ -680,7 +684,6 @@ EVENTS = { "Speed too low", AlertStatus.normal, AlertSize.mid, Priority.HIGH, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), - ET.NO_ENTRY: NoEntryAlert("Speed Too Low"), }, EventName.speedTooHigh: { diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index bdcc7b799f..47366239cf 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -5bad0192bf35d8f08f26dd5ac72b3c1d62a57569 \ No newline at end of file +5abe4f99eec3633bc30fda47c272e0f19a840a29 \ No newline at end of file From 66455b075d918d9f04fae6921d0a692ee3f8afd0 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 2 Jun 2020 17:32:55 -0700 Subject: [PATCH 196/656] locationd profiling (#1625) --- selfdrive/test/profiling/lib.py | 2 ++ selfdrive/test/profiling/locationd.py | 49 +++++++++++++++++++++++++++ 2 files changed, 51 insertions(+) create mode 100755 selfdrive/test/profiling/locationd.py diff --git a/selfdrive/test/profiling/lib.py b/selfdrive/test/profiling/lib.py index 0495be80c3..997b48f673 100644 --- a/selfdrive/test/profiling/lib.py +++ b/selfdrive/test/profiling/lib.py @@ -82,6 +82,8 @@ class SubMaster(messaging.SubMaster): self.logMonoTime[w] = msg.logMonoTime self.i += 1 + if self.i == self.max_i: + raise ReplayDone if w == self.trigger: break diff --git a/selfdrive/test/profiling/locationd.py b/selfdrive/test/profiling/locationd.py new file mode 100755 index 0000000000..4c478cf778 --- /dev/null +++ b/selfdrive/test/profiling/locationd.py @@ -0,0 +1,49 @@ +#!/usr/bin/env python3 + +import cProfile # pylint: disable=import-error +import pprofile # pylint: disable=import-error +import pyprof2calltree # pylint: disable=import-error + +from tools.lib.logreader import LogReader +from selfdrive.locationd.locationd import locationd_thread +from selfdrive.test.profiling.lib import SubMaster, PubMaster, ReplayDone + +BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" + +CARS = { + 'toyota': ("77611a1fac303767|2020-02-29--13-29-33/3", "TOYOTA COROLLA TSS2 2019"), +} + + +def get_inputs(msgs, process): + sub_socks = ['gpsLocationExternal', 'sensorEvents', 'cameraOdometry', 'liveCalibration', 'carState'] + trigger = 'cameraOdometry' + + sm = SubMaster(msgs, trigger, sub_socks) + pm = PubMaster() + return sm, pm + + +if __name__ == "__main__": + segment, fingerprint = CARS['toyota'] + segment = segment.replace('|', '/') + rlog_url = f"{BASE_URL}{segment}/rlog.bz2" + msgs = list(LogReader(rlog_url)) + + # Statistical + sm, pm = get_inputs(msgs, 'locationd') + with pprofile.StatisticalProfile()(period=0.00001) as pr: + try: + locationd_thread(sm, pm) + except ReplayDone: + pass + pr.dump_stats('cachegrind.out.locationd_statistical') + + # Deterministic + sm, pm = get_inputs(msgs, 'controlsd') + with cProfile.Profile() as pr: + try: + locationd_thread(sm, pm) + except ReplayDone: + pass + pyprof2calltree.convert(pr.getstats(), 'cachegrind.out.locationd_deterministic') From 6e0bb25ab4659db306df10ba90fdc18562b2cc4f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 2 Jun 2020 17:39:58 -0700 Subject: [PATCH 197/656] run deleter when offroad --- selfdrive/manager.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index bee1dacb4c..a8e81c205c 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -224,6 +224,7 @@ if ANDROID: 'logcatd', 'tombstoned', 'updated', + 'deleter', ] car_started_processes = [ @@ -252,7 +253,6 @@ if ANDROID: 'clocksd', 'gpsd', 'dmonitoringmodeld', - 'deleter', ] def register_managed_process(name, desc, car_started=False): From e3ffdf3647075ce7415a9ba6b808b5021931acc1 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 3 Jun 2020 11:11:06 -0700 Subject: [PATCH 198/656] Paramsd can now be killed normally --- selfdrive/manager.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index a8e81c205c..a92d2e0634 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -207,7 +207,7 @@ unkillable_processes = ['camerad'] interrupt_processes: List[str] = [] # processes to end with SIGKILL instead of SIGTERM -kill_processes = ['sensord', 'paramsd'] +kill_processes = ['sensord'] # processes to end if thermal conditions exceed Green parameters green_temp_processes = ['uploader'] From 0f20ac728f4558ee8a849646f366d816a2479b62 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 3 Jun 2020 11:31:12 -0700 Subject: [PATCH 199/656] Bounds checks on liveParameters for testing on desk --- selfdrive/controls/lib/pathplanner.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index 48ae4baca0..40e6c38002 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -87,7 +87,12 @@ class PathPlanner(): # Run MPC self.angle_steers_des_prev = self.angle_steers_des_mpc - VM.update_params(sm['liveParameters'].stiffnessFactor, sm['liveParameters'].steerRatio) + + # Update vehicle model + x = max(sm['liveParameters'].stiffnessFactor, 0.1) + sr = max(sm['liveParameters'].steerRatio, 0.1) + VM.update_params(x, sr) + curvature_factor = VM.curvature_factor(v_ego) self.LP.parse_model(sm['model']) From d1d2984f366e6b541b80c5364cd1f17f817ecb02 Mon Sep 17 00:00:00 2001 From: George Hotz Date: Wed, 3 Jun 2020 11:31:34 -0700 Subject: [PATCH 200/656] fetch image from route script --- .pre-commit-config.yaml | 2 +- tools/scripts/fetch_image_from_route.py | 37 +++++++++++++++++++++++++ 2 files changed, 38 insertions(+), 1 deletion(-) create mode 100755 tools/scripts/fetch_image_from_route.py diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index d65b68b13d..e559d87b3b 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,7 +17,7 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(opendbc)|(laika_repo)|(rednose_repo)/' args: - - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E265,E266,E302,E305,E402,E501,E722,E741,W504 + - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E265,E266,E302,E305,E402,E501,E722,E741,W504,W391 - --statistics - repo: local hooks: diff --git a/tools/scripts/fetch_image_from_route.py b/tools/scripts/fetch_image_from_route.py new file mode 100755 index 0000000000..e9111d9de2 --- /dev/null +++ b/tools/scripts/fetch_image_from_route.py @@ -0,0 +1,37 @@ +#!/usr/bin/env python3 +import sys + +if len(sys.argv) < 4: + print("%s " % sys.argv[0]) + print('example: ./fetch_image_from_route.py "02c45f73a2e5c6e9|2020-06-01--18-03-08" 3 500') + exit(0) + +import requests +from PIL import Image +from tools.lib.auth_config import get_token +from tools.lib.framereader import FrameReader + +jwt = get_token() + +route = sys.argv[1] +segment = int(sys.argv[2]) +frame = int(sys.argv[3]) + +url = 'https://api.commadotai.com/v1/route/'+sys.argv[1]+"/files" +r = requests.get(url, headers={"Authorization": "JWT "+jwt}) +assert r.status_code == 200 +print("got api response") + +cameras = r.json()['cameras'] +if segment >= len(cameras): + raise Exception("segment %d not found, got %d segments" % (segment, len(cameras))) + +fr = FrameReader(cameras[segment]) +if frame >= fr.frame_count: + raise Exception("frame %d not found, got %d frames" % (frame, fr.frame_count)) + +im = Image.fromarray(fr.get(frame, count=1, pix_fmt="rgb24")[0]) +fn = "uxxx_"+route.replace("|", "_")+"_%d_%d.png" % (segment, frame) +im.save(fn) +print("saved %s" % fn) + From 2144154c328abf67b7fb265c580226e3b94a59e6 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 3 Jun 2020 12:12:27 -0700 Subject: [PATCH 201/656] update rednose --- rednose_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rednose_repo b/rednose_repo index 40f9d48c63..026464a3d1 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit 40f9d48c63f49e24a1ff56181434af747a503fc2 +Subproject commit 026464a3d143b34e1daaf7654745ce418d5266b9 From ab83e48ec4f7c7ddaa742d9797b0d38646fdb268 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Wed, 3 Jun 2020 12:54:49 -0700 Subject: [PATCH 202/656] Add pre-commit hooks (#1629) --- .pre-commit-config.yaml | 4 ++ SAFETY.md | 4 +- common/transformations/README.md | 6 +- selfdrive/camerad/cameras/camera_qcom2.c | 16 ++--- selfdrive/camerad/cameras/sensor2_i2c.h | 4 +- selfdrive/camerad/imgproc/conv.cl | 12 ++-- selfdrive/camerad/imgproc/pool.cl | 4 +- selfdrive/camerad/transforms/rgb_to_yuv.c | 2 +- selfdrive/common/buffering.c | 4 +- selfdrive/common/framebuffer.cc | 2 +- selfdrive/locationd/paramsd.cc | 2 +- selfdrive/loggerd/frame_logger.h | 2 +- selfdrive/loggerd/loggerd.cc | 2 +- selfdrive/modeld/modeld.cc | 2 +- selfdrive/modeld/thneed/debug/main.cc | 6 +- .../thneed/debug/microbenchmark/gemm_image.cl | 4 +- .../modeld/thneed/debug/microbenchmark/go.c | 4 +- selfdrive/ui/text/text.c | 2 +- tools/lib/vidindex/vidindex.c | 6 +- tools/nui/FileReader.cpp | 2 +- tools/nui/Unlogger.cpp | 4 +- tools/nui/main.cpp | 18 ++--- tools/nui/nui | 1 - tools/sim/README.md | 10 +-- tools/sim/start_carla.sh | 2 +- tools/webcam/README.md | 70 +++++++++---------- 26 files changed, 99 insertions(+), 96 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index e559d87b3b..d6319e48e7 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -6,6 +6,10 @@ repos: - id: check-json - id: check-xml - id: check-yaml + - id: check-merge-conflict + - id: check-symlinks + - id: trailing-whitespace + exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(opendbc)|(laika_repo)|(rednose_repo)|(phonelibs)|(lib_mpc_export)/' - repo: https://github.com/pre-commit/mirrors-mypy rev: master hooks: diff --git a/SAFETY.md b/SAFETY.md index 5a3c287fe9..9cf8933b93 100644 --- a/SAFETY.md +++ b/SAFETY.md @@ -1,7 +1,7 @@ openpilot Safety ====== -openpilot is an Adaptive Cruise Control (ACC) and Automated Lane Centering (ALC) system. +openpilot is an Adaptive Cruise Control (ACC) and Automated Lane Centering (ALC) system. Like other ACC and ALC systems, openpilot is a failsafe passive system and it requires the driver to be alert and to pay attention at all times. @@ -22,7 +22,7 @@ hardware-in-the-loop and in-vehicle tests before each software release. Following Hazard and Risk Analysis and FMEA, at a very high level, we have designed openpilot ensuring two main safety requirements. -1. The driver must always be capable to immediately retake manual control of the vehicle, +1. The driver must always be capable to immediately retake manual control of the vehicle, by stepping on either pedal or by pressing the cancel button. 2. The vehicle must not alter its trajectory too quickly for the driver to safely react. This means that while the system is engaged, the actuators are constrained diff --git a/common/transformations/README.md b/common/transformations/README.md index 119dae630e..dd9cdcc78b 100644 --- a/common/transformations/README.md +++ b/common/transformations/README.md @@ -25,14 +25,14 @@ by generating a rotation matrix and multiplying. Orientation Conventations ------ -Quaternions, rotation matrices and euler angles are three +Quaternions, rotation matrices and euler angles are three equivalent representations of orientation and all three are used throughout the code base. For euler angles the preferred convention is [roll, pitch, yaw] which corresponds to rotations around the [x, y, z] axes. All euler angles should always be in radians or radians/s unless -for plotting or display purposes. For quaternions the hamilton +for plotting or display purposes. For quaternions the hamilton notations is preferred which is [qw, qx, qy, qz]. All quaternions should always be normalized with a strictly positive qw. **These quaternions are a unique representation of orientation whereas euler angles @@ -49,7 +49,7 @@ EONs are not all mounted in the exact same way. To compensate for the effects of Example ------ -To transform global Mesh3D positions and orientations (positions_ecef, quats_ecef) into the local frame described by the +To transform global Mesh3D positions and orientations (positions_ecef, quats_ecef) into the local frame described by the first position and orientation from Mesh3D one would do: ``` ecef_from_local = rot_from_quat(quats_ecef[0]) diff --git a/selfdrive/camerad/cameras/camera_qcom2.c b/selfdrive/camerad/cameras/camera_qcom2.c index 75fa803a53..060010de7b 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.c +++ b/selfdrive/camerad/cameras/camera_qcom2.c @@ -261,7 +261,7 @@ void sensors_init(int video0_fd, int sensor_fd, int camera_num) { power->power_settings[2].power_seq_type = 2; // digital power->power_settings[3].power_seq_type = 8; // reset low power = (void*)power + (sizeof(struct cam_cmd_power) + (power->count-1)*sizeof(struct cam_power_settings)); - + unconditional_wait = (void*)power; unconditional_wait->cmd_type = CAMERA_SENSOR_CMD_TYPE_WAIT; unconditional_wait->delay = 5; @@ -424,7 +424,7 @@ void config_isp(struct CameraState *s, int io_mem_handle, int fence, int request 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}; + 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}; memcpy(buf2, tmp, sizeof(tmp)); if (io_mem_handle != 0) { @@ -610,7 +610,7 @@ static void camera_open(CameraState *s, VisionBuf* b) { acquire_dev_cmd.handle_type = CAM_HANDLE_USER_POINTER; acquire_dev_cmd.num_resources = 1; acquire_dev_cmd.resource_hdl = (uint64_t)&isp_resource; - + isp_resource.resource_id = CAM_ISP_RES_ID_PORT; isp_resource.length = sizeof(struct cam_isp_in_port_info) + sizeof(struct cam_isp_out_port_info)*(1-1); isp_resource.handle_type = CAM_HANDLE_USER_POINTER; @@ -643,7 +643,7 @@ static void camera_open(CameraState *s, VisionBuf* b) { in_port_info->test_pattern = 0x2; // 0x3? in_port_info->usage_type = 0x0; - + in_port_info->left_start = 0x0; in_port_info->left_stop = FRAME_WIDTH - 1; in_port_info->left_width = FRAME_WIDTH; @@ -664,10 +664,10 @@ static void camera_open(CameraState *s, VisionBuf* b) { in_port_info->num_out_res = 0x1; in_port_info->data[0] = (struct cam_isp_out_port_info){ - .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, + .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, //.format = CAM_FORMAT_MIPI_RAW_12, .format = CAM_FORMAT_MIPI_RAW_10, - .width = FRAME_WIDTH, + .width = FRAME_WIDTH, .height = FRAME_HEIGHT, .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, }; @@ -700,7 +700,7 @@ static void camera_open(CameraState *s, VisionBuf* b) { CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); sensors_i2c(s, start_reg_array, sizeof(start_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMON); - sensors_i2c(s, stop_reg_array, sizeof(stop_reg_array)/sizeof(struct i2c_random_wr_payload), + sensors_i2c(s, stop_reg_array, sizeof(stop_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMOFF); // config csiphy @@ -817,7 +817,7 @@ void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *ca s->rear.device_iommu = s->front.device_iommu = s->wide.device_iommu = device_iommu; s->rear.cdm_iommu = s->front.cdm_iommu = s->wide.cdm_iommu = cdm_iommu; - // subscribe + // subscribe LOG("-- Subscribing"); static struct v4l2_event_subscription sub = {0}; sub.type = 0x8000000; diff --git a/selfdrive/camerad/cameras/sensor2_i2c.h b/selfdrive/camerad/cameras/sensor2_i2c.h index 621d28251e..7174bb897a 100644 --- a/selfdrive/camerad/cameras/sensor2_i2c.h +++ b/selfdrive/camerad/cameras/sensor2_i2c.h @@ -302,8 +302,8 @@ struct i2c_random_wr_payload init_array_ar0231[] = { }; struct i2c_random_wr_payload poke_array_ov7750[] = { - {0x3208, 0x0}, {0x380e, 0x1a}, {0x380f, 0xf0}, {0x3500, 0x0}, {0x3501, 0x0}, {0x3502, 0x10}, {0x350a, 0x0}, {0x350b, 0x10}, {0x3208, 0x10}, {0x3208, 0xa0}, - //{0x3208, 0x0}, {0x380e, 0x1a}, {0x380f, 0xf0}, {0x3500, 0x0}, {0x3501, 0x0}, {0x3502, 0x10}, {0x350a, 0x0}, {0x350b, 0x10}, {0x3208, 0x10}, {0x3208, 0xa0}, + {0x3208, 0x0}, {0x380e, 0x1a}, {0x380f, 0xf0}, {0x3500, 0x0}, {0x3501, 0x0}, {0x3502, 0x10}, {0x350a, 0x0}, {0x350b, 0x10}, {0x3208, 0x10}, {0x3208, 0xa0}, + //{0x3208, 0x0}, {0x380e, 0x1a}, {0x380f, 0xf0}, {0x3500, 0x0}, {0x3501, 0x0}, {0x3502, 0x10}, {0x350a, 0x0}, {0x350b, 0x10}, {0x3208, 0x10}, {0x3208, 0xa0}, }; struct i2c_random_wr_payload preinit_array_ov7750[] = { diff --git a/selfdrive/camerad/imgproc/conv.cl b/selfdrive/camerad/imgproc/conv.cl index f92d356705..a7115ae76c 100644 --- a/selfdrive/camerad/imgproc/conv.cl +++ b/selfdrive/camerad/imgproc/conv.cl @@ -3,7 +3,7 @@ // convert input rgb image to single channel then conv __kernel void rgb2gray_conv2d( - const __global uchar * input, + const __global uchar * input, __global short * output, __constant short * filter, __local uchar3 * cached @@ -23,8 +23,8 @@ __kernel void rgb2gray_conv2d( // pad if ( - get_global_id(0) < HALF_FILTER_SIZE || - get_global_id(0) > IMAGE_W - HALF_FILTER_SIZE - 1 || + get_global_id(0) < HALF_FILTER_SIZE || + get_global_id(0) > IMAGE_W - HALF_FILTER_SIZE - 1 || get_global_id(1) < HALF_FILTER_SIZE || get_global_id(1) > IMAGE_H - HALF_FILTER_SIZE - 1 ) @@ -32,11 +32,11 @@ __kernel void rgb2gray_conv2d( barrier(CLK_LOCAL_MEM_FENCE); return; } - else + else { int localColOffset = -1; int globalColOffset = -1; - + // cache extra if ( get_local_id(0) < HALF_FILTER_SIZE ) { @@ -51,7 +51,7 @@ __kernel void rgb2gray_conv2d( { localColOffset = get_local_id(0) + TWICE_HALF_FILTER_SIZE; globalColOffset = HALF_FILTER_SIZE; - + cached[ myLocal + HALF_FILTER_SIZE ].x = input[ my * 3 + HALF_FILTER_SIZE * 3 ]; cached[ myLocal + HALF_FILTER_SIZE ].y = input[ my * 3 + HALF_FILTER_SIZE * 3 + 1]; cached[ myLocal + HALF_FILTER_SIZE ].z = input[ my * 3 + HALF_FILTER_SIZE * 3 + 2]; diff --git a/selfdrive/camerad/imgproc/pool.cl b/selfdrive/camerad/imgproc/pool.cl index 3ba86ae24e..d674b5f363 100644 --- a/selfdrive/camerad/imgproc/pool.cl +++ b/selfdrive/camerad/imgproc/pool.cl @@ -1,6 +1,6 @@ // calculate variance in each subregion __kernel void var_pool( - const __global char * input, + const __global char * input, __global ushort * output // should not be larger than 128*128 so uint16 ) { @@ -11,7 +11,7 @@ __kernel void var_pool( float fsum = 0; char mean, max; - + for (int i = 0; i < size; i++) { int x_offset = i % X_PITCH; int y_offset = i / X_PITCH; diff --git a/selfdrive/camerad/transforms/rgb_to_yuv.c b/selfdrive/camerad/transforms/rgb_to_yuv.c index b9e66b36db..1a36650b9f 100644 --- a/selfdrive/camerad/transforms/rgb_to_yuv.c +++ b/selfdrive/camerad/transforms/rgb_to_yuv.c @@ -43,7 +43,7 @@ void rgb_to_yuv_queue(RGBToYUVState* s, cl_command_queue q, cl_mem rgb_cl, cl_me err = clSetKernelArg(s->rgb_to_yuv_krnl, 1, sizeof(cl_mem), &yuv_cl); assert(err == 0); const size_t work_size[2] = { - (size_t)(s->width + (s->width % 4 == 0 ? 0 : (4 - s->width % 4))) / 4, + (size_t)(s->width + (s->width % 4 == 0 ? 0 : (4 - s->width % 4))) / 4, (size_t)(s->height + (s->height % 4 == 0 ? 0 : (4 - s->height % 4))) / 4 }; cl_event event; diff --git a/selfdrive/common/buffering.c b/selfdrive/common/buffering.c index 9cbb1b86e0..bba2e82ab9 100644 --- a/selfdrive/common/buffering.c +++ b/selfdrive/common/buffering.c @@ -70,7 +70,7 @@ void tbuffer_dispatch(TBuffer *tb, int idx) { efd_write(tb->efd); pthread_cond_signal(&tb->cv); - pthread_mutex_unlock(&tb->lock); + pthread_mutex_unlock(&tb->lock); } int tbuffer_acquire(TBuffer *tb) { @@ -344,7 +344,7 @@ void pool_push(Pool *s, int idx) { for (int i=0; iqueues[i]; if (!c->inited) continue; - + pthread_mutex_lock(&c->lock); if (((c->head+1) % c->num) == c->tail) { // queue is full. skip for now diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc index 7bea565d59..1d8ccdbdb2 100644 --- a/selfdrive/common/framebuffer.cc +++ b/selfdrive/common/framebuffer.cc @@ -98,7 +98,7 @@ extern "C" FramebufferState* framebuffer_init( assert(success); printf("egl version %d.%d\n", s->egl_major, s->egl_minor); - + EGLint num_configs; success = eglChooseConfig(s->display, attribs, &s->config, 1, &num_configs); assert(success); diff --git a/selfdrive/locationd/paramsd.cc b/selfdrive/locationd/paramsd.cc index 80eda71053..b5fa380c37 100644 --- a/selfdrive/locationd/paramsd.cc +++ b/selfdrive/locationd/paramsd.cc @@ -138,7 +138,7 @@ int main(int argc, char *argv[]) { } if (sm.updated("cameraOdometry")){ localizer.handle_log(sm["cameraOdometry"]); - } + } } return 0; } diff --git a/selfdrive/loggerd/frame_logger.h b/selfdrive/loggerd/frame_logger.h index bfc0681b75..85ddabafdc 100644 --- a/selfdrive/loggerd/frame_logger.h +++ b/selfdrive/loggerd/frame_logger.h @@ -15,7 +15,7 @@ public: int LogFrame(uint64_t ts, const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, int *frame_segment) { std::lock_guard guard(lock); - + if (opening) { Open(next_path); opening = false; diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index b7c7303c0e..d9c5017f95 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -729,7 +729,7 @@ int main(int argc, char** argv) { for (auto s : socks){ delete s; } - + delete poller; delete s.ctx; return 0; diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 217654dc21..793474e652 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -44,7 +44,7 @@ void* live_thread(void *arg) { while (!do_exit) { if (sm.update(10) > 0){ - + auto extrinsic_matrix = sm["liveCalibration"].getLiveCalibration().getExtrinsicMatrix(); Eigen::Matrix extrinsic_matrix_eigen; for (int i = 0; i < 4*3; i++){ diff --git a/selfdrive/modeld/thneed/debug/main.cc b/selfdrive/modeld/thneed/debug/main.cc index 07a7d1235b..b9848705de 100644 --- a/selfdrive/modeld/thneed/debug/main.cc +++ b/selfdrive/modeld/thneed/debug/main.cc @@ -180,7 +180,7 @@ if (intercept) { //disassemble((uint32_t *)qcmd.data(), qcmd.size()/4); //queue_cmds.push_back(qcmd); } - + #ifdef DUMP char tmp[0x100]; snprintf(tmp, sizeof(tmp), "/tmp/thneed/run_%d_%d", run_num, ioctl_num++); @@ -515,7 +515,7 @@ cl_mem clCreateImage(cl_context context, cl_mem_flags flags, const cl_image_form assert(image_desc->image_array_size == 0); assert(image_desc->image_slice_pitch == 0); //assert(image_desc->image_width * image_desc->image_height * 2 == image_desc->image_row_pitch); - + image img; img.image_width = image_desc->image_width; img.image_height = image_desc->image_height; @@ -689,7 +689,7 @@ int main(int argc, char* argv[]) { maps[len] = '\0'; fclose(f); printf("%s\n", maps);*/ - + printf("buffers: %lu images: %lu\n", buffers.size(), images.size()); printf("queues: %lu\n", queue_cmds.size()); diff --git a/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl b/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl index 46b6bf6ef8..f466a8ca49 100644 --- a/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl +++ b/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl @@ -14,8 +14,8 @@ #pragma OPENCL EXTENSION cl_khr_fp16 : enable __kernel void gemm(const int M, const int N, const int K, - read_only image2d_t A, - read_only image2d_t B, + read_only image2d_t A, + read_only image2d_t B, write_only image2d_t C) { const sampler_t smp = CLK_NORMALIZED_COORDS_FALSE | diff --git a/selfdrive/modeld/thneed/debug/microbenchmark/go.c b/selfdrive/modeld/thneed/debug/microbenchmark/go.c index 5635085638..18b91a6cb2 100644 --- a/selfdrive/modeld/thneed/debug/microbenchmark/go.c +++ b/selfdrive/modeld/thneed/debug/microbenchmark/go.c @@ -128,7 +128,7 @@ int main(int argc, char *argv[]) { M = N = K = 1024; //M = 128; K = 2112; N = 352; - + cl_kernel kern = clCreateKernel(prog, "gemm", &err); assert(err == 0); printf("creating kernel %p\n", kern); @@ -255,7 +255,7 @@ int main(int argc, char *argv[]) { clSetKernelArg(kern, 20, sizeof(n), &n); clSetKernelArg(kern, 21, sizeof(n), &n); v = 16; clSetKernelArg(kern, 22, sizeof(v), &v); - + size_t global_work_size[3] = {88, 4, 8}; size_t local_work_size[3] = {4, 4, 8}; #endif diff --git a/selfdrive/ui/text/text.c b/selfdrive/ui/text/text.c index cd910cc80b..6a2b6c753e 100644 --- a/selfdrive/ui/text/text.c +++ b/selfdrive/ui/text/text.c @@ -81,7 +81,7 @@ assert(font >= 0); float lineh; nvgTextMetrics(vg, NULL, NULL, &lineh); - + // nvgTextBox strips leading whitespace. We have to reimplement char * next = strtok(text, "\n"); while (next != NULL){ diff --git a/tools/lib/vidindex/vidindex.c b/tools/lib/vidindex/vidindex.c index a8d53d947e..4857c60dd2 100644 --- a/tools/lib/vidindex/vidindex.c +++ b/tools/lib/vidindex/vidindex.c @@ -18,7 +18,7 @@ static uint32_t read24be(const uint8_t* ptr) { } static void write32le(FILE *of, uint32_t v) { uint8_t va[4] = { - v & 0xff, (v >> 8) & 0xff, (v >> 16) & 0xff, (v >> 24) & 0xff + v & 0xff, (v >> 8) & 0xff, (v >> 16) & 0xff, (v >> 24) & 0xff }; fwrite(va, 1, sizeof(va), of); } @@ -135,7 +135,7 @@ static void hevc_index(const uint8_t *data, size_t file_size, FILE *of_prefix, F bs_get(&bs, 1); } uint32_t slice_type = bs_ue(&bs); - + // write the index write32le(of_index, slice_type); write32le(of_index, ptr - data); @@ -244,7 +244,7 @@ static void h264_index(const uint8_t *data, size_t file_size, FILE *of_prefix, F uint32_t pic_parameter_set_id = bs_ue(&bs); uint32_t frame_num = bs_get(&bs, sps_log2_max_frame_num_minus4+4); - + if (first_mb_in_slice == 0) { write32le(of_index, slice_type); write32le(of_index, ptr - data); diff --git a/tools/nui/FileReader.cpp b/tools/nui/FileReader.cpp index d52305b10e..fe360da98b 100644 --- a/tools/nui/FileReader.cpp +++ b/tools/nui/FileReader.cpp @@ -71,7 +71,7 @@ LogReader::LogReader(const QString& file, Events *events_, QReadWriteLock* event while (1) { mergeEvents(cdled.get()); } - }); + }); } void LogReader::mergeEvents(int dled) { diff --git a/tools/nui/Unlogger.cpp b/tools/nui/Unlogger.cpp index c217a06783..d48c607f45 100644 --- a/tools/nui/Unlogger.cpp +++ b/tools/nui/Unlogger.cpp @@ -4,7 +4,7 @@ #include #include -// include the dynamic struct +// include the dynamic struct #include "cereal/gen/cpp/car.capnp.c++" #include "cereal/gen/cpp/log.capnp.c++" @@ -24,7 +24,7 @@ static inline uint64_t nanos_since_boot() { } -Unlogger::Unlogger(Events *events_, QReadWriteLock* events_lock_, QMap *frs_, int seek) +Unlogger::Unlogger(Events *events_, QReadWriteLock* events_lock_, QMap *frs_, int seek) : events(events_), events_lock(events_lock_), frs(frs_) { ctx = Context::create(); YAML::Node service_list = YAML::LoadFile("../../cereal/service_list.yaml"); diff --git a/tools/nui/main.cpp b/tools/nui/main.cpp index c05275542f..46dab5dff6 100644 --- a/tools/nui/main.cpp +++ b/tools/nui/main.cpp @@ -44,7 +44,7 @@ class Window : public QWidget { QMap lrs; QMap frs; - + // cache the bar QPixmap *px = NULL; @@ -72,7 +72,7 @@ Window::Window(QString route_, int seek, int use_api_) : route(route_), use_api( file.open(QIODevice::ReadOnly | QIODevice::Text); settings = file.readAll(); file.close(); - + QJsonDocument sd = QJsonDocument::fromJson(settings.toUtf8()); qWarning() << sd.isNull(); // <- print false :) QJsonObject sett2 = sd.object(); @@ -97,7 +97,7 @@ bool Window::addSegment(int i) { lrs.insert(i, new LogReader(fn, &events, &events_lock, &unlogger->eidx)); } else { QString log_fn = this->log_paths.at(i).toString(); - lrs.insert(i, new LogReader(log_fn, &events, &events_lock, &unlogger->eidx)); + lrs.insert(i, new LogReader(log_fn, &events, &events_lock, &unlogger->eidx)); } @@ -114,8 +114,8 @@ bool Window::addSegment(int i) { QString camera_fn = this->camera_paths.at(i).toString(); frs.insert(i, new FrameReader(qPrintable(camera_fn))); } - - + + return true; } return false; @@ -193,9 +193,9 @@ void Window::paintEvent(QPaintEvent *event) { tt.drawLine(lt, 300-lvv, rt, 300-vv); if (enabled) { - tt.setPen(Qt::green); + tt.setPen(Qt::green); } else { - tt.setPen(Qt::blue); + tt.setPen(Qt::blue); } tt.drawLine(rt, 300, rt, 600); @@ -237,7 +237,7 @@ int main(int argc, char *argv[]) { QApplication app(argc, argv); QString route(argv[1]); - + int use_api = QString::compare(QString("use_api"), route, Qt::CaseInsensitive) == 0; int seek = QString(argv[2]).toInt(); printf("seek: %d\n", seek); @@ -251,7 +251,7 @@ int main(int argc, char *argv[]) { } Window window(route, seek, use_api); - + window.resize(1920, 800); window.setWindowTitle("nui unlogger"); window.show(); diff --git a/tools/nui/nui b/tools/nui/nui index 35d3cfa68f..5214802156 100755 --- a/tools/nui/nui +++ b/tools/nui/nui @@ -9,4 +9,3 @@ if [ $# -gt 0 ]; then else echo "Please Enter a Route" fi - \ No newline at end of file diff --git a/tools/sim/README.md b/tools/sim/README.md index 8277ab1f10..4b64d4a8d2 100644 --- a/tools/sim/README.md +++ b/tools/sim/README.md @@ -10,24 +10,24 @@ git clone https://github.com/commaai/openpilot.git # Add export PYTHONPATH=$HOME/openpilot to your bashrc # Have a working tensorflow+keras in python3.7.3 (with [packages] in openpilot/Pipfile) ``` -## Install (in tab 1) +## Install (in tab 1) ``` cd ~/openpilot/tools/sim ./start_carla.sh # install CARLA 0.9.7 and start the server ``` -## openpilot (in tab 2) +## openpilot (in tab 2) ``` cd ~/openpilot/selfdrive/ PASSIVE=0 NOBOARD=1 ./manager.py ``` -## bridge (in tab 3) +## bridge (in tab 3) ``` # links carla to openpilot, will "start the car" according to manager cd ~/openpilot/tools/sim ./bridge.py ``` -## Controls -Now you can control the simulator with the keys: +## Controls +Now you can control the simulator with the keys: 1: Cruise up 5 mph diff --git a/tools/sim/start_carla.sh b/tools/sim/start_carla.sh index 42c956c2f7..cc5e961b81 100755 --- a/tools/sim/start_carla.sh +++ b/tools/sim/start_carla.sh @@ -15,4 +15,4 @@ if [ ! -d carla ]; then fi cd carla -./CarlaUE4.sh +./CarlaUE4.sh diff --git a/tools/webcam/README.md b/tools/webcam/README.md index f03f811b35..e5589fbc5f 100644 --- a/tools/webcam/README.md +++ b/tools/webcam/README.md @@ -1,49 +1,49 @@ Run openpilot with webcam on PC/laptop ===================== -What's needed: -- Ubuntu 16.04 -- Python 3.7.3 -- GPU (recommended) -- Two USB webcams, at least 720p and 78 degrees FOV (e.g. Logitech C920/C615) -- [Car harness](https://comma.ai/shop/products/comma-car-harness) w/ black panda (or the outdated grey panda/giraffe combo) to connect to your car -- [Panda paw](https://comma.ai/shop/products/panda-paw) (or USB-A to USB-A cable) to connect panda to your computer -- Tape, Charger, ... -That's it! +What's needed: +- Ubuntu 16.04 +- Python 3.7.3 +- GPU (recommended) +- Two USB webcams, at least 720p and 78 degrees FOV (e.g. Logitech C920/C615) +- [Car harness](https://comma.ai/shop/products/comma-car-harness) w/ black panda (or the outdated grey panda/giraffe combo) to connect to your car +- [Panda paw](https://comma.ai/shop/products/panda-paw) (or USB-A to USB-A cable) to connect panda to your computer +- Tape, Charger, ... +That's it! -## Clone openpilot and install the requirements +## Clone openpilot and install the requirements ``` -cd ~ -git clone https://github.com/commaai/openpilot.git +cd ~ +git clone https://github.com/commaai/openpilot.git ``` -- Follow [this readme](https://github.com/commaai/openpilot/tree/master/tools) to install the requirements -- Add line "export PYTHONPATH=$HOME/openpilot" to your ~/.bashrc -- You also need to install tensorflow 2.2 and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 -- Install [OpenCL Driver](http://registrationcenter-download.intel.com/akdlm/irc_nas/vcp/15532/l_opencl_p_18.1.0.015.tgz) -- (Note: the code assumes cl platforms order to be 0.GPU/1.CPU when running clinfo; if reverse, change the -1 to -2 in selfdrive/modeld/modeld.cc#L130; helping us refactor this mess is encouraged) -- Install [OpenCV4](https://www.pyimagesearch.com/2018/08/15/how-to-install-opencv-4-on-ubuntu/) (ignore the Python part) +- Follow [this readme](https://github.com/commaai/openpilot/tree/master/tools) to install the requirements +- Add line "export PYTHONPATH=$HOME/openpilot" to your ~/.bashrc +- You also need to install tensorflow 2.2 and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 +- Install [OpenCL Driver](http://registrationcenter-download.intel.com/akdlm/irc_nas/vcp/15532/l_opencl_p_18.1.0.015.tgz) +- (Note: the code assumes cl platforms order to be 0.GPU/1.CPU when running clinfo; if reverse, change the -1 to -2 in selfdrive/modeld/modeld.cc#L130; helping us refactor this mess is encouraged) +- Install [OpenCV4](https://www.pyimagesearch.com/2018/08/15/how-to-install-opencv-4-on-ubuntu/) (ignore the Python part) -## Build openpilot for webcam +## Build openpilot for webcam ``` -cd ~/openpilot +cd ~/openpilot ``` -- check out selfdrive/camerad/cameras/camera_webcam.cc line72&146 before building if any camera is upside down +- check out selfdrive/camerad/cameras/camera_webcam.cc line72&146 before building if any camera is upside down ``` -scons use_webcam=1 -touch prebuilt +scons use_webcam=1 +touch prebuilt ``` -## Connect the hardwares -- Connect the road facing camera first, then the driver facing camera -- (default indexes are 1 and 2; can be modified in selfdrive/camerad/cameras/camera_webcam.cc) -- Connect your computer to panda +## Connect the hardwares +- Connect the road facing camera first, then the driver facing camera +- (default indexes are 1 and 2; can be modified in selfdrive/camerad/cameras/camera_webcam.cc) +- Connect your computer to panda -## GO +## GO ``` -cd ~/openpilot/tools/webcam -./accept_terms.py # accept the user terms so that thermald can detect the car started -cd ~/openpilot/selfdrive -PASSIVE=0 NOSENSOR=1 WEBCAM=1 ./manager.py +cd ~/openpilot/tools/webcam +./accept_terms.py # accept the user terms so that thermald can detect the car started +cd ~/openpilot/selfdrive +PASSIVE=0 NOSENSOR=1 WEBCAM=1 ./manager.py ``` -- Start the car, then the UI should show the road webcam's view -- Adjust and secure the webcams (you can run tools/webcam/front_mount_helper.py to help mount the driver camera) -- Finish calibration and engage! +- Start the car, then the UI should show the road webcam's view +- Adjust and secure the webcams (you can run tools/webcam/front_mount_helper.py to help mount the driver camera) +- Finish calibration and engage! From 240041708450d916bb49ee229ee4cff0e5f5ab59 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 3 Jun 2020 13:47:47 -0700 Subject: [PATCH 203/656] vehicle model types (#1631) --- .pre-commit-config.yaml | 1 + selfdrive/controls/lib/vehicle_model.py | 166 ++++++++++++----------- selfdrive/debug/internal/test_paramsd.py | 3 +- 3 files changed, 87 insertions(+), 83 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index d6319e48e7..01b88ce1d0 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -15,6 +15,7 @@ repos: hooks: - id: mypy exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(opendbc)|(laika_repo)|(rednose_repo)/' + additional_dependencies: ['git+https://github.com/numpy/numpy-stubs'] - repo: https://github.com/PyCQA/flake8 rev: master hooks: diff --git a/selfdrive/controls/lib/vehicle_model.py b/selfdrive/controls/lib/vehicle_model.py index 85acca54d9..dc3d1f4b25 100755 --- a/selfdrive/controls/lib/vehicle_model.py +++ b/selfdrive/controls/lib/vehicle_model.py @@ -14,83 +14,12 @@ A depends on longitudinal speed, u [m/s], and vehicle parameters CP """ import numpy as np from numpy.linalg import solve +from typing import Tuple +from cereal import car -def create_dyn_state_matrices(u, VM): - """Returns the A and B matrix for the dynamics system - - Args: - u: Vehicle speed [m/s] - VM: Vehicle model - - Returns: - A tuple with the 2x2 A matrix, and 2x1 B matrix - - Parameters in the vehicle model: - cF: Tire stiffnes Front [N/rad] - cR: Tire stiffnes Front [N/rad] - aF: Distance from CG to front wheels [m] - aR: Distance from CG to rear wheels [m] - m: Mass [kg] - j: Rotational inertia [kg m^2] - sR: Steering ratio [-] - chi: Steer ratio rear [-] - """ - A = np.zeros((2, 2)) - B = np.zeros((2, 1)) - A[0, 0] = - (VM.cF + VM.cR) / (VM.m * u) - A[0, 1] = - (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.m * u) - u - A[1, 0] = - (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.j * u) - A[1, 1] = - (VM.cF * VM.aF**2 + VM.cR * VM.aR**2) / (VM.j * u) - B[0, 0] = (VM.cF + VM.chi * VM.cR) / VM.m / VM.sR - B[1, 0] = (VM.cF * VM.aF - VM.chi * VM.cR * VM.aR) / VM.j / VM.sR - return A, B - - -def kin_ss_sol(sa, u, VM): - """Calculate the steady state solution at low speeds - At low speeds the tire slip is undefined, so a kinematic - model is used. - - Args: - sa: Steering angle [rad] - u: Speed [m/s] - VM: Vehicle model - - Returns: - 2x1 matrix with steady state solution - """ - K = np.zeros((2, 1)) - K[0, 0] = VM.aR / VM.sR / VM.l * u - K[1, 0] = 1. / VM.sR / VM.l * u - return K * sa - - -def dyn_ss_sol(sa, u, VM): - """Calculate the steady state solution when x_dot = 0, - Ax + Bu = 0 => x = A^{-1} B u - - Args: - sa: Steering angle [rad] - u: Speed [m/s] - VM: Vehicle model - - Returns: - 2x1 matrix with steady state solution - """ - A, B = create_dyn_state_matrices(u, VM) - return -solve(A, B) * sa - - -def calc_slip_factor(VM): - """The slip factor is a measure of how the curvature changes with speed - it's positive for Oversteering vehicle, negative (usual case) otherwise. - """ - return VM.m * (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.l**2 * VM.cF * VM.cR) - - -class VehicleModel(): - def __init__(self, CP): +class VehicleModel: + def __init__(self, CP: car.CarParams): """ Args: CP: Car Parameters @@ -107,13 +36,13 @@ class VehicleModel(): self.cR_orig = CP.tireStiffnessRear self.update_params(1.0, CP.steerRatio) - def update_params(self, stiffness_factor, steer_ratio): + def update_params(self, stiffness_factor: float, steer_ratio: float) -> None: """Update the vehicle model with a new stiffness factor and steer ratio""" self.cF = stiffness_factor * self.cF_orig self.cR = stiffness_factor * self.cR_orig self.sR = steer_ratio - def steady_state_sol(self, sa, u): + def steady_state_sol(self, sa: float, u: float) -> np.ndarray: """Returns the steady state solution. If the speed is too small we can't use the dynamic model (tire slip is undefined), @@ -131,7 +60,7 @@ class VehicleModel(): else: return kin_ss_sol(sa, u, self) - def calc_curvature(self, sa, u): + def calc_curvature(self, sa: float, u: float) -> float: """Returns the curvature. Multiplied by the speed this will give the yaw rate. Args: @@ -143,7 +72,7 @@ class VehicleModel(): """ return self.curvature_factor(u) * sa / self.sR - def curvature_factor(self, u): + def curvature_factor(self, u: float) -> float: """Returns the curvature factor. Multiplied by wheel angle (not steering wheel angle) this will give the curvature. @@ -156,7 +85,7 @@ class VehicleModel(): sf = calc_slip_factor(self) return (1. - self.chi) / (1. - sf * u**2) / self.l - def get_steer_from_curvature(self, curv, u): + def get_steer_from_curvature(self, curv: float, u: float) -> float: """Calculates the required steering wheel angle for a given curvature Args: @@ -169,7 +98,7 @@ class VehicleModel(): return curv * self.sR * 1.0 / self.curvature_factor(u) - def get_steer_from_yaw_rate(self, yaw_rate, u): + def get_steer_from_yaw_rate(self, yaw_rate: float, u: float) -> float: """Calculates the required steering wheel angle for a given yaw_rate Args: @@ -182,7 +111,7 @@ class VehicleModel(): curv = yaw_rate / u return self.get_steer_from_curvature(curv, u) - def yaw_rate(self, sa, u): + def yaw_rate(self, sa: float, u: float) -> float: """Calculate yaw rate Args: @@ -193,3 +122,76 @@ class VehicleModel(): Yaw rate [rad/s] """ return self.calc_curvature(sa, u) * u + + +def kin_ss_sol(sa: float, u: float, VM: VehicleModel) -> np.ndarray: + """Calculate the steady state solution at low speeds + At low speeds the tire slip is undefined, so a kinematic + model is used. + + Args: + sa: Steering angle [rad] + u: Speed [m/s] + VM: Vehicle model + + Returns: + 2x1 matrix with steady state solution + """ + K = np.zeros((2, 1)) + K[0, 0] = VM.aR / VM.sR / VM.l * u + K[1, 0] = 1. / VM.sR / VM.l * u + return K * sa + + +def create_dyn_state_matrices(u: float, VM: VehicleModel) -> Tuple[np.ndarray, np.ndarray]: + """Returns the A and B matrix for the dynamics system + + Args: + u: Vehicle speed [m/s] + VM: Vehicle model + + Returns: + A tuple with the 2x2 A matrix, and 2x1 B matrix + + Parameters in the vehicle model: + cF: Tire stiffnes Front [N/rad] + cR: Tire stiffnes Front [N/rad] + aF: Distance from CG to front wheels [m] + aR: Distance from CG to rear wheels [m] + m: Mass [kg] + j: Rotational inertia [kg m^2] + sR: Steering ratio [-] + chi: Steer ratio rear [-] + """ + A = np.zeros((2, 2)) + B = np.zeros((2, 1)) + A[0, 0] = - (VM.cF + VM.cR) / (VM.m * u) + A[0, 1] = - (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.m * u) - u + A[1, 0] = - (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.j * u) + A[1, 1] = - (VM.cF * VM.aF**2 + VM.cR * VM.aR**2) / (VM.j * u) + B[0, 0] = (VM.cF + VM.chi * VM.cR) / VM.m / VM.sR + B[1, 0] = (VM.cF * VM.aF - VM.chi * VM.cR * VM.aR) / VM.j / VM.sR + return A, B + + +def dyn_ss_sol(sa: float, u: float, VM: VehicleModel) -> np.ndarray: + """Calculate the steady state solution when x_dot = 0, + Ax + Bu = 0 => x = A^{-1} B u + + Args: + sa: Steering angle [rad] + u: Speed [m/s] + VM: Vehicle model + + Returns: + 2x1 matrix with steady state solution + """ + A, B = create_dyn_state_matrices(u, VM) + return -solve(A, B) * sa + + +def calc_slip_factor(VM): + """The slip factor is a measure of how the curvature changes with speed + it's positive for Oversteering vehicle, negative (usual case) otherwise. + """ + return VM.m * (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.l**2 * VM.cF * VM.cR) diff --git a/selfdrive/debug/internal/test_paramsd.py b/selfdrive/debug/internal/test_paramsd.py index 3553949ac8..fa8c31ef1e 100755 --- a/selfdrive/debug/internal/test_paramsd.py +++ b/selfdrive/debug/internal/test_paramsd.py @@ -4,6 +4,7 @@ import numpy as np import math from tqdm import tqdm +from typing import cast import seaborn as sns import matplotlib.pyplot as plt @@ -34,7 +35,7 @@ speeds = 10 * np.sin(2 * np.pi * ts / 200.) + 25 angle_offsets = math.radians(1.0) * np.ones_like(ts) angle_offsets[ts > 60] = 0 -steering_angles = np.radians(5 * np.cos(2 * np.pi * ts / 100.)) +steering_angles = cast(np.ndarray, np.radians(5 * np.cos(2 * np.pi * ts / 100.))) xs = [] ys = [] From c76cf53175f0aab81ba9a0e08846d2f549361c92 Mon Sep 17 00:00:00 2001 From: George Hotz Date: Wed, 3 Jun 2020 13:51:42 -0700 Subject: [PATCH 204/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index cc14179697..46728e7e3b 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit cc14179697fac4757daeaa7968ac29d490204693 +Subproject commit 46728e7e3b47cf73586e33540dc0b65317e308ce From 73db0791997efa270f6793b7acb422aedc22d21f Mon Sep 17 00:00:00 2001 From: Jafar Al-Gharaibeh Date: Wed, 3 Jun 2020 16:01:32 -0500 Subject: [PATCH 205/656] Fix rounding of minSteerSpeed in events (#1620) I thought I was missing a rounding in Mazda code, but it turned out to be a missing rounding after the recent event refactoring Python3 interpreter: >>> print(" %d %d" % (1.6,1.4)) 1 1 >>> print(" %d %d" % (round(1.6),round(1.4))) 2 1 >>> print(" %d %d" % (int(round(1.6)),round(1.4))) 2 1 >>> print(" %d %d" % (int(round(1.6)),int(round(1.4)))) 2 1 Signed-off-by: Jafar Al-Gharaibeh --- selfdrive/car/mazda/interface.py | 2 +- selfdrive/controls/lib/events.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 20ddf5ae94..059d734153 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -44,7 +44,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kf = 0.00006 # No steer below disable speed - ret.minSteerSpeed = round(LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS) + ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS ret.centerToFront = ret.wheelbase * 0.41 diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index ff97a6bbd5..3e8f985fe7 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -161,7 +161,7 @@ class EngagementAlert(Alert): audible_alert, .2, 0., 0.), def below_steer_speed_alert(CP, sm, metric): - speed = CP.minSteerSpeed * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH) + speed = int(round(CP.minSteerSpeed * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH))) unit = "kph" if metric else "mph" return Alert( "TAKE CONTROL", From 4e7fe3a9ec4fddd517ea470af3b7eb3a6fd415e3 Mon Sep 17 00:00:00 2001 From: George Hotz Date: Wed, 3 Jun 2020 14:18:42 -0700 Subject: [PATCH 206/656] save valid_len --- cereal | 2 +- selfdrive/modeld/models/driving.cc | 85 +++++++++++++++--------------- 2 files changed, 44 insertions(+), 43 deletions(-) diff --git a/cereal b/cereal index 46728e7e3b..7dcbf6c41f 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 46728e7e3b47cf73586e33540dc0b65317e308ce +Subproject commit 7dcbf6c41fb30b85dbb597fe771dc9f5e7f29161 diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 3b14199867..1940667d80 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -175,7 +175,7 @@ void fill_path(cereal::ModelData::PathData::Builder path, const float * data, bo float valid_len; // clamp to 5 and 192 - valid_len = fmin(192, fmax(5, data[MODEL_PATH_DISTANCE*2])); + valid_len = fmin(192, fmax(5, data[MODEL_PATH_DISTANCE*2])); for (int i=0; i(); - event.setLogMonoTime(nanos_since_boot()); - - auto framed = event.initModel(); - framed.setFrameId(frame_id); - framed.setTimestampEof(timestamp_eof); - - auto lpath = framed.initPath(); - fill_path(lpath, net_outputs.path, false, 0); - auto left_lane = framed.initLeftLane(); - fill_path(left_lane, net_outputs.left_lane, true, 1.8); - auto right_lane = framed.initRightLane(); - fill_path(right_lane, net_outputs.right_lane, true, -1.8); - auto longi = framed.initLongitudinal(); - fill_longi(longi, net_outputs.long_x, net_outputs.long_v, net_outputs.long_a); - - - // Find the distribution that corresponds to the current lead - int mdn_max_idx = 0; - int t_offset = 0; - for (int i=1; i net_outputs.lead[mdn_max_idx*MDN_GROUP_SIZE + 8 + t_offset]) { - mdn_max_idx = i; - } + // make msg + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + + auto framed = event.initModel(); + framed.setFrameId(frame_id); + framed.setTimestampEof(timestamp_eof); + + auto lpath = framed.initPath(); + fill_path(lpath, net_outputs.path, false, 0); + auto left_lane = framed.initLeftLane(); + fill_path(left_lane, net_outputs.left_lane, true, 1.8); + auto right_lane = framed.initRightLane(); + fill_path(right_lane, net_outputs.right_lane, true, -1.8); + auto longi = framed.initLongitudinal(); + fill_longi(longi, net_outputs.long_x, net_outputs.long_v, net_outputs.long_a); + + + // Find the distribution that corresponds to the current lead + int mdn_max_idx = 0; + int t_offset = 0; + for (int i=1; i net_outputs.lead[mdn_max_idx*MDN_GROUP_SIZE + 8 + t_offset]) { + mdn_max_idx = i; } - auto lead = framed.initLead(); - fill_lead(lead, net_outputs.lead, mdn_max_idx, t_offset); - // Find the distribution that corresponds to the lead in 2s - mdn_max_idx = 0; - t_offset = 1; - for (int i=1; i net_outputs.lead[mdn_max_idx*MDN_GROUP_SIZE + 8 + t_offset]) { - mdn_max_idx = i; - } + } + auto lead = framed.initLead(); + fill_lead(lead, net_outputs.lead, mdn_max_idx, t_offset); + // Find the distribution that corresponds to the lead in 2s + mdn_max_idx = 0; + t_offset = 1; + for (int i=1; i net_outputs.lead[mdn_max_idx*MDN_GROUP_SIZE + 8 + t_offset]) { + mdn_max_idx = i; } - auto lead_future = framed.initLeadFuture(); - fill_lead(lead_future, net_outputs.lead, mdn_max_idx, t_offset); + } + auto lead_future = framed.initLeadFuture(); + fill_lead(lead_future, net_outputs.lead, mdn_max_idx, t_offset); - auto meta = framed.initMeta(); - fill_meta(meta, net_outputs.meta); + auto meta = framed.initMeta(); + fill_meta(meta, net_outputs.meta); - pm.send("model", msg); - } + pm.send("model", msg); +} void posenet_publish(PubMaster &pm, uint32_t frame_id, const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { From f19d25dd8d3e521fab82195027cc08cd08cb80d8 Mon Sep 17 00:00:00 2001 From: George Hotz Date: Wed, 3 Jun 2020 14:22:45 -0700 Subject: [PATCH 207/656] calloc an extra byte in read_file --- selfdrive/common/util.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/selfdrive/common/util.c b/selfdrive/common/util.c index 9bdb23f999..1aed0eaae6 100644 --- a/selfdrive/common/util.c +++ b/selfdrive/common/util.c @@ -19,7 +19,9 @@ void* read_file(const char* path, size_t* out_len) { long f_len = ftell(f); rewind(f); - char* buf = (char*)calloc(f_len, 1); + // calloc one extra byte so the file will always be NULL terminated + // cl_cached_program_from_file relies on this + char* buf = (char*)calloc(f_len+1, 1); assert(buf); size_t num_read = fread(buf, f_len, 1, f); From eebdf52ff57857171c55df3cdc10f64adc2ad039 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Wed, 3 Jun 2020 15:18:30 -0700 Subject: [PATCH 208/656] add Rav4_TSS2 engine fw --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 7ff2265eb7..25366774a7 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -715,6 +715,7 @@ FW_VERSIONS = { b'\x01896634A19000\x00\x00\x00\x00', b'\x01896634A22000\x00\x00\x00\x00', b'\x018966342U4000\x00\x00\x00\x00', + b'\x018966342T9000\x00\x00\x00\x00', b'\x01F152642551\x00\x00\x00\x00\x00\x00', b'\x028966342Y8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', b'\x02896634A18000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', From 367155168a0c9fb698c8248a5c28c66c2987ae65 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Wed, 3 Jun 2020 16:13:34 -0700 Subject: [PATCH 209/656] Update Flake8 config (#1624) * update flake8 checks * add E502 * no whitespace warnings * fix violations * no W391 Co-authored-by: Jason Young --- .pre-commit-config.yaml | 5 +++-- selfdrive/athena/test_helpers.py | 2 +- selfdrive/car/chrysler/values.py | 2 ++ selfdrive/car/ford/values.py | 2 ++ selfdrive/car/gm/values.py | 2 ++ selfdrive/car/honda/carstate.py | 6 ++++-- selfdrive/car/honda/values.py | 2 ++ selfdrive/car/hyundai/carstate.py | 3 ++- selfdrive/car/hyundai/values.py | 2 ++ selfdrive/car/isotp_parallel_query.py | 3 ++- selfdrive/car/mazda/values.py | 2 ++ selfdrive/car/nissan/values.py | 2 ++ selfdrive/car/subaru/values.py | 2 ++ selfdrive/car/toyota/values.py | 2 ++ selfdrive/car/volkswagen/values.py | 2 ++ selfdrive/controls/tests/test_monitoring.py | 2 ++ selfdrive/debug/compare_fingerprints.py | 1 + selfdrive/locationd/locationd.py | 3 ++- selfdrive/locationd/models/gnss_kf.py | 3 ++- selfdrive/modeld/test/polyfit/test.py | 2 ++ selfdrive/test/longitudinal_maneuvers/plant.py | 3 ++- selfdrive/test/openpilotci_upload.py | 4 +++- selfdrive/test/test_car_models.py | 3 ++- selfdrive/thermald/thermald.py | 3 ++- selfdrive/updated.py | 3 ++- selfdrive/version.py | 3 ++- tools/lib/auth_config.py | 2 +- tools/lib/logreader.py | 3 ++- tools/replay/ui.py | 3 ++- tools/replay/unlog_segment.py | 2 +- 30 files changed, 60 insertions(+), 19 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 01b88ce1d0..840b263ee3 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -20,9 +20,10 @@ repos: rev: master hooks: - id: flake8 - exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(opendbc)|(laika_repo)|(rednose_repo)/' + exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(opendbc)|(laika_repo)|(rednose_repo)|(selfdrive/debug)/' args: - - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E265,E266,E302,E305,E402,E501,E722,E741,W504,W391 + - --select=E112,E113,E304,E501,E502,E701,E702,E703,E71,E72,E731,W191,W6 + - --max-line-length=240 - --statistics - repo: local hooks: diff --git a/selfdrive/athena/test_helpers.py b/selfdrive/athena/test_helpers.py index 2919de6637..77a94c0787 100644 --- a/selfdrive/athena/test_helpers.py +++ b/selfdrive/athena/test_helpers.py @@ -46,7 +46,7 @@ class MockParams(): def __init__(self): self.params = { "DongleId": b"0000000000000000", - "GithubSshKeys": b"ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAABAQC307aE+nuHzTAgaJhzSf5v7ZZQW9gaperjhCmyPyl4PzY7T1mDGenTlVTN7yoVFZ9UfO9oMQqo0n1OwDIiqbIFxqnhrHU0cYfj88rI85m5BEKlNu5RdaVTj1tcbaPpQc5kZEolaI1nDDjzV0lwS7jo5VYDHseiJHlik3HH1SgtdtsuamGR2T80q1SyW+5rHoMOJG73IH2553NnWuikKiuikGHUYBd00K1ilVAK2xSiMWJp55tQfZ0ecr9QjEsJ+J/efL4HqGNXhffxvypCXvbUYAFSddOwXUPo5BTKevpxMtH+2YrkpSjocWA04VnTYFiPG6U4ItKmbLOTFZtPzoez private" + "GithubSshKeys": b"ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAABAQC307aE+nuHzTAgaJhzSf5v7ZZQW9gaperjhCmyPyl4PzY7T1mDGenTlVTN7yoVFZ9UfO9oMQqo0n1OwDIiqbIFxqnhrHU0cYfj88rI85m5BEKlNu5RdaVTj1tcbaPpQc5kZEolaI1nDDjzV0lwS7jo5VYDHseiJHlik3HH1SgtdtsuamGR2T80q1SyW+5rHoMOJG73IH2553NnWuikKiuikGHUYBd00K1ilVAK2xSiMWJp55tQfZ0ecr9QjEsJ+J/efL4HqGNXhffxvypCXvbUYAFSddOwXUPo5BTKevpxMtH+2YrkpSjocWA04VnTYFiPG6U4ItKmbLOTFZtPzoez private" # noqa: E501 } def get(self, k, encoding=None): diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 9af22c07a1..5c91445da9 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -1,3 +1,5 @@ +# flake8: noqa + from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 191f06cbc8..7c4d0aed98 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -1,3 +1,5 @@ +# flake8: noqa + from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index c2bc7e01e1..cb77b09705 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -1,3 +1,5 @@ +# flake8: noqa + from cereal import car from selfdrive.car import dbc_dict Ecu = car.CarParams.Ecu diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 8635831db1..c8360d756e 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -184,7 +184,8 @@ class CarState(CarStateBase): self.prev_cruise_setting = self.cruise_setting # ******************* parse out can ******************* - if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT): # TODO: find wheels moving bit in dbc + # TODO: find wheels moving bit in dbc + if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT): ret.standstill = cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] < 0.1 ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]['DRIVERS_DOOR_OPEN']) elif self.CP.carFingerprint == CAR.ODYSSEY_CHN: @@ -233,7 +234,8 @@ class CarState(CarStateBase): ret.rightBlinker = cp.vl["SCM_FEEDBACK"]['RIGHT_BLINKER'] != 0 self.brake_hold = cp.vl["VSA_STATUS"]['BRAKE_HOLD_ACTIVE'] - if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT): + if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, + CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT): self.park_brake = cp.vl["EPB_STATUS"]['EPB_STATE'] != 0 main_on = cp.vl["SCM_FEEDBACK"]['MAIN_ON'] elif self.CP.carFingerprint == CAR.ODYSSEY_CHN: diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 1901eaf579..2deed083a7 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -1,3 +1,5 @@ +# flake8: noqa + from cereal import car from selfdrive.car import dbc_dict diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 57435eadbe..f252ce7911 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -59,7 +59,8 @@ class CarState(CarStateBase): ret.gasPressed = bool(cp.vl["EMS16"]["CF_Ems_AclAct"]) # TODO: refactor gear parsing in function - # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, as this seems to be standard over all cars, but is not the preferred method. + # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, + # as this seems to be standard over all cars, but is not the preferred method. if self.CP.carFingerprint in FEATURES["use_cluster_gears"]: if cp.vl["CLU15"]["CF_Clu_InhibitD"] == 1: ret.gearShifter = GearShifter.drive diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 777ddb39d4..64b776685a 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1,3 +1,5 @@ +# flake8: noqa + from cereal import car from selfdrive.car import dbc_dict Ecu = car.CarParams.Ecu diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py index cda36d50fb..c5185dec5c 100644 --- a/selfdrive/car/isotp_parallel_query.py +++ b/selfdrive/car/isotp_parallel_query.py @@ -82,7 +82,8 @@ class IsoTpParallelQuery(): id_addr = rx_addr or tx_addr[0] sub_addr = tx_addr[1] - can_client = CanClient(self._can_tx, partial(self._can_rx, id_addr, sub_addr=sub_addr), tx_addr[0], rx_addr, self.bus, sub_addr=sub_addr, debug=self.debug) + can_client = CanClient(self._can_tx, partial(self._can_rx, id_addr, sub_addr=sub_addr), tx_addr[0], rx_addr, + self.bus, sub_addr=sub_addr, debug=self.debug) max_len = 8 if sub_addr is None else 7 diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 491fa72c8a..c6268e95a0 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -1,3 +1,5 @@ +# flake8: noqa + from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index ccd88954cc..0630a8cb94 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -1,3 +1,5 @@ +# flake8: noqa + from selfdrive.car import dbc_dict STEER_THRESHOLD = 1.0 diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index b75fa9c386..8d50b36ab4 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -1,3 +1,5 @@ +# flake8: noqa + from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 25366774a7..641c00e20a 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1,3 +1,5 @@ +# flake8: noqa + from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 30c32b6080..3937a7c154 100644 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -1,3 +1,5 @@ +# flake8: noqa + from selfdrive.car import dbc_dict class CarControllerParams: diff --git a/selfdrive/controls/tests/test_monitoring.py b/selfdrive/controls/tests/test_monitoring.py index 0753300bf6..b653555f6a 100644 --- a/selfdrive/controls/tests/test_monitoring.py +++ b/selfdrive/controls/tests/test_monitoring.py @@ -1,3 +1,5 @@ +# flake8: noqa + import unittest import numpy as np from cereal import car diff --git a/selfdrive/debug/compare_fingerprints.py b/selfdrive/debug/compare_fingerprints.py index a0c80a740e..5b7ba58b1e 100755 --- a/selfdrive/debug/compare_fingerprints.py +++ b/selfdrive/debug/compare_fingerprints.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +# flake8: noqa # put 2 fingeprints and print the diffs f1 = { diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 959684e1b6..3b78a0ca66 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -95,7 +95,8 @@ class Localizer(): device_from_ecef = rot_from_quat(predicted_state[States.ECEF_ORIENTATION]).T vel_device = device_from_ecef.dot(vel_ecef) device_from_ecef_eul = euler_from_quat(predicted_state[States.ECEF_ORIENTATION]).T - idxs = list(range(States.ECEF_ORIENTATION_ERR.start, States.ECEF_ORIENTATION_ERR.stop)) + list(range(States.ECEF_VELOCITY_ERR.start, States.ECEF_VELOCITY_ERR.stop)) + idxs = list(range(States.ECEF_ORIENTATION_ERR.start, States.ECEF_ORIENTATION_ERR.stop)) + \ + list(range(States.ECEF_VELOCITY_ERR.start, States.ECEF_VELOCITY_ERR.stop)) condensed_cov = predicted_cov[idxs][:, idxs] HH = H(*list(np.concatenate([device_from_ecef_eul, vel_ecef]))) vel_device_cov = HH.dot(condensed_cov).dot(HH.T) diff --git a/selfdrive/locationd/models/gnss_kf.py b/selfdrive/locationd/models/gnss_kf.py index db1a7e81a5..3f4baab7b5 100755 --- a/selfdrive/locationd/models/gnss_kf.py +++ b/selfdrive/locationd/models/gnss_kf.py @@ -119,7 +119,8 @@ class GNSSKalman(): self.dim_state = self.x_initial.shape[0] # init filter - self.filter = EKF_sym(generated_dir, self.name, self.Q, self.x_initial, self.P_initial, self.dim_state, self.dim_state, maha_test_kinds=self.maha_test_kinds) + self.filter = EKF_sym(generated_dir, self.name, self.Q, self.x_initial, self.P_initial, self.dim_state, + self.dim_state, maha_test_kinds=self.maha_test_kinds) self.init_state(GNSSKalman.x_initial, covs=GNSSKalman.P_initial) @property diff --git a/selfdrive/modeld/test/polyfit/test.py b/selfdrive/modeld/test/polyfit/test.py index 0caadf352a..82776e81ef 100644 --- a/selfdrive/modeld/test/polyfit/test.py +++ b/selfdrive/modeld/test/polyfit/test.py @@ -1,3 +1,5 @@ +# flake8: noqa + import numpy as np pts = np.array([3.1261718, 3.1642578, 3.0548828, 3.1125, 3.190625, 3.01875, 2.9816406, 3.1222656, 2.9728515, 2.9826171, 3.034375, 3.0392578, 3.1642578, 3.0792968, 3.0011718, 3.0705078, 2.9904296, 3.0089843, 3.0597656, 3.0978515, 2.9210937, 2.9992187, 2.9474609, 2.9621093, 2.9289062, 2.89375, 2.7975585, 2.9015625, 2.8175781, 2.9132812, 2.8175781, 2.7501953, 2.8332031, 2.8166015, 2.7638671, 2.8878906, 2.7599609, 2.6999023, 2.6720703, 2.6398437, 2.7243164, 2.6120117, 2.6588867, 2.5558593, 2.5978515, 2.5485351, 2.4269531, 2.5001953, 2.4855468, 2.4367187, 2.2973144, 2.2812011, 2.2890136, 2.39375, 2.2836425, 2.3815429, 2.2138183, 2.1964843, 2.1840332, 2.1759765, 2.0421875, 2.1034667, 2.0281494, 2.0880859, 1.9706542, 1.9276855, 1.8522155, 1.8991821, 1.7780273, 1.8180053, 1.8326843, 1.8270385, 1.7182128, 1.6439941, 1.5360839, 1.68385, 1.4584472, 1.5955322, 1.6002929, 1.4157226, 1.4704101, 1.2936523, 1.2990234, 1.4281738, 1.4357421, 1.409375, 1.2511718, 1.2194335, 1.1554687, 1.043164, 1.0954101, 1.0392578, 1.0895507, 1.0880859, 0.897168, 0.83369142, 0.86494142, 0.87763673, 0.85322267, 0.72968751, 0.57832032, 0.73066407, 0.78828126, 0.69160157, 0.64375, 0.5919922, 0.5529297, 0.52070314, 0.60957032, 0.51093751, 0.3576172, 0.49921876, 0.284375, 0.21992187, 0.25214845, 0.30683595, 0.30976564, 0.2716797, 0.22089843, 0.25507814, 0.084179685, 0.071484372, 0.1828125, 0.15644531, 0.13789062, 0.054882813, 0.021679688, -0.091601565, -0.0203125, -0.13359375, -0.037890624, -0.29765624, -0.15605469, -0.30351561, -0.055468749, -0.22148438, -0.246875, -0.31718749, -0.25468749, -0.35234374, -0.16484375, -0.56523436, -0.56523436, -0.39921874, -0.58671874, -0.45585936, -0.50859374, -0.44023436, -0.42656249, -0.56328124, -0.70195311, -0.403125, -0.76445311, -0.98710936, -0.7625, -0.75273436, -0.825, -0.996875, -0.86210936, -0.99492186, -0.85625, -0.88359374, -0.97148436, -1.0320313, -1.1609375, -1.1296875, -1.0203125, -1.0691407, -1.2371094, -1.1277344, -1.2214844, -1.1921875, -1.2996094, -1.2917969, -1.3699219, -1.434375, -1.3699219, -1.3601563, -1.5730469, -1.3152344, -1.4851563, -1.48125, -1.5925782, -1.746875, -1.5847657, -1.6003907, -1.5984375, -1.7703125, -1.8328125, -1.8152344, -1.9714844, -1.9421875]) diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index f8c265d07f..3447f119fc 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -239,7 +239,8 @@ class Plant(): # print at 5hz if (self.frame % (self.rate//5)) == 0: - print("%6.2f m %6.2f m/s %6.2f m/s2 %.2f ang gas: %.2f brake: %.2f steer: %5.2f lead_rel: %6.2f m %6.2f m/s" % (distance, speed, acceleration, self.angle_steer, gas, brake, steer_torque, d_rel, v_rel)) + print("%6.2f m %6.2f m/s %6.2f m/s2 %.2f ang gas: %.2f brake: %.2f steer: %5.2f lead_rel: %6.2f m %6.2f m/s" + % (distance, speed, acceleration, self.angle_steer, gas, brake, steer_torque, d_rel, v_rel)) # ******** publish the car ******** vls_tuple = namedtuple('vls', [ diff --git a/selfdrive/test/openpilotci_upload.py b/selfdrive/test/openpilotci_upload.py index 177f854bfd..64391532f9 100755 --- a/selfdrive/test/openpilotci_upload.py +++ b/selfdrive/test/openpilotci_upload.py @@ -8,7 +8,9 @@ def upload_file(path, name): from azure.storage.blob import BlockBlobService sas_token = os.getenv("TOKEN", None) if sas_token is None: - sas_token = subprocess.check_output("az storage container generate-sas --account-name commadataci --name openpilotci --https-only --permissions lrw --expiry $(date -u '+%Y-%m-%dT%H:%M:%SZ' -d '+1 hour') --auth-mode login --as-user --output tsv", shell=True).decode().strip("\n") + cmd = "az storage container generate-sas --account-name commadataci --name openpilotci --https-only --permissions \ + lrw --expiry $(date -u '+%Y-%m-%dT%H:%M:%SZ' -d '+1 hour') --auth-mode login --as-user --output tsv" + sas_token = subprocess.check_output(cmd, shell=True).decode().strip("\n") service = BlockBlobService(account_name="commadataci", sas_token=sas_token) service.create_blob_from_path("openpilotci", name, path) return "https://commadataci.blob.core.windows.net/openpilotci/" + name diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index eb01c41bc9..5c8d900624 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -461,7 +461,8 @@ if __name__ == "__main__": # Start unlogger print("Start unlogger") unlogger_cmd = [os.path.join(BASEDIR, 'tools/replay/unlogger.py'), route, '/tmp'] - unlogger = subprocess.Popen(unlogger_cmd + ['--disable', 'frame,encodeIdx,plan,pathPlan,liveLongitudinalMpc,radarState,controlsState,liveTracks,liveMpc,sendcan,carState,carControl,carEvents,carParams', '--no-interactive'], preexec_fn=os.setsid) # pylint: disable=subprocess-popen-preexec-fn + disable_socks = 'frame,encodeIdx,plan,pathPlan,liveLongitudinalMpc,radarState,controlsState,liveTracks,liveMpc,sendcan,carState,carControl,carEvents,carParams' + unlogger = subprocess.Popen(unlogger_cmd + ['--disable', disable_socks, '--no-interactive'], preexec_fn=os.setsid) # pylint: disable=subprocess-popen-preexec-fn print("Check sockets") extra_socks = [] diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 5d97141cb2..4cbcc6fb42 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -17,7 +17,8 @@ from selfdrive.swaglog import cloudlog import cereal.messaging as messaging from selfdrive.loggerd.config import get_available_percent from selfdrive.pandad import get_expected_signature -from selfdrive.thermald.power_monitoring import PowerMonitoring, get_battery_capacity, get_battery_status, get_battery_current, get_battery_voltage, get_usb_present +from selfdrive.thermald.power_monitoring import PowerMonitoring, get_battery_capacity, get_battery_status, \ + get_battery_current, get_battery_voltage, get_usb_present FW_SIGNATURE = get_expected_signature() diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 9775df027e..47f2d55a59 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -280,7 +280,8 @@ def attempt_update(): upstream_hash = run(["git", "rev-parse", "@{u}"], OVERLAY_MERGED).rstrip() new_version = cur_hash != upstream_hash - git_fetch_result = len(git_fetch_output) > 0 and (git_fetch_output != "Failed to add the host to the list of known hosts (/data/data/com.termux/files/home/.ssh/known_hosts).\n") + err_msg = "Failed to add the host to the list of known hosts (/data/data/com.termux/files/home/.ssh/known_hosts).\n" + git_fetch_result = len(git_fetch_output) > 0 and (git_fetch_output != err_msg) cloudlog.info("comparing %s to %s" % (cur_hash, upstream_hash)) if new_version or git_fetch_result: diff --git a/selfdrive/version.py b/selfdrive/version.py index b45fe384bd..13a16022ac 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -67,7 +67,8 @@ try: dirty_files = subprocess.check_output(["git", "diff-index", branch, "--"], encoding='utf8') commit = subprocess.check_output(["git", "rev-parse", "--verify", "HEAD"], encoding='utf8').rstrip() origin_commit = subprocess.check_output(["git", "rev-parse", "--verify", branch], encoding='utf8').rstrip() - cloudlog.event("dirty comma branch", version=version, dirty=dirty, origin=origin, branch=branch, dirty_files=dirty_files, commit=commit, origin_commit=origin_commit) + cloudlog.event("dirty comma branch", version=version, dirty=dirty, origin=origin, branch=branch, + dirty_files=dirty_files, commit=commit, origin_commit=origin_commit) except subprocess.CalledProcessError: dirty = True diff --git a/tools/lib/auth_config.py b/tools/lib/auth_config.py index 68bd535993..1e604970ae 100644 --- a/tools/lib/auth_config.py +++ b/tools/lib/auth_config.py @@ -13,7 +13,7 @@ def get_token(): with open(os.path.join(CONFIG_DIR, 'auth.json')) as f: auth = json.load(f) return auth['access_token'] - except: + except Exception: raise MissingAuthConfigError('Authenticate with tools/lib/auth.py') def set_token(token): diff --git a/tools/lib/logreader.py b/tools/lib/logreader.py index 3a25ef21bc..4d08b8aaed 100755 --- a/tools/lib/logreader.py +++ b/tools/lib/logreader.py @@ -73,7 +73,8 @@ class MultiLogIterator(object): self._idx += 1 else: self._idx = 0 - self._current_log = next(i for i in range(self._current_log + 1, len(self._log_readers) + 1) if i == len(self._log_readers) or self._log_paths[i] is not None) + self._current_log = next(i for i in range(self._current_log + 1, len(self._log_readers) + 1) + if i == len(self._log_readers) or self._log_paths[i] is not None) # wraparound if self._current_log == len(self._log_readers): if self._wraparound: diff --git a/tools/replay/ui.py b/tools/replay/ui.py index 438f86f918..f0058989a7 100755 --- a/tools/replay/ui.py +++ b/tools/replay/ui.py @@ -66,7 +66,8 @@ def ui_thread(addr, frame_address): top_down_surface = pygame.surface.Surface((UP.lidar_x, UP.lidar_y), 0, 8) frame = messaging.sub_sock('frame', addr=addr, conflate=True) - sm = messaging.SubMaster(['carState', 'plan', 'carControl', 'radarState', 'liveCalibration', 'controlsState', 'liveTracks', 'model', 'liveMpc', 'liveParameters', 'pathPlan'], addr=addr) + sm = messaging.SubMaster(['carState', 'plan', 'carControl', 'radarState', 'liveCalibration', 'controlsState', + 'liveTracks', 'model', 'liveMpc', 'liveParameters', 'pathPlan'], addr=addr) calibration = None img = np.zeros((480, 640, 3), dtype='uint8') diff --git a/tools/replay/unlog_segment.py b/tools/replay/unlog_segment.py index 1c80cd0470..94520b3baa 100755 --- a/tools/replay/unlog_segment.py +++ b/tools/replay/unlog_segment.py @@ -102,6 +102,6 @@ if __name__ == "__main__": try: replay(args.segment, args.loop) termios.tcsetattr(sys.stdin, termios.TCSADRAIN, orig_settings) - except: + except Exception: termios.tcsetattr(sys.stdin, termios.TCSADRAIN, orig_settings) raise From f4e8df7ee6de2998968bfa93f09f2359ca21b89e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 3 Jun 2020 19:28:41 -0700 Subject: [PATCH 210/656] slow down upload check when offroad (#1634) --- selfdrive/loggerd/uploader.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index b479574b02..5b14bba8a8 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -256,8 +256,9 @@ def uploader_fn(exit_event): return d = uploader.next_file_to_upload(with_raw=allow_raw_upload and should_upload) - if d is None: - time.sleep(5) + if d is None: # Nothing to upload + offroad = params.get("IsOffroad") == b'1' + time.sleep(60 if offroad else 5) continue key, fn = d From 355159f04a7676b2c6a6ea1687211ba7bda428be Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 4 Jun 2020 14:09:37 -0700 Subject: [PATCH 211/656] pre-commit handles flake8 now --- .github/workflows/test.yaml | 4 +--- CONTRIBUTING.md | 2 +- Dockerfile.openpilot | 1 - flake8_openpilot.sh | 9 --------- 4 files changed, 2 insertions(+), 14 deletions(-) delete mode 100755 flake8_openpilot.sh diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index eb0499c32d..9dcbed9edb 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -36,7 +36,7 @@ jobs: external/bin selfdrive/modeld/runners $TEST_DIR # need these so docker copy won't fail - cp Pipfile Pipfile.lock flake8_openpilot.sh pylint_openpilot.sh .pylintrc \ + cp Pipfile Pipfile.lock pylint_openpilot.sh .pylintrc \ cppcheck_openpilot.sh .coveragerc-app .pre-commit-config.yaml $TEST_DIR cd $TEST_DIR mkdir laika laika_repo tools release @@ -73,8 +73,6 @@ jobs: submodules: true - name: Build Docker image run: eval "$BUILD" - - name: flake8 - run: $RUN "cd /tmp/openpilot/ && ./flake8_openpilot.sh" - name: pylint run: $RUN "cd /tmp/openpilot/ && ./pylint_openpilot.sh" - name: pre-commit diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index e101650d49..b8564c1e85 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -22,7 +22,7 @@ All PRs and commits are automatically checked by Github Actions. Check out `.git ### Code Style and Linting -Code is automatically checked for style by Github Actions as part of the automated tests. You can also run these tests yourself by running `pylint_openpilot.sh` and `flake8_openpilot.sh`. +Code is automatically checked for style by Github Actions as part of the automated tests. You can also run these tests yourself by running `pre-commit run --all`. ## Car Ports (openpilot) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 0ef6912418..d2956b8104 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -78,7 +78,6 @@ RUN mkdir -p /tmp/openpilot COPY SConstruct \ cppcheck_openpilot.sh \ - flake8_openpilot.sh \ pylint_openpilot.sh \ .pylintrc \ .pre-commit-config.yaml \ diff --git a/flake8_openpilot.sh b/flake8_openpilot.sh deleted file mode 100755 index a2d99655cf..0000000000 --- a/flake8_openpilot.sh +++ /dev/null @@ -1,9 +0,0 @@ -#!/usr/bin/env bash - -# only pyflakes check (--select=F) -RESULT=$(python3 -m flake8 --select=F $(eval echo $(cat <(find cereal) <(find opendbc) release/files_common release/files_common | tr '\n' ' ') | tr ' ' '\n' | grep "\.py$")) -if [[ $RESULT ]]; then - echo "Pyflakes found errors in the code. Please fix and try again" - echo "$RESULT" - exit 1 -fi From 966e2d41544a7ccbcf901355b8116734c448aa63 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 4 Jun 2020 14:19:10 -0700 Subject: [PATCH 212/656] pre-commit also handles pylint --- .github/workflows/test.yaml | 5 +---- Dockerfile.openpilot | 1 - pylint_openpilot.sh | 11 ----------- 3 files changed, 1 insertion(+), 16 deletions(-) delete mode 100755 pylint_openpilot.sh diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 9dcbed9edb..ced9fe65cc 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -36,8 +36,7 @@ jobs: external/bin selfdrive/modeld/runners $TEST_DIR # need these so docker copy won't fail - cp Pipfile Pipfile.lock pylint_openpilot.sh .pylintrc \ - cppcheck_openpilot.sh .coveragerc-app .pre-commit-config.yaml $TEST_DIR + cp Pipfile Pipfile.lock .pylintrc cppcheck_openpilot.sh .coveragerc-app .pre-commit-config.yaml $TEST_DIR cd $TEST_DIR mkdir laika laika_repo tools release - name: Build Docker image @@ -73,8 +72,6 @@ jobs: submodules: true - name: Build Docker image run: eval "$BUILD" - - name: pylint - run: $RUN "cd /tmp/openpilot/ && ./pylint_openpilot.sh" - name: pre-commit run: $RUN "cd /tmp/openpilot/ && git init && git add -A && pre-commit run --all" - name: cppcheck diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index d2956b8104..ec4ee189dc 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -78,7 +78,6 @@ RUN mkdir -p /tmp/openpilot COPY SConstruct \ cppcheck_openpilot.sh \ - pylint_openpilot.sh \ .pylintrc \ .pre-commit-config.yaml \ .coveragerc-app \ diff --git a/pylint_openpilot.sh b/pylint_openpilot.sh deleted file mode 100755 index 910c5cd09a..0000000000 --- a/pylint_openpilot.sh +++ /dev/null @@ -1,11 +0,0 @@ -#!/usr/bin/env bash - -python3 -m pylint --disable=R,C,W $(eval echo <(find cereal) <(find opendbc) $(cat release/files_common release/files_common | tr '\n' ' ') | tr ' ' '\n' | grep "\.py$") - -exit_status=$? -(( res = exit_status & 3 )) - -if [[ $res != 0 ]]; then - echo "Pylint found errors in the code. Please fix and try again" - exit 1 -fi From 7db4e5bd0573ff8ed0cdd841d909701f27886231 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 4 Jun 2020 14:27:54 -0700 Subject: [PATCH 213/656] update run_docker_tests.sh --- run_docker_tests.sh | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/run_docker_tests.sh b/run_docker_tests.sh index 92cd57b87a..f208ad1b9c 100755 --- a/run_docker_tests.sh +++ b/run_docker_tests.sh @@ -1,15 +1,16 @@ #!/bin/bash set -e +# NOTE: this may be not an up-to-date list of tests and checks, see .github/workflows/test.yaml for the current list of tests + SETUP="cd /tmp/openpilot && " BUILD="cd /tmp/openpilot && scons -c && scons -j$(nproc) && " RUN="docker run --shm-size 1G --rm tmppilot /bin/bash -c" docker build -t tmppilot -f Dockerfile.openpilot . -$RUN "$SETUP cd /tmp/openpilot/selfdrive/test/ && ./test_fingerprints.py" -$RUN "$SETUP ./flake8_openpilot.sh" -$RUN "$SETUP ./pylint_openpilot.sh" +$RUN "$SETUP cd selfdrive/test/ && ./test_fingerprints.py" +$RUN "$SETUP git init && git add -A && pre-commit run --all" $RUN "$BUILD python -m unittest discover common && \ python -m unittest discover opendbc/can && \ python -m unittest discover selfdrive/boardd && \ From 63c8e8439b6d19020055f922340d8e33d906363a Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 4 Jun 2020 18:57:25 -0700 Subject: [PATCH 214/656] Model + camerad test (#1622) * kind of works * move that * hack to get camerad to reliably terminate * not sure why SIGTERM wasn't working before * compare bytes * clean up some hacks * gitignore * fix that * WIP * no reboot * comparison works * pretty print * fix build * run in jenkins * python path * space * raise timeout * new eon * skip the copy * spinner * spin less * update model ref commit * reenable that * clean up * fix jenkinsfile * parallel * wrap it in a stage * fix linter * better progress * lower timeout Co-authored-by: Comma Device Co-authored-by: Adeeb Shihadeh --- Jenkinsfile | 30 +++-- SConstruct | 7 +- release/files_common | 1 - selfdrive/camerad/SConscript | 7 +- .../camerad/cameras/camera_frame_stream.cc | 10 +- selfdrive/camerad/main.cc | 16 +-- selfdrive/common/SConscript | 7 +- selfdrive/common/visionimg.cc | 2 +- selfdrive/test/.gitignore | 6 + selfdrive/test/openpilotci.py | 26 +++++ selfdrive/test/openpilotci_upload.py | 22 ---- selfdrive/test/phone_ci.py | 75 +++++++++++++ selfdrive/test/process_replay/.gitignore | 2 - .../test/process_replay/camera_replay.py | 103 ++++++++++++++++++ .../process_replay/model_replay_ref_commit | 1 + selfdrive/test/process_replay/update_model.py | 2 +- selfdrive/test/process_replay/update_refs.py | 2 +- tools/lib/auth_config.py | 6 +- 18 files changed, 271 insertions(+), 54 deletions(-) create mode 100644 selfdrive/test/openpilotci.py delete mode 100755 selfdrive/test/openpilotci_upload.py create mode 100755 selfdrive/test/phone_ci.py delete mode 100644 selfdrive/test/process_replay/.gitignore create mode 100755 selfdrive/test/process_replay/camera_replay.py create mode 100644 selfdrive/test/process_replay/model_replay_ref_commit diff --git a/Jenkinsfile b/Jenkinsfile index d34cd70375..b7d58cfd64 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -10,13 +10,29 @@ pipeline { COMMA_JWT = credentials('athena-test-jwt') } stages { - stage('EON Build/Test') { - steps { - lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_name', quantity: 1){ - timeout(time: 30, unit: 'MINUTES') { - dir(path: 'release') { - sh 'pip install paramiko' - sh 'python remote_build.py' + stage('Device Tests') { + parallel { + stage('Build/Test') { + steps { + lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_name', quantity: 1){ + timeout(time: 30, unit: 'MINUTES') { + dir(path: 'release') { + sh 'pip install paramiko' + sh 'python remote_build.py' + } + } + } + } + } + stage('Replay Tests') { + steps { + lock(resource: "", label: 'eon2', inversePrecedence: true, variable: 'eon_name', quantity: 1){ + timeout(time: 45, unit: 'MINUTES') { + dir(path: 'selfdrive/test') { + sh 'pip install paramiko' + sh 'python phone_ci.py' + } + } } } } diff --git a/SConstruct b/SConstruct index 285a1743b6..79304e29f6 100644 --- a/SConstruct +++ b/SConstruct @@ -18,6 +18,7 @@ if arch == "aarch64" and not os.path.isdir("/system"): arch = "larch64" webcam = bool(ARGUMENTS.get("use_webcam", 0)) +QCOM_REPLAY = arch == "aarch64" and os.getenv("QCOM_REPLAY") is not None if arch == "aarch64" or arch == "larch64": lenv = { @@ -56,6 +57,10 @@ if arch == "aarch64" or arch == "larch64": cxxflags = ["-DQCOM", "-mcpu=cortex-a57"] rpath = ["/system/vendor/lib64"] + if QCOM_REPLAY: + cflags += ["-DQCOM_REPLAY"] + cxxflags += ["-DQCOM_REPLAY"] + else: lenv = { "PATH": "#external/bin:" + os.environ['PATH'], @@ -179,7 +184,7 @@ def abspath(x): # still needed for apks zmq = 'zmq' -Export('env', 'arch', 'zmq', 'SHARED', 'webcam') +Export('env', 'arch', 'zmq', 'SHARED', 'webcam', 'QCOM_REPLAY') # cereal and messaging are shared with the system SConscript(['cereal/SConscript']) diff --git a/release/files_common b/release/files_common index 2ef07b565e..b41b511dd0 100644 --- a/release/files_common +++ b/release/files_common @@ -327,7 +327,6 @@ selfdrive/test/test_openpilot.py selfdrive/test/test_fingerprints.py selfdrive/test/test_car_models.py -selfdrive/test/process_replay/.gitignore selfdrive/test/process_replay/__init__.py selfdrive/test/process_replay/compare_logs.py selfdrive/test/process_replay/process_replay.py diff --git a/selfdrive/camerad/SConscript b/selfdrive/camerad/SConscript index 618df342c8..eeb3bcb931 100644 --- a/selfdrive/camerad/SConscript +++ b/selfdrive/camerad/SConscript @@ -1,10 +1,13 @@ -Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'webcam') +Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'webcam', 'QCOM_REPLAY') libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', cereal, messaging, 'czmq', 'zmq', 'capnp', 'kj', visionipc, gpucommon] if arch == "aarch64": libs += ['gsl', 'CB', 'adreno_utils', 'EGL', 'GLESv3', 'cutils', 'ui'] - cameras = ['cameras/camera_qcom.cc'] + if QCOM_REPLAY: + cameras = ['cameras/camera_frame_stream.cc'] + else: + cameras = ['cameras/camera_qcom.cc'] elif arch == "larch64": libs += [] cameras = ['cameras/camera_qcom2.c'] diff --git a/selfdrive/camerad/cameras/camera_frame_stream.cc b/selfdrive/camerad/cameras/camera_frame_stream.cc index 37045f4378..0a77eb1187 100644 --- a/selfdrive/camerad/cameras/camera_frame_stream.cc +++ b/selfdrive/camerad/cameras/camera_frame_stream.cc @@ -90,11 +90,11 @@ void run_frame_stream(DualCameraState *s) { CameraInfo cameras_supported[CAMERA_ID_MAX] = { [CAMERA_ID_IMX298] = { - .frame_width = FRAME_WIDTH, - .frame_height = FRAME_HEIGHT, - .frame_stride = FRAME_WIDTH*3, - .bayer = false, - .bayer_flip = false, + .frame_width = FRAME_WIDTH, + .frame_height = FRAME_HEIGHT, + .frame_stride = FRAME_WIDTH*3, + .bayer = false, + .bayer_flip = false, }, [CAMERA_ID_OV8865] = { .frame_width = 1632, diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index f914989ead..d65913bb46 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -2,7 +2,7 @@ #include #include -#ifdef QCOM +#if defined(QCOM) && !defined(QCOM_REPLAY) #include "cameras/camera_qcom.h" #elif QCOM2 #include "cameras/camera_qcom2.h" @@ -403,7 +403,7 @@ void* processing_thread(void *arg) { visionbuf_sync(&s->rgb_bufs[rgb_idx], VISIONBUF_SYNC_FROM_DEVICE); -#ifdef QCOM +#if defined(QCOM) && !defined(QCOM_REPLAY) /*FILE *dump_rgb_file = fopen("/tmp/process_dump.rgb", "wb"); fwrite(s->rgb_bufs[rgb_idx].addr, s->rgb_bufs[rgb_idx].len, sizeof(uint8_t), dump_rgb_file); fclose(dump_rgb_file); @@ -515,7 +515,7 @@ void* processing_thread(void *arg) { framed.setLensTruePos(frame_data.lens_true_pos); framed.setGainFrac(frame_data.gain_frac); -#ifdef QCOM +#if defined(QCOM) && !defined(QCOM_REPLAY) kj::ArrayPtr focus_vals(&s->cameras.rear.focus[0], NUM_FOCUS); kj::ArrayPtr focus_confs(&s->cameras.rear.confidence[0], NUM_FOCUS); framed.setFocusVal(focus_vals); @@ -1215,7 +1215,7 @@ void party(VisionState *s) { zsock_signal(s->terminate_pub, 0); -#ifndef QCOM2 +#if !defined(QCOM2) && !defined(QCOM_REPLAY) LOG("joining frontview_thread"); err = pthread_join(frontview_thread_handle, NULL); assert(err == 0); @@ -1255,7 +1255,7 @@ int main(int argc, char *argv[]) { init_buffers(s); -#if defined(QCOM) || defined(QCOM2) +#if (defined(QCOM) && !defined(QCOM_REPLAY)) || defined(QCOM2) s->pm = new PubMaster({"frame", "frontFrame", "thumbnail"}); #endif @@ -1263,9 +1263,9 @@ int main(int argc, char *argv[]) { party(s); -#if defined(QCOM) || defined(QCOM2) - delete s->pm; -#endif + if (s->pm != NULL) { + delete s->pm; + } free_buffers(s); cl_free(s); diff --git a/selfdrive/common/SConscript b/selfdrive/common/SConscript index 18f9fdf4a8..8ecf786ffe 100644 --- a/selfdrive/common/SConscript +++ b/selfdrive/common/SConscript @@ -1,4 +1,4 @@ -Import('env', 'arch', 'SHARED') +Import('env', 'arch', 'SHARED', 'QCOM_REPLAY') if SHARED: fxn = env.SharedLibrary @@ -21,8 +21,11 @@ if arch == "aarch64": files += [ 'framebuffer.cc', 'touch.c', - 'visionbuf_ion.c', ] + if QCOM_REPLAY: + files += ['visionbuf_cl.c'] + else: + files += ['visionbuf_ion.c'] _gpu_libs = ['gui', 'adreno_utils'] elif arch == "larch64": defines = {"CLU_NO_CACHE": None} diff --git a/selfdrive/common/visionimg.cc b/selfdrive/common/visionimg.cc index a533acb597..35fe7095d0 100644 --- a/selfdrive/common/visionimg.cc +++ b/selfdrive/common/visionimg.cc @@ -37,7 +37,7 @@ extern "C" void compute_aligned_width_and_height(int width, #endif void visionimg_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h) { -#ifdef QCOM +#if defined(QCOM) && !defined(QCOM_REPLAY) compute_aligned_width_and_height(ALIGN(width, 32), ALIGN(height, 32), 3, 0, 0, 512, aligned_w, aligned_h); #else *aligned_w = width; *aligned_h = height; diff --git a/selfdrive/test/.gitignore b/selfdrive/test/.gitignore index 96feaba0c2..eb8c79a61a 100644 --- a/selfdrive/test/.gitignore +++ b/selfdrive/test/.gitignore @@ -1,2 +1,8 @@ out/ docker_out/ + +process_replay/diff.txt +process_replay/model_diff.txt + +*.bz2 +*.hevc diff --git a/selfdrive/test/openpilotci.py b/selfdrive/test/openpilotci.py new file mode 100644 index 0000000000..be8aefac78 --- /dev/null +++ b/selfdrive/test/openpilotci.py @@ -0,0 +1,26 @@ +#!/usr/bin/env python3 +import os +import sys +import subprocess + +BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" + +def get_url(route_name, segment_num, log_type="rlog"): + ext = "hevc" if log_type in ["fcamera", "dcamera"] else "bz2" + return BASE_URL + "%s/%s/%s.%s" % (route_name.replace("|", "/"), segment_num, log_type, ext) + +def upload_file(path, name): + from azure.storage.blob import BlockBlobService + sas_token = os.getenv("TOKEN", None) + if sas_token is None: + sas_token = subprocess.check_output("az storage container generate-sas --account-name commadataci --name openpilotci --https-only --permissions lrw \ + --expiry $(date -u '+%Y-%m-%dT%H:%M:%SZ' -d '+1 hour') --auth-mode login --as-user --output tsv", shell=True).decode().strip("\n") + service = BlockBlobService(account_name="commadataci", sas_token=sas_token) + service.create_blob_from_path("openpilotci", name, path) + return "https://commadataci.blob.core.windows.net/openpilotci/" + name + +if __name__ == "__main__": + for f in sys.argv[1:]: + name = os.path.basename(f) + url = upload_file(f, name) + print(url) diff --git a/selfdrive/test/openpilotci_upload.py b/selfdrive/test/openpilotci_upload.py deleted file mode 100755 index 64391532f9..0000000000 --- a/selfdrive/test/openpilotci_upload.py +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import subprocess - - -def upload_file(path, name): - from azure.storage.blob import BlockBlobService - sas_token = os.getenv("TOKEN", None) - if sas_token is None: - cmd = "az storage container generate-sas --account-name commadataci --name openpilotci --https-only --permissions \ - lrw --expiry $(date -u '+%Y-%m-%dT%H:%M:%SZ' -d '+1 hour') --auth-mode login --as-user --output tsv" - sas_token = subprocess.check_output(cmd, shell=True).decode().strip("\n") - service = BlockBlobService(account_name="commadataci", sas_token=sas_token) - service.create_blob_from_path("openpilotci", name, path) - return "https://commadataci.blob.core.windows.net/openpilotci/" + name - -if __name__ == "__main__": - for f in sys.argv[1:]: - name = os.path.basename(f) - url = upload_file(f, name) - print(url) diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py new file mode 100755 index 0000000000..6ee2b396e7 --- /dev/null +++ b/selfdrive/test/phone_ci.py @@ -0,0 +1,75 @@ +#!/usr/bin/env python3 +import paramiko # pylint: disable=import-error +import os +import sys +import re +import time +import socket + +TEST_DIR = "/data/openpilotci" + +def run_test(name, test_func): + ssh = paramiko.SSHClient() + ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy()) + + key_file = open(os.path.join(os.path.dirname(__file__), "../../release/id_rsa_public")) + key = paramiko.RSAKey.from_private_key(key_file) + + print("SSH to phone {}".format(name)) + + # Try connecting for one minute + t_start = time.time() + while True: + try: + ssh.connect(hostname=name, port=8022, pkey=key, timeout=10) + except (paramiko.ssh_exception.SSHException, socket.timeout, paramiko.ssh_exception.NoValidConnectionsError): + print("Connection failed") + if time.time() - t_start > 60: + raise + else: + break + time.sleep(1) + + conn = ssh.invoke_shell() + branch = os.environ['GIT_BRANCH'] + commit = os.environ.get('GIT_COMMIT', branch) + + conn.send("uname -a\n") + + conn.send(f"cd {TEST_DIR}\n") + conn.send("git reset --hard\n") + conn.send("git fetch origin\n") + conn.send("git checkout %s\n" % commit) + conn.send("git clean -xdf\n") + conn.send("git submodule update --init\n") + conn.send("git submodule foreach --recursive git reset --hard\n") + conn.send("git submodule foreach --recursive git clean -xdf\n") + conn.send("echo \"git took $SECONDS seconds\"\n") + + test_func(conn) + + conn.send('echo "RESULT:" $?\n') + conn.send("exit\n") + return conn + +def test_modeld(conn): + conn.send(f"cd selfdrive/test/process_replay && PYTHONPATH={TEST_DIR} ./camera_replay.py\n") + +if __name__ == "__main__": + eon_name = os.environ.get('eon_name', None) + + conn = run_test(eon_name, test_modeld) + + dat = b"" + + while True: + recvd = conn.recv(4096) + if len(recvd) == 0: + break + + dat += recvd + sys.stdout.buffer.write(recvd) + sys.stdout.flush() + + returns = re.findall(rb'^RESULT: (\d+)', dat[-1024:], flags=re.MULTILINE) + sys.exit(int(returns[0])) diff --git a/selfdrive/test/process_replay/.gitignore b/selfdrive/test/process_replay/.gitignore deleted file mode 100644 index 6d339d54f6..0000000000 --- a/selfdrive/test/process_replay/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -*.bz2 -diff.txt diff --git a/selfdrive/test/process_replay/camera_replay.py b/selfdrive/test/process_replay/camera_replay.py new file mode 100755 index 0000000000..e2cb8cd9e2 --- /dev/null +++ b/selfdrive/test/process_replay/camera_replay.py @@ -0,0 +1,103 @@ +#!/usr/bin/env python3 +import os +import sys +import time +from typing import Any +from tqdm import tqdm + +from common.android import ANDROID +if ANDROID: + os.environ['QCOM_REPLAY'] = "1" +import selfdrive.manager as manager + +from common.spinner import Spinner +import cereal.messaging as messaging +from tools.lib.framereader import FrameReader +from tools.lib.logreader import LogReader +from selfdrive.test.openpilotci import BASE_URL, get_url +from selfdrive.test.process_replay.compare_logs import compare_logs, save_log +from selfdrive.test.process_replay.test_processes import format_diff +from selfdrive.version import get_git_commit + +TEST_ROUTE = "5b7c365c50084530|2020-04-15--16-13-24" + +def camera_replay(lr, fr): + + spinner = Spinner() + + pm = messaging.PubMaster(['frame', 'liveCalibration']) + sm = messaging.SubMaster(['model']) + + # TODO: add dmonitoringmodeld + print("preparing procs") + manager.prepare_managed_process("camerad") + manager.prepare_managed_process("modeld") + try: + print("starting procs") + manager.start_managed_process("camerad") + manager.start_managed_process("modeld") + time.sleep(5) + print("procs started") + + cal = [msg for msg in lr if msg.which() == "liveCalibration"] + for msg in cal[:5]: + pm.send(msg.which(), msg.as_builder()) + + log_msgs = [] + frame_idx = 0 + for msg in tqdm(lr): + if msg.which() == "liveCalibrationd": + pm.send(msg.which(), msg.as_builder()) + elif msg.which() == "frame": + f = msg.as_builder() + img = fr.get(frame_idx, pix_fmt="rgb24")[0][:, ::, -1] + f.frame.image = img.flatten().tobytes() + frame_idx += 1 + + pm.send(msg.which(), f) + log_msgs.append(messaging.recv_one(sm.sock['model'])) + + spinner.update("modeld replay %d/%d" % (frame_idx, fr.frame_count)) + + if frame_idx >= fr.frame_count: + break + except KeyboardInterrupt: + pass + + print("replay done") + spinner.close() + manager.kill_managed_process('modeld') + time.sleep(2) + manager.kill_managed_process('camerad') + return log_msgs + + +if __name__ == "__main__": + + update = "--update" in sys.argv + + lr = LogReader(get_url(TEST_ROUTE, 0)) + fr = FrameReader(get_url(TEST_ROUTE, 0, log_type="fcamera")) + + log_msgs = camera_replay(list(lr), fr) + + if update: + ref_commit = get_git_commit() + log_fn = "%s_%s_%s.bz2" % (TEST_ROUTE, "model", ref_commit) + save_log(log_fn, log_msgs) + with open("model_replay_ref_commit", "w") as f: + f.write(ref_commit) + else: + ref_commit = open("model_replay_ref_commit").read().strip() + log_fn = "%s_%s_%s.bz2" % (TEST_ROUTE, "model", ref_commit) + cmp_log = LogReader(BASE_URL + log_fn) + results: Any = {TEST_ROUTE: {}} + results[TEST_ROUTE]["modeld"] = compare_logs(cmp_log, log_msgs, ignore_fields=['logMonoTime', 'valid']) + diff1, diff2, failed = format_diff(results, ref_commit) + + print(diff1) + with open("model_diff.txt", "w") as f: + f.write(diff2) + + sys.exit(int(failed)) + diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit new file mode 100644 index 0000000000..e98217b72a --- /dev/null +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -0,0 +1 @@ +18e43945403c4022b1de72237d89736e1a8ab4c7 \ No newline at end of file diff --git a/selfdrive/test/process_replay/update_model.py b/selfdrive/test/process_replay/update_model.py index d3dab335ef..31629563e2 100755 --- a/selfdrive/test/process_replay/update_model.py +++ b/selfdrive/test/process_replay/update_model.py @@ -2,7 +2,7 @@ import os import sys -from selfdrive.test.openpilotci_upload import upload_file +from selfdrive.test.openpilotci import upload_file from selfdrive.test.process_replay.compare_logs import save_log from selfdrive.test.process_replay.test_processes import segments, get_segment from selfdrive.version import get_git_commit diff --git a/selfdrive/test/process_replay/update_refs.py b/selfdrive/test/process_replay/update_refs.py index 37997dad0d..b4243c56d3 100755 --- a/selfdrive/test/process_replay/update_refs.py +++ b/selfdrive/test/process_replay/update_refs.py @@ -2,7 +2,7 @@ import os import sys -from selfdrive.test.openpilotci_upload import upload_file +from selfdrive.test.openpilotci import upload_file from selfdrive.test.process_replay.compare_logs import save_log from selfdrive.test.process_replay.process_replay import replay_process, CONFIGS from selfdrive.test.process_replay.test_processes import segments, get_segment diff --git a/tools/lib/auth_config.py b/tools/lib/auth_config.py index 1e604970ae..0cc3e33b51 100644 --- a/tools/lib/auth_config.py +++ b/tools/lib/auth_config.py @@ -1,11 +1,15 @@ import json import os +from common.android import ANDROID from common.file_helpers import mkdirs_exists_ok class MissingAuthConfigError(Exception): pass -CONFIG_DIR = os.path.expanduser('~/.comma') +if ANDROID: + CONFIG_DIR = "/tmp/.comma" +else: + CONFIG_DIR = os.path.expanduser('~/.comma') mkdirs_exists_ok(CONFIG_DIR) def get_token(): From 3463f1165e5546f8c8054e8dcedc830607ad643b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 5 Jun 2020 11:29:09 -0700 Subject: [PATCH 215/656] quick LGTM fixes --- selfdrive/common/visionimg.cc | 2 +- selfdrive/locationd/ubloxd_test.cc | 4 ++-- tools/lib/index_log/index_log.cc | 5 +---- 3 files changed, 4 insertions(+), 7 deletions(-) diff --git a/selfdrive/common/visionimg.cc b/selfdrive/common/visionimg.cc index 35fe7095d0..e0220c18f2 100644 --- a/selfdrive/common/visionimg.cc +++ b/selfdrive/common/visionimg.cc @@ -49,7 +49,7 @@ VisionImg visionimg_alloc_rgb24(int width, int height, VisionBuf *out_buf) { visionimg_compute_aligned_width_and_height(width, height, &aligned_w, &aligned_h); int stride = aligned_w * 3; - size_t size = aligned_w * aligned_h * 3; + size_t size = (size_t) aligned_w * aligned_h * 3; VisionBuf buf = visionbuf_allocate(size); diff --git a/selfdrive/locationd/ubloxd_test.cc b/selfdrive/locationd/ubloxd_test.cc index fc7146625f..b63e26b82d 100644 --- a/selfdrive/locationd/ubloxd_test.cc +++ b/selfdrive/locationd/ubloxd_test.cc @@ -26,13 +26,13 @@ using namespace ublox; extern volatile sig_atomic_t do_exit; -void write_file(std::string fpath, uint8_t *to_write, int len) { +void write_file(std::string fpath, uint8_t *to_write, int length) { FILE* f = fopen(fpath.c_str(), "wb"); if (!f) { std::cout << "Open " << fpath << " failed" << std::endl; return; } - fwrite(to_write, len, 1, f); + fwrite(to_write, length, 1, f); fclose(f); } diff --git a/tools/lib/index_log/index_log.cc b/tools/lib/index_log/index_log.cc index 8eb4a5e34e..ee7c7502db 100644 --- a/tools/lib/index_log/index_log.cc +++ b/tools/lib/index_log/index_log.cc @@ -41,7 +41,6 @@ int main(int argc, char** argv) { auto words = kj::arrayPtr((const capnp::word*)log_data, log_size/sizeof(capnp::word)); while (words.size() > 0) { - uint64_t idx = ((uintptr_t)words.begin() - (uintptr_t)log_data); // printf("%llu - %ld\n", idx, words.size()); const char* idx_bytes = (const char*)&idx; @@ -49,11 +48,9 @@ int main(int argc, char** argv) { try { capnp::FlatArrayMessageReader reader(words); words = kj::arrayPtr(reader.getEnd(), words.end()); - } catch (kj::Exception exc) { + } catch (const kj::Exception& exc) { break; } - - } munmap(log_data, log_size); From c7ff6dd194b48629dbd05a2cc87afd328fffa3a5 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 6 Jun 2020 03:42:01 +0800 Subject: [PATCH 216/656] pass DMonitoringResult as referer (#1639) --- selfdrive/modeld/models/dmonitoring.cc | 2 +- selfdrive/modeld/models/dmonitoring.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 6dc90718d1..15b28dd8d6 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -144,7 +144,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ return ret; } -void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult res) { +void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res){ // make msg capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); diff --git a/selfdrive/modeld/models/dmonitoring.h b/selfdrive/modeld/models/dmonitoring.h index c0a0cf4463..83d014f8db 100644 --- a/selfdrive/modeld/models/dmonitoring.h +++ b/selfdrive/modeld/models/dmonitoring.h @@ -37,7 +37,7 @@ typedef struct DMonitoringModelState { void dmonitoring_init(DMonitoringModelState* s); DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height); -void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult res); +void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res); void dmonitoring_free(DMonitoringModelState* s); #ifdef __cplusplus From 5f58307153cd018a6c5e3a8da9416a6749cbabea Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 6 Jun 2020 03:42:23 +0800 Subject: [PATCH 217/656] pass subframes_map by refer (#1640) --- selfdrive/locationd/ublox_msg.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/ublox_msg.cc b/selfdrive/locationd/ublox_msg.cc index 6f3bd6b635..74c1f28d52 100644 --- a/selfdrive/locationd/ublox_msg.cc +++ b/selfdrive/locationd/ublox_msg.cc @@ -39,7 +39,7 @@ inline int GET_FIELD_S(uint32_t w, uint32_t nb, uint32_t pos) { class EphemerisData { public: - EphemerisData(uint8_t svId, subframes_map subframes) { + EphemerisData(uint8_t svId, subframes_map &subframes) { this->svId = svId; int week_no = GET_FIELD_U(subframes[1][2+0], 10, 20); int t_gd = GET_FIELD_S(subframes[1][2+4], 8, 6); From 7666d99694615f0a4a960e0b739018c4628ffa50 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 5 Jun 2020 12:46:49 -0700 Subject: [PATCH 218/656] Remove common/messaging.h (#1635) * remove common/messaging.h * release files --- release/files_common | 1 - selfdrive/boardd/boardd.cc | 1 - selfdrive/common/messaging.h | 15 --------------- selfdrive/locationd/paramsd.cc | 1 - 4 files changed, 18 deletions(-) delete mode 100644 selfdrive/common/messaging.h diff --git a/release/files_common b/release/files_common index b41b511dd0..a0fc3743ff 100644 --- a/release/files_common +++ b/release/files_common @@ -190,7 +190,6 @@ selfdrive/common/util.[c,h] selfdrive/common/efd.[c,h] selfdrive/common/cqueue.[c,h] selfdrive/common/clutil.[c,h] -selfdrive/common/messaging.h selfdrive/common/params.h selfdrive/common/params.cc selfdrive/common/mutex.h diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index ad6363440f..c6a0a7a40e 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -18,7 +18,6 @@ #include "cereal/gen/cpp/car.capnp.h" #include "common/util.h" -#include "common/messaging.h" #include "common/params.h" #include "common/swaglog.h" #include "common/timing.h" diff --git a/selfdrive/common/messaging.h b/selfdrive/common/messaging.h deleted file mode 100644 index dd1198e826..0000000000 --- a/selfdrive/common/messaging.h +++ /dev/null @@ -1,15 +0,0 @@ -// the c version of cereal/messaging.py - -#include - -// TODO: refactor to take in service instead of endpoint? -void *sub_sock(void *ctx, const char *endpoint) { - void* sock = zmq_socket(ctx, ZMQ_SUB); - assert(sock); - zmq_setsockopt(sock, ZMQ_SUBSCRIBE, "", 0); - int reconnect_ivl = 500; - zmq_setsockopt(sock, ZMQ_RECONNECT_IVL_MAX, &reconnect_ivl, sizeof(reconnect_ivl)); - zmq_connect(sock, endpoint); - return sock; -} - diff --git a/selfdrive/locationd/paramsd.cc b/selfdrive/locationd/paramsd.cc index b5fa380c37..3841ccc5bb 100644 --- a/selfdrive/locationd/paramsd.cc +++ b/selfdrive/locationd/paramsd.cc @@ -8,7 +8,6 @@ #include "json11.hpp" #include "common/swaglog.h" -#include "common/messaging.h" #include "common/params.h" #include "common/timing.h" From c454bff2f842dce9f66bae60e93ad68d0cc392e6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 5 Jun 2020 12:52:55 -0700 Subject: [PATCH 219/656] remove trailing whitespace pre-commi hook for now --- .pre-commit-config.yaml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 840b263ee3..af18f795ff 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -8,8 +8,6 @@ repos: - id: check-yaml - id: check-merge-conflict - id: check-symlinks - - id: trailing-whitespace - exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(opendbc)|(laika_repo)|(rednose_repo)|(phonelibs)|(lib_mpc_export)/' - repo: https://github.com/pre-commit/mirrors-mypy rev: master hooks: From 72cc0fc801fc4df60cc23e6818580a91e76f4f18 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 5 Jun 2020 14:03:24 -0700 Subject: [PATCH 220/656] use pipenv for dev dependencies --- tools/README.md | 129 ----------------------------------------- tools/requirements.txt | 13 ----- tools/ubuntu_setup.sh | 8 +-- 3 files changed, 1 insertion(+), 149 deletions(-) delete mode 100644 tools/requirements.txt diff --git a/tools/README.md b/tools/README.md index ea0fd7d83a..badec0210c 100644 --- a/tools/README.md +++ b/tools/README.md @@ -28,135 +28,6 @@ openpilot tools and the following setup steps are developed and tested on Ubuntu Setup ============ - 1. Run ubuntu_setup.sh, make sure everything completed correctly 2. Compile openpilot by running ```scons``` in the openpilot directory diff --git a/tools/requirements.txt b/tools/requirements.txt deleted file mode 100644 index d5887cb5ef..0000000000 --- a/tools/requirements.txt +++ /dev/null @@ -1,13 +0,0 @@ -aenum -atomicwrites -futures -libarchive -lru-dict -matplotlib -numpy -opencv-python -pygame -hexdump -pycurl -tenacity -av==0.5.0 diff --git a/tools/ubuntu_setup.sh b/tools/ubuntu_setup.sh index 9d3abc7993..e46d7b29fe 100755 --- a/tools/ubuntu_setup.sh +++ b/tools/ubuntu_setup.sh @@ -85,13 +85,7 @@ pyenv rehash pip install pipenv==2018.11.26 # pipenv setup (in openpilot dir) -pipenv install --system --deploy - -# to make tools work -pip install -r tools/requirements.txt - -# to make modeld work on PC with nvidia GPU -pip install tensorflow==2.2 +pipenv install --dev --system --deploy # for loggerd to work on ubuntu # TODO: PC should log somewhere else From 68531b071cde6fa5856d9b68bed63ecb50e03c2a Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Fri, 5 Jun 2020 17:09:41 -0400 Subject: [PATCH 221/656] Reduce scheduler latency for realtime processes (#1638) * WIP: reduce boardd and other lags * Copypasta fault * Silence spurious startup warning Co-authored-by: Comma Device --- common/realtime.py | 28 +++++++++++++++++++++------- launch_chffrplus.sh | 28 ++++++++++++++++------------ selfdrive/boardd/boardd.cc | 8 +++++--- selfdrive/camerad/main.cc | 6 +++--- selfdrive/common/util.c | 14 ++++++++++++++ selfdrive/common/util.h | 1 + selfdrive/controls/controlsd.py | 5 +++-- selfdrive/controls/dmonitoringd.py | 2 +- selfdrive/controls/plannerd.py | 2 +- selfdrive/controls/radard.py | 2 +- 10 files changed, 66 insertions(+), 30 deletions(-) diff --git a/common/realtime.py b/common/realtime.py index c21222e88c..e734438646 100644 --- a/common/realtime.py +++ b/common/realtime.py @@ -6,6 +6,7 @@ import subprocess import multiprocessing from cffi import FFI +from common.android import ANDROID from common.common_pyx import sec_since_boot # pylint: disable=no-name-in-module, import-error @@ -20,11 +21,7 @@ ffi = FFI() ffi.cdef("long syscall(long number, ...);") libc = ffi.dlopen(None) - -def set_realtime_priority(level): - if os.getuid() != 0: - print("not setting priority, not root") - return +def _get_tid(): if platform.machine() == "x86_64": NR_gettid = 186 elif platform.machine() == "aarch64": @@ -32,8 +29,25 @@ def set_realtime_priority(level): else: raise NotImplementedError - tid = libc.syscall(NR_gettid) - return subprocess.call(['chrt', '-f', '-p', str(level), str(tid)]) + return libc.syscall(NR_gettid) + + +def set_realtime_priority(level): + if os.getuid() != 0: + print("not setting priority, not root") + return + + return subprocess.call(['chrt', '-f', '-p', str(level), str(_get_tid())]) + +def set_core_affinity(core): + if os.getuid() != 0: + print("not setting affinity, not root") + return + + if ANDROID: + return subprocess.call(['taskset', '-p', str(core), str(_get_tid())]) + else: + return -1 class Ratekeeper(): diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index f88f6fb7d1..2d3fa39d4e 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -55,18 +55,22 @@ function launch { fi fi - # no cpu rationing for now - echo 0-3 > /dev/cpuset/background/cpus - echo 0-3 > /dev/cpuset/system-background/cpus - echo 0-3 > /dev/cpuset/foreground/boost/cpus - echo 0-3 > /dev/cpuset/foreground/cpus - echo 0-3 > /dev/cpuset/android/cpus - - # change interrupt affinity - echo 3 > /proc/irq/6/smp_affinity_list # MDSS - echo 1 > /proc/irq/78/smp_affinity_list # Modem, can potentially lock up - echo 2 > /proc/irq/733/smp_affinity_list # USB - echo 2 > /proc/irq/736/smp_affinity_list # USB + # Android and other system processes are not permitted to run on CPU 3 + # NEOS installed app processes can run anywhere + echo 0-2 > /dev/cpuset/background/cpus + echo 0-2 > /dev/cpuset/system-background/cpus + [ -d "/dev/cpuset/foreground/boost/cpus" ] && echo 0-2 > /dev/cpuset/foreground/boost/cpus # Not present in < NEOS 15 + echo 0-2 > /dev/cpuset/foreground/cpus + echo 0-2 > /dev/cpuset/android/cpus + echo 0-3 > /dev/cpuset/app/cpus + + # Collect RIL and other possibly long-running I/O interrupts onto CPU 1 + echo 1 > /proc/irq/78/smp_affinity_list # qcom,smd-modem (LTE radio) + echo 1 > /proc/irq/33/smp_affinity_list # ufshcd (flash storage) + echo 1 > /proc/irq/35/smp_affinity_list # wifi (wlan_pci) + # USB traffic needs realtime handling on cpu 3 + [ -d "/proc/irq/733" ] && echo 3 > /proc/irq/733/smp_affinity_list # USB for LeEco + [ -d "/proc/irq/736" ] && echo 3 > /proc/irq/736/smp_affinity_list # USB for OP3T DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index c6a0a7a40e..91de75a364 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -856,9 +856,11 @@ int main() { int err; LOGW("starting boardd"); - // set process priority - err = set_realtime_priority(4); - LOG("setpriority returns %d", err); + // set process priority and affinity + err = set_realtime_priority(54); + LOG("set priority returns %d", err); + err = set_core_affinity(3); + LOG("set affinity returns %d", err); // check the environment if (getenv("STARTED")) { diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index d65913bb46..b1c6684675 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -342,7 +342,7 @@ void* processing_thread(void *arg) { set_thread_name("processing"); - err = set_realtime_priority(1); + err = set_realtime_priority(51); LOG("setpriority returns %d", err); // init cl stuff @@ -1203,7 +1203,7 @@ void party(VisionState *s) { #endif // priority for cameras - err = set_realtime_priority(1); + err = set_realtime_priority(51); LOG("setpriority returns %d", err); cameras_run(&s->cameras); @@ -1234,7 +1234,7 @@ void party(VisionState *s) { int main(int argc, char *argv[]) { int err; - set_realtime_priority(1); + set_realtime_priority(51); zsys_handler_set(NULL); signal(SIGINT, (sighandler_t)set_do_exit); diff --git a/selfdrive/common/util.c b/selfdrive/common/util.c index 1aed0eaae6..dce6e8ac67 100644 --- a/selfdrive/common/util.c +++ b/selfdrive/common/util.c @@ -7,6 +7,7 @@ #ifdef __linux__ #include #include +#define __USE_GNU #include #endif @@ -61,3 +62,16 @@ int set_realtime_priority(int level) { #endif } +int set_core_affinity(int core) { +#ifdef QCOM + + long tid = syscall(SYS_gettid); + cpu_set_t rt_cpu; + + CPU_ZERO(&rt_cpu); + CPU_SET(core, &rt_cpu); + return sched_setaffinity(tid, sizeof(rt_cpu), &rt_cpu); +#else + return -1; +#endif +} diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h index ed0c88f2c8..4b0e29aada 100644 --- a/selfdrive/common/util.h +++ b/selfdrive/common/util.h @@ -44,6 +44,7 @@ void* read_file(const char* path, size_t* out_len); void set_thread_name(const char* name); int set_realtime_priority(int level); +int set_core_affinity(int core); #ifdef __cplusplus } diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 7d4591626d..2c1a444d9f 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -3,7 +3,7 @@ import os import gc from cereal import car, log from common.numpy_fast import clip -from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper, DT_CTRL +from common.realtime import sec_since_boot, set_realtime_priority, set_core_affinity, Ratekeeper, DT_CTRL from common.profiler import Profiler from common.params import Params, put_nonblocking import cereal.messaging as messaging @@ -39,7 +39,8 @@ EventName = car.CarEvent.EventName class Controls: def __init__(self, sm=None, pm=None, can_sock=None): gc.disable() - set_realtime_priority(3) + set_realtime_priority(53) + set_core_affinity(3) # Setup sockets self.pm = pm diff --git a/selfdrive/controls/dmonitoringd.py b/selfdrive/controls/dmonitoringd.py index 0f949c2e89..2a21e920f4 100755 --- a/selfdrive/controls/dmonitoringd.py +++ b/selfdrive/controls/dmonitoringd.py @@ -12,7 +12,7 @@ def dmonitoringd_thread(sm=None, pm=None): gc.disable() # start the loop - set_realtime_priority(3) + set_realtime_priority(53) params = Params() diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 21ea32a51a..b439681a3a 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -15,7 +15,7 @@ def plannerd_thread(sm=None, pm=None): gc.disable() # start the loop - set_realtime_priority(2) + set_realtime_priority(52) cloudlog.info("plannerd is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 3ae766281b..0ba14dcf26 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -174,7 +174,7 @@ class RadarD(): # fuses camera and radar data for best lead detection def radard_thread(sm=None, pm=None, can_sock=None): - set_realtime_priority(2) + set_realtime_priority(52) # wait for stats about the car to come in from controls cloudlog.info("radard is waiting for CarParams") From 19512315ffc6db82b06b5b8f688ee09656a620e4 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 5 Jun 2020 14:20:52 -0700 Subject: [PATCH 222/656] boardd: no conflate on sendcan (#1645) --- selfdrive/boardd/boardd.cc | 22 +++++++++++++++++----- 1 file changed, 17 insertions(+), 5 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 91de75a364..bc6dcea457 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -588,17 +588,29 @@ void can_send(cereal::Event::Reader &event) { void *can_send_thread(void *crap) { LOGD("start send thread"); - SubMaster sm({"sendcan"}); - // drain sendcan to delete any stale messages from previous runs - sm.drain(); + Context * context = Context::create(); + SubSocket * subscriber = SubSocket::create(context, "sendcan"); + assert(subscriber != NULL); + // run as fast as messages come in while (!do_exit) { - if (sm.update(1000) > 0){ - can_send(sm["sendcan"]); + Message * msg = subscriber->receive(); + + if (msg){ + auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), msg->getData(), msg->getSize()); + + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + can_send(event); + delete msg; } } + delete subscriber; + delete context; + return NULL; } From d720f28ecb35c06a5ffb6004e79d82c80707fcde Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 6 Jun 2020 06:33:45 +0800 Subject: [PATCH 223/656] ui.cc: remove variables from UIScene, use event::Reader to get data (#1585) * use struct to store lead status * remove white space * use RadarState::LeadData::Reader * use reader to get thermal data * use reader * continue * remove variables reset submodules,fix some errors reset submodules revert * remove s->scene.gps_planner_active * modify * cleanup * done * resolve conflict * remove irrelevant comment * remove white space --- selfdrive/ui/paint.cc | 66 +++++++++++++------------ selfdrive/ui/sidebar.cc | 12 ++--- selfdrive/ui/ui.cc | 107 +++++++++++----------------------------- selfdrive/ui/ui.hpp | 47 +++--------------- 4 files changed, 78 insertions(+), 154 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 8e40314e3d..3be25899b0 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -110,11 +110,13 @@ static void ui_draw_circle_image(NVGcontext *vg, float x, float y, int size, int ui_draw_circle_image(vg, x, y, size, image, nvgRGBA(0, 0, 0, (255 * bg_alpha)), img_alpha); } -static void draw_lead(UIState *s, float d_rel, float v_rel, float y_rel){ +static void draw_lead(UIState *s, const cereal::RadarState::LeadData::Reader &lead){ // Draw lead car indicator float fillAlpha = 0; float speedBuff = 10.; float leadBuff = 40.; + float d_rel = lead.getDRel(); + float v_rel = lead.getVRel(); if (d_rel < leadBuff) { fillAlpha = 255*(1.0-(d_rel/leadBuff)); if (v_rel < 0) { @@ -122,7 +124,7 @@ static void draw_lead(UIState *s, float d_rel, float v_rel, float y_rel){ } fillAlpha = (int)(fmin(fillAlpha, 255)); } - draw_chevron(s, d_rel, y_rel, 25, nvgRGBA(201, 34, 49, fillAlpha), COLOR_YELLOW); + draw_chevron(s, d_rel, lead.getYRel(), 25, nvgRGBA(201, 34, 49, fillAlpha), COLOR_YELLOW); } static void ui_draw_lane_line(UIState *s, const model_path_vertices_data *pvd, NVGcolor color) { @@ -154,7 +156,7 @@ static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) bool started = false; float off = is_mpc?0.3:0.5; - float lead_d = scene->lead_d_rel*2.; + float lead_d = scene->lead_data[0].getDRel()*2.; float path_height = is_mpc?(lead_d>5.)?fmin(lead_d, 25.)-fmin(lead_d*0.35, 10.):20. :(lead_d>0.)?fmin(lead_d, 50.)-fmin(lead_d*0.35, 10.):49.; pvd->cnt = 0; @@ -205,7 +207,7 @@ static void update_all_track_data(UIState *s) { // Draw vision path update_track_data(s, false, &s->track_vertices[0]); - if (scene->engaged) { + if (scene->controls_state.getEnabled()) { // Draw MPC path when engaged update_track_data(s, true, &s->track_vertices[1]); } @@ -340,10 +342,9 @@ static void ui_draw_lane(UIState *s, const PathData *path, model_path_vertices_d static void ui_draw_vision_lanes(UIState *s) { const UIScene *scene = &s->scene; model_path_vertices_data *pvd = &s->model_path_vertices[0]; - if(s->model_changed) { + if(s->sm->updated("model")) { update_all_lane_lines_data(s, scene->model.left_lane, pvd); update_all_lane_lines_data(s, scene->model.right_lane, pvd + MODEL_LANE_PATH_CNT); - s->model_changed = false; } // Draw left lane edge ui_draw_lane( @@ -357,13 +358,12 @@ static void ui_draw_vision_lanes(UIState *s) { pvd + MODEL_LANE_PATH_CNT, nvgRGBAf(1.0, 1.0, 1.0, scene->model.right_lane.prob)); - if(s->livempc_or_radarstate_changed) { + if(s->sm->updated("radarState")) { update_all_track_data(s); - s->livempc_or_radarstate_changed = false; } // Draw vision path ui_draw_track(s, false, &s->track_vertices[0]); - if (scene->engaged) { + if (scene->controls_state.getEnabled()) { // Draw MPC path when engaged ui_draw_track(s, true, &s->track_vertices[1]); } @@ -394,11 +394,11 @@ static void ui_draw_world(UIState *s) { // Draw lane edges and vision/mpc tracks ui_draw_vision_lanes(s); - if (scene->lead_status) { - draw_lead(s, scene->lead_d_rel, scene->lead_v_rel, scene->lead_y_rel); + if (scene->lead_data[0].getStatus()) { + draw_lead(s, scene->lead_data[0]); } - if ((scene->lead_status2) && (std::abs(scene->lead_d_rel - scene->lead_d_rel2) > 3.0)) { - draw_lead(s, scene->lead_d_rel2, scene->lead_v_rel2, scene->lead_y_rel2); + if (scene->lead_data[1].getStatus() && (std::abs(scene->lead_data[0].getDRel() - scene->lead_data[1].getDRel()) > 3.0)) { + draw_lead(s, scene->lead_data[1]); } nvgRestore(s->vg); } @@ -408,7 +408,7 @@ static void ui_draw_vision_maxspeed(UIState *s) { return; }*/ char maxspeed_str[32]; - float maxspeed = s->scene.v_cruise; + float maxspeed = s->scene.controls_state.getVCruise(); int maxspeed_calc = maxspeed * 0.6225 + 0.5; float speedlimit = s->scene.speedlimit; int speedlim_calc = speedlimit * 2.2369363 + 0.5; @@ -421,7 +421,7 @@ static void ui_draw_vision_maxspeed(UIState *s) { bool is_cruise_set = (maxspeed != 0 && maxspeed != SET_SPEED_NA); bool is_speedlim_valid = s->scene.speedlimit_valid; - bool is_set_over_limit = is_speedlim_valid && s->scene.engaged && + bool is_set_over_limit = is_speedlim_valid && s->scene.controls_state.getEnabled() && is_cruise_set && maxspeed_calc > (speedlim_calc + speed_lim_off); int viz_maxspeed_w = 184; @@ -476,7 +476,7 @@ static void ui_draw_vision_speedlimit(UIState *s) { if (s->is_ego_over_limit) { hysteresis_offset = 0.0; } - s->is_ego_over_limit = is_speedlim_valid && s->scene.v_ego > (speedlimit + s->speed_lim_off + hysteresis_offset); + s->is_ego_over_limit = is_speedlim_valid && s->scene.controls_state.getVEgo() > (speedlimit + s->speed_lim_off + hysteresis_offset); int viz_speedlim_w = 180; int viz_speedlim_h = 202; @@ -522,9 +522,10 @@ static void ui_draw_vision_speedlimit(UIState *s) { static void ui_draw_vision_speed(UIState *s) { const UIScene *scene = &s->scene; - float speed = s->scene.v_ego * 2.2369363 + 0.5; + float v_ego = s->scene.controls_state.getVEgo(); + float speed = v_ego * 2.2369363 + 0.5; if (s->is_metric){ - speed = s->scene.v_ego * 3.6 + 0.5; + speed = v_ego * 3.6 + 0.5; } const int viz_speed_w = 280; const int viz_speed_x = scene->ui_viz_rx+((scene->ui_viz_rw/2)-(viz_speed_w/2)); @@ -543,7 +544,7 @@ static void ui_draw_vision_event(UIState *s) { const int viz_event_w = 220; const int viz_event_x = ((s->scene.ui_viz_rx + s->scene.ui_viz_rw) - (viz_event_w + (bdr_s*2))); const int viz_event_y = (box_y + (bdr_s*1.5)); - if (s->scene.decel_for_model && s->scene.engaged) { + if (s->scene.controls_state.getDecelForModel() && s->scene.controls_state.getEnabled()) { // draw winding road sign const int img_turn_size = 160*1.5; ui_draw_image(s->vg, viz_event_x - (img_turn_size / 4), viz_event_y + bdr_s - 25, img_turn_size, img_turn_size, s->img_turn, 1.0f); @@ -561,7 +562,7 @@ static void ui_draw_vision_event(UIState *s) { color = nvgRGBA(23, 51, 73, 255); } - if (s->scene.engageable){ + if (s->scene.controls_state.getEngageable()){ ui_draw_circle_image(s->vg, bg_wheel_x, bg_wheel_y, bg_wheel_size, s->img_wheel, color, 1.0f, bg_wheel_y - 25); } } @@ -578,7 +579,7 @@ static void ui_draw_vision_face(UIState *s) { const int face_size = 96; const int face_x = (s->scene.ui_viz_rx + face_size + (bdr_s * 2)); const int face_y = (footer_y + ((footer_h - face_size) / 2)); - ui_draw_circle_image(s->vg, face_x, face_y, face_size, s->img_face, s->scene.monitoring_active); + ui_draw_circle_image(s->vg, face_x, face_y, face_size, s->img_face, s->scene.controls_state.getDriverMonitoringOn()); } static void ui_draw_driver_view(UIState *s) { @@ -610,30 +611,31 @@ static void ui_draw_driver_view(UIState *s) { ui_draw_rect(s->vg, valid_frame_x + valid_frame_w, box_y, frame_w - valid_frame_w - (valid_frame_x - frame_x), box_h, nvgRGBA(23, 51, 73, 255)); // draw face box - if (scene->face_prob > 0.4) { + if (scene->driver_state.getFaceProb() > 0.4) { + auto fxy_list = scene->driver_state.getFacePosition(); + const int face_x = fxy_list[0]; + const int face_y = fxy_list[1]; int fbox_x; - int fbox_y = box_y + (scene->face_y + 0.5) * box_h - 0.5 * 0.6 * box_h / 2;; + int fbox_y = box_y + (face_y + 0.5) * box_h - 0.5 * 0.6 * box_h / 2;; if (!scene->is_rhd) { - fbox_x = valid_frame_x + (1 - (scene->face_x + 0.5)) * (box_h / 2) - 0.5 * 0.6 * box_h / 2; + fbox_x = valid_frame_x + (1 - (face_x + 0.5)) * (box_h / 2) - 0.5 * 0.6 * box_h / 2; } else { - fbox_x = valid_frame_x + valid_frame_w - box_h / 2 + (scene->face_x + 0.5) * (box_h / 2) - 0.5 * 0.6 * box_h / 2; + fbox_x = valid_frame_x + valid_frame_w - box_h / 2 + (face_x + 0.5) * (box_h / 2) - 0.5 * 0.6 * box_h / 2; } - if (std::abs(scene->face_x) <= 0.35 && std::abs(scene->face_y) <= 0.4) { + if (std::abs(face_x) <= 0.35 && std::abs(face_y) <= 0.4) { ui_draw_rect(s->vg, fbox_x, fbox_y, 0.6 * box_h / 2, 0.6 * box_h / 2, - nvgRGBAf(1.0, 1.0, 1.0, 0.8 - ((std::abs(scene->face_x) > std::abs(scene->face_y) ? std::abs(scene->face_x) : std::abs(scene->face_y))) * 0.6 / 0.375), + nvgRGBAf(1.0, 1.0, 1.0, 0.8 - ((std::abs(face_x) > std::abs(face_y) ? std::abs(face_x) : std::abs(face_y))) * 0.6 / 0.375), 35, 10); } else { ui_draw_rect(s->vg, fbox_x, fbox_y, 0.6 * box_h / 2, 0.6 * box_h / 2, nvgRGBAf(1.0, 1.0, 1.0, 0.2), 35, 10); } - } else { - ; } // draw face icon const int face_size = 85; - const int face_x = (valid_frame_x + face_size + (bdr_s * 2)) + (scene->is_rhd ? valid_frame_w - box_h / 2:0); - const int face_y = (box_y + box_h - face_size - bdr_s - (bdr_s * 1.5)); - ui_draw_circle_image(s->vg, face_x, face_y, face_size, s->img_face, scene->face_prob > 0.4); + const int x = (valid_frame_x + face_size + (bdr_s * 2)) + (scene->is_rhd ? valid_frame_w - box_h / 2:0); + const int y = (box_y + box_h - face_size - bdr_s - (bdr_s * 1.5)); + ui_draw_circle_image(s->vg, x, y, face_size, s->img_face, scene->driver_state.getFaceProb() > 0.4); } static void ui_draw_vision_header(UIState *s) { diff --git a/selfdrive/ui/sidebar.cc b/selfdrive/ui/sidebar.cc index 3b30ac7574..5d75a9bbfb 100644 --- a/selfdrive/ui/sidebar.cc +++ b/selfdrive/ui/sidebar.cc @@ -34,7 +34,7 @@ static void ui_draw_sidebar_network_strength(UIState *s) { const int network_img_w = 176; const int network_img_x = !s->scene.uilayout_sidebarcollapsed ? 58 : -(sbr_w); const int network_img_y = 196; - const int img_idx = s->scene.networkType == cereal::ThermalData::NetworkType::NONE ? 0 : network_strength_map[s->scene.networkStrength]; + const int img_idx = s->scene.thermal.getNetworkType() == cereal::ThermalData::NetworkType::NONE ? 0 : network_strength_map[s->scene.thermal.getNetworkStrength()]; ui_draw_image(s->vg, network_img_x, network_img_y, network_img_w, network_img_h, s->img_network[img_idx], 1.0f); } @@ -44,10 +44,10 @@ static void ui_draw_sidebar_battery_icon(UIState *s) { const int battery_img_x = !s->scene.uilayout_sidebarcollapsed ? 160 : -(sbr_w); const int battery_img_y = 255; - int battery_img = s->scene.batteryCharging ? s->img_battery_charging : s->img_battery; + int battery_img = s->scene.thermal.getBatteryStatus() == "Charging" ? s->img_battery_charging : s->img_battery; ui_draw_rect(s->vg, battery_img_x + 6, battery_img_y + 5, - ((battery_img_w - 19) * (s->scene.batteryPercent * 0.01)), battery_img_h - 11, COLOR_WHITE); + ((battery_img_w - 19) * (s->scene.thermal.getBatteryPercent() * 0.01)), battery_img_h - 11, COLOR_WHITE); ui_draw_image(s->vg, battery_img_x, battery_img_y, battery_img_w, battery_img_h, battery_img, 1.0f); } @@ -64,7 +64,7 @@ static void ui_draw_sidebar_network_type(UIState *s) { const int network_y = 273; const int network_w = 100; const int network_h = 100; - const char *network_type = network_type_map[s->scene.networkType]; + const char *network_type = network_type_map[s->scene.thermal.getNetworkType()]; nvgFillColor(s->vg, COLOR_WHITE); nvgFontSize(s->vg, 48); nvgFontFaceId(s->vg, s->font_sans_regular); @@ -127,12 +127,12 @@ static void ui_draw_sidebar_temp_metric(UIState *s) { char temp_value_str[32]; char temp_value_unit[32]; const int temp_y_offset = 0; - snprintf(temp_value_str, sizeof(temp_value_str), "%d", s->scene.paTemp); + snprintf(temp_value_str, sizeof(temp_value_str), "%d", s->scene.thermal.getPa0()); snprintf(temp_value_unit, sizeof(temp_value_unit), "%s", "°C"); snprintf(temp_label_str, sizeof(temp_label_str), "%s", "TEMP"); strcat(temp_value_str, temp_value_unit); - ui_draw_sidebar_metric(s, temp_label_str, temp_value_str, temp_severity_map[s->scene.thermalStatus], temp_y_offset, NULL); + ui_draw_sidebar_metric(s, temp_label_str, temp_value_str, temp_severity_map[s->scene.thermal.getThermalStatus()], temp_y_offset, NULL); } static void ui_draw_sidebar_panda_metric(UIState *s) { diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index cd76ebe7c3..1807adee70 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -207,9 +207,6 @@ static void ui_init(UIState *s) { set_awake(s, true); - s->model_changed = false; - s->livempc_or_radarstate_changed = false; - ui_nvg_init(s); } @@ -228,18 +225,16 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, s->cur_vision_idx = -1; s->cur_vision_front_idx = -1; - s->scene = (UIScene){ - .frontview = getenv("FRONTVIEW") != NULL, - .fullview = getenv("FULLVIEW") != NULL, - .transformed_width = ui_info.transformed_width, - .transformed_height = ui_info.transformed_height, - .front_box_x = ui_info.front_box_x, - .front_box_y = ui_info.front_box_y, - .front_box_width = ui_info.front_box_width, - .front_box_height = ui_info.front_box_height, - .world_objects_visible = false, // Invisible until we receive a calibration message. - .gps_planner_active = false, - }; + s->scene.frontview = getenv("FRONTVIEW") != NULL; + s->scene.fullview = getenv("FULLVIEW") != NULL; + s->scene.transformed_width = ui_info.transformed_width; + s->scene.transformed_height = ui_info.transformed_height; + s->scene.front_box_x = ui_info.front_box_x; + s->scene.front_box_y = ui_info.front_box_y; + s->scene.front_box_width = ui_info.front_box_width; + s->scene.front_box_height = ui_info.front_box_height; + s->scene.world_objects_visible = false; // Invisible until we receive a calibration message. + s->scene.gps_planner_active = false; s->rgb_width = back_bufs.width; s->rgb_height = back_bufs.height; @@ -307,23 +302,12 @@ void handle_message(UIState *s, SubMaster &sm) { UIScene &scene = s->scene; if (s->started && sm.updated("controlsState")) { auto event = sm["controlsState"]; - auto data = event.getControlsState(); + scene.controls_state = event.getControlsState(); s->controls_timeout = 1 * UI_FREQ; - scene.frontview = data.getRearViewCam(); + scene.frontview = scene.controls_state.getRearViewCam(); if (!scene.frontview){ s->controls_seen = true; } - if (data.getVCruise() != scene.v_cruise) { - scene.v_cruise_update_ts = event.getLogMonoTime(); - } - scene.v_cruise = data.getVCruise(); - scene.v_ego = data.getVEgo(); - scene.curvature = data.getCurvature(); - scene.engaged = data.getEnabled(); - scene.engageable = data.getEngageable(); - scene.gps_planner_active = data.getGpsPlannerActive(); - scene.monitoring_active = data.getDriverMonitoringOn(); - scene.decel_for_model = data.getDecelForModel(); - auto alert_sound = data.getAlertSound(); + auto alert_sound = scene.controls_state.getAlertSound(); const auto sound_none = cereal::CarControl::HUDControl::AudibleAlert::NONE; if (alert_sound != s->alert_sound){ if (s->alert_sound != sound_none){ @@ -331,34 +315,33 @@ void handle_message(UIState *s, SubMaster &sm) { } if (alert_sound != sound_none){ play_alert_sound(alert_sound); - s->alert_type = data.getAlertType(); + s->alert_type = scene.controls_state.getAlertType(); } s->alert_sound = alert_sound; } - scene.alert_text1 = data.getAlertText1(); - scene.alert_text2 = data.getAlertText2(); - scene.alert_ts = event.getLogMonoTime(); - scene.alert_size = data.getAlertSize(); - auto alertStatus = data.getAlertStatus(); + scene.alert_text1 = scene.controls_state.getAlertText1(); + scene.alert_text2 = scene.controls_state.getAlertText2(); + scene.alert_size = scene.controls_state.getAlertSize(); + auto alertStatus = scene.controls_state.getAlertStatus(); if (alertStatus == cereal::ControlsState::AlertStatus::USER_PROMPT) { update_status(s, STATUS_WARNING); } else if (alertStatus == cereal::ControlsState::AlertStatus::CRITICAL) { update_status(s, STATUS_ALERT); } else{ - update_status(s, scene.engaged ? STATUS_ENGAGED : STATUS_DISENGAGED); + update_status(s, scene.controls_state.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED); } - scene.alert_blinkingrate = data.getAlertBlinkingRate(); - if (scene.alert_blinkingrate > 0.) { + float alert_blinkingrate = scene.controls_state.getAlertBlinkingRate(); + if (alert_blinkingrate > 0.) { if (s->alert_blinked) { if (s->alert_blinking_alpha > 0.0 && s->alert_blinking_alpha < 1.0) { - s->alert_blinking_alpha += (0.05*scene.alert_blinkingrate); + s->alert_blinking_alpha += (0.05*alert_blinkingrate); } else { s->alert_blinked = false; } } else { if (s->alert_blinking_alpha > 0.25) { - s->alert_blinking_alpha -= (0.05*scene.alert_blinkingrate); + s->alert_blinking_alpha -= (0.05*alert_blinkingrate); } else { s->alert_blinking_alpha += 0.25; s->alert_blinked = true; @@ -368,18 +351,8 @@ void handle_message(UIState *s, SubMaster &sm) { } if (sm.updated("radarState")) { auto data = sm["radarState"].getRadarState(); - - auto leaddatad = data.getLeadOne(); - scene.lead_status = leaddatad.getStatus(); - scene.lead_d_rel = leaddatad.getDRel(); - scene.lead_y_rel = leaddatad.getYRel(); - scene.lead_v_rel = leaddatad.getVRel(); - auto leaddatad2 = data.getLeadTwo(); - scene.lead_status2 = leaddatad2.getStatus(); - scene.lead_d_rel2 = leaddatad2.getDRel(); - scene.lead_y_rel2 = leaddatad2.getYRel(); - scene.lead_v_rel2 = leaddatad2.getVRel(); - s->livempc_or_radarstate_changed = true; + scene.lead_data[0] = data.getLeadOne(); + scene.lead_data[1] = data.getLeadTwo(); } if (sm.updated("liveCalibration")) { scene.world_objects_visible = true; @@ -390,7 +363,6 @@ void handle_message(UIState *s, SubMaster &sm) { } if (sm.updated("model")) { read_model(scene.model, sm["model"].getModel()); - s->model_changed = true; } // else if (which == cereal::Event::LIVE_MPC) { // auto data = event.getLiveMpc(); @@ -406,9 +378,6 @@ void handle_message(UIState *s, SubMaster &sm) { auto data = sm["uiLayoutState"].getUiLayoutState(); s->active_app = data.getActiveApp(); scene.uilayout_sidebarcollapsed = data.getSidebarCollapsed(); - if (data.getMockEngaged() != scene.uilayout_mockengaged) { - scene.uilayout_mockengaged = data.getMockEngaged(); - } } #ifdef SHOW_SPEEDLIMIT if (sm.updated("liveMapData")) { @@ -416,16 +385,7 @@ void handle_message(UIState *s, SubMaster &sm) { } #endif if (sm.updated("thermal")) { - auto data = sm["thermal"].getThermal(); - scene.networkType = data.getNetworkType(); - scene.networkStrength = data.getNetworkStrength(); - scene.batteryPercent = data.getBatteryPercent(); - scene.batteryCharging = data.getBatteryStatus() == "Charging"; - scene.freeSpace = data.getFreeSpace(); - scene.thermalStatus = data.getThermalStatus(); - scene.paTemp = data.getPa0(); - - s->thermal_started = data.getStarted(); + scene.thermal = sm["thermal"].getThermal(); } if (sm.updated("ubloxGnss")) { auto data = sm["ubloxGnss"].getUbloxGnss(); @@ -438,20 +398,15 @@ void handle_message(UIState *s, SubMaster &sm) { s->hardware_timeout = 5*30; // 5 seconds at 30 fps } if (sm.updated("driverState")) { - auto data = sm["driverState"].getDriverState(); - scene.face_prob = data.getFaceProb(); - auto fxy_list = data.getFacePosition(); - scene.face_x = fxy_list[0]; - scene.face_y = fxy_list[1]; + scene.driver_state = sm["driverState"].getDriverState(); } if (sm.updated("dMonitoringState")) { auto data = sm["dMonitoringState"].getDMonitoringState(); scene.is_rhd = data.getIsRHD(); - scene.awareness_status = data.getAwarenessStatus(); s->preview_started = data.getIsPreview(); } - s->started = s->thermal_started || s->preview_started ; + s->started = scene.thermal.getStarted() || s->preview_started ; // Handle onroad/offroad transition if (!s->started) { if (s->status != STATUS_STOPPED) { @@ -471,9 +426,7 @@ void handle_message(UIState *s, SubMaster &sm) { } static void check_messages(UIState *s) { - while (true) { - if (s->sm->update(0) == 0) - break; + if (s->sm->update(0) > 0){ handle_message(s, *(s->sm)); } } @@ -911,7 +864,7 @@ int main(int argc, char* argv[]) { if (s->volume_timeout > 0) { s->volume_timeout--; } else { - int volume = fmin(MAX_VOLUME, MIN_VOLUME + s->scene.v_ego / 5); // up one notch every 5 m/s + int volume = fmin(MAX_VOLUME, MIN_VOLUME + s->scene.controls_state.getVEgo() / 5); // up one notch every 5 m/s set_volume(volume); s->volume_timeout = 5 * UI_FREQ; } diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 25215fe08b..2b70a9b27c 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -90,7 +90,6 @@ const uint8_t bg_colors[][4] = { [STATUS_ALERT] = {0xC9, 0x22, 0x31, 0xff}, }; - typedef struct UIScene { int frontview; int fullview; @@ -105,61 +104,35 @@ typedef struct UIScene { bool world_objects_visible; mat4 extrinsic_matrix; // Last row is 0 so we can use mat4. - float v_cruise; - uint64_t v_cruise_update_ts; - float v_ego; - bool decel_for_model; - float speedlimit; bool speedlimit_valid; - bool map_valid; - - float curvature; - int engaged; - bool engageable; - bool monitoring_active; + bool is_rhd; + bool map_valid; bool uilayout_sidebarcollapsed; bool uilayout_mapenabled; - bool uilayout_mockengaged; // responsive layout int ui_viz_rx; int ui_viz_rw; int ui_viz_ro; - int lead_status; - float lead_d_rel, lead_y_rel, lead_v_rel; - - int lead_status2; - float lead_d_rel2, lead_y_rel2, lead_v_rel2; - - float face_prob; - bool is_rhd; - float face_x, face_y; - int front_box_x, front_box_y, front_box_width, front_box_height; - uint64_t alert_ts; std::string alert_text1; std::string alert_text2; cereal::ControlsState::AlertSize alert_size; - float alert_blinkingrate; - - float awareness_status; // Used to show gps planner status bool gps_planner_active; - cereal::ThermalData::NetworkType networkType; - cereal::ThermalData::NetworkStrength networkStrength; - int batteryPercent; - bool batteryCharging; - float freeSpace; - cereal::ThermalData::ThermalStatus thermalStatus; - int paTemp; cereal::HealthData::HwType hwType; int satelliteCount; uint8_t athenaStatus; + + cereal::ThermalData::Reader thermal; + cereal::RadarState::LeadData::Reader lead_data[2]; + cereal::ControlsState::Reader controls_state; + cereal::DriverState::Reader driver_state; } UIScene; typedef struct { @@ -266,17 +239,13 @@ typedef struct UIState { float alert_blinking_alpha; bool alert_blinked; bool started; - bool thermal_started, preview_started; + bool preview_started; bool vision_seen; std::atomic light_sensor; int touch_fd; - // Hints for re-calculations and redrawing - bool model_changed; - bool livempc_or_radarstate_changed; - GLuint frame_vao[2], frame_vbo[2], frame_ibo[2]; mat4 rear_frame_mat, front_frame_mat; From 8c346dfae56e839d11a45b38ca8049556bc4ae38 Mon Sep 17 00:00:00 2001 From: "dependabot-preview[bot]" <27856297+dependabot-preview[bot]@users.noreply.github.com> Date: Fri, 5 Jun 2020 15:55:17 -0700 Subject: [PATCH 224/656] Create Dependabot config file (#1648) Co-authored-by: dependabot-preview[bot] <27856297+dependabot-preview[bot]@users.noreply.github.com> --- .github/dependabot.yml | 8 ++++++++ 1 file changed, 8 insertions(+) create mode 100644 .github/dependabot.yml diff --git a/.github/dependabot.yml b/.github/dependabot.yml new file mode 100644 index 0000000000..def16ca23e --- /dev/null +++ b/.github/dependabot.yml @@ -0,0 +1,8 @@ +version: 2 +updates: +- package-ecosystem: pip + directory: "/" + schedule: + interval: daily + time: '15:00' + open-pull-requests-limit: 10 From 15dc6044d44e7f85293cb9b0187c7d2a51a84c55 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 5 Jun 2020 16:01:53 -0700 Subject: [PATCH 225/656] Remove slow down for turns (#1647) * Remove slow down for turns * update ref --- selfdrive/controls/lib/planner.py | 31 +----------------------- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 2 insertions(+), 31 deletions(-) diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index ea87adae55..88c4d694aa 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -78,8 +78,6 @@ class Planner(): self.a_acc = 0.0 self.v_cruise = 0.0 self.a_cruise = 0.0 - self.v_model = 0.0 - self.a_model = 0.0 self.longitudinalPlanSource = 'cruise' self.fcw_checker = FCWChecker() @@ -90,7 +88,7 @@ class Planner(): def choose_solution(self, v_cruise_setpoint, enabled): if enabled: - solutions = {'model': self.v_model, 'cruise': self.v_cruise} + solutions = {'cruise': self.v_cruise} if self.mpc1.prev_lead_status: solutions['mpc1'] = self.mpc1.v_mpc if self.mpc2.prev_lead_status: @@ -109,9 +107,6 @@ class Planner(): elif slowest == 'cruise': self.v_acc = self.v_cruise self.a_acc = self.a_cruise - elif slowest == 'model': - self.v_acc = self.v_model - self.a_acc = self.a_model self.v_acc_future = min([self.mpc1.v_mpc_future, self.mpc2.v_mpc_future, v_cruise_setpoint]) @@ -133,24 +128,6 @@ class Planner(): enabled = (long_control_state == LongCtrlState.pid) or (long_control_state == LongCtrlState.stopping) following = lead_1.status and lead_1.dRel < 45.0 and lead_1.vLeadK > v_ego and lead_1.aLeadK > 0.0 - if len(sm['model'].path.poly): - path = list(sm['model'].path.poly) - - # Curvature of polynomial https://en.wikipedia.org/wiki/Curvature#Curvature_of_the_graph_of_a_function - # y = a x^3 + b x^2 + c x + d, y' = 3 a x^2 + 2 b x + c, y'' = 6 a x + 2 b - # k = y'' / (1 + y'^2)^1.5 - # TODO: compute max speed without using a list of points and without numpy - y_p = 3 * path[0] * self.path_x**2 + 2 * path[1] * self.path_x + path[2] - y_pp = 6 * path[0] * self.path_x + 2 * path[1] - curv = y_pp / (1. + y_p**2)**1.5 - - a_y_max = 2.975 - v_ego * 0.0375 # ~1.85 @ 75mph, ~2.6 @ 25mph - v_curvature = np.sqrt(a_y_max / np.clip(np.abs(curv), 1e-4, None)) - model_speed = np.min(v_curvature) - model_speed = max(20.0 * CV.MPH_TO_MS, model_speed) # Don't slow down below 20mph - else: - model_speed = MAX_SPEED - # Calculate speed for normal cruise control if enabled and not self.first_loop: accel_limits = [float(x) for x in calc_cruise_accel_limits(v_ego, following)] @@ -168,12 +145,6 @@ class Planner(): jerk_limits[1], jerk_limits[0], LON_MPC_STEP) - self.v_model, self.a_model = speed_smoother(self.v_acc_start, self.a_acc_start, - model_speed, - 2*accel_limits[1], accel_limits[0], - 2*jerk_limits[1], jerk_limits[0], - LON_MPC_STEP) - # cruise speed can't be negative even is user is distracted self.v_cruise = max(self.v_cruise, 0.) else: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 47366239cf..c285bfb49c 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -5abe4f99eec3633bc30fda47c272e0f19a840a29 \ No newline at end of file +0533f640ab27f7b5af57aa4ebf4a29200550b3e8 \ No newline at end of file From 7770041f9201c4f84717435b7a585fd70a937923 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Fri, 5 Jun 2020 17:40:56 -0700 Subject: [PATCH 226/656] Getting PC openpilot working again (#1650) * fixup keras_runner to work and be nicer * truncate the lane lines based on the valid len --- selfdrive/common/modeldata.h | 1 + selfdrive/modeld/modeld.cc | 5 +-- selfdrive/modeld/runners/keras_runner.py | 39 +++++++++--------------- selfdrive/modeld/runners/tfmodel.cc | 12 ++++---- selfdrive/ui/paint.cc | 23 +++++--------- selfdrive/ui/ui.cc | 2 ++ 6 files changed, 33 insertions(+), 49 deletions(-) diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h index 555a75614c..111e20a413 100644 --- a/selfdrive/common/modeldata.h +++ b/selfdrive/common/modeldata.h @@ -13,6 +13,7 @@ typedef struct PathData { float std; float stds[MODEL_PATH_DISTANCE]; float poly[POLYFIT_DEGREE]; + float validLen; } PathData; typedef struct LeadData { diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 793474e652..5404f61b3c 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -107,7 +107,7 @@ int main(int argc, char **argv) { char cBuffer[1024]; clGetPlatformInfo(platform_id[clPlatform], CL_PLATFORM_NAME, sizeof(cBuffer), &cBuffer, NULL); - LOGD("got %d opencl platform(s), using %s", num_platforms, cBuffer); + LOG("got %d opencl platform(s), using %s", num_platforms, cBuffer); err = clGetDeviceIDs(platform_id[clPlatform], CL_DEVICE_TYPE_DEFAULT, 1, &device_id, &num_devices); @@ -118,6 +118,7 @@ int main(int argc, char **argv) { q = clCreateCommandQueue(context, device_id, 0, &err); assert(err == 0); + LOGD("opencl init complete"); } // init the models @@ -192,7 +193,7 @@ int main(int argc, char **argv) { model_publish(pm, extra.frame_id, model_buf, extra.timestamp_eof); posenet_publish(pm, extra.frame_id, model_buf, extra.timestamp_eof); - LOGD("model process: %.2fms, from last %.2fms", mt2-mt1, mt1-last); + LOG("model process: %.2fms, from last %.2fms", mt2-mt1, mt1-last); last = mt1; } diff --git a/selfdrive/modeld/runners/keras_runner.py b/selfdrive/modeld/runners/keras_runner.py index c692ac5988..0a9eddeac7 100755 --- a/selfdrive/modeld/runners/keras_runner.py +++ b/selfdrive/modeld/runners/keras_runner.py @@ -5,12 +5,9 @@ from __future__ import print_function import tensorflow as tf # pylint: disable=import-error import os import sys -import tensorflow.keras as keras # pylint: disable=import-error import numpy as np -from tensorflow.keras.models import Model # pylint: disable=import-error from tensorflow.keras.models import load_model # pylint: disable=import-error - def read(sz): dd = [] gt = 0 @@ -19,21 +16,24 @@ def read(sz): assert(len(st) > 0) dd.append(st) gt += len(st) - return np.fromstring(b''.join(dd), dtype=np.float32) - + return np.frombuffer(b''.join(dd), dtype=np.float32) def write(d): os.write(1, d.tobytes()) - def run_loop(m): - isize = m.inputs[0].shape[1] - osize = m.outputs[0].shape[1] - print("ready to run keras model %d -> %d" % (isize, osize), file=sys.stderr) + ishapes = [[1]+ii.shape[1:] for ii in m.inputs] + print("ready to run keras model", ishapes, file=sys.stderr) while 1: - idata = read(isize).reshape((1, isize)) - ret = m.predict_on_batch(idata) - write(ret) + inputs = [] + for shp in ishapes: + ts = np.product(shp) + #print("reshaping %s with offset %d" % (str(shp), offset), file=sys.stderr) + inputs.append(read(ts).reshape(shp)) + ret = m.predict_on_batch(inputs) + #print(ret, file=sys.stderr) + for r in ret: + write(r) if __name__ == "__main__": @@ -45,17 +45,6 @@ if __name__ == "__main__": m = load_model(sys.argv[1]) print(m, file=sys.stderr) - bs = [int(np.product(ii.shape[1:])) for ii in m.inputs] - ri = keras.layers.Input((sum(bs),)) - - tii = [] - acc = 0 - for i, ii in enumerate(m.inputs): - print(ii, file=sys.stderr) - ti = keras.layers.Lambda(lambda x, i=i: x[:, acc:acc + bs[i]], output_shape=(1, bs[i]))(ri) - acc += bs[i] - tr = keras.layers.Reshape(ii.shape[1:])(ti) - tii.append(tr) - no = keras.layers.Concatenate()(m(tii)) - m = Model(inputs=ri, outputs=[no]) + run_loop(m) + diff --git a/selfdrive/modeld/runners/tfmodel.cc b/selfdrive/modeld/runners/tfmodel.cc index c955e54a77..c96fedfbf0 100644 --- a/selfdrive/modeld/runners/tfmodel.cc +++ b/selfdrive/modeld/runners/tfmodel.cc @@ -62,20 +62,20 @@ void TFModel::pwrite(float *buf, int size) { cbuf += err; tw -= err; } - //printf("host write done\n"); + LOGD("host write of size %d done", size); } void TFModel::pread(float *buf, int size) { char *cbuf = (char *)buf; int tr = size*sizeof(float); while (tr > 0) { + LOGD("host read remaining %d/%d", tr, size*sizeof(float)); int err = read(pipeout[0], cbuf, tr); - //printf("host read %d/%d\n", err, tr); assert(err >= 0); cbuf += err; tr -= err; } - //printf("host read done\n"); + LOGD("host read done"); } void TFModel::addRecurrent(float *state, int state_size) { @@ -99,12 +99,12 @@ void TFModel::execute(float *net_input_buf, int buf_size) { if (desire_input_buf != NULL) { pwrite(desire_input_buf, desire_state_size); } - if (rnn_input_buf != NULL) { - pwrite(rnn_input_buf, rnn_state_size); - } if (traffic_convention_input_buf != NULL) { pwrite(traffic_convention_input_buf, traffic_convention_size); } + if (rnn_input_buf != NULL) { + pwrite(rnn_input_buf, rnn_state_size); + } pread(output, output_size); } diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 3be25899b0..60e403aff6 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -247,16 +247,6 @@ static void ui_draw_track(UIState *s, bool is_mpc, track_vertices_data *pvd) { nvgFill(s->vg); } -static void draw_steering(UIState *s, float curvature) { - float points[50]; - for (int i = 0; i < 50; i++) { - float y_actual = i * tan(asin(clamp(i * curvature, -0.999, 0.999)) / 2.); - points[i] = y_actual; - } - - // ui_draw_lane_edge(s, points, 0.0, nvgRGBA(0, 0, 255, 128), 5); -} - static void draw_frame(UIState *s) { const UIScene *scene = &s->scene; @@ -298,9 +288,10 @@ static inline bool valid_frame_pt(UIState *s, float x, float y) { return x >= 0 && x <= s->rgb_width && y >= 0 && y <= s->rgb_height; } -static void update_lane_line_data(UIState *s, const float *points, float off, bool is_ghost, model_path_vertices_data *pvd) { +static void update_lane_line_data(UIState *s, const float *points, float off, bool is_ghost, model_path_vertices_data *pvd, float valid_len) { pvd->cnt = 0; - for (int i = 0; i < MODEL_PATH_MAX_VERTICES_CNT / 2; i++) { + int rcount = fmin(MODEL_PATH_MAX_VERTICES_CNT / 2, valid_len); + for (int i = 0; i < rcount; i++) { float px = (float)i; float py = points[i] - off; const vec4 p_car_space = (vec4){{px, py, 0., 1.}}; @@ -311,7 +302,7 @@ static void update_lane_line_data(UIState *s, const float *points, float off, bo pvd->v[pvd->cnt].y = p_full_frame.v[1]; pvd->cnt += 1; } - for (int i = MODEL_PATH_MAX_VERTICES_CNT / 2; i > 0; i--) { + for (int i = rcount; i > 0; i--) { float px = (float)i; float py = is_ghost?(points[i]-off):(points[i]+off); const vec4 p_car_space = (vec4){{px, py, 0., 1.}}; @@ -325,10 +316,10 @@ static void update_lane_line_data(UIState *s, const float *points, float off, bo } static void update_all_lane_lines_data(UIState *s, const PathData &path, model_path_vertices_data *pstart) { - update_lane_line_data(s, path.points, 0.025*path.prob, false, pstart); + update_lane_line_data(s, path.points, 0.025*path.prob, false, pstart, path.validLen); float var = fmin(path.std, 0.7); - update_lane_line_data(s, path.points, -var, true, pstart + 1); - update_lane_line_data(s, path.points, var, true, pstart + 2); + update_lane_line_data(s, path.points, -var, true, pstart + 1, path.validLen); + update_lane_line_data(s, path.points, var, true, pstart + 2, path.validLen); } static void ui_draw_lane(UIState *s, const PathData *path, model_path_vertices_data *pstart, NVGcolor color) { diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 1807adee70..96ec3571af 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -279,6 +279,8 @@ static void read_path(PathData& p, const cereal::ModelData::PathData::Reader &pa for (int i = 0; i < MODEL_PATH_DISTANCE; i++) { p.points[i] = p.poly[0] * (i*i*i) + p.poly[1] * (i*i)+ p.poly[2] * i + p.poly[3]; } + + p.validLen = pathp.getValidLen(); } static void read_model(ModelData &d, const cereal::ModelData::Reader &model) { From 51061175252d14265e608fe6ed5640d0840fdb70 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 5 Jun 2020 21:52:58 -0700 Subject: [PATCH 227/656] More rigorous definition of calibration --- common/transformations/README.md | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/common/transformations/README.md b/common/transformations/README.md index dd9cdcc78b..f10852228a 100644 --- a/common/transformations/README.md +++ b/common/transformations/README.md @@ -45,7 +45,12 @@ while rotating around the rotated axes, not the original axes. Calibration ------ -EONs are not all mounted in the exact same way. To compensate for the effects of this the vision model takes in an image that is "calibrated". This means the image is aligned so the direction of travel of the car when it is going straight and the road is flat is always in the location on the image. This calibration is defined by a pitch and yaw angle that describe the direction of travel vector in device frame. +Device frame is aligned with the road-facing camera used by openpilot. However, when controlling the vehicle it makes more sense to think in a reference frame aligned with the vehicle. These two reference frames are not necessarily aligned. Calibration is defined as the roll, pitch and yaw angles that describe the orientation of the vehicle in device frame. The vehicle orientation is the orientation of the vehicles's body, the orientation of the vehicle can change relative to the road because of suspension movements. + +The roll of the vehicle is defined to be 0 when the vehicle is on a flat road and not turning. Pitch and yaw are defined as the angles that describe the direction in which the vehicle travels when it is driving on a flat road and not turning. + +It is important for openpilot's driving model to take in images that look as if the calibration angles were all zero. To achieve this the images input into the model are transformed with the estimated calibration angles. At the moment, roll calibration is always estimated to be zero. + Example ------ From c6bd1874503b26e8443ecb28afd6819b44684e78 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 6 Jun 2020 21:21:25 -0700 Subject: [PATCH 228/656] clean up webcam readme --- panda | 2 +- tools/webcam/README.md | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/panda b/panda index e0a706e4f0..6848c7576b 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit e0a706e4f013b69253f300eeeda3a60915e10adf +Subproject commit 6848c7576b5ab2b0944e7e0d37ce856242ce673d diff --git a/tools/webcam/README.md b/tools/webcam/README.md index e5589fbc5f..9243a79061 100644 --- a/tools/webcam/README.md +++ b/tools/webcam/README.md @@ -5,7 +5,7 @@ What's needed: - Python 3.7.3 - GPU (recommended) - Two USB webcams, at least 720p and 78 degrees FOV (e.g. Logitech C920/C615) -- [Car harness](https://comma.ai/shop/products/comma-car-harness) w/ black panda (or the outdated grey panda/giraffe combo) to connect to your car +- [Car harness](https://comma.ai/shop/products/comma-car-harness) with black panda (or the outdated grey panda/giraffe combo) to connect to your car - [Panda paw](https://comma.ai/shop/products/panda-paw) (or USB-A to USB-A cable) to connect panda to your computer - Tape, Charger, ... That's it! @@ -17,7 +17,7 @@ git clone https://github.com/commaai/openpilot.git ``` - Follow [this readme](https://github.com/commaai/openpilot/tree/master/tools) to install the requirements - Add line "export PYTHONPATH=$HOME/openpilot" to your ~/.bashrc -- You also need to install tensorflow 2.2 and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 +- Install tensorflow 2.2 and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 - Install [OpenCL Driver](http://registrationcenter-download.intel.com/akdlm/irc_nas/vcp/15532/l_opencl_p_18.1.0.015.tgz) - (Note: the code assumes cl platforms order to be 0.GPU/1.CPU when running clinfo; if reverse, change the -1 to -2 in selfdrive/modeld/modeld.cc#L130; helping us refactor this mess is encouraged) - Install [OpenCV4](https://www.pyimagesearch.com/2018/08/15/how-to-install-opencv-4-on-ubuntu/) (ignore the Python part) @@ -26,13 +26,13 @@ git clone https://github.com/commaai/openpilot.git ``` cd ~/openpilot ``` -- check out selfdrive/camerad/cameras/camera_webcam.cc line72&146 before building if any camera is upside down +- check out selfdrive/camerad/cameras/camera_webcam.cc lines 72 and 146 before building if any camera is upside down ``` scons use_webcam=1 touch prebuilt ``` -## Connect the hardwares +## Connect the hardware - Connect the road facing camera first, then the driver facing camera - (default indexes are 1 and 2; can be modified in selfdrive/camerad/cameras/camera_webcam.cc) - Connect your computer to panda From 4509ee7247ce3fdc9400501c4c16b13d6b0a29a5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 8 Jun 2020 13:12:55 -0700 Subject: [PATCH 229/656] bump submodules --- cereal | 2 +- panda | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 7dcbf6c41f..1aaf1bfd7c 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 7dcbf6c41fb30b85dbb597fe771dc9f5e7f29161 +Subproject commit 1aaf1bfd7c07e1c5184e8f13823e8ed02e2c7af2 diff --git a/panda b/panda index 6848c7576b..70e39040b4 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 6848c7576b5ab2b0944e7e0d37ce856242ce673d +Subproject commit 70e39040b48601cb8de571b81cf4ac88b918bae2 From c8377131dc155d1c1330762fbe79a47205204604 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Tue, 9 Jun 2020 00:15:22 +0300 Subject: [PATCH 230/656] fix auto resume logic (#1657) --- selfdrive/car/hyundai/carcontroller.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index dfd07d581c..9026afbb3a 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -89,7 +89,7 @@ class CarController(): # interval after 6 msgs if self.resume_cnt > 5: self.last_resume_frame = frame - self.clu11_cnt = 0 + self.resume_cnt = 0 # reset lead distnce after the car starts moving elif self.last_lead_distance != 0: self.last_lead_distance = 0 From c24a7e248a295641f58d39e0db25dde1b742fc16 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Mon, 8 Jun 2020 14:24:14 -0700 Subject: [PATCH 231/656] Release cleanup (#1649) * start cleanup * whitelist submodule release files * don't need to ship tests * revert changes to build script * add those tests back * fix typo * whitelist dbcs * test * run the right test * whitelist opendbc/can * revert that * add missing dotfiles * clean up * ford DBCs Co-authored-by: Comma Device --- .github/workflows/test.yaml | 10 +- release/build_devel.sh | 38 +----- release/files_common | 142 +++++++++++++++++---- selfdrive/car/tests/test_car_interfaces.py | 1 + 4 files changed, 132 insertions(+), 59 deletions(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index ced9fe65cc..d2b04ef1a6 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -28,9 +28,6 @@ jobs: cp -pR --parents $(cat release/files_common) $TEST_DIR cp Dockerfile.openpilot $TEST_DIR - # copy submodules - cp -pR panda/ opendbc/ cereal/ $TEST_DIR - # need this to build on x86 cp -pR --parents phonelibs/libyuv phonelibs/snpe \ external/bin selfdrive/modeld/runners $TEST_DIR @@ -41,8 +38,11 @@ jobs: mkdir laika laika_repo tools release - name: Build Docker image run: cd $TEST_DIR && eval "$BUILD" - - name: Build openpilot - run: $RUN "cd /tmp/openpilot && scons -j$(nproc)" + - name: Build openpiot and run quick check + run: | + $RUN "cd /tmp/openpilot && \ + scons -j$(nproc) && \ + $UNIT_TEST selfdrive/car" docker_push: name: docker push diff --git a/release/build_devel.sh b/release/build_devel.sh index c3028d5520..32c8baf869 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -9,23 +9,6 @@ echo $$ > /dev/cpuset/app/tasks echo $PPID > /dev/cpuset/app/tasks -add_subtree() { - echo "[-] adding $2 subtree T=$SECONDS" - if [ -d "$2" ]; then - if git subtree pull --prefix "$2" https://github.com/commaai/"$1".git "$3" --squash -m "Merge $2 subtree"; then - echo "git subtree pull succeeds" - else - echo "git subtree pull failed, fixing" - git merge --abort || true - git rm -r $2 - git commit -m "Remove old $2 subtree" - git subtree add --prefix "$2" https://github.com/commaai/"$1".git "$3" --squash - fi - else - git subtree add --prefix "$2" https://github.com/commaai/"$1".git "$3" --squash - fi -} - SOURCE_DIR=/data/openpilot_source TARGET_DIR=/data/openpilot @@ -39,13 +22,12 @@ export GIT_SSH_COMMAND="ssh -i /tmp/deploy_key" echo "[-] Setting up repo T=$SECONDS" if [ ! -d "$TARGET_DIR" ]; then - mkdir -p $TARGET_DIR - cd $TARGET_DIR - git init - git remote add origin git@github.com:commaai/openpilot.git + mkdir -p $TARGET_DIR + cd $TARGET_DIR + git init + git remote add origin git@github.com:commaai/openpilot.git fi - echo "[-] fetching public T=$SECONDS" cd $TARGET_DIR git prune || true @@ -61,11 +43,6 @@ git checkout master-ci git reset --hard origin/devel git clean -xdf -# subtrees to make updates more reliable. updating them needs a clean tree -add_subtree "cereal" "cereal" master -add_subtree "panda" "panda" master -add_subtree "opendbc" "opendbc" master - # leave .git alone echo "[-] erasing old openpilot T=$SECONDS" rm -rf $TARGET_DIR/* $TARGET_DIR/.gitmodules @@ -73,9 +50,6 @@ rm -rf $TARGET_DIR/* $TARGET_DIR/.gitmodules # delete dotfiles in root find . -maxdepth 1 -type f -delete -# dont delete our subtrees -git checkout -- cereal panda opendbc - # reset tree and get version cd $SOURCE_DIR git clean -xdf @@ -122,8 +96,8 @@ make obj/comma.bin popd if [ ! -z "$PUSH" ]; then - echo "[-] Pushing to $PUSH T=$SECONDS" - git push -f origin master-ci:$PUSH + echo "[-] Pushing to $PUSH T=$SECONDS" + git push -f origin master-ci:$PUSH fi echo "[-] done pushing T=$SECONDS" diff --git a/release/files_common b/release/files_common index a0fc3743ff..1bd4929770 100644 --- a/release/files_common +++ b/release/files_common @@ -1,9 +1,6 @@ README.md SAFETY.md -codecov.yml -lgtm.yml - .gitignore LICENSE launch_chffrplus.sh @@ -43,7 +40,6 @@ common/manager_helpers.py common/kalman/.gitignore common/kalman/* -common/kalman/tests/* common/transformations/__init__.py common/transformations/camera.py @@ -73,8 +69,6 @@ selfdrive/updated.py selfdrive/athena/__init__.py selfdrive/athena/athenad.py selfdrive/athena/manage_athenad.py -selfdrive/athena/test.py -selfdrive/athena/test_helpers.py selfdrive/boardd/.gitignore selfdrive/boardd/SConscript @@ -84,7 +78,6 @@ selfdrive/boardd/boardd.py selfdrive/boardd/boardd_api_impl.pyx selfdrive/boardd/boardd_setup.py selfdrive/boardd/can_list_to_can_capnp.cc -selfdrive/boardd/tests/** selfdrive/car/__init__.py selfdrive/car/car_helpers.py @@ -93,6 +86,8 @@ selfdrive/car/interfaces.py selfdrive/car/vin.py selfdrive/car/fw_versions.py selfdrive/car/isotp_parallel_query.py +selfdrive/car/tests/__init__.py +selfdrive/car/tests/test_car_interfaces.py selfdrive/car/chrysler/__init__.py selfdrive/car/chrysler/carstate.py selfdrive/car/chrysler/interface.py @@ -100,7 +95,6 @@ selfdrive/car/chrysler/radar_interface.py selfdrive/car/chrysler/values.py selfdrive/car/chrysler/carcontroller.py selfdrive/car/chrysler/chryslercan.py -selfdrive/car/chrysler/test_chryslercan.py selfdrive/car/honda/__init__.py selfdrive/car/honda/carstate.py selfdrive/car/honda/interface.py @@ -170,7 +164,6 @@ selfdrive/clocksd/.gitignore selfdrive/clocksd/SConscript selfdrive/clocksd/clocksd.cc -selfdrive/debug/mpc/* selfdrive/debug/*.py selfdrive/common/SConscript @@ -208,7 +201,6 @@ selfdrive/common/spinner.h selfdrive/controls/__init__.py -selfdrive/controls/tests/* selfdrive/controls/controlsd.py selfdrive/controls/plannerd.py selfdrive/controls/radard.py @@ -269,7 +261,6 @@ selfdrive/locationd/ubloxd_main.cc selfdrive/locationd/ubloxd_test.cc selfdrive/locationd/ublox_msg.cc selfdrive/locationd/ublox_msg.h -selfdrive/locationd/test/*.py selfdrive/locationd/locationd.py selfdrive/locationd/paramsd.py @@ -308,7 +299,6 @@ selfdrive/loggerd/__init__.py selfdrive/loggerd/config.py selfdrive/loggerd/uploader.py selfdrive/loggerd/deleter.py -selfdrive/loggerd/tests/* selfdrive/sensord/SConscript selfdrive/sensord/gpsd.cc @@ -321,19 +311,10 @@ selfdrive/thermald/thermald.py selfdrive/thermald/power_monitoring.py selfdrive/test/__init__.py -selfdrive/test/longitudinal_maneuvers/*.py selfdrive/test/test_openpilot.py selfdrive/test/test_fingerprints.py selfdrive/test/test_car_models.py -selfdrive/test/process_replay/__init__.py -selfdrive/test/process_replay/compare_logs.py -selfdrive/test/process_replay/process_replay.py -selfdrive/test/process_replay/test_processes.py -selfdrive/test/process_replay/update_refs.py -selfdrive/test/process_replay/ref_commit -selfdrive/test/process_replay/README.md - selfdrive/ui/SConscript selfdrive/ui/*.c selfdrive/ui/*.cc @@ -437,6 +418,123 @@ installer/updater/Makefile scripts/update_now.sh scripts/stop_updater.sh -pyextra/** +pyextra/logentries/** rednose/** + +cereal/.gitignore +cereal/__init__.py +cereal/car.capnp +cereal/log.capnp +cereal/services.py +cereal/service_list.yaml +cereal/SConscript +cereal/include/** +cereal/messaging/.gitignore +cereal/messaging/__init__.py +cereal/messaging/bridge.cc +cereal/messaging/impl_msgq.cc +cereal/messaging/impl_msgq.hpp +cereal/messaging/impl_zmq.cc +cereal/messaging/impl_zmq.hpp +cereal/messaging/messaging.cc +cereal/messaging/messaging.hpp +cereal/messaging/messaging.pxd +cereal/messaging/messaging_pyx.pyx +cereal/messaging/messaging_pyx_setup.py +cereal/messaging/msgq.cc +cereal/messaging/msgq.hpp +cereal/messaging/socketmaster.cc + +panda/.gitignore +panda/__init__.py +panda/VERSION +panda/board/** +panda/certs/** +panda/common/** +panda/crypto/** +panda/python/** + +opendbc/.gitignore +opendbc/__init__.py +opendbc/can/__init__.py +opendbc/can/SConscript +opendbc/can/can_define.py +opendbc/can/common.cc +opendbc/can/common.h +opendbc/can/common.pxd +opendbc/can/common_dbc.h +opendbc/can/dbc.cc +opendbc/can/dbc.py +opendbc/can/dbc_template.cc +opendbc/can/packer.cc +opendbc/can/packer.py +opendbc/can/packer_pyx.pyx +opendbc/can/packer_pyx_setup.py +opendbc/can/parser.cc +opendbc/can/parser.py +opendbc/can/parser_pyx.pyx +opendbc/can/parser_pyx_setup.py +opendbc/can/process_dbc.py +opendbc/can/dbc_out/.gitkeep +opendbc/can/dbc_out/.gitignore + +opendbc/chrysler_pacifica_2017_hybrid.dbc +opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc + +opendbc/gm_global_a_powertrain.dbc +opendbc/gm_global_a_object.dbc +opendbc/gm_global_a_chassis.dbc + +opendbc/ford_fusion_2018_pt.dbc +opendbc/ford_fusion_2018_adas.dbc + +opendbc/honda_accord_s2t_2018_can_generated.dbc +opendbc/honda_accord_lx15t_2018_can_generated.dbc +opendbc/acura_ilx_2016_can_generated.dbc +opendbc/acura_rdx_2018_can_generated.dbc +opendbc/honda_civic_touring_2016_can_generated.dbc +opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc +opendbc/honda_civic_sedan_16_diesel_2019_can_generated.dbc +opendbc/honda_crv_touring_2016_can_generated.dbc +opendbc/honda_crv_ex_2017_can_generated.dbc +opendbc/honda_crv_executive_2016_can_generated.dbc +opendbc/honda_crv_hybrid_2019_can_generated.dbc +opendbc/honda_fit_ex_2018_can_generated.dbc +opendbc/honda_hrv_touring_2019_can_generated.dbc +opendbc/honda_odyssey_exl_2018_generated.dbc +opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc +opendbc/honda_pilot_touring_2017_can_generated.dbc +opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc +opendbc/honda_insight_ex_2019_can_generated.dbc +opendbc/acura_ilx_2016_nidec.dbc + +opendbc/hyundai_kia_generic.dbc + +opendbc/mazda_2017.dbc + +opendbc/nissan_x_trail_2017.dbc +opendbc/nissan_leaf_2018.dbc + +opendbc/subaru_global_2017.dbc + +opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc +opendbc/toyota_rav4_2017_pt_generated.dbc +opendbc/toyota_prius_2017_pt_generated.dbc +opendbc/toyota_corolla_2017_pt_generated.dbc +opendbc/lexus_rx_350_2016_pt_generated.dbc +opendbc/lexus_rx_hybrid_2017_pt_generated.dbc +opendbc/toyota_nodsu_pt_generated.dbc +opendbc/toyota_nodsu_hybrid_pt_generated.dbc +opendbc/toyota_camry_hybrid_2018_pt_generated.dbc +opendbc/toyota_highlander_2017_pt_generated.dbc +opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc +opendbc/toyota_avalon_2017_pt_generated.dbc +opendbc/toyota_sienna_xle_2018_pt_generated.dbc +opendbc/lexus_is_2018_pt_generated.dbc +opendbc/lexus_ct200h_2018_pt_generated.dbc +opendbc/lexus_nx300h_2018_pt_generated.dbc +opendbc/toyota_adas.dbc +opendbc/toyota_tss2_adas.dbc + +opendbc/vw_mqb_2010.dbc diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index c6c908efd8..1800a71d03 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -13,6 +13,7 @@ class TestCarInterfaces(unittest.TestCase): all_cars = all_known_cars() for car_name in all_cars: + print(car_name) fingerprint = FINGERPRINTS[car_name][0] CarInterface, CarController, CarState = interfaces[car_name] From 5fdb60d43e8d141c086d9c25f2235cfb18106a17 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 9 Jun 2020 08:24:55 +0800 Subject: [PATCH 232/656] remove function is_leon (#1660) --- selfdrive/ui/ui.cc | 19 ++----------------- 1 file changed, 2 insertions(+), 17 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 96ec3571af..8127e9ee05 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -14,6 +14,7 @@ #include "common/touch.h" #include "common/visionimg.h" #include "common/params.h" +#include "common/utilpp.h" #include "ui.hpp" static int last_brightness = -1; @@ -716,22 +717,6 @@ fail: #endif -int is_leon() { - #define MAXCHAR 1000 - FILE *fp; - char str[MAXCHAR]; - const char* filename = "/proc/cmdline"; - - fp = fopen(filename, "r"); - if (fp == NULL){ - printf("Could not open file %s",filename); - return 0; - } - fgets(str, MAXCHAR, fp); - fclose(fp); - return strstr(str, "letv") != NULL; -} - int main(int argc, char* argv[]) { int err; setpriority(PRIO_PROCESS, 0, -14); @@ -762,7 +747,7 @@ int main(int argc, char* argv[]) { ui_sound_init(); // light sensor scaling params - const int LEON = is_leon(); + const bool LEON = util::read_file("/proc/cmdline").find("letv") != std::string::npos; float brightness_b, brightness_m; int result = read_param(&brightness_b, "BRIGHTNESS_B", true); From 7bf9b04570b0eea77de33181a58134ec8ddb4b19 Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Mon, 8 Jun 2020 19:29:33 -0700 Subject: [PATCH 233/656] ensure mkdirs_exists_ok is not called for URLs --- common/file_helpers.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/common/file_helpers.py b/common/file_helpers.py index c33ebac6f6..d4a0004108 100644 --- a/common/file_helpers.py +++ b/common/file_helpers.py @@ -5,6 +5,8 @@ from atomicwrites import AtomicWriter def mkdirs_exists_ok(path): + if path.startswith('http'): + raise ValueError('URL path') try: os.makedirs(path) except OSError: From 3b180240d53564274a9258ff1f851a478bb0b741 Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Tue, 9 Jun 2020 08:56:16 -0700 Subject: [PATCH 234/656] mkdirs_exists_ok more specific URL detection --- common/file_helpers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/file_helpers.py b/common/file_helpers.py index d4a0004108..c7a70ab879 100644 --- a/common/file_helpers.py +++ b/common/file_helpers.py @@ -5,7 +5,7 @@ from atomicwrites import AtomicWriter def mkdirs_exists_ok(path): - if path.startswith('http'): + if path.startswith('http://') or path.startswith('https://'): raise ValueError('URL path') try: os.makedirs(path) From 2fa07d2c0a0df3fc7ee3d738a51f8c4ce5eef282 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Tue, 9 Jun 2020 11:23:53 -0700 Subject: [PATCH 235/656] Add Rav4 esp fw --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 641c00e20a..9b30e91dff 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -655,6 +655,7 @@ FW_VERSIONS = { b'F15260R102\x00\x00\x00\x00\x00\x00', b'F15260R103\x00\x00\x00\x00\x00\x00', b'F152642493\x00\x00\x00\x00\x00\x00', + b'F152642492\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'881514201300\x00\x00\x00\x00', From d4858e5ff5753f8a800f3e90cb4c0f69213b87f3 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Tue, 9 Jun 2020 13:25:15 -0700 Subject: [PATCH 236/656] Move driver monitoring out of controls (#1642) * move dmonitoring out of controls * run monitoring unit tests in CI --- .github/workflows/test.yaml | 1 + release/files_common | 7 ++++--- selfdrive/manager.py | 4 ++-- selfdrive/{controls => monitoring}/dmonitoringd.py | 2 +- selfdrive/{controls/lib => monitoring}/driver_monitor.py | 0 selfdrive/{controls/lib => monitoring}/driverview.py | 0 .../{controls/tests => monitoring}/test_monitoring.py | 2 +- 7 files changed, 9 insertions(+), 7 deletions(-) rename selfdrive/{controls => monitoring}/dmonitoringd.py (97%) rename selfdrive/{controls/lib => monitoring}/driver_monitor.py (100%) rename selfdrive/{controls/lib => monitoring}/driverview.py (100%) rename selfdrive/{controls/tests => monitoring}/test_monitoring.py (99%) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index d2b04ef1a6..b6d422c9f3 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -106,6 +106,7 @@ jobs: $UNIT_TEST opendbc/can && \ $UNIT_TEST selfdrive/boardd && \ $UNIT_TEST selfdrive/controls && \ + $UNIT_TEST selfdrive/monitoring && \ $UNIT_TEST selfdrive/loggerd && \ $UNIT_TEST selfdrive/car && \ $UNIT_TEST selfdrive/locationd && \ diff --git a/release/files_common b/release/files_common index 1bd4929770..26ca00915c 100644 --- a/release/files_common +++ b/release/files_common @@ -204,13 +204,11 @@ selfdrive/controls/__init__.py selfdrive/controls/controlsd.py selfdrive/controls/plannerd.py selfdrive/controls/radard.py -selfdrive/controls/dmonitoringd.py selfdrive/controls/lib/__init__.py selfdrive/controls/lib/alertmanager.py selfdrive/controls/lib/alerts_offroad.json selfdrive/controls/lib/events.py selfdrive/controls/lib/drive_helpers.py -selfdrive/controls/lib/driver_monitor.py selfdrive/controls/lib/latcontrol_pid.py selfdrive/controls/lib/latcontrol_indi.py selfdrive/controls/lib/latcontrol_lqr.py @@ -225,7 +223,6 @@ selfdrive/controls/lib/speed_smoother.py selfdrive/controls/lib/fcw.py selfdrive/controls/lib/long_mpc.py selfdrive/controls/lib/long_mpc_model.py -selfdrive/controls/lib/driverview.py selfdrive/controls/lib/cluster/* @@ -380,6 +377,10 @@ selfdrive/modeld/runners/snpemodel.h selfdrive/modeld/runners/runmodel.h selfdrive/modeld/runners/run.h +selfdrive/monitoring/dmonitoringd.py +selfdrive/monitoring/driver_monitor.py +selfdrive/monitoring/driverview.py + selfdrive/assets selfdrive/assets/fonts/*.ttf diff --git a/selfdrive/manager.py b/selfdrive/manager.py index a92d2e0634..ed8b6a9f28 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -169,7 +169,7 @@ managed_processes = { "controlsd": "selfdrive.controls.controlsd", "plannerd": "selfdrive.controls.plannerd", "radard": "selfdrive.controls.radard", - "dmonitoringd": "selfdrive.controls.dmonitoringd", + "dmonitoringd": "selfdrive.monitoring.dmonitoringd", "ubloxd": ("selfdrive/locationd", ["./ubloxd"]), "loggerd": ("selfdrive/loggerd", ["./loggerd"]), "logmessaged": "selfdrive.logmessaged", @@ -189,7 +189,7 @@ managed_processes = { "updated": "selfdrive.updated", "dmonitoringmodeld": ("selfdrive/modeld", ["./dmonitoringmodeld"]), "modeld": ("selfdrive/modeld", ["./modeld"]), - "driverview": "selfdrive.controls.lib.driverview", + "driverview": "selfdrive.monitoring.driverview", } daemon_processes = { diff --git a/selfdrive/controls/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py similarity index 97% rename from selfdrive/controls/dmonitoringd.py rename to selfdrive/monitoring/dmonitoringd.py index 2a21e920f4..4939d604d7 100755 --- a/selfdrive/controls/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -5,7 +5,7 @@ from common.realtime import set_realtime_priority from common.params import Params import cereal.messaging as messaging from selfdrive.controls.lib.events import Events -from selfdrive.controls.lib.driver_monitor import DriverStatus, MAX_TERMINAL_ALERTS, MAX_TERMINAL_DURATION +from selfdrive.monitoring.driver_monitor import DriverStatus, MAX_TERMINAL_ALERTS, MAX_TERMINAL_DURATION from selfdrive.locationd.calibration_helpers import Calibration def dmonitoringd_thread(sm=None, pm=None): diff --git a/selfdrive/controls/lib/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py similarity index 100% rename from selfdrive/controls/lib/driver_monitor.py rename to selfdrive/monitoring/driver_monitor.py diff --git a/selfdrive/controls/lib/driverview.py b/selfdrive/monitoring/driverview.py similarity index 100% rename from selfdrive/controls/lib/driverview.py rename to selfdrive/monitoring/driverview.py diff --git a/selfdrive/controls/tests/test_monitoring.py b/selfdrive/monitoring/test_monitoring.py similarity index 99% rename from selfdrive/controls/tests/test_monitoring.py rename to selfdrive/monitoring/test_monitoring.py index b653555f6a..a741115cae 100644 --- a/selfdrive/controls/tests/test_monitoring.py +++ b/selfdrive/monitoring/test_monitoring.py @@ -5,7 +5,7 @@ import numpy as np from cereal import car from common.realtime import DT_DMON from selfdrive.controls.lib.events import Events -from selfdrive.controls.lib.driver_monitor import DriverStatus, MAX_TERMINAL_ALERTS, \ +from selfdrive.monitoring.driver_monitor import DriverStatus, MAX_TERMINAL_ALERTS, \ _AWARENESS_TIME, _AWARENESS_PRE_TIME_TILL_TERMINAL, \ _AWARENESS_PROMPT_TIME_TILL_TERMINAL, _DISTRACTED_TIME, \ _DISTRACTED_PRE_TIME_TILL_TERMINAL, _DISTRACTED_PROMPT_TIME_TILL_TERMINAL, \ From 90d97de74ddc4672b35a5186e868794468a44345 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 10 Jun 2020 04:46:49 +0800 Subject: [PATCH 237/656] add function read_db_bytes (#1662) --- selfdrive/boardd/boardd.cc | 35 +++++++----------- selfdrive/common/params.cc | 13 +++++++ selfdrive/common/params.h | 8 ++--- selfdrive/locationd/paramsd.cc | 27 ++++++-------- selfdrive/loggerd/loggerd.cc | 58 ++++++++---------------------- selfdrive/modeld/models/driving.cc | 8 ++--- 6 files changed, 56 insertions(+), 93 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index bc6dcea457..f1f87cb8db 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -85,45 +85,39 @@ void *safety_setter_thread(void *s) { libusb_control_transfer(dev_handle, 0x40, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::ELM327), 0, NULL, 0, TIMEOUT); pthread_mutex_unlock(&usb_lock); - char *value_vin; - size_t value_vin_sz = 0; - // switch to SILENT when CarVin param is read while (1) { if (do_exit) return NULL; - const int result = read_db_value("CarVin", &value_vin, &value_vin_sz); - if (value_vin_sz > 0) { + std::vector value_vin = read_db_bytes("CarVin"); + if (value_vin.size() > 0) { // sanity check VIN format - assert(value_vin_sz == 17); + assert(value_vin.size() == 17); + std::string str_vin(value_vin.begin(), value_vin.end()); + LOGW("got CarVin %s", str_vin.c_str()); break; } usleep(100*1000); } - LOGW("got CarVin %s", value_vin); - free(value_vin); // VIN query done, stop listening to OBDII pthread_mutex_lock(&usb_lock); libusb_control_transfer(dev_handle, 0x40, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::NO_OUTPUT), 0, NULL, 0, TIMEOUT); pthread_mutex_unlock(&usb_lock); - char *value; - size_t value_sz = 0; - + std::vector params; LOGW("waiting for params to set safety model"); while (1) { if (do_exit) return NULL; - const int result = read_db_value("CarParams", &value, &value_sz); - if (value_sz > 0) break; + params = read_db_bytes("CarParams"); + if (params.size() > 0) break; usleep(100*1000); } - LOGW("got %d bytes CarParams", value_sz); + LOGW("got %d bytes CarParams", params.size()); // 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); - free(value); + auto amsg = kj::heapArray((params.size() / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), params.data(), params.size()); capnp::FlatArrayMessageReader cmsg(amsg); cereal::CarParams::Reader car_params = cmsg.getRoot(); @@ -407,10 +401,8 @@ void can_health(PubMaster &pm) { bool cdp_mode = health.usb_power_mode == (uint8_t)(cereal::HealthData::UsbPowerMode::CDP); bool no_ignition_exp = no_ignition_cnt > NO_IGNITION_CNT_MAX; if ((no_ignition_exp || (voltage_f < VBATT_PAUSE_CHARGING)) && cdp_mode && !ignition) { - char *disable_power_down = NULL; - size_t disable_power_down_sz = 0; - const int result = read_db_value("DisablePowerDown", &disable_power_down, &disable_power_down_sz); - if (disable_power_down_sz != 1 || disable_power_down[0] != '1') { + std::vector disable_power_down = read_db_bytes("DisablePowerDown"); + if (disable_power_down.size() != 1 || disable_power_down[0] != '1') { printf("TURN OFF CHARGING!\n"); pthread_mutex_lock(&usb_lock); libusb_control_transfer(dev_handle, 0xc0, 0xe6, (uint16_t)(cereal::HealthData::UsbPowerMode::CLIENT), 0, NULL, 0, TIMEOUT); @@ -418,7 +410,6 @@ void can_health(PubMaster &pm) { printf("POWER DOWN DEVICE\n"); system("service call power 17 i32 0 i32 1"); } - if (disable_power_down) free(disable_power_down); } if (!no_ignition_exp && (voltage_f > VBATT_START_CHARGING) && !cdp_mode) { printf("TURN ON CHARGING!\n"); diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index 5ab2eae349..4d9c214d37 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -13,6 +13,7 @@ #include #include +#include #include "common/util.h" #include "common/utilpp.h" @@ -353,3 +354,15 @@ int read_db_all(std::map *params, bool persistent_para close(lock_fd); return 0; } + +std::vector read_db_bytes(const char* param_name, bool persistent_param) { + std::vector bytes; + char* value; + size_t sz; + int result = read_db_value(param_name, &value, &sz, persistent_param); + if (result == 0) { + bytes.assign(value, value+sz); + free(value); + } + return bytes; +} diff --git a/selfdrive/common/params.h b/selfdrive/common/params.h index ea002eb0de..49af04b4fd 100644 --- a/selfdrive/common/params.h +++ b/selfdrive/common/params.h @@ -1,6 +1,4 @@ -#ifndef _SELFDRIVE_COMMON_PARAMS_H_ -#define _SELFDRIVE_COMMON_PARAMS_H_ - +#pragma once #include #ifdef __cplusplus @@ -39,7 +37,7 @@ void read_db_value_blocking(const char* key, char** value, size_t* value_sz, boo #ifdef __cplusplus #include #include +#include int read_db_all(std::map *params, bool persistent_param = false); +std::vector read_db_bytes(const char* param_name, bool persistent_param = false); #endif - -#endif // _SELFDRIVE_COMMON_PARAMS_H_ diff --git a/selfdrive/locationd/paramsd.cc b/selfdrive/locationd/paramsd.cc index 3841ccc5bb..bb45ea2b4b 100644 --- a/selfdrive/locationd/paramsd.cc +++ b/selfdrive/locationd/paramsd.cc @@ -31,40 +31,33 @@ int main(int argc, char *argv[]) { Localizer localizer; // Read car params - char *value; - size_t value_sz = 0; - + std::vector params; LOGW("waiting for params to set vehicle model"); while (true) { - read_db_value("CarParams", &value, &value_sz); - if (value_sz > 0) break; + params = read_db_bytes("CarParams"); + if (params.size() > 0) break; usleep(100*1000); } - LOGW("got %d bytes CarParams", value_sz); + LOGW("got %d bytes CarParams", params.size()); // make copy due to alignment issues - auto amsg = kj::heapArray((value_sz / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), value, value_sz); - free(value); - + auto amsg = kj::heapArray((params.size() / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), params.data(), params.size()); + capnp::FlatArrayMessageReader cmsg(amsg); cereal::CarParams::Reader car_params = cmsg.getRoot(); // Read params from previous run - const int result = read_db_value("LiveParameters", &value, &value_sz); - std::string fingerprint = car_params.getCarFingerprint(); std::string vin = car_params.getCarVin(); double sR = car_params.getSteerRatio(); double x = 1.0; double ao = 0.0; double posenet_invalid_count = 0; - - if (result == 0){ - auto str = std::string(value, value_sz); - free(value); - + std::vector live_params = read_db_bytes("LiveParameters"); + if (live_params.size() > 0){ std::string err; + std::string str(live_params.begin(), live_params.end()); auto json = json11::Json::parse(str, err); if (json.is_null() || !err.empty()) { std::string log = "Error parsing json: " + err; diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index d9c5017f95..cb2e5d4753 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -91,11 +91,8 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { int err; if (front) { - char *value; - const int result = read_db_value("RecordFront", &value, NULL); - if (result != 0) return; - if (value[0] != '1') { free(value); return; } - free(value); + std::vector value = read_db_bytes("RecordFront"); + if (value.size() == 0 || value[0] != '1') return; LOGW("recording front camera"); set_thread_name("FrontCameraEncoder"); @@ -454,30 +451,23 @@ kj::Array gen_init_data() { init.setDirty(true); } - char* git_commit = NULL; - size_t size; - read_db_value("GitCommit", &git_commit, &size); - if (git_commit) { - init.setGitCommit(capnp::Text::Reader(git_commit, size)); + std::vector git_commit = read_db_bytes("GitCommit"); + if (git_commit.size() > 0) { + init.setGitCommit(capnp::Text::Reader(git_commit.data(), git_commit.size())); } - char* git_branch = NULL; - read_db_value("GitBranch", &git_branch, &size); - if (git_branch) { - init.setGitBranch(capnp::Text::Reader(git_branch, size)); + std::vector git_branch = read_db_bytes("GitBranch"); + if (git_branch.size() > 0) { + init.setGitBranch(capnp::Text::Reader(git_branch.data(), git_branch.size())); } - char* git_remote = NULL; - read_db_value("GitRemote", &git_remote, &size); - if (git_remote) { - init.setGitRemote(capnp::Text::Reader(git_remote, size)); + std::vector git_remote = read_db_bytes("GitRemote"); + if (git_remote.size() > 0) { + init.setGitRemote(capnp::Text::Reader(git_remote.data(), git_remote.size())); } - char* passive = NULL; - read_db_value("Passive", &passive, NULL); - init.setPassive(passive && strlen(passive) && passive[0] == '1'); - - + std::vector passive = read_db_bytes("Passive"); + init.setPassive(passive.size() > 0 && passive[0] == '1'); { // log params std::map params; @@ -491,27 +481,7 @@ kj::Array gen_init_data() { i++; } } - - - auto words = capnp::messageToFlatArray(msg); - - if (git_commit) { - free((void*)git_commit); - } - - if (git_branch) { - free((void*)git_branch); - } - - if (git_remote) { - free((void*)git_remote); - } - - if (passive) { - free((void*)passive); - } - - return words; + return capnp::messageToFlatArray(msg); } static int clear_locks_fn(const char* fpath, const struct stat *sb, int tyupeflag) { diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 1940667d80..b24762ebf0 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -60,11 +60,9 @@ void model_init(ModelState* s, cl_device_id device_id, cl_context context, int t for (int i = 0; i < TRAFFIC_CONVENTION_LEN; i++) s->traffic_convention[i] = 0.0; s->m->addTrafficConvention(s->traffic_convention, TRAFFIC_CONVENTION_LEN); - char *string; - const int result = read_db_value("IsRHD", &string, NULL); - if (result == 0) { - bool is_rhd = string[0] == '1'; - free(string); + std::vector result = read_db_bytes("IsRHD"); + if (result.size() > 0) { + bool is_rhd = result[0] == '1'; if (is_rhd) { s->traffic_convention[1] = 1.0; } else { From c18e7da3c25c59a19efda8ec3a1b716c2571cc2f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 9 Jun 2020 16:44:26 -0700 Subject: [PATCH 238/656] Write orientation & transform in C++ (#1637) * locationd at 20hz * update ref * bump cereal * dont modify global state * add scons files * ecef2geodetic and geodetic2ecef * Finish local coords class * Add header file * Add orientation.cc * cleanup * Add functions to header file * Add cython wrapper * y u no work? * This passes the tests * test rot2quat and quat2rot * Teste euler2rot and rot2euler * rot_matrix * test ecef_euler_from_ned and ned_euler_from_ecef * add benchmark * Add test * Consistent newlines * no more radians supported in geodetic * test localcoord single * test localcoord single * all tests pass * Unused import * Add alternate namings * Add source for formulas * no explicit tests needed * remove benchmark * Add release files * Typo * Remove print statement * no access to raw transform matrix * temporarily add tolerance * handcode quat2euler * update ref --- .editorconfig | 2 +- .gitignore | 1 + SConstruct | 1 + cereal | 2 +- common/transformations/.gitignore | 2 + common/transformations/SConscript | 9 + common/transformations/coordinates.cc | 104 ++++++ common/transformations/coordinates.hpp | 36 ++ common/transformations/coordinates.py | 118 +------ common/transformations/orientation.cc | 147 ++++++++ common/transformations/orientation.hpp | 17 + common/transformations/orientation.py | 321 +++--------------- common/transformations/setup.py | 42 +++ .../transformations/tests/test_coordinates.py | 9 - .../transformations/tests/test_orientation.py | 2 +- common/transformations/transformations.pxd | 68 ++++ common/transformations/transformations.pyx | 156 +++++++++ release/files_common | 11 +- selfdrive/locationd/locationd.py | 34 +- selfdrive/test/process_replay/compare_logs.py | 2 +- .../test/process_replay/process_replay.py | 17 +- selfdrive/test/process_replay/ref_commit | 2 +- 22 files changed, 683 insertions(+), 420 deletions(-) create mode 100644 common/transformations/.gitignore create mode 100644 common/transformations/SConscript create mode 100644 common/transformations/coordinates.cc create mode 100644 common/transformations/coordinates.hpp create mode 100644 common/transformations/orientation.cc create mode 100644 common/transformations/orientation.hpp create mode 100644 common/transformations/setup.py create mode 100644 common/transformations/transformations.pxd create mode 100644 common/transformations/transformations.pyx diff --git a/.editorconfig b/.editorconfig index e0da061025..879e6eebca 100644 --- a/.editorconfig +++ b/.editorconfig @@ -5,7 +5,7 @@ end_of_line = lf insert_final_newline = true trim_trailing_whitespace = true -[{*.py, *.pyx, *pxd}] +[{*.py, *.pyx, *.pxd}] charset = utf-8 indent_style = space indent_size = 2 diff --git a/.gitignore b/.gitignore index 9f2de0181e..eae40333af 100644 --- a/.gitignore +++ b/.gitignore @@ -62,3 +62,4 @@ htmlcov pandaextra .mypy_cache/ +flycheck_* diff --git a/SConstruct b/SConstruct index 79304e29f6..6d80f6e521 100644 --- a/SConstruct +++ b/SConstruct @@ -212,6 +212,7 @@ SConscript(['opendbc/can/SConscript']) SConscript(['common/SConscript']) SConscript(['common/kalman/SConscript']) +SConscript(['common/transformations/SConscript']) SConscript(['phonelibs/SConscript']) if arch != "Darwin": diff --git a/cereal b/cereal index 1aaf1bfd7c..0021fa2419 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 1aaf1bfd7c07e1c5184e8f13823e8ed02e2c7af2 +Subproject commit 0021fa241994cd9d94945ba305b0f3f1c43feaae diff --git a/common/transformations/.gitignore b/common/transformations/.gitignore new file mode 100644 index 0000000000..a67290f09a --- /dev/null +++ b/common/transformations/.gitignore @@ -0,0 +1,2 @@ +transformations +transformations.cpp diff --git a/common/transformations/SConscript b/common/transformations/SConscript new file mode 100644 index 0000000000..7c051746a3 --- /dev/null +++ b/common/transformations/SConscript @@ -0,0 +1,9 @@ +Import('env') + +d = Dir('.') + +env.Command( + ['transformations.so'], + ['transformations.pxd', 'transformations.pyx', + 'coordinates.cc', 'orientation.cc', 'coordinates.hpp', 'orientation.hpp'], + 'cd ' + d.path + ' && python3 setup.py build_ext --inplace') diff --git a/common/transformations/coordinates.cc b/common/transformations/coordinates.cc new file mode 100644 index 0000000000..313683b6f6 --- /dev/null +++ b/common/transformations/coordinates.cc @@ -0,0 +1,104 @@ +#define _USE_MATH_DEFINES + +#include +#include +#include + +#include "coordinates.hpp" + +#define DEG2RAD(x) ((x) * M_PI / 180.0) +#define RAD2DEG(x) ((x) * 180.0 / M_PI) + + +double a = 6378137; +double b = 6356752.3142; +double esq = 6.69437999014 * 0.001; +double e1sq = 6.73949674228 * 0.001; + + +static Geodetic to_degrees(Geodetic geodetic){ + geodetic.lat = RAD2DEG(geodetic.lat); + geodetic.lon = RAD2DEG(geodetic.lon); + return geodetic; +} + +static Geodetic to_radians(Geodetic geodetic){ + geodetic.lat = DEG2RAD(geodetic.lat); + geodetic.lon = DEG2RAD(geodetic.lon); + return geodetic; +} + + +ECEF geodetic2ecef(Geodetic g){ + g = to_radians(g); + double xi = sqrt(1.0 - esq * pow(sin(g.lat), 2)); + double x = (a / xi + g.alt) * cos(g.lat) * cos(g.lon); + double y = (a / xi + g.alt) * cos(g.lat) * sin(g.lon); + double z = (a / xi * (1.0 - esq) + g.alt) * sin(g.lat); + return {x, y, z}; +} + +Geodetic ecef2geodetic(ECEF e){ + // Convert from ECEF to geodetic using Ferrari's methods + // https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#Ferrari.27s_solution + double x = e.x; + double y = e.y; + double z = e.z; + + double r = sqrt(x * x + y * y); + double Esq = a * a - b * b; + double F = 54 * b * b * z * z; + double G = r * r + (1 - esq) * z * z - esq * Esq; + double C = (esq * esq * F * r * r) / (pow(G, 3)); + double S = cbrt(1 + C + sqrt(C * C + 2 * C)); + double P = F / (3 * pow((S + 1 / S + 1), 2) * G * G); + double Q = sqrt(1 + 2 * esq * esq * P); + double r_0 = -(P * esq * r) / (1 + Q) + sqrt(0.5 * a * a*(1 + 1.0 / Q) - P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r); + double U = sqrt(pow((r - esq * r_0), 2) + z * z); + double V = sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z); + double Z_0 = b * b * z / (a * V); + double h = U * (1 - b * b / (a * V)); + + double lat = atan((z + e1sq * Z_0) / r); + double lon = atan2(y, x); + + return to_degrees({lat, lon, h}); +} + +LocalCoord::LocalCoord(Geodetic g, ECEF e){ + init_ecef << e.x, e.y, e.z; + + g = to_radians(g); + + ned2ecef_matrix << + -sin(g.lat)*cos(g.lon), -sin(g.lon), -cos(g.lat)*cos(g.lon), + -sin(g.lat)*sin(g.lon), cos(g.lon), -cos(g.lat)*sin(g.lon), + cos(g.lat), 0, -sin(g.lat); + ecef2ned_matrix = ned2ecef_matrix.transpose(); +} + +NED LocalCoord::ecef2ned(ECEF e) { + Eigen::Vector3d ecef; + ecef << e.x, e.y, e.z; + + Eigen::Vector3d ned = (ecef2ned_matrix * (ecef - init_ecef)); + return {ned[0], ned[1], ned[2]}; +} + +ECEF LocalCoord::ned2ecef(NED n) { + Eigen::Vector3d ned; + ned << n.n, n.e, n.d; + + Eigen::Vector3d ecef = (ned2ecef_matrix * ned) + init_ecef; + return {ecef[0], ecef[1], ecef[2]}; +} + +NED LocalCoord::geodetic2ned(Geodetic g) { + ECEF e = ::geodetic2ecef(g); + return ecef2ned(e); +} + +Geodetic LocalCoord::ned2geodetic(NED n){ + ECEF e = ned2ecef(n); + return ::ecef2geodetic(e); +} diff --git a/common/transformations/coordinates.hpp b/common/transformations/coordinates.hpp new file mode 100644 index 0000000000..be6fe2e75f --- /dev/null +++ b/common/transformations/coordinates.hpp @@ -0,0 +1,36 @@ +#pragma once + +struct ECEF { + double x, y, z; + Eigen::Vector3d to_vector(){ + return Eigen::Vector3d(x, y, z); + } +}; + +struct NED { + double n, e, d; +}; + +struct Geodetic { + double lat, lon, alt; + bool radians=false; +}; + +ECEF geodetic2ecef(Geodetic g); +Geodetic ecef2geodetic(ECEF e); + +class LocalCoord { +private: + Eigen::Matrix3d ned2ecef_matrix; + Eigen::Matrix3d ecef2ned_matrix; + Eigen::Vector3d init_ecef; +public: + LocalCoord(Geodetic g, ECEF e); + LocalCoord(Geodetic g) : LocalCoord(g, ::geodetic2ecef(g)) {} + LocalCoord(ECEF e) : LocalCoord(::ecef2geodetic(e), e) {} + + NED ecef2ned(ECEF e); + ECEF ned2ecef(NED n); + NED geodetic2ned(Geodetic g); + Geodetic ned2geodetic(NED n); +}; diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index e39ad697aa..46cc0ded0d 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -1,113 +1,19 @@ -""" -Coordinate transformation module. All methods accept arrays as input -with each row as a position. -""" -import numpy as np +# pylint: skip-file +from common.transformations.orientation import numpy_wrap +from common.transformations.transformations import (ecef2geodetic_single, + geodetic2ecef_single) +from common.transformations.transformations import LocalCoord as LocalCoord_single -a = 6378137 -b = 6356752.3142 -esq = 6.69437999014 * 0.001 -e1sq = 6.73949674228 * 0.001 +class LocalCoord(LocalCoord_single): + ecef2ned = numpy_wrap(LocalCoord_single.ecef2ned_single, (3,), (3,)) + ned2ecef = numpy_wrap(LocalCoord_single.ned2ecef_single, (3,), (3,)) + geodetic2ned = numpy_wrap(LocalCoord_single.geodetic2ned_single, (3,), (3,)) + ned2geodetic = numpy_wrap(LocalCoord_single.ned2geodetic_single, (3,), (3,)) -def geodetic2ecef(geodetic, radians=False): - geodetic = np.array(geodetic) - input_shape = geodetic.shape - geodetic = np.atleast_2d(geodetic) - - ratio = 1.0 if radians else (np.pi / 180.0) - lat = ratio*geodetic[:, 0] - lon = ratio*geodetic[:, 1] - alt = geodetic[:, 2] - - xi = np.sqrt(1 - esq * np.sin(lat)**2) - x = (a / xi + alt) * np.cos(lat) * np.cos(lon) - y = (a / xi + alt) * np.cos(lat) * np.sin(lon) - z = (a / xi * (1 - esq) + alt) * np.sin(lat) - ecef = np.array([x, y, z]).T - return ecef.reshape(input_shape) - - -def ecef2geodetic(ecef, radians=False): - """ - Convert ECEF coordinates to geodetic using ferrari's method - """ - # Save shape and export column - ecef = np.atleast_1d(ecef) - input_shape = ecef.shape - ecef = np.atleast_2d(ecef) - x, y, z = ecef[:, 0], ecef[:, 1], ecef[:, 2] - - ratio = 1.0 if radians else (180.0 / np.pi) - - # Conver from ECEF to geodetic using Ferrari's methods - # https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#Ferrari.27s_solution - r = np.sqrt(x * x + y * y) - Esq = a * a - b * b - F = 54 * b * b * z * z - G = r * r + (1 - esq) * z * z - esq * Esq - C = (esq * esq * F * r * r) / (pow(G, 3)) - S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C)) - P = F / (3 * pow((S + 1 / S + 1), 2) * G * G) - Q = np.sqrt(1 + 2 * esq * esq * P) - r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - - P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r) - U = np.sqrt(pow((r - esq * r_0), 2) + z * z) - V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z) - Z_0 = b * b * z / (a * V) - h = U * (1 - b * b / (a * V)) - lat = ratio*np.arctan((z + e1sq * Z_0) / r) - lon = ratio*np.arctan2(y, x) - - # stack the new columns and return to the original shape - geodetic = np.column_stack((lat, lon, h)) - return geodetic.reshape(input_shape) - +geodetic2ecef = numpy_wrap(geodetic2ecef_single, (3,), (3,)) +ecef2geodetic = numpy_wrap(ecef2geodetic_single, (3,), (3,)) geodetic_from_ecef = ecef2geodetic ecef_from_geodetic = geodetic2ecef - - -class LocalCoord(): - """ - Allows conversions to local frames. In this case NED. - That is: North East Down from the start position in - meters. - """ - def __init__(self, init_geodetic, init_ecef): - self.init_ecef = init_ecef - lat, lon, _ = (np.pi/180)*np.array(init_geodetic) - self.ned2ecef_matrix = np.array([[-np.sin(lat)*np.cos(lon), -np.sin(lon), -np.cos(lat)*np.cos(lon)], - [-np.sin(lat)*np.sin(lon), np.cos(lon), -np.cos(lat)*np.sin(lon)], - [np.cos(lat), 0, -np.sin(lat)]]) - self.ecef2ned_matrix = self.ned2ecef_matrix.T - self.ecef_from_ned_matrix = self.ned2ecef_matrix - self.ned_from_ecef_matrix = self.ecef2ned_matrix - - @classmethod - def from_geodetic(cls, init_geodetic): - init_ecef = geodetic2ecef(init_geodetic) - return LocalCoord(init_geodetic, init_ecef) - - @classmethod - def from_ecef(cls, init_ecef): - init_geodetic = ecef2geodetic(init_ecef) - return LocalCoord(init_geodetic, init_ecef) - - def ecef2ned(self, ecef): - ecef = np.array(ecef) - return np.dot(self.ecef2ned_matrix, (ecef - self.init_ecef).T).T - - def ned2ecef(self, ned): - ned = np.array(ned) - # Transpose so that init_ecef will broadcast correctly for 1d or 2d ned. - return (np.dot(self.ned2ecef_matrix, ned.T).T + self.init_ecef) - - def geodetic2ned(self, geodetic): - ecef = geodetic2ecef(geodetic) - return self.ecef2ned(ecef) - - def ned2geodetic(self, ned): - ecef = self.ned2ecef(ned) - return ecef2geodetic(ecef) diff --git a/common/transformations/orientation.cc b/common/transformations/orientation.cc new file mode 100644 index 0000000000..086219d234 --- /dev/null +++ b/common/transformations/orientation.cc @@ -0,0 +1,147 @@ +#define _USE_MATH_DEFINES + +#include +#include +#include + +#include "orientation.hpp" +#include "coordinates.hpp" + +Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat){ + if (quat.w() > 0){ + return quat; + } else { + return Eigen::Quaterniond(-quat.w(), -quat.x(), -quat.y(), -quat.z()); + } +} + +Eigen::Quaterniond euler2quat(Eigen::Vector3d euler){ + Eigen::Quaterniond q; + + q = Eigen::AngleAxisd(euler(2), Eigen::Vector3d::UnitZ()) + * Eigen::AngleAxisd(euler(1), Eigen::Vector3d::UnitY()) + * Eigen::AngleAxisd(euler(0), Eigen::Vector3d::UnitX()); + return ensure_unique(q); +} + + +Eigen::Vector3d quat2euler(Eigen::Quaterniond quat){ + // TODO: switch to eigen implementation if the range of the Euler angles doesn't matter anymore + // Eigen::Vector3d euler = quat.toRotationMatrix().eulerAngles(2, 1, 0); + // return {euler(2), euler(1), euler(0)}; + double gamma = atan2(2 * (quat.w() * quat.x() + quat.y() * quat.z()), 1 - 2 * (quat.x()*quat.x() + quat.y()*quat.y())); + double theta = asin(2 * (quat.w() * quat.y() - quat.z() * quat.x())); + double psi = atan2(2 * (quat.w() * quat.z() + quat.x() * quat.y()), 1 - 2 * (quat.y()*quat.y() + quat.z()*quat.z())); + return {gamma, theta, psi}; +} + +Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat){ + return quat.toRotationMatrix(); +} + +Eigen::Quaterniond rot2quat(Eigen::Matrix3d rot){ + return ensure_unique(Eigen::Quaterniond(rot)); +} + +Eigen::Matrix3d euler2rot(Eigen::Vector3d euler){ + return quat2rot(euler2quat(euler)); +} + +Eigen::Vector3d rot2euler(Eigen::Matrix3d rot){ + return quat2euler(rot2quat(rot)); +} + +Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw){ + return euler2rot({roll, pitch, yaw}); +} + +Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle){ + Eigen::Quaterniond q; + q = Eigen::AngleAxisd(angle, axis); + return q.toRotationMatrix(); +} + + +Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose) { + /* + Using Rotations to Build Aerospace Coordinate Systems + Don Koks + https://apps.dtic.mil/dtic/tr/fulltext/u2/a484864.pdf + */ + LocalCoord converter = LocalCoord(ecef_init); + Eigen::Vector3d zero = ecef_init.to_vector(); + + Eigen::Vector3d x0 = converter.ned2ecef({1, 0, 0}).to_vector() - zero; + Eigen::Vector3d y0 = converter.ned2ecef({0, 1, 0}).to_vector() - zero; + Eigen::Vector3d z0 = converter.ned2ecef({0, 0, 1}).to_vector() - zero; + + Eigen::Vector3d x1 = rot(z0, ned_pose(2)) * x0; + Eigen::Vector3d y1 = rot(z0, ned_pose(2)) * y0; + Eigen::Vector3d z1 = rot(z0, ned_pose(2)) * z0; + + Eigen::Vector3d x2 = rot(y1, ned_pose(1)) * x1; + Eigen::Vector3d y2 = rot(y1, ned_pose(1)) * y1; + Eigen::Vector3d z2 = rot(y1, ned_pose(1)) * z1; + + Eigen::Vector3d x3 = rot(x2, ned_pose(0)) * x2; + Eigen::Vector3d y3 = rot(x2, ned_pose(0)) * y2; + + + x0 = Eigen::Vector3d(1, 0, 0); + y0 = Eigen::Vector3d(0, 1, 0); + z0 = Eigen::Vector3d(0, 0, 1); + + double psi = atan2(x3.dot(y0), x3.dot(x0)); + double theta = atan2(-x3.dot(z0), sqrt(pow(x3.dot(x0), 2) + pow(x3.dot(y0), 2))); + + y2 = rot(z0, psi) * y0; + z2 = rot(y2, theta) * z0; + + double phi = atan2(y3.dot(z2), y3.dot(y2)); + + return {phi, theta, psi}; +} + +Eigen::Vector3d ned_euler_from_ecef(ECEF ecef_init, Eigen::Vector3d ecef_pose){ + /* + Using Rotations to Build Aerospace Coordinate Systems + Don Koks + https://apps.dtic.mil/dtic/tr/fulltext/u2/a484864.pdf + */ + LocalCoord converter = LocalCoord(ecef_init); + + Eigen::Vector3d x0 = Eigen::Vector3d(1, 0, 0); + Eigen::Vector3d y0 = Eigen::Vector3d(0, 1, 0); + Eigen::Vector3d z0 = Eigen::Vector3d(0, 0, 1); + + Eigen::Vector3d x1 = rot(z0, ecef_pose(2)) * x0; + Eigen::Vector3d y1 = rot(z0, ecef_pose(2)) * y0; + Eigen::Vector3d z1 = rot(z0, ecef_pose(2)) * z0; + + Eigen::Vector3d x2 = rot(y1, ecef_pose(1)) * x1; + Eigen::Vector3d y2 = rot(y1, ecef_pose(1)) * y1; + Eigen::Vector3d z2 = rot(y1, ecef_pose(1)) * z1; + + Eigen::Vector3d x3 = rot(x2, ecef_pose(0)) * x2; + Eigen::Vector3d y3 = rot(x2, ecef_pose(0)) * y2; + + Eigen::Vector3d zero = ecef_init.to_vector(); + x0 = converter.ned2ecef({1, 0, 0}).to_vector() - zero; + y0 = converter.ned2ecef({0, 1, 0}).to_vector() - zero; + z0 = converter.ned2ecef({0, 0, 1}).to_vector() - zero; + + double psi = atan2(x3.dot(y0), x3.dot(x0)); + double theta = atan2(-x3.dot(z0), sqrt(pow(x3.dot(x0), 2) + pow(x3.dot(y0), 2))); + + y2 = rot(z0, psi) * y0; + z2 = rot(y2, theta) * z0; + + double phi = atan2(y3.dot(z2), y3.dot(y2)); + + return {phi, theta, psi}; +} + + + +int main(void){ +} diff --git a/common/transformations/orientation.hpp b/common/transformations/orientation.hpp new file mode 100644 index 0000000000..da95f7099d --- /dev/null +++ b/common/transformations/orientation.hpp @@ -0,0 +1,17 @@ +#pragma once +#include +#include "coordinates.hpp" + + +Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat); + +Eigen::Quaterniond euler2quat(Eigen::Vector3d euler); +Eigen::Vector3d quat2euler(Eigen::Quaterniond quat); +Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat); +Eigen::Quaterniond rot2quat(Eigen::Matrix3d rot); +Eigen::Matrix3d euler2rot(Eigen::Vector3d euler); +Eigen::Vector3d rot2euler(Eigen::Matrix3d rot); +Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw); +Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle); +Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose); +Eigen::Vector3d ned_euler_from_ecef(ECEF ecef_init, Eigen::Vector3d ecef_pose); diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py index e6161ea28d..b0e028d4e3 100644 --- a/common/transformations/orientation.py +++ b/common/transformations/orientation.py @@ -1,125 +1,47 @@ -''' -Vectorized functions that transform between -rotation matrices, euler angles and quaternions. -All support lists, array or array of arrays as inputs. -Supports both x2y and y_from_x format (y_from_x preferred!). -''' - +# pylint: skip-file import numpy as np -from numpy import dot, inner, array, linalg -from common.transformations.coordinates import LocalCoord - - -def euler2quat(eulers): - eulers = array(eulers) - if len(eulers.shape) > 1: - output_shape = (-1, 4) - else: - output_shape = (4,) - eulers = np.atleast_2d(eulers) - gamma, theta, psi = eulers[:, 0], eulers[:, 1], eulers[:, 2] - - q0 = np.cos(gamma / 2) * np.cos(theta / 2) * np.cos(psi / 2) + \ - np.sin(gamma / 2) * np.sin(theta / 2) * np.sin(psi / 2) - q1 = np.sin(gamma / 2) * np.cos(theta / 2) * np.cos(psi / 2) - \ - np.cos(gamma / 2) * np.sin(theta / 2) * np.sin(psi / 2) - q2 = np.cos(gamma / 2) * np.sin(theta / 2) * np.cos(psi / 2) + \ - np.sin(gamma / 2) * np.cos(theta / 2) * np.sin(psi / 2) - q3 = np.cos(gamma / 2) * np.cos(theta / 2) * np.sin(psi / 2) - \ - np.sin(gamma / 2) * np.sin(theta / 2) * np.cos(psi / 2) - - quats = array([q0, q1, q2, q3]).T - for i in range(len(quats)): - if quats[i, 0] < 0: - quats[i] = -quats[i] - return quats.reshape(output_shape) - - -def quat2euler(quats): - quats = array(quats) - if len(quats.shape) > 1: - output_shape = (-1, 3) - else: - output_shape = (3,) - quats = np.atleast_2d(quats) - q0, q1, q2, q3 = quats[:, 0], quats[:, 1], quats[:, 2], quats[:, 3] - - gamma = np.arctan2(2 * (q0 * q1 + q2 * q3), 1 - 2 * (q1**2 + q2**2)) - theta = np.arcsin(2 * (q0 * q2 - q3 * q1)) - psi = np.arctan2(2 * (q0 * q3 + q1 * q2), 1 - 2 * (q2**2 + q3**2)) - - eulers = array([gamma, theta, psi]).T - return eulers.reshape(output_shape) - - -def quat2rot(quats): - quats = array(quats) - input_shape = quats.shape - quats = np.atleast_2d(quats) - Rs = np.zeros((quats.shape[0], 3, 3)) - q0 = quats[:, 0] - q1 = quats[:, 1] - q2 = quats[:, 2] - q3 = quats[:, 3] - Rs[:, 0, 0] = q0 * q0 + q1 * q1 - q2 * q2 - q3 * q3 - Rs[:, 0, 1] = 2 * (q1 * q2 - q0 * q3) - Rs[:, 0, 2] = 2 * (q0 * q2 + q1 * q3) - Rs[:, 1, 0] = 2 * (q1 * q2 + q0 * q3) - Rs[:, 1, 1] = q0 * q0 - q1 * q1 + q2 * q2 - q3 * q3 - Rs[:, 1, 2] = 2 * (q2 * q3 - q0 * q1) - Rs[:, 2, 0] = 2 * (q1 * q3 - q0 * q2) - Rs[:, 2, 1] = 2 * (q0 * q1 + q2 * q3) - Rs[:, 2, 2] = q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3 - - if len(input_shape) < 2: - return Rs[0] - else: - return Rs - - -def rot2quat(rots): - input_shape = rots.shape - if len(input_shape) < 3: - rots = array([rots]) - K3 = np.empty((len(rots), 4, 4)) - K3[:, 0, 0] = (rots[:, 0, 0] - rots[:, 1, 1] - rots[:, 2, 2]) / 3.0 - K3[:, 0, 1] = (rots[:, 1, 0] + rots[:, 0, 1]) / 3.0 - K3[:, 0, 2] = (rots[:, 2, 0] + rots[:, 0, 2]) / 3.0 - K3[:, 0, 3] = (rots[:, 1, 2] - rots[:, 2, 1]) / 3.0 - K3[:, 1, 0] = K3[:, 0, 1] - K3[:, 1, 1] = (rots[:, 1, 1] - rots[:, 0, 0] - rots[:, 2, 2]) / 3.0 - K3[:, 1, 2] = (rots[:, 2, 1] + rots[:, 1, 2]) / 3.0 - K3[:, 1, 3] = (rots[:, 2, 0] - rots[:, 0, 2]) / 3.0 - K3[:, 2, 0] = K3[:, 0, 2] - K3[:, 2, 1] = K3[:, 1, 2] - K3[:, 2, 2] = (rots[:, 2, 2] - rots[:, 0, 0] - rots[:, 1, 1]) / 3.0 - K3[:, 2, 3] = (rots[:, 0, 1] - rots[:, 1, 0]) / 3.0 - K3[:, 3, 0] = K3[:, 0, 3] - K3[:, 3, 1] = K3[:, 1, 3] - K3[:, 3, 2] = K3[:, 2, 3] - K3[:, 3, 3] = (rots[:, 0, 0] + rots[:, 1, 1] + rots[:, 2, 2]) / 3.0 - q = np.empty((len(rots), 4)) - for i in range(len(rots)): - _, eigvecs = linalg.eigh(K3[i].T) - eigvecs = eigvecs[:, 3:] - q[i, 0] = eigvecs[-1] - q[i, 1:] = -eigvecs[:-1].flatten() - if q[i, 0] < 0: - q[i] = -q[i] - - if len(input_shape) < 3: - return q[0] - else: - return q - - -def euler2rot(eulers): - return rotations_from_quats(euler2quat(eulers)) - - -def rot2euler(rots): - return quat2euler(quats_from_rotations(rots)) +from common.transformations.transformations import (ecef_euler_from_ned_single, + euler2quat_single, + euler2rot_single, + ned_euler_from_ecef_single, + quat2euler_single, + quat2rot_single, + rot2euler_single, + rot2quat_single, + rot_matrix) + + +def numpy_wrap(function, input_shape, output_shape): + """Wrap a function to take either an input or list of inputs and return the correct shape""" + def f(*inps): + *args, inp = inps + inp = np.array(inp) + shape = inp.shape + + if len(shape) == len(input_shape): + out_shape = output_shape + else: + out_shape = (shape[0],) + output_shape + + # Add empty dimension if inputs is not a list + if len(shape) == len(input_shape): + inp.shape = (1, ) + inp.shape + + result = np.asarray([function(*args, i) for i in inp]) + result.shape = out_shape + return result + return f + + +euler2quat = numpy_wrap(euler2quat_single, (3,), (4,)) +quat2euler = numpy_wrap(quat2euler_single, (4,), (3,)) +quat2rot = numpy_wrap(quat2rot_single, (4,), (3, 3)) +rot2quat = numpy_wrap(rot2quat_single, (3, 3), (4,)) +euler2rot = numpy_wrap(euler2rot_single, (3,), (3, 3)) +rot2euler = numpy_wrap(rot2euler_single, (3, 3), (3,)) +ecef_euler_from_ned = numpy_wrap(ecef_euler_from_ned_single, (3,), (3,)) +ned_euler_from_ecef = numpy_wrap(ned_euler_from_ecef_single, (3,), (3,)) quats_from_rotations = rot2quat quat_from_rot = rot2quat @@ -130,162 +52,3 @@ euler_from_rot = rot2euler euler_from_quat = quat2euler rot_from_euler = euler2rot quat_from_euler = euler2quat - - -''' -Random helpers below -''' - - -def quat_product(q, r): - t = np.zeros(4) - t[0] = r[0] * q[0] - r[1] * q[1] - r[2] * q[2] - r[3] * q[3] - t[1] = r[0] * q[1] + r[1] * q[0] - r[2] * q[3] + r[3] * q[2] - t[2] = r[0] * q[2] + r[1] * q[3] + r[2] * q[0] - r[3] * q[1] - t[3] = r[0] * q[3] - r[1] * q[2] + r[2] * q[1] + r[3] * q[0] - return t - - -def rot_matrix(roll, pitch, yaw): - cr, sr = np.cos(roll), np.sin(roll) - cp, sp = np.cos(pitch), np.sin(pitch) - cy, sy = np.cos(yaw), np.sin(yaw) - rr = array([[1, 0, 0], [0, cr, -sr], [0, sr, cr]]) - rp = array([[cp, 0, sp], [0, 1, 0], [-sp, 0, cp]]) - ry = array([[cy, -sy, 0], [sy, cy, 0], [0, 0, 1]]) - return ry.dot(rp.dot(rr)) - - -def rot(axis, angle): - # Rotates around an arbitrary axis - ret_1 = (1 - np.cos(angle)) * array([[axis[0]**2, axis[0] * axis[1], axis[0] * axis[2]], [ - axis[1] * axis[0], axis[1]**2, axis[1] * axis[2] - ], [axis[2] * axis[0], axis[2] * axis[1], axis[2]**2]]) - ret_2 = np.cos(angle) * np.eye(3) - ret_3 = np.sin(angle) * array([[0, -axis[2], axis[1]], [axis[2], 0, -axis[0]], - [-axis[1], axis[0], 0]]) - return ret_1 + ret_2 + ret_3 - - -def ecef_euler_from_ned(ned_ecef_init, ned_pose): - ''' - Got it from here: - Using Rotations to Build Aerospace Coordinate Systems - -Don Koks - ''' - converter = LocalCoord.from_ecef(ned_ecef_init) - x0 = converter.ned2ecef([1, 0, 0]) - converter.ned2ecef([0, 0, 0]) - y0 = converter.ned2ecef([0, 1, 0]) - converter.ned2ecef([0, 0, 0]) - z0 = converter.ned2ecef([0, 0, 1]) - converter.ned2ecef([0, 0, 0]) - - x1 = rot(z0, ned_pose[2]).dot(x0) - y1 = rot(z0, ned_pose[2]).dot(y0) - z1 = rot(z0, ned_pose[2]).dot(z0) - - x2 = rot(y1, ned_pose[1]).dot(x1) - y2 = rot(y1, ned_pose[1]).dot(y1) - z2 = rot(y1, ned_pose[1]).dot(z1) - - x3 = rot(x2, ned_pose[0]).dot(x2) - y3 = rot(x2, ned_pose[0]).dot(y2) - #z3 = rot(x2, ned_pose[0]).dot(z2) - - x0 = array([1, 0, 0]) - y0 = array([0, 1, 0]) - z0 = array([0, 0, 1]) - - psi = np.arctan2(inner(x3, y0), inner(x3, x0)) - theta = np.arctan2(-inner(x3, z0), np.sqrt(inner(x3, x0)**2 + inner(x3, y0)**2)) - y2 = rot(z0, psi).dot(y0) - z2 = rot(y2, theta).dot(z0) - phi = np.arctan2(inner(y3, z2), inner(y3, y2)) - - ret = array([phi, theta, psi]) - return ret - - -def ned_euler_from_ecef(ned_ecef_init, ecef_poses): - ''' - Got the math from here: - Using Rotations to Build Aerospace Coordinate Systems - -Don Koks - - Also accepts array of ecef_poses and array of ned_ecef_inits. - Where each row is a pose and an ecef_init. - ''' - ned_ecef_init = array(ned_ecef_init) - ecef_poses = array(ecef_poses) - output_shape = ecef_poses.shape - ned_ecef_init = np.atleast_2d(ned_ecef_init) - if ned_ecef_init.shape[0] == 1: - ned_ecef_init = np.tile(ned_ecef_init[0], (output_shape[0], 1)) - ecef_poses = np.atleast_2d(ecef_poses) - - ned_poses = np.zeros(ecef_poses.shape) - for i, ecef_pose in enumerate(ecef_poses): - converter = LocalCoord.from_ecef(ned_ecef_init[i]) - x0 = array([1, 0, 0]) - y0 = array([0, 1, 0]) - z0 = array([0, 0, 1]) - - x1 = rot(z0, ecef_pose[2]).dot(x0) - y1 = rot(z0, ecef_pose[2]).dot(y0) - z1 = rot(z0, ecef_pose[2]).dot(z0) - - x2 = rot(y1, ecef_pose[1]).dot(x1) - y2 = rot(y1, ecef_pose[1]).dot(y1) - z2 = rot(y1, ecef_pose[1]).dot(z1) - - x3 = rot(x2, ecef_pose[0]).dot(x2) - y3 = rot(x2, ecef_pose[0]).dot(y2) - #z3 = rot(x2, ecef_pose[0]).dot(z2) - - x0 = converter.ned2ecef([1, 0, 0]) - converter.ned2ecef([0, 0, 0]) - y0 = converter.ned2ecef([0, 1, 0]) - converter.ned2ecef([0, 0, 0]) - z0 = converter.ned2ecef([0, 0, 1]) - converter.ned2ecef([0, 0, 0]) - - psi = np.arctan2(inner(x3, y0), inner(x3, x0)) - theta = np.arctan2(-inner(x3, z0), np.sqrt(inner(x3, x0)**2 + inner(x3, y0)**2)) - y2 = rot(z0, psi).dot(y0) - z2 = rot(y2, theta).dot(z0) - phi = np.arctan2(inner(y3, z2), inner(y3, y2)) - ned_poses[i] = array([phi, theta, psi]) - - return ned_poses.reshape(output_shape) - - -def ecef2car(car_ecef, psi, theta, points_ecef, ned_converter): - """ - TODO: add roll rotation - Converts an array of points in ecef coordinates into - x-forward, y-left, z-up coordinates - Parameters - ---------- - psi: yaw, radian - theta: pitch, radian - Returns - ------- - [x, y, z] coordinates in car frame - """ - - # input is an array of points in ecef cocrdinates - # output is an array of points in car's coordinate (x-front, y-left, z-up) - - # convert points to NED - points_ned = [] - for p in points_ecef: - points_ned.append(ned_converter.ecef2ned_matrix.dot(array(p) - car_ecef)) - - points_ned = np.vstack(points_ned).T - - # n, e, d -> x, y, z - # Calculate relative postions and rotate wrt to heading and pitch of car - invert_R = array([[1., 0., 0.], [0., -1., 0.], [0., 0., -1.]]) - - c, s = np.cos(psi), np.sin(psi) - yaw_R = array([[c, s, 0.], [-s, c, 0.], [0., 0., 1.]]) - - c, s = np.cos(theta), np.sin(theta) - pitch_R = array([[c, 0., -s], [0., 1., 0.], [s, 0., c]]) - - return dot(pitch_R, dot(yaw_R, dot(invert_R, points_ned))) diff --git a/common/transformations/setup.py b/common/transformations/setup.py new file mode 100644 index 0000000000..c239a97450 --- /dev/null +++ b/common/transformations/setup.py @@ -0,0 +1,42 @@ +import os +import numpy +import sysconfig + +from Cython.Build import cythonize +from Cython.Distutils import build_ext +from distutils.core import Extension, setup # pylint: disable=import-error,no-name-in-module + +def get_ext_filename_without_platform_suffix(filename): + name, ext = os.path.splitext(filename) + ext_suffix = sysconfig.get_config_var('EXT_SUFFIX') + + if ext_suffix == ext: + return filename + + ext_suffix = ext_suffix.replace(ext, '') + idx = name.find(ext_suffix) + + if idx == -1: + return filename + else: + return name[:idx] + ext + + +class BuildExtWithoutPlatformSuffix(build_ext): + def get_ext_filename(self, ext_name): + filename = super().get_ext_filename(ext_name) + return get_ext_filename_without_platform_suffix(filename) + + +setup( + name='Cython transformations wrapper', + cmdclass={'build_ext': BuildExtWithoutPlatformSuffix}, + ext_modules=cythonize( + Extension( + "transformations", + sources=["transformations.pyx"], + language="c++", + extra_compile_args=["-std=c++14"], + include_dirs=[numpy.get_include()], + ) +)) diff --git a/common/transformations/tests/test_coordinates.py b/common/transformations/tests/test_coordinates.py index a7fbfcde34..dc70faed0b 100755 --- a/common/transformations/tests/test_coordinates.py +++ b/common/transformations/tests/test_coordinates.py @@ -11,12 +11,6 @@ geodetic_positions = np.array([[37.7610403, -122.4778699, 115], [15.1392514, 103.6976037, 24], [24.2302229, 44.2835412, 1650]]) -geodetic_positions_radians = np.array([[0.65905448, -2.13764209, 115], - [0.47968789, -1.19706477, 2380], - [0.5670869, -1.98361593, -6], - [0.26422978, 1.80986461, 24], - [0.42289717, 0.7728936, 1650]]) - ecef_positions = np.array([[-2711076.55270557, -4259167.14692758, 3884579.87669935], [ 2068042.69652729, -5273435.40316622, 2927004.89190746], [-2160412.60461669, -4932588.89873832, 3406542.29652851], @@ -78,9 +72,6 @@ class TestNED(unittest.TestCase): np.testing.assert_allclose(geodetic_positions[:, 2], coord.ecef2geodetic(ecef_positions)[:, 2], rtol=1e-9, atol=1e-4) np.testing.assert_allclose(ecef_positions, coord.geodetic2ecef(geodetic_positions), rtol=1e-9) - np.testing.assert_allclose(geodetic_positions_radians[0], coord.ecef2geodetic(ecef_positions[0], radians=True), rtol=1e-5) - np.testing.assert_allclose(geodetic_positions_radians[:, :2], coord.ecef2geodetic(ecef_positions, radians=True)[:, :2], rtol=1e-7) - np.testing.assert_allclose(geodetic_positions_radians[:, 2], coord.ecef2geodetic(ecef_positions, radians=True)[:, 2], rtol=1e-7, atol=1e-4) def test_ned(self): for ecef_pos in ecef_positions: diff --git a/common/transformations/tests/test_orientation.py b/common/transformations/tests/test_orientation.py index 906389757b..50978e1a63 100755 --- a/common/transformations/tests/test_orientation.py +++ b/common/transformations/tests/test_orientation.py @@ -61,7 +61,7 @@ class TestOrientation(unittest.TestCase): for i in range(len(eulers)): np.testing.assert_allclose(ned_eulers[i], ned_euler_from_ecef(ecef_positions[i], eulers[i]), rtol=1e-7) #np.testing.assert_allclose(eulers[i], ecef_euler_from_ned(ecef_positions[i], ned_eulers[i]), rtol=1e-7) - np.testing.assert_allclose(ned_eulers, ned_euler_from_ecef(ecef_positions, eulers), rtol=1e-7) + # np.testing.assert_allclose(ned_eulers, ned_euler_from_ecef(ecef_positions, eulers), rtol=1e-7) if __name__ == "__main__": diff --git a/common/transformations/transformations.pxd b/common/transformations/transformations.pxd new file mode 100644 index 0000000000..b0666d5ecf --- /dev/null +++ b/common/transformations/transformations.pxd @@ -0,0 +1,68 @@ +from libcpp cimport bool + +cdef extern from "orientation.cc": + pass + +cdef extern from "orientation.hpp": + cdef cppclass Quaternion "Eigen::Quaterniond": + Quaternion() + Quaternion(double, double, double, double) + double w() + double x() + double y() + double z() + + cdef cppclass Vector3 "Eigen::Vector3d": + Vector3() + Vector3(double, double, double) + double operator()(int) + + cdef cppclass Matrix3 "Eigen::Matrix3d": + Matrix3() + Matrix3(double*) + + double operator()(int, int) + + Quaternion euler2quat(Vector3) + Vector3 quat2euler(Quaternion) + Matrix3 quat2rot(Quaternion) + Quaternion rot2quat(Matrix3) + Vector3 rot2euler(Matrix3) + Matrix3 euler2rot(Vector3) + Matrix3 rot_matrix(double, double, double) + Vector3 ecef_euler_from_ned(ECEF, Vector3) + Vector3 ned_euler_from_ecef(ECEF, Vector3) + + +cdef extern from "coordinates.cc": + cdef struct ECEF: + double x + double y + double z + + cdef struct NED: + double n + double e + double d + + cdef struct Geodetic: + double lat + double lon + double alt + bool radians + + ECEF geodetic2ecef(Geodetic) + Geodetic ecef2geodetic(ECEF) + + cdef cppclass LocalCoord_c "LocalCoord": + LocalCoord_c(Geodetic, ECEF) + LocalCoord_c(Geodetic) + LocalCoord_c(ECEF) + + NED ecef2ned(ECEF) + ECEF ned2ecef(NED) + NED geodetic2ned(Geodetic) + Geodetic ned2geodetic(NED) + +cdef extern from "coordinates.hpp": + pass diff --git a/common/transformations/transformations.pyx b/common/transformations/transformations.pyx new file mode 100644 index 0000000000..2a4e8e67b3 --- /dev/null +++ b/common/transformations/transformations.pyx @@ -0,0 +1,156 @@ +from transformations cimport Matrix3, Vector3, Quaternion +from transformations cimport ECEF, NED, Geodetic + +from transformations cimport euler2quat as euler2quat_c +from transformations cimport quat2euler as quat2euler_c +from transformations cimport quat2rot as quat2rot_c +from transformations cimport rot2quat as rot2quat_c +from transformations cimport euler2rot as euler2rot_c +from transformations cimport rot2euler as rot2euler_c +from transformations cimport rot_matrix as rot_matrix_c +from transformations cimport ecef_euler_from_ned as ecef_euler_from_ned_c +from transformations cimport ned_euler_from_ecef as ned_euler_from_ecef_c +from transformations cimport geodetic2ecef as geodetic2ecef_c +from transformations cimport ecef2geodetic as ecef2geodetic_c +from transformations cimport LocalCoord_c + + +import cython +import numpy as np +cimport numpy as np + +cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): + return np.array([ + [m(0, 0), m(0, 1), m(0, 2)], + [m(1, 0), m(1, 1), m(1, 2)], + [m(2, 0), m(2, 1), m(2, 2)], + ]) + +cdef Matrix3 numpy2matrix (np.ndarray[double, ndim=2, mode="fortran"] m): + assert m.shape[0] == 3 + assert m.shape[1] == 3 + return Matrix3(m.data) + +cdef ECEF list2ecef(ecef): + cdef ECEF e; + e.x = ecef[0] + e.y = ecef[1] + e.z = ecef[2] + return e + +cdef NED list2ned(ned): + cdef NED n; + n.n = ned[0] + n.e = ned[1] + n.d = ned[2] + return n + +cdef Geodetic list2geodetic(geodetic): + cdef Geodetic g + g.lat = geodetic[0] + g.lon = geodetic[1] + g.alt = geodetic[2] + return g + +def euler2quat_single(euler): + cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + cdef Quaternion q = euler2quat_c(e) + return [q.w(), q.x(), q.y(), q.z()] + +def quat2euler_single(quat): + cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + cdef Vector3 e = quat2euler_c(q); + return [e(0), e(1), e(2)] + +def quat2rot_single(quat): + cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + cdef Matrix3 r = quat2rot_c(q) + return matrix2numpy(r) + +def rot2quat_single(rot): + cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + cdef Quaternion q = rot2quat_c(r) + return [q.w(), q.x(), q.y(), q.z()] + +def euler2rot_single(euler): + cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + cdef Matrix3 r = euler2rot_c(e) + return matrix2numpy(r) + +def rot2euler_single(rot): + cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + cdef Vector3 e = rot2euler_c(r) + return [e(0), e(1), e(2)] + +def rot_matrix(roll, pitch, yaw): + return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + +def ecef_euler_from_ned_single(ecef_init, ned_pose): + cdef ECEF init = list2ecef(ecef_init) + cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + + cdef Vector3 e = ecef_euler_from_ned_c(init, pose) + return [e(0), e(1), e(2)] + +def ned_euler_from_ecef_single(ecef_init, ecef_pose): + cdef ECEF init = list2ecef(ecef_init) + cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + + cdef Vector3 e = ned_euler_from_ecef_c(init, pose) + return [e(0), e(1), e(2)] + +def geodetic2ecef_single(geodetic): + cdef Geodetic g = list2geodetic(geodetic) + cdef ECEF e = geodetic2ecef_c(g) + return [e.x, e.y, e.z] + +def ecef2geodetic_single(ecef): + cdef ECEF e = list2ecef(ecef) + cdef Geodetic g = ecef2geodetic_c(e) + return [g.lat, g.lon, g.alt] + + +cdef class LocalCoord: + cdef LocalCoord_c * lc + + def __init__(self, geodetic=None, ecef=None): + assert (geodetic is not None) or (ecef is not None) + if geodetic is not None: + self.lc = new LocalCoord_c(list2geodetic(geodetic)) + elif ecef is not None: + self.lc = new LocalCoord_c(list2ecef(ecef)) + + @classmethod + def from_geodetic(cls, geodetic): + return cls(geodetic=geodetic) + + @classmethod + def from_ecef(cls, ecef): + return cls(ecef=ecef) + + def ecef2ned_single(self, ecef): + assert self.lc + cdef ECEF e = list2ecef(ecef) + cdef NED n = self.lc.ecef2ned(e) + return [n.n, n.e, n.d] + + def ned2ecef_single(self, ned): + assert self.lc + cdef NED n = list2ned(ned) + cdef ECEF e = self.lc.ned2ecef(n) + return [e.x, e.y, e.z] + + def geodetic2ned_single(self, geodetic): + assert self.lc + cdef Geodetic g = list2geodetic(geodetic) + cdef NED n = self.lc.geodetic2ned(g) + return [n.n, n.e, n.d] + + def ned2geodetic_single(self, ned): + assert self.lc + cdef NED n = list2ned(ned) + cdef Geodetic g = self.lc.ned2geodetic(n) + return [g.lat, g.lon, g.alt] + + def __dealloc__(self): + del self.lc diff --git a/release/files_common b/release/files_common index 26ca00915c..7ef893ebc5 100644 --- a/release/files_common +++ b/release/files_common @@ -43,9 +43,18 @@ common/kalman/* common/transformations/__init__.py common/transformations/camera.py -common/transformations/coordinates.py common/transformations/model.py + +common/transformations/SConscript +common/transformations/setup.py +common/transformations/coordinates.py +common/transformations/coordinates.cc +common/transformations/coordinates.hpp common/transformations/orientation.py +common/transformations/orientation.cc +common/transformations/orientation.hpp +common/transformations/transformations.pxd +common/transformations/transformations.pyx common/api/__init__.py diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 3b78a0ca66..00f31b644c 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -21,7 +21,6 @@ from sympy.utilities.lambdify import lambdify from rednose.helpers.sympy_helpers import euler_rotate -OUTPUT_DECIMATION = 2 VISION_DECIMATION = 2 SENSOR_DECIMATION = 10 @@ -194,7 +193,7 @@ class Localizer(): self.converter = coord.LocalCoord.from_geodetic([log.latitude, log.longitude, log.altitude]) ecef_pos = self.converter.ned2ecef([0, 0, 0]) - ecef_vel = self.converter.ned2ecef_matrix.dot(np.array(log.vNED)) + ecef_vel = self.converter.ned2ecef(np.array(log.vNED)) - ecef_pos ecef_pos_R = np.diag([(3*log.verticalAccuracy)**2]*3) ecef_vel_R = np.diag([(log.speedAccuracy)**2]*3) @@ -263,14 +262,15 @@ class Localizer(): self.update_kalman(current_time, ObservationKind.PHONE_ACCEL, [-v[2], -v[1], -v[0]]) def handle_live_calib(self, current_time, log): - self.calib = log.rpyCalib - self.device_from_calib = rot_from_euler(self.calib) - self.calib_from_device = self.device_from_calib.T - self.calibrated = log.calStatus == 1 + if len(log.rpyCalib): + self.calib = log.rpyCalib + self.device_from_calib = rot_from_euler(self.calib) + self.calib_from_device = self.device_from_calib.T + self.calibrated = log.calStatus == 1 def reset_kalman(self, current_time=None, init_orient=None): self.filter_time = current_time - init_x = LiveKalman.initial_x + init_x = LiveKalman.initial_x.copy() # too nonlinear to init on completely wrong if init_orient is not None: init_x[3:7] = init_orient @@ -295,7 +295,6 @@ def locationd_thread(sm, pm, disabled_logs=None): pm = messaging.PubMaster(['liveLocationKalman']) localizer = Localizer(disabled_logs=disabled_logs) - camera_odometry_cnt = 0 while True: sm.update() @@ -315,19 +314,16 @@ def locationd_thread(sm, pm, disabled_logs=None): localizer.handle_live_calib(t, sm[sock]) if sm.updated['cameraOdometry']: - camera_odometry_cnt += 1 + t = sm.logMonoTime['cameraOdometry'] + msg = messaging.new_message('liveLocationKalman') + msg.logMonoTime = t - if camera_odometry_cnt % OUTPUT_DECIMATION == 0: - t = sm.logMonoTime['cameraOdometry'] - msg = messaging.new_message('liveLocationKalman') - msg.logMonoTime = t + msg.liveLocationKalman = localizer.liveLocationMsg(t * 1e-9) + msg.liveLocationKalman.inputsOK = sm.all_alive_and_valid() - msg.liveLocationKalman = localizer.liveLocationMsg(t * 1e-9) - msg.liveLocationKalman.inputsOK = sm.all_alive_and_valid() - - gps_age = (t / 1e9) - localizer.last_gps_fix - msg.liveLocationKalman.gpsOK = gps_age < 1.0 - pm.send('liveLocationKalman', msg) + gps_age = (t / 1e9) - localizer.last_gps_fix + msg.liveLocationKalman.gpsOK = gps_age < 1.0 + pm.send('liveLocationKalman', msg) def main(sm=None, pm=None): diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py index 10f5231df0..39bf8690ac 100755 --- a/selfdrive/test/process_replay/compare_logs.py +++ b/selfdrive/test/process_replay/compare_logs.py @@ -70,7 +70,7 @@ def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None): if msg1_bytes != msg2_bytes: msg1_dict = msg1.to_dict(verbose=True) msg2_dict = msg2.to_dict(verbose=True) - dd = dictdiffer.diff(msg1_dict, msg2_dict, ignore=ignore_fields, tolerance=0) + dd = dictdiffer.diff(msg1_dict, msg2_dict, ignore=ignore_fields) diff.extend(dd) return diff diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index b42fefea26..6fd3c8ec2d 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -66,7 +66,11 @@ class FakeSocket: class DumbSocket: def __init__(self, s=None): if s is not None: - dat = messaging.new_message(s) + try: + dat = messaging.new_message(s) + except capnp.lib.capnp.KjException: # pylint: disable=c-extension-no-member + # lists + dat = messaging.new_message(s, 0) self.data = dat.to_bytes() def receive(self, non_blocking=False): @@ -255,6 +259,17 @@ CONFIGS = [ init_callback=get_car_params, should_recv_callback=None, ), + ProcessConfig( + proc_name="locationd", + pub_sub={ + "cameraOdometry": ["liveLocationKalman"], + "sensorEvents": [], "gpsLocationExternal": [], "liveCalibration": [], "carState": [], + }, + ignore=["logMonoTime", "valid"], + init_callback=get_car_params, + should_recv_callback=None, + ), + ] def replay_process(cfg, lr): diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index c285bfb49c..bb6039e7e5 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -0533f640ab27f7b5af57aa4ebf4a29200550b3e8 \ No newline at end of file +834f4cd7e90ff266ced8ea142d7d7d05076186aa \ No newline at end of file From a777fa851e8a444cadb516fc4e35b641018f0559 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 9 Jun 2020 16:45:56 -0700 Subject: [PATCH 239/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 0021fa2419..68fdf28670 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 0021fa241994cd9d94945ba305b0f3f1c43feaae +Subproject commit 68fdf28670b48a16a60498b4e5cc1984e7e66651 From a2e6e4c71c804bb5caf59e4df1609320d66247ef Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Tue, 9 Jun 2020 18:59:27 -0500 Subject: [PATCH 240/656] 2016 RX350 F Sport (#1671) @gweedor#9653 DongleID 28f8c941d8b28743 --- selfdrive/car/toyota/values.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 9b30e91dff..ff210b03b2 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -849,22 +849,27 @@ FW_VERSIONS = { CAR.LEXUS_RX: { (Ecu.engine, 0x700, None): [ b'\x01896630E41200\x00\x00\x00\x00', + b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152648473\x00\x00\x00\x00\x00\x00', + b'F152648831\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'881514810500\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B0E012\x00\x00\x00\x00\x00\x00', + b'8965B48271\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F4701100\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'8646F4802001\x00\x00\x00\x00', b'8646F4802100\x00\x00\x00\x00', + b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', ], }, CAR.LEXUS_RXH: { From fac023147127fd79805b54428ac33b819f1138cd Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 9 Jun 2020 17:36:16 -0700 Subject: [PATCH 241/656] wider margins on stiffness --- selfdrive/locationd/paramsd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index 70ffd4795c..487dc640e0 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -127,7 +127,7 @@ def main(sm=None, pm=None): msg.liveParameters.valid = all(( abs(msg.liveParameters.angleOffsetAverage) < 10.0, abs(msg.liveParameters.angleOffset) < 10.0, - 0.5 <= msg.liveParameters.stiffnessFactor <= 2.0, + 0.2 <= msg.liveParameters.stiffnessFactor <= 5.0, min_sr <= msg.liveParameters.steerRatio <= max_sr, )) From dc68b4defd0e9a100e117504c869f18f1c881105 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 9 Jun 2020 17:38:42 -0700 Subject: [PATCH 242/656] don't reboot on PC --- selfdrive/manager.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index ed8b6a9f28..fcf75ff1c9 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -359,9 +359,11 @@ def kill_managed_process(name): cloudlog.critical("unkillable process %s failed to exit! rebooting in 15 if it doesn't die" % name) join_process(running[name], 15) if running[name].exitcode is None: - cloudlog.critical("FORCE REBOOTING PHONE!") - os.system("date >> /sdcard/unkillable_reboot") - os.system("reboot") + cloudlog.critical("unkillable process %s failed to die!" % name) + if ANDROID: + cloudlog.critical("FORCE REBOOTING PHONE!") + os.system("date >> /sdcard/unkillable_reboot") + os.system("reboot") raise RuntimeError else: cloudlog.info("killing %s with SIGKILL" % name) From 53a8df5a4133b9020363a381322da6177c9f45ed Mon Sep 17 00:00:00 2001 From: martinl Date: Wed, 10 Jun 2020 17:30:09 +0300 Subject: [PATCH 243/656] Fix typo in Github Actions workflow (#1673) --- .github/workflows/test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index b6d422c9f3..fa1a82b29a 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -38,7 +38,7 @@ jobs: mkdir laika laika_repo tools release - name: Build Docker image run: cd $TEST_DIR && eval "$BUILD" - - name: Build openpiot and run quick check + - name: Build openpilot and run quick check run: | $RUN "cd /tmp/openpilot && \ scons -j$(nproc) && \ From 8ad1135e80f93b19bb2f0a6b4c7531a9b5eb7d8a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 11 Jun 2020 01:28:18 +0800 Subject: [PATCH 244/656] add set_brightness in framebuffer.h (#1659) --- selfdrive/common/framebuffer.cc | 19 ++++++++++--------- selfdrive/common/framebuffer.h | 7 ++----- selfdrive/ui/linux.cc | 2 ++ selfdrive/ui/text/text.c | 9 --------- selfdrive/ui/ui.cc | 13 +++++-------- 5 files changed, 19 insertions(+), 31 deletions(-) diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc index 1d8ccdbdb2..46e1b38d70 100644 --- a/selfdrive/common/framebuffer.cc +++ b/selfdrive/common/framebuffer.cc @@ -12,7 +12,6 @@ #include #include -#define BACKLIGHT_CONTROL "/sys/class/leds/lcd-backlight/brightness" #define BACKLIGHT_LEVEL "205" using namespace android; @@ -123,14 +122,7 @@ extern "C" FramebufferState* framebuffer_init( printf("gl version %s\n", glGetString(GL_VERSION)); - - // set brightness - int brightness_fd = open(BACKLIGHT_CONTROL, O_RDWR); - if (brightness_fd != -1){ - const char brightness_level[] = BACKLIGHT_LEVEL; - write(brightness_fd, brightness_level, strlen(brightness_level)); - close(brightness_fd); - } + set_brightness(BACKLIGHT_LEVEL); if (out_w) *out_w = w; if (out_h) *out_h = h; @@ -143,3 +135,12 @@ extern "C" void framebuffer_swap(FramebufferState *s) { assert(glGetError() == GL_NO_ERROR); } +extern "C" bool set_brightness(int brightness) { + FILE *f = fopen("/sys/class/leds/lcd-backlight/brightness", "wb"); + if (f != NULL) { + fprintf(f, "%d", brightness); + fclose(f); + return true; + } + return false; +} diff --git a/selfdrive/common/framebuffer.h b/selfdrive/common/framebuffer.h index 45920b8e42..45053bbb14 100644 --- a/selfdrive/common/framebuffer.h +++ b/selfdrive/common/framebuffer.h @@ -1,5 +1,4 @@ -#ifndef FRAMEBUFFER_H -#define FRAMEBUFFER_H +#pragma once #ifdef __cplusplus extern "C" { @@ -13,6 +12,7 @@ FramebufferState* framebuffer_init( void framebuffer_set_power(FramebufferState *s, int mode); void framebuffer_swap(FramebufferState *s); +bool set_brightness(int brightness); /* Display power modes */ enum { @@ -40,9 +40,6 @@ enum { HWC_POWER_MODE_DOZE_SUSPEND = 3, }; - #ifdef __cplusplus } #endif - -#endif diff --git a/selfdrive/ui/linux.cc b/selfdrive/ui/linux.cc index 8e4a8492dc..e5bb672b48 100644 --- a/selfdrive/ui/linux.cc +++ b/selfdrive/ui/linux.cc @@ -64,6 +64,8 @@ void framebuffer_swap(FramebufferState *s) { glfwPollEvents(); } +bool set_brightness(int brightness) { return true; } + void touch_init(TouchState *s) { printf("touch_init\n"); } diff --git a/selfdrive/ui/text/text.c b/selfdrive/ui/text/text.c index 6a2b6c753e..43c43e4689 100644 --- a/selfdrive/ui/text/text.c +++ b/selfdrive/ui/text/text.c @@ -14,7 +14,6 @@ #include "nanovg_gl.h" #include "nanovg_gl_utils.h" - #include "common/framebuffer.h" #include "common/touch.h" @@ -25,14 +24,6 @@ extern const unsigned char _binary_opensans_regular_ttf_start[]; extern const unsigned char _binary_opensans_regular_ttf_end[]; -static void set_brightness(int brightness) { - FILE *f = fopen("/sys/class/leds/lcd-backlight/brightness", "wb"); - if (f != NULL) { - fprintf(f, "%d", brightness); - fclose(f); - } -} - int main(int argc, char** argv) { int err; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 8127e9ee05..65cbb35cba 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -17,13 +17,10 @@ #include "common/utilpp.h" #include "ui.hpp" -static int last_brightness = -1; -static void set_brightness(UIState *s, int brightness) { +static void ui_set_brightness(UIState *s, int brightness) { + static int last_brightness = -1; if (last_brightness != brightness && (s->awake || brightness == 0)) { - FILE *f = fopen("/sys/class/leds/lcd-backlight/brightness", "wb"); - if (f != NULL) { - fprintf(f, "%d", brightness); - fclose(f); + if (set_brightness(brightness)) { last_brightness = brightness; } } @@ -56,7 +53,7 @@ static void set_awake(UIState *s, bool awake) { enable_event_processing(true); } else { LOGW("awake off"); - set_brightness(s, 0); + ui_set_brightness(s, 0); framebuffer_set_power(s->fb, HWC_POWER_MODE_OFF); enable_event_processing(false); } @@ -788,7 +785,7 @@ int main(int argc, char* argv[]) { if (clipped_brightness > 512) clipped_brightness = 512; smooth_brightness = clipped_brightness * 0.01 + smooth_brightness * 0.99; if (smooth_brightness > 255) smooth_brightness = 255; - set_brightness(s, (int)smooth_brightness); + ui_set_brightness(s, (int)smooth_brightness); // resize vision for collapsing sidebar const bool hasSidebar = !s->scene.uilayout_sidebarcollapsed; From 29262db5d63f0e5d65c2f00d4929991fb2e0d848 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 10 Jun 2020 11:35:45 -0700 Subject: [PATCH 245/656] add getter for LocalCoord transformation matrices --- common/transformations/coordinates.hpp | 3 +-- common/transformations/transformations.pxd | 3 +++ common/transformations/transformations.pyx | 16 ++++++++++++++++ 3 files changed, 20 insertions(+), 2 deletions(-) diff --git a/common/transformations/coordinates.hpp b/common/transformations/coordinates.hpp index be6fe2e75f..d8beb59ea9 100644 --- a/common/transformations/coordinates.hpp +++ b/common/transformations/coordinates.hpp @@ -20,11 +20,10 @@ ECEF geodetic2ecef(Geodetic g); Geodetic ecef2geodetic(ECEF e); class LocalCoord { -private: +public: Eigen::Matrix3d ned2ecef_matrix; Eigen::Matrix3d ecef2ned_matrix; Eigen::Vector3d init_ecef; -public: LocalCoord(Geodetic g, ECEF e); LocalCoord(Geodetic g) : LocalCoord(g, ::geodetic2ecef(g)) {} LocalCoord(ECEF e) : LocalCoord(::ecef2geodetic(e), e) {} diff --git a/common/transformations/transformations.pxd b/common/transformations/transformations.pxd index b0666d5ecf..cb3ee53b19 100644 --- a/common/transformations/transformations.pxd +++ b/common/transformations/transformations.pxd @@ -55,6 +55,9 @@ cdef extern from "coordinates.cc": Geodetic ecef2geodetic(ECEF) cdef cppclass LocalCoord_c "LocalCoord": + Matrix3 ned2ecef_matrix + Matrix3 ecef2ned_matrix + LocalCoord_c(Geodetic, ECEF) LocalCoord_c(Geodetic) LocalCoord_c(ECEF) diff --git a/common/transformations/transformations.pyx b/common/transformations/transformations.pyx index 2a4e8e67b3..194257e037 100644 --- a/common/transformations/transformations.pyx +++ b/common/transformations/transformations.pyx @@ -120,6 +120,22 @@ cdef class LocalCoord: elif ecef is not None: self.lc = new LocalCoord_c(list2ecef(ecef)) + @property + def ned2ecef_matrix(self): + return matrix2numpy(self.lc.ned2ecef_matrix) + + @property + def ecef2ned_matrix(self): + return matrix2numpy(self.lc.ecef2ned_matrix) + + @property + def ned_from_ecef_matrix(self): + return self.ecef2ned_matrix + + @property + def ecef_from_ned_matrix(self): + return self.ned2ecef_matrix + @classmethod def from_geodetic(cls, geodetic): return cls(geodetic=geodetic) From 431690be1e0843eda72a7e703344d7a2d20f12fd Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 10 Jun 2020 11:41:45 -0700 Subject: [PATCH 246/656] Move helper function definition to top of file --- selfdrive/common/framebuffer.cc | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc index 46e1b38d70..11404edd97 100644 --- a/selfdrive/common/framebuffer.cc +++ b/selfdrive/common/framebuffer.cc @@ -31,6 +31,21 @@ struct FramebufferState { EGLContext context; }; +extern "C" void framebuffer_swap(FramebufferState *s) { + eglSwapBuffers(s->display, s->surface); + assert(glGetError() == GL_NO_ERROR); +} + +extern "C" bool set_brightness(int brightness) { + FILE *f = fopen("/sys/class/leds/lcd-backlight/brightness", "wb"); + if (f != NULL) { + fprintf(f, "%d", brightness); + fclose(f); + return true; + } + return false; +} + extern "C" void framebuffer_set_power(FramebufferState *s, int mode) { SurfaceComposerClient::setDisplayPowerMode(s->dtoken, mode); } @@ -129,18 +144,3 @@ extern "C" FramebufferState* framebuffer_init( return s; } - -extern "C" void framebuffer_swap(FramebufferState *s) { - eglSwapBuffers(s->display, s->surface); - assert(glGetError() == GL_NO_ERROR); -} - -extern "C" bool set_brightness(int brightness) { - FILE *f = fopen("/sys/class/leds/lcd-backlight/brightness", "wb"); - if (f != NULL) { - fprintf(f, "%d", brightness); - fclose(f); - return true; - } - return false; -} From ceba6fc6754b73c8fff114a45001b8d1fd5cbd2b Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 10 Jun 2020 12:42:00 -0700 Subject: [PATCH 247/656] Set brightness takes an int --- selfdrive/common/framebuffer.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc index 11404edd97..d39fa8cb49 100644 --- a/selfdrive/common/framebuffer.cc +++ b/selfdrive/common/framebuffer.cc @@ -12,7 +12,7 @@ #include #include -#define BACKLIGHT_LEVEL "205" +#define BACKLIGHT_LEVEL 205 using namespace android; From ec5fc0e92b5f381c5e2c464d3fa65c8db0fc3246 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Wed, 10 Jun 2020 14:40:22 -0700 Subject: [PATCH 248/656] Update realtime priority for modeld/dmonitoringd (#1675) --- selfdrive/modeld/dmonitoringmodeld.cc | 2 +- selfdrive/modeld/modeld.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/modeld/dmonitoringmodeld.cc b/selfdrive/modeld/dmonitoringmodeld.cc index c987e44482..e39fba1689 100644 --- a/selfdrive/modeld/dmonitoringmodeld.cc +++ b/selfdrive/modeld/dmonitoringmodeld.cc @@ -23,7 +23,7 @@ static void set_do_exit(int sig) { int main(int argc, char **argv) { int err; - set_realtime_priority(1); + set_realtime_priority(51); // messaging SubMaster sm({"dMonitoringState"}); diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 5404f61b3c..7206f5a9e8 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -73,7 +73,7 @@ void* live_thread(void *arg) { int main(int argc, char **argv) { int err; - set_realtime_priority(1); + set_realtime_priority(51); // start calibration thread pthread_t live_thread_handle; From 681ef81ed82650e5cc1d420362d363ee83f7a9ad Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Wed, 10 Jun 2020 15:15:51 -0700 Subject: [PATCH 249/656] fix dtype (#1676) --- selfdrive/ui/paint.cc | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 60e403aff6..71e26b657e 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -604,10 +604,10 @@ static void ui_draw_driver_view(UIState *s) { // draw face box if (scene->driver_state.getFaceProb() > 0.4) { auto fxy_list = scene->driver_state.getFacePosition(); - const int face_x = fxy_list[0]; - const int face_y = fxy_list[1]; - int fbox_x; - int fbox_y = box_y + (face_y + 0.5) * box_h - 0.5 * 0.6 * box_h / 2;; + const float face_x = fxy_list[0]; + const float face_y = fxy_list[1]; + float fbox_x; + float fbox_y = box_y + (face_y + 0.5) * box_h - 0.5 * 0.6 * box_h / 2;; if (!scene->is_rhd) { fbox_x = valid_frame_x + (1 - (face_x + 0.5)) * (box_h / 2) - 0.5 * 0.6 * box_h / 2; } else { From c82fda995b2b79e9956e42fe641cfe31d4b3932d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 10 Jun 2020 15:21:43 -0700 Subject: [PATCH 250/656] Increase temperature range --- selfdrive/thermald/thermald.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 4cbcc6fb42..a67f086dd1 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -272,10 +272,10 @@ def thermald_thread(): if max_cpu_temp > 107. or bat_temp >= 63.: # onroad not allowed thermal_status = ThermalStatus.danger - elif max_comp_temp > 92.5 or bat_temp > 60.: # CPU throttling starts around ~90C + elif max_comp_temp > 100.0 or bat_temp > 60.: # hysteresis between onroad not allowed and engage not allowed thermal_status = clip(thermal_status, ThermalStatus.red, ThermalStatus.danger) - elif max_cpu_temp > 87.5: + elif max_cpu_temp > 97.0: # hysteresis between engage not allowed and uploader not allowed thermal_status = clip(thermal_status, ThermalStatus.yellow, ThermalStatus.red) elif max_cpu_temp > 80.0: From 87bbbd41005c93dd6fae872622102fbd14f9afef Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 10 Jun 2020 17:25:48 -0700 Subject: [PATCH 251/656] Clean mesh3d 2 (#1618) * seems overkill * not too extreme * make linter happy * try adding accel scale * some tweaks * Revert "some tweaks" This reverts commit 58cec365da650fa653dee91c7a5cbe37b8289908. * Revert "Revert "some tweaks"" This reverts commit 517108b5b676b4ab31bba92a9eb59afa1b3d3faf. * stability concerns * this works * still works * ugh sympy is weird, still may be not correct * comment clean * comment * clarify * fix * unused --- selfdrive/locationd/models/loc_kf.py | 69 ++++++++++++++-------------- 1 file changed, 35 insertions(+), 34 deletions(-) diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index 421b0a64f9..013fbc7303 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -48,6 +48,7 @@ class States(): GLONASS_BIAS = slice(26, 27) # GLONASS bias in m expressed as bias + freq_num*freq_slope GLONASS_FREQ_SLOPE = slice(27, 28) # GLONASS bias in m expressed as bias + freq_num*freq_slope CLOCK_ACCELERATION = slice(28, 29) # clock acceleration in light-meters/s**2, + ACCELEROMETER_SCALE = slice(29, 30) # scale of mems accelerometer # Error-state has different slices because it is an ESKF ECEF_POS_ERR = slice(0, 3) @@ -64,11 +65,12 @@ class States(): GLONASS_BIAS_ERR = slice(25, 26) GLONASS_FREQ_SLOPE_ERR = slice(26, 27) CLOCK_ACCELERATION_ERR = slice(27, 28) + ACCELEROMETER_SCALE_ERR = slice(28, 29) class LocKalman(): name = "loc" - x_initial = np.array([-2.7e6, 4.2e6, 3.8e6, + x_initial = np.array([0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -79,7 +81,8 @@ class LocKalman(): 1, 0, 0, 0, 0, 0, - 0]) + 0, + 1], dtype=np.float64) # state covariance P_initial = np.diag([1e16, 1e16, 1e16, @@ -93,7 +96,8 @@ class LocKalman(): 0.01**2, (0.01)**2, (0.01)**2, (0.01)**2, 10**2, 1**2, - 0.2**2]) + 0.2**2, + 0.05**2]) # process noise Q = np.diag([0.03**2, 0.03**2, 0.03**2, @@ -107,7 +111,8 @@ class LocKalman(): 0.001**2, (0.05 / 60)**2, (0.05 / 60)**2, (0.05 / 60)**2, (.1)**2, (.01)**2, - 0.005**2]) + 0.005**2, + (0.02 / 100)**2]) # measurements that need to pass mahalanobis distance outlier rejector maha_test_kinds = [ObservationKind.ORB_FEATURES] # , ObservationKind.PSEUDORANGE, ObservationKind.PSEUDORANGE_RATE] @@ -137,21 +142,19 @@ class LocKalman(): vx, vy, vz = v omega = state[States.ANGULAR_VELOCITY, :] vroll, vpitch, vyaw = omega - #cb = state[States.CLOCK_BIAS, :][0, 0] - #cd = state[States.CLOCK_DRIFT, :][0, 0] - cb, cd = state[13:15, :] + cb = state[States.CLOCK_BIAS, :] + cd = state[States.CLOCK_DRIFT, :] roll_bias, pitch_bias, yaw_bias = state[States.GYRO_BIAS, :] - #odo_scale = state[States.ODO_SCALE, :][0,0] - odo_scale = state[18, :] + odo_scale = state[States.ODO_SCALE, :] acceleration = state[States.ACCELERATION, :] - #focal_scale = state[States.FOCAL_SCALE, :][0,0] - focal_scale = state[22, :] + focal_scale = state[States.FOCAL_SCALE, :] imu_angles = state[States.IMU_OFFSET, :] - glonass_bias, glonass_freq_slope = state[26:28, :] - ca = state[28, 0] - #glonass_bias = state[States.GLONASS_BIAS, :][0,0] - #glonass_freq_slope = state[States.GLONASS_FREQ_SLOPE, :][0,0] - #ca = state[States.CLOCK_ACCELERATION, :][0,0] + imu_angles[0, 0] = 0 + imu_angles[2, 0] = 0 + glonass_bias = state[States.GLONASS_BIAS, :] + glonass_freq_slope = state[States.GLONASS_FREQ_SLOPE, :] + ca = state[States.CLOCK_ACCELERATION, :] + accel_scale = state[States.ACCELEROMETER_SCALE, :] dt = sp.Symbol('dt') @@ -173,10 +176,8 @@ class LocKalman(): state_dot[States.ECEF_POS, :] = v state_dot[States.ECEF_ORIENTATION, :] = q_dot state_dot[States.ECEF_VELOCITY, 0] = quat_rot * acceleration - state_dot[13, 0] = cd - state_dot[14, 0] = ca - #state_dot[States.CLOCK_BIAS, 0][0,0] = cd - state_dot[States.CLOCK_DRIFT, 0][0, 0] = ca + state_dot[States.CLOCK_BIAS, :] = cd + state_dot[States.CLOCK_DRIFT, :] = ca # Basic descretization, 1st order intergrator # Can be pretty bad if dt is big @@ -187,10 +188,9 @@ class LocKalman(): quat_err = state_err[States.ECEF_ORIENTATION_ERR, :] v_err = state_err[States.ECEF_VELOCITY_ERR, :] omega_err = state_err[States.ANGULAR_VELOCITY_ERR, :] - #cd_err = state_err[States.CLOCK_DRIFT_ERR, :][0,:] - cd_err = state_err[13, :] + cd_err = state_err[States.CLOCK_DRIFT_ERR, :] acceleration_err = state_err[States.ACCELERATION_ERR, :] - ca_err = state_err[27, :] + ca_err = state_err[States.CLOCK_ACCELERATION_ERR, :] # Time derivative of the state error as a function of state error and state quat_err_matrix = euler_rotate(quat_err[0], quat_err[1], quat_err[2]) @@ -199,10 +199,8 @@ class LocKalman(): state_err_dot[States.ECEF_POS_ERR, :] = v_err state_err_dot[States.ECEF_ORIENTATION_ERR, :] = q_err_dot state_err_dot[States.ECEF_VELOCITY_ERR, :] = quat_err_matrix * quat_rot * (acceleration + acceleration_err) - #state_err_dot[States.CLOCK_BIAS_ERR, :][0,:] = cd_err - #state_err_dot[States.CLOCK_DRIFT_ERR, :][0,:] = ca_err - state_err_dot[12, :][0, :] = cd_err - state_err_dot[13, :][0, :] = ca_err + state_err_dot[States.CLOCK_BIAS_ERR, :] = cd_err + state_err_dot[States.CLOCK_DRIFT_ERR, :] = ca_err f_err_sym = state_err + dt * state_err_dot # convenient indexing @@ -266,7 +264,7 @@ class LocKalman(): (x - sat_x)**2 + (y - sat_y)**2 + (z - sat_z)**2 - ) + cb + ) + cb[0] ]) h_pseudorange_glonass_sym = sp.Matrix([ @@ -274,7 +272,7 @@ class LocKalman(): (x - sat_x)**2 + (y - sat_y)**2 + (z - sat_z)**2 - ) + cb + glonass_bias + glonass_freq_slope * glonass_freq + ) + cb[0] + glonass_bias[0] + glonass_freq_slope[0] * glonass_freq ]) los_vector = (sp.Matrix(sat_pos_vel_sym[0:3]) - sp.Matrix([x, y, z])) @@ -282,7 +280,7 @@ class LocKalman(): h_pseudorange_rate_sym = sp.Matrix([los_vector[0] * (sat_vx - vx) + los_vector[1] * (sat_vy - vy) + los_vector[2] * (sat_vz - vz) + - cd]) + cd[0]]) imu_rot = euler_rotate(*imu_angles) h_gyro_sym = imu_rot * sp.Matrix([vroll + roll_bias, @@ -290,8 +288,9 @@ class LocKalman(): vyaw + yaw_bias]) pos = sp.Matrix([x, y, z]) - gravity = quat_rot.T * ((EARTH_GM / ((x**2 + y**2 + z**2)**(3.0 / 2.0))) * pos) - h_acc_sym = imu_rot * (gravity + acceleration) + # add 1 for stability, prevent division by 0 + gravity = quat_rot.T * ((EARTH_GM / ((x**2 + y**2 + z**2 + 1)**(3.0 / 2.0))) * pos) + h_acc_sym = imu_rot * (accel_scale[0] * (gravity + acceleration)) h_phone_rot_sym = sp.Matrix([vroll, vpitch, vyaw]) speed = sp.sqrt(vx**2 + vy**2 + vz**2) @@ -325,7 +324,9 @@ class LocKalman(): # MSCKF configuration if N > 0: - focal_scale = 1 + # experimentally found this is correct value for imx298 with 910 focal length + # this is a variable so it can change with focus, but we disregard that for now + focal_scale = 1.01 # Add observation functions for orb feature tracks track_epos_sym = sp.MatrixSymbol('track_epos_sym', 3, 1) track_x, track_y, track_z = track_epos_sym @@ -366,7 +367,7 @@ class LocKalman(): ObservationKind.PHONE_ACCEL: np.diag([.5**2, .5**2, .5**2]), ObservationKind.CAMERA_ODO_ROTATION: np.diag([0.05**2, 0.05**2, 0.05**2]), ObservationKind.IMU_FRAME: np.diag([0.05**2, 0.05**2, 0.05**2]), - ObservationKind.NO_ROT: np.diag([0.00025**2, 0.00025**2, 0.00025**2]), + ObservationKind.NO_ROT: np.diag([0.0025**2, 0.0025**2, 0.0025**2]), ObservationKind.ECEF_POS: np.diag([5**2, 5**2, 5**2])} # MSCKF stuff From cf72a4eb34287218f385e75849902755203d55ec Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 10 Jun 2020 17:48:51 -0700 Subject: [PATCH 252/656] don't clear scons cache in CI --- selfdrive/manager.py | 16 ++++++++++------ selfdrive/test/process_replay/camera_replay.py | 1 + 2 files changed, 11 insertions(+), 6 deletions(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index fcf75ff1c9..9c4fbc3d57 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -123,12 +123,16 @@ if not prebuilt: compile_output += r if retry: - print("scons build failed, cleaning in") - for i in range(3, -1, -1): - print("....%d" % i) - time.sleep(1) - subprocess.check_call(["scons", "-c"], cwd=BASEDIR, env=env) - shutil.rmtree("/tmp/scons_cache") + if not os.getenv("CI"): + print("scons build failed, cleaning in") + for i in range(3, -1, -1): + print("....%d" % i) + time.sleep(1) + subprocess.check_call(["scons", "-c"], cwd=BASEDIR, env=env) + shutil.rmtree("/tmp/scons_cache") + else: + print("scons build failed after retry") + sys.exit(1) else: # Build failed log errors errors = [line.decode('utf8', 'replace') for line in compile_output diff --git a/selfdrive/test/process_replay/camera_replay.py b/selfdrive/test/process_replay/camera_replay.py index e2cb8cd9e2..da277dd7cb 100755 --- a/selfdrive/test/process_replay/camera_replay.py +++ b/selfdrive/test/process_replay/camera_replay.py @@ -6,6 +6,7 @@ from typing import Any from tqdm import tqdm from common.android import ANDROID +os.environ['CI'] = "1" if ANDROID: os.environ['QCOM_REPLAY'] = "1" import selfdrive.manager as manager From 1932e2824eabe85cf5df458301a188e24061bec6 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Wed, 10 Jun 2020 18:40:49 -0700 Subject: [PATCH 253/656] Clear build products before NEOS update (#1677) Co-authored-by: Comma Device --- launch_chffrplus.sh | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 2d3fa39d4e..0985f0845e 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -86,6 +86,12 @@ function launch { cp "$DIR/scripts/continue.sh" "/data/data/com.termux/files/continue.sh" fi + if [ ! -f "$BASEDIR/prebuilt" ]; then + echo "Clearing build products and resetting scons state prior to NEOS update" + cd $BASEDIR && scons --clean + rm -rf /tmp/scons_cache + rm -r $BASEDIR/.sconsign.dblite + fi "$DIR/installer/updater/updater" "file://$DIR/installer/updater/update.json" fi From 97b1ee25a7cff52216f5a1e8c5cb2b4b5847eba2 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Wed, 10 Jun 2020 22:47:10 -0500 Subject: [PATCH 254/656] 2016 RX350 F Sport corrections (#1679) This fixes the botched PR I did yesterday... https://github.com/commaai/openpilot/pull/1671 Accidentally used CAR.LEXUS_RXH_TSS2 firmware from my clipboard yesterday, instead of @gweedor#9653's... Today I was extra careful ;-) @gweedor#9653 DongleID 28f8c941d8b28743 --- selfdrive/car/toyota/values.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index ff210b03b2..c52f597077 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -848,28 +848,29 @@ FW_VERSIONS = { }, CAR.LEXUS_RX: { (Ecu.engine, 0x700, None): [ + b'\x01896630E37200\x00\x00\x00\x00', b'\x01896630E41200\x00\x00\x00\x00', - b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152648473\x00\x00\x00\x00\x00\x00', - b'F152648831\x00\x00\x00\x00\x00\x00', + b'F152648492\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ + b'881514810300\x00\x00\x00\x00', b'881514810500\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ + b'8965B0E011\x00\x00\x00\x00\x00\x00', b'8965B0E012\x00\x00\x00\x00\x00\x00', - b'8965B48271\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4701000\x00\x00\x00\x00', b'8821F4701100\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4801200\x00\x00\x00\x00', b'8646F4802001\x00\x00\x00\x00', b'8646F4802100\x00\x00\x00\x00', - b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', ], }, CAR.LEXUS_RXH: { From fab939eebc7fcf67dbbb52f9352ba67c41598746 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 11 Jun 2020 14:38:19 -0700 Subject: [PATCH 255/656] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index b875f970fc..076eb51b17 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit b875f970fc6ddad5befe2f6831f4bcda354d8bea +Subproject commit 076eb51b1726906ce3365b2d3a52bad8622ed558 From f05685992a94cdc0c4f4e5649aa0debfa2ca688c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 11 Jun 2020 16:24:23 -0700 Subject: [PATCH 256/656] update dockerhub token --- .github/workflows/test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index fa1a82b29a..b16e0660b5 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -58,7 +58,7 @@ jobs: run: eval "$BUILD" - name: Push to dockerhub run: | - docker login -u wmelching -p ${{ secrets.DOCKERHUB_TOKEN }} + docker login -u wmelching -p ${{ secrets.COMMA_DOCKERHUB_TOKEN}} docker tag tmppilot docker.io/commaai/openpilot:latest docker push docker.io/commaai/openpilot:latest From 66ae0854b4cdee8dbc763d365c6e10b57237cec7 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 11 Jun 2020 16:37:45 -0700 Subject: [PATCH 257/656] Big batch of FW versions (#1682) * wip big batch of fw versions * Add the rest * And two more --- selfdrive/car/honda/values.py | 187 +++++++++++++- selfdrive/car/hyundai/values.py | 49 +++- selfdrive/car/toyota/values.py | 286 ++++++++++++++++++--- selfdrive/debug/test_fw_query_on_routes.py | 45 +++- 4 files changed, 517 insertions(+), 50 deletions(-) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 2deed083a7..0b2fb4fd32 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -151,8 +151,10 @@ FW_VERSIONS = { (Ecu.programmedFuelInjection, 0x18da10f1, None): [ b'37805-6A0-A640\x00\x00', b'37805-6B2-A550\x00\x00', + b'37805-6B2-A560\x00\x00', b'37805-6B2-A650\x00\x00', b'37805-6B2-A660\x00\x00', + b'37805-6B2-A720\x00\x00', b'37805-6B2-M520\x00\x00', ], (Ecu.shiftByWire, 0x18da0bf1, None): [ @@ -160,14 +162,20 @@ FW_VERSIONS = { ], (Ecu.transmission, 0x18da1ef1, None): [ b'28102-6B8-A560\x00\x00', + b'28102-6B8-A570\x00\x00', + b'28102-6B8-A800\x00\x00', + b'28102-6B8-C570\x00\x00', b'28102-6B8-M520\x00\x00', ], (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ b'46114-TVA-A060\x00\x00', b'46114-TVA-A080\x00\x00', + b'46114-TVA-A120\x00\x00', ], (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TVA-C040\x00\x00', b'57114-TVA-C050\x00\x00', + b'57114-TVA-C060\x00\x00', ], (Ecu.eps, 0x18da30f1, None): [ b'39990-TVA-A150\x00\x00', @@ -184,8 +192,10 @@ FW_VERSIONS = { (Ecu.combinationMeter, 0x18da60f1, None): [ b'78109-TVA-A210\x00\x00', b'78109-TVC-A010\x00\x00', + b'78109-TVC-A020\x00\x00', b'78109-TVC-A110\x00\x00', b'78109-TVC-A210\x00\x00', + b'78109-TVC-C110\x00\x00', b'78109-TVC-M510\x00\x00', ], (Ecu.hud, 0x18da61f1, None): [ @@ -208,15 +218,21 @@ FW_VERSIONS = { CAR.ACCORD_15: { (Ecu.programmedFuelInjection, 0x18da10f1, None): [ b'37805-6A0-9620\x00\x00', + b'37805-6A0-A540\x00\x00', b'37805-6A0-A640\x00\x00', + b'37805-6A0-A650\x00\x00', b'37805-6A0-A740\x00\x00', + b'37805-6A0-A750\x00\x00', b'37805-6A0-A840\x00\x00', b'37805-6A0-A850\x00\x00', + b'37805-6A0-C540\x00\x00', b'37805-6A1-H650\x00\x00', ], (Ecu.transmission, 0x18da1ef1, None): [ b'28101-6A7-A220\x00\x00', + b'28101-6A7-A230\x00\x00', b'28101-6A7-A320\x00\x00', + b'28101-6A7-A330\x00\x00', b'28101-6A7-A510\x00\x00', b'28101-6A9-H140\x00\x00', ], @@ -226,16 +242,19 @@ FW_VERSIONS = { (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ b'46114-TVA-A050\x00\x00', b'46114-TVA-A060\x00\x00', + b'46114-TVA-A080\x00\x00', b'46114-TVA-A120\x00\x00', b'46114-TVE-H550\x00\x00', ], (Ecu.combinationMeter, 0x18da60f1, None): [ b'78109-TVA-A010\x00\x00', + b'78109-TVA-A110\x00\x00', b'78109-TVA-A210\x00\x00', b'78109-TVA-A220\x00\x00', b'78109-TVA-A310\x00\x00', - b'78109-TWA-A210\x00\x00', + b'78109-TVA-C010\x00\x00', b'78109-TVE-H610\x00\x00', + b'78109-TWA-A210\x00\x00', ], (Ecu.hud, 0x18da61f1, None): [ b'78209-TVA-A010\x00\x00', @@ -272,15 +291,19 @@ FW_VERSIONS = { ], (Ecu.vsa, 0x18da28f1, None): [ b'57114-TWA-A040\x00\x00', + b'57114-TWA-A050\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ b'77959-TWA-A440\x00\x00', ], (Ecu.combinationMeter, 0x18da60f1, None): [ b'78109-TWA-A010\x00\x00', + b'78109-TWA-A020\x00\x00', + b'78109-TWA-A110\x00\x00', b'78109-TWA-A120\x00\x00', b'78109-TWA-A210\x00\x00', - b'78109-TWA-A110\x00\x00', + b'78109-TWA-A220\x00\x00', + ], (Ecu.shiftByWire, 0x18da0bf1, None): [ b'54008-TWA-A910\x00\x00', @@ -307,10 +330,20 @@ FW_VERSIONS = { b'37805-5AA-A670\x00\x00', b'37805-5AA-A680\x00\x00', b'37805-5AA-A810\x00\x00', + b'37805-5AA-C680\x00\x00', b'37805-5AA-C820\x00\x00', + b'37805-5AA-L650\x00\x00', b'37805-5AA-L660\x00\x00', + b'37805-5AA-L680\x00\x00', + b'37805-5AA-L690\x00\x00', b'37805-5AJ-A610\x00\x00', + b'37805-5AJ-A620\x00\x00', + b'37805-5BA-A310\x00\x00', b'37805-5BA-A510\x00\x00', + b'37805-5BA-A740\x00\x00', + b'37805-5BA-A760\x00\x00', + b'37805-5BA-A960\x00\x00', + b'37805-5BA-L930\x00\x00', b'37805-5BA-L940\x00\x00', b'37805-5BA-L960\x00\x00', ], @@ -326,6 +359,7 @@ FW_VERSIONS = { b'28101-5DJ-A510\x00\x00', ], (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TBA-A540\x00\x00', b'57114-TBA-A550\x00\x00', b'57114-TBA-A560\x00\x00', b'57114-TBA-A570\x00\x00', @@ -342,20 +376,28 @@ FW_VERSIONS = { b'77959-TBG-A030\x00\x00', ], (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TBA-A510\x00\x00', + b'78109-TBA-A520\x00\x00', + b'78109-TBA-A530\x00\x00', b'78109-TBC-A310\x00\x00', b'78109-TBC-A320\x00\x00', b'78109-TBC-A510\x00\x00', b'78109-TBC-A520\x00\x00', b'78109-TBC-A530\x00\x00', + b'78109-TBC-C510\x00\x00', + b'78109-TBC-C520\x00\x00', b'78109-TBC-C530\x00\x00', b'78109-TBH-A530\x00\x00', b'78109-TEG-A310\x00\x00', ], (Ecu.fwdCamera, 0x18dab0f1, None): [ + b'36161-TBA-A020\x00\x00', b'36161-TBA-A030\x00\x00', + b'36161-TBA-A040\x00\x00', b'36161-TBC-A020\x00\x00', b'36161-TBC-A030\x00\x00', b'36161-TEG-A010\x00\x00', + b'36161-TEG-A020\x00\x00', ], (Ecu.gateway, 0x18daeff1, None): [ b'38897-TBA-A010\x00\x00', @@ -364,7 +406,9 @@ FW_VERSIONS = { }, CAR.CIVIC_BOSCH: { (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-5AA-A940\x00\x00', b'37805-5AA-A950\x00\x00', + b'37805-5AA-L940\x00\x00', b'37805-5AA-L950\x00\x00', b'37805-5AN-A750\x00\x00', b'37805-5AN-A830\x00\x00', @@ -372,18 +416,29 @@ FW_VERSIONS = { b'37805-5AN-A930\x00\x00', b'37805-5AN-A940\x00\x00', b'37805-5AN-A950\x00\x00', + b'37805-5AN-AG20\x00\x00', b'37805-5AN-AH20\x00\x00', + b'37805-5AN-AK20\x00\x00', + b'37805-5AN-AR20\x00\x00', b'37805-5AN-L940\x00\x00', b'37805-5AN-LF20\x00\x00', b'37805-5AN-LH20\x00\x00', b'37805-5AN-LJ20\x00\x00', + b'37805-5AN-LR20\x00\x00', + b'37805-5AN-LS20\x00\x00', b'37805-5AW-G720\x00\x00', b'37805-5AZ-E850\x00\x00', + b'37805-5BB-A630\x00\x00', + b'37805-5BB-A640\x00\x00', + b'37805-5BB-C540\x00\x00', + b'37805-5BB-C630\x00\x00', + b'37805-5BB-L540\x00\x00', b'37805-5BB-L640\x00\x00', - b'37805-5AN-AG20\x00\x00', ], (Ecu.transmission, 0x18da1ef1, None): [ b'28101-5CG-A920\x00\x00', + b'28101-5CG-AB10\x00\x00', + b'28101-5CG-C110\x00\x00', b'28101-5CG-C220\x00\x00', b'28101-5CG-C320\x00\x00', b'28101-5CG-G020\x00\x00', @@ -392,14 +447,19 @@ FW_VERSIONS = { b'28101-5CK-A150\x00\x00', b'28101-5CK-C130\x00\x00', b'28101-5CK-C140\x00\x00', + b'28101-5DJ-A610\x00\x00', b'28101-5DJ-A710\x00\x00', b'28101-5DV-E330\x00\x00', ], (Ecu.vsa, 0x18da28f1, None): [ b'57114-TBG-A340\x00\x00', + b'57114-TBG-A350\x00\x00', b'57114-TGG-A340\x00\x00', - b'57114-TGL-G330\x00\x00', b'57114-TGG-C320\x00\x00', + b'57114-TGG-L320\x00\x00', + b'57114-TGG-L330\x00\x00', + b'57114-TGL-G330\x00\x00', + ], (Ecu.eps, 0x18da30f1, None): [ b'39990-TBA-C020\x00\x00', @@ -414,34 +474,43 @@ FW_VERSIONS = { b'77959-TBA-A060\x00\x00', b'77959-TEA-G020\x00\x00', b'77959-TGG-A020\x00\x00', + b'77959-TGG-A030\x00\x00', b'77959-TGG-G010\x00\x00', ], (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TBA-A110\x00\x00', b'78109-TBA-A910\x00\x00', + b'78109-TBA-C340\x00\x00', + b'78109-TBA-C910\x00\x00', b'78109-TBC-A740\x00\x00', b'78109-TFJ-G020\x00\x00', b'78109-TGG-A210\x00\x00', b'78109-TGG-A220\x00\x00', b'78109-TGG-A310\x00\x00', b'78109-TGG-A320\x00\x00', + b'78109-TGG-A330\x00\x00', + b'78109-TGG-A610\x00\x00', + b'78109-TGG-A620\x00\x00', b'78109-TGG-A810\x00\x00', b'78109-TGG-A820\x00\x00', b'78109-TGL-G120\x00\x00', - b'78109-TGG-A610\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36802-TBA-A150\x00\x00', b'36802-TFJ-G060\x00\x00', b'36802-TGG-A050\x00\x00', - b'36802-TGL-G040\x00\x00', b'36802-TGG-A060\x00\x00', + b'36802-TGG-A130\x00\x00', + b'36802-TGL-G040\x00\x00', ], (Ecu.fwdCamera, 0x18dab5f1, None): [ b'36161-TBA-A130\x00\x00', + b'36161-TBA-A140\x00\x00', b'36161-TFJ-G070\x00\x00', b'36161-TGG-A060\x00\x00', - b'36161-TGL-G050\x00\x00', b'36161-TGG-A080\x00\x00', + b'36161-TGG-A120\x00\x00', + b'36161-TGL-G050\x00\x00', ], (Ecu.gateway, 0x18daeff1, None): [ b'38897-TBA-A110\x00\x00', @@ -460,19 +529,29 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x18dab5f1, None): [b'36161-TFK-G130\x00\x00'], (Ecu.gateway, 0x18daeff1, None): [b'38897-TBA-A020\x00\x00'], }, + CAR.CRV: { + (Ecu.vsa, 0x18da28f1, None): [b'57114-T1W-A230\x00\x00',], + (Ecu.srs, 0x18da53f1, None): [b'77959-T0A-A230\x00\x00',], + (Ecu.combinationMeter, 0x18da60f1, None): [b'78109-T1W-A210\x00\x00',], + (Ecu.fwdRadar, 0x18dab0f1, None): [b'36161-T1W-A830\x00\x00',], + }, CAR.CRV_5G: { (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-5PA-3060\x00\x00', b'37805-5PA-3080\x00\x00', b'37805-5PA-4050\x00\x00', + b'37805-5PA-6520\x00\x00', b'37805-5PA-6530\x00\x00', b'37805-5PA-6630\x00\x00', + b'37805-5PA-9640\x00\x00', + b'37805-5PA-9830\x00\x00', + b'37805-5PA-A650\x00\x00', b'37805-5PA-A670\x00\x00', b'37805-5PA-A680\x00\x00', b'37805-5PA-A850\x00\x00', b'37805-5PA-A870\x00\x00', b'37805-5PA-A880\x00\x00', b'37805-5PA-A890\x00\x00', - b'37805-5PA-9640\x00\x00', b'37805-5PD-Q630\x00\x00', ], (Ecu.transmission, 0x18da1ef1, None): [ @@ -481,9 +560,11 @@ FW_VERSIONS = { b'28101-5RG-A040\x00\x00', b'28101-5RG-A120\x00\x00', b'28101-5RG-A220\x00\x00', + b'28101-5RH-A020\x00\x00', b'28101-5RH-A030\x00\x00', b'28101-5RH-A040\x00\x00', b'28101-5RH-A120\x00\x00', + b'28101-5RH-A220\x00\x00', b'28101-5RL-Q010\x00\x00', ], (Ecu.vsa, 0x18da28f1, None): [ @@ -496,6 +577,7 @@ FW_VERSIONS = { (Ecu.eps, 0x18da30f1, None): [ b'39990-TLA,A040\x00\x00', b'39990-TLA-A040\x00\x00', + b'39990-TLA-A110\x00\x00', b'39990-TLA-A220\x00\x00', b'39990-TMT-T010\x00\x00', ], @@ -512,6 +594,7 @@ FW_VERSIONS = { b'78109-TLA-C210\x00\x00', b'78109-TLB-A110\x00\x00', b'78109-TLB-A210\x00\x00', + b'78109-TLB-A220\x00\x00', b'78109-TMC-Q210\x00\x00', ], (Ecu.gateway, 0x18daeff1, None): [ @@ -552,30 +635,61 @@ FW_VERSIONS = { CAR.CRV_HYBRID: { (Ecu.vsa, 0x18da28f1, None): [ b'57114-TPA-G020\x00\x00', + b'57114-TPG-A020\x00\x00', ], (Ecu.eps, 0x18da30f1, None): [ b'39990-TPA-G030\x00\x00', + b'39990-TPG-A020\x00\x00', ], (Ecu.gateway, 0x18daeff1, None): [ b'38897-TMA-H110\x00\x00', + b'38897-TPG-A110\x00\x00', ], (Ecu.shiftByWire, 0x18da0bf1, None): [ b'54008-TMB-H510\x00\x00', + b'54008-TMB-H610\x00\x00', ], (Ecu.fwdCamera, 0x18dab5f1, None): [ b'36161-TPA-E050\x00\x00', + b'36161-TPG-A030\x00\x00', ], (Ecu.combinationMeter, 0x18da60f1, None): [ b'78109-TPA-G520\x00\x00', + b'78109-TPG-A110\x00\x00', ], (Ecu.hud, 0x18da61f1, None): [ b'78209-TLA-X010\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36802-TPA-E040\x00\x00', + b'36802-TPG-A020\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ b'77959-TLA-G220\x00\x00', + b'77959-TLA-C320\x00\x00', + ], + }, + CAR.FIT: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T5R-L220\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T5R-C020\x00\x00', + b'39990-T5R-C030\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T5A-J010\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-T5A-A420\x00\x00', + b'78109-T5A-A910\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T5R-A240\x00\x00', + b'36161-T5R-A520\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T5R-A230\x00\x00', ], }, CAR.ODYSSEY: { @@ -602,13 +716,16 @@ FW_VERSIONS = { b'36161-THR-A030\x00\x00', b'36161-THR-A110\x00\x00', b'36161-THR-A720\x00\x00', + b'36161-THR-A730\x00\x00', b'36161-THR-A810\x00\x00', + b'36161-THR-A910\x00\x00', b'36161-THR-C010\x00\x00', ], (Ecu.transmission, 0x18da1ef1, None): [ b'28101-5NZ-A310\x00\x00', b'28101-5NZ-C310\x00\x00', b'28102-5MX-A001\x00\x00', + b'28102-5MX-A600\x00\x00', b'28102-5MX-A610\x00\x00', b'28102-5MX-A710\x00\x00', b'28102-5MX-A900\x00\x00', @@ -624,12 +741,16 @@ FW_VERSIONS = { b'78109-THR-A230\x00\x00', b'78109-THR-A430\x00\x00', b'78109-THR-A820\x00\x00', + b'78109-THR-A830\x00\x00', b'78109-THR-AB20\x00\x00', b'78109-THR-AB20\x00\x00', + b'78109-THR-AB30\x00\x00', b'78109-THR-AB40\x00\x00', b'78109-THR-AC40\x00\x00', + b'78109-THR-AE20\x00\x00', b'78109-THR-AE40\x00\x00', b'78109-THR-AL10\x00\x00', + b'78109-THR-AN10\x00\x00', b'78109-THR-C330\x00\x00', b'78109-THR-CE20\x00\x00', ], @@ -637,14 +758,58 @@ FW_VERSIONS = { b'54008-THR-A020\x00\x00', ], }, + CAR.PILOT: { + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TG7-A520\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5EZ-A210\x00\x00', + b'28101-5EZ-A100\x00\x00', + b'28101-5EZ-A060\x00\x00', + b'28101-5EZ-A050\x00\x00', + ], + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-RLV-C910\x00\x00', + b'37805-RLV-C520\x00\x00', + b'37805-RLV-C510\x00\x00', + b'37805-RLV-4070\x00\x00', + b'37805-RLV-A830\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TG7-A040\x00\x00', + b'39990-TG7-A030\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab0f1, None): [ + b'36161-TG7-A520\x00\x00', + b'36161-TG7-A820\x00\x00', + b'36161-TG7-A720\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TG7-A110\x00\x00', + b'77959-TG7-A020\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TG7-A720\x00\x00', + b'78109-TG7-A520\x00\x00', + b'78109-TG7-A420\x00\x00', + b'78109-TG7-A040\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TG7-A140\x00\x00', + b'57114-TG7-A240\x00\x00', + b'57114-TG7-A230\x00\x00', + ], + + }, CAR.PILOT_2019: { (Ecu.eps, 0x18da30f1, None): [ b'39990-TG7-A060\x00\x00', b'39990-TGS-A230\x00\x00', ], (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TG7-A110\x00\x00', b'38897-TG7-A030\x00\x00', + b'38897-TG7-A110\x00\x00', + b'38897-TG7-A210\x00\x00', ], (Ecu.fwdCamera, 0x18dab0f1, None): [ b'36161-TG7-A630\x00\x00', @@ -659,6 +824,8 @@ FW_VERSIONS = { ], (Ecu.combinationMeter, 0x18da60f1, None): [ b'78109-TG7-AJ20\x00\x00', + b'78109-TG7-AK10\x00\x00', + b'78109-TG7-AK20\x00\x00', b'78109-TG7-AP10\x00\x00', b'78109-TG7-AP20\x00\x00', b'78109-TG8-AJ20\x00\x00', @@ -680,6 +847,7 @@ FW_VERSIONS = { b'39990-T6Z-A030\x00\x00', ], (Ecu.fwdCamera, 0x18dab0f1, None): [ + b'36161-T6Z-A020\x00\x00', b'36161-T6Z-A310\x00\x00', b'36161-T6Z-A520\x00\x00', ], @@ -695,6 +863,7 @@ FW_VERSIONS = { b'77959-T6Z-A020\x00\x00', ], (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T6Z-A120\x00\x00', b'57114-T6Z-A130\x00\x00', b'57114-T6Z-A520\x00\x00', ], diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 64b776685a..3e26699704 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -135,12 +135,49 @@ ECU_FINGERPRINT = { FW_VERSIONS = { CAR.SONATA: { - (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 '], - (Ecu.esp, 0x7d1, None): [b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100\xf1\xa01.04'], - (Ecu.engine, 0x7e0, None): [b'\xf1\x87391162M003\xf1\xa0000F'], - (Ecu.eps, 0x7d4, None): [b'\xf1\x8756310L0010\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101\xf1\xa01.01'], - (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016'], - (Ecu.transmission, 0x7e1, None): [b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v'], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', + b'\xf1\x00DN8_ SCC F-CU- 1.00 1.00 99110-L0000 ', + ], + (Ecu.esp, 0x7d1, None): [ + b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100\xf1\xa01.04', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x87391162M003\xf1\xa0000F', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x8756310L0010\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101\xf1\xa01.01', + b'\xf1\x8756310-L0010\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101\xf1\xa01.01', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.00 99211-L0000 190716', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + ], + }, + CAR.SANTA_FE: { + (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 \xf1\xa01.02'], + (Ecu.esp, 0x7d1, None): [b'\xf1\x00TM ESC \x02 100\x18\x030 58910-S2600\xf1\xa01.00',], + (Ecu.engine, 0x7e0, None): [b'\xf1\x81606EA051\x00\x00\x00\x00\x00\x00\x00\x00'], + (Ecu.eps, 0x7d4, None): [b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409'], + (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00TM MFC AT USA LHD 1.00 1.00 99211-S2000 180409'], + (Ecu.transmission, 0x7e1, None): [b'\xf1\x87SBJWAA6562474GG0ffvgeTeFx\x88\x97\x88ww\x87www\x87w\x84o\xfa\xff\x87fO\xff\xc2 \xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS1\x00\x00\x00\x00'], + }, + CAR.KIA_STINGER: { + (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 \xf1\xa01.01'], + (Ecu.engine, 0x7e0, None): [ b'\xf1\x81640E0051\x00\x00\x00\x00\x00\x00\x00\x00',], + (Ecu.eps, 0x7d4, None): [b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104'], + (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822'], + (Ecu.transmission, 0x7e1, None): [b'\xf1\x87VDHLG17118862DK2\x8awWwgu\x96wVfUVwv\x97xWvfvUTGTx\x87o\xff\xc9\xed\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0'], + }, + CAR.KIA_OPTIMA_H: { + (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ',], + (Ecu.engine, 0x7e0, None): [b'\xf1\x816H6F4051\x00\x00\x00\x00\x00\x00\x00\x00',], + (Ecu.eps, 0x7d4, None): [b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109',], + (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424',], + (Ecu.transmission, 0x7e1, None): [b"\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PDE0G16NS2\xf4'\\\x91",], } } diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index c52f597077..a0aeea6ea0 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -274,27 +274,47 @@ IGNORED_FINGERPRINTS = [CAR.RAV4H_TSS2, CAR.HIGHLANDERH_TSS2, CAR.LEXUS_RXH_TSS2 FW_VERSIONS = { CAR.AVALON: { (Ecu.esp, 0x7b0, None): [b'F152607060\x00\x00\x00\x00\x00\x00'], - (Ecu.dsu, 0x791, None): [b'881510705200\x00\x00\x00\x00'], + (Ecu.dsu, 0x791, None): [ + b'881510705200\x00\x00\x00\x00', + b'881510701300\x00\x00\x00\x00', + ], (Ecu.eps, 0x7a1, None): [b'8965B41051\x00\x00\x00\x00\x00\x00'], - (Ecu.engine, 0x7e0, None): [b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00'], - (Ecu.fwdRadar, 0x750, 0xf): [b'8821F4702100\x00\x00\x00\x00'], - (Ecu.fwdCamera, 0x750, 0x6d): [b'8646F0703000\x00\x00\x00\x00'], + (Ecu.engine, 0x7e0, None): [ + b'\x0230721100\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0701100\x00\x00\x00\x00', + b'8646F0703000\x00\x00\x00\x00', + ], }, CAR.CAMRY: { (Ecu.engine, 0x700, None): [ + b'\x018966306L3100\x00\x00\x00\x00', + b'\x018966306L4200\x00\x00\x00\x00', b'\x018966306L5200\x00\x00\x00\x00', + b'\x018966306Q3100\x00\x00\x00\x00', + b'\x018966306Q4000\x00\x00\x00\x00', + b'\x018966306Q4100\x00\x00\x00\x00', + b'\x018966333P3100\x00\x00\x00\x00', + b'\x018966333P3200\x00\x00\x00\x00', b'\x018966333P4200\x00\x00\x00\x00', b'\x018966333P4300\x00\x00\x00\x00', b'\x018966333P4400\x00\x00\x00\x00', b'\x018966333P4500\x00\x00\x00\x00', b'\x018966333P4700\x00\x00\x00\x00', + b'\x018966333Q6000\x00\x00\x00\x00', b'\x018966333Q6200\x00\x00\x00\x00', - b'\x018966306Q4100\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ - b'8821F0607200 ', + b'8821F0601200 ', b'8821F0601300 ', b'8821F0603300 ', + b'8821F0607200 ', b'8821F0608000 ', ], (Ecu.esp, 0x7b0, None): [ @@ -309,6 +329,7 @@ FW_VERSIONS = { b'8965B33580\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ # Same as 0x791 + b'8821F0601200 ', b'8821F0601300 ', b'8821F0603300 ', b'8821F0607200 ', @@ -324,49 +345,94 @@ FW_VERSIONS = { }, CAR.CAMRYH: { (Ecu.engine, 0x700, None): [ + b'\x018966333N4300\x00\x00\x00\x00', + b'\x018966333X0000\x00\x00\x00\x00', b'\x028966306B2100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306B2300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', b'\x028966306N8200\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8400\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', b'\x028966306R5000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R5000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', b'\x028966306R6000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R6000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306S0000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306N8100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306S1100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ + b'F152633214\x00\x00\x00\x00\x00\x00', + b'F152633660\x00\x00\x00\x00\x00\x00', b'F152633712\x00\x00\x00\x00\x00\x00', b'F152633713\x00\x00\x00\x00\x00\x00', b'F152633B51\x00\x00\x00\x00\x00\x00', + b'F152633B60\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'8821F0601200 ', b'8821F0601300 ', + b'8821F0603400 ', + b'8821F0604200 ', + b'8821F0606200 ', b'8821F0607200 ', b'8821F0608000 ', + b'8821F0609000 ', + b'8821F0609100 ', ], (Ecu.eps, 0x7a1, None): [ b'8965B33540\x00\x00\x00\x00\x00\x00', + b'8965B33542\x00\x00\x00\x00\x00\x00', + b'8965B33550\x00\x00\x00\x00\x00\x00', + b'8965B33551\x00\x00\x00\x00\x00\x00', b'8965B33580\x00\x00\x00\x00\x00\x00', + b'8965B33581\x00\x00\x00\x00\x00\x00', + b'8965B33611\x00\x00\x00\x00\x00\x00', + b'8965B33621\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ # Same as 0x791 b'8821F0601200 ', b'8821F0601300 ', + b'8821F0603400 ', + b'8821F0604200 ', + b'8821F0606200 ', b'8821F0607200 ', b'8821F0608000 ', + b'8821F0609000 ', + b'8821F0609100 ', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'8646F0601200 ', b'8646F0601300 ', + b'8646F0601400 ', + b'8646F0603500 ', + b'8646F0604100 ', b'8646F0605000 ', + b'8646F0606000 ', + b'8646F0606100 ', + b'8646F0607000 ', + b'8646F0607100 ', ], }, CAR.CHR: { (Ecu.engine, 0x700, None): [ + b'\x01896631017100\x00\x00\x00\x00', + b'\x01896631017200\x00\x00\x00\x00', b'\x0189663F413100\x00\x00\x00\x00', + b'\x0189663F414100\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ + b'8821F0W01000 ', b'8821FF401600 ', b'8821FF404100 ', + b'8821FF405100 ', + b'8821FF406000 ', ], (Ecu.esp, 0x7b0, None): [ + b'F152610020\x00\x00\x00\x00\x00\x00', + b'F152610153\x00\x00\x00\x00\x00\x00', + b'F1526F4034\x00\x00\x00\x00\x00\x00', + b'F1526F4044\x00\x00\x00\x00\x00\x00', b'F1526F4073\x00\x00\x00\x00\x00\x00', b'F1526F4122\x00\x00\x00\x00\x00\x00', ], @@ -375,24 +441,47 @@ FW_VERSIONS = { b'8965B10040\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ + b'\x033F401100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203102\x00\x00\x00\x00', b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F0W01000 ', b'8821FF401600 ', b'8821FF404100 ', + b'8821FF405100 ', + b'8821FF406000 ', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'8646FF401800 ', b'8646FF404000 ', + b'8646FF406000 ', ], }, CAR.CHRH: { - (Ecu.engine, 0x700, None): [b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00'], - (Ecu.esp, 0x7b0, None): [b'F152610040\x00\x00\x00\x00\x00\x00'], - (Ecu.dsu, 0x791, None): [b'8821FF407100 '], - (Ecu.eps, 0x7a1, None): [b'8965B10050\x00\x00\x00\x00\x00\x00'], - (Ecu.fwdRadar, 0x750, 0xf): [b'8821FF407100 '], - (Ecu.fwdCamera, 0x750, 0x6d): [b'8646FF407000 '], + (Ecu.engine, 0x700, None): [ + b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F423000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + ], + (Ecu.esp, 0x7b0, None): [ + b'F152610040\x00\x00\x00\x00\x00\x00', + b'F152610190\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'8821FF404000 ', + b'8821FF407100 ', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B10040\x00\x00\x00\x00\x00\x00', + b'8965B10050\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821FF404000 ', + b'8821FF407100 ', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646FF404000 ', + b'8646FF407000 ', + ], }, CAR.COROLLA: { (Ecu.engine, 0x7e0, None): [ @@ -434,6 +523,7 @@ FW_VERSIONS = { b'\x01896630ZG5000\x00\x00\x00\x00', b'\x01896630ZG5100\x00\x00\x00\x00', b'\x01896630ZG5200\x00\x00\x00\x00', + b'\x01896630ZG5300\x00\x00\x00\x00', b'\x01896630ZQ5000\x00\x00\x00\x00', b'\x018966312L8000\x00\x00\x00\x00', b'\x018966312P9000\x00\x00\x00\x00', @@ -463,6 +553,7 @@ FW_VERSIONS = { b'\x01F152612641\x00\x00\x00\x00\x00\x00', b'\x01F152612B10\x00\x00\x00\x00\x00\x00', b'\x01F152612B60\x00\x00\x00\x00\x00\x00', + b'\x01F152612B61\x00\x00\x00\x00\x00\x00', b'\x01F152612B90\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ @@ -476,6 +567,7 @@ FW_VERSIONS = { b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F1201200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], }, CAR.COROLLAH_TSS2: { @@ -519,13 +611,19 @@ FW_VERSIONS = { }, CAR.HIGHLANDER: { (Ecu.engine, 0x700, None): [ + b'\x01896630E09000\x00\x00\x00\x00', b'\x01896630E43100\x00\x00\x00\x00', + b'\x01896630E43200\x00\x00\x00\x00', + b'\x01896630E44200\x00\x00\x00\x00', + b'\x01896630E45000\x00\x00\x00\x00', + b'\x01896630E45100\x00\x00\x00\x00', b'\x01896630E45200\x00\x00\x00\x00', + b'\x01896630E74000\x00\x00\x00\x00', + b'\x01896630E76000\x00\x00\x00\x00', b'\x01896630E83000\x00\x00\x00\x00', b'\x01896630E84000\x00\x00\x00\x00', b'\x01896630E85000\x00\x00\x00\x00', b'\x01896630E88000\x00\x00\x00\x00', - b'\x01896630E09000\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B48140\x00\x00\x00\x00\x00\x00', @@ -547,23 +645,70 @@ FW_VERSIONS = { ], }, CAR.HIGHLANDERH: { - (Ecu.eps, 0x7a1, None): [b'8965B48160\x00\x00\x00\x00\x00\x00'], - (Ecu.esp, 0x7b0, None): [b'F152648541\x00\x00\x00\x00\x00\x00'], - (Ecu.engine, 0x7e0, None): [b'\x0230E40000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00'], - (Ecu.fwdRadar, 0x750, 0xf): [b'8821F4702100\x00\x00\x00\x00'], - (Ecu.fwdCamera, 0x750, 0x6d): [b'8646F0E01200\x00\x00\x00\x00'], + (Ecu.eps, 0x7a1, None): [ + b'8965B48160\x00\x00\x00\x00\x00\x00' + ], + (Ecu.esp, 0x7b0, None): [ + b'F152648541\x00\x00\x00\x00\x00\x00', + b'F152648542\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0230E40000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230EA2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0E01200\x00\x00\x00\x00', + b'8646F0E01300\x00\x00\x00\x00', + ], + }, + CAR.HIGHLANDER_TSS2: { + (Ecu.eps, 0x7a1, None): [ + b'8965B48241\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x7b0, None): [ + b'\x01F15260E051\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896630E64100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + ], }, CAR.HIGHLANDERH_TSS2: { - (Ecu.eps, 0x7a1, None): [b'8965B48241\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [b'\x01F15264872300\x00\x00\x00\x00', ], - (Ecu.engine, 0x700, None): [b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', ], - (Ecu.fwdRadar, 0x750, 0xf): [b'\x018821F3301400\x00\x00\x00\x00', ], - (Ecu.fwdCamera, 0x750, 0x6d): [b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', ], + (Ecu.eps, 0x7a1, None): [ + b'8965B48241\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x7b0, None): [ + b'\x01F15264872300\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + ], }, CAR.LEXUS_IS: { - (Ecu.engine, 0x700, None): [b'\x018966353Q2300\x00\x00\x00\x00'], + (Ecu.engine, 0x700, None): [ + b'\x018966353M7100\x00\x00\x00\x00', + b'\x018966353Q2300\x00\x00\x00\x00', + ], (Ecu.esp, 0x7b0, None): [b'F152653330\x00\x00\x00\x00\x00\x00'], - (Ecu.dsu, 0x791, None): [b'881515306400\x00\x00\x00\x00'], + (Ecu.dsu, 0x791, None): [ + b'881515306400\x00\x00\x00\x00', + b'881515306500\x00\x00\x00\x00', + ], (Ecu.eps, 0x7a1, None): [b'8965B53271\x00\x00\x00\x00\x00\x00'], (Ecu.fwdRadar, 0x750, 0xf): [b'8821F4702300\x00\x00\x00\x00'], (Ecu.fwdCamera, 0x750, 0x6d): [b'8646F5301400\x00\x00\x00\x00'], @@ -572,7 +717,9 @@ FW_VERSIONS = { (Ecu.engine, 0x700, None): [ b'\x02896634761000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896634761100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634761200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896634763000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634765000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896634769100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896634774000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896634774100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', @@ -580,17 +727,22 @@ FW_VERSIONS = { b'\x02896634782000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896634784000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347A5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x028966347A8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x03896634759100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701002\x00\x00\x00\x00', + b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', b'\x03896634760100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634760300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703001\x00\x00\x00\x00', b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', b'\x03896634768100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', + b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', b'\x03896634789000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707001\x00\x00\x00\x00', @@ -605,24 +757,26 @@ FW_VERSIONS = { ], (Ecu.esp, 0x7b0, None): [ b'F152647290\x00\x00\x00\x00\x00\x00', + b'F152647300\x00\x00\x00\x00\x00\x00', b'F152647310\x00\x00\x00\x00\x00\x00', b'F152647414\x00\x00\x00\x00\x00\x00', b'F152647415\x00\x00\x00\x00\x00\x00', b'F152647416\x00\x00\x00\x00\x00\x00', b'F152647417\x00\x00\x00\x00\x00\x00', + b'F152647470\x00\x00\x00\x00\x00\x00', b'F152647490\x00\x00\x00\x00\x00\x00', b'F152647684\x00\x00\x00\x00\x00\x00', b'F152647862\x00\x00\x00\x00\x00\x00', b'F152647863\x00\x00\x00\x00\x00\x00', b'F152647864\x00\x00\x00\x00\x00\x00', b'F152647865\x00\x00\x00\x00\x00\x00', - b'F152647470\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'881514702300\x00\x00\x00\x00', b'881514703100\x00\x00\x00\x00', b'881514704100\x00\x00\x00\x00', b'881514706000\x00\x00\x00\x00', + b'881514706100\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F4702000\x00\x00\x00\x00', @@ -643,13 +797,17 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\x02342Q1000\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02342Q1100\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q1200\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02342Q1300\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02342Q2000\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02342Q2100\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q2200\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q4000\x00\x00\x00\x00\x00\x00\x00\x0054215000\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B42082\x00\x00\x00\x00\x00\x00', b'8965B42083\x00\x00\x00\x00\x00\x00', + b'8965B42063\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F15260R102\x00\x00\x00\x00\x00\x00', @@ -658,6 +816,7 @@ FW_VERSIONS = { b'F152642492\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ + b'881514201200\x00\x00\x00\x00', b'881514201300\x00\x00\x00\x00', b'881514201400\x00\x00\x00\x00', ], @@ -691,6 +850,7 @@ FW_VERSIONS = { ], (Ecu.dsu, 0x791, None): [ b'881514202200\x00\x00\x00\x00', + b'881514202300\x00\x00\x00\x00', b'881514202400\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ @@ -708,18 +868,22 @@ FW_VERSIONS = { }, CAR.RAV4_TSS2: { (Ecu.engine, 0x700, None): [ + b'\x01896630R58000\x00\x00\x00\x00', b'\x018966342E2000\x00\x00\x00\x00', b'\x018966342M8000\x00\x00\x00\x00', b'\x018966342T1000\x00\x00\x00\x00', b'\x018966342T6000\x00\x00\x00\x00', + b'\x018966342T9000\x00\x00\x00\x00', + b'\x018966342U4000\x00\x00\x00\x00', b'\x018966342V3100\x00\x00\x00\x00', b'\x018966342X5000\x00\x00\x00\x00', b'\x01896634A05000\x00\x00\x00\x00', b'\x01896634A19000\x00\x00\x00\x00', + b'\x01896634A19100\x00\x00\x00\x00', + b'\x01896634A20000\x00\x00\x00\x00', b'\x01896634A22000\x00\x00\x00\x00', - b'\x018966342U4000\x00\x00\x00\x00', - b'\x018966342T9000\x00\x00\x00\x00', b'\x01F152642551\x00\x00\x00\x00\x00\x00', + b'\x028966342T0000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', b'\x028966342Y8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', b'\x02896634A18000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', ], @@ -727,8 +891,10 @@ FW_VERSIONS = { b'F152642520\x00\x00\x00\x00\x00\x00', b'\x01F15260R210\x00\x00\x00\x00\x00\x00', b'\x01F15260R220\x00\x00\x00\x00\x00\x00', + b'\x01F15260R300\x00\x00\x00\x00\x00\x00', b'\x01F152642551\x00\x00\x00\x00\x00\x00', b'\x01F152642561\x00\x00\x00\x00\x00\x00', + b'\x01F152642700\x00\x00\x00\x00\x00\x00', b'\x01F152642710\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ @@ -747,6 +913,7 @@ FW_VERSIONS = { b'\x028646F4203300\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F4203500\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], }, CAR.RAV4H_TSS2: { @@ -801,14 +968,18 @@ FW_VERSIONS = { CAR.SIENNA: { (Ecu.engine, 0x700, None): [ b'\x01896630832100\x00\x00\x00\x00', + b'\x01896630838000\x00\x00\x00\x00', + b'\x01896630838100\x00\x00\x00\x00', b'\x01896630842000\x00\x00\x00\x00', + b'\x01896630851000\x00\x00\x00\x00', b'\x01896630851100\x00\x00\x00\x00', - b'\x01896630860000\x00\x00\x00\x00', b'\x01896630852100\x00\x00\x00\x00', b'\x01896630859000\x00\x00\x00\x00', + b'\x01896630860000\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B45070\x00\x00\x00\x00\x00\x00', + b'8965B45082\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152608130\x00\x00\x00\x00\x00\x00', @@ -818,6 +989,7 @@ FW_VERSIONS = { ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F4702100\x00\x00\x00\x00', + b'8821F4702200\x00\x00\x00\x00', b'8821F4702300\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ @@ -846,12 +1018,34 @@ FW_VERSIONS = { b'\x028646F3304100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', ], }, + CAR.LEXUS_NXH: { + (Ecu.engine, 0x7e0, None): [ + b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x7b0, None): [ + b'F152678160\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881517804300\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B78100\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F7801300\x00\x00\x00\x00', + ], + }, CAR.LEXUS_RX: { (Ecu.engine, 0x700, None): [ b'\x01896630E37200\x00\x00\x00\x00', + b'\x01896630E41000\x00\x00\x00\x00', b'\x01896630E41200\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ + b'F152648472\x00\x00\x00\x00\x00\x00', b'F152648473\x00\x00\x00\x00\x00\x00', b'F152648492\x00\x00\x00\x00\x00\x00', ], @@ -868,6 +1062,7 @@ FW_VERSIONS = { b'8821F4701100\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4801100\x00\x00\x00\x00', b'8646F4801200\x00\x00\x00\x00', b'8646F4802001\x00\x00\x00\x00', b'8646F4802100\x00\x00\x00\x00', @@ -875,17 +1070,22 @@ FW_VERSIONS = { }, CAR.LEXUS_RXH: { (Ecu.engine, 0x7e0, None): [ + b'\x02348N0000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02348Q4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02348T1100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348V6000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02348Z3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ + b'F152648361\x00\x00\x00\x00\x00\x00', b'F152648501\x00\x00\x00\x00\x00\x00', + b'F152648502\x00\x00\x00\x00\x00\x00', + b'F152648504\x00\x00\x00\x00\x00\x00', b'F152648A30\x00\x00\x00\x00\x00\x00', - b'F152648361\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'881514811300\x00\x00\x00\x00', + b'881514811500\x00\x00\x00\x00', b'881514811700\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ @@ -895,14 +1095,36 @@ FW_VERSIONS = { ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F4701000\x00\x00\x00\x00', + b'8821F4701100\x00\x00\x00\x00', + b'8821F4701200\x00\x00\x00\x00', b'8821F4701300\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'8646F4801200\x00\x00\x00\x00', + b'8646F4802100\x00\x00\x00\x00', b'8646F4802200\x00\x00\x00\x00', b'8646F4809000\x00\x00\x00\x00', ], }, + CAR.LEXUS_RX_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x01896630EB0000\x00\x00\x00\x00', + b'\x01896630EA9000\x00\x00\x00\x00', + ], + (Ecu.esp, 0x7b0, None): [ + b'\x01F15260E031\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B48271\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + ], + }, CAR.LEXUS_RXH_TSS2: { (Ecu.engine, 0x7e0, None): [ b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index 0cba85a480..6ca5436e9c 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -1,6 +1,7 @@ #!/usr/bin/env python3 # type: ignore +from collections import defaultdict import argparse import os import traceback @@ -9,9 +10,11 @@ from tools.lib.logreader import LogReader from selfdrive.car.fw_versions import match_fw_to_car from selfdrive.car.toyota.values import FW_VERSIONS as TOYOTA_FW_VERSIONS from selfdrive.car.honda.values import FW_VERSIONS as HONDA_FW_VERSIONS +from selfdrive.car.hyundai.values import FW_VERSIONS as HYUNDAI_FW_VERSIONS from selfdrive.car.toyota.values import FINGERPRINTS as TOYOTA_FINGERPRINTS from selfdrive.car.honda.values import FINGERPRINTS as HONDA_FINGERPRINTS +from selfdrive.car.hyundai.values import FINGERPRINTS as HYUNDAI_FINGERPRINTS if __name__ == "__main__": @@ -25,6 +28,8 @@ if __name__ == "__main__": else: routes = [args.route] + mismatches = defaultdict(list) + wrong = 0 good = 0 @@ -47,6 +52,8 @@ if __name__ == "__main__": break elif msg.which() == "carParams": + bts = msg.carParams.as_builder().to_bytes() + car_fw = msg.carParams.carFw if len(car_fw) == 0: break @@ -57,7 +64,7 @@ if __name__ == "__main__": if args.car is not None: live_fingerprint = args.car - if live_fingerprint not in list(TOYOTA_FINGERPRINTS.keys()) + list(HONDA_FINGERPRINTS.keys()): + if live_fingerprint not in list(TOYOTA_FINGERPRINTS.keys()) + list(HONDA_FINGERPRINTS.keys()) + list(HYUNDAI_FINGERPRINTS.keys()): continue candidates = match_fw_to_car(car_fw) @@ -75,9 +82,10 @@ if __name__ == "__main__": print(f" (Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}],") print("Mismatches") - for car_fws in [TOYOTA_FW_VERSIONS, HONDA_FW_VERSIONS]: + found = False + for car_fws in [TOYOTA_FW_VERSIONS, HONDA_FW_VERSIONS, HYUNDAI_FW_VERSIONS]: if live_fingerprint in car_fws: - + found = True expected = car_fws[live_fingerprint] for (_, expected_addr, expected_sub_addr), v in expected.items(): for version in car_fw: @@ -88,11 +96,42 @@ if __name__ == "__main__": if version.fwVersion not in v: print(f"({hex(addr)}, {'None' if sub_addr is None else hex(sub_addr)}) - {version.fwVersion}") + # Add to global list of mismatches + mismatch = (addr, sub_addr, version.fwVersion) + if mismatch not in mismatches[live_fingerprint]: + mismatches[live_fingerprint].append(mismatch) + + # No FW versions for this car yet, add them all to mismatch list + if not found: + for version in car_fw: + sub_addr = None if version.subAddress == 0 else version.subAddress + addr = version.address + mismatch = (addr, sub_addr, version.fwVersion) + if mismatch not in mismatches[live_fingerprint]: + mismatches[live_fingerprint].append(mismatch) + print() wrong += 1 break except Exception: traceback.print_exc() + except KeyboardInterrupt: + break print(f"Fingerprinted: {good} - Not fingerprinted: {wrong}") print(f"Number of dongle ids checked: {len(dongles)}") + print() + + # Print FW versions that need to be added seperated out by car and address + for car, m in mismatches.items(): + print(car) + addrs = defaultdict(list) + for (addr, sub_addr, version) in m: + addrs[(addr, sub_addr)].append(version) + + for (addr, sub_addr), versions in addrs.items(): + print(f" ({hex(addr)}, {'None' if sub_addr is None else hex(sub_addr)}): [") + for v in versions: + print(f" {v},") + print(" ]") + print() From 5230b071d25a31bf3c313282b578b846b5d92cbe Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 11 Jun 2020 16:43:18 -0700 Subject: [PATCH 258/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 70e39040b4..74c607f79a 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 70e39040b48601cb8de571b81cf4ac88b918bae2 +Subproject commit 74c607f79acd2baace27265f763480af75496dac From b678449707ae69b593f0f9b3f8600c7efa3c040a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 12 Jun 2020 09:06:47 +0800 Subject: [PATCH 259/656] use malloc (#1674) --- selfdrive/common/util.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/common/util.c b/selfdrive/common/util.c index dce6e8ac67..3728dabcd0 100644 --- a/selfdrive/common/util.c +++ b/selfdrive/common/util.c @@ -20,9 +20,9 @@ void* read_file(const char* path, size_t* out_len) { long f_len = ftell(f); rewind(f); - // calloc one extra byte so the file will always be NULL terminated + // malloc one extra byte so the file will always be NULL terminated // cl_cached_program_from_file relies on this - char* buf = (char*)calloc(f_len+1, 1); + char* buf = (char*)malloc(f_len+1); assert(buf); size_t num_read = fread(buf, f_len, 1, f); @@ -33,6 +33,7 @@ void* read_file(const char* path, size_t* out_len) { return NULL; } + buf[f_len] = '\0'; if (out_len) { *out_len = f_len; } From 15faf1791455fd9b4199ae1b6bf1289b08b8e340 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 11 Jun 2020 18:19:40 -0700 Subject: [PATCH 260/656] Add Palisade fw versions --- selfdrive/car/hyundai/values.py | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 3e26699704..14bff6625e 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -178,6 +178,14 @@ FW_VERSIONS = { (Ecu.eps, 0x7d4, None): [b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109',], (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424',], (Ecu.transmission, 0x7e1, None): [b"\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PDE0G16NS2\xf4'\\\x91",], + }, + CAR.PALISADE: { + (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 \xf1\xa01.04',], + (Ecu.esp, 0x7d1, None): [b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330',], + (Ecu.engine, 0x7e0, None): [b'\xf1\x81640J0051\x00\x00\x00\x00\x00\x00\x00\x00',], + (Ecu.eps, 0x7d4, None): [b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103',], + (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125',], + (Ecu.transmission, 0x7e1, None): [b'\xf1\x87LDKVBN424201KF26\xba\xaa\x9a\xa9\x99\x99\x89\x98\x89\x99\xa8\x99\x88\x99\x98\x89\x88\x99\xa8\x89v\x7f\xf7\xffwf_\xffq\xa6\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7',], } } From 344a9a369983f58fe1e71f84478ded5c766e0d1b Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Thu, 11 Jun 2020 18:21:59 -0700 Subject: [PATCH 261/656] Fixups for Mac, and a bunch for PC (#1654) * fix mac nui * fix cereal * builds on mac without warnings * ui swap shouldn't be instant on pc * camerad builds on mac * modeld, and now everything, builds on mac * ui draws pictures on mac now * fix camerad shutdown * support ui looping on pc * python3 on that * SCNu64 should be cross platform * bump cereal and new apk * clean up Co-authored-by: Adeeb Shihadeh --- SConstruct | 13 ++++---- apk/ai.comma.plus.offroad.apk | 4 +-- cereal | 2 +- selfdrive/camerad/SConscript | 4 +++ .../camerad/cameras/camera_frame_stream.cc | 14 ++------ selfdrive/camerad/main.cc | 32 +++++++------------ selfdrive/common/ipc.c | 8 +++++ selfdrive/common/util.h | 1 + selfdrive/common/visionbuf_cl.c | 6 ++++ selfdrive/common/visionipc.c | 4 +-- selfdrive/modeld/SConscript | 9 ++++++ selfdrive/modeld/models/commonmodel.h | 4 +++ selfdrive/proclogd/proclogd.cc | 16 +++++----- selfdrive/ui/linux.cc | 2 +- selfdrive/ui/paint.cc | 7 ++-- selfdrive/ui/ui.cc | 17 ++++++++-- tools/nui/get_files_comma_api.py | 1 + tools/nui/nui | 17 +++++++--- tools/replay/camera.py | 2 +- 19 files changed, 100 insertions(+), 63 deletions(-) mode change 100644 => 100755 tools/nui/get_files_comma_api.py diff --git a/SConstruct b/SConstruct index 6d80f6e521..28f0be2e12 100644 --- a/SConstruct +++ b/SConstruct @@ -62,6 +62,9 @@ if arch == "aarch64" or arch == "larch64": cxxflags += ["-DQCOM_REPLAY"] else: + cflags = [] + cxxflags = [] + lenv = { "PATH": "#external/bin:" + os.environ['PATH'], } @@ -77,6 +80,8 @@ else: "/usr/local/lib", "/System/Library/Frameworks/OpenGL.framework/Libraries", ] + cflags.append("-DGL_SILENCE_DEPRECATION") + cxxflags.append("-DGL_SILENCE_DEPRECATION") else: libpath = [ "#phonelibs/snpe/x86_64-linux-clang", @@ -96,9 +101,6 @@ else: # allows shared libraries to work globally rpath = [os.path.join(os.getcwd(), x) for x in rpath] - cflags = [] - cxxflags = [] - ccflags_asan = ["-fsanitize=address", "-fno-omit-frame-pointer"] if GetOption('asan') else [] ldflags_asan = ["-fsanitize=address"] if GetOption('asan') else [] @@ -215,9 +217,8 @@ SConscript(['common/kalman/SConscript']) SConscript(['common/transformations/SConscript']) SConscript(['phonelibs/SConscript']) -if arch != "Darwin": - SConscript(['selfdrive/camerad/SConscript']) - SConscript(['selfdrive/modeld/SConscript']) +SConscript(['selfdrive/camerad/SConscript']) +SConscript(['selfdrive/modeld/SConscript']) SConscript(['selfdrive/controls/lib/cluster/SConscript']) SConscript(['selfdrive/controls/lib/lateral_mpc/SConscript']) diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk index bf72f55619..f633a75123 100644 --- a/apk/ai.comma.plus.offroad.apk +++ b/apk/ai.comma.plus.offroad.apk @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:fbfb2e9870d4833819542833d62ce934b5ad284b30d727604188fd2a3676f0e6 -size 13699659 +oid sha256:3b29d0ce5a60f77f46a3124724b4d19095205bb7d0a9fc64d58685aa94cf81b1 +size 13700367 diff --git a/cereal b/cereal index 68fdf28670..9915b2086a 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 68fdf28670b48a16a60498b4e5cc1984e7e66651 +Subproject commit 9915b2086a4205d9a28eead6139d5d7cbb73b00b diff --git a/selfdrive/camerad/SConscript b/selfdrive/camerad/SConscript index eeb3bcb931..1b205198c6 100644 --- a/selfdrive/camerad/SConscript +++ b/selfdrive/camerad/SConscript @@ -22,6 +22,10 @@ else: else: libs += [] cameras = ['cameras/camera_frame_stream.cc'] + if arch == "Darwin": + del libs[libs.index('OpenCL')] + env = env.Clone() + env['FRAMEWORKS'] = ['OpenCL'] env.SharedLibrary('snapshot/visionipc', ["#selfdrive/common/visionipc.c", "#selfdrive/common/ipc.c"]) diff --git a/selfdrive/camerad/cameras/camera_frame_stream.cc b/selfdrive/camerad/cameras/camera_frame_stream.cc index 0a77eb1187..cea6272b4a 100644 --- a/selfdrive/camerad/cameras/camera_frame_stream.cc +++ b/selfdrive/camerad/cameras/camera_frame_stream.cc @@ -70,18 +70,8 @@ void run_frame_stream(DualCameraState *s) { cl_command_queue q = rear_camera->camera_bufs[buf_idx].copy_q; cl_mem yuv_cl = rear_camera->camera_bufs[buf_idx].buf_cl; - cl_event map_event; - void *yuv_buf = (void *)clEnqueueMapBuffer(q, yuv_cl, CL_TRUE, - CL_MAP_WRITE, 0, frame.getImage().size(), - 0, NULL, &map_event, &err); - assert(err == 0); - clWaitForEvents(1, &map_event); - clReleaseEvent(map_event); - memcpy(yuv_buf, frame.getImage().begin(), frame.getImage().size()); - - clEnqueueUnmapMemObject(q, yuv_cl, yuv_buf, 0, NULL, &map_event); - clWaitForEvents(1, &map_event); - clReleaseEvent(map_event); + + clEnqueueWriteBuffer(q, yuv_cl, CL_TRUE, 0, frame.getImage().size(), frame.getImage().begin(), 0, NULL, NULL); tbuffer_dispatch(tb, buf_idx); } } diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index b1c6684675..2178a0c611 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -15,6 +15,7 @@ #include "common/util.h" #include "common/swaglog.h" +#include "common/ipc.h" #include "common/visionipc.h" #include "common/visionbuf.h" #include "common/visionimg.h" @@ -346,8 +347,12 @@ void* processing_thread(void *arg) { LOG("setpriority returns %d", err); // init cl stuff +#ifdef __APPLE__ + cl_command_queue q = clCreateCommandQueue(s->context, s->device_id, 0, &err); +#else const cl_queue_properties props[] = {0}; //CL_QUEUE_PRIORITY_KHR, CL_QUEUE_PRIORITY_HIGH_KHR, 0}; cl_command_queue q = clCreateCommandQueueWithProperties(s->context, s->device_id, props, &err); +#endif assert(err == 0); // init the net @@ -542,7 +547,7 @@ void* processing_thread(void *arg) { // one thumbnail per 5 seconds (instead of %5 == 0 posenet) if (cnt % 100 == 3) { uint8_t* thumbnail_buffer = NULL; - uint64_t thumbnail_len = 0; + unsigned long thumbnail_len = 0; unsigned char *row = (unsigned char *)malloc(s->rgb_width/4*3); @@ -852,21 +857,7 @@ void* visionserver_thread(void* arg) { assert(terminate); void* terminate_raw = zsock_resolve(terminate); - unlink(VIPC_SOCKET_PATH); - - int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); - struct sockaddr_un addr = { - .sun_family = AF_UNIX, - .sun_path = VIPC_SOCKET_PATH, - }; - err = bind(sock, (struct sockaddr *)&addr, sizeof(addr)); - assert(err == 0); - - err = listen(sock, 3); - assert(err == 0); - - // printf("waiting\n"); - + int sock = ipc_bind(VIPC_SOCKET_PATH); while (!do_exit) { zmq_pollitem_t polls[2] = {{0}}; polls[0].socket = terminate_raw; @@ -1134,9 +1125,10 @@ void init_buffers(VisionState *s) { 3); s->krnl_rgb_laplacian = clCreateKernel(s->prg_rgb_laplacian, "rgb2gray_conv2d", &err); assert(err == 0); - s->rgb_conv_roi_cl = clCreateBuffer(s->context, CL_MEM_READ_WRITE | CL_MEM_SVM_FINE_GRAIN_BUFFER, + // TODO: Removed CL_MEM_SVM_FINE_GRAIN_BUFFER, confirm it doesn't matter + s->rgb_conv_roi_cl = clCreateBuffer(s->context, CL_MEM_READ_WRITE, s->rgb_width/NUM_SEGMENTS_X * s->rgb_height/NUM_SEGMENTS_Y * 3 * sizeof(uint8_t), NULL, NULL); - s->rgb_conv_result_cl = clCreateBuffer(s->context, CL_MEM_READ_WRITE | CL_MEM_SVM_FINE_GRAIN_BUFFER, + s->rgb_conv_result_cl = clCreateBuffer(s->context, CL_MEM_READ_WRITE, s->rgb_width/NUM_SEGMENTS_X * s->rgb_height/NUM_SEGMENTS_Y * sizeof(int16_t), NULL, NULL); s->rgb_conv_filter_cl = clCreateBuffer(s->context, CL_MEM_READ_ONLY | CL_MEM_COPY_HOST_PTR, 9 * sizeof(int16_t), (void*)&lapl_conv_krnl, NULL); @@ -1194,7 +1186,7 @@ void party(VisionState *s) { processing_thread, s); assert(err == 0); -#ifndef QCOM2 +#if !defined(QCOM2) && !defined(__APPLE__) // TODO: fix front camera on qcom2 pthread_t frontview_thread_handle; err = pthread_create(&frontview_thread_handle, NULL, @@ -1215,7 +1207,7 @@ void party(VisionState *s) { zsock_signal(s->terminate_pub, 0); -#if !defined(QCOM2) && !defined(QCOM_REPLAY) +#if !defined(QCOM2) && !defined(QCOM_REPLAY) && !defined(__APPLE__) LOG("joining frontview_thread"); err = pthread_join(frontview_thread_handle, NULL); assert(err == 0); diff --git a/selfdrive/common/ipc.c b/selfdrive/common/ipc.c index 41b0cc0eaa..28a30d1a10 100644 --- a/selfdrive/common/ipc.c +++ b/selfdrive/common/ipc.c @@ -15,7 +15,11 @@ int ipc_connect(const char* socket_path) { int err; +#ifdef __APPLE__ + int sock = socket(AF_UNIX, SOCK_STREAM, 0); +#else int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); +#endif if (sock < 0) return -1; struct sockaddr_un addr = { .sun_family = AF_UNIX, @@ -35,7 +39,11 @@ int ipc_bind(const char* socket_path) { unlink(socket_path); +#ifdef __APPLE__ + int sock = socket(AF_UNIX, SOCK_STREAM, 0); +#else int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); +#endif struct sockaddr_un addr = { .sun_family = AF_UNIX, }; diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h index 4b0e29aada..a9052146c7 100644 --- a/selfdrive/common/util.h +++ b/selfdrive/common/util.h @@ -29,6 +29,7 @@ typedef void (*sighandler_t)(int sig); #define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0])) +#undef ALIGN #define ALIGN(x, align) (((x) + (align)-1) & ~((align)-1)) #ifdef __cplusplus diff --git a/selfdrive/common/visionbuf_cl.c b/selfdrive/common/visionbuf_cl.c index 5e94649811..c68950baa8 100644 --- a/selfdrive/common/visionbuf_cl.c +++ b/selfdrive/common/visionbuf_cl.c @@ -18,11 +18,17 @@ int offset = 0; void *malloc_with_fd(size_t len, int *fd) { char full_path[0x100]; +#ifdef __APPLE__ + snprintf(full_path, sizeof(full_path)-1, "/tmp/visionbuf_%d_%d", getpid(), offset++); +#else snprintf(full_path, sizeof(full_path)-1, "/dev/shm/visionbuf_%d_%d", getpid(), offset++); +#endif *fd = open(full_path, O_RDWR | O_CREAT, 0777); + assert(*fd >= 0); unlink(full_path); ftruncate(*fd, len); void *addr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, *fd, 0); + assert(addr != MAP_FAILED); return addr; } diff --git a/selfdrive/common/visionipc.c b/selfdrive/common/visionipc.c index a9c4e8a133..bae05ccc77 100644 --- a/selfdrive/common/visionipc.c +++ b/selfdrive/common/visionipc.c @@ -35,7 +35,7 @@ int vipc_recv(int fd, VisionPacket *out_p) { p2.d = p.d; *out_p = p2; } - //printf("%d = vipc_recv(%d, %d): %d %d %d %u\n", ret, fd, p2.num_fds, out_p->d.stream_bufs.type, out_p->d.stream_bufs.width, out_p->d.stream_bufs.height, out_p->d.stream_bufs.buf_len); + //printf("%d = vipc_recv(%d, %d): %d %d %d %zu\n", ret, fd, p2.num_fds, out_p->d.stream_bufs.type, out_p->d.stream_bufs.width, out_p->d.stream_bufs.height, out_p->d.stream_bufs.buf_len); return ret; } @@ -47,7 +47,7 @@ int vipc_send(int fd, const VisionPacket *p2) { .d = p2->d, }; int ret = ipc_sendrecv_with_fds(true, fd, (void*)&p, sizeof(p), (int*)p2->fds, p2->num_fds, NULL); - //printf("%d = vipc_send(%d, %d): %d %d %d %u\n", ret, fd, p2->num_fds, p2->d.stream_bufs.type, p2->d.stream_bufs.width, p2->d.stream_bufs.height, p2->d.stream_bufs.buf_len); + //printf("%d = vipc_send(%d, %d): %d %d %d %zu\n", ret, fd, p2->num_fds, p2->d.stream_bufs.type, p2->d.stream_bufs.width, p2->d.stream_bufs.height, p2->d.stream_bufs.buf_len); return ret; } diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 1bf1d345de..c97500e7d1 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -27,6 +27,15 @@ else: # tell runners to use it lenv['CFLAGS'].append("-DUSE_TF_MODEL") lenv['CXXFLAGS'].append("-DUSE_TF_MODEL") + if arch == "Darwin": + # fix OpenCL + del libs[libs.index('OpenCL')] + lenv['FRAMEWORKS'] = ['OpenCL'] + + # no SNPE on Mac + del libs[libs.index('SNPE')] + del libs[libs.index('symphony-cpu')] + del common_src[common_src.index('runners/snpemodel.cc')] common = lenv.Object(common_src) diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h index 0a03d281ad..bb52366481 100644 --- a/selfdrive/modeld/models/commonmodel.h +++ b/selfdrive/modeld/models/commonmodel.h @@ -2,7 +2,11 @@ #define COMMONMODEL_H #define CL_USE_DEPRECATED_OPENCL_1_2_APIS +#ifdef __APPLE__ +#include +#else #include +#endif #include "common/mat.h" #include "transforms/transform.h" diff --git a/selfdrive/proclogd/proclogd.cc b/selfdrive/proclogd/proclogd.cc index 878ebc499e..7c77c12ceb 100644 --- a/selfdrive/proclogd/proclogd.cc +++ b/selfdrive/proclogd/proclogd.cc @@ -99,14 +99,14 @@ int main() { uint64_t mem_cached = 0, mem_active = 0, mem_inactive = 0, mem_shared = 0; while (std::getline(smem, mem_line)) { - if (util::starts_with(mem_line, "MemTotal:")) sscanf(mem_line.data(), "MemTotal: %lu kB", &mem_total); - else if (util::starts_with(mem_line, "MemFree:")) sscanf(mem_line.data(), "MemFree: %lu kB", &mem_free); - else if (util::starts_with(mem_line, "MemAvailable:")) sscanf(mem_line.data(), "MemAvailable: %lu kB", &mem_available); - else if (util::starts_with(mem_line, "Buffers:")) sscanf(mem_line.data(), "Buffers: %lu kB", &mem_buffers); - else if (util::starts_with(mem_line, "Cached:")) sscanf(mem_line.data(), "Cached: %lu kB", &mem_cached); - else if (util::starts_with(mem_line, "Active:")) sscanf(mem_line.data(), "Active: %lu kB", &mem_active); - else if (util::starts_with(mem_line, "Inactive:")) sscanf(mem_line.data(), "Inactive: %lu kB", &mem_inactive); - else if (util::starts_with(mem_line, "Shmem:")) sscanf(mem_line.data(), "Shmem: %lu kB", &mem_shared); + if (util::starts_with(mem_line, "MemTotal:")) sscanf(mem_line.data(), "MemTotal: %" SCNu64 " kB", &mem_total); + else if (util::starts_with(mem_line, "MemFree:")) sscanf(mem_line.data(), "MemFree: %" SCNu64 " kB", &mem_free); + else if (util::starts_with(mem_line, "MemAvailable:")) sscanf(mem_line.data(), "MemAvailable: %" SCNu64 " kB", &mem_available); + else if (util::starts_with(mem_line, "Buffers:")) sscanf(mem_line.data(), "Buffers: %" SCNu64 " kB", &mem_buffers); + else if (util::starts_with(mem_line, "Cached:")) sscanf(mem_line.data(), "Cached: %" SCNu64 " kB", &mem_cached); + else if (util::starts_with(mem_line, "Active:")) sscanf(mem_line.data(), "Active: %" SCNu64 " kB", &mem_active); + else if (util::starts_with(mem_line, "Inactive:")) sscanf(mem_line.data(), "Inactive: %" SCNu64 " kB", &mem_inactive); + else if (util::starts_with(mem_line, "Shmem:")) sscanf(mem_line.data(), "Shmem: %" SCNu64 " kB", &mem_shared); } mem.setTotal(mem_total * 1024); diff --git a/selfdrive/ui/linux.cc b/selfdrive/ui/linux.cc index e5bb672b48..17a3938f75 100644 --- a/selfdrive/ui/linux.cc +++ b/selfdrive/ui/linux.cc @@ -43,7 +43,7 @@ FramebufferState* framebuffer_init( } glfwMakeContextCurrent(window); - glfwSwapInterval(0); + glfwSwapInterval(1); // clear screen glClearColor(0.2f, 0.2f, 0.2f, 1.0f); diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 71e26b657e..24f4a9d4af 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -269,6 +269,7 @@ static void draw_frame(UIState *s) { glBindTexture(GL_TEXTURE_2D, s->frame_texs[s->cur_vision_idx]); #ifndef QCOM // TODO: a better way to do this? + //printf("%d\n", ((int*)s->priv_hnds[s->cur_vision_idx])[0]); glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, 1164, 874, 0, GL_RGB, GL_UNSIGNED_BYTE, s->priv_hnds[s->cur_vision_idx]); #endif } @@ -807,10 +808,10 @@ static const char frame_fragment_shader[] = "#version 150 core\n" "precision mediump float;\n" "uniform sampler2D uTexture;\n" - "out vec4 vTexCoord;\n" - "out vec4 outColor;\n" + "in vec4 vTexCoord;\n" + "out vec4 colorOut;\n" "void main() {\n" - " outColor = texture(uTexture, vTexCoord.xy);\n" + " colorOut = texture(uTexture, vTexCoord.xy);\n" "}\n"; #else static const char frame_vertex_shader[] = diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 65cbb35cba..88e3328645 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -406,7 +406,7 @@ void handle_message(UIState *s, SubMaster &sm) { s->preview_started = data.getIsPreview(); } - s->started = scene.thermal.getStarted() || s->preview_started ; + s->started = scene.thermal.getStarted() || s->preview_started; // Handle onroad/offroad transition if (!s->started) { if (s->status != STATUS_STOPPED) { @@ -415,6 +415,13 @@ void handle_message(UIState *s, SubMaster &sm) { s->vision_seen = false; s->controls_seen = false; s->active_app = cereal::UiLayoutState::App::HOME; + + #ifndef QCOM + // disconnect from visionipc on PC + close(s->ipc_fd); + s->ipc_fd = -1; + #endif + update_offroad_layout_state(s); } } else if (s->status == STATUS_STOPPED) { @@ -514,8 +521,14 @@ static void ui_update(UIState *s) { zmq_pollitem_t polls[1] = {{0}}; // Take an rgb image from visiond if there is one + assert(s->ipc_fd >= 0); while(true) { - assert(s->ipc_fd >= 0); + if (s->ipc_fd < 0) { + // TODO: rethink this, for now it should only trigger on PC + LOGW("vision disconnected by other thread"); + s->vision_connected = false; + return; + } polls[0].fd = s->ipc_fd; polls[0].events = ZMQ_POLLIN; #ifdef UI_60FPS diff --git a/tools/nui/get_files_comma_api.py b/tools/nui/get_files_comma_api.py old mode 100644 new mode 100755 index 515f0efd86..b350e8488e --- a/tools/nui/get_files_comma_api.py +++ b/tools/nui/get_files_comma_api.py @@ -1,3 +1,4 @@ +#!/usr/bin/env python3 import json import sys diff --git a/tools/nui/nui b/tools/nui/nui index 5214802156..7c77df9559 100755 --- a/tools/nui/nui +++ b/tools/nui/nui @@ -1,11 +1,18 @@ -#!/bin/sh +#!/bin/bash -e if [ $# -gt 0 ]; then - if [ "$INTERNAL" = 1 ]; then - ./_nui "$1" + if [ "$INTERNAL" = 1 ]; then + ./_nui "$1" + else + ./get_files_comma_api.py $1 + if [ -f ./_nui ]; then + ./_nui use_api + elif [ -f _nui.app/Contents/MacOS/_nui ]; then + ./_nui.app/Contents/MacOS/_nui use_api else - python get_files_comma_api.py $1 && ./_nui use_api + echo "nui not found, please build it" fi + fi else - echo "Please Enter a Route" + echo "Please Enter a Route" fi diff --git a/tools/replay/camera.py b/tools/replay/camera.py index ad6db041d2..8a552785eb 100755 --- a/tools/replay/camera.py +++ b/tools/replay/camera.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import os from common.basedir import BASEDIR From 6810333075694c9c72d3c689f05462f6e6565e88 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 10:57:30 -0700 Subject: [PATCH 262/656] Sim hw type is grey panda now --- tools/sim/bridge.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index 9ffdc8c827..88ab3f9742 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -60,7 +60,7 @@ def health_function(): dat.valid = True dat.health = { 'ignitionLine': True, - 'hwType': "whitePanda", + 'hwType': "greyPanda", 'controlsAllowed': True } pm.send('health', dat) From b19098dbf8d95835d23cd9c93d779a6523e03d28 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 11:48:14 -0700 Subject: [PATCH 263/656] remove pycocotools --- Pipfile | 1 - Pipfile.lock | 403 ++++++++++++++++++++++++++------------------------- 2 files changed, 203 insertions(+), 201 deletions(-) diff --git a/Pipfile b/Pipfile index 5fb643ad85..fa4309ef0c 100644 --- a/Pipfile +++ b/Pipfile @@ -19,7 +19,6 @@ control = "*" datadog = "*" dlib = "*" elasticsearch = "*" -pycocotools = {git = "https://github.com/cocodataset/cocoapi.git",subdirectory = "PythonAPI"} gunicorn = "*" "h5py" = "*" hexdump = "*" diff --git a/Pipfile.lock b/Pipfile.lock index e297d667e1..44b8466036 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "ebed80be69f5b38143ddf30e96b8d7f6d3214a4296088276e01795f15ad6e1c2" + "sha256": "96924e487a9d20b4fb06eea1e6536816a157a9606051da58741c66fa6630371a" }, "pipfile-spec": 6, "requires": { @@ -18,11 +18,11 @@ "default": { "astroid": { "hashes": [ - "sha256:4c17cea3e592c21b6e222f673868961bad77e1f985cb1694ed077475a89229c1", - "sha256:d8506842a3faf734b81599c8b98dcc423de863adcc1999248480b18bd31a0f38" + "sha256:2f4078c2a41bf377eea06d71c9d2ba4eb8f6b1af2135bec27bbbb7d8f12bb703", + "sha256:bc58d83eb610252fd8de6363e39d4f1d0619c894b0ed24603b881c02e64c7386" ], "markers": "python_version >= '3.5'", - "version": "==2.4.1" + "version": "==2.4.2" }, "atomicwrites": { "hashes": [ @@ -34,10 +34,10 @@ }, "certifi": { "hashes": [ - "sha256:1d987a998c75633c40847cc966fcf5904906c920a7f17ef374f5aa4282abd304", - "sha256:51fcb31174be6e6664c5f69e3e1691a2d72a1a12e90f872cbdb1567eb47b6519" + "sha256:5ad7e9a056d25ffa5082862e36f119f7f7cec6457fa07ee2f8c339814b80c9b1", + "sha256:9cd41137dc19af6a5e03b630eefe7d1f458d964d406342dd3edf625839b944cc" ], - "version": "==2020.4.5.1" + "version": "==2020.4.5.2" }, "cffi": { "hashes": [ @@ -132,42 +132,50 @@ }, "cython": { "hashes": [ - "sha256:00348a2675b53282535aa22c4d444076b08010aa47f4bf10622542c213c37452", - "sha256:0fa549d45e8aa658e270a7e85a0e7b8bf7b3dfdc59fcd4f4dbf54d854f4abdb5", - "sha256:111941da36709f53170af6b0f81ec3df883364ff02d20f742e815b27ea37dfa0", - "sha256:22b7c38d3f1af1bc7906b1a7b42354b4cf47d36bbdf687a581a050e72ddd249b", - "sha256:29960b4c2789a9d6024be5fff75a55e52ae7f32d265fe52c0e40414f20d4d6db", - "sha256:32ae95d3c3fe4dbb5d3f430accdc93247e2204791f4f70a5f2a8fac2d3105524", - "sha256:381f8570ab287670c14f8138591788c1a801b185899939d08f4c60c284b4940d", - "sha256:44d9acf4dd75d66b456c21d2ee0bcea3b49065775aa955a11be62a64fc5210ec", - "sha256:4b971daa8c05c3277c4c7be4be5e7cd2e4971377ca752563c55a1c1f88d819c8", - "sha256:58598e9a35cb89916c2fd80c0b2f4b7443542281f804206e90eae7f9acb79b81", - "sha256:61bff7ae850986ebdf8b7fb01c63be94e75ba73f2dcbc9338ca687ff810488b8", - "sha256:69ae45714b1fd5ebb309d787c278b5316cb504b287dae95456ccf50d8c55f537", - "sha256:7a1ebe4f811ce0c1642d432ef8ae9bea1db93c7215eb1e95eb4bcb7503a42107", - "sha256:8418a201c229f8af7eae11b3d22df699a37cfe934a113e032d59369a13a7ef13", - "sha256:97f98a7dc0d58ea833dc1f8f8b3ce07adf4c0f030d1886c5399a2135ed415258", - "sha256:9fde858f57952c9e55fae20cffeaf0bd5554a0630f0bd537879e57e60d8f105f", - "sha256:ad5abd7ee54f48be7efa95f4ad0d7df44a84970d57330b151a049642ffc1705b", - "sha256:b31f3dc2931b84c99d0038013304986cd690f5debb8471dbba1ca8584601b230", - "sha256:c50fa9238c37b43d17234c8083371f4d4da208153d13f86d9db8925c16bb2850", - "sha256:cd262da047a60f0d90fa83d6416e901519a5de6d4d68218d62dcb15f12fdcb1b", - "sha256:e7838dadab758a7caa4f726e523930d491dbc4f93c4a01d9de6828f342ea1188", - "sha256:edf5b76f6fff07f236510bb578b6ba6387e534af9ecdbe7892c591dbe1ea3314", - "sha256:ee9a913482dfc5a62242ea66abff93f3dbe28729bce590014c8445e39af3d95c", - "sha256:f4bb0e06a463cc280562cc54e53fefb2bf14b0b8d00c042781c71f17e78b1847", - "sha256:ffd24c9bd35127138215f56ad833db1966cdc47ac659a31bde96949018e477c2" - ], - "index": "pypi", - "version": "==0.29.19" + "sha256:0754ec9d45518d0dbb5da72db2c8b063d40c4c51779618c68431054de179387f", + "sha256:0bb201124f67b8d5e6a3e7c02257ca56a90204611971ecca76c02897096f097d", + "sha256:0f3488bf2a9e049d1907d35ad8834f542f8c03d858d1bca6d0cbc06b719163e0", + "sha256:1024714b0f7829b0f712db9cebec92c2782b1f42409b8575cacc340aa438d4ba", + "sha256:10b6d2e2125169158128b7f11dad8bb0d8f5fba031d5d4f8492f3afbd06491d7", + "sha256:16ed0260d031d90dda43997e9b0f0eebc3cf18e6ece91cad7b0fb17cd4bfb29b", + "sha256:22d91af5fc2253f717a1b80b8bb45acb655f643611983fd6f782b9423f8171c7", + "sha256:2d84e8d2a0c698c1bce7c2a4677f9f03b076e9f0af7095947ecd2a900ffceea5", + "sha256:34dd57f5ac5a0e3d53da964994fc1b7e7ee3f86172d7a1f0bde8a1f90739e04d", + "sha256:384582b5024007dfdabc9753e3e0f85d61837b0103b0ee3f8acf04a4bcfad175", + "sha256:4473f169d6dd02174eb76396cb38ce469f377c08b21965ddf4f88bbbebd5816e", + "sha256:57f32d1095ad7fad1e7f2ff6e8c6a7197fa532c8e6f4d044ff69212e0bf05461", + "sha256:5dfe519e400a1672a3ac5bdfb5e957a9c14c52caafb01f4a923998ec9ae77736", + "sha256:60def282839ed81a2ffae29d2df0a6777fd74478c6e82c6c3f4b54e698b9d11c", + "sha256:7089fb2be9a9869b9aa277bc6de401928954ce70e139c3cf9b244ae5f490b8f2", + "sha256:714b8926a84e3e39c5278e43fb8823598db82a4b015cff263b786dc609a5e7d6", + "sha256:7352b88f2213325c1e111561496a7d53b0326e7f07e6f81f9b8b21420e40851c", + "sha256:809f0a3f647052c4bcbc34a15f53a5dab90de1a83ebd77add37ed5d3e6ee5d97", + "sha256:8598b09f7973ccb15c03b21d3185dc129ae7c60d0a6caf8176b7099a4b83483e", + "sha256:8dc68f93b257718ea0e2bc9be8e3c61d70b6e49ab82391125ba0112a30a21025", + "sha256:9bfd42c1d40aa26bf76186cba0d89be66ba47e36fa7ea56d71f377585a53f7c4", + "sha256:a21cb3423acd6dbf383c9e41e8e60c93741987950434c85145864458d30099f3", + "sha256:a49d0f5c55ad0f4aacad32f058a71d0701cb8936d6883803e50698fa04cac8d2", + "sha256:a985a7e3c7f1663af398938029659a4381cfe9d1bd982cf19c46b01453e81775", + "sha256:b3233341c3fe352b1090168bd087686880b582b635d707b2c8f5d4f1cc1fa533", + "sha256:b32965445b8dbdc36c69fba47e024060f9b39b1b4ceb816da5028eea01924505", + "sha256:b553473c31297e4ca77fbaea2eb2329889d898c03941d90941679247c17e38fb", + "sha256:b56c02f14f1708411d95679962b742a1235d33a23535ce4a7f75425447701245", + "sha256:b7bb0d54ff453c7516d323c3c78b211719f39a506652b79b7e85ba447d5fa9e7", + "sha256:c5df2c42d4066cda175cd4d075225501e1842cfdbdaeeb388eb7685c367cc3ce", + "sha256:c5e29333c9e20df384645902bed7a67a287b979da1886c8f10f88e57b69e0f4b", + "sha256:d0b445def03b4cd33bd2d1ae6fbbe252b6d1ef7077b3b5ba3f2c698a190d26e5", + "sha256:d490a54814b69d814b157ac86ada98c15fd77fabafc23732818ed9b9f1f0af80" + ], + "index": "pypi", + "version": "==0.29.20" }, "flake8": { "hashes": [ - "sha256:c69ac1668e434d37a2d2880b3ca9aafd54b3a10a3ac1ab101d22f29e29cf8634", - "sha256:ccaa799ef9893cebe69fdfefed76865aeaefbb94cb8545617b2298786a4de9a5" + "sha256:15e351d19611c887e482fb960eae4d44845013cc142d42896e9862f775d8cf5c", + "sha256:f04b9fcbac03b0a3e58c0ab3a0ecc462e023a9faf046d57794184028123aa208" ], "index": "pypi", - "version": "==3.8.2" + "version": "==3.8.3" }, "flask": { "hashes": [ @@ -334,30 +342,30 @@ }, "numpy": { "hashes": [ - "sha256:00d7b54c025601e28f468953d065b9b121ddca7fff30bed7be082d3656dd798d", - "sha256:02ec9582808c4e48be4e93cd629c855e644882faf704bc2bd6bbf58c08a2a897", - "sha256:0e6f72f7bb08f2f350ed4408bb7acdc0daba637e73bce9f5ea2b207039f3af88", - "sha256:1be2e96314a66f5f1ce7764274327fd4fb9da58584eaff00b5a5221edefee7d6", - "sha256:2466fbcf23711ebc5daa61d28ced319a6159b260a18839993d871096d66b93f7", - "sha256:2b573fcf6f9863ce746e4ad00ac18a948978bb3781cffa4305134d31801f3e26", - "sha256:3f0dae97e1126f529ebb66f3c63514a0f72a177b90d56e4bce8a0b5def34627a", - "sha256:50fb72bcbc2cf11e066579cb53c4ca8ac0227abb512b6cbc1faa02d1595a2a5d", - "sha256:57aea170fb23b1fd54fa537359d90d383d9bf5937ee54ae8045a723caa5e0961", - "sha256:709c2999b6bd36cdaf85cf888d8512da7433529f14a3689d6e37ab5242e7add5", - "sha256:7d59f21e43bbfd9a10953a7e26b35b6849d888fc5a331fa84a2d9c37bd9fe2a2", - "sha256:904b513ab8fbcbdb062bed1ce2f794ab20208a1b01ce9bd90776c6c7e7257032", - "sha256:96dd36f5cdde152fd6977d1bbc0f0561bccffecfde63cd397c8e6033eb66baba", - "sha256:9933b81fecbe935e6a7dc89cbd2b99fea1bf362f2790daf9422a7bb1dc3c3085", - "sha256:bbcc85aaf4cd84ba057decaead058f43191cc0e30d6bc5d44fe336dc3d3f4509", - "sha256:dccd380d8e025c867ddcb2f84b439722cf1f23f3a319381eac45fd077dee7170", - "sha256:e22cd0f72fc931d6abc69dc7764484ee20c6a60b0d0fee9ce0426029b1c1bdae", - "sha256:ed722aefb0ebffd10b32e67f48e8ac4c5c4cf5d3a785024fdf0e9eb17529cd9d", - "sha256:efb7ac5572c9a57159cf92c508aad9f856f1cb8e8302d7fdb99061dbe52d712c", - "sha256:efdba339fffb0e80fcc19524e4fdbda2e2b5772ea46720c44eaac28096d60720", - "sha256:f22273dd6a403ed870207b853a856ff6327d5cbce7a835dfa0645b3fc00273ec" - ], - "index": "pypi", - "version": "==1.18.4" + "sha256:0172304e7d8d40e9e49553901903dc5f5a49a703363ed756796f5808a06fc233", + "sha256:34e96e9dae65c4839bd80012023aadd6ee2ccb73ce7fdf3074c62f301e63120b", + "sha256:3676abe3d621fc467c4c1469ee11e395c82b2d6b5463a9454e37fe9da07cd0d7", + "sha256:3dd6823d3e04b5f223e3e265b4a1eae15f104f4366edd409e5a5e413a98f911f", + "sha256:4064f53d4cce69e9ac613256dc2162e56f20a4e2d2086b1956dd2fcf77b7fac5", + "sha256:4674f7d27a6c1c52a4d1aa5f0881f1eff840d2206989bae6acb1c7668c02ebfb", + "sha256:7d42ab8cedd175b5ebcb39b5208b25ba104842489ed59fbb29356f671ac93583", + "sha256:965df25449305092b23d5145b9bdaeb0149b6e41a77a7d728b1644b3c99277c1", + "sha256:9c9d6531bc1886454f44aa8f809268bc481295cf9740827254f53c30104f074a", + "sha256:a78e438db8ec26d5d9d0e584b27ef25c7afa5a182d1bf4d05e313d2d6d515271", + "sha256:a7acefddf994af1aeba05bbbafe4ba983a187079f125146dc5859e6d817df824", + "sha256:a87f59508c2b7ceb8631c20630118cc546f1f815e034193dc72390db038a5cb3", + "sha256:ac792b385d81151bae2a5a8adb2b88261ceb4976dbfaaad9ce3a200e036753dc", + "sha256:b03b2c0badeb606d1232e5f78852c102c0a7989d3a534b3129e7856a52f3d161", + "sha256:b39321f1a74d1f9183bf1638a745b4fd6fe80efbb1f6b32b932a588b4bc7695f", + "sha256:cae14a01a159b1ed91a324722d746523ec757357260c6804d11d6147a9e53e3f", + "sha256:cd49930af1d1e49a812d987c2620ee63965b619257bd76eaaa95870ca08837cf", + "sha256:e15b382603c58f24265c9c931c9a45eebf44fe2e6b4eaedbb0d025ab3255228b", + "sha256:e91d31b34fc7c2c8f756b4e902f901f856ae53a93399368d9a0dc7be17ed2ca0", + "sha256:ef627986941b5edd1ed74ba89ca43196ed197f1a206a3f18cc9faf2fb84fd675", + "sha256:f718a7949d1c4f622ff548c572e0c03440b49b9531ff00e4ed5738b459f011e8" + ], + "index": "pypi", + "version": "==1.18.5" }, "pillow": { "hashes": [ @@ -482,11 +490,11 @@ }, "pylint": { "hashes": [ - "sha256:b95e31850f3af163c2283ed40432f053acbc8fc6eba6a069cb518d9dbf71848c", - "sha256:dd506acce0427e9e08fb87274bcaa953d38b50a58207170dbf5b36cf3e16957b" + "sha256:7dd78437f2d8d019717dbf287772d0b2dbdfd13fc016aa7faa08d67bccc46adc", + "sha256:d0ece7d223fe422088b0e8f13fa0a1e8eb745ebffcb8ed53d3e95394b6101a1c" ], "index": "pypi", - "version": "==2.5.2" + "version": "==2.5.3" }, "pyserial": { "hashes": [ @@ -619,11 +627,11 @@ }, "tqdm": { "hashes": [ - "sha256:4733c4a10d0f2a4d098d801464bdaf5240c7dadd2a7fde4ee93b0a0efd9fb25e", - "sha256:acdafb20f51637ca3954150d0405ff1a7edde0ff19e38fb99a80a66210d2a28f" + "sha256:07c06493f1403c1380b630ae3dcbe5ae62abcf369a93bbc052502279f189ab8c", + "sha256:cd140979c2bebd2311dfb14781d8f19bd5a9debb92dcab9f6ef899c987fcf71f" ], "index": "pypi", - "version": "==4.46.0" + "version": "==4.46.1" }, "urllib3": { "hashes": [ @@ -672,10 +680,10 @@ }, "adal": { "hashes": [ - "sha256:2ae7e02cea4552349fed6d8c9912da400f7e643fc30098defe0dcd01945e7c54", - "sha256:a74ff45b88db18d3d3d0c50d0d2d6d411866648f457bef4be714ba0b8e30d515" + "sha256:7a15d22b1ee7ce1be92441199958748982feba6b7dec35fbf60f9b607bad1bc0", + "sha256:b332316f54d947f39acd9628e7d61d90f6e54d413d6f97025a51482c96bac6bc" ], - "version": "==1.2.3" + "version": "==1.2.4" }, "aenum": { "hashes": [ @@ -727,11 +735,11 @@ }, "astroid": { "hashes": [ - "sha256:4c17cea3e592c21b6e222f673868961bad77e1f985cb1694ed077475a89229c1", - "sha256:d8506842a3faf734b81599c8b98dcc423de863adcc1999248480b18bd31a0f38" + "sha256:2f4078c2a41bf377eea06d71c9d2ba4eb8f6b1af2135bec27bbbb7d8f12bb703", + "sha256:bc58d83eb610252fd8de6363e39d4f1d0619c894b0ed24603b881c02e64c7386" ], "markers": "python_version >= '3.5'", - "version": "==2.4.1" + "version": "==2.4.2" }, "astunparse": { "hashes": [ @@ -758,11 +766,11 @@ }, "azure-cli-core": { "hashes": [ - "sha256:191a4c0ab4e606d61891c05b017fba68e90586f27f65aa45d35b9a99fe37132d", - "sha256:c1fb19abc52b1de7441e6fefbda924cba4ef663e80b713d6f9bc27e7478bb41f" + "sha256:28f89203a61441916b442d423767e23d06b662d50ed19a850492ccaf992e4ef5", + "sha256:a9ff22a09fc5f546750d0735123320ff9841cfb1e1e36cdcb56005effe61cd4e" ], "index": "pypi", - "version": "==2.6.0" + "version": "==2.7.0" }, "azure-cli-nspkg": { "hashes": [ @@ -790,11 +798,11 @@ }, "azure-core": { "hashes": [ - "sha256:2b7613b37ff6503312e5ec7c9ce2efab8fa0dbfe4c6c1d3bf91bab51db9bd6dc", - "sha256:afa6a6ae577859392e1ed3acb024bf5bddeb1bbb67f3191c35c587505ff431a0" + "sha256:7bf695b017acea3da28e0390a2dea5b7e15a9fa3ef1af50ff020bcfe7dacb6a4", + "sha256:d10b74e783cff90d56360e61162afdd22276d62dc9467e657ae866449eae7648" ], "index": "pypi", - "version": "==1.5.0" + "version": "==1.6.0" }, "azure-mgmt-core": { "hashes": [ @@ -845,10 +853,10 @@ }, "backcall": { "hashes": [ - "sha256:38ecd85be2c1e78f77fd91700c76e14667dc21e2713b63876c0eb901196e01e4", - "sha256:bbbf4b1e5cd2bdb08f915895b51081c041bac22394fdfcfdfbe9f14b77c08bf2" + "sha256:5cbdbf27be5e7cfadb448baf0aa95508f91f2bbc6c6437cd9cd06e2a4c215e1e", + "sha256:fbbce6a29f263178a1f7915c1940bde0ec2b2a967566fe1c65c1dfb7422bd255" ], - "version": "==0.1.0" + "version": "==0.2.0" }, "backports.lzma": { "hashes": [ @@ -899,18 +907,18 @@ }, "boto3": { "hashes": [ - "sha256:1bdab4f87ff39d5aab59b0aae69965bf604fa5608984c673877f4c62c1f16240", - "sha256:2b4924ccc1603d562969b9f3c8c74ff4a1f3bdbafe857c990422c73d8e2e229e" + "sha256:aa8370f4ba58ffc1d68960fe42689dd716e8159f27f6b86b2211c130d19f9724", + "sha256:acaabe139ac605cfd4bf22f5edc15dbdcad20a020284d168421ab37df21a6319" ], "index": "pypi", - "version": "==1.13.18" + "version": "==1.14.1" }, "botocore": { "hashes": [ - "sha256:93574cf95a64c71d35c12c93a23f6214cf2f4b461be3bda3a436381cbe126a84", - "sha256:e65eb27cae262a510e335bc0c0e286e9e42381b1da0aafaa79fa13c1d8d74a95" + "sha256:7d829b162e550b201ea07600862fccbbdc028cf88a111338f964e424b0e1c562", + "sha256:db21cc82f1d6e76aec91d8801e17fa701019805268914b2d0d538a2344fba74a" ], - "version": "==1.16.18" + "version": "==1.17.1" }, "cachetools": { "hashes": [ @@ -922,10 +930,10 @@ }, "certifi": { "hashes": [ - "sha256:1d987a998c75633c40847cc966fcf5904906c920a7f17ef374f5aa4282abd304", - "sha256:51fcb31174be6e6664c5f69e3e1691a2d72a1a12e90f872cbdb1567eb47b6519" + "sha256:5ad7e9a056d25ffa5082862e36f119f7f7cec6457fa07ee2f8c339814b80c9b1", + "sha256:9cd41137dc19af6a5e03b630eefe7d1f458d964d406342dd3edf625839b944cc" ], - "version": "==2020.4.5.1" + "version": "==2020.4.5.2" }, "cffi": { "hashes": [ @@ -1107,10 +1115,10 @@ }, "dlib": { "hashes": [ - "sha256:d0eeaca07bc4c75973ad0f739a541d8fa4003af778f0dc1c2c595d470823819a" + "sha256:a3f5070df590c3f510dde2f4c84b1b20e3ef64a02932ed657da490834ecac7e4" ], "index": "pypi", - "version": "==19.19.0" + "version": "==19.20.0" }, "docutils": { "hashes": [ @@ -1214,11 +1222,11 @@ }, "geoalchemy2": { "hashes": [ - "sha256:4385da5e24d01ee9d2af8ef0179994745d2a39931a84df04e74ebdb9a49c0c41", - "sha256:a5a2444d90ce7f2c6b2d7bd7346c8aed16fd32c3e190e631576a51814e8f7ee9" + "sha256:3b83654db15ed807a7bdb2e7dd1c787a47cfc3e4fb92a0558685001fbb7342da", + "sha256:d9336f17df3e7a10f94d1ea2488dcfb97a8bc23fe7f5edea425ddab553534b0a" ], "index": "pypi", - "version": "==0.8.3" + "version": "==0.8.4" }, "git-pylint-commit-hook": { "hashes": [ @@ -1229,11 +1237,11 @@ }, "google-auth": { "hashes": [ - "sha256:1b3732b121917124adfe602de148ef5cba351792cf9527f99e6b61b84f74a7f5", - "sha256:7a9119c4ed518e4ea596cc896e6c567b923b57db40be70e5aec990055aea85d3" + "sha256:1c96c33ad94a492cf21016ac69285d7409d7d046b5cda0a46793e1323a97d657", + "sha256:846feb49ccdd86f74f86fc01f5d679c0b7256af1680fc985db26021b037fbc4e" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.16.0" + "version": "==1.17.1" }, "google-auth-oauthlib": { "hashes": [ @@ -1346,11 +1354,11 @@ }, "identify": { "hashes": [ - "sha256:be66b9673d59336acd18a3a0e0c10d35b8a780309561edf16c46b6b74b83f6af", - "sha256:ef6fa3d125c27516f8d1aaa2038c3263d741e8723825eb38350cdc0288ab35eb" + "sha256:249ebc7e2066d6393d27c1b1be3b70433f824a120b1d8274d362f1eb419e3b52", + "sha256:781fd3401f5d2b17b22a8b18b493a48d5d948e3330634e82742e23f9c20234ef" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.4.17" + "version": "==1.4.19" }, "idna": { "hashes": [ @@ -1378,11 +1386,11 @@ }, "ipython": { "hashes": [ - "sha256:5b241b84bbf0eb085d43ae9d46adf38a13b45929ca7774a740990c2c242534bb", - "sha256:f0126781d0f959da852fb3089e170ed807388e986a8dd4e6ac44855845b0fb1c" + "sha256:0ef1433879816a960cd3ae1ae1dc82c64732ca75cec8dab5a4e29783fb571d0e", + "sha256:1b85d65632211bf5d3e6f1406f3393c8c429a47d7b947b9a87812aa5bce6595c" ], "index": "pypi", - "version": "==7.14.0" + "version": "==7.15.0" }, "ipython-genutils": { "hashes": [ @@ -1704,10 +1712,10 @@ }, "msrest": { "hashes": [ - "sha256:f52f880a2145c075f436083ee9a274ddc54c62181e4c41c9ac11520fbae547e5", - "sha256:f54a60084969656faa2755bfa5f614951b07a870e97dfc8f0b0b8ea94a63b5b5" + "sha256:214c5be98954cb45feb6a6a858a7ae6d41a664e80294b65db225bbaa33d9ca3c", + "sha256:88b31e937eba95bda5b9a910b28498fdc130718bb5f8dd98a6af0d333670c897" ], - "version": "==0.6.14" + "version": "==0.6.16" }, "msrestazure": { "hashes": [ @@ -1741,23 +1749,23 @@ }, "mypy": { "hashes": [ - "sha256:15b948e1302682e3682f11f50208b726a246ab4e6c1b39f9264a8796bb416aa2", - "sha256:219a3116ecd015f8dca7b5d2c366c973509dfb9a8fc97ef044a36e3da66144a1", - "sha256:3b1fc683fb204c6b4403a1ef23f0b1fac8e4477091585e0c8c54cbdf7d7bb164", - "sha256:3beff56b453b6ef94ecb2996bea101a08f1f8a9771d3cbf4988a61e4d9973761", - "sha256:7687f6455ec3ed7649d1ae574136835a4272b65b3ddcf01ab8704ac65616c5ce", - "sha256:7ec45a70d40ede1ec7ad7f95b3c94c9cf4c186a32f6bacb1795b60abd2f9ef27", - "sha256:86c857510a9b7c3104cf4cde1568f4921762c8f9842e987bc03ed4f160925754", - "sha256:8a627507ef9b307b46a1fea9513d5c98680ba09591253082b4c48697ba05a4ae", - "sha256:8dfb69fbf9f3aeed18afffb15e319ca7f8da9642336348ddd6cab2713ddcf8f9", - "sha256:a34b577cdf6313bf24755f7a0e3f3c326d5c1f4fe7422d1d06498eb25ad0c600", - "sha256:a8ffcd53cb5dfc131850851cc09f1c44689c2812d0beb954d8138d4f5fc17f65", - "sha256:b90928f2d9eb2f33162405f32dde9f6dcead63a0971ca8a1b50eb4ca3e35ceb8", - "sha256:c56ffe22faa2e51054c5f7a3bc70a370939c2ed4de308c690e7949230c995913", - "sha256:f91c7ae919bbc3f96cd5e5b2e786b2b108343d1d7972ea130f7de27fdd547cf3" + "sha256:00cb1964a7476e871d6108341ac9c1a857d6bd20bf5877f4773ac5e9d92cd3cd", + "sha256:127de5a9b817a03a98c5ae8a0c46a20dc44442af6dcfa2ae7f96cb519b312efa", + "sha256:1f3976a945ad7f0a0727aafdc5651c2d3278e3c88dee94e2bf75cd3386b7b2f4", + "sha256:2f8c098f12b402c19b735aec724cc9105cc1a9eea405d08814eb4b14a6fb1a41", + "sha256:4ef13b619a289aa025f2273e05e755f8049bb4eaba6d703a425de37d495d178d", + "sha256:5d142f219bf8c7894dfa79ebfb7d352c4c63a325e75f10dfb4c3db9417dcd135", + "sha256:62eb5dd4ea86bda8ce386f26684f7f26e4bfe6283c9f2b6ca6d17faf704dcfad", + "sha256:64c36eb0936d0bfb7d8da49f92c18e312ad2e3ed46e5548ae4ca997b0d33bd59", + "sha256:75eed74d2faf2759f79c5f56f17388defd2fc994222312ec54ee921e37b31ad4", + "sha256:974bebe3699b9b46278a7f076635d219183da26e1a675c1f8243a69221758273", + "sha256:a5e5bb12b7982b179af513dddb06fca12285f0316d74f3964078acbfcf4c68f2", + "sha256:d31291df31bafb997952dc0a17ebb2737f802c754aed31dd155a8bfe75112c57", + "sha256:d3b4941de44341227ece1caaf5b08b23e42ad4eeb8b603219afb11e9d4cfb437", + "sha256:eadb865126da4e3c4c95bdb47fe1bb087a3e3ea14d39a3b13224b8a4d9f9a102" ], "index": "pypi", - "version": "==0.770" + "version": "==0.780" }, "mypy-extensions": { "hashes": [ @@ -1776,11 +1784,11 @@ }, "nbformat": { "hashes": [ - "sha256:049af048ed76b95c3c44043620c17e56bc001329e07f83fec4f177f0e3d7b757", - "sha256:276343c78a9660ab2a63c28cc33da5f7c58c092b3f3a40b6017ae2ce6689320d" + "sha256:54d4d6354835a936bad7e8182dcd003ca3dc0cedfee5a306090e04854343b340", + "sha256:ea55c9b817855e2dfcd3f66d74857342612a60b1f09653440f4a5845e6e3523f" ], "markers": "python_version >= '3.5'", - "version": "==5.0.6" + "version": "==5.0.7" }, "networkx": { "hashes": [ @@ -1792,9 +1800,9 @@ }, "nodeenv": { "hashes": [ - "sha256:5b2438f2e42af54ca968dd1b374d14a1194848955187b0e5e4be1f73813a5212" + "sha256:4b0b77afa3ba9b54f4b6396e60b0c83f59eaeb2d63dc3cc7a70f7f4af96c82bc" ], - "version": "==1.3.5" + "version": "==1.4.0" }, "notebook": { "hashes": [ @@ -1806,30 +1814,30 @@ }, "numpy": { "hashes": [ - "sha256:00d7b54c025601e28f468953d065b9b121ddca7fff30bed7be082d3656dd798d", - "sha256:02ec9582808c4e48be4e93cd629c855e644882faf704bc2bd6bbf58c08a2a897", - "sha256:0e6f72f7bb08f2f350ed4408bb7acdc0daba637e73bce9f5ea2b207039f3af88", - "sha256:1be2e96314a66f5f1ce7764274327fd4fb9da58584eaff00b5a5221edefee7d6", - "sha256:2466fbcf23711ebc5daa61d28ced319a6159b260a18839993d871096d66b93f7", - "sha256:2b573fcf6f9863ce746e4ad00ac18a948978bb3781cffa4305134d31801f3e26", - "sha256:3f0dae97e1126f529ebb66f3c63514a0f72a177b90d56e4bce8a0b5def34627a", - "sha256:50fb72bcbc2cf11e066579cb53c4ca8ac0227abb512b6cbc1faa02d1595a2a5d", - "sha256:57aea170fb23b1fd54fa537359d90d383d9bf5937ee54ae8045a723caa5e0961", - "sha256:709c2999b6bd36cdaf85cf888d8512da7433529f14a3689d6e37ab5242e7add5", - "sha256:7d59f21e43bbfd9a10953a7e26b35b6849d888fc5a331fa84a2d9c37bd9fe2a2", - "sha256:904b513ab8fbcbdb062bed1ce2f794ab20208a1b01ce9bd90776c6c7e7257032", - "sha256:96dd36f5cdde152fd6977d1bbc0f0561bccffecfde63cd397c8e6033eb66baba", - "sha256:9933b81fecbe935e6a7dc89cbd2b99fea1bf362f2790daf9422a7bb1dc3c3085", - "sha256:bbcc85aaf4cd84ba057decaead058f43191cc0e30d6bc5d44fe336dc3d3f4509", - "sha256:dccd380d8e025c867ddcb2f84b439722cf1f23f3a319381eac45fd077dee7170", - "sha256:e22cd0f72fc931d6abc69dc7764484ee20c6a60b0d0fee9ce0426029b1c1bdae", - "sha256:ed722aefb0ebffd10b32e67f48e8ac4c5c4cf5d3a785024fdf0e9eb17529cd9d", - "sha256:efb7ac5572c9a57159cf92c508aad9f856f1cb8e8302d7fdb99061dbe52d712c", - "sha256:efdba339fffb0e80fcc19524e4fdbda2e2b5772ea46720c44eaac28096d60720", - "sha256:f22273dd6a403ed870207b853a856ff6327d5cbce7a835dfa0645b3fc00273ec" - ], - "index": "pypi", - "version": "==1.18.4" + "sha256:0172304e7d8d40e9e49553901903dc5f5a49a703363ed756796f5808a06fc233", + "sha256:34e96e9dae65c4839bd80012023aadd6ee2ccb73ce7fdf3074c62f301e63120b", + "sha256:3676abe3d621fc467c4c1469ee11e395c82b2d6b5463a9454e37fe9da07cd0d7", + "sha256:3dd6823d3e04b5f223e3e265b4a1eae15f104f4366edd409e5a5e413a98f911f", + "sha256:4064f53d4cce69e9ac613256dc2162e56f20a4e2d2086b1956dd2fcf77b7fac5", + "sha256:4674f7d27a6c1c52a4d1aa5f0881f1eff840d2206989bae6acb1c7668c02ebfb", + "sha256:7d42ab8cedd175b5ebcb39b5208b25ba104842489ed59fbb29356f671ac93583", + "sha256:965df25449305092b23d5145b9bdaeb0149b6e41a77a7d728b1644b3c99277c1", + "sha256:9c9d6531bc1886454f44aa8f809268bc481295cf9740827254f53c30104f074a", + "sha256:a78e438db8ec26d5d9d0e584b27ef25c7afa5a182d1bf4d05e313d2d6d515271", + "sha256:a7acefddf994af1aeba05bbbafe4ba983a187079f125146dc5859e6d817df824", + "sha256:a87f59508c2b7ceb8631c20630118cc546f1f815e034193dc72390db038a5cb3", + "sha256:ac792b385d81151bae2a5a8adb2b88261ceb4976dbfaaad9ce3a200e036753dc", + "sha256:b03b2c0badeb606d1232e5f78852c102c0a7989d3a534b3129e7856a52f3d161", + "sha256:b39321f1a74d1f9183bf1638a745b4fd6fe80efbb1f6b32b932a588b4bc7695f", + "sha256:cae14a01a159b1ed91a324722d746523ec757357260c6804d11d6147a9e53e3f", + "sha256:cd49930af1d1e49a812d987c2620ee63965b619257bd76eaaa95870ca08837cf", + "sha256:e15b382603c58f24265c9c931c9a45eebf44fe2e6b4eaedbb0d025ab3255228b", + "sha256:e91d31b34fc7c2c8f756b4e902f901f856ae53a93399368d9a0dc7be17ed2ca0", + "sha256:ef627986941b5edd1ed74ba89ca43196ed197f1a206a3f18cc9faf2fb84fd675", + "sha256:f718a7949d1c4f622ff548c572e0c03440b49b9531ff00e4ed5738b459f011e8" + ], + "index": "pypi", + "version": "==1.18.5" }, "oauthlib": { "hashes": [ @@ -1913,25 +1921,25 @@ }, "pandas": { "hashes": [ - "sha256:07c1b58936b80eafdfe694ce964ac21567b80a48d972879a359b3ebb2ea76835", - "sha256:0ebe327fb088df4d06145227a4aa0998e4f80a9e6aed4b61c1f303bdfdf7c722", - "sha256:11c7cb654cd3a0e9c54d81761b5920cdc86b373510d829461d8f2ed6d5905266", - "sha256:12f492dd840e9db1688126216706aa2d1fcd3f4df68a195f9479272d50054645", - "sha256:167a1315367cea6ec6a5e11e791d9604f8e03f95b57ad227409de35cf850c9c5", - "sha256:1a7c56f1df8d5ad8571fa251b864231f26b47b59cbe41aa5c0983d17dbb7a8e4", - "sha256:1fa4bae1a6784aa550a1c9e168422798104a85bf9c77a1063ea77ee6f8452e3a", - "sha256:32f42e322fb903d0e189a4c10b75ba70d90958cc4f66a1781ed027f1a1d14586", - "sha256:387dc7b3c0424327fe3218f81e05fc27832772a5dffbed385013161be58df90b", - "sha256:6597df07ea361231e60c00692d8a8099b519ed741c04e65821e632bc9ccb924c", - "sha256:743bba36e99d4440403beb45a6f4f3a667c090c00394c176092b0b910666189b", - "sha256:858a0d890d957ae62338624e4aeaf1de436dba2c2c0772570a686eaca8b4fc85", - "sha256:863c3e4b7ae550749a0bb77fa22e601a36df9d2905afef34a6965bed092ba9e5", - "sha256:a210c91a02ec5ff05617a298ad6f137b9f6f5771bf31f2d6b6367d7f71486639", - "sha256:ca84a44cf727f211752e91eab2d1c6c1ab0f0540d5636a8382a3af428542826e", - "sha256:d234bcf669e8b4d6cbcd99e3ce7a8918414520aeb113e2a81aeb02d0a533d7f7" + "sha256:034185bb615dc96d08fa13aacba8862949db19d5e7804d6ee242d086f07bcc46", + "sha256:0c9b7f1933e3226cc16129cf2093338d63ace5c85db7c9588e3e1ac5c1937ad5", + "sha256:1f6fcf0404626ca0475715da045a878c7062ed39bc859afc4ccf0ba0a586a0aa", + "sha256:1fc963ba33c299973e92d45466e576d11f28611f3549469aec4a35658ef9f4cc", + "sha256:29b4cfee5df2bc885607b8f016e901e63df7ffc8f00209000471778f46cc6678", + "sha256:2a8b6c28607e3f3c344fe3e9b3cd76d2bf9f59bc8c0f2e582e3728b80e1786dc", + "sha256:2bc2ff52091a6ac481cc75d514f06227dc1b10887df1eb72d535475e7b825e31", + "sha256:415e4d52fcfd68c3d8f1851cef4d947399232741cc994c8f6aa5e6a9f2e4b1d8", + "sha256:519678882fd0587410ece91e3ff7f73ad6ded60f6fcb8aa7bcc85c1dc20ecac6", + "sha256:51e0abe6e9f5096d246232b461649b0aa627f46de8f6344597ca908f2240cbaa", + "sha256:698e26372dba93f3aeb09cd7da2bb6dd6ade248338cfe423792c07116297f8f4", + "sha256:83af85c8e539a7876d23b78433d90f6a0e8aa913e37320785cf3888c946ee874", + "sha256:982cda36d1773076a415ec62766b3c0a21cdbae84525135bdb8f460c489bb5dd", + "sha256:a647e44ba1b3344ebc5991c8aafeb7cca2b930010923657a273b41d86ae225c4", + "sha256:b35d625282baa7b51e82e52622c300a1ca9f786711b2af7cbe64f1e6831f4126", + "sha256:bab51855f8b318ef39c2af2c11095f45a10b74cbab4e3c8199efcc5af314c648" ], "markers": "python_version >= '3.6.1'", - "version": "==1.0.3" + "version": "==1.0.4" }, "pandocfilters": { "hashes": [ @@ -2022,11 +2030,11 @@ }, "pre-commit": { "hashes": [ - "sha256:5559e09afcac7808933951ffaf4ff9aac524f31efbc3f24d021540b6c579813c", - "sha256:703e2e34cbe0eedb0d319eff9f7b83e2022bb5a3ab5289a6a8841441076514d0" + "sha256:c5c8fd4d0e1c363723aaf0a8f9cba0f434c160b48c4028f4bae6d219177945b3", + "sha256:da463cf8f0e257f9af49047ba514f6b90dbd9b4f92f4c8847a3ccd36834874c7" ], "index": "pypi", - "version": "==2.4.0" + "version": "==2.5.1" }, "prometheus-client": { "hashes": [ @@ -2110,12 +2118,6 @@ ], "version": "==0.2.8" }, - "pycocotools": { - "git": "https://github.com/cocodataset/cocoapi.git", - "ref": "8c9bcc3cf640524c4c20a9c40e89cb6a2f2fa0e9", - "subdirectory": "PythonAPI", - "version": "==2.0" - }, "pycparser": { "hashes": [ "sha256:2d475327684562c3a96cc71adf7dc8c4f0565175cf86b6d7a404ff4c771f15f0", @@ -2205,11 +2207,11 @@ }, "pylint": { "hashes": [ - "sha256:b95e31850f3af163c2283ed40432f053acbc8fc6eba6a069cb518d9dbf71848c", - "sha256:dd506acce0427e9e08fb87274bcaa953d38b50a58207170dbf5b36cf3e16957b" + "sha256:7dd78437f2d8d019717dbf287772d0b2dbdfd13fc016aa7faa08d67bccc46adc", + "sha256:d0ece7d223fe422088b0e8f13fa0a1e8eb745ebffcb8ed53d3e95394b6101a1c" ], "index": "pypi", - "version": "==2.5.2" + "version": "==2.5.3" }, "pylogbeat": { "hashes": [ @@ -2399,11 +2401,11 @@ }, "python-logstash-async": { "hashes": [ - "sha256:96492d7080bd197baf889d3ea927206e987161e08d3fce9cfb0557c6c6d4013e", - "sha256:c07d7f80d06b807ac8ab613562d7f246056ffb57320e60c714cd421ff053c2c2" + "sha256:56b0fd4c06ede320d7f1defa6b4f6b442227a880ce84f44c88b69c313e35cd6f", + "sha256:57aebfccd8a7e0ee5b7c4bdb7c941e84eac3c3e30c5619feabb5444d9b827d2b" ], "index": "pypi", - "version": "==1.6.4" + "version": "==1.6.6" }, "python-socketio": { "hashes": [ @@ -2513,11 +2515,11 @@ }, "redis": { "hashes": [ - "sha256:2ef11f489003f151777c064c5dbc6653dfb9f3eade159bcadc524619fddc2242", - "sha256:6d65e84bc58091140081ee9d9c187aab0480097750fac44239307a3bdf0b1251" + "sha256:0e7e0cfca8660dea8b7d5cd8c4f6c5e29e11f31158c0b0ae91a397f00e5a05a2", + "sha256:432b788c4530cfe16d8d943a09d40ca6c16149727e4afe8c2c9d5580c59d9f24" ], "index": "pypi", - "version": "==3.5.2" + "version": "==3.5.3" }, "requests": { "hashes": [ @@ -2544,10 +2546,11 @@ }, "rsa": { "hashes": [ - "sha256:14ba45700ff1ec9eeb206a2ce76b32814958a98e372006c8fb76ba820211be66", - "sha256:1a836406405730121ae9823e19c6e806c62bbad73f890574fff50efa4122c487" + "sha256:0ddc7ab19b5781148e405a4de7f1e9929e8c1e015d11a53b81e9a6242ee8e098", + "sha256:efaf0c32afee1c136e5cd2e7ceecf2dfc65dac00fb812a1b3b8b72f6fea38dbb" ], - "version": "==4.0" + "markers": "python_version >= '3'", + "version": "==4.4.1" }, "s2sphere": { "hashes": [ @@ -2810,11 +2813,11 @@ }, "tifffile": { "hashes": [ - "sha256:12a9ffc702de8f5ea6a7c39f69654143fb419059773e964be6293a16a0b2cbf9", - "sha256:b212b7eb7651208c79ec95899f0dfe5684d68f4254cf782247af4f56f8e00cc8" + "sha256:66d90f05eec5e62336d87d0d09e6a218012afdf834c22d66abc62ba88b355e39", + "sha256:e79403a8b98b0df7ade8d43469151b959fd56239001471fac62beabca6f56377" ], "markers": "python_version >= '3.6'", - "version": "==2020.5.25" + "version": "==2020.6.3" }, "toml": { "hashes": [ @@ -2889,18 +2892,18 @@ }, "virtualenv": { "hashes": [ - "sha256:a116629d4e7f4d03433b8afa27f43deba09d48bc48f5ecefa4f015a178efb6cf", - "sha256:a730548b27366c5e6cbdf6f97406d861cccece2e22275e8e1a757aeff5e00c70" + "sha256:27ee4f826a432a2a0933a762829c4dda15b728dd89b43d4ee354461e245acc93", + "sha256:c518b120bfdbbb111e52700fbb80f56c923a3f228d9140baa02d043da2949809" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==20.0.21" + "version": "==20.0.22" }, "wcwidth": { "hashes": [ - "sha256:cafe2186b3c009a04067022ce1dcd79cb38d8d65ee4f4791b8888d6599d1bbe1", - "sha256:ee73862862a156bf77ff92b09034fc4825dd3af9cf81bc5b360668d425f3c5f1" + "sha256:79375666b9954d4a1a10739315816324c3e73110af9d0e102d906fdb0aec009f", + "sha256:8c6b5b6ee1360b842645f336d9e5d68c55817c26d3050f46b235ef2bc650e48f" ], - "version": "==0.1.9" + "version": "==0.2.4" }, "webencodings": { "hashes": [ From 3061aea9f45dac4cb51d60d2a926a812ecf9a5d0 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 12:06:26 -0700 Subject: [PATCH 264/656] Update Sonata stiffnes --- selfdrive/car/hyundai/interface.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index c38f54923d..bde37e10bf 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -41,6 +41,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 1513. + STD_CARGO_KG ret.wheelbase = 2.84 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable + tire_stiffness_factor = 0.65 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.SONATA_2019: From 7e80ae3f09202180b3a94f0af88c85b9f2cdfa79 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 12 Jun 2020 12:09:05 -0700 Subject: [PATCH 265/656] Push docker image with prebuilt openpilot to dockerhub (#1686) * add CI job to push a prebuilt image to dockerhhub' * fix config * Update test.yaml * better name * only run on schedule --- .github/workflows/test.yaml | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index b16e0660b5..4ee271fdb1 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -1,5 +1,9 @@ name: openpilot tests -on: [push, pull_request] +on: + push: + pull_request: + schedule: + - cron: '0 * * * *' env: RUN: docker run --shm-size 1G --rm tmppilot /bin/sh -c @@ -62,6 +66,24 @@ jobs: docker tag tmppilot docker.io/commaai/openpilot:latest docker push docker.io/commaai/openpilot:latest + docker_push_prebuilt: + name: docker push prebuilt + runs-on: ubuntu-16.04 + timeout-minutes: 50 + if: github.event_name == 'schedule' && github.repository == 'commaai/openpilot' + needs: [static_analysis, unit_tests, process_replay, test_longitudinal, test_car_models] + steps: + - uses: actions/checkout@v2 + with: + submodules: true + - name: Build Docker image + run: echo "RUN cd /tmp/openpilot && scons -c && scons -j3" >> Dockerfile.openpilot && eval "$BUILD" + - name: Push to dockerhub + run: | + docker login -u wmelching -p ${{ secrets.COMMA_DOCKERHUB_TOKEN}} + docker tag tmppilot docker.io/commaai/openpilot_prebuilt:latest + docker push docker.io/commaai/openpilot_prebuilt:latest + static_analysis: name: static analysis runs-on: ubuntu-16.04 From ef1c7b6833fe86c5541eb79b8129d0663db00c7a Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 12:09:04 -0700 Subject: [PATCH 266/656] Reset stiffness at beginning of each drive --- selfdrive/locationd/paramsd.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index 487dc640e0..ad820b4ea2 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -100,6 +100,10 @@ def main(sm=None, pm=None): } cloudlog.info("Parameter learner resetting to default values") + # When driving in wet conditions the stiffness can go down, and then be too low on the next drive + # Without a way to detect this we have to reset the stiffness every drive + params['stiffnessFactor'] = 1.0 + learner = ParamsLearner(CP, params['steerRatio'], params['stiffnessFactor'], math.radians(params['angleOffsetAverage'])) min_sr, max_sr = 0.5 * CP.steerRatio, 2.0 * CP.steerRatio From 0f26c04a7bd632ca3d51698786f2aa7e0024e606 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 12:14:16 -0700 Subject: [PATCH 267/656] use older pre-commit version --- Pipfile | 2 +- Pipfile.lock | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Pipfile b/Pipfile index fa4309ef0c..aee85f18fa 100644 --- a/Pipfile +++ b/Pipfile @@ -71,7 +71,7 @@ scikit-image = "*" pygame = "==2.0.0.dev8" pprofile = "*" pyprof2calltree = "*" -pre-commit = "*" +pre-commit = "==2.4.0" mypy = "*" [packages] diff --git a/Pipfile.lock b/Pipfile.lock index 44b8466036..7d97f2e967 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "96924e487a9d20b4fb06eea1e6536816a157a9606051da58741c66fa6630371a" + "sha256": "74a23e7ac1a5e8835d3d8c97f917cda7edaa53934d3cfa89c4cc8bc03da1b0d5" }, "pipfile-spec": 6, "requires": { @@ -2030,11 +2030,11 @@ }, "pre-commit": { "hashes": [ - "sha256:c5c8fd4d0e1c363723aaf0a8f9cba0f434c160b48c4028f4bae6d219177945b3", - "sha256:da463cf8f0e257f9af49047ba514f6b90dbd9b4f92f4c8847a3ccd36834874c7" + "sha256:5559e09afcac7808933951ffaf4ff9aac524f31efbc3f24d021540b6c579813c", + "sha256:703e2e34cbe0eedb0d319eff9f7b83e2022bb5a3ab5289a6a8841441076514d0" ], "index": "pypi", - "version": "==2.5.1" + "version": "==2.4.0" }, "prometheus-client": { "hashes": [ From 6f46eed874e85f41de1bca4a7b0b65bfc4a295d8 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 12:25:18 -0700 Subject: [PATCH 268/656] Fixed virtualenv https://github.com/pypa/virtualenv/issues/1857 --- Pipfile | 2 +- Pipfile.lock | 20 ++++++++++---------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/Pipfile b/Pipfile index aee85f18fa..fa4309ef0c 100644 --- a/Pipfile +++ b/Pipfile @@ -71,7 +71,7 @@ scikit-image = "*" pygame = "==2.0.0.dev8" pprofile = "*" pyprof2calltree = "*" -pre-commit = "==2.4.0" +pre-commit = "*" mypy = "*" [packages] diff --git a/Pipfile.lock b/Pipfile.lock index 7d97f2e967..82cb88818f 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "74a23e7ac1a5e8835d3d8c97f917cda7edaa53934d3cfa89c4cc8bc03da1b0d5" + "sha256": "96924e487a9d20b4fb06eea1e6536816a157a9606051da58741c66fa6630371a" }, "pipfile-spec": 6, "requires": { @@ -1237,11 +1237,11 @@ }, "google-auth": { "hashes": [ - "sha256:1c96c33ad94a492cf21016ac69285d7409d7d046b5cda0a46793e1323a97d657", - "sha256:846feb49ccdd86f74f86fc01f5d679c0b7256af1680fc985db26021b037fbc4e" + "sha256:25d3c4e457db5504c62b3e329e8e67d2c29a0cecec3aa5347ced030d8700a75d", + "sha256:e634b649967d83c02dd386ecae9ce4a571528d59d51a4228757e45f5404a060b" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.17.1" + "version": "==1.17.2" }, "google-auth-oauthlib": { "hashes": [ @@ -2030,11 +2030,11 @@ }, "pre-commit": { "hashes": [ - "sha256:5559e09afcac7808933951ffaf4ff9aac524f31efbc3f24d021540b6c579813c", - "sha256:703e2e34cbe0eedb0d319eff9f7b83e2022bb5a3ab5289a6a8841441076514d0" + "sha256:c5c8fd4d0e1c363723aaf0a8f9cba0f434c160b48c4028f4bae6d219177945b3", + "sha256:da463cf8f0e257f9af49047ba514f6b90dbd9b4f92f4c8847a3ccd36834874c7" ], "index": "pypi", - "version": "==2.4.0" + "version": "==2.5.1" }, "prometheus-client": { "hashes": [ @@ -2892,11 +2892,11 @@ }, "virtualenv": { "hashes": [ - "sha256:27ee4f826a432a2a0933a762829c4dda15b728dd89b43d4ee354461e245acc93", - "sha256:c518b120bfdbbb111e52700fbb80f56c923a3f228d9140baa02d043da2949809" + "sha256:5102fbf1ec57e80671ef40ed98a84e980a71194cedf30c87c2b25c3a9e0b0107", + "sha256:ccfb8e1e05a1174f7bd4c163700277ba730496094fe1a58bea9d4ac140a207c8" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==20.0.22" + "version": "==20.0.23" }, "wcwidth": { "hashes": [ From 2a12c653d51fd1a6d1c0e6f08dab624de65f6e2f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 13:20:54 -0700 Subject: [PATCH 269/656] update process replay after sonata stiffness change --- selfdrive/test/process_replay/ref_commit | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index bb6039e7e5..d6f4f35172 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -834f4cd7e90ff266ced8ea142d7d7d05076186aa \ No newline at end of file +6f46eed874e85f41de1bca4a7b0b65bfc4a295d8 \ No newline at end of file From 955d2aefdd6dd0c4de4820175a18f67c81be6783 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 15:03:32 -0700 Subject: [PATCH 270/656] Cool down device before going onroad if CPU temp over 75 C (#1688) * Block going onroad when temperatures are too high * add relay check --- selfdrive/thermald/thermald.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index a67f086dd1..9e4a26c001 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -184,6 +184,7 @@ def thermald_thread(): should_start_prev = False handle_fan = None is_uno = False + has_relay = False params = Params() pm = PowerMonitoring() @@ -212,6 +213,7 @@ def thermald_thread(): # Setup fan handler on first connect to panda if handle_fan is None and health.health.hwType != log.HealthData.HwType.unknown: is_uno = health.health.hwType == log.HealthData.HwType.uno + has_relay = health.health.hwType in [log.HealthData.HwType.blackPanda, log.HealthData.HwType.uno] if is_uno or not ANDROID: cloudlog.info("Setting up UNO fan handler") @@ -268,8 +270,10 @@ def thermald_thread(): fan_speed = handle_fan(max_cpu_temp, bat_temp, fan_speed, ignition) msg.thermal.fanSpeed = fan_speed - # thermal logic with hysterisis - if max_cpu_temp > 107. or bat_temp >= 63.: + # If device is offroad we want to cool down before going onroad + # since going onroad increases load and can make temps go over 107 + # We only do this if there is a relay that prevents the car from faulting + if max_cpu_temp > 107. or bat_temp >= 63. or (has_relay and (started_ts is None) and max_cpu_temp > 75.0): # onroad not allowed thermal_status = ThermalStatus.danger elif max_comp_temp > 100.0 or bat_temp > 60.: From 0bbe870b5f90c25427c4d21cabe4a0f78291eee9 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 12 Jun 2020 15:32:50 -0700 Subject: [PATCH 271/656] Delay alert creation for some events (#1689) * add creation delay parameter to alerts * 1s delay for sensorsInvalid and canError * bump cereal * update refs --- cereal | 2 +- selfdrive/controls/controlsd.py | 6 ----- selfdrive/controls/lib/events.py | 29 +++++++++++++----------- selfdrive/test/process_replay/ref_commit | 2 +- 4 files changed, 18 insertions(+), 21 deletions(-) diff --git a/cereal b/cereal index 9915b2086a..b93b165a5c 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 9915b2086a4205d9a28eead6139d5d7cbb73b00b +Subproject commit b93b165a5c9de33325d7b01aa033073c978d1007 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 2c1a444d9f..4f42eb804b 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -118,7 +118,6 @@ class Controls: self.v_cruise_kph_last = 0 self.mismatch_counter = 0 self.can_error_counter = 0 - self.consecutive_can_error_count = 0 self.last_blinker_frame = 0 self.saturated_count = 0 self.events_prev = [] @@ -191,11 +190,6 @@ class Controls: if self.can_rcv_error or (not CS.canValid and self.sm.frame > 5 / DT_CTRL): self.events.add(EventName.canError) - self.consecutive_can_error_count += 1 - else: - self.consecutive_can_error_count = 0 - if self.consecutive_can_error_count > 2 / DT_CTRL: - self.events.add(EventName.canErrorPersistent) if self.mismatch_counter >= 200: self.events.add(EventName.controlsMismatch) if not self.sm.alive['plan'] and self.sm.alive['pathPlan']: diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 3e8f985fe7..e365dfc926 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -1,7 +1,7 @@ from cereal import log, car +from common.realtime import DT_CTRL from selfdrive.config import Conversions as CV - from selfdrive.locationd.calibration_helpers import Filter AlertSize = log.ControlsState.AlertSize @@ -37,6 +37,7 @@ class Events: def __init__(self): self.events = [] self.static_events = [] + self.events_prev = dict.fromkeys(EVENTS.keys(), 0) @property def names(self): @@ -51,6 +52,7 @@ class Events: self.events.append(event_name) def clear(self): + self.events_prev = {k: (v+1 if k in self.events else 0) for k, v in self.events_prev.items()} self.events = self.static_events.copy() def any(self, event_type): @@ -71,8 +73,10 @@ class Events: alert = EVENTS[e][et] if not isinstance(alert, Alert): alert = alert(*callback_args) - alert.alert_type = EVENT_NAME[e] - ret.append(alert) + + if DT_CTRL * (self.events_prev[e] + 1) >= alert.creation_delay: + alert.alert_type = EVENT_NAME[e] + ret.append(alert) return ret def add_from_msg(self, events): @@ -101,7 +105,8 @@ class Alert: duration_sound, duration_hud_alert, duration_text, - alert_rate=0.): + alert_rate=0., + creation_delay=0.): self.alert_type = "" self.alert_text_1 = alert_text_1 @@ -118,6 +123,7 @@ class Alert: self.start_time = 0. self.alert_rate = alert_rate + self.creation_delay = creation_delay # typecheck that enums are valid on startup tst = car.CarControl.new_message() @@ -308,14 +314,6 @@ EVENTS = { Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimePrompt, 1., 2., 3.), }, - EventName.canErrorPersistent: { - ET.PERMANENT: Alert( - "CAN Error: Check Connections", - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), - }, - # ********** events only containing alerts that display while engaged ********** EventName.vehicleModelInvalid: { @@ -515,7 +513,7 @@ EVENTS = { "No Data from Device Sensors", "Reboot your Device", AlertStatus.normal, AlertSize.mid, - Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=1.), ET.NO_ENTRY: NoEntryAlert("No Data from Device Sensors"), }, @@ -617,6 +615,11 @@ EVENTS = { EventName.canError: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("CAN Error: Check Connections"), + ET.PERMANENT: Alert( + "CAN Error: Check Connections", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=1.), ET.NO_ENTRY: NoEntryAlert("CAN Error: Check Connections"), }, diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index d6f4f35172..8e0be9100a 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -6f46eed874e85f41de1bca4a7b0b65bfc4a295d8 \ No newline at end of file +b85c090b3dba832b4af83a847df5b5ac2c824284 \ No newline at end of file From 1ea80bedadb64843c8c9daa63bc1e6855163c80c Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 15:24:04 -0700 Subject: [PATCH 272/656] Add mention about improved thermal management to release notes --- RELEASES.md | 1 + 1 file changed, 1 insertion(+) diff --git a/RELEASES.md b/RELEASES.md index 17989d1d85..0c0bb519cb 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -2,6 +2,7 @@ Version 0.8 (2020-xx-xx) ======================== * White panda is no longer supported, upgrade to comma two or black panda * Improved vehicle model estimation using high precision localizer + * Improved thermal management on comma two Version 0.7.6 (2020-06-05) ======================== From 684f7b2cc073010eb9e9cebfecbf1205be17d5a8 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 16:03:35 -0700 Subject: [PATCH 273/656] no gps warning after 5 minutes (#1692) --- cereal | 2 +- selfdrive/controls/controlsd.py | 2 ++ selfdrive/controls/lib/events.py | 8 ++++++++ 3 files changed, 11 insertions(+), 1 deletion(-) diff --git a/cereal b/cereal index b93b165a5c..d4d52a567b 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit b93b165a5c9de33325d7b01aa033073c978d1007 +Subproject commit d4d52a567bfd17a5130429657b341618ed657627 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 4f42eb804b..e03c2ed002 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -202,6 +202,8 @@ class Controls: if not self.sm['liveLocationKalman'].inputsOK and os.getenv("NOSENSOR") is None: if self.sm.frame > 5 / DT_CTRL: # Give locationd some time to receive all the inputs self.events.add(EventName.sensorDataInvalid) + if not self.sm['liveLocationKalman'].gpsOK and os.getenv("NOSENSOR") is None: + self.events.add(EventName.noGps) if not self.sm['pathPlan'].paramsValid: self.events.add(EventName.vehicleModelInvalid) if not self.sm['liveLocationKalman'].posenetOK: diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index e365dfc926..1e953cfbf3 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -517,6 +517,14 @@ EVENTS = { ET.NO_ENTRY: NoEntryAlert("No Data from Device Sensors"), }, + EventName.noGps: { + ET.PERMANENT: Alert( + "Poor GPS reception", + "Check GPS antenna placement", + AlertStatus.normal, AlertSize.mid, + Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=300.), + }, + EventName.soundsUnavailable: { ET.PERMANENT: Alert( "Speaker not found", From 17619a63eee80b178d4b0d5c0b8e8beaa6b5650c Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 12 Jun 2020 16:04:03 -0700 Subject: [PATCH 274/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index d4d52a567b..9774f7a08b 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit d4d52a567bfd17a5130429657b341618ed657627 +Subproject commit 9774f7a08b7766a423bb663176ed97afdd57d83c From 32c4367ffbd5c472ad6f6a84f89458b29b4465e1 Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Fri, 12 Jun 2020 16:11:27 -0700 Subject: [PATCH 275/656] ffmpeg hwaccel is better --- tools/lib/framereader.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/tools/lib/framereader.py b/tools/lib/framereader.py index f1155dbdc8..d1b7acf72e 100644 --- a/tools/lib/framereader.py +++ b/tools/lib/framereader.py @@ -222,7 +222,8 @@ def decompress_video_data(rawdat, vid_fmt, w, h, pix_fmt): proc = subprocess.Popen( ["ffmpeg", "-threads", threads, - "-c:v", "hevc" if not cuda else "hevc_cuvid", + "-hwaccel", "none" if not cuda else "cuda", + "-c:v", "hevc", "-vsync", "0", "-f", vid_fmt, "-flags2", "showall", @@ -345,7 +346,8 @@ class VideoStreamDecompressor: self.proc = subprocess.Popen( ["ffmpeg", "-threads", threads, - "-c:v", "hevc" if not cuda else "hevc_cuvid", + "-hwaccel", "none" if not cuda else "cuda", + "-c:v", "hevc", # "-avioflags", "direct", "-analyzeduration", "0", "-probesize", "32", From 855a630dfc14f004cafb771822aa2d1dd06fc05c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 12 Jun 2020 17:45:32 -0700 Subject: [PATCH 276/656] rename docker containers --- .github/workflows/test.yaml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 4ee271fdb1..dc06161021 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -12,8 +12,8 @@ env: UNIT_TEST: coverage run --append -m unittest discover BUILD: | docker pull $(grep -ioP '(?<=^from)\s+\S+' Dockerfile.openpilot) || true - docker pull docker.io/commaai/openpilot:latest || true - docker build --cache-from docker.io/commaai/openpilot:latest -t tmppilot -f Dockerfile.openpilot . + docker pull docker.io/commaai/openpilotci:latest || true + docker build --cache-from docker.io/commaai/openpilotci:latest -t tmppilot -f Dockerfile.openpilot . jobs: build_release: @@ -63,8 +63,8 @@ jobs: - name: Push to dockerhub run: | docker login -u wmelching -p ${{ secrets.COMMA_DOCKERHUB_TOKEN}} - docker tag tmppilot docker.io/commaai/openpilot:latest - docker push docker.io/commaai/openpilot:latest + docker tag tmppilot docker.io/commaai/openpilotci:latest + docker push docker.io/commaai/openpilotci:latest docker_push_prebuilt: name: docker push prebuilt @@ -81,8 +81,8 @@ jobs: - name: Push to dockerhub run: | docker login -u wmelching -p ${{ secrets.COMMA_DOCKERHUB_TOKEN}} - docker tag tmppilot docker.io/commaai/openpilot_prebuilt:latest - docker push docker.io/commaai/openpilot_prebuilt:latest + docker tag tmppilot docker.io/commaai/openpilot:latest + docker push docker.io/commaai/openpilot:latest static_analysis: name: static analysis From 92c29c426916765b3af8d976a62502ece295f39e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 12 Jun 2020 20:38:45 -0700 Subject: [PATCH 277/656] bump cereal --- cereal | 2 +- selfdrive/controls/lib/events.py | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/cereal b/cereal index 9774f7a08b..18698b113e 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 9774f7a08b7766a423bb663176ed97afdd57d83c +Subproject commit 18698b113e8b7a3fda230179e3bdf837d7ba9b7e diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 1e953cfbf3..f463d3cedd 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -189,6 +189,8 @@ EVENTS = { EventName.gasPressed: {ET.PRE_ENABLE: None}, + EventName.focusRecoverActive: {}, + # ********** events only containing alerts displayed in all states ********** EventName.debugAlert: { From 437b974505a80011352bfa636e14445cea8c87c7 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 12 Jun 2020 20:55:59 -0700 Subject: [PATCH 278/656] Add hyundai legacy safety mode (#1693) --- panda | 2 +- selfdrive/car/hyundai/interface.py | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/panda b/panda index 74c607f79a..d0442fd1e4 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 74c607f79acd2baace27265f763480af75496dac +Subproject commit d0442fd1e45589880c12b27c8a744cd1f540f540 diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index bde37e10bf..e3bbc0f71a 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -135,6 +135,10 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + # these cars require a special panda safety mode due to missing counters and checksums in the messages + if candidate in [CAR.HYUNDAI_GENESIS]: + ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy + ret.centerToFront = ret.wheelbase * 0.4 # TODO: get actual value, for now starting with reasonable value for From 3316e19aa4c905d4ab2d2c414bb14817649c6729 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Sat, 13 Jun 2020 10:36:29 -0500 Subject: [PATCH 279/656] Added C-HR Hybrid engine f/w (#1695) @joxaarol#2418's 2020 C-HR Hybrid DongleID b7087e3bfd3a9cf6 https://discord.com/channels/469524606043160576/524592892627517450/721373655174742086 I also alphanumerically sorted the engine firmwares as a best practice, and to be consistent. --- selfdrive/car/toyota/values.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index a0aeea6ea0..40548e39f8 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -459,8 +459,9 @@ FW_VERSIONS = { }, CAR.CHRH: { (Ecu.engine, 0x700, None): [ - b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x0289663F423000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0189663F438000\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152610040\x00\x00\x00\x00\x00\x00', From 981a166a7c8e2305870993480b9804ba2420319b Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 14 Jun 2020 23:31:36 +0800 Subject: [PATCH 280/656] remove duplite #include (#1697) --- selfdrive/locationd/ublox_msg.cc | 1 - selfdrive/locationd/ubloxd.cc | 1 - selfdrive/locationd/ubloxd_main.cc | 1 - selfdrive/locationd/ubloxd_test.cc | 1 - 4 files changed, 4 deletions(-) diff --git a/selfdrive/locationd/ublox_msg.cc b/selfdrive/locationd/ublox_msg.cc index 74c1f28d52..0bc8c0e6ff 100644 --- a/selfdrive/locationd/ublox_msg.cc +++ b/selfdrive/locationd/ublox_msg.cc @@ -6,7 +6,6 @@ #include #include #include -#include #include #include #include diff --git a/selfdrive/locationd/ubloxd.cc b/selfdrive/locationd/ubloxd.cc index 13420f05a5..4ffc010f3e 100644 --- a/selfdrive/locationd/ubloxd.cc +++ b/selfdrive/locationd/ubloxd.cc @@ -7,7 +7,6 @@ #include #include #include -#include #include #include #include diff --git a/selfdrive/locationd/ubloxd_main.cc b/selfdrive/locationd/ubloxd_main.cc index 43989a338a..d409d64158 100644 --- a/selfdrive/locationd/ubloxd_main.cc +++ b/selfdrive/locationd/ubloxd_main.cc @@ -7,7 +7,6 @@ #include #include #include -#include #include #include #include diff --git a/selfdrive/locationd/ubloxd_test.cc b/selfdrive/locationd/ubloxd_test.cc index b63e26b82d..8653cedeab 100644 --- a/selfdrive/locationd/ubloxd_test.cc +++ b/selfdrive/locationd/ubloxd_test.cc @@ -7,7 +7,6 @@ #include #include #include -#include #include #include #include From 1d9920a1773041df9938e9f20066bbf35903f6bb Mon Sep 17 00:00:00 2001 From: Michael Honan Date: Mon, 15 Jun 2020 11:17:29 +1000 Subject: [PATCH 281/656] Impreza 2018-20 should be 2017-20 (#1701) --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 80c48babee..2ffe99daec 100644 --- a/README.md +++ b/README.md @@ -157,7 +157,7 @@ Community Maintained Cars and Features | Nissan | Rogue 20192 | Propilot | Stock | 0mph | 0mph | | Nissan | X-Trail 20172 | Propilot | Stock | 0mph | 0mph | | Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | -| Subaru | Impreza 2018-20 | EyeSight | Stock | 0mph | 0mph | +| Subaru | Impreza 2017-20 | EyeSight | Stock | 0mph | 0mph | | Volkswagen| Golf 2015-19 | Driver Assistance | Stock | 0mph | 0mph | 1Requires a [panda](https://comma.ai/shop/products/panda-obd-ii-dongle) and [community built giraffe](https://zoneos.com/volt/). ***NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).***
From 224672705c6bc5e7476275648813d39e17d3e476 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Mon, 15 Jun 2020 11:45:37 -0700 Subject: [PATCH 282/656] Hyundai Ioniq EV LTD (#1694) * add ioniq * bump panda * test route * bump pnada --- README.md | 1 + panda | 2 +- selfdrive/car/hyundai/carstate.py | 34 ++++++++++++++++++++++-------- selfdrive/car/hyundai/interface.py | 11 +++++++++- selfdrive/car/hyundai/values.py | 9 +++++++- selfdrive/test/test_car_models.py | 12 +++++++---- 6 files changed, 53 insertions(+), 16 deletions(-) diff --git a/README.md b/README.md index 2ffe99daec..5fee0d2acf 100644 --- a/README.md +++ b/README.md @@ -141,6 +141,7 @@ Community Maintained Cars and Features | Holden | Astra 20171 | Adaptive Cruise | openpilot | 0mph | 7mph | | Hyundai | Elantra 2017-192 | SCC + LKAS | Stock | 19mph | 34mph | | Hyundai | Genesis 2015-162 | SCC + LKAS | Stock | 19mph | 37mph | +| Hyundai | Ioniq 2019 Electric | SCC + LKAS | Stock | 0mph | 32mph | | Hyundai | Kona 2017-192 | SCC + LKAS | Stock | 22mph | 0mph | | Hyundai | Kona 2019 EV2 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Palisade 20202 | All | Stock | 0mph | 0mph | diff --git a/panda b/panda index d0442fd1e4..abb229c9e7 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit d0442fd1e45589880c12b27c8a744cd1f540f540 +Subproject commit abb229c9e7a25418db7e2eee8308de15ffb496af diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index f252ce7911..6a7bc6bcf0 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -1,5 +1,5 @@ from cereal import car -from selfdrive.car.hyundai.values import DBC, STEER_THRESHOLD, FEATURES +from selfdrive.car.hyundai.values import DBC, STEER_THRESHOLD, FEATURES, EV_HYBRID from selfdrive.car.interfaces import CarStateBase from opendbc.can.parser import CANParser from selfdrive.config import Conversions as CV @@ -54,9 +54,12 @@ class CarState(CarStateBase): # TODO: Check this ret.brakeLights = bool(cp.vl["TCS13"]['BrakeLight'] or ret.brakePressed) - #TODO: find pedal signal for EV/HYBRID Cars - ret.gas = cp.vl["EMS12"]['PV_AV_CAN'] / 100 - ret.gasPressed = bool(cp.vl["EMS16"]["CF_Ems_AclAct"]) + if self.CP.carFingerprint in EV_HYBRID: + ret.gas = cp.vl["E_EMS11"]['Accel_Pedal_Pos'] / 256. + ret.gasPressed = ret.gas > 0 + else: + ret.gas = cp.vl["EMS12"]['PV_AV_CAN'] / 100 + ret.gasPressed = bool(cp.vl["EMS16"]["CF_Ems_AclAct"]) # TODO: refactor gear parsing in function # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, @@ -180,9 +183,6 @@ class CarState(CarStateBase): ("SCCInfoDisplay", "SCC11", 0), ("ACC_ObjDist", "SCC11", 0), ("ACCMode", "SCC12", 1), - - ("PV_AV_CAN", "EMS12", 0), - ("CF_Ems_AclAct", "EMS16", 0), ] checks = [ @@ -198,9 +198,25 @@ class CarState(CarStateBase): ("SAS11", 100), ("SCC11", 50), ("SCC12", 50), - ("EMS12", 100), - ("EMS16", 100), ] + + if CP.carFingerprint in EV_HYBRID: + signals += [ + ("Accel_Pedal_Pos", "E_EMS11", 0), + ] + checks += [ + ("E_EMS11", 50), + ] + else: + signals += [ + ("PV_AV_CAN", "EMS12", 0), + ("CF_Ems_AclAct", "EMS16", 0), + ] + checks += [ + ("EMS12", 100), + ("EMS16", 100), + ] + if CP.carFingerprint in FEATURES["use_cluster_gears"]: signals += [ ("CF_Clu_InhibitD", "CLU15", 0), diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index e3bbc0f71a..07c339ffcb 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -126,6 +126,15 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + elif candidate == CAR.IONIQ_EV_LTD: + ret.lateralTuning.pid.kf = 0.00006 + ret.mass = 1490. + STD_CARGO_KG #weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx + ret.wheelbase = 2.7 + ret.steerRatio = 13.73 #Spec + tire_stiffness_factor = 0.385 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.KIA_FORTE: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3558. * CV.LB_TO_KG @@ -136,7 +145,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] # these cars require a special panda safety mode due to missing counters and checksums in the messages - if candidate in [CAR.HYUNDAI_GENESIS]: + if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD]: ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy ret.centerToFront = ret.wheelbase * 0.4 diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 14bff6625e..3bb17f0e5a 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -20,6 +20,7 @@ class CAR: GENESIS_G80 = "GENESIS G80 2017" GENESIS_G90 = "GENESIS G90 2017" HYUNDAI_GENESIS = "HYUNDAI GENESIS 2015-2016" + IONIQ_EV_LTD = "HYUNDAI IONIQ ELECTRIC LIMITED 2019" KIA_FORTE = "KIA FORTE E 2018" KIA_OPTIMA = "KIA OPTIMA SX 2019 & 2016" KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019" @@ -109,6 +110,9 @@ FINGERPRINTS = { CAR.GENESIS_G90: [{ 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1162: 4, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2003: 8, 2004: 8, 2005: 8, 2008: 8, 2011: 8, 2012: 8, 2013: 8 }], + CAR.IONIQ_EV_LTD: [{ + 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1425: 2, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1507: 8, 1535: 8 + }], CAR.KONA: [{ 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 909: 8, 916: 8, 1040: 8, 1078: 4, 1107: 5, 1136: 8, 1156: 8, 1170: 8, 1173: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 2004: 8, 2009: 8, 2012: 8 }], @@ -197,15 +201,18 @@ CHECKSUM = { FEATURES = { "use_cluster_gears": [CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30], # Use Cluster for Gear Selection, rather than Transmission "use_tcu_gears": [CAR.KIA_OPTIMA, CAR.SONATA_2019], # Use TCU Message for Gear Selection - "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.KONA_EV], # Use TCU Message for Gear Selection + "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV], # Use TCU Message for Gear Selection } +EV_HYBRID = [CAR.IONIQ_EV_LTD] + DBC = { CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None), CAR.ELANTRA_GT_I30: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G80: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G90: dbc_dict('hyundai_kia_generic', None), CAR.HYUNDAI_GENESIS: dbc_dict('hyundai_kia_generic', None), + CAR.IONIQ_EV_LTD: dbc_dict('hyundai_kia_generic', None), CAR.KIA_FORTE: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 5c8d900624..0a6cc6af4d 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -192,6 +192,10 @@ routes = { 'carFingerprint': HYUNDAI.PALISADE, 'enableCamera': True, }, + "610ebb9faaad6b43|2020-06-13--15-28-36": { + 'carFingerprint': HYUNDAI.IONIQ_EV_LTD, + 'enableCamera': True, + }, "f7b6be73e3dfd36c|2019-05-12--18-07-16": { 'carFingerprint': TOYOTA.AVALON, 'enableCamera': False, @@ -364,14 +368,14 @@ routes = { 'carFingerprint': NISSAN.LEAF, 'enableCamera': True, }, - "32a319f057902bb3|2020-04-27--15-18-58": { - 'carFingerprint': MAZDA.CX5, - 'enableCamera': True, - }, "059ab9162e23198e|2020-05-30--09-41-01": { 'carFingerprint': NISSAN.ROGUE, 'enableCamera': True, }, + "32a319f057902bb3|2020-04-27--15-18-58": { + 'carFingerprint': MAZDA.CX5, + 'enableCamera': True, + }, } passive_routes: List[str] = [ From 10cb6ab87ab812ada7c26d5b67d95a739d8d3b54 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 15 Jun 2020 13:31:28 -0700 Subject: [PATCH 283/656] dont conflate in ubloxd --- selfdrive/locationd/ubloxd_main.cc | 23 +++++++++++++++++++---- 1 file changed, 19 insertions(+), 4 deletions(-) diff --git a/selfdrive/locationd/ubloxd_main.cc b/selfdrive/locationd/ubloxd_main.cc index d409d64158..d869c85196 100644 --- a/selfdrive/locationd/ubloxd_main.cc +++ b/selfdrive/locationd/ubloxd_main.cc @@ -27,7 +27,6 @@ void set_do_exit(int sig) { } using namespace ublox; -const long ZMQ_POLL_TIMEOUT = 1000; // In miliseconds int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) { LOGW("starting ubloxd"); signal(SIGINT, (sighandler_t) set_do_exit); @@ -35,13 +34,25 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) UbloxMsgParser parser; - SubMaster sm({"ubloxRaw"}); + Context * context = Context::create(); + SubSocket * subscriber = SubSocket::create(context, "ubloxRaw"); + assert(subscriber != NULL); + PubMaster pm({"ubloxGnss", "gpsLocationExternal"}); while (!do_exit) { - if (sm.update(ZMQ_POLL_TIMEOUT) == 0) continue; + Message * msg = subscriber->receive(); + if (!msg){ + continue; + } + + auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), msg->getData(), msg->getSize()); + + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + auto ubloxRaw = event.getUbloxRaw(); - auto ubloxRaw = sm["ubloxRaw"].getUbloxRaw(); const uint8_t *data = ubloxRaw.begin(); size_t len = ubloxRaw.size(); size_t bytes_consumed = 0; @@ -93,7 +104,11 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) } bytes_consumed += bytes_consumed_this_time; } + free(msg); } + delete subscriber; + delete context; + return 0; } From 8cacc14b3180e831ed4fa0782102f973efe8851f Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 16 Jun 2020 06:26:38 +0800 Subject: [PATCH 284/656] Sound refactor (#1589) * Soud refactor * remove files from files_common * add timeout to set_volumn * add param volume to init * done * test.cc * fix typo * add repeat param instead of loop * revert submodule * add member function currentSound * remove function create_player from class member * fix build error fix repeat * rename CHECK_RESULT to ReturnOnError * set currentSound_ before posible err * use std::map to initialize sound table cleanup cleanup cleanup fix bug in stop change paramater name * done * remove function CreatePlayer, create player in init() * resolve conflict * remove sound test * rebase * remove whitespace * Apply great review suggestion * use player's SLVolumeItf interface to set volume * use float * leave the volume control the way it is --- release/files_common | 2 - selfdrive/ui/SConscript | 2 +- selfdrive/ui/linux.cc | 13 +- selfdrive/ui/slplay.c | 184 -------------------------- selfdrive/ui/slplay.h | 21 --- selfdrive/ui/sound.cc | 182 +++++++++++++++---------- selfdrive/ui/sound.hpp | 38 ++++-- selfdrive/ui/test/build_play_sound.sh | 3 - selfdrive/ui/test/play_sound.c | 37 ------ selfdrive/ui/ui.cc | 42 ++---- selfdrive/ui/ui.hpp | 12 +- 11 files changed, 159 insertions(+), 377 deletions(-) delete mode 100644 selfdrive/ui/slplay.c delete mode 100644 selfdrive/ui/slplay.h delete mode 100755 selfdrive/ui/test/build_play_sound.sh delete mode 100644 selfdrive/ui/test/play_sound.c diff --git a/release/files_common b/release/files_common index 7ef893ebc5..9728a0c4a6 100644 --- a/release/files_common +++ b/release/files_common @@ -322,9 +322,7 @@ selfdrive/test/test_fingerprints.py selfdrive/test/test_car_models.py selfdrive/ui/SConscript -selfdrive/ui/*.c selfdrive/ui/*.cc -selfdrive/ui/*.h selfdrive/ui/*.hpp selfdrive/ui/ui selfdrive/ui/spinner/Makefile diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 88bde059ea..8f22824fbb 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -4,7 +4,7 @@ src = ['ui.cc', 'paint.cc', 'sidebar.cc', '#phonelibs/nanovg/nanovg.c'] libs = [common, 'zmq', 'czmq', 'capnp', 'kj', 'm', cereal, messaging, gpucommon, visionipc] if arch == "aarch64": - src += ['sound.cc', 'slplay.c'] + src += ['sound.cc'] libs += ['EGL', 'GLESv3', 'gnustl_shared', 'log', 'utils', 'gui', 'hardware', 'ui', 'CB', 'gsl', 'adreno_utils', 'OpenSLES', 'cutils', 'uuid', 'OpenCL'] linkflags = ['-Wl,-rpath=/system/lib64,-rpath=/system/comma/usr/lib'] else: diff --git a/selfdrive/ui/linux.cc b/selfdrive/ui/linux.cc index 17a3938f75..97fe769e0a 100644 --- a/selfdrive/ui/linux.cc +++ b/selfdrive/ui/linux.cc @@ -82,13 +82,12 @@ int touch_read(TouchState *s, int* out_x, int* out_y) { #include "sound.hpp" -void ui_sound_init() {} -void ui_sound_destroy() {} - -void set_volume(int volume) {} - -void play_alert_sound(AudibleAlert alert) {} -void stop_alert_sound(AudibleAlert alert) {} +bool Sound::init(int volume) { return true; } +bool Sound::play(AudibleAlert alert, int repeat) { return true; } +void Sound::stop() {} +void Sound::setVolume(int volume, int timeout_seconds) {} +AudibleAlert Sound::currentPlaying() { return AudibleAlert::NONE; } +Sound::~Sound() {} #include "common/visionimg.h" #include diff --git a/selfdrive/ui/slplay.c b/selfdrive/ui/slplay.c deleted file mode 100644 index ddfbad56c5..0000000000 --- a/selfdrive/ui/slplay.c +++ /dev/null @@ -1,184 +0,0 @@ -#include -#include -#include -#include -#include - -#include "common/timing.h" -#include "slplay.h" - -SLEngineItf engineInterface = NULL; -SLObjectItf outputMix = NULL; -SLObjectItf engine = NULL; -uri_player players[32] = {{NULL, NULL, NULL}}; - -uint64_t loop_start = 0; -uint64_t loop_start_ctx = 0; - -uri_player* get_player_by_uri(const char* uri) { - for (uri_player *s = players; s->uri != NULL; s++) { - if (strcmp(s->uri, uri) == 0) { - return s; - } - } - - return NULL; -} - -uri_player* slplay_create_player_for_uri(const char* uri, char **error) { - uri_player player = { uri, NULL, NULL }; - - SLresult result; - SLDataLocator_URI locUri = {SL_DATALOCATOR_URI, (SLchar *) uri}; - SLDataFormat_MIME formatMime = {SL_DATAFORMAT_MIME, NULL, SL_CONTAINERTYPE_UNSPECIFIED}; - SLDataSource audioSrc = {&locUri, &formatMime}; - - SLDataLocator_OutputMix outMix = {SL_DATALOCATOR_OUTPUTMIX, outputMix}; - SLDataSink audioSnk = {&outMix, NULL}; - - result = (*engineInterface)->CreateAudioPlayer(engineInterface, &player.player, &audioSrc, &audioSnk, 0, NULL, NULL); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to create audio player"; - return NULL; - } - - result = (*(player.player))->Realize(player.player, SL_BOOLEAN_FALSE); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to realize audio player"; - return NULL; - } - - result = (*(player.player))->GetInterface(player.player, SL_IID_PLAY, &(player.playInterface)); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to get player interface"; - return NULL; - } - - result = (*(player.playInterface))->SetPlayState(player.playInterface, SL_PLAYSTATE_PAUSED); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to initialize playstate to SL_PLAYSTATE_PAUSED"; - return NULL; - } - - uri_player *p = players; - while (p->uri != NULL) { - p++; - } - *p = player; - - return p; -} - -void slplay_setup(char **error) { - SLresult result; - SLEngineOption engineOptions[] = {{SL_ENGINEOPTION_THREADSAFE, SL_BOOLEAN_TRUE}}; - result = slCreateEngine(&engine, 1, engineOptions, 0, NULL, NULL); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to create OpenSL engine"; - } - - result = (*engine)->Realize(engine, SL_BOOLEAN_FALSE); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to realize OpenSL engine"; - } - - result = (*engine)->GetInterface(engine, SL_IID_ENGINE, &engineInterface); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to realize OpenSL engine"; - } - - const SLInterfaceID ids[1] = {SL_IID_VOLUME}; - const SLboolean req[1] = {SL_BOOLEAN_FALSE}; - result = (*engineInterface)->CreateOutputMix(engineInterface, &outputMix, 1, ids, req); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to create output mix"; - } - - result = (*outputMix)->Realize(outputMix, SL_BOOLEAN_FALSE); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to realize output mix"; - } -} - -void slplay_destroy() { - for (uri_player *player = players; player->uri != NULL; player++) { - if (player->player) { - (*(player->player))->Destroy(player->player); - } - } - - (*outputMix)->Destroy(outputMix); - (*engine)->Destroy(engine); -} - -void slplay_stop(uri_player* player, char **error) { - SLPlayItf playInterface = player->playInterface; - SLresult result; - - // stop a loop - loop_start = 0; - - result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_PAUSED); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to set SL_PLAYSTATE_STOPPED"; - return; - } -} - -void slplay_stop_uri(const char* uri, char **error) { - uri_player* player = get_player_by_uri(uri); - slplay_stop(player, error); -} - -void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event) { - uint64_t cb_loop_start = *((uint64_t*)context); - if (event == SL_PLAYEVENT_HEADATEND && cb_loop_start == loop_start) { - (*playItf)->SetPlayState(playItf, SL_PLAYSTATE_STOPPED); - (*playItf)->SetMarkerPosition(playItf, 0); - (*playItf)->SetPlayState(playItf, SL_PLAYSTATE_PLAYING); - } -} - -void slplay_play (const char *uri, bool loop, char **error) { - SLresult result; - - uri_player* player = get_player_by_uri(uri); - if (player == NULL) { - player = slplay_create_player_for_uri(uri, error); - if (*error) { - return; - } - } - - SLPlayItf playInterface = player->playInterface; - if (loop) { - loop_start = nanos_since_boot(); - loop_start_ctx = loop_start; - result = (*playInterface)->RegisterCallback(playInterface, slplay_callback, &loop_start_ctx); - if (result != SL_RESULT_SUCCESS) { - char error[64]; - snprintf(error, sizeof(error), "Failed to register callback. %d", result); - *error = error[0]; - return; - } - - result = (*playInterface)->SetCallbackEventsMask(playInterface, SL_PLAYEVENT_HEADATEND); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to set callback event mask"; - return; - } - } - - // Reset the audio player - result = (*playInterface)->ClearMarkerPosition(playInterface); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to clear marker position"; - return; - } - result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_PAUSED); - result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_STOPPED); - result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_PLAYING); - if (result != SL_RESULT_SUCCESS) { - *error = "Failed to set SL_PLAYSTATE_PLAYING"; - } -} diff --git a/selfdrive/ui/slplay.h b/selfdrive/ui/slplay.h deleted file mode 100644 index f8c39ceeb7..0000000000 --- a/selfdrive/ui/slplay.h +++ /dev/null @@ -1,21 +0,0 @@ -#ifndef SLPLAY_H -#define SLPLAY_H - -#include -#include -#include - -typedef struct { - const char* uri; - SLObjectItf player; - SLPlayItf playInterface; -} uri_player; - -void slplay_setup(char **error); -uri_player* slplay_create_player_for_uri(const char* uri, char **error); -void slplay_play (const char *uri, bool loop, char **error); -void slplay_stop_uri (const char* uri, char **error); -void slplay_destroy(); - -#endif - diff --git a/selfdrive/ui/sound.cc b/selfdrive/ui/sound.cc index f64cde07ef..1b02f14321 100644 --- a/selfdrive/ui/sound.cc +++ b/selfdrive/ui/sound.cc @@ -1,91 +1,137 @@ -#include -#include "sound.hpp" +#include "sound.hpp" +#include +#include +#include #include "common/swaglog.h" +#include "common/timing.h" + +#define LogOnError(func, msg) \ + if ((func) != SL_RESULT_SUCCESS) { LOGW(msg); } + +#define ReturnOnError(func, msg) \ + if ((func) != SL_RESULT_SUCCESS) { LOGW(msg); return false; } + +static std::map sound_map{ + {AudibleAlert::CHIME_DISENGAGE, "../assets/sounds/disengaged.wav"}, + {AudibleAlert::CHIME_ENGAGE, "../assets/sounds/engaged.wav"}, + {AudibleAlert::CHIME_WARNING1, "../assets/sounds/warning_1.wav"}, + {AudibleAlert::CHIME_WARNING2, "../assets/sounds/warning_2.wav"}, + {AudibleAlert::CHIME_WARNING2_REPEAT, "../assets/sounds/warning_2.wav"}, + {AudibleAlert::CHIME_WARNING_REPEAT, "../assets/sounds/warning_repeat.wav"}, + {AudibleAlert::CHIME_ERROR, "../assets/sounds/error.wav"}, + {AudibleAlert::CHIME_PROMPT, "../assets/sounds/error.wav"}}; + +struct Sound::Player { + SLObjectItf player; + SLPlayItf playItf; + // slplay_callback runs on a background thread,use atomic to ensure thread safe. + std::atomic repeat; +}; -typedef struct { - AudibleAlert alert; - const char* uri; - bool loop; -} sound_file; +bool Sound::init(int volume) { + SLEngineOption engineOptions[] = {{SL_ENGINEOPTION_THREADSAFE, SL_BOOLEAN_TRUE}}; + const SLInterfaceID ids[1] = {SL_IID_VOLUME}; + const SLboolean req[1] = {SL_BOOLEAN_FALSE}; + SLEngineItf engineInterface = NULL; + ReturnOnError(slCreateEngine(&engine_, 1, engineOptions, 0, NULL, NULL), "Failed to create OpenSL engine"); + ReturnOnError((*engine_)->Realize(engine_, SL_BOOLEAN_FALSE), "Failed to realize OpenSL engine"); + ReturnOnError((*engine_)->GetInterface(engine_, SL_IID_ENGINE, &engineInterface), "Failed to get OpenSL engine interface"); + ReturnOnError((*engineInterface)->CreateOutputMix(engineInterface, &outputMix_, 1, ids, req), "Failed to create output mix"); + ReturnOnError((*outputMix_)->Realize(outputMix_, SL_BOOLEAN_FALSE), "Failed to realize output mix"); + + for (auto &kv : sound_map) { + SLDataLocator_URI locUri = {SL_DATALOCATOR_URI, (SLchar *)kv.second}; + SLDataFormat_MIME formatMime = {SL_DATAFORMAT_MIME, NULL, SL_CONTAINERTYPE_UNSPECIFIED}; + SLDataSource audioSrc = {&locUri, &formatMime}; + SLDataLocator_OutputMix outMix = {SL_DATALOCATOR_OUTPUTMIX, outputMix_}; + SLDataSink audioSnk = {&outMix, NULL}; + + SLObjectItf player = NULL; + SLPlayItf playItf = NULL; + ReturnOnError((*engineInterface)->CreateAudioPlayer(engineInterface, &player, &audioSrc, &audioSnk, 0, NULL, NULL), "Failed to create audio player"); + ReturnOnError((*player)->Realize(player, SL_BOOLEAN_FALSE), "Failed to realize audio player"); + ReturnOnError((*player)->GetInterface(player, SL_IID_PLAY, &playItf), "Failed to get player interface"); + ReturnOnError((*playItf)->SetPlayState(playItf, SL_PLAYSTATE_PAUSED), "Failed to initialize playstate to SL_PLAYSTATE_PAUSED"); + + player_[kv.first] = new Sound::Player{player, playItf}; + } -extern "C"{ -#include "slplay.h" + setVolume(volume); + return true; } -int last_volume = 0; - -void set_volume(int volume) { - if (last_volume != volume) { - char volume_change_cmd[64]; - sprintf(volume_change_cmd, "service call audio 3 i32 3 i32 %d i32 1 &", volume); - - // 5 second timeout at 60fps - int volume_changed = system(volume_change_cmd); - last_volume = volume; +AudibleAlert Sound::currentPlaying() { + if (currentSound_ != AudibleAlert::NONE) { + auto playItf = player_.at(currentSound_)->playItf; + SLuint32 state; + if (SL_RESULT_SUCCESS == (*playItf)->GetPlayState(playItf, &state) && + (state == SL_PLAYSTATE_STOPPED || state == SL_PLAYSTATE_PAUSED)) { + currentSound_ = AudibleAlert::NONE; + } } + return currentSound_; } - -sound_file sound_table[] = { - { cereal::CarControl::HUDControl::AudibleAlert::CHIME_DISENGAGE, "../assets/sounds/disengaged.wav", false }, - { cereal::CarControl::HUDControl::AudibleAlert::CHIME_ENGAGE, "../assets/sounds/engaged.wav", false }, - { cereal::CarControl::HUDControl::AudibleAlert::CHIME_WARNING1, "../assets/sounds/warning_1.wav", false }, - { cereal::CarControl::HUDControl::AudibleAlert::CHIME_WARNING2, "../assets/sounds/warning_2.wav", false }, - { cereal::CarControl::HUDControl::AudibleAlert::CHIME_WARNING2_REPEAT, "../assets/sounds/warning_2.wav", true }, - { cereal::CarControl::HUDControl::AudibleAlert::CHIME_WARNING_REPEAT, "../assets/sounds/warning_repeat.wav", true }, - { cereal::CarControl::HUDControl::AudibleAlert::CHIME_ERROR, "../assets/sounds/error.wav", false }, - { cereal::CarControl::HUDControl::AudibleAlert::CHIME_PROMPT, "../assets/sounds/error.wav", false }, - { cereal::CarControl::HUDControl::AudibleAlert::NONE, NULL, false }, -}; - -sound_file* get_sound_file(AudibleAlert alert) { - for (sound_file *s = sound_table; s->alert != cereal::CarControl::HUDControl::AudibleAlert::NONE; s++) { - if (s->alert == alert) { - return s; - } +void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event) { + Sound::Player *s = reinterpret_cast(context); + if (event == SL_PLAYEVENT_HEADATEND && s->repeat > 1) { + --s->repeat; + (*playItf)->SetPlayState(playItf, SL_PLAYSTATE_STOPPED); + (*playItf)->SetMarkerPosition(playItf, 0); + (*playItf)->SetPlayState(playItf, SL_PLAYSTATE_PLAYING); } - - return NULL; } -void play_alert_sound(AudibleAlert alert) { - sound_file* sound = get_sound_file(alert); - char* error = NULL; +bool Sound::play(AudibleAlert alert, int repeat) { + if (currentSound_ != AudibleAlert::NONE) { + stop(); + } + auto player = player_.at(alert); + SLPlayItf playItf = player->playItf; + player->repeat = repeat; + if (player->repeat > 0) { + ReturnOnError((*playItf)->RegisterCallback(playItf, slplay_callback, player), "Failed to register callback"); + ReturnOnError((*playItf)->SetCallbackEventsMask(playItf, SL_PLAYEVENT_HEADATEND), "Failed to set callback event mask"); + } - slplay_play(sound->uri, sound->loop, &error); - if(error) { - LOGW("error playing sound: %s", error); + // Reset the audio player + ReturnOnError((*playItf)->ClearMarkerPosition(playItf), "Failed to clear marker position"); + uint32_t states[] = {SL_PLAYSTATE_PAUSED, SL_PLAYSTATE_STOPPED, SL_PLAYSTATE_PLAYING}; + for (auto state : states) { + ReturnOnError((*playItf)->SetPlayState(playItf, state), "Failed to set SL_PLAYSTATE_PLAYING"); } + currentSound_ = alert; + return true; } -void stop_alert_sound(AudibleAlert alert) { - sound_file* sound = get_sound_file(alert); - char* error = NULL; - - slplay_stop_uri(sound->uri, &error); - if(error) { - LOGW("error stopping sound: %s", error); +void Sound::stop() { + if (currentSound_ != AudibleAlert::NONE) { + auto player = player_.at(currentSound_); + player->repeat = 0; + LogOnError((*(player->playItf))->SetPlayState(player->playItf, SL_PLAYSTATE_PAUSED), "Failed to set SL_PLAYSTATE_PAUSED"); + currentSound_ = AudibleAlert::NONE; } } -void ui_sound_init() { - char *error = NULL; - slplay_setup(&error); - if (error) goto fail; - - for (sound_file *s = sound_table; s->alert != cereal::CarControl::HUDControl::AudibleAlert::NONE; s++) { - slplay_create_player_for_uri(s->uri, &error); - if (error) goto fail; +void Sound::setVolume(int volume, int timeout_seconds) { + if (last_volume_ == volume) return; + + double current_time = nanos_since_boot(); + if ((current_time - last_set_volume_time_) > (timeout_seconds * (1e+9))) { + char volume_change_cmd[64]; + snprintf(volume_change_cmd, sizeof(volume_change_cmd), "service call audio 3 i32 3 i32 %d i32 1 &", volume); + system(volume_change_cmd); + last_volume_ = volume; + last_set_volume_time_ = current_time; } - return; - -fail: - LOGW(error); - exit(1); } -void ui_sound_destroy() { - slplay_destroy(); +Sound::~Sound() { + for (auto &kv : player_) { + (*(kv.second->player))->Destroy(kv.second->player); + delete kv.second; + } + if (outputMix_) (*outputMix_)->Destroy(outputMix_); + if (engine_) (*engine_)->Destroy(engine_); } - diff --git a/selfdrive/ui/sound.hpp b/selfdrive/ui/sound.hpp index ec8934ef38..6439571621 100644 --- a/selfdrive/ui/sound.hpp +++ b/selfdrive/ui/sound.hpp @@ -1,17 +1,33 @@ -#ifndef __SOUND_HPP -#define __SOUND_HPP - +#pragma once +#include #include "cereal/gen/cpp/log.capnp.h" -typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert; - -void ui_sound_init(); -void ui_sound_destroy(); +#if defined(QCOM) || defined(QCOM2) +#include +#include +#endif -void set_volume(int volume); +typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert; -void play_alert_sound(AudibleAlert alert); -void stop_alert_sound(AudibleAlert alert); +class Sound { + public: + Sound() = default; + bool init(int volume); + bool play(AudibleAlert alert, int repeat = 0); + void stop(); + void setVolume(int volume, int timeout_seconds = 5); + AudibleAlert currentPlaying(); + ~Sound(); + private: +#if defined(QCOM) || defined(QCOM2) + SLObjectItf engine_ = nullptr; + SLObjectItf outputMix_ = nullptr; + int last_volume_ = 0; + double last_set_volume_time_ = 0.; + AudibleAlert currentSound_ = AudibleAlert::NONE; + struct Player; + std::map player_; + friend void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event); #endif - +}; diff --git a/selfdrive/ui/test/build_play_sound.sh b/selfdrive/ui/test/build_play_sound.sh deleted file mode 100755 index 802bdee8fc..0000000000 --- a/selfdrive/ui/test/build_play_sound.sh +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh -clang -fPIC -o play_sound play_sound.c ../slplay.c -I ../../ -I ../ -lOpenSLES -Wl,-rpath=/system/lib64 - diff --git a/selfdrive/ui/test/play_sound.c b/selfdrive/ui/test/play_sound.c deleted file mode 100644 index 030a9f25a5..0000000000 --- a/selfdrive/ui/test/play_sound.c +++ /dev/null @@ -1,37 +0,0 @@ -#include -#include "slplay.h" - -void play_sound(char *uri, int volume) { - char **error = NULL; - printf("call slplay_setup\n"); - slplay_setup(error); - if (error) { printf("%s\n", *error); return; } - - printf("call slplay_create_player_for_uri\n"); - slplay_create_player_for_uri(uri, error); - if (error) { printf("%s\n", *error); return; } - - printf("call slplay_play\n"); - - while (1) { - char volume_change_cmd[64]; - sprintf(volume_change_cmd, "service call audio 3 i32 3 i32 %d i32 1", volume); - system(volume_change_cmd); - - slplay_play(uri, false, error); - if (error) { printf("%s\n", *error); return; } - - sleep(1); - } -} - -int main(int argc, char *argv[]) { - int volume = 10; - if (argc > 2) { - volume = atoi(argv[2]); - } - printf("setting volume to %d\n", volume); - - play_sound(argv[1], volume); - return 0; -} diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 88e3328645..bc827c3c57 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -308,16 +308,12 @@ void handle_message(UIState *s, SubMaster &sm) { if (!scene.frontview){ s->controls_seen = true; } auto alert_sound = scene.controls_state.getAlertSound(); - const auto sound_none = cereal::CarControl::HUDControl::AudibleAlert::NONE; - if (alert_sound != s->alert_sound){ - if (s->alert_sound != sound_none){ - stop_alert_sound(s->alert_sound); - } - if (alert_sound != sound_none){ - play_alert_sound(alert_sound); - s->alert_type = scene.controls_state.getAlertType(); + if (alert_sound != s->sound.currentPlaying()) { + if (alert_sound == AudibleAlert::NONE) { + s->sound.stop(); + } else { + s->sound.play(alert_sound); } - s->alert_sound = alert_sound; } scene.alert_text1 = scene.controls_state.getAlertText1(); scene.alert_text2 = scene.controls_state.getAlertText2(); @@ -411,7 +407,6 @@ void handle_message(UIState *s, SubMaster &sm) { if (!s->started) { if (s->status != STATUS_STOPPED) { update_status(s, STATUS_STOPPED); - s->alert_sound_timeout = 0; s->vision_seen = false; s->controls_seen = false; s->active_app = cereal::UiLayoutState::App::HOME; @@ -754,7 +749,6 @@ int main(int argc, char* argv[]) { TouchState touch = {0}; touch_init(&touch); s->touch_fd = touch.fd; - ui_sound_init(); // light sensor scaling params const bool LEON = util::read_file("/proc/cmdline").find("letv") != std::string::npos; @@ -774,9 +768,8 @@ int main(int argc, char* argv[]) { const int MIN_VOLUME = LEON ? 12 : 9; const int MAX_VOLUME = LEON ? 15 : 12; + assert(s->sound.init(MIN_VOLUME)); - set_volume(MIN_VOLUME); - s->volume_timeout = 5 * UI_FREQ; int draws = 0; s->scene.satelliteCount = -1; @@ -858,13 +851,7 @@ int main(int argc, char* argv[]) { should_swap = true; } - if (s->volume_timeout > 0) { - s->volume_timeout--; - } else { - int volume = fmin(MAX_VOLUME, MIN_VOLUME + s->scene.controls_state.getVEgo() / 5); // up one notch every 5 m/s - set_volume(volume); - s->volume_timeout = 5 * UI_FREQ; - } + s->sound.setVolume(fmin(MAX_VOLUME, MIN_VOLUME + s->scene.controls_state.getVEgo() / 5), 5); // up one notch every 5 m/s // If car is started and controlsState times out, display an alert if (s->controls_timeout > 0) { @@ -877,25 +864,13 @@ int main(int argc, char* argv[]) { s->scene.alert_text1 = "TAKE CONTROL IMMEDIATELY"; s->scene.alert_text2 = "Controls Unresponsive"; - ui_draw_vision_alert(s, s->scene.alert_size, s->status, s->scene.alert_text1.c_str(), s->scene.alert_text2.c_str()); - s->alert_sound_timeout = 2 * UI_FREQ; - s->alert_sound = cereal::CarControl::HUDControl::AudibleAlert::CHIME_WARNING_REPEAT; - play_alert_sound(s->alert_sound); + s->sound.play(AudibleAlert::CHIME_WARNING_REPEAT, 3); // loop sound 3 times } - - s->alert_sound_timeout--; s->controls_seen = false; } - // stop playing alert sound - if ((!s->started || (s->started && s->alert_sound_timeout == 0)) && - s->alert_sound != cereal::CarControl::HUDControl::AudibleAlert::NONE) { - stop_alert_sound(s->alert_sound); - s->alert_sound = cereal::CarControl::HUDControl::AudibleAlert::NONE; - } - read_param_timeout(&s->is_metric, "IsMetric", &s->is_metric_timeout); read_param_timeout(&s->longitudinal_control, "LongitudinalControl", &s->longitudinal_control_timeout); read_param_timeout(&s->limit_set_speed, "LimitSetSpeed", &s->limit_set_speed_timeout); @@ -928,7 +903,6 @@ int main(int argc, char* argv[]) { } set_awake(s, true); - ui_sound_destroy(); // wake up bg thread to exit pthread_mutex_lock(&s->lock); diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 2b70a9b27c..07f2428ca6 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -1,6 +1,4 @@ -#ifndef _UI_H -#define _UI_H - +#pragma once #include "messaging.hpp" #ifdef __APPLE__ @@ -214,9 +212,7 @@ typedef struct UIState { // timeouts int awake_timeout; - int volume_timeout; int controls_timeout; - int alert_sound_timeout; int speed_lim_off_timeout; int is_metric_timeout; int longitudinal_control_timeout; @@ -234,8 +230,6 @@ typedef struct UIState { bool limit_set_speed; float speed_lim_off; bool is_ego_over_limit; - std::string alert_type; - AudibleAlert alert_sound; float alert_blinking_alpha; bool alert_blinked; bool started; @@ -252,6 +246,8 @@ typedef struct UIState { model_path_vertices_data model_path_vertices[MODEL_LANE_PATH_CNT * 2]; track_vertices_data track_vertices[2]; + + Sound sound; } UIState; // API @@ -263,5 +259,3 @@ void ui_draw_image(NVGcontext *vg, float x, float y, float w, float h, int image void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGcolor color, float r = 0, int width = 0); void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint &paint, float r = 0); void ui_nvg_init(UIState *s); - -#endif From 4ca8283d739ab31e2fdbd2aeb658cb4f0d2e1bcc Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 15 Jun 2020 15:58:12 -0700 Subject: [PATCH 285/656] Modeld: loop over platforms to find CPU/GPU (#1710) * Modeld: loop over platforms to find gpu * Remove prints * PC needs CPU * Keep default for qcom * Update error message --- selfdrive/modeld/modeld.cc | 63 ++++++++++++++++++++++++++------------ tools/webcam/README.md | 1 - 2 files changed, 43 insertions(+), 21 deletions(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 7206f5a9e8..c383d5cffd 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -84,40 +84,63 @@ int main(int argc, char **argv) { PubMaster pm({"model", "cameraOdometry"}); SubMaster sm({"pathPlan"}); +#ifdef QCOM + cl_device_type device_type = CL_DEVICE_TYPE_DEFAULT; +#else + cl_device_type device_type = CL_DEVICE_TYPE_CPU; +#endif + // cl init cl_device_id device_id; cl_context context; cl_command_queue q; { - // TODO: refactor this - cl_platform_id platform_id[2]; - cl_uint num_devices; cl_uint num_platforms; + err = clGetPlatformIDs(0, NULL, &num_platforms); + assert(err == 0); - err = clGetPlatformIDs(sizeof(platform_id)/sizeof(cl_platform_id), platform_id, &num_platforms); + cl_platform_id * platform_ids = new cl_platform_id[num_platforms]; + err = clGetPlatformIDs(num_platforms, platform_ids, NULL); assert(err == 0); - #ifdef QCOM - int clPlatform = 0; - #else - // don't use nvidia on pc, it's broken - // TODO: write this nicely - int clPlatform = num_platforms-1; - #endif + LOGD("got %d opencl platform(s)", num_platforms); char cBuffer[1024]; - clGetPlatformInfo(platform_id[clPlatform], CL_PLATFORM_NAME, sizeof(cBuffer), &cBuffer, NULL); - LOG("got %d opencl platform(s), using %s", num_platforms, cBuffer); + bool opencl_platform_found = false; - err = clGetDeviceIDs(platform_id[clPlatform], CL_DEVICE_TYPE_DEFAULT, 1, - &device_id, &num_devices); - assert(err == 0); + for (size_t i = 0; i < num_platforms; i++){ + err = clGetPlatformInfo(platform_ids[i], CL_PLATFORM_NAME, sizeof(cBuffer), &cBuffer, NULL); + assert(err == 0); + LOGD("platform[%zu] CL_PLATFORM_NAME: %s", i, cBuffer); + + cl_uint num_devices; + err = clGetDeviceIDs(platform_ids[i], device_type, 0, NULL, &num_devices); + if (err != 0|| !num_devices){ + continue; + } + + // Get first device + err = clGetDeviceIDs(platform_ids[i], device_type, 1, &device_id, NULL); + assert(err == 0); + + context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); + assert(err == 0); + + q = clCreateCommandQueue(context, device_id, 0, &err); + assert(err == 0); + + opencl_platform_found = true; + break; + } + + delete[] platform_ids; + + if (!opencl_platform_found){ + LOGE("No valid openCL platform found"); + assert(opencl_platform_found); + } - context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); - assert(err == 0); - q = clCreateCommandQueue(context, device_id, 0, &err); - assert(err == 0); LOGD("opencl init complete"); } diff --git a/tools/webcam/README.md b/tools/webcam/README.md index 9243a79061..c1e7d27d07 100644 --- a/tools/webcam/README.md +++ b/tools/webcam/README.md @@ -19,7 +19,6 @@ git clone https://github.com/commaai/openpilot.git - Add line "export PYTHONPATH=$HOME/openpilot" to your ~/.bashrc - Install tensorflow 2.2 and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 - Install [OpenCL Driver](http://registrationcenter-download.intel.com/akdlm/irc_nas/vcp/15532/l_opencl_p_18.1.0.015.tgz) -- (Note: the code assumes cl platforms order to be 0.GPU/1.CPU when running clinfo; if reverse, change the -1 to -2 in selfdrive/modeld/modeld.cc#L130; helping us refactor this mess is encouraged) - Install [OpenCV4](https://www.pyimagesearch.com/2018/08/15/how-to-install-opencv-4-on-ubuntu/) (ignore the Python part) ## Build openpilot for webcam From 9e34ed4e8ccf624125177df4f3a8511d02115a86 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 15 Jun 2020 16:01:30 -0700 Subject: [PATCH 286/656] bump cereal --- cereal | 2 +- selfdrive/controls/lib/events.py | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/cereal b/cereal index 18698b113e..e0f77b2331 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 18698b113e8b7a3fda230179e3bdf837d7ba9b7e +Subproject commit e0f77b23319b15d166da6a5a5419f5428e37c20e diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index f463d3cedd..db36fe99ca 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -189,6 +189,9 @@ EVENTS = { EventName.gasPressed: {ET.PRE_ENABLE: None}, + EventName.wrongCruiseMode: {}, + EventName.laneChangeBlocked: {}, + EventName.focusRecoverActive: {}, # ********** events only containing alerts displayed in all states ********** From a34e8a64fc80eefefd85d5a4e1f3bfb7f112e96c Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Mon, 15 Jun 2020 16:37:34 -0700 Subject: [PATCH 287/656] Many readme updates --- README.md | 34 +++++++++++++++++----------------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/README.md b/README.md index 5fee0d2acf..7d29096bd5 100644 --- a/README.md +++ b/README.md @@ -117,9 +117,9 @@ Supported Cars | Toyota | Rav4 Hybrid 2019-20 | All | openpilot | 0mph | 0mph | | Toyota | Sienna 2018-20 | All | Stock3| 0mph | 0mph | -1[Comma Pedal](https://community.comma.ai/wiki/index.php/Comma_Pedal) is used to provide stop-and-go capability to some of the openpilot-supported cars that don't currently support stop-and-go. Here is how to [build a Comma Pedal](https://medium.com/@jfrux/comma-pedal-building-with-macrofab-6328bea791e8). ***NOTE: The Comma Pedal is not officially supported by [comma](https://comma.ai).***
+1[Comma Pedal](https://github.com/commaai/openpilot/wiki/comma-pedal) is used to provide stop-and-go capability to some of the openpilot-supported cars that don't currently support stop-and-go. ***NOTE: The Comma Pedal is not officially supported by [comma](https://comma.ai).***
22019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.
-3When disconnecting the Driver Support Unit (DSU), openpilot ACC will replace stock ACC. For DSU locations, see [Toyota Wiki page](https://community.comma.ai/wiki/index.php/Toyota). ***NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).***
+3When disconnecting the Driver Support Unit (DSU), openpilot ACC will replace stock ACC. ***NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).***
428mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.
Community Maintained Cars and Features @@ -135,25 +135,25 @@ Community Maintained Cars and Features | Chrysler | Pacifica 2020 | Adaptive Cruise | Stock | 0mph | 39mph | | Chrysler | Pacifica Hybrid 2017-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Chrysler | Pacifica Hybrid 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | -| Genesis | G80 20182 | All | Stock | 0mph | 0mph | +| Genesis | G80 2018 | All | Stock | 0mph | 0mph | | Genesis | G90 2018 | All | Stock | 0mph | 0mph | | GMC | Acadia Denali 20182| Adaptive Cruise | openpilot | 0mph | 7mph | | Holden | Astra 20171 | Adaptive Cruise | openpilot | 0mph | 7mph | -| Hyundai | Elantra 2017-192 | SCC + LKAS | Stock | 19mph | 34mph | -| Hyundai | Genesis 2015-162 | SCC + LKAS | Stock | 19mph | 37mph | +| Hyundai | Elantra 2017-19 | SCC + LKAS | Stock | 19mph | 34mph | +| Hyundai | Genesis 2015-16 | SCC + LKAS | Stock | 19mph | 37mph | | Hyundai | Ioniq 2019 Electric | SCC + LKAS | Stock | 0mph | 32mph | -| Hyundai | Kona 2017-192 | SCC + LKAS | Stock | 22mph | 0mph | -| Hyundai | Kona 2019 EV2 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Palisade 20202 | All | Stock | 0mph | 0mph | +| Hyundai | Kona 2017-19 | SCC + LKAS | Stock | 22mph | 0mph | +| Hyundai | Kona 2019 EV | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Palisade 2020 | All | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2019-20 | All | Stock | 0mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019 | Adaptive Cruise | Stock | 0mph | 39mph | -| Kia | Forte 2018-192 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Optima 20172 | SCC + LKAS/LDWS | Stock | 0mph | 32mph | -| Kia | Optima 20192 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Sorento 20182 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Stinger 20182 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Forte 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Optima 2017 | SCC + LKAS/LDWS | Stock | 0mph | 32mph | +| Kia | Optima 2019 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Sorento 2018 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Stinger 2018 | SCC + LKAS | Stock | 0mph | 0mph | | Nissan | Leaf 2018-192 | Propilot | Stock | 0mph | 0mph | | Nissan | Rogue 20192 | Propilot | Stock | 0mph | 0mph | | Nissan | X-Trail 20172 | Propilot | Stock | 0mph | 0mph | @@ -161,8 +161,8 @@ Community Maintained Cars and Features | Subaru | Impreza 2017-20 | EyeSight | Stock | 0mph | 0mph | | Volkswagen| Golf 2015-19 | Driver Assistance | Stock | 0mph | 0mph | -1Requires a [panda](https://comma.ai/shop/products/panda-obd-ii-dongle) and [community built giraffe](https://zoneos.com/volt/). ***NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).***
-2May require a custom connector for the developer [car harness](https://comma.ai/shop/products/car-harness)
+1Requires an [OBD-II car harness](https://comma.ai/shop/products/comma-car-harness) and [community built giraffe](https://github.com/commaai/openpilot/wiki/GM). ***NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).***
+2Requires a custom connector for the developer [car harness](https://comma.ai/shop/products/car-harness)
Although it's not upstream, there's a community of people getting openpilot to run on Tesla's [here](https://tinkla.us/) @@ -175,7 +175,7 @@ Installation Instructions Install openpilot on an EON or comma two by entering ``https://openpilot.comma.ai`` during the installer setup. -Follow these [video instructions](https://youtu.be/3nlkomHathI) to properly mount the device on the windshield. Note: openpilot features an automatic pose calibration routine and openpilot performance should not be affected by small pitch and yaw misalignments caused by imprecise device mounting. +Follow these [video instructions](https://youtu.be/lcjqxCymins) to properly mount the device on the windshield. Note: openpilot features an automatic pose calibration routine and openpilot performance should not be affected by small pitch and yaw misalignments caused by imprecise device mounting. Before placing the device on your windshield, check the state and local laws and ordinances where you drive. Some state laws prohibit or restrict the placement of objects on the windshield of a motor vehicle. @@ -278,7 +278,7 @@ openpilot is developed by [comma](https://comma.ai/) and by users like you. We w You can add support for your car by following guides we have written for [Brand](https://medium.com/@comma_ai/how-to-write-a-car-port-for-openpilot-7ce0785eda84) and [Model](https://medium.com/@comma_ai/openpilot-port-guide-for-toyota-models-e5467f4b5fe6) ports. Generally, a car with adaptive cruise control and lane keep assist is a good candidate. [Join our Discord](https://discord.comma.ai) to discuss car ports: most car makes have a dedicated channel. -Want to get paid to work on openpilot? [comma is hiring](https://comma.ai/jobs/). We also have a [bounty program](https://comma.ai/bounties.html). +Want to get paid to work on openpilot? [comma is hiring](https://comma.ai/jobs/). And [follow us on Twitter](https://twitter.com/comma_ai). From be9034b2631510ce4409c0c5c319ac6e2488a21e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Mon, 15 Jun 2020 16:49:18 -0700 Subject: [PATCH 288/656] Remove apks submodule (#1711) * remove apks submodule * missed that --- .gitignore | 2 ++ .gitmodules | 4 ---- apks | 1 - 3 files changed, 2 insertions(+), 5 deletions(-) delete mode 160000 apks diff --git a/.gitignore b/.gitignore index eae40333af..fb1cbfc0b6 100644 --- a/.gitignore +++ b/.gitignore @@ -54,6 +54,8 @@ openpilot notebooks xx panda_jungle +apks +openpilot-apks .coverage* coverage.xml diff --git a/.gitmodules b/.gitmodules index 3d228f5cd3..1e6110b7a6 100644 --- a/.gitmodules +++ b/.gitmodules @@ -7,13 +7,9 @@ [submodule "laika_repo"] path = laika_repo url = ../../commaai/laika.git -[submodule "apks"] - path = apks - url = ../../commaai/openpilot-apks.git [submodule "cereal"] path = cereal url = ../../commaai/cereal.git - [submodule "rednose_repo"] path = rednose_repo url = ../../commaai/rednose.git diff --git a/apks b/apks deleted file mode 160000 index f5d2c1715c..0000000000 --- a/apks +++ /dev/null @@ -1 +0,0 @@ -Subproject commit f5d2c1715c9482d898062110ce4c612093aa5d4f From 2afe22481348920d490daad32be1ce9898a7ab89 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 15 Jun 2020 17:20:31 -0700 Subject: [PATCH 289/656] need to do something about the valid (#1713) --- selfdrive/locationd/locationd.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 00f31b644c..155174aa60 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -7,7 +7,7 @@ import common.transformations.coordinates as coord from common.transformations.orientation import ecef_euler_from_ned, \ euler_from_quat, \ ned_euler_from_ecef, \ - quat_from_euler, \ + quat_from_euler, euler_from_rot, \ rot_from_quat, rot_from_euler from rednose.helpers import KalmanError from selfdrive.locationd.models.live_kf import LiveKalman, States, ObservationKind @@ -81,6 +81,8 @@ class Localizer(): #fix_pos_geo_std = np.abs(coord.ecef2geodetic(fix_ecef + fix_ecef_std) - fix_pos_geo) orientation_ecef = euler_from_quat(predicted_state[States.ECEF_ORIENTATION]) orientation_ecef_std = predicted_std[States.ECEF_ORIENTATION_ERR] + device_from_ecef = rot_from_quat(predicted_state[States.ECEF_ORIENTATION]).T + calibrated_orientation_ecef = euler_from_rot(calib_from_device.dot(device_from_ecef)) acc_calib = calib_from_device.dot(predicted_state[States.ACCELERATION]) acc_calib_std = np.sqrt(np.diagonal(calib_from_device.dot( @@ -91,7 +93,6 @@ class Localizer(): predicted_cov[States.ANGULAR_VELOCITY_ERR, States.ANGULAR_VELOCITY_ERR]).dot( calib_from_device.T))) - device_from_ecef = rot_from_quat(predicted_state[States.ECEF_ORIENTATION]).T vel_device = device_from_ecef.dot(vel_ecef) device_from_ecef_eul = euler_from_quat(predicted_state[States.ECEF_ORIENTATION]).T idxs = list(range(States.ECEF_ORIENTATION_ERR.start, States.ECEF_ORIENTATION_ERR.stop)) + \ @@ -133,6 +134,9 @@ class Localizer(): fix.orientationECEF.value = to_float(orientation_ecef) fix.orientationECEF.std = to_float(orientation_ecef_std) fix.orientationECEF.valid = True + fix.calibratedOrientationECEF.value = to_float(calibrated_orientation_ecef) + #fix.calibratedOrientationECEF.std = to_float(calibrated_orientation_ecef_std) + #fix.calibratedOrientationECEF.valid = True fix.orientationNED.value = to_float(orientation_ned) #fix.orientationNED.std = to_float(orientation_ned_std) #fix.orientationNED.valid = True From 637eecc2b26a6137a3415231183be54be448e638 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 15 Jun 2020 17:20:49 -0700 Subject: [PATCH 290/656] save bad calib too for display (#1678) --- selfdrive/locationd/calibrationd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index cb35763cd5..e95f00c2c9 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -88,7 +88,7 @@ class Calibrator(): end_status = self.cal_status self.just_calibrated = False - if start_status == Calibration.UNCALIBRATED and end_status == Calibration.CALIBRATED: + if start_status == Calibration.UNCALIBRATED and end_status != Calibration.UNCALIBRATED: self.just_calibrated = True def handle_v_ego(self, v_ego): From d21758939420dba7d9dba842739914432a77e024 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Mon, 15 Jun 2020 17:29:33 -0700 Subject: [PATCH 291/656] add stuff to liveloc --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index e0f77b2331..295cef4d78 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit e0f77b23319b15d166da6a5a5419f5428e37c20e +Subproject commit 295cef4d78b8795997723d8d55717c4c5e4b5865 From ed7e568b70d1de79cf741d8de4a9a79991c7239c Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 15 Jun 2020 17:55:03 -0700 Subject: [PATCH 292/656] update ref --- selfdrive/test/process_replay/ref_commit | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 8e0be9100a..5e03e2ab90 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -b85c090b3dba832b4af83a847df5b5ac2c824284 \ No newline at end of file +d21758939420dba7d9dba842739914432a77e024 \ No newline at end of file From 25688f36cc16f4a4ce57e2e6d7a5c33e78cd520f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Mon, 15 Jun 2020 18:11:50 -0700 Subject: [PATCH 293/656] Block entry on non-adaptive cruise mode (#1708) * block entry on non-adaptive cruise mode * user disable * toyota --- selfdrive/car/interfaces.py | 2 ++ selfdrive/car/toyota/carstate.py | 2 ++ selfdrive/controls/lib/events.py | 6 +++++- 3 files changed, 9 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index db6b75319a..c73aa93847 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -107,6 +107,8 @@ class CarInterfaceBase(): events.add(EventName.stockAeb) if cs_out.vEgo > MAX_CTRL_SPEED: events.add(EventName.speedTooHigh) + if cs_out.cruiseState.nonAdaptive: + events.add(EventName.wrongCruiseMode) if cs_out.steerError: events.add(EventName.steerUnavailable) diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 1c8c3735d7..02bd893eeb 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -90,6 +90,8 @@ class CarState(CarStateBase): else: ret.cruiseState.standstill = self.pcm_acc_status == 7 ret.cruiseState.enabled = bool(cp.vl["PCM_CRUISE"]['CRUISE_ACTIVE']) + # TODO: CRUISE_STATE is a 4 bit signal, find any other non-adaptive cruise states + ret.cruiseState.nonAdaptive = cp.vl["PCM_CRUISE"]['CRUISE_STATE'] in [5] if self.CP.carFingerprint == CAR.PRIUS: ret.genericToggle = cp.vl["AUTOPARK_STATUS"]['STATE'] != 0 diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index db36fe99ca..7d1895e038 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -189,7 +189,6 @@ EVENTS = { EventName.gasPressed: {ET.PRE_ENABLE: None}, - EventName.wrongCruiseMode: {}, EventName.laneChangeBlocked: {}, EventName.focusRecoverActive: {}, @@ -485,6 +484,11 @@ EVENTS = { duration_hud_alert=0.), }, + EventName.wrongCruiseMode: { + ET.USER_DISABLE: EngagementAlert(AudibleAlert.chimeDisengage), + ET.NO_ENTRY: NoEntryAlert("Enable Adaptive Cruise"), + }, + EventName.steerTempUnavailable: { ET.WARNING: Alert( "TAKE CONTROL", From f418794e40798f7c4a1b6a1496878d755bd2746c Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 15 Jun 2020 18:53:09 -0700 Subject: [PATCH 294/656] Add Accord FW version --- selfdrive/car/honda/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 0b2fb4fd32..c5b6d2c2f3 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -178,6 +178,7 @@ FW_VERSIONS = { b'57114-TVA-C060\x00\x00', ], (Ecu.eps, 0x18da30f1, None): [ + b'39990-TVA,A150\x00\x00', b'39990-TVA-A150\x00\x00', b'39990-TVA-A160\x00\x00', b'39990-TVA-X030\x00\x00', From 3335f6b48c8b0988a230f00cd6a4158b447533b1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 15 Jun 2020 21:18:40 -0700 Subject: [PATCH 295/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index abb229c9e7..e13774ba8c 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit abb229c9e7a25418db7e2eee8308de15ffb496af +Subproject commit e13774ba8c36297d7213fe41690f8f120ff43c23 From 80101b350b1f3de13d546bc0a45874e8132de2db Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Tue, 16 Jun 2020 10:36:04 -0700 Subject: [PATCH 296/656] modeld process time logging to DEBUG (#1720) Co-authored-by: Jason Young --- selfdrive/modeld/modeld.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index c383d5cffd..e5cbc02223 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -216,7 +216,7 @@ int main(int argc, char **argv) { model_publish(pm, extra.frame_id, model_buf, extra.timestamp_eof); posenet_publish(pm, extra.frame_id, model_buf, extra.timestamp_eof); - LOG("model process: %.2fms, from last %.2fms", mt2-mt1, mt1-last); + LOGD("model process: %.2fms, from last %.2fms", mt2-mt1, mt1-last); last = mt1; } From fed9325d226e29282d7da9a873dbe6b2bd8ee4a1 Mon Sep 17 00:00:00 2001 From: George Hotz Date: Tue, 16 Jun 2020 12:00:40 -0700 Subject: [PATCH 297/656] neos update for only kernel --- installer/updater/update_kernel.json | 7 +++++++ 1 file changed, 7 insertions(+) create mode 100644 installer/updater/update_kernel.json diff --git a/installer/updater/update_kernel.json b/installer/updater/update_kernel.json new file mode 100644 index 0000000000..9e1383dc92 --- /dev/null +++ b/installer/updater/update_kernel.json @@ -0,0 +1,7 @@ +{ + "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-3f9cfbd4f70a19463a34b232704d506b1df0a10c59f6608db7e9d1829aec9b38-kernel.zip", + "ota_hash": "3f9cfbd4f70a19463a34b232704d506b1df0a10c59f6608db7e9d1829aec9b38", + "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-97c27e6ed04ed6bb0608b845a2d4100912093f9380c3f2ba6b56bccd608e5f6e.img", + "recovery_len": 15861036, + "recovery_hash": "97c27e6ed04ed6bb0608b845a2d4100912093f9380c3f2ba6b56bccd608e5f6e" +} From 6c156d7f45ee21f77fbafcb9867fb0712adb53f5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Tue, 16 Jun 2020 12:21:41 -0700 Subject: [PATCH 298/656] NEOS update required alert (#1722) * NEOS update required * permanent alert * bump cereal --- cereal | 2 +- selfdrive/controls/controlsd.py | 5 +++++ selfdrive/controls/lib/events.py | 9 +++++++++ 3 files changed, 15 insertions(+), 1 deletion(-) diff --git a/cereal b/cereal index 295cef4d78..c0c3cc16b2 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 295cef4d78b8795997723d8d55717c4c5e4b5865 +Subproject commit c0c3cc16b2ee2aafa7d13b67563463be663c240c diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index e03c2ed002..4f2ec6b3c4 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -1,6 +1,7 @@ #!/usr/bin/env python3 import os import gc +import subprocess from cereal import car, log from common.numpy_fast import clip from common.realtime import sec_since_boot, set_realtime_priority, set_core_affinity, Ratekeeper, DT_CTRL @@ -142,6 +143,10 @@ class Controls: if hw_type == HwType.whitePanda: self.events.add(EventName.whitePandaUnsupported, static=True) + uname = subprocess.check_output(["uname", "-v"], encoding='utf8').strip() + if uname == "#1 SMP PREEMPT Wed Jun 10 12:40:53 PDT 2020": + self.events.add(EventName.neosUpdateRequired, static=True) + # controlsd is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) self.prof = Profiler(False) # off by default diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 7d1895e038..0c56c04bb2 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -517,6 +517,15 @@ EVENTS = { ET.NO_ENTRY: NoEntryAlert("Speed Too Low"), }, + EventName.neosUpdateRequired: { + ET.PERMANENT: Alert( + "NEOS Update Required", + "Please Wait for Update", + AlertStatus.normal, AlertSize.mid, + Priority.HIGHEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + ET.NO_ENTRY: NoEntryAlert("NEOS Update Required"), + }, + EventName.sensorDataInvalid: { ET.PERMANENT: Alert( "No Data from Device Sensors", From 58c1504f1a54b3c544b20d5c82f4e90e88276d8a Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Tue, 16 Jun 2020 14:51:55 -0700 Subject: [PATCH 299/656] Revert broken NEOS kernel (#1723) * untested * bump kernel --- installer/updater/update_kernel.json | 4 ++-- launch_chffrplus.sh | 4 ++++ 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/installer/updater/update_kernel.json b/installer/updater/update_kernel.json index 9e1383dc92..41dc595b00 100644 --- a/installer/updater/update_kernel.json +++ b/installer/updater/update_kernel.json @@ -1,6 +1,6 @@ { - "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-3f9cfbd4f70a19463a34b232704d506b1df0a10c59f6608db7e9d1829aec9b38-kernel.zip", - "ota_hash": "3f9cfbd4f70a19463a34b232704d506b1df0a10c59f6608db7e9d1829aec9b38", + "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-3bd2b3bdd6a501569e00b8f12786d65e0fd2788c0dd238f8c986e3e2e504683a-kernel.zip", + "ota_hash": "3bd2b3bdd6a501569e00b8f12786d65e0fd2788c0dd238f8c986e3e2e504683a", "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-97c27e6ed04ed6bb0608b845a2d4100912093f9380c3f2ba6b56bccd608e5f6e.img", "recovery_len": 15861036, "recovery_hash": "97c27e6ed04ed6bb0608b845a2d4100912093f9380c3f2ba6b56bccd608e5f6e" diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 0985f0845e..60102fbd71 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -93,6 +93,10 @@ function launch { rm -r $BASEDIR/.sconsign.dblite fi "$DIR/installer/updater/updater" "file://$DIR/installer/updater/update.json" + else + if [[ $(uname -v) == "#1 SMP PREEMPT Wed Jun 10 12:40:53 PDT 2020" ]]; then + "$DIR/installer/updater/updater" "file://$DIR/installer/updater/update_kernel.json" + fi fi From dbc609b240e598b06aec82c25d761d18d9c022ee Mon Sep 17 00:00:00 2001 From: Scott Adair Date: Tue, 16 Jun 2020 21:35:42 -0400 Subject: [PATCH 300/656] ESP Firmware for Hyundai Palisade (#1728) --- selfdrive/car/hyundai/values.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 3bb17f0e5a..6963a16c6c 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -185,7 +185,10 @@ FW_VERSIONS = { }, CAR.PALISADE: { (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 \xf1\xa01.04',], - (Ecu.esp, 0x7d1, None): [b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330',], + (Ecu.esp, 0x7d1, None): [ + b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330', + b'\xf1\x00LX ESC \v 102\x19\x05\a 58910-S8330\xf1\xa01.02', + ], (Ecu.engine, 0x7e0, None): [b'\xf1\x81640J0051\x00\x00\x00\x00\x00\x00\x00\x00',], (Ecu.eps, 0x7d4, None): [b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103',], (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125',], From 2a9b5b395c0efc583b925632d122ba5ad9aa745b Mon Sep 17 00:00:00 2001 From: Johannes Schmitz Date: Thu, 18 Jun 2020 02:53:17 +0200 Subject: [PATCH 301/656] Clarify shortcut usage in Carla simulation mode (#1724) The keys to control openpilot have to be pressed with focus on the terminal running the Carla bridge. Also improve table formatting. --- tools/sim/README.md | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/tools/sim/README.md b/tools/sim/README.md index 4b64d4a8d2..06cb03907a 100644 --- a/tools/sim/README.md +++ b/tools/sim/README.md @@ -10,31 +10,31 @@ git clone https://github.com/commaai/openpilot.git # Add export PYTHONPATH=$HOME/openpilot to your bashrc # Have a working tensorflow+keras in python3.7.3 (with [packages] in openpilot/Pipfile) ``` -## Install (in tab 1) +## Install (in terminal 1) ``` cd ~/openpilot/tools/sim ./start_carla.sh # install CARLA 0.9.7 and start the server ``` -## openpilot (in tab 2) +## openpilot (in terminal 2) ``` cd ~/openpilot/selfdrive/ PASSIVE=0 NOBOARD=1 ./manager.py ``` -## bridge (in tab 3) +## bridge (in terminal 3) ``` # links carla to openpilot, will "start the car" according to manager cd ~/openpilot/tools/sim ./bridge.py ``` ## Controls -Now you can control the simulator with the keys: - -1: Cruise up 5 mph - -2: Cruise down 5 mph - -3: Cruise cancel - -q: Exit all +Now put the focus on the terminal running bridge.py and you can control +openpilot driving in the simulation with the following keys + +| key | functionality | +| :---: | :---------------: | +| 1 | Cruise up 5 mph | +| 2 | Cruise down 5 mph | +| 3 | Cruise cancel | +| q | Exit all | From 08f715f176f6240ad91220f97d1d656c0beaf831 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 17 Jun 2020 23:24:36 -0700 Subject: [PATCH 302/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index e13774ba8c..5b14945140 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit e13774ba8c36297d7213fe41690f8f120ff43c23 +Subproject commit 5b1494514042721b63f71254700ddcf94dbbd9c7 From ee2f60f1cc1d95ba7b4288af143fc6f7132ab728 Mon Sep 17 00:00:00 2001 From: eFini Date: Fri, 19 Jun 2020 01:31:42 +1000 Subject: [PATCH 303/656] remove dpulicated firmware id, already existed 3 lines above (#1736) --- selfdrive/car/honda/values.py | 1 - 1 file changed, 1 deletion(-) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index c5b6d2c2f3..baa174f7a5 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -469,7 +469,6 @@ FW_VERSIONS = { b'39990-TGG-A020\x00\x00', b'39990-TGG-A120\x00\x00', b'39990-TGL-E130\x00\x00', - b'39990-TGG-A020\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ b'77959-TBA-A060\x00\x00', From bbb6fa1172b11cb890e60c7c7c5db19d5fb220c5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Thu, 18 Jun 2020 11:48:28 -0700 Subject: [PATCH 304/656] Remove logentries from pyextra (#1721) * remove logentries from pyextra * update release files * gitignore --- pyextra/logentries/__init__.py | 1 - pyextra/logentries/helpers.py | 49 -------- pyextra/logentries/metrics.py | 57 --------- pyextra/logentries/utils.py | 218 --------------------------------- release/files_common | 2 +- 5 files changed, 1 insertion(+), 326 deletions(-) delete mode 100644 pyextra/logentries/__init__.py delete mode 100644 pyextra/logentries/helpers.py delete mode 100644 pyextra/logentries/metrics.py delete mode 100644 pyextra/logentries/utils.py diff --git a/pyextra/logentries/__init__.py b/pyextra/logentries/__init__.py deleted file mode 100644 index b64e423b8b..0000000000 --- a/pyextra/logentries/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from .utils import LogentriesHandler diff --git a/pyextra/logentries/helpers.py b/pyextra/logentries/helpers.py deleted file mode 100644 index bec676e22a..0000000000 --- a/pyextra/logentries/helpers.py +++ /dev/null @@ -1,49 +0,0 @@ - -""" This file contains some helpers methods in both Python2 and 3 """ -import sys -import re - -if sys.version < '3': - # Python2.x imports - import Queue - import codecs -else: - # Python 3.x imports - import queue - - -def check_token(token): - """ Checks if the given token is a valid UUID.""" - valid = re.compile(r"^[0-9a-fA-F]{8}-[0-9a-fA-F]{4}-" - r"[0-9a-fA-F]{4}-[0-9a-fA-F]{4}-[0-9a-fA-F]{12}$") - - return valid.match(token) - -# We need to do some things different pending if its Python 2.x or 3.x -if sys.version < '3': - def to_unicode(ch): - return codecs.unicode_escape_decode(ch)[0] - - def is_unicode(ch): - return isinstance(ch, unicode) - - def create_unicode(ch): - try: - return unicode(ch, 'utf-8') - except UnicodeDecodeError as e: - return str(e) - - def create_queue(max_size): - return Queue.Queue(max_size) -else: - def to_unicode(ch): - return ch - - def is_unicode(ch): - return isinstance(ch, str) - - def create_unicode(ch): - return str(ch) - - def create_queue(max_size): - return queue.Queue(max_size) diff --git a/pyextra/logentries/metrics.py b/pyextra/logentries/metrics.py deleted file mode 100644 index 03ddb64374..0000000000 --- a/pyextra/logentries/metrics.py +++ /dev/null @@ -1,57 +0,0 @@ -from logentries import LogentriesHandler -from threading import Lock -from functools import wraps -import logging -import time -import sys -import psutil - -glob_time = 0 -glob_name = 0 - -log = logging.getLogger('logentries') -log.setLevel(logging.INFO) - -class Metric(object): - - def __init__(self, token): - self._count = 0.0 - self._sum = 0.0 - self._lock = Lock() - self.token = token - handler = LogentriesHandler(token) - log.addHandler(handler) - - def observe(self, amount): - with self._lock: - self._count += 1 - self._sum += amount - - def metric(self): - '''Mesaure function execution time in seconds - and forward it to Logentries''' - - class Timer(object): - - def __init__(self, summary): - self._summary = summary - - def __enter__(self): - self._start = time.time() - - def __exit__(self, typ, value, traceback): - global glob_time - self._summary.observe(max(time.time() - self._start, 0)) - glob_time = time.time()- self._start - log.info("function_name=" + glob_name + " " + "execution_time=" + str(glob_time) + " " + "cpu=" + str(psutil.cpu_percent(interval=None)) + " " + "cpu_count=" + str(psutil.cpu_count())+ " " + "memory=" + str(psutil.virtual_memory()) ) - - def __call__(self, f): - @wraps(f) - def wrapped(*args, **kwargs): - with self: - global glob_name - glob_name = f.__name__ - - return f(*args, **kwargs) - return wrapped - return Timer(self) diff --git a/pyextra/logentries/utils.py b/pyextra/logentries/utils.py deleted file mode 100644 index c17a1070cd..0000000000 --- a/pyextra/logentries/utils.py +++ /dev/null @@ -1,218 +0,0 @@ -# coding: utf-8 -# vim: set ts=4 sw=4 et: -""" This file contains some utils for connecting to Logentries - as well as storing logs in a queue and sending them.""" - -VERSION = '2.0.7' - -from logentries import helpers as le_helpers - -import logging -import threading -import socket -import random -import time -import sys - -import certifi - - -# Size of the internal event queue -QUEUE_SIZE = 32768 -# Logentries API server address -LE_API_DEFAULT = "data.logentries.com" -# Port number for token logging to Logentries API server -LE_PORT_DEFAULT = 80 -LE_TLS_PORT_DEFAULT = 443 -# Minimal delay between attempts to reconnect in seconds -MIN_DELAY = 0.1 -# Maximal delay between attempts to recconect in seconds -MAX_DELAY = 10 -# Unicode Line separator character \u2028 -LINE_SEP = le_helpers.to_unicode('\u2028') - - -# LE appender signature - used for debugging messages -LE = "LE: " -# Error message displayed when an incorrect Token has been detected -INVALID_TOKEN = ("\n\nIt appears the LOGENTRIES_TOKEN " - "parameter you entered is incorrect!\n\n") - - -def dbg(msg): - print(LE + msg) - - -class PlainTextSocketAppender(threading.Thread): - def __init__(self, verbose=True, le_api=LE_API_DEFAULT, le_port=LE_PORT_DEFAULT, le_tls_port=LE_TLS_PORT_DEFAULT): - threading.Thread.__init__(self) - - # Logentries API server address - self.le_api = le_api - - # Port number for token logging to Logentries API server - self.le_port = le_port - self.le_tls_port = le_tls_port - - self.daemon = True - self.verbose = verbose - self._conn = None - self._queue = le_helpers.create_queue(QUEUE_SIZE) - - def empty(self): - return self._queue.empty() - - def open_connection(self): - self._conn = socket.socket(socket.AF_INET, socket.SOCK_STREAM) - self._conn.connect((self.le_api, self.le_port)) - - def reopen_connection(self): - self.close_connection() - - root_delay = MIN_DELAY - while True: - try: - self.open_connection() - return - except Exception: - if self.verbose: - dbg("Unable to connect to Logentries") - - root_delay *= 2 - if(root_delay > MAX_DELAY): - root_delay = MAX_DELAY - - wait_for = root_delay + random.uniform(0, root_delay) - - try: - time.sleep(wait_for) - except KeyboardInterrupt: - raise - - def close_connection(self): - if self._conn is not None: - self._conn.close() - - def run(self): - try: - # Open connection - self.reopen_connection() - - # Send data in queue - while True: - # Take data from queue - data = self._queue.get(block=True) - - # Replace newlines with Unicode line separator - # for multi-line events - if not le_helpers.is_unicode(data): - multiline = le_helpers.create_unicode(data).replace( - '\n', LINE_SEP) - else: - multiline = data.replace('\n', LINE_SEP) - multiline += "\n" - # Send data, reconnect if needed - while True: - try: - self._conn.send(multiline.encode('utf-8')) - except socket.error: - self.reopen_connection() - continue - break - except KeyboardInterrupt: - if self.verbose: - dbg("Logentries asynchronous socket client interrupted") - - self.close_connection() - -SocketAppender = PlainTextSocketAppender - -try: - import ssl - ssl_enabled = True -except ImportError: # for systems without TLS support. - ssl_enabled = False - dbg("Unable to import ssl module. Will send over port 80.") -else: - class TLSSocketAppender(PlainTextSocketAppender): - - def open_connection(self): - sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) - sock = ssl.wrap_socket( - sock=sock, - keyfile=None, - certfile=None, - server_side=False, - cert_reqs=ssl.CERT_REQUIRED, - ssl_version=getattr( - ssl, - 'PROTOCOL_TLSv1_2', - ssl.PROTOCOL_TLSv1 - ), - ca_certs=certifi.where(), - do_handshake_on_connect=True, - suppress_ragged_eofs=True, - ) - - sock.connect((self.le_api, self.le_tls_port)) - self._conn = sock - - -class LogentriesHandler(logging.Handler): - def __init__(self, token, use_tls=True, verbose=True, format=None, le_api=LE_API_DEFAULT, le_port=LE_PORT_DEFAULT, le_tls_port=LE_TLS_PORT_DEFAULT): - logging.Handler.__init__(self) - self.token = token - self.good_config = True - self.verbose = verbose - # give the socket 10 seconds to flush, - # otherwise drop logs - self.timeout = 10 - if not le_helpers.check_token(token): - if self.verbose: - dbg(INVALID_TOKEN) - self.good_config = False - if format is None: - format = logging.Formatter('%(asctime)s : %(levelname)s, %(message)s', - '%a %b %d %H:%M:%S %Z %Y') - self.setFormatter(format) - self.setLevel(logging.DEBUG) - if use_tls and ssl_enabled: - self._thread = TLSSocketAppender(verbose=verbose, le_api=le_api, le_port=le_port, le_tls_port=le_tls_port) - else: - self._thread = SocketAppender(verbose=verbose, le_api=le_api, le_port=le_port, le_tls_port=le_tls_port) - - def flush(self): - # wait for all queued logs to be send - now = time.time() - while not self._thread.empty(): - time.sleep(0.2) - if time.time() - now > self.timeout: - break - - def emit_raw(self, msg): - if self.good_config and not self._thread.is_alive(): - try: - self._thread.start() - if self.verbose: - dbg("Starting Logentries Asynchronous Socket Appender") - except RuntimeError: # It's already started. - pass - - msg = self.token + msg - try: - self._thread._queue.put_nowait(msg) - except Exception: - # Queue is full, try to remove the oldest message and put again - try: - self._thread._queue.get_nowait() - self._thread._queue.put_nowait(msg) - except Exception: - # Race condition, no need for any action here - pass - - def emit(self, record): - msg = self.format(record).rstrip('\n') - self.emit_raw(msg) - - def close(self): - logging.Handler.close(self) diff --git a/release/files_common b/release/files_common index 9728a0c4a6..1732476b1e 100644 --- a/release/files_common +++ b/release/files_common @@ -426,7 +426,7 @@ installer/updater/Makefile scripts/update_now.sh scripts/stop_updater.sh -pyextra/logentries/** +pyextra/.gitignore rednose/** From 6385fae0e66afe1e0dfd4180d92886fa3a6a7ae7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 18 Jun 2020 11:58:08 -0700 Subject: [PATCH 305/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 5b14945140..31f8a0d862 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 5b1494514042721b63f71254700ddcf94dbbd9c7 +Subproject commit 31f8a0d862f699d0d06593085aa16a8cd657bccc From 472fe6696278b4137466e401496d1561a799a0da Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Thu, 18 Jun 2020 12:24:47 -0700 Subject: [PATCH 306/656] GM cleanup + ignition fix (#1729) * small cleanup * alertmanager handles that * improve tuning * below steer speed * Revert "improve tuning" This reverts commit 5d2de147d2c9979af09b7964ad59e4b95ddb2f2a. * bump panda * update refs * bump panda --- selfdrive/car/gm/carcontroller.py | 17 +++-------------- selfdrive/car/gm/carstate.py | 12 +++++------- selfdrive/car/gm/gmcan.py | 10 +++++++--- selfdrive/car/gm/interface.py | 3 +++ selfdrive/car/gm/values.py | 3 --- selfdrive/test/process_replay/ref_commit | 2 +- 6 files changed, 19 insertions(+), 28 deletions(-) diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 2018d73306..9b8e68fee4 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -44,11 +44,11 @@ class CarController(): self.apply_steer_last = 0 self.lka_icon_status_last = (False, False) self.steer_rate_limited = False - self.fcw_frames = 0 self.params = CarControllerParams() self.packer_pt = CANPacker(DBC[CP.carFingerprint]['pt']) + self.packer_obj = CANPacker(DBC[CP.carFingerprint]['radar']) self.packer_ch = CANPacker(DBC[CP.carFingerprint]['chassis']) def update(self, enabled, CS, frame, actuators, @@ -59,10 +59,6 @@ class CarController(): # Send CAN commands. can_sends = [] - # FCW: trigger FCWAlert for 100 frames (4 seconds) - if hud_alert == VisualAlert.fcw: - self.fcw_frames = 100 - # STEER if (frame % P.STEER_STEP) == 0: lkas_enabled = enabled and not CS.out.steerWarning and CS.out.vEgo > P.MIN_STEER_SPEED @@ -98,18 +94,11 @@ class CarController(): at_full_stop = enabled and CS.out.standstill near_stop = enabled and (CS.out.vEgo < P.NEAR_STOP_BRAKE_PHASE) can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, CanBus.CHASSIS, apply_brake, idx, near_stop, at_full_stop)) - - at_full_stop = enabled and CS.out.standstill can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, CanBus.POWERTRAIN, apply_gas, idx, enabled, at_full_stop)) # Send dashboard UI commands (ACC status), 25hz if (frame % 4) == 0: - # Send FCW if applicable - send_fcw = 0 - if self.fcw_frames > 0: - send_fcw = 0x3 - self.fcw_frames -= 1 - + send_fcw = hud_alert == VisualAlert.fcw can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, CanBus.POWERTRAIN, enabled, hud_v_cruise * CV.MS_TO_KPH, hud_show_car, send_fcw)) # Radar needs to know current speed and yaw rate (50hz), @@ -120,7 +109,7 @@ class CarController(): if frame % time_and_headlights_step == 0: idx = (frame // time_and_headlights_step) % 4 can_sends.append(gmcan.create_adas_time_status(CanBus.OBSTACLE, int((tt - self.start_time) * 60), idx)) - can_sends.append(gmcan.create_adas_headlights_status(CanBus.OBSTACLE)) + can_sends.append(gmcan.create_adas_headlights_status(self.packer_obj, CanBus.OBSTACLE)) speed_and_accelerometer_step = 2 if frame % speed_and_accelerometer_step == 0: diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 2eb3ff7cdb..7f45e7ea9e 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -5,8 +5,7 @@ from opendbc.can.can_define import CANDefine from opendbc.can.parser import CANParser from selfdrive.car.interfaces import CarStateBase from selfdrive.car.gm.values import DBC, CAR, AccState, CanBus, \ - CruiseButtons, is_eps_status_ok, \ - STEER_THRESHOLD + CruiseButtons, STEER_THRESHOLD class CarState(CarStateBase): @@ -58,18 +57,17 @@ class CarState(CarStateBase): ret.espDisabled = pt_cp.vl["ESPStatus"]['TractionControlOn'] != 1 self.pcm_acc_status = pt_cp.vl["AcceleratorPedal2"]['CruiseState'] - regen_pressed = False + ret.brakePressed = ret.brake > 1e-5 + # Regen braking is braking if self.car_fingerprint == CAR.VOLT: - regen_pressed = bool(pt_cp.vl["EBCMRegenPaddle"]['RegenPaddle']) + ret.brakePressed = ret.brakePressed or bool(pt_cp.vl["EBCMRegenPaddle"]['RegenPaddle']) - # Regen braking is braking - ret.brakePressed = ret.brake > 1e-5 or regen_pressed ret.cruiseState.enabled = self.pcm_acc_status != AccState.OFF ret.cruiseState.standstill = self.pcm_acc_status == AccState.STANDSTILL # 0 - inactive, 1 - active, 2 - temporary limited, 3 - failed self.lkas_status = pt_cp.vl["PSCMStatus"]['LKATorqueDeliveredStatus'] - ret.steerWarning = not is_eps_status_ok(self.lkas_status, self.car_fingerprint) + ret.steerWarning = self.lkas_status not in [0, 1] return ret diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py index 5cd81ead11..9dd78e4df8 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/selfdrive/car/gm/gmcan.py @@ -72,7 +72,7 @@ def create_acc_dashboard_command(packer, bus, acc_engaged, target_speed_kph, lea "ACCCmdActive" : acc_engaged, "ACCAlwaysOne2" : 1, "ACCLeadCar" : lead_car_in_sight, - "FCWAlert": fcw + "FCWAlert": 0x3 if fcw else 0 } return packer.make_can_msg("ASCMActiveCruiseControlStatus", bus, values) @@ -104,8 +104,12 @@ def create_adas_accelerometer_speed_status(bus, speed_ms, idx): dat += [(idx << 5) + (far_range_mode << 4) + (near_range_mode << 3) + (chksum >> 8), chksum & 0xff] return make_can_msg(0x308, bytes(dat), bus) -def create_adas_headlights_status(bus): - return make_can_msg(0x310, b"\x42\x04", bus) +def create_adas_headlights_status(packer, bus): + values = { + "Always42": 0x42, + "Always4": 0x4, + } + return packer.make_can_msg("ASCMHeadlight", bus, values) def create_lka_icon_command(bus, active, critical, steer): if active and steer == 1: diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index f63f8d7741..1328b11fe0 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -34,6 +34,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.444 # not optimized yet # Start with a baseline lateral tuning for all GM vehicles. Override tuning as needed in each model section below. + ret.minSteerSpeed = 7 * CV.MPH_TO_MS ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 @@ -156,6 +157,8 @@ class CarInterface(CarInterfaceBase): events.add(EventName.resumeRequired) if self.CS.pcm_acc_status == AccState.FAULTED: events.add(EventName.controlsFailed) + if ret.vEgo < self.CP.minSteerSpeed: + events.add(car.CarEvent.EventName.belowSteerSpeed) # handle button presses for b in ret.buttonEvents: diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index cb77b09705..efe696f8a6 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -32,9 +32,6 @@ class CanBus: CHASSIS = 2 SW_GMLAN = 3 -def is_eps_status_ok(eps_status, car_fingerprint): - return eps_status in [0, 1] - FINGERPRINTS = { # Astra BK MY17, ASCM unplugged CAR.HOLDEN_ASTRA: [{ diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 5e03e2ab90..3423ee6519 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -d21758939420dba7d9dba842739914432a77e024 \ No newline at end of file +fe829cbe7ff161f098f680f3bfe3b8daeba2f220 \ No newline at end of file From b3101998ed6457e83e326f87be9f062ac97c0030 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 18 Jun 2020 13:01:28 -0700 Subject: [PATCH 307/656] update no GPS alert for comma two users --- selfdrive/controls/lib/events.py | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 0c56c04bb2..52f5e11a72 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -166,6 +166,9 @@ class EngagementAlert(Alert): Priority.MID, VisualAlert.none, audible_alert, .2, 0., 0.), + +# ********** alert callback functions ********** + def below_steer_speed_alert(CP, sm, metric): speed = int(round(CP.minSteerSpeed * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH))) unit = "kph" if metric else "mph" @@ -184,6 +187,14 @@ def calibration_incomplete_alert(CP, sm, metric): AlertStatus.normal, AlertSize.mid, Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2) +def no_gps_alert(CP, sm, metric): + two = sm['thermal'].hwType == log.HealthData.HwType.uno + return Alert( + "Poor GPS reception", + "Contact Support" if two else "Check GPS antenna placement", + AlertStatus.normal, AlertSize.mid, + Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=300.), + EVENTS = { # ********** events with no alerts ********** @@ -536,11 +547,7 @@ EVENTS = { }, EventName.noGps: { - ET.PERMANENT: Alert( - "Poor GPS reception", - "Check GPS antenna placement", - AlertStatus.normal, AlertSize.mid, - Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=300.), + ET.PERMANENT: no_gps_alert, }, EventName.soundsUnavailable: { From 9b6864b31a19b943baa8fa7ad25ac83463f77392 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 18 Jun 2020 14:23:11 -0700 Subject: [PATCH 308/656] fix 'openpilot' symlink being created in release branches --- release/build_release2.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/release/build_release2.sh b/release/build_release2.sh index 8e1466830b..1e74251d20 100755 --- a/release/build_release2.sh +++ b/release/build_release2.sh @@ -41,7 +41,7 @@ rm -rf /data/openpilot/pandaextra popd # Build stuff -ln -sf /data/openpilot /data/pythonpath +ln -sfn /data/openpilot /data/pythonpath export PYTHONPATH="/data/openpilot:/data/openpilot/pyextra" SCONS_CACHE=1 scons -j3 nosetests -s selfdrive/test/test_openpilot.py From e892d6a9d9efa624ae486d6c8449a452fd1286ee Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 18 Jun 2020 14:40:57 -0700 Subject: [PATCH 309/656] if sky visible --- selfdrive/controls/lib/events.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 52f5e11a72..6d69586c87 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -191,7 +191,7 @@ def no_gps_alert(CP, sm, metric): two = sm['thermal'].hwType == log.HealthData.HwType.uno return Alert( "Poor GPS reception", - "Contact Support" if two else "Check GPS antenna placement", + "If sky visible, contact support" if two else "Check GPS antenna placement", AlertStatus.normal, AlertSize.mid, Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=300.), From fd8514eee339e68df48c27711b79e90cbca43f76 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 18 Jun 2020 15:37:03 -0700 Subject: [PATCH 310/656] hwType is in health --- selfdrive/controls/lib/events.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 6d69586c87..079c79e72b 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -188,12 +188,12 @@ def calibration_incomplete_alert(CP, sm, metric): Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2) def no_gps_alert(CP, sm, metric): - two = sm['thermal'].hwType == log.HealthData.HwType.uno + two = sm['health'].hwType == log.HealthData.HwType.uno return Alert( "Poor GPS reception", - "If sky visible, contact support" if two else "Check GPS antenna placement", + "If sky is visible, contact support" if two else "Check GPS antenna placement", AlertStatus.normal, AlertSize.mid, - Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=300.), + Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=300.) EVENTS = { # ********** events with no alerts ********** From 853dfcd59ace1e7ee2f13b45403af94065fd921f Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Thu, 18 Jun 2020 17:38:19 -0500 Subject: [PATCH 311/656] Added 2020 RX350 fwdRadar f/w x018821F3301100 (#1739) @ottopilot#7631 DongleID/route 3a5c5101bd71ad5d|2020-06-18--16-56-51 --- selfdrive/car/toyota/values.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 40548e39f8..ce4ff5df2e 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1119,8 +1119,9 @@ FW_VERSIONS = { b'8965B48271\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F3301100\x00\x00\x00\x00', b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', From 5198457ca0364b011d5a34e81b459be52fe4e55d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 18 Jun 2020 17:50:01 -0700 Subject: [PATCH 312/656] make sure everything runs before ending test (#1741) --- selfdrive/manager.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 9c4fbc3d57..ee2e2f42d3 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -515,8 +515,14 @@ def manager_thread(): if dt > 90: last_proc = messaging.recv_sock(proc_sock, wait=True) + all_running = all(running[p].is_alive() for p in car_started_processes) + cleanup_all_processes(None, None) - sys.exit(print_cpu_usage(first_proc, last_proc)) + return_code = print_cpu_usage(first_proc, last_proc) + + if not all_running: + return_code = 1 + sys.exit(return_code) def manager_prepare(spinner=None): # build all processes From d0254e60970c9938990c07fd2709240d01b8f453 Mon Sep 17 00:00:00 2001 From: Michael Honan Date: Sat, 20 Jun 2020 04:28:10 +1000 Subject: [PATCH 313/656] Added 2019 C-HR FPv2 firmware (#1743) --- selfdrive/car/toyota/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index ce4ff5df2e..2de264b931 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -427,6 +427,7 @@ FW_VERSIONS = { b'8821FF404100 ', b'8821FF405100 ', b'8821FF406000 ', + b'8821F0W01100 ', ], (Ecu.esp, 0x7b0, None): [ b'F152610020\x00\x00\x00\x00\x00\x00', @@ -443,6 +444,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\x033F401100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203102\x00\x00\x00\x00', b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F0W01000 ', @@ -450,6 +452,7 @@ FW_VERSIONS = { b'8821FF404100 ', b'8821FF405100 ', b'8821FF406000 ', + b'8821F0W01100 ', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'8646FF401800 ', From fa0b47e6f24dd7cdb28e0637331a39dec0006867 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 20 Jun 2020 02:37:31 +0800 Subject: [PATCH 314/656] save Reader to local variable to avoid repeating validate the pointer (#1717) --- selfdrive/boardd/boardd.cc | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index f1f87cb8db..9c8f6ebac7 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -531,13 +531,15 @@ void can_send(cereal::Event::Reader &event) { //Older than 1 second. Dont send. return; } - int msg_count = event.getSendcan().size(); + + auto can_data_list = event.getSendcan(); + int msg_count = can_data_list.size(); uint32_t *send = (uint32_t*)malloc(msg_count*0x10); memset(send, 0, msg_count*0x10); for (int i = 0; i < msg_count; i++) { - auto cmsg = event.getSendcan()[i]; + auto cmsg = can_data_list[i]; if (cmsg.getAddress() >= 0x800) { // extended send[i*4] = (cmsg.getAddress() << 3) | 5; @@ -545,9 +547,10 @@ void can_send(cereal::Event::Reader &event) { // normal send[i*4] = (cmsg.getAddress() << 21) | 1; } - assert(cmsg.getDat().size() <= 8); - send[i*4+1] = cmsg.getDat().size() | (cmsg.getSrc() << 4); - memcpy(&send[i*4+2], cmsg.getDat().begin(), cmsg.getDat().size()); + auto can_data = cmsg.getDat(); + assert(can_data.size() <= 8); + send[i*4+1] = can_data.size() | (cmsg.getSrc() << 4); + memcpy(&send[i*4+2], can_data.begin(), can_data.size()); } // send to board From c8082190a07b6534dffcd7c88945af8b26b241c0 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 20 Jun 2020 02:38:39 +0800 Subject: [PATCH 315/656] release resources in modeld (#1700) --- selfdrive/modeld/modeld.cc | 2 ++ selfdrive/modeld/models/commonmodel.c | 4 ++++ 2 files changed, 6 insertions(+) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index e5cbc02223..5b07ba2636 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -231,6 +231,8 @@ int main(int argc, char **argv) { LOG("joining live_thread"); err = pthread_join(live_thread_handle, NULL); assert(err == 0); + clReleaseCommandQueue(q); + clReleaseContext(context); return 0; } diff --git a/selfdrive/modeld/models/commonmodel.c b/selfdrive/modeld/models/commonmodel.c index db990af0cb..1b93718c88 100644 --- a/selfdrive/modeld/models/commonmodel.c +++ b/selfdrive/modeld/models/commonmodel.c @@ -55,6 +55,10 @@ float *frame_prepare(ModelFrame* frame, cl_command_queue q, void frame_free(ModelFrame* frame) { transform_destroy(&frame->transform); loadyuv_destroy(&frame->loadyuv); + clReleaseMemObject(frame->net_input); + clReleaseMemObject(frame->transformed_v_cl); + clReleaseMemObject(frame->transformed_u_cl); + clReleaseMemObject(frame->transformed_y_cl); } From 0cda65b58e4cb452ac2c3e8a45e3bf7e2905b32f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 19 Jun 2020 12:42:33 -0700 Subject: [PATCH 316/656] catch CalledProcessError when detecting kernel version --- selfdrive/controls/controlsd.py | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 4f2ec6b3c4..744b594626 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -3,6 +3,7 @@ import os import gc import subprocess from cereal import car, log +from common.android import ANDROID from common.numpy_fast import clip from common.realtime import sec_since_boot, set_realtime_priority, set_core_affinity, Ratekeeper, DT_CTRL from common.profiler import Profiler @@ -78,7 +79,7 @@ class Controls: internet_needed or not openpilot_enabled_toggle # detect sound card presence and ensure successful init - sounds_available = (not os.path.isfile('/EON') or (os.path.isfile('/proc/asound/card0/state') and + sounds_available = (not ANDROID or (os.path.isfile('/proc/asound/card0/state') and open('/proc/asound/card0/state').read().strip() == 'ONLINE')) car_recognized = self.CP.carName != 'mock' @@ -143,8 +144,13 @@ class Controls: if hw_type == HwType.whitePanda: self.events.add(EventName.whitePandaUnsupported, static=True) - uname = subprocess.check_output(["uname", "-v"], encoding='utf8').strip() - if uname == "#1 SMP PREEMPT Wed Jun 10 12:40:53 PDT 2020": + try: + bad_kernel = subprocess.check_output(["uname", "-v"], encoding='utf8').strip() == \ + "#1 SMP PREEMPT Wed Jun 10 12:40:53 PDT 2020" + except subprocess.CalledProcessError: + bad_kernel = True + + if bad_kernel: self.events.add(EventName.neosUpdateRequired, static=True) # controlsd is driven by can recv, expected at 100Hz From 2b20479a5c37eeefe6ef6c3b91016c7d5874af30 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 19 Jun 2020 13:26:52 -0700 Subject: [PATCH 317/656] Move kernel check to before creating the submaster, prevent SIGUSR2 --- selfdrive/controls/controlsd.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 744b594626..c078b3c4b6 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -44,6 +44,12 @@ class Controls: set_realtime_priority(53) set_core_affinity(3) + try: + bad_kernel = subprocess.check_output(["uname", "-v"], encoding='utf8').strip() == \ + "#1 SMP PREEMPT Wed Jun 10 12:40:53 PDT 2020" + except subprocess.CalledProcessError: + bad_kernel = True + # Setup sockets self.pm = pm if self.pm is None: @@ -144,12 +150,6 @@ class Controls: if hw_type == HwType.whitePanda: self.events.add(EventName.whitePandaUnsupported, static=True) - try: - bad_kernel = subprocess.check_output(["uname", "-v"], encoding='utf8').strip() == \ - "#1 SMP PREEMPT Wed Jun 10 12:40:53 PDT 2020" - except subprocess.CalledProcessError: - bad_kernel = True - if bad_kernel: self.events.add(EventName.neosUpdateRequired, static=True) From a1d4dd3adc22cfaf6a6d4e8a9f9f6c984dcb55f1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 19 Jun 2020 13:46:24 -0700 Subject: [PATCH 318/656] release2 cleanup (#1703) * cleanup intermediate files * test car interfaces --- release/build_devel.sh | 1 + release/build_release2.sh | 13 +++++++++++++ 2 files changed, 14 insertions(+) diff --git a/release/build_devel.sh b/release/build_devel.sh index 32c8baf869..9febb866df 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -84,6 +84,7 @@ echo -n "1" > /data/params/d/CommunityFeaturesToggle PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" nosetests -s selfdrive/test/test_openpilot.py PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" GET_CPU_USAGE=1 selfdrive/manager.py +PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" selfdrive/car/tests/test_car_interfaces.py echo "[-] testing panda build T=$SECONDS" pushd panda/board/ diff --git a/release/build_release2.sh b/release/build_release2.sh index 1e74251d20..08f727b1b2 100755 --- a/release/build_release2.sh +++ b/release/build_release2.sh @@ -44,12 +44,22 @@ popd ln -sfn /data/openpilot /data/pythonpath export PYTHONPATH="/data/openpilot:/data/openpilot/pyextra" SCONS_CACHE=1 scons -j3 + +# Run tests nosetests -s selfdrive/test/test_openpilot.py +selfdrive/car/tests/test_car_interfaces.py # Cleanup +find . -name '*.a' -delete +find . -name '*.o' -delete +find . -name '*.os' -delete find . -name '*.pyc' -delete +find . -name '__pycache__' -delete rm .sconsign.dblite +# Restore phonelibs +git checkout phonelibs/ + # Mark as prebuilt release touch prebuilt @@ -57,6 +67,9 @@ touch prebuilt git add -f . git commit --amend -m "openpilot v$VERSION" +# Print committed files that are normally gitignored +#git status --ignored + # Push to release2-staging git push -f origin release2-staging From 9e273eb2ec9830b4e2af82168e5f68da71c66761 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 19 Jun 2020 13:56:46 -0700 Subject: [PATCH 319/656] ubloxd free->delete, fixes #1742 --- selfdrive/locationd/ubloxd_main.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/ubloxd_main.cc b/selfdrive/locationd/ubloxd_main.cc index d869c85196..8e6007a75c 100644 --- a/selfdrive/locationd/ubloxd_main.cc +++ b/selfdrive/locationd/ubloxd_main.cc @@ -104,7 +104,7 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) } bytes_consumed += bytes_consumed_this_time; } - free(msg); + delete msg; } delete subscriber; From 24de8174dcb59fea10402060b8dd1db6ecdaf0f5 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 19 Jun 2020 14:11:23 -0700 Subject: [PATCH 320/656] Only show gps event after 1 km (#1747) --- selfdrive/controls/controlsd.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index c078b3c4b6..37b7e802d6 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -128,6 +128,7 @@ class Controls: self.can_error_counter = 0 self.last_blinker_frame = 0 self.saturated_count = 0 + self.distance_traveled = 0 self.events_prev = [] self.current_alert_types = [] @@ -213,8 +214,9 @@ class Controls: if not self.sm['liveLocationKalman'].inputsOK and os.getenv("NOSENSOR") is None: if self.sm.frame > 5 / DT_CTRL: # Give locationd some time to receive all the inputs self.events.add(EventName.sensorDataInvalid) - if not self.sm['liveLocationKalman'].gpsOK and os.getenv("NOSENSOR") is None: - self.events.add(EventName.noGps) + if not self.sm['liveLocationKalman'].gpsOK and (self.distance_traveled > 1000) and os.getenv("NOSENSOR") is None: + # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes + self.events.add(EventName.noGps) if not self.sm['pathPlan'].paramsValid: self.events.add(EventName.vehicleModelInvalid) if not self.sm['liveLocationKalman'].posenetOK: @@ -259,6 +261,8 @@ class Controls: if not self.sm['health'].controlsAllowed and self.enabled: self.mismatch_counter += 1 + self.distance_traveled += CS.vEgo * DT_CTRL + return CS def state_transition(self, CS): From 78b428e53441da339f8d13b78bfcf1f5ca192d6f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 19 Jun 2020 14:53:55 -0700 Subject: [PATCH 321/656] fix alert sounds looping --- selfdrive/ui/sound.cc | 8 -------- 1 file changed, 8 deletions(-) diff --git a/selfdrive/ui/sound.cc b/selfdrive/ui/sound.cc index 1b02f14321..3eee6f831c 100644 --- a/selfdrive/ui/sound.cc +++ b/selfdrive/ui/sound.cc @@ -62,14 +62,6 @@ bool Sound::init(int volume) { } AudibleAlert Sound::currentPlaying() { - if (currentSound_ != AudibleAlert::NONE) { - auto playItf = player_.at(currentSound_)->playItf; - SLuint32 state; - if (SL_RESULT_SUCCESS == (*playItf)->GetPlayState(playItf, &state) && - (state == SL_PLAYSTATE_STOPPED || state == SL_PLAYSTATE_PAUSED)) { - currentSound_ = AudibleAlert::NONE; - } - } return currentSound_; } From 01a486308d7fbcd661d8f8786c140222703f659a Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Fri, 19 Jun 2020 15:53:48 -0700 Subject: [PATCH 322/656] c++ify thneed to remove memory leaks (#1737) Co-authored-by: Comma Device --- selfdrive/modeld/thneed/thneed.cc | 30 +++++++++++++++--------------- selfdrive/modeld/thneed/thneed.h | 11 +++++++---- 2 files changed, 22 insertions(+), 19 deletions(-) diff --git a/selfdrive/modeld/thneed/thneed.cc b/selfdrive/modeld/thneed/thneed.cc index cd1242b086..9a593d9e04 100644 --- a/selfdrive/modeld/thneed/thneed.cc +++ b/selfdrive/modeld/thneed/thneed.cc @@ -8,7 +8,7 @@ Thneed *g_thneed = NULL; int g_fd = -1; -std::map, std::string> g_args; +map, string> g_args; static inline uint64_t nanos_since_boot() { struct timespec t; @@ -43,9 +43,7 @@ int ioctl(int filedes, unsigned long request, void *argp) { if (thneed->record & 1) { thneed->timestamp = cmd->timestamp; thneed->context_id = cmd->context_id; - CachedCommand *ccmd = new CachedCommand(thneed, cmd); - //ccmd->disassemble(); - thneed->cmds.push_back(ccmd); + thneed->cmds.push_back(unique_ptr(new CachedCommand(thneed, cmd))); } if (thneed->record & 2) { printf("IOCTL_KGSL_GPU_COMMAND(%2zu): flags: 0x%lx context_id: %u timestamp: %u\n", @@ -66,9 +64,7 @@ int ioctl(int filedes, unsigned long request, void *argp) { } if (thneed->record & 1) { - struct kgsl_gpuobj_sync_obj *new_objs = (struct kgsl_gpuobj_sync_obj *)malloc(sizeof(struct kgsl_gpuobj_sync_obj)*cmd->count); - memcpy(new_objs, objs, sizeof(struct kgsl_gpuobj_sync_obj)*cmd->count); - thneed->syncobjs.push_back(std::make_pair(cmd->count, new_objs)); + thneed->syncobjs.push_back(string((char *)objs, sizeof(struct kgsl_gpuobj_sync_obj)*cmd->count)); } } else if (request == IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID) { struct kgsl_device_waittimestamp_ctxtid *cmd = (struct kgsl_device_waittimestamp_ctxtid *)argp; @@ -111,6 +107,10 @@ GPUMalloc::GPUMalloc(int size, int fd) { remaining = size; } +GPUMalloc::~GPUMalloc() { + // TODO: free the GPU malloced area +} + void *GPUMalloc::alloc(int size) { if (size > remaining) return NULL; remaining -= size; @@ -170,7 +170,7 @@ void CachedCommand::exec(bool wait) { Thneed::Thneed() { assert(g_fd != -1); fd = g_fd; - ram = new GPUMalloc(0x40000, fd); + ram = make_unique(0x40000, fd); record = 1; timestamp = -1; g_thneed = this; @@ -235,9 +235,9 @@ void Thneed::execute(float **finputs, float *foutput, bool slow) { for (auto it = syncobjs.begin(); it != syncobjs.end(); ++it) { struct kgsl_gpuobj_sync cmd; - cmd.objs = (uint64_t)it->second; - cmd.obj_len = it->first * sizeof(struct kgsl_gpuobj_sync_obj); - cmd.count = it->first; + cmd.objs = (uint64_t)it->data(); + cmd.obj_len = it->length(); + cmd.count = it->length() / sizeof(struct kgsl_gpuobj_sync_obj); ret = ioctl(fd, IOCTL_KGSL_GPUOBJ_SYNC, &cmd); assert(ret == 0); @@ -275,7 +275,7 @@ cl_int (*my_clSetKernelArg)(cl_kernel kernel, cl_uint arg_index, size_t arg_size cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) { if (my_clSetKernelArg == NULL) my_clSetKernelArg = reinterpret_cast(dlsym(RTLD_NEXT, "REAL_clSetKernelArg")); if (arg_value != NULL) { - g_args[std::make_pair(kernel, arg_index)] = std::string((char*)arg_value, arg_size); + g_args[make_pair(kernel, arg_index)] = string((char*)arg_value, arg_size); } cl_int ret = my_clSetKernelArg(kernel, arg_index, arg_size, arg_value); return ret; @@ -310,7 +310,7 @@ cl_int thneed_clEnqueueNDRangeKernel(cl_command_queue command_queue, for (int i = 0; i < num_args; i++) { char arg_name[0x100]; clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); - std::string arg = g_args[std::make_pair(kernel, i)]; + string arg = g_args[make_pair(kernel, i)]; if (strcmp(arg_name, "input") == 0 && strcmp(name, "zero_pad_image_float") == 0) { cl_mem mem; @@ -343,7 +343,7 @@ cl_int thneed_clEnqueueNDRangeKernel(cl_command_queue command_queue, char arg_name[0x100]; clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_TYPE_NAME, sizeof(arg_type), arg_type, NULL); clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); - std::string arg = g_args[std::make_pair(kernel, i)]; + string arg = g_args[make_pair(kernel, i)]; printf(" %s %s", arg_type, arg_name); void *arg_value = (void*)arg.data(); int arg_size = arg.size(); @@ -405,7 +405,7 @@ cl_int thneed_clEnqueueNDRangeKernel(cl_command_queue command_queue, //#define SAVE_KERNELS #ifdef SAVE_KERNELS -std::map program_source; +map program_source; cl_program (*my_clCreateProgramWithSource)(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) = NULL; cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) { diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h index 89e8522570..36f0bfed7f 100644 --- a/selfdrive/modeld/thneed/thneed.h +++ b/selfdrive/modeld/thneed/thneed.h @@ -5,11 +5,14 @@ #include #include +using namespace std; + class Thneed; class GPUMalloc { public: GPUMalloc(int size, int fd); + ~GPUMalloc(); void *alloc(int size); private: uint64_t base; @@ -34,7 +37,7 @@ class Thneed { void stop(); void execute(float **finputs, float *foutput, bool slow=false); - std::vector inputs; + vector inputs; cl_mem output; cl_command_queue command_queue; @@ -43,9 +46,9 @@ class Thneed { // protected? int record; int timestamp; - GPUMalloc *ram; - std::vector cmds; - std::vector > syncobjs; + unique_ptr ram; + vector > cmds; + vector syncobjs; int fd; }; From ccf6b80c7e5aa24b922ed60a519eab91a1d5ec9b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 19 Jun 2020 16:16:48 -0700 Subject: [PATCH 323/656] Cleanup startup event handling (#1748) * cleanup startup event * always show permanent * lowest * update refs --- selfdrive/car/car_helpers.py | 12 +++++++----- selfdrive/controls/controlsd.py | 4 ++-- selfdrive/controls/lib/events.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/version.py | 3 +++ 5 files changed, 14 insertions(+), 9 deletions(-) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 573bd6f962..478db2375c 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -1,6 +1,7 @@ import os from common.params import Params from common.basedir import BASEDIR +from selfdrive.version import comma_remote, tested_branch from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_known_cars from selfdrive.car.vin import get_vin, VIN_UNKNOWN from selfdrive.car.fw_versions import get_fw_versions, match_fw_to_car @@ -13,11 +14,12 @@ EventName = car.CarEvent.EventName HwType = log.HealthData.HwType -def get_startup_event(car_recognized, controller_available, hw_type): - event = EventName.startup - if Params().get("GitRemote", encoding="utf8") in ['git@github.com:commaai/openpilot.git', 'https://github.com/commaai/openpilot.git']: - if Params().get("GitBranch", encoding="utf8") not in ['devel', 'release2-staging', 'dashcam-staging', 'release2', 'dashcam']: - event = EventName.startupMaster +def get_startup_event(car_recognized, controller_available): + if comma_remote and tested_branch: + event = EventName.startup + else: + event = EventName.startupMaster + if not car_recognized: event = EventName.startupNoCar elif car_recognized and not controller_available: diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 37b7e802d6..fed3f1d088 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -130,7 +130,7 @@ class Controls: self.saturated_count = 0 self.distance_traveled = 0 self.events_prev = [] - self.current_alert_types = [] + self.current_alert_types = [ET.PERMANENT] self.sm['liveCalibration'].calStatus = Calibration.INVALID self.sm['thermal'].freeSpace = 1. @@ -138,7 +138,7 @@ class Controls: self.sm['dMonitoringState'].awarenessStatus = 1. self.sm['dMonitoringState'].faceDetected = False - self.startup_event = get_startup_event(car_recognized, controller_available, hw_type) + self.startup_event = get_startup_event(car_recognized, controller_available) if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 079c79e72b..6fd2aaa0e2 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -294,7 +294,7 @@ EVENTS = { "Dashcam Mode", "Car Unrecognized", AlertStatus.normal, AlertSize.mid, - Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), }, EventName.stockAeb: { diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 3423ee6519..be6523e27b 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -fe829cbe7ff161f098f680f3bfe3b8daeba2f220 \ No newline at end of file +a8b50cfc06473f66896b3f74a562263d3cccec36 \ No newline at end of file diff --git a/selfdrive/version.py b/selfdrive/version.py index 13a16022ac..02416a90a0 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -46,6 +46,8 @@ training_version = b"0.2.0" terms_version = b"2" dirty = True +comma_remote = False +tested_branch = False origin = get_git_remote() branch = get_git_full_branchname() @@ -58,6 +60,7 @@ try: if (origin is not None) and (branch is not None): comma_remote = origin.startswith('git@github.com:commaai') or origin.startswith('https://github.com/commaai') + tested_branch = branch in ['devel', 'release2-staging', 'dashcam-staging', 'release2', 'dashcam'] dirty = not comma_remote dirty = dirty or ('master' in branch) From 77b7d306834feeba6ac131bfa438465e18d0a3f2 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 19 Jun 2020 16:54:42 -0700 Subject: [PATCH 324/656] Remove kernel check from controlsd --- selfdrive/controls/controlsd.py | 11 +---------- 1 file changed, 1 insertion(+), 10 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index fed3f1d088..2798ec236d 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -1,7 +1,6 @@ #!/usr/bin/env python3 import os import gc -import subprocess from cereal import car, log from common.android import ANDROID from common.numpy_fast import clip @@ -38,18 +37,13 @@ LaneChangeState = log.PathPlan.LaneChangeState LaneChangeDirection = log.PathPlan.LaneChangeDirection EventName = car.CarEvent.EventName + class Controls: def __init__(self, sm=None, pm=None, can_sock=None): gc.disable() set_realtime_priority(53) set_core_affinity(3) - try: - bad_kernel = subprocess.check_output(["uname", "-v"], encoding='utf8').strip() == \ - "#1 SMP PREEMPT Wed Jun 10 12:40:53 PDT 2020" - except subprocess.CalledProcessError: - bad_kernel = True - # Setup sockets self.pm = pm if self.pm is None: @@ -151,9 +145,6 @@ class Controls: if hw_type == HwType.whitePanda: self.events.add(EventName.whitePandaUnsupported, static=True) - if bad_kernel: - self.events.add(EventName.neosUpdateRequired, static=True) - # controlsd is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) self.prof = Profiler(False) # off by default From 0681fc04ad39e266dc3b7b621d6ab51c87020529 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 19 Jun 2020 16:56:56 -0700 Subject: [PATCH 325/656] debug script to track droppped frames (#1749) --- .../internal/measure_modeld_packet_drop.py | 30 +++++++++++++++++++ 1 file changed, 30 insertions(+) create mode 100755 selfdrive/debug/internal/measure_modeld_packet_drop.py diff --git a/selfdrive/debug/internal/measure_modeld_packet_drop.py b/selfdrive/debug/internal/measure_modeld_packet_drop.py new file mode 100755 index 0000000000..457771df0e --- /dev/null +++ b/selfdrive/debug/internal/measure_modeld_packet_drop.py @@ -0,0 +1,30 @@ +#!/usr/bin/env python3 +import cereal.messaging as messaging + +if __name__ == "__main__": + modeld_sock = messaging.sub_sock("model") + + last_frame_id = None + start_t = None + frame_cnt = 0 + dropped = 0 + + while True: + m = messaging.recv_one(modeld_sock) + frame_id = m.model.frameId + t = m.logMonoTime / 1e9 + frame_cnt += 1 + + if start_t is None: + start_t = t + last_frame_id = frame_id + continue + + d_frame = frame_id - last_frame_id + dropped += d_frame - 1 + + expected_num_frames = int((t - start_t) * 20) + frame_drop = 100 * (1 - (expected_num_frames / frame_cnt)) + print(f"Num dropped {dropped}, Drop compared to 20Hz: {frame_drop:.2f}%") + + last_frame_id = frame_id From a8e7a187ca115a5fe5f3a04923dbe50bd00871c7 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 19 Jun 2020 16:57:28 -0700 Subject: [PATCH 326/656] Fix modeld dropping frames if processing takes over 50 ms --- selfdrive/modeld/modeld.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 5b07ba2636..23aae757a8 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -160,7 +160,7 @@ int main(int argc, char **argv) { VisionStream stream; while (!do_exit) { VisionStreamBufs buf_info; - err = visionstream_init(&stream, VISION_STREAM_YUV, true, &buf_info); + err = visionstream_init(&stream, VISION_STREAM_YUV, false, &buf_info); if (err) { LOGW("visionstream connect failed"); usleep(100000); From 968443c545ab1443fb2aefe0583d414c384182a7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 19 Jun 2020 19:28:56 -0700 Subject: [PATCH 327/656] Alert when controls fails to start (#1750) * alert when controls fails to start * more friendly * fix sound * remove that * just else Co-authored-by: Comma Device --- selfdrive/ui/ui.cc | 27 ++++++++++++++++++--------- 1 file changed, 18 insertions(+), 9 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index bc827c3c57..ccb975d0dc 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -510,6 +510,7 @@ static void ui_update(UIState *s) { s->vision_connect_firstrun = false; + s->controls_timeout = 6 * UI_FREQ; s->alert_blinking_alpha = 1.0; s->alert_blinked = false; } @@ -853,22 +854,30 @@ int main(int argc, char* argv[]) { s->sound.setVolume(fmin(MAX_VOLUME, MIN_VOLUME + s->scene.controls_state.getVEgo() / 5), 5); // up one notch every 5 m/s - // If car is started and controlsState times out, display an alert if (s->controls_timeout > 0) { s->controls_timeout--; - } else { - if (s->started && s->controls_seen && s->scene.alert_text2 != "Controls Unresponsive") { + } else if (s->started) { + if (!s->controls_seen) { + // car is started, but controlsState hasn't been seen at all + LOGE("Controls failed to start"); + s->scene.alert_text1 = "openpilot Unavailable"; + s->scene.alert_text2 = "Controls Failed to Start"; + s->scene.alert_size = cereal::ControlsState::AlertSize::MID; + update_status(s, STATUS_WARNING); + } else { + // car is started, but controls is lagging or died LOGE("Controls unresponsive"); - s->scene.alert_size = cereal::ControlsState::AlertSize::FULL; - update_status(s, STATUS_ALERT); + + if (s->scene.alert_text2 != "Controls Unresponsive") { + s->sound.play(AudibleAlert::CHIME_WARNING_REPEAT, 3); // loop sound 3 times + } s->scene.alert_text1 = "TAKE CONTROL IMMEDIATELY"; s->scene.alert_text2 = "Controls Unresponsive"; - ui_draw_vision_alert(s, s->scene.alert_size, s->status, s->scene.alert_text1.c_str(), s->scene.alert_text2.c_str()); - - s->sound.play(AudibleAlert::CHIME_WARNING_REPEAT, 3); // loop sound 3 times + s->scene.alert_size = cereal::ControlsState::AlertSize::FULL; + update_status(s, STATUS_ALERT); } - s->controls_seen = false; + ui_draw_vision_alert(s, s->scene.alert_size, s->status, s->scene.alert_text1.c_str(), s->scene.alert_text2.c_str()); } read_param_timeout(&s->is_metric, "IsMetric", &s->is_metric_timeout); From 8f9c01f66b96d093cc47d24a547d72d10c9b3e28 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 19 Jun 2020 19:53:47 -0700 Subject: [PATCH 328/656] New issue templates (#1751) * add pc bug report template * better description * update pc * labels * route moved * commment * clean up * enhancement question * at --- .github/ISSUE_TEMPLATE/bug_report.md | 24 ++++++++++++++---------- .github/ISSUE_TEMPLATE/bug_report_pc.md | 25 +++++++++++++++++++++++++ .github/ISSUE_TEMPLATE/enhancement.md | 8 ++++++++ .github/ISSUE_TEMPLATE/question.md | 17 +++++++++++++++++ 4 files changed, 64 insertions(+), 10 deletions(-) create mode 100644 .github/ISSUE_TEMPLATE/bug_report_pc.md create mode 100644 .github/ISSUE_TEMPLATE/enhancement.md create mode 100644 .github/ISSUE_TEMPLATE/question.md diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md index 47b8af1905..eef3048994 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -1,26 +1,30 @@ --- name: Bug report -about: Create a report to help us improve openpilot +about: For issues with running openpilot on your comma device title: '' labels: '' assignees: '' - --- **Describe the bug** -A clear and concise description of what the bug is. + + **How to reproduce or log data** -Steps to reproduce the behavior, or a explorer/cabana link to the exact drive and timestamp of when the bug occurred. + + **Expected behavior** -A clear and concise description of what you expected to happen. + + **Device/Version information (please complete the following information):** - - Device: [e.g. EON/EON Gold] - - Dongle ID: [e.g. 77611a1fac303767, can be found in Settings -> Device -> Dongle ID] - - Version: [e.g. 0.6.4], or commit hash when on devel - - Car make/model [e.g. Toyota Prius 2016] + - Device: [e.g. EON/EON Gold/comma two] + - Dongle ID: [e.g. 77611a1fac303767, can be found in Settings -> Device -> Dongle ID or my.comma.ai/useradmin] + - Route: [e.g. 77611a1fac303767|2020-05-11--16-37-07, can be found in my.comma.ai/useradmin] + - Version: [commit hash when on a non-release branch, or version number when on devel or release2 (e.g. 0.7.6)] + - Car make/model: [e.g. Toyota Prius 2016] **Additional context** -Add any other context about the problem here. + + diff --git a/.github/ISSUE_TEMPLATE/bug_report_pc.md b/.github/ISSUE_TEMPLATE/bug_report_pc.md new file mode 100644 index 0000000000..c1471ec61c --- /dev/null +++ b/.github/ISSUE_TEMPLATE/bug_report_pc.md @@ -0,0 +1,25 @@ +--- +name: PC Bug report +about: For issues with running openpilot on PC +title: '' +labels: 'PC' +assignees: '' +--- + +**Describe the bug** + + + +**How to reproduce or log data** + + + +**Expected behavior** + + + +**Additional context** + + + +Operating system: [e.g. Ubuntu 16.04] diff --git a/.github/ISSUE_TEMPLATE/enhancement.md b/.github/ISSUE_TEMPLATE/enhancement.md new file mode 100644 index 0000000000..896d349ca7 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/enhancement.md @@ -0,0 +1,8 @@ +--- +name: Enhancement +about: +title: '' +labels: 'enhancement' +assignees: '' +--- + diff --git a/.github/ISSUE_TEMPLATE/question.md b/.github/ISSUE_TEMPLATE/question.md new file mode 100644 index 0000000000..c0f34eac7e --- /dev/null +++ b/.github/ISSUE_TEMPLATE/question.md @@ -0,0 +1,17 @@ +--- +name: Question +about: +title: '' +labels: 'question' +assignees: '' +--- + + From 4bd481245b09dc36001d6109cd278469a911bf7c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 19 Jun 2020 19:55:38 -0700 Subject: [PATCH 329/656] issue templates need descriptions apparently --- .github/ISSUE_TEMPLATE/enhancement.md | 2 +- .github/ISSUE_TEMPLATE/question.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/enhancement.md b/.github/ISSUE_TEMPLATE/enhancement.md index 896d349ca7..bb3379d9ae 100644 --- a/.github/ISSUE_TEMPLATE/enhancement.md +++ b/.github/ISSUE_TEMPLATE/enhancement.md @@ -1,6 +1,6 @@ --- name: Enhancement -about: +about: suggestions for openpilot enhancements title: '' labels: 'enhancement' assignees: '' diff --git a/.github/ISSUE_TEMPLATE/question.md b/.github/ISSUE_TEMPLATE/question.md index c0f34eac7e..eecd709edf 100644 --- a/.github/ISSUE_TEMPLATE/question.md +++ b/.github/ISSUE_TEMPLATE/question.md @@ -1,6 +1,6 @@ --- name: Question -about: +about: questions about openpilot title: '' labels: 'question' assignees: '' From 2ce2260edad35bf2998e6b49ac9334d29b969eb6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 19 Jun 2020 20:28:14 -0700 Subject: [PATCH 330/656] Pull request templates (#1752) * pull request templates * car port checklist * fix link * no space * newline --- .github/PULL_REQUEST_TEMPLATE/bugfix.md | 15 +++++++++++++++ .github/PULL_REQUEST_TEMPLATE/car_bugfix.md | 19 +++++++++++++++++++ .github/PULL_REQUEST_TEMPLATE/car_port.md | 14 ++++++++++++++ .github/PULL_REQUEST_TEMPLATE/fingerprint.md | 11 +++++++++++ .github/PULL_REQUEST_TEMPLATE/refactor.md | 15 +++++++++++++++ 5 files changed, 74 insertions(+) create mode 100644 .github/PULL_REQUEST_TEMPLATE/bugfix.md create mode 100644 .github/PULL_REQUEST_TEMPLATE/car_bugfix.md create mode 100644 .github/PULL_REQUEST_TEMPLATE/car_port.md create mode 100644 .github/PULL_REQUEST_TEMPLATE/fingerprint.md create mode 100644 .github/PULL_REQUEST_TEMPLATE/refactor.md diff --git a/.github/PULL_REQUEST_TEMPLATE/bugfix.md b/.github/PULL_REQUEST_TEMPLATE/bugfix.md new file mode 100644 index 0000000000..e28661db3b --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE/bugfix.md @@ -0,0 +1,15 @@ +--- +name: Bug fix +about: For openpilot bug fixes +title: '' +labels: 'bugfix' +assignees: '' +--- + +**Description** + + + +**Verification** + + diff --git a/.github/PULL_REQUEST_TEMPLATE/car_bugfix.md b/.github/PULL_REQUEST_TEMPLATE/car_bugfix.md new file mode 100644 index 0000000000..d0c8bc58e4 --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE/car_bugfix.md @@ -0,0 +1,19 @@ +--- +name: Car Bug fix +about: For vehicle/brand specifc bug fixes +title: '' +labels: 'car bug fix' +assignees: '' +--- + +**Description** + + + +**Verification** + + + +**Route** + +Route: [a route with the bug fix] diff --git a/.github/PULL_REQUEST_TEMPLATE/car_port.md b/.github/PULL_REQUEST_TEMPLATE/car_port.md new file mode 100644 index 0000000000..b81c293885 --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE/car_port.md @@ -0,0 +1,14 @@ +--- +name: Car port +about: For new car ports +title: '' +labels: 'car port' +assignees: '' +--- + +**Checklist** + +- [ ] added to README +- [ ] test route added to [test_car_models](../../selfdrive/test/test_car_models.py) +- [ ] route with openpilot: +- [ ] route with stock system: diff --git a/.github/PULL_REQUEST_TEMPLATE/fingerprint.md b/.github/PULL_REQUEST_TEMPLATE/fingerprint.md new file mode 100644 index 0000000000..466d4f98f4 --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE/fingerprint.md @@ -0,0 +1,11 @@ +--- +name: Fingerprint +about: For adding fingerprints to existing cars +title: '' +labels: 'fingerprint' +assignees: '' +--- + +Discord username: [] + +Route: [] diff --git a/.github/PULL_REQUEST_TEMPLATE/refactor.md b/.github/PULL_REQUEST_TEMPLATE/refactor.md new file mode 100644 index 0000000000..1ee21c1bba --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE/refactor.md @@ -0,0 +1,15 @@ +--- +name: Refactor +about: For code refactors +title: '' +labels: 'refactor' +assignees: '' +--- + +**Description** + + + +**Verification** + + From cab96374c5c511adcb83882c52502924a2d08089 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 19 Jun 2020 20:34:51 -0700 Subject: [PATCH 331/656] more generic alert text for wrongCarMode --- selfdrive/controls/lib/events.py | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 6fd2aaa0e2..3831946f5b 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -195,6 +195,12 @@ def no_gps_alert(CP, sm, metric): AlertStatus.normal, AlertSize.mid, Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=300.) +def wrong_car_mode_alert(CP, sm, metric): + text = "Cruise Mode Disabled" + if CP.carName == "honda": + text = "Main Switch Off" + return NoEntryAlert(text, duration_hud_alert=0.), + EVENTS = { # ********** events with no alerts ********** @@ -491,8 +497,7 @@ EVENTS = { EventName.wrongCarMode: { ET.USER_DISABLE: EngagementAlert(AudibleAlert.chimeDisengage), - ET.NO_ENTRY: NoEntryAlert("Main Switch Off", - duration_hud_alert=0.), + ET.NO_ENTRY: wrong_car_mode_alert, }, EventName.wrongCruiseMode: { From 3c461ca5ccf1b0ae2b9164feced96a5aa4998555 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 19 Jun 2020 20:39:34 -0700 Subject: [PATCH 332/656] Add cppcheck as a pre-commit hook (#1646) * add cppcheck as a pre-commit hook * fix Dockerfile * update precommit config * exclude panda and opendbc --- .github/workflows/test.yaml | 14 +------------- .gitignore | 1 - .pre-commit-config.yaml | 13 +++++++++++++ Dockerfile.openpilot | 1 - cppcheck_openpilot.sh | 4 ---- selfdrive/ui/sidebar.cc | 2 +- 6 files changed, 15 insertions(+), 20 deletions(-) delete mode 100755 cppcheck_openpilot.sh diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index dc06161021..4f6bb66d02 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -37,7 +37,7 @@ jobs: external/bin selfdrive/modeld/runners $TEST_DIR # need these so docker copy won't fail - cp Pipfile Pipfile.lock .pylintrc cppcheck_openpilot.sh .coveragerc-app .pre-commit-config.yaml $TEST_DIR + cp Pipfile Pipfile.lock .pylintrc .coveragerc-app .pre-commit-config.yaml $TEST_DIR cd $TEST_DIR mkdir laika laika_repo tools release - name: Build Docker image @@ -96,18 +96,6 @@ jobs: run: eval "$BUILD" - name: pre-commit run: $RUN "cd /tmp/openpilot/ && git init && git add -A && pre-commit run --all" - - name: cppcheck - run: $PERSIST "cd /tmp/openpilot/ && ./cppcheck_openpilot.sh 2> cppcheck_report.txt" - - name: Print cppcheck report - if: always() - run: | - docker cp tmppilot:/tmp/openpilot/cppcheck_report.txt cppcheck_report.txt - cat cppcheck_report.txt - - uses: actions/upload-artifact@v2 - if: always() - with: - name: cppcheck_report.txt - path: cppcheck_report.txt unit_tests: name: unit tests diff --git a/.gitignore b/.gitignore index fb1cbfc0b6..31ced88ca9 100644 --- a/.gitignore +++ b/.gitignore @@ -59,7 +59,6 @@ openpilot-apks .coverage* coverage.xml -cppcheck_report.txt htmlcov pandaextra diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index af18f795ff..491d5fb498 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -31,3 +31,16 @@ repos: language: system types: [python] exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' +- repo: local + hooks: + - id: cppcheck + name: cppcheck + entry: cppcheck + language: system + types: [c++] + exclude: '^(phonelibs)|(external)|(cereal)|(opendbc)|(panda)|(tools)|(selfdrive/modeld/thneed/debug)|(selfdrive/modeld/test)|(selfdrive/camerad/test)/' + args: + - --error-exitcode=1 + - --quiet + - --force + - -j8 diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index ec4ee189dc..71827ae9b8 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -77,7 +77,6 @@ RUN pyenv install 3.8.2 && \ RUN mkdir -p /tmp/openpilot COPY SConstruct \ - cppcheck_openpilot.sh \ .pylintrc \ .pre-commit-config.yaml \ .coveragerc-app \ diff --git a/cppcheck_openpilot.sh b/cppcheck_openpilot.sh deleted file mode 100755 index 6f6520806f..0000000000 --- a/cppcheck_openpilot.sh +++ /dev/null @@ -1,4 +0,0 @@ -#!/bin/bash - -cppcheck --force -j$(nproc) selfdrive/ common/ opendbc/ cereal/ installer/ 2> cppcheck_report.txt - diff --git a/selfdrive/ui/sidebar.cc b/selfdrive/ui/sidebar.cc index 5d75a9bbfb..890ea7e7ac 100644 --- a/selfdrive/ui/sidebar.cc +++ b/selfdrive/ui/sidebar.cc @@ -136,7 +136,7 @@ static void ui_draw_sidebar_temp_metric(UIState *s) { } static void ui_draw_sidebar_panda_metric(UIState *s) { - int panda_severity; + int panda_severity = 2; char panda_message_str[32]; const int panda_y_offset = 32 + 148; From be08124d80dc47571c2f869ac659192ce95328c9 Mon Sep 17 00:00:00 2001 From: Michael Honan Date: Tue, 23 Jun 2020 03:18:04 +1000 Subject: [PATCH 333/656] Added firmware versions for RAV4 TSS2 Non-Hybrid (#1756) --- selfdrive/car/toyota/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 2de264b931..f8f05cc3c1 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -880,6 +880,7 @@ FW_VERSIONS = { b'\x018966342T9000\x00\x00\x00\x00', b'\x018966342U4000\x00\x00\x00\x00', b'\x018966342V3100\x00\x00\x00\x00', + b'\x018966342V3200\x00\x00\x00\x00', b'\x018966342X5000\x00\x00\x00\x00', b'\x01896634A05000\x00\x00\x00\x00', b'\x01896634A19000\x00\x00\x00\x00', @@ -900,10 +901,12 @@ FW_VERSIONS = { b'\x01F152642561\x00\x00\x00\x00\x00\x00', b'\x01F152642700\x00\x00\x00\x00\x00\x00', b'\x01F152642710\x00\x00\x00\x00\x00\x00', + b'\x01F152642750\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B42170\x00\x00\x00\x00\x00\x00', b'8965B42171\x00\x00\x00\x00\x00\x00', + b'8965B42181\x00\x00\x00\x00\x00\x00', b'\x028965B0R01200\x00\x00\x00\x008965B0R02200\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ From a64f0119e0d86ab77aaf16a9b6ee2dfeb0d002df Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 23 Jun 2020 02:29:18 +0800 Subject: [PATCH 334/656] Fix resource leak in visionbuf_free (#1699) * fix resource leak in visionbuf_free * add mmap_len to VisionBuf --- selfdrive/common/visionbuf.h | 1 + selfdrive/common/visionbuf_ion.c | 7 ++++++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/selfdrive/common/visionbuf.h b/selfdrive/common/visionbuf.h index 8958bdd1d0..95f4826a96 100644 --- a/selfdrive/common/visionbuf.h +++ b/selfdrive/common/visionbuf.h @@ -14,6 +14,7 @@ extern "C" { typedef struct VisionBuf { size_t len; + size_t mmap_len; void* addr; int handle; int fd; diff --git a/selfdrive/common/visionbuf_ion.c b/selfdrive/common/visionbuf_ion.c index e5dddfad22..3068994d28 100644 --- a/selfdrive/common/visionbuf_ion.c +++ b/selfdrive/common/visionbuf_ion.c @@ -7,7 +7,7 @@ #include #include #include - +#include #include #include @@ -64,6 +64,7 @@ VisionBuf visionbuf_allocate(size_t len) { return (VisionBuf){ .len = len, + .mmap_len = ion_alloc.len, .addr = addr, .handle = ion_alloc.handle, .fd = ion_fd_data.fd, @@ -73,6 +74,7 @@ VisionBuf visionbuf_allocate(size_t len) { VisionBuf visionbuf_allocate_cl(size_t len, cl_device_id device_id, cl_context ctx, cl_mem *out_mem) { VisionBuf r = visionbuf_allocate(len); *out_mem = visionbuf_to_cl(&r, device_id, ctx); + r.buf_cl = *out_mem; return r; } @@ -137,6 +139,9 @@ void visionbuf_sync(const VisionBuf* buf, int dir) { } void visionbuf_free(const VisionBuf* buf) { + clReleaseMemObject(buf->buf_cl); + munmap(buf->addr, buf->mmap_len); + close(buf->fd); struct ion_handle_data handle_data = { .handle = buf->handle, }; From 6cb2d83253c818cb0618bf8ed0e51a500a2af5a2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 22 Jun 2020 11:32:34 -0700 Subject: [PATCH 335/656] add upate_kernel.json to release files --- release/files_common | 1 + 1 file changed, 1 insertion(+) diff --git a/release/files_common b/release/files_common index 1732476b1e..c35df3976f 100644 --- a/release/files_common +++ b/release/files_common @@ -421,6 +421,7 @@ phonelibs/android_system_core/** installer/updater/updater installer/updater/updater.cc installer/updater/update.json +installer/updater/update_kernel.json installer/updater/Makefile scripts/update_now.sh From ddd6029a865ba63d94b2679c68048d59e1922f70 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Mon, 22 Jun 2020 12:40:23 -0600 Subject: [PATCH 336/656] Add Civic hatch fw version (#1758) --- selfdrive/car/honda/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index baa174f7a5..4e1cebf76d 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -419,6 +419,7 @@ FW_VERSIONS = { b'37805-5AN-A950\x00\x00', b'37805-5AN-AG20\x00\x00', b'37805-5AN-AH20\x00\x00', + b'37805-5AN-AJ30\x00\x00', b'37805-5AN-AK20\x00\x00', b'37805-5AN-AR20\x00\x00', b'37805-5AN-L940\x00\x00', From d204d87b95114f8aa6e719b4628be2abe8be27dc Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 22 Jun 2020 14:00:17 -0700 Subject: [PATCH 337/656] enable flake8 F error codes --- .pre-commit-config.yaml | 2 +- common/transformations/orientation.py | 3 +-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 491d5fb498..3b4fa8a340 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -20,7 +20,7 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(opendbc)|(laika_repo)|(rednose_repo)|(selfdrive/debug)/' args: - - --select=E112,E113,E304,E501,E502,E701,E702,E703,E71,E72,E731,W191,W6 + - --select=F,E112,E113,E304,E501,E502,E701,E702,E703,E71,E72,E731,W191,W6 - --max-line-length=240 - --statistics - repo: local diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py index b0e028d4e3..f0920942b6 100644 --- a/common/transformations/orientation.py +++ b/common/transformations/orientation.py @@ -8,8 +8,7 @@ from common.transformations.transformations import (ecef_euler_from_ned_single, quat2euler_single, quat2rot_single, rot2euler_single, - rot2quat_single, - rot_matrix) + rot2quat_single) def numpy_wrap(function, input_shape, output_shape): From fa7b5d38b8fbddb2b778516da6e9a5be6c6670a3 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 22 Jun 2020 14:05:34 -0700 Subject: [PATCH 338/656] bump submodules --- opendbc | 2 +- panda | 2 +- rednose_repo | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/opendbc b/opendbc index 076eb51b17..df1bb08344 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 076eb51b1726906ce3365b2d3a52bad8622ed558 +Subproject commit df1bb083440804c07d93f84d117d9e625b8fdb5a diff --git a/panda b/panda index 31f8a0d862..ca12a1c660 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 31f8a0d862f699d0d06593085aa16a8cd657bccc +Subproject commit ca12a1c6603328dcb3ddbef67f158fecf245f74b diff --git a/rednose_repo b/rednose_repo index 026464a3d1..307c771fca 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit 026464a3d143b34e1daaf7654745ce418d5266b9 +Subproject commit 307c771fcaa5e301ccb18d3ab9fdedddd675c569 From 264015c584a0a010ba5f63af67da2e6bddebbea4 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 22 Jun 2020 14:27:07 -0700 Subject: [PATCH 339/656] cleanup no sensor data alert (#1760) --- .gitignore | 2 ++ cereal | 2 +- selfdrive/controls/controlsd.py | 2 +- selfdrive/locationd/locationd.py | 1 + 4 files changed, 5 insertions(+), 2 deletions(-) diff --git a/.gitignore b/.gitignore index 31ced88ca9..b8d9a39b4a 100644 --- a/.gitignore +++ b/.gitignore @@ -64,3 +64,5 @@ pandaextra .mypy_cache/ flycheck_* + +cppcheck_report.txt diff --git a/cereal b/cereal index c0c3cc16b2..8d5230e59b 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit c0c3cc16b2ee2aafa7d13b67563463be663c240c +Subproject commit 8d5230e59b0ed7c93c66863d0cd19e5f180e417c diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 2798ec236d..3fbf4aa5dd 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -202,7 +202,7 @@ class Controls: self.events.add(EventName.commIssue) if not self.sm['pathPlan'].mpcSolutionValid: self.events.add(EventName.plannerError) - if not self.sm['liveLocationKalman'].inputsOK and os.getenv("NOSENSOR") is None: + if not self.sm['liveLocationKalman'].sensorsOK and os.getenv("NOSENSOR") is None: if self.sm.frame > 5 / DT_CTRL: # Give locationd some time to receive all the inputs self.events.add(EventName.sensorDataInvalid) if not self.sm['liveLocationKalman'].gpsOK and (self.distance_traveled > 1000) and os.getenv("NOSENSOR") is None: diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 155174aa60..cf621386dc 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -324,6 +324,7 @@ def locationd_thread(sm, pm, disabled_logs=None): msg.liveLocationKalman = localizer.liveLocationMsg(t * 1e-9) msg.liveLocationKalman.inputsOK = sm.all_alive_and_valid() + msg.liveLocationKalman.sensorsOK = sm.alive['sensorEvents'] and sm.valid['sensorEvents'] gps_age = (t / 1e9) - localizer.last_gps_fix msg.liveLocationKalman.gpsOK = gps_age < 1.0 From 88f92663780665b27fafdb5ab86ad501cad4cbcf Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 22 Jun 2020 14:27:58 -0700 Subject: [PATCH 340/656] Make model packets invalid when frames are too old (#1759) * make model packets invalid when frames are too old * add frame numbers to cloudlog --- selfdrive/modeld/modeld.cc | 9 +++++---- selfdrive/modeld/models/driving.cc | 10 ++++++---- selfdrive/modeld/models/driving.h | 6 ++++-- 3 files changed, 15 insertions(+), 10 deletions(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 23aae757a8..691d3f32e8 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -82,7 +82,7 @@ int main(int argc, char **argv) { // messaging PubMaster pm({"model", "cameraOdometry"}); - SubMaster sm({"pathPlan"}); + SubMaster sm({"pathPlan", "frame"}); #ifdef QCOM cl_device_type device_type = CL_DEVICE_TYPE_DEFAULT; @@ -202,6 +202,7 @@ int main(int argc, char **argv) { } mat3 model_transform = matmul3(yuv_transform, transform); + uint32_t frame_id = sm["frame"].getFrame().getFrameId(); mt1 = millis_since_boot(); @@ -213,10 +214,10 @@ int main(int argc, char **argv) { model_transform, NULL, vec_desire); mt2 = millis_since_boot(); - model_publish(pm, extra.frame_id, model_buf, extra.timestamp_eof); - posenet_publish(pm, extra.frame_id, model_buf, extra.timestamp_eof); + model_publish(pm, extra.frame_id, frame_id, model_buf, extra.timestamp_eof); + posenet_publish(pm, extra.frame_id, frame_id, model_buf, extra.timestamp_eof); - LOGD("model process: %.2fms, from last %.2fms", mt2-mt1, mt1-last); + LOGD("model process: %.2fms, from last %.2fms, vipc_frame_id %zu, frame_id, %zu", mt2-mt1, mt1-last, extra.frame_id, frame_id); last = mt1; } diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index b24762ebf0..88674fb604 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -245,7 +245,7 @@ void fill_longi(cereal::ModelData::LongitudinalData::Builder longi, const float longi.setAccelerations(accel); } -void model_publish(PubMaster &pm, uint32_t frame_id, +void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { // make msg capnp::MallocMessageBuilder msg; @@ -253,7 +253,7 @@ void model_publish(PubMaster &pm, uint32_t frame_id, event.setLogMonoTime(nanos_since_boot()); auto framed = event.initModel(); - framed.setFrameId(frame_id); + framed.setFrameId(vipc_frame_id); framed.setTimestampEof(timestamp_eof); auto lpath = framed.initPath(); @@ -290,11 +290,12 @@ void model_publish(PubMaster &pm, uint32_t frame_id, auto meta = framed.initMeta(); fill_meta(meta, net_outputs.meta); + event.setValid(frame_id - vipc_frame_id < MAX_FRAME_AGE); pm.send("model", msg); } -void posenet_publish(PubMaster &pm, uint32_t frame_id, +void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); @@ -324,7 +325,8 @@ void posenet_publish(PubMaster &pm, uint32_t frame_id, posenetd.setRotStd(rot_std_vs); posenetd.setTimestampEof(timestamp_eof); - posenetd.setFrameId(frame_id); + posenetd.setFrameId(vipc_frame_id); + event.setValid(frame_id - vipc_frame_id < MAX_FRAME_AGE); pm.send("cameraOdometry", msg); } diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index 223a540b37..29d7a68f6a 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -35,6 +35,8 @@ #define TIME_DISTANCE 100 #define POSE_SIZE 12 +#define MAX_FRAME_AGE 5 + struct ModelDataRaw { float *path; float *left_lane; @@ -71,8 +73,8 @@ ModelDataRaw model_eval_frame(ModelState* s, cl_command_queue q, void model_free(ModelState* s); void poly_fit(float *in_pts, float *in_stds, float *out); -void model_publish(PubMaster &pm, uint32_t frame_id, +void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, const ModelDataRaw &data, uint64_t timestamp_eof); -void posenet_publish(PubMaster &pm, uint32_t frame_id, +void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, const ModelDataRaw &data, uint64_t timestamp_eof); #endif From bfeefb6fd3498a14b27d6c83f5b254ab7113d3dd Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 22 Jun 2020 14:41:15 -0700 Subject: [PATCH 341/656] Locationd: only process valid log messages (#1761) --- selfdrive/locationd/locationd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index cf621386dc..3a5d515538 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -304,7 +304,7 @@ def locationd_thread(sm, pm, disabled_logs=None): sm.update() for sock, updated in sm.updated.items(): - if updated: + if updated and sm.valid[sock]: t = sm.logMonoTime[sock] * 1e-9 if sock == "sensorEvents": localizer.handle_sensors(t, sm[sock]) From c3171e66b35a5db2625bc15d5d82de31d5c2ff4e Mon Sep 17 00:00:00 2001 From: Comma Device Date: Mon, 22 Jun 2020 16:25:44 -0700 Subject: [PATCH 342/656] bring back cycle_alerts.py --- selfdrive/debug/cycle_alerts.py | 56 +++++++++++++++++++++++++++++++++ 1 file changed, 56 insertions(+) create mode 100755 selfdrive/debug/cycle_alerts.py diff --git a/selfdrive/debug/cycle_alerts.py b/selfdrive/debug/cycle_alerts.py new file mode 100755 index 0000000000..bd48e6c6d8 --- /dev/null +++ b/selfdrive/debug/cycle_alerts.py @@ -0,0 +1,56 @@ +#!/usr/bin/env python3 +import argparse +import time +import zmq + +import cereal.messaging as messaging +from cereal.services import service_list +from selfdrive.controls.lib.events import EVENTS, Alert + +def now_millis(): return time.time() * 1000 + +ALERTS = [a for _, et in EVENTS.items() for _, a in et.items() if isinstance(a, Alert)] + +#from cereal import car +#ALERTS = [a for a in ALERTS if a.audible_alert == car.CarControl.HUDControl.AudibleAlert.chimeWarningRepeat] + +default_alerts = sorted(ALERTS, key=lambda alert: (alert.alert_size, len(alert.alert_text_2))) + +def cycle_alerts(duration_millis, alerts=None): + if alerts is None: + alerts = default_alerts + + controls_state = messaging.pub_sock('controlsState') + + idx, last_alert_millis = 0, 0 + alert = alerts[0] + while 1: + if (now_millis() - last_alert_millis) > duration_millis: + alert = alerts[idx] + idx = (idx + 1) % len(alerts) + last_alert_millis = now_millis() + print('sending {}'.format(str(alert))) + + dat = messaging.new_message() + dat.init('controlsState') + + dat.controlsState.alertType = alert.alert_type + dat.controlsState.alertText1 = alert.alert_text_1 + dat.controlsState.alertText2 = alert.alert_text_2 + dat.controlsState.alertSize = alert.alert_size + #dat.controlsState.alertStatus = alert.alert_status + dat.controlsState.alertSound = alert.audible_alert + controls_state.send(dat.to_bytes()) + + time.sleep(0.01) + +if __name__ == '__main__': + parser = argparse.ArgumentParser() + parser.add_argument('--duration', type=int, default=1000) + parser.add_argument('--alert-types', nargs='+') + args = parser.parse_args() + alerts = None + if args.alert_types: + alerts = [next(a for a in ALERTS if a.alert_type==alert_type) for alert_type in args.alert_types] + + cycle_alerts(args.duration, alerts=alerts) From d4e87853550db41f36bedeeb092d1b2de2deb7b4 Mon Sep 17 00:00:00 2001 From: Comma Device Date: Mon, 22 Jun 2020 16:45:39 -0700 Subject: [PATCH 343/656] fix linter --- selfdrive/debug/cycle_alerts.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/selfdrive/debug/cycle_alerts.py b/selfdrive/debug/cycle_alerts.py index bd48e6c6d8..63b7d758c5 100755 --- a/selfdrive/debug/cycle_alerts.py +++ b/selfdrive/debug/cycle_alerts.py @@ -1,10 +1,12 @@ #!/usr/bin/env python3 +# flake8: noqa +# pylint: skip-file +# type: ignore + import argparse import time -import zmq import cereal.messaging as messaging -from cereal.services import service_list from selfdrive.controls.lib.events import EVENTS, Alert def now_millis(): return time.time() * 1000 @@ -41,7 +43,7 @@ def cycle_alerts(duration_millis, alerts=None): #dat.controlsState.alertStatus = alert.alert_status dat.controlsState.alertSound = alert.audible_alert controls_state.send(dat.to_bytes()) - + time.sleep(0.01) if __name__ == '__main__': From a3dd33593abb57e49ef599327481eebad1d06d96 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 22 Jun 2020 17:50:04 -0700 Subject: [PATCH 344/656] add link to the wiki on the new issue page --- .github/ISSUE_TEMPLATE/config.yml | 5 +++++ 1 file changed, 5 insertions(+) create mode 100644 .github/ISSUE_TEMPLATE/config.yml diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml new file mode 100644 index 0000000000..13c3f5b1ef --- /dev/null +++ b/.github/ISSUE_TEMPLATE/config.yml @@ -0,0 +1,5 @@ +blank_issues_enabled: false +contact_links: + - name: Community Wiki + url: https://github.com/commaai/openpilot/wiki + about: Check out our community wiki From af22b282ff20201914a462488700971cfe32cb20 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Mon, 22 Jun 2020 19:22:02 -0700 Subject: [PATCH 345/656] Fix some alert sounds not repeating (#1763) * fix sounds not repeating * fix PC build * 3 loop Co-authored-by: Comma Device --- selfdrive/debug/internal/sounds/set_volume.sh | 6 ++++ selfdrive/ui/linux.cc | 5 ++- selfdrive/ui/sound.cc | 34 ++++++++----------- selfdrive/ui/sound.hpp | 7 ++-- selfdrive/ui/ui.cc | 6 ++-- 5 files changed, 29 insertions(+), 29 deletions(-) create mode 100755 selfdrive/debug/internal/sounds/set_volume.sh diff --git a/selfdrive/debug/internal/sounds/set_volume.sh b/selfdrive/debug/internal/sounds/set_volume.sh new file mode 100755 index 0000000000..b25a421822 --- /dev/null +++ b/selfdrive/debug/internal/sounds/set_volume.sh @@ -0,0 +1,6 @@ +#!/usr/bin/bash +while true +do + service call audio 3 i32 3 i32 $1 i32 1 + sleep 1 +done diff --git a/selfdrive/ui/linux.cc b/selfdrive/ui/linux.cc index 97fe769e0a..590a6de28f 100644 --- a/selfdrive/ui/linux.cc +++ b/selfdrive/ui/linux.cc @@ -83,10 +83,9 @@ int touch_read(TouchState *s, int* out_x, int* out_y) { #include "sound.hpp" bool Sound::init(int volume) { return true; } -bool Sound::play(AudibleAlert alert, int repeat) { return true; } +bool Sound::play(AudibleAlert alert) { return true; } void Sound::stop() {} -void Sound::setVolume(int volume, int timeout_seconds) {} -AudibleAlert Sound::currentPlaying() { return AudibleAlert::NONE; } +void Sound::setVolume(int volume) {} Sound::~Sound() {} #include "common/visionimg.h" diff --git a/selfdrive/ui/sound.cc b/selfdrive/ui/sound.cc index 3eee6f831c..79a8fd6e26 100644 --- a/selfdrive/ui/sound.cc +++ b/selfdrive/ui/sound.cc @@ -12,21 +12,21 @@ #define ReturnOnError(func, msg) \ if ((func) != SL_RESULT_SUCCESS) { LOGW(msg); return false; } -static std::map sound_map{ - {AudibleAlert::CHIME_DISENGAGE, "../assets/sounds/disengaged.wav"}, - {AudibleAlert::CHIME_ENGAGE, "../assets/sounds/engaged.wav"}, - {AudibleAlert::CHIME_WARNING1, "../assets/sounds/warning_1.wav"}, - {AudibleAlert::CHIME_WARNING2, "../assets/sounds/warning_2.wav"}, - {AudibleAlert::CHIME_WARNING2_REPEAT, "../assets/sounds/warning_2.wav"}, - {AudibleAlert::CHIME_WARNING_REPEAT, "../assets/sounds/warning_repeat.wav"}, - {AudibleAlert::CHIME_ERROR, "../assets/sounds/error.wav"}, - {AudibleAlert::CHIME_PROMPT, "../assets/sounds/error.wav"}}; +static std::map> sound_map { + {AudibleAlert::CHIME_DISENGAGE, {"../assets/sounds/disengaged.wav", 0}}, + {AudibleAlert::CHIME_ENGAGE, {"../assets/sounds/engaged.wav", 0}}, + {AudibleAlert::CHIME_WARNING1, {"../assets/sounds/warning_1.wav", 0}}, + {AudibleAlert::CHIME_WARNING2, {"../assets/sounds/warning_2.wav", 0}}, + {AudibleAlert::CHIME_WARNING2_REPEAT, {"../assets/sounds/warning_2.wav", 3}}, + {AudibleAlert::CHIME_WARNING_REPEAT, {"../assets/sounds/warning_repeat.wav", 3}}, + {AudibleAlert::CHIME_ERROR, {"../assets/sounds/error.wav", 0}}, + {AudibleAlert::CHIME_PROMPT, {"../assets/sounds/error.wav", 0}}}; struct Sound::Player { SLObjectItf player; SLPlayItf playItf; // slplay_callback runs on a background thread,use atomic to ensure thread safe. - std::atomic repeat; + std::atomic repeat; }; bool Sound::init(int volume) { @@ -41,7 +41,7 @@ bool Sound::init(int volume) { ReturnOnError((*outputMix_)->Realize(outputMix_, SL_BOOLEAN_FALSE), "Failed to realize output mix"); for (auto &kv : sound_map) { - SLDataLocator_URI locUri = {SL_DATALOCATOR_URI, (SLchar *)kv.second}; + SLDataLocator_URI locUri = {SL_DATALOCATOR_URI, (SLchar *)kv.second.first}; SLDataFormat_MIME formatMime = {SL_DATAFORMAT_MIME, NULL, SL_CONTAINERTYPE_UNSPECIFIED}; SLDataSource audioSrc = {&locUri, &formatMime}; SLDataLocator_OutputMix outMix = {SL_DATALOCATOR_OUTPUTMIX, outputMix_}; @@ -61,10 +61,6 @@ bool Sound::init(int volume) { return true; } -AudibleAlert Sound::currentPlaying() { - return currentSound_; -} - void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event) { Sound::Player *s = reinterpret_cast(context); if (event == SL_PLAYEVENT_HEADATEND && s->repeat > 1) { @@ -75,13 +71,13 @@ void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event } } -bool Sound::play(AudibleAlert alert, int repeat) { +bool Sound::play(AudibleAlert alert) { if (currentSound_ != AudibleAlert::NONE) { stop(); } auto player = player_.at(alert); SLPlayItf playItf = player->playItf; - player->repeat = repeat; + player->repeat = sound_map[alert].second; if (player->repeat > 0) { ReturnOnError((*playItf)->RegisterCallback(playItf, slplay_callback, player), "Failed to register callback"); ReturnOnError((*playItf)->SetCallbackEventsMask(playItf, SL_PLAYEVENT_HEADATEND), "Failed to set callback event mask"); @@ -106,11 +102,11 @@ void Sound::stop() { } } -void Sound::setVolume(int volume, int timeout_seconds) { +void Sound::setVolume(int volume) { if (last_volume_ == volume) return; double current_time = nanos_since_boot(); - if ((current_time - last_set_volume_time_) > (timeout_seconds * (1e+9))) { + if ((current_time - last_set_volume_time_) > (5 * (1e+9))) { // 5s timeout on updating the volume char volume_change_cmd[64]; snprintf(volume_change_cmd, sizeof(volume_change_cmd), "service call audio 3 i32 3 i32 %d i32 1 &", volume); system(volume_change_cmd); diff --git a/selfdrive/ui/sound.hpp b/selfdrive/ui/sound.hpp index 6439571621..c147f87b68 100644 --- a/selfdrive/ui/sound.hpp +++ b/selfdrive/ui/sound.hpp @@ -13,14 +13,13 @@ class Sound { public: Sound() = default; bool init(int volume); - bool play(AudibleAlert alert, int repeat = 0); + bool play(AudibleAlert alert); void stop(); - void setVolume(int volume, int timeout_seconds = 5); - AudibleAlert currentPlaying(); + void setVolume(int volume); ~Sound(); - private: #if defined(QCOM) || defined(QCOM2) + private: SLObjectItf engine_ = nullptr; SLObjectItf outputMix_ = nullptr; int last_volume_ = 0; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index ccb975d0dc..2b8b97cff8 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -308,7 +308,7 @@ void handle_message(UIState *s, SubMaster &sm) { if (!scene.frontview){ s->controls_seen = true; } auto alert_sound = scene.controls_state.getAlertSound(); - if (alert_sound != s->sound.currentPlaying()) { + if (scene.alert_text2.compare(scene.controls_state.getAlertText2()) != 0) { if (alert_sound == AudibleAlert::NONE) { s->sound.stop(); } else { @@ -852,7 +852,7 @@ int main(int argc, char* argv[]) { should_swap = true; } - s->sound.setVolume(fmin(MAX_VOLUME, MIN_VOLUME + s->scene.controls_state.getVEgo() / 5), 5); // up one notch every 5 m/s + s->sound.setVolume(fmin(MAX_VOLUME, MIN_VOLUME + s->scene.controls_state.getVEgo() / 5)); // up one notch every 5 m/s if (s->controls_timeout > 0) { s->controls_timeout--; @@ -869,7 +869,7 @@ int main(int argc, char* argv[]) { LOGE("Controls unresponsive"); if (s->scene.alert_text2 != "Controls Unresponsive") { - s->sound.play(AudibleAlert::CHIME_WARNING_REPEAT, 3); // loop sound 3 times + s->sound.play(AudibleAlert::CHIME_WARNING_REPEAT); } s->scene.alert_text1 = "TAKE CONTROL IMMEDIATELY"; From 5e10efead11073279f7119f07df2825713f033c4 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 22 Jun 2020 19:31:29 -0700 Subject: [PATCH 346/656] Fix unsigned overflow in modeld frame age computation --- selfdrive/modeld/models/driving.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 88674fb604..7156b09733 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -290,7 +290,7 @@ void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, auto meta = framed.initMeta(); fill_meta(meta, net_outputs.meta); - event.setValid(frame_id - vipc_frame_id < MAX_FRAME_AGE); + event.setValid(frame_id < vipc_frame_id + MAX_FRAME_AGE); pm.send("model", msg); } @@ -326,7 +326,7 @@ void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, posenetd.setTimestampEof(timestamp_eof); posenetd.setFrameId(vipc_frame_id); - event.setValid(frame_id - vipc_frame_id < MAX_FRAME_AGE); + event.setValid(frame_id < vipc_frame_id + MAX_FRAME_AGE); pm.send("cameraOdometry", msg); } From b5efaef98afb812846a5f1c8df07970a9c73e7be Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 22 Jun 2020 22:47:16 -0700 Subject: [PATCH 347/656] test for duplicate ECU firmware versions --- selfdrive/car/honda/values.py | 2 -- selfdrive/car/tests/test_fw_fingerprint.py | 12 ++++++++++++ 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 4e1cebf76d..ba2ce9ce19 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -203,7 +203,6 @@ FW_VERSIONS = { b'78209-TVA-A010\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TVA-A160\x00\x00', b'36802-TVA-A160\x00\x00', b'36802-TVA-A170\x00\x00', b'36802-TWA-A070\x00\x00', @@ -744,7 +743,6 @@ FW_VERSIONS = { b'78109-THR-A820\x00\x00', b'78109-THR-A830\x00\x00', b'78109-THR-AB20\x00\x00', - b'78109-THR-AB20\x00\x00', b'78109-THR-AB30\x00\x00', b'78109-THR-AB40\x00\x00', b'78109-THR-AC40\x00\x00', diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index ff07f9fd7d..4d166639e5 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -1,12 +1,14 @@ #!/usr/bin/env python3 import unittest from cereal import car +from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.fw_versions import match_fw_to_car from selfdrive.car.toyota.values import CAR as TOYOTA CarFw = car.CarParams.CarFw Ecu = car.CarParams.Ecu +ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} class TestFwFingerprint(unittest.TestCase): def assertFingerprints(self, candidates, expected): @@ -41,6 +43,16 @@ class TestFwFingerprint(unittest.TestCase): self.assertFingerprints(match_fw_to_car(CP.carFw), TOYOTA.RAV4_TSS2) + def test_no_duplicate_fw_versions(self): + passed = True + for car_name, ecus in FW_VERSIONS.items(): + for ecu, ecu_fw in ecus.items(): + duplicates = set([fw for fw in ecu_fw if ecu_fw.count(fw) > 1]) + if len(duplicates): + print(car_name, ECU_NAME[ecu[0]], duplicates) + passed = False + + self.assertTrue(passed, "Duplicate FW versions found") if __name__ == "__main__": unittest.main() From 574724765f8d1c2d6c6dc5cfdc0821264258c101 Mon Sep 17 00:00:00 2001 From: Thinh Nguyen Date: Tue, 23 Jun 2020 09:01:46 -0700 Subject: [PATCH 348/656] Add firmware for 2020 RAV4 Hybrid TSS2 (#1764) * Add firmware for 2020 RAV4 Hybrid TSS2 * Remove duplicate values --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index f8f05cc3c1..6b828fec56 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -951,6 +951,7 @@ FW_VERSIONS = { b'\x018821F3301400\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F4203300\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F4203500\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', From 51b7dc0e385945faf0341c52b14555e75e804d04 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 23 Jun 2020 10:46:33 -0700 Subject: [PATCH 349/656] fix engage/disengage sounds --- selfdrive/controls/lib/events.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/ui/ui.cc | 3 ++- selfdrive/ui/ui.hpp | 1 + 4 files changed, 5 insertions(+), 3 deletions(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 3831946f5b..3970a57bd7 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -75,7 +75,7 @@ class Events: alert = alert(*callback_args) if DT_CTRL * (self.events_prev[e] + 1) >= alert.creation_delay: - alert.alert_type = EVENT_NAME[e] + alert.alert_type = f"{EVENT_NAME[e]}/{et}" ret.append(alert) return ret diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index be6523e27b..31fdb6ce07 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -a8b50cfc06473f66896b3f74a562263d3cccec36 \ No newline at end of file +12861083f7fdcfd2876d7f8102f1853a3248e2a7 \ No newline at end of file diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 2b8b97cff8..f352adf699 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -308,7 +308,7 @@ void handle_message(UIState *s, SubMaster &sm) { if (!scene.frontview){ s->controls_seen = true; } auto alert_sound = scene.controls_state.getAlertSound(); - if (scene.alert_text2.compare(scene.controls_state.getAlertText2()) != 0) { + if (scene.alert_type.compare(scene.controls_state.getAlertType()) != 0) { if (alert_sound == AudibleAlert::NONE) { s->sound.stop(); } else { @@ -318,6 +318,7 @@ void handle_message(UIState *s, SubMaster &sm) { scene.alert_text1 = scene.controls_state.getAlertText1(); scene.alert_text2 = scene.controls_state.getAlertText2(); scene.alert_size = scene.controls_state.getAlertSize(); + scene.alert_type = scene.controls_state.getAlertType(); auto alertStatus = scene.controls_state.getAlertStatus(); if (alertStatus == cereal::ControlsState::AlertStatus::USER_PROMPT) { update_status(s, STATUS_WARNING); diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 07f2428ca6..8ee48ed4d9 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -118,6 +118,7 @@ typedef struct UIScene { std::string alert_text1; std::string alert_text2; + std::string alert_type; cereal::ControlsState::AlertSize alert_size; // Used to show gps planner status From a5ce72465b3ff7111e18433fe40e5538b85ade83 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Tue, 23 Jun 2020 11:01:05 -0700 Subject: [PATCH 350/656] 2017 Lexus RX350 F Sport fw versions --- selfdrive/car/toyota/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 6b828fec56..2a1fa6e680 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1051,11 +1051,13 @@ FW_VERSIONS = { b'\x01896630E37200\x00\x00\x00\x00', b'\x01896630E41000\x00\x00\x00\x00', b'\x01896630E41200\x00\x00\x00\x00', + b'\x01896630E37300\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152648472\x00\x00\x00\x00\x00\x00', b'F152648473\x00\x00\x00\x00\x00\x00', b'F152648492\x00\x00\x00\x00\x00\x00', + b'F152648493\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'881514810300\x00\x00\x00\x00', From 59e77423c4af2f867b26a2e1c239399e6b637b55 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 23 Jun 2020 11:40:40 -0700 Subject: [PATCH 351/656] remove unsused file --- common/compat.py | 3 --- 1 file changed, 3 deletions(-) delete mode 100644 common/compat.py diff --git a/common/compat.py b/common/compat.py deleted file mode 100644 index 369f5e2d84..0000000000 --- a/common/compat.py +++ /dev/null @@ -1,3 +0,0 @@ -# py2,3 compatiblity helpers - -basestring = (str, bytes) From 3aa99a01d7a29c69f1b767b3fca30d18a6047425 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Tue, 23 Jun 2020 14:33:32 -0700 Subject: [PATCH 352/656] recover EON/C2 AF (#1665) --- selfdrive/camerad/cameras/camera_qcom.cc | 139 ++++++++---------- selfdrive/camerad/cameras/camera_qcom.h | 15 ++ selfdrive/camerad/imgproc/utils.h | 6 +- selfdrive/camerad/main.cc | 27 ++++ selfdrive/controls/controlsd.py | 5 +- selfdrive/controls/lib/events.py | 10 +- .../test/longitudinal_maneuvers/plant.py | 4 + .../test/process_replay/process_replay.py | 2 +- 8 files changed, 124 insertions(+), 84 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index 1c7af57ba8..d9baec2870 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -123,6 +123,8 @@ static void camera_init(CameraState *s, int camera_id, int camera_num, s->max_gain = max_gain; s->fps = fps; + s->self_recover = 0; + zsock_t *ops_sock = zsock_new_push(">inproc://cameraops"); assert(ops_sock); s->ops_sock = zsock_resolve(ops_sock); @@ -1745,8 +1747,13 @@ static void parse_autofocus(CameraState *s, uint8_t *d) { avg_focus += s->focus[i]; } } + // self recover override + if (s->self_recover > 1) { + s->focus_err = 200 * ((s->self_recover % 2 == 0) ? 1:-1); // far for even numbers, close for odd + s->self_recover -= 2; + return; + } - //printf("\n"); if (good_count < 4) { s->focus_err = nan(""); return; @@ -1770,8 +1777,8 @@ static void do_autofocus(CameraState *s) { float err = s->focus_err; float sag = (s->last_sag_acc_z/9.8) * 128; - const int dac_up = s->device == DEVICE_LP3? 634:456; - const int dac_down = s->device == DEVICE_LP3? 366:224; + const int dac_up = s->device == DEVICE_LP3? LP3_AF_DAC_UP:OP3T_AF_DAC_UP; + const int dac_down = s->device == DEVICE_LP3? LP3_AF_DAC_DOWN:OP3T_AF_DAC_DOWN; if (!isnan(err)) { // learn lens_true_pos @@ -1980,43 +1987,6 @@ static FrameMetadata get_frame_metadata(CameraState *s, uint32_t frame_id) { }; } -static bool acceleration_from_sensor_sock(void *sock, float *vs) { - int err; - bool ret = false; - zmq_msg_t msg; - err = zmq_msg_init(&msg); - assert(err == 0); - - err = zmq_msg_recv(&msg, sock, 0); - assert(err >= 0); - - void *data = zmq_msg_data(&msg); - size_t size = zmq_msg_size(&msg); - - auto amsg = kj::heapArray(size / sizeof(capnp::word) + 1); - memcpy(amsg.begin(), data, size); - capnp::FlatArrayMessageReader cmsg(amsg); - auto event = cmsg.getRoot(); - if (event.which() == cereal::Event::SENSOR_EVENTS) { - auto sensor_events = event.getSensorEvents(); - for (auto sensor_event : sensor_events) { - if (sensor_event.which() == cereal::SensorEventData::ACCELERATION) { - auto v = sensor_event.getAcceleration().getV(); - if (v.size() < 3) { - continue; //wtf - } - for (int j = 0; j < 3; j++) { - vs[j] = v[j]; - } - ret = true; - break; - } - } - } - zmq_msg_close(&msg); - return ret; -} - static void ops_term() { zsock_t *ops_sock = zsock_new_push(">inproc://cameraops"); assert(ops_sock); @@ -2036,66 +2006,81 @@ static void* ops_thread(void* arg) { zsock_t *cameraops = zsock_new_pull("@inproc://cameraops"); assert(cameraops); - zsock_t *sensor_sock = zsock_new_sub(">tcp://127.0.0.1:8003", ""); - assert(sensor_sock); - zsock_t *terminate = zsock_new_sub(">inproc://terminate", ""); assert(terminate); - zpoller_t *poller = zpoller_new(cameraops, sensor_sock, terminate, NULL); + zpoller_t *poller = zpoller_new(cameraops, terminate, NULL); assert(poller); - while (!do_exit) { + SubMaster sm({"sensorEvents"}); // msgq submaster + while (!do_exit) { + // zmq handling zsock_t *which = (zsock_t*)zpoller_wait(poller, -1); - if (which == terminate || which == NULL) { + if (which == terminate) { break; - } - void* sockraw = zsock_resolve(which); - - if (which == cameraops) { - zmq_msg_t msg; - err = zmq_msg_init(&msg); - assert(err == 0); - - err = zmq_msg_recv(&msg, sockraw, 0); - assert(err >= 0); - - CameraMsg cmsg; - if (zmq_msg_size(&msg) == sizeof(cmsg)) { - memcpy(&cmsg, zmq_msg_data(&msg), zmq_msg_size(&msg)); - - //LOGD("cameraops %d", cmsg.type); + } else if (which != NULL) { + void* sockraw = zsock_resolve(which); + + if (which == cameraops) { + zmq_msg_t msg; + err = zmq_msg_init(&msg); + assert(err == 0); + + err = zmq_msg_recv(&msg, sockraw, 0); + assert(err >= 0); + + CameraMsg cmsg; + if (zmq_msg_size(&msg) == sizeof(cmsg)) { + memcpy(&cmsg, zmq_msg_data(&msg), zmq_msg_size(&msg)); + + //LOGD("cameraops %d", cmsg.type); + + if (cmsg.type == CAMERA_MSG_AUTOEXPOSE) { + if (cmsg.camera_num == 0) { + do_autoexposure(&s->rear, cmsg.grey_frac); + do_autofocus(&s->rear); + } else { + do_autoexposure(&s->front, cmsg.grey_frac); + } + } else if (cmsg.type == -1) { + break; + } + } - if (cmsg.type == CAMERA_MSG_AUTOEXPOSE) { - if (cmsg.camera_num == 0) { - do_autoexposure(&s->rear, cmsg.grey_frac); - do_autofocus(&s->rear); - } else { - do_autoexposure(&s->front, cmsg.grey_frac); + zmq_msg_close(&msg); + } + } + // msgq handling + if (sm.update(0) > 0) { + float vals[3] = {0.0}; + bool got_accel = false; + + auto sensor_events = sm["sensorEvents"].getSensorEvents(); + for (auto sensor_event : sensor_events) { + if (sensor_event.which() == cereal::SensorEventData::ACCELERATION) { + auto v = sensor_event.getAcceleration().getV(); + if (v.size() < 3) { + continue; //wtf } - } else if (cmsg.type == -1) { + for (int j = 0; j < 3; j++) { + vals[j] = v[j]; + } + got_accel = true; break; } } - zmq_msg_close(&msg); - - } else if (which == sensor_sock) { - float vs[3] = {0.0}; - bool got_accel = acceleration_from_sensor_sock(sockraw, vs); - uint64_t ts = nanos_since_boot(); if (got_accel && ts - s->rear.last_sag_ts > 10000000) { // 10 ms s->rear.last_sag_ts = ts; - s->rear.last_sag_acc_z = -vs[2]; + s->rear.last_sag_acc_z = -vals[2]; } } } zpoller_destroy(&poller); zsock_destroy(&cameraops); - zsock_destroy(&sensor_sock); zsock_destroy(&terminate); return NULL; diff --git a/selfdrive/camerad/cameras/camera_qcom.h b/selfdrive/camerad/cameras/camera_qcom.h index 1a9c31baa3..063b813c7b 100644 --- a/selfdrive/camerad/cameras/camera_qcom.h +++ b/selfdrive/camerad/cameras/camera_qcom.h @@ -4,6 +4,7 @@ #include #include #include +#include "messaging.hpp" #include "msmb_isp.h" #include "msmb_ispif.h" @@ -25,6 +26,18 @@ #define NUM_FOCUS 8 +#define LP3_AF_DAC_DOWN 366 +#define LP3_AF_DAC_UP 634 +#define LP3_AF_DAC_M 440 +#define LP3_AF_DAC_3SIG 52 +#define OP3T_AF_DAC_DOWN 224 +#define OP3T_AF_DAC_UP 456 +#define OP3T_AF_DAC_M 300 +#define OP3T_AF_DAC_3SIG 96 + +#define FOCUS_RECOVER_PATIENCE 50 // 2.5 seconds of complete blur +#define FOCUS_RECOVER_STEPS 240 // 6 seconds + #ifdef __cplusplus extern "C" { #endif @@ -100,6 +113,8 @@ typedef struct CameraState { float last_sag_acc_z; float lens_true_pos; + int self_recover; // af recovery counter, neg is patience, pos is active + int fps; mat3 transform; diff --git a/selfdrive/camerad/imgproc/utils.h b/selfdrive/camerad/imgproc/utils.h index f77a456912..203ac57a66 100644 --- a/selfdrive/camerad/imgproc/utils.h +++ b/selfdrive/camerad/imgproc/utils.h @@ -11,8 +11,8 @@ #define ROI_Y_MIN 2 #define ROI_Y_MAX 3 -#define LM_THRESH 222 -#define LM_PREC_THRESH 0.9 +#define LM_THRESH 120 +#define LM_PREC_THRESH 0.9 // 90 perc is blur // only apply to QCOM #define FULL_STRIDE_X 1280 @@ -27,4 +27,4 @@ const int16_t lapl_conv_krnl[9] = {0, 1, 0, void get_lapmap_one(int16_t *lap, uint16_t *res, int x_pitch, int y_pitch); bool is_blur(uint16_t *lapmap); -#endif \ No newline at end of file +#endif diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index 2178a0c611..d1e659b465 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -475,6 +475,32 @@ void* processing_thread(void *arg) { /*t11 = millis_since_boot(); printf("process time: %f ms\n ----- \n", t11 - t10); t10 = millis_since_boot();*/ + + // setup self recover + if (is_blur(&s->lapres[0]) && + (s->cameras.rear.lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_DOWN:OP3T_AF_DAC_DOWN)+1 || + s->cameras.rear.lens_true_pos > (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_UP:OP3T_AF_DAC_UP)-1) && + s->cameras.rear.self_recover < 2) { + // truly stuck, needs help + s->cameras.rear.self_recover -= 1; + if (s->cameras.rear.self_recover < -FOCUS_RECOVER_PATIENCE) { + LOGW("rear camera bad state detected. attempting recovery from %.1f, recover state is %d", + s->cameras.rear.lens_true_pos, s->cameras.rear.self_recover); + s->cameras.rear.self_recover = FOCUS_RECOVER_STEPS + ((s->cameras.rear.lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M:OP3T_AF_DAC_M))?1:0); // parity determined by which end is stuck at + } + } else if ((s->cameras.rear.lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M - LP3_AF_DAC_3SIG:OP3T_AF_DAC_M - OP3T_AF_DAC_3SIG) || + s->cameras.rear.lens_true_pos > (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M + LP3_AF_DAC_3SIG:OP3T_AF_DAC_M + OP3T_AF_DAC_3SIG)) && + s->cameras.rear.self_recover < 2) { + // in suboptimal position with high prob, but may still recover by itself + s->cameras.rear.self_recover -= 1; + if (s->cameras.rear.self_recover < -(FOCUS_RECOVER_PATIENCE*3)) { + LOGW("rear camera bad state detected. attempting recovery from %.1f, recover state is %d", s->cameras.rear.lens_true_pos, s->cameras.rear.self_recover); + s->cameras.rear.self_recover = FOCUS_RECOVER_STEPS/2 + ((s->cameras.rear.lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M:OP3T_AF_DAC_M))?1:0); + } + } else if (s->cameras.rear.self_recover < 0) { + s->cameras.rear.self_recover += 1; // reset if fine + } + #endif double t2 = millis_since_boot(); @@ -527,6 +553,7 @@ void* processing_thread(void *arg) { framed.setFocusConf(focus_confs); kj::ArrayPtr sharpness_score(&s->lapres[0], (ROI_X_MAX-ROI_X_MIN+1)*(ROI_Y_MAX-ROI_Y_MIN+1)); framed.setSharpnessScore(sharpness_score); + framed.setRecoverState(s->cameras.rear.self_recover); #endif // TODO: add this back diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 3fbf4aa5dd..9de1069169 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -52,7 +52,7 @@ class Controls: self.sm = sm if self.sm is None: - self.sm = messaging.SubMaster(['thermal', 'health', 'model', 'liveCalibration', + self.sm = messaging.SubMaster(['thermal', 'health', 'frame', 'model', 'liveCalibration', 'dMonitoringState', 'plan', 'pathPlan', 'liveLocationKalman']) self.can_sock = can_sock @@ -212,6 +212,9 @@ class Controls: self.events.add(EventName.vehicleModelInvalid) if not self.sm['liveLocationKalman'].posenetOK: self.events.add(EventName.posenetInvalid) + if not self.sm['frame'].recoverState < 2: + # counter>=2 is active + self.events.add(EventName.focusRecoverActive) if not self.sm['plan'].radarValid: self.events.add(EventName.radarFault) if self.sm['plan'].radarCanError: diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 3970a57bd7..805471903c 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -208,8 +208,6 @@ EVENTS = { EventName.laneChangeBlocked: {}, - EventName.focusRecoverActive: {}, - # ********** events only containing alerts displayed in all states ********** EventName.debugAlert: { @@ -524,6 +522,14 @@ EVENTS = { ET.NO_ENTRY: NoEntryAlert("Vision Model Output Uncertain"), }, + EventName.focusRecoverActive: { + ET.WARNING: Alert( + "TAKE CONTROL", + "Attempting Refocus: Camera Focus Invalid", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimeWarning1, .4, 2., 3.), + }, + EventName.outOfSpace: { ET.NO_ENTRY: NoEntryAlert("Out of Storage Space", duration_hud_alert=0.), diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index 3447f119fc..9acb9cd282 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -112,6 +112,7 @@ class Plant(): Plant.logcan = messaging.pub_sock('can') Plant.sendcan = messaging.sub_sock('sendcan') Plant.model = messaging.pub_sock('model') + Plant.frame_pub = messaging.pub_sock('frame') Plant.live_params = messaging.pub_sock('liveParameters') Plant.live_location_kalman = messaging.pub_sock('liveLocationKalman') Plant.health = messaging.pub_sock('health') @@ -161,6 +162,7 @@ class Plant(): def close(self): Plant.logcan.close() Plant.model.close() + Plant.frame_pub.close() Plant.live_params.close() Plant.live_location_kalman.close() @@ -391,6 +393,7 @@ class Plant(): if publish_model and self.frame % 5 == 0: md = messaging.new_message('model') cal = messaging.new_message('liveCalibration') + fp = messaging.new_message('frame') md.model.frameId = 0 for x in [md.model.path, md.model.leftLane, md.model.rightLane]: x.points = [0.0]*50 @@ -422,6 +425,7 @@ class Plant(): # fake values? Plant.model.send(md.to_bytes()) Plant.cal.send(cal.to_bytes()) + Plant.frame_pub.send(fp.to_bytes()) Plant.logcan.send(can_list_to_can_capnp(can_msgs)) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 6fd3c8ec2d..19e6301d3a 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -213,7 +213,7 @@ CONFIGS = [ pub_sub={ "can": ["controlsState", "carState", "carControl", "sendcan", "carEvents", "carParams"], "thermal": [], "health": [], "liveCalibration": [], "dMonitoringState": [], "plan": [], "pathPlan": [], "gpsLocation": [], "liveLocationKalman": [], - "model": [], + "model": [], "frame": [], }, ignore=["logMonoTime", "valid", "controlsState.startMonoTime", "controlsState.cumLagMs"], init_callback=fingerprint, From 99949cc27db23662bb97747ce911a99829e9cc15 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 23 Jun 2020 15:16:55 -0700 Subject: [PATCH 353/656] ui, fix vision_seen when starting with camerad already running --- selfdrive/ui/ui.cc | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index f352adf699..d622d61563 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -198,6 +198,9 @@ static void ui_init(UIState *s) { s->pm = new PubMaster({"offroadLayout"}); s->ipc_fd = -1; + s->scene.satelliteCount = -1; + s->started = false; + s->vision_seen = false; // init display s->fb = framebuffer_init("ui", 0, true, &s->fb_w, &s->fb_h); @@ -734,6 +737,7 @@ int main(int argc, char* argv[]) { UIState uistate = {}; UIState *s = &uistate; ui_init(s); + enable_event_processing(true); pthread_t connect_thread_handle; @@ -774,10 +778,6 @@ int main(int argc, char* argv[]) { int draws = 0; - s->scene.satelliteCount = -1; - s->started = false; - s->vision_seen = false; - while (!do_exit) { bool should_swap = false; if (!s->started) { From 0842e98ad832ec5dbd1afe1bfda5893c21aa1ef6 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 23 Jun 2020 15:26:25 -0700 Subject: [PATCH 354/656] fix #1762, add timeout on ubloxRaw receive --- selfdrive/locationd/ubloxd_main.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/ubloxd_main.cc b/selfdrive/locationd/ubloxd_main.cc index 8e6007a75c..690f4449f9 100644 --- a/selfdrive/locationd/ubloxd_main.cc +++ b/selfdrive/locationd/ubloxd_main.cc @@ -41,7 +41,7 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) PubMaster pm({"ubloxGnss", "gpsLocationExternal"}); while (!do_exit) { - Message * msg = subscriber->receive(); + Message * msg = subscriber->receive(100); if (!msg){ continue; } From b44569284a70b07b15daa580922d895a70956c20 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Tue, 23 Jun 2020 15:33:04 -0700 Subject: [PATCH 355/656] test each model fingerprints with FW fingerprinting (#1769) * test each model fingerprints with FW fingerprinting * lock * test for all --- Dockerfile.openpilot | 3 +- Pipfile | 1 + Pipfile.lock | 164 +++++++++++---------- selfdrive/car/tests/test_fw_fingerprint.py | 39 ++++- 4 files changed, 125 insertions(+), 82 deletions(-) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 71827ae9b8..865f6bdc20 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -72,7 +72,8 @@ RUN pyenv install 3.8.2 && \ azure-storage-nspkg==3.1.0 \ pycurl==7.43.0.3 \ coverage==5.1 \ - pre-commit==2.4.0 + pre-commit==2.4.0 \ + parameterized==0.7.4 RUN mkdir -p /tmp/openpilot diff --git a/Pipfile b/Pipfile index fa4309ef0c..5a0ef77d4e 100644 --- a/Pipfile +++ b/Pipfile @@ -73,6 +73,7 @@ pprofile = "*" pyprof2calltree = "*" pre-commit = "*" mypy = "*" +parameterized = "*" [packages] atomicwrites = "*" diff --git a/Pipfile.lock b/Pipfile.lock index 82cb88818f..138e3c42c3 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "96924e487a9d20b4fb06eea1e6536816a157a9606051da58741c66fa6630371a" + "sha256": "b65256d0b4dedee753a145abd1aff2f81d98ddb4015f69baa8ccb374121bb4c4" }, "pipfile-spec": 6, "requires": { @@ -813,10 +813,10 @@ }, "azure-mgmt-resource": { "hashes": [ - "sha256:055e85a4053a987bf427653e75f537c750ecc27c0e7c74623a67cb859689b5a6", - "sha256:dc12f7998e2c1fd4088a8da5f02936c2985ceb7acbe994571c8b3778f26a7501" + "sha256:bd9a3938f5423741329436d2da09693845c2fad96c35fadbd7c5ae5213208345", + "sha256:c1e2d834dee84953a4e25bef119008854a861d6d3fbe79b436589dc042e5a7c5" ], - "version": "==9.0.0" + "version": "==10.0.0" }, "azure-nspkg": { "hashes": [ @@ -915,10 +915,10 @@ }, "botocore": { "hashes": [ - "sha256:7d829b162e550b201ea07600862fccbbdc028cf88a111338f964e424b0e1c562", - "sha256:db21cc82f1d6e76aec91d8801e17fa701019805268914b2d0d538a2344fba74a" + "sha256:7dd59bc766d567ca83bc6113aa139d92ba447738ccdfcd40788848553d329a52", + "sha256:cd4bb2d96ff2ec6bf4fbcdb2f241d0fb6ba1e7955b4721cf1d81f13db02768b6" ], - "version": "==1.17.1" + "version": "==1.17.9" }, "cachetools": { "hashes": [ @@ -1237,11 +1237,11 @@ }, "google-auth": { "hashes": [ - "sha256:25d3c4e457db5504c62b3e329e8e67d2c29a0cecec3aa5347ced030d8700a75d", - "sha256:e634b649967d83c02dd386ecae9ce4a571528d59d51a4228757e45f5404a060b" + "sha256:5e3f540b7b0b892000d542cea6b818b837c230e9a4db9337bb2973bcae0fc078", + "sha256:d6b390d3bb0969061ffec7e5766c45c1b39e13c302691e35029f1ad1ccd8ca3b" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.17.2" + "version": "==1.18.0" }, "google-auth-oauthlib": { "hashes": [ @@ -1260,39 +1260,39 @@ }, "grpcio": { "hashes": [ - "sha256:10cdc8946a7c2284bbc8e16d346eaa2beeaae86ea598f345df86d4ef7dfedb84", - "sha256:23bc395a32c2465564cb242e48bdd2fdbe5a4aebf307649a800da1b971ee7f29", - "sha256:2637ce96b7c954d2b71060f50eb4c72f81668f1b2faa6cbdc74677e405978901", - "sha256:3d8c510b6eabce5192ce126003d74d7751c7218d3e2ad39fcf02400d7ec43abe", - "sha256:5024b26e17a1bfc9390fb3b8077bf886eee02970af780fd23072970ef08cefe8", - "sha256:517538a54afdd67162ea2af1ac3326c0752c5d13e6ddadbc4885f6a28e91ab28", - "sha256:524ae8d3da61b856cf08abb3d0947df05402919e4be1f88328e0c1004031f72e", - "sha256:54e4658c09084b09cd83a5ea3a8bce78e4031ff1010bb8908c399a22a76a6f08", - "sha256:57c8cc2ae8cb94c3a89671af7e1380a4cdfcd6bab7ba303f4461ec32ded250ae", - "sha256:5fd9ffe938e9225c654c60eb21ff011108cc27302db85200413807e0eda99a4a", - "sha256:75b2247307a7ecaf6abc9eb2bd04af8f88816c111b87bf0044d7924396e9549c", - "sha256:7bf3cb1e0f4a9c89f7b748583b994bdce183103d89d5ff486da48a7668a052c7", - "sha256:7e02a7c40304eecee203f809a982732bd37fad4e798acad98fe73c66e44ff2db", - "sha256:806c9759f5589b3761561187408e0313a35c5c53f075c7590effab8d27d67dfe", - "sha256:80e9f9f6265149ca7c84e1c8c31c2cf3e2869c45776fbe8880a3133a11d6d290", - "sha256:81bbf78a399e0ee516c81ddad8601f12af3fc9b30f2e4b2fbd64efd327304a4d", - "sha256:886d48c32960b39e059494637eb0157a694956248d03b0de814447c188b74799", - "sha256:97b72bf2242a351a89184134adbb0ae3b422e6893c6c712bc7669e2eab21501b", - "sha256:97fcbdf1f12e0079d26db73da11ee35a09adc870b1e72fbff0211f6a8003a4e8", - "sha256:9cfb4b71cc3c8757f137d47000f9d90d4bd818733f9ab4f78bd447e052a4cb9a", - "sha256:9ef0370bcf629ece4e7e37796e4604e2514b920669be2911fc3f9c163a73a57b", - "sha256:a6dddb177b3cfa0cfe299fb9e07d6a3382cc79466bef48fe9c4326d5c5b1dcb8", - "sha256:a97ea91e31863c9a3879684b5fb3c6ab4b17c5431787548fc9f52b9483ea9c25", - "sha256:b49f243936b0f6ae8eb6adf88a1e54e736f1c6724a1bff6b591d105d708263ad", - "sha256:b85f355fc24b68a6c52f2750e7141110d1fcd07dfdc9b282de0000550fe0511b", - "sha256:c3a0ef12ee86f6e72db50e01c3dba7735a76d8c30104b9b0f7fd9d65ceb9d93f", - "sha256:da0ca9b1089d00e39a8b83deec799a4e5c37ec1b44d804495424acde50531868", - "sha256:e90f3d11185c36593186e5ff1f581acc6ddfa4190f145b0366e579de1f52803b", - "sha256:ebf0ccb782027ef9e213e03b6d00bbd8dabd80959db7d468c0738e6d94b5204c", - "sha256:eede3039c3998e2cc0f6713f4ac70f235bd32967c9b958a17bf937aceebc12c3", - "sha256:ff7931241351521b8df01d7448800ce0d59364321d8d82c49b826d455678ff08" - ], - "version": "==1.29.0" + "sha256:08362b8b09562179b14db6ffce4b88e1a6a6edac8bccb85dd35f7b214fa5a0f5", + "sha256:09bea7902adc33620d68462671942e163ab12214073ffb613d2fef3df94254f6", + "sha256:0c334d6cbe27ebaa9e7211236dc99f3a9ca2ea4b3bf89b0d2544df2924343cc5", + "sha256:0c4e316e02fc227c6fba858707baee46f30d890754fc4acdf2cfec2ea0bf0aa1", + "sha256:14743e8fdfdabbab1a2075ffafd25e0a8b1a864505e3cccdf19793766cdc4624", + "sha256:1f45ec5003101f16673436b150bac73c2355cd9ae78cb14f3707be01a39b5450", + "sha256:2121afee4e3ebea7df1137bfb4dc396b1856aff4c517780108d9ce82f57bf2f8", + "sha256:2522f1808fe41bd8807feb5330025378553745b727eacb07562319205d1fd405", + "sha256:31e9891ac742e6866aec0cf67f1892618982cfbaf08bdcf3bb2e0f0828530c38", + "sha256:32fe6369143c262d096995ebdd55eeb77f0e1dbe8343a956462ef0607527c7bc", + "sha256:37da010e209289085d3362f371d9feefc152790859470f5e413d84a95a8d3998", + "sha256:38ab75168a9024d393bf43343960da425736038d249920955f223bc762587697", + "sha256:3cb78f8078ae583810c2eb47e536b0803a039656685144db43897e8beca4e203", + "sha256:474bb992355b4a3cb8d7cb783b2d81f628c16ea921cec54ff492420e11c896f5", + "sha256:74e8b6bd0f7ae64a7eecfe9bf10bc7a905d3b3eb2775cd3a9fdcdafd277469dd", + "sha256:795f351ef70a931f8f7be6a10a509714ec0a6e36c674a071abe5da8eb6b8bb35", + "sha256:7b47ec90cab0827679b511f7f9ef4fb0077cb5d7bb3d7b917154e718bb4d983b", + "sha256:7f264d740906655a147448d57e4422723639d2d3f891734b8d5eb1675cb47192", + "sha256:872d45a2e01f47db095bec032470a8c5c0a5ebd00fc930b5ae35c756b20d2cff", + "sha256:8d3249566b2d8b97925fbb2ae6c5b63c5ebdb919828230eae06a25e9614e051b", + "sha256:9ae898c15d122a046f04ea99327e3e0bd10593eb413c4810b931103da6311a21", + "sha256:ac97beab4a749c7faf6f267f7b149f6dff4f3ad64f6f6ac1d94d04019785d6a4", + "sha256:afe1f9173b51945e66c72002995eb6d4217384aaaee53215ae85d8543251fec2", + "sha256:b022cedea66b7d6774bbd7d32d5a8a374947fb572da1a6915210b09a6f51cbdf", + "sha256:b0f7bfba0ae7a97b802348aba4e08b1e84988103cc1eb887241e7b069010058a", + "sha256:b8e5194fb20f4365eacfc3c33d61662651e12e166978186faf378ee972eb0bab", + "sha256:b934542dd61746651f7907d2d7878f62ef42fdb46935088fc6a1d8266a406ba5", + "sha256:c8ad75925e87ed68d5f7d5e3ec4b9f2ed209fae67c0abbcbd17481cc474421ba", + "sha256:d18e7fb5c5c336cc349d06cde24582e0bfa5e067fdd6268bf1519c4eb4af0199", + "sha256:d5eee9d205518ee4feb9c424475ddad18a44fea97ff405780e7cd1d6df8ee96a", + "sha256:e8f2f5d16e0164c415f1b31a8d9a81f2e4645a43d1b261375d6bab7b0adf511f" + ], + "version": "==1.30.0" }, "gunicorn": { "hashes": [ @@ -1354,11 +1354,11 @@ }, "identify": { "hashes": [ - "sha256:249ebc7e2066d6393d27c1b1be3b70433f824a120b1d8274d362f1eb419e3b52", - "sha256:781fd3401f5d2b17b22a8b18b493a48d5d948e3330634e82742e23f9c20234ef" + "sha256:acf0712ab4042642e8f44e9532d95c26fbe60c0ab8b6e5b654dd1bc6512810e0", + "sha256:b2cd24dece806707e0b50517c1b3bcf3044e0b1cb13a72e7d34aa31c91f2a55a" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.4.19" + "version": "==1.4.20" }, "idna": { "hashes": [ @@ -1431,11 +1431,11 @@ }, "jedi": { "hashes": [ - "sha256:cd60c93b71944d628ccac47df9a60fec53150de53d42dc10a7fc4b5ba6aae798", - "sha256:df40c97641cb943661d2db4c33c2e1ff75d491189423249e989bcea4464f3030" + "sha256:1ddb0ec78059e8e27ec9eb5098360b4ea0a3dd840bedf21415ea820c21b40a22", + "sha256:807d5d4f96711a2bcfdd5dfa3b1ae6d09aa53832b182090b222b5efb81f52f63" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==0.17.0" + "version": "==0.17.1" }, "jinja2": { "hashes": [ @@ -1921,25 +1921,25 @@ }, "pandas": { "hashes": [ - "sha256:034185bb615dc96d08fa13aacba8862949db19d5e7804d6ee242d086f07bcc46", - "sha256:0c9b7f1933e3226cc16129cf2093338d63ace5c85db7c9588e3e1ac5c1937ad5", - "sha256:1f6fcf0404626ca0475715da045a878c7062ed39bc859afc4ccf0ba0a586a0aa", - "sha256:1fc963ba33c299973e92d45466e576d11f28611f3549469aec4a35658ef9f4cc", - "sha256:29b4cfee5df2bc885607b8f016e901e63df7ffc8f00209000471778f46cc6678", - "sha256:2a8b6c28607e3f3c344fe3e9b3cd76d2bf9f59bc8c0f2e582e3728b80e1786dc", - "sha256:2bc2ff52091a6ac481cc75d514f06227dc1b10887df1eb72d535475e7b825e31", - "sha256:415e4d52fcfd68c3d8f1851cef4d947399232741cc994c8f6aa5e6a9f2e4b1d8", - "sha256:519678882fd0587410ece91e3ff7f73ad6ded60f6fcb8aa7bcc85c1dc20ecac6", - "sha256:51e0abe6e9f5096d246232b461649b0aa627f46de8f6344597ca908f2240cbaa", - "sha256:698e26372dba93f3aeb09cd7da2bb6dd6ade248338cfe423792c07116297f8f4", - "sha256:83af85c8e539a7876d23b78433d90f6a0e8aa913e37320785cf3888c946ee874", - "sha256:982cda36d1773076a415ec62766b3c0a21cdbae84525135bdb8f460c489bb5dd", - "sha256:a647e44ba1b3344ebc5991c8aafeb7cca2b930010923657a273b41d86ae225c4", - "sha256:b35d625282baa7b51e82e52622c300a1ca9f786711b2af7cbe64f1e6831f4126", - "sha256:bab51855f8b318ef39c2af2c11095f45a10b74cbab4e3c8199efcc5af314c648" + "sha256:02f1e8f71cd994ed7fcb9a35b6ddddeb4314822a0e09a9c5b2d278f8cb5d4096", + "sha256:13f75fb18486759da3ff40f5345d9dd20e7d78f2a39c5884d013456cec9876f0", + "sha256:35b670b0abcfed7cad76f2834041dcf7ae47fd9b22b63622d67cdc933d79f453", + "sha256:4c73f373b0800eb3062ffd13d4a7a2a6d522792fa6eb204d67a4fad0a40f03dc", + "sha256:5759edf0b686b6f25a5d4a447ea588983a33afc8a0081a0954184a4a87fd0dd7", + "sha256:5a7cf6044467c1356b2b49ef69e50bf4d231e773c3ca0558807cdba56b76820b", + "sha256:69c5d920a0b2a9838e677f78f4dde506b95ea8e4d30da25859db6469ded84fa8", + "sha256:8778a5cc5a8437a561e3276b85367412e10ae9fff07db1eed986e427d9a674f8", + "sha256:9871ef5ee17f388f1cb35f76dc6106d40cb8165c562d573470672f4cdefa59ef", + "sha256:9c31d52f1a7dd2bb4681d9f62646c7aa554f19e8e9addc17e8b1b20011d7522d", + "sha256:ab8173a8efe5418bbe50e43f321994ac6673afc5c7c4839014cf6401bbdd0705", + "sha256:ae961f1f0e270f1e4e2273f6a539b2ea33248e0e3a11ffb479d757918a5e03a9", + "sha256:b3c4f93fcb6e97d993bf87cdd917883b7dab7d20c627699f360a8fb49e9e0b91", + "sha256:c9410ce8a3dee77653bc0684cfa1535a7f9c291663bd7ad79e39f5ab58f67ab3", + "sha256:f69e0f7b7c09f1f612b1f8f59e2df72faa8a6b41c5a436dde5b615aaf948f107", + "sha256:faa42a78d1350b02a7d2f0dbe3c80791cf785663d6997891549d0f86dc49125e" ], "markers": "python_version >= '3.6.1'", - "version": "==1.0.4" + "version": "==1.0.5" }, "pandocfilters": { "hashes": [ @@ -1947,6 +1947,14 @@ ], "version": "==1.4.2" }, + "parameterized": { + "hashes": [ + "sha256:190f8cc7230eee0b56b30d7f074fd4d165f7c45e6077582d0813c8557e738490", + "sha256:59ab908e31c01505a987a2be78854e19cb1630c047bbab7848169c371d614d56" + ], + "index": "pypi", + "version": "==0.7.4" + }, "paramiko": { "hashes": [ "sha256:920492895db8013f6cc0179293147f830b8c7b21fdfc839b6bad760c27459d9f", @@ -2501,10 +2509,10 @@ }, "qtconsole": { "hashes": [ - "sha256:89442727940126c65c2f94a058f1b4693a0f5d4c4b192fd6518ba3b11f4791aa", - "sha256:fd48bf1051d6e69cec1f9e2596cfaa94e3c726c70c5d848681ebce10c029f5fd" + "sha256:4f43d0b049eacb7d723772847f0c465feccce0ccb398871a6e146001a22bad23", + "sha256:f5cb275d30fc8085e2d1d18bc363e5ba0ce6e559bf37d7d6727b773134298754" ], - "version": "==4.7.4" + "version": "==4.7.5" }, "qtpy": { "hashes": [ @@ -2546,11 +2554,11 @@ }, "rsa": { "hashes": [ - "sha256:0ddc7ab19b5781148e405a4de7f1e9929e8c1e015d11a53b81e9a6242ee8e098", - "sha256:efaf0c32afee1c136e5cd2e7ceecf2dfc65dac00fb812a1b3b8b72f6fea38dbb" + "sha256:109ea5a66744dd859bf16fe904b8d8b627adafb9408753161e766a92e7d681fa", + "sha256:6166864e23d6b5195a5cfed6cd9fed0fe774e226d8f854fcb23b7bbef0350233" ], "markers": "python_version >= '3'", - "version": "==4.4.1" + "version": "==4.6" }, "s2sphere": { "hashes": [ @@ -2892,18 +2900,18 @@ }, "virtualenv": { "hashes": [ - "sha256:5102fbf1ec57e80671ef40ed98a84e980a71194cedf30c87c2b25c3a9e0b0107", - "sha256:ccfb8e1e05a1174f7bd4c163700277ba730496094fe1a58bea9d4ac140a207c8" + "sha256:f332ba0b2dfbac9f6b1da9f11224f0036b05cdb4df23b228527c2a2d5504aeed", + "sha256:ffffcb3c78a671bb3d590ac3bc67c081ea2188befeeb058870cba13e7f82911b" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==20.0.23" + "version": "==20.0.25" }, "wcwidth": { "hashes": [ - "sha256:79375666b9954d4a1a10739315816324c3e73110af9d0e102d906fdb0aec009f", - "sha256:8c6b5b6ee1360b842645f336d9e5d68c55817c26d3050f46b235ef2bc650e48f" + "sha256:beb4802a9cebb9144e99086eff703a642a13d6a0052920003a230f3294bbe784", + "sha256:c4d647b99872929fdb7bdcaa4fbe7f01413ed3d98077df798530e5b04f116c83" ], - "version": "==0.2.4" + "version": "==0.2.5" }, "webencodings": { "hashes": [ diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index 4d166639e5..a9050e2373 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -1,5 +1,9 @@ #!/usr/bin/env python3 +import random import unittest +from itertools import product +from parameterized import parameterized + from cereal import car from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.fw_versions import match_fw_to_car @@ -14,7 +18,7 @@ class TestFwFingerprint(unittest.TestCase): def assertFingerprints(self, candidates, expected): candidates = list(candidates) self.assertEqual(len(candidates), 1) - self.assertEqual(candidates[0], TOYOTA.RAV4_TSS2) + self.assertEqual(candidates[0], expected) def test_rav4_tss2(self): CP = car.CarParams.new_message() @@ -43,13 +47,42 @@ class TestFwFingerprint(unittest.TestCase): self.assertFingerprints(match_fw_to_car(CP.carFw), TOYOTA.RAV4_TSS2) + @parameterized.expand([(k, v) for k, v in FW_VERSIONS.items()]) + def test_fw_fingerprint_all(self, car_model, ecus): + # TODO: this is too slow, so don't run for now + return + + ecu_fw_lists = [] # pylint: disable=W0101 + for ecu, fw_versions in ecus.items(): + ecu_name, addr, sub_addr = ecu + ecu_fw_lists.append([]) + for fw in fw_versions: + ecu_fw_lists[-1].append({"ecu": ecu_name, "fwVersion": fw, "address": addr, + "subAddress": 0 if sub_addr is None else sub_addr}) + CP = car.CarParams.new_message() + for car_fw in product(*ecu_fw_lists): + CP.carFw = car_fw + self.assertFingerprints(match_fw_to_car(CP.carFw), car_model) + + @parameterized.expand([(k, v) for k, v in FW_VERSIONS.items()]) + def test_fw_fingerprint(self, car_model, ecus): + CP = car.CarParams.new_message() + for _ in range(20): + fw = [] + for ecu, fw_versions in ecus.items(): + ecu_name, addr, sub_addr = ecu + fw.append({"ecu": ecu_name, "fwVersion": random.choice(fw_versions), + "address": addr, "subAddress": 0 if sub_addr is None else sub_addr}) + CP.carFw = fw + self.assertFingerprints(match_fw_to_car(CP.carFw), car_model) + def test_no_duplicate_fw_versions(self): passed = True - for car_name, ecus in FW_VERSIONS.items(): + for car_model, ecus in FW_VERSIONS.items(): for ecu, ecu_fw in ecus.items(): duplicates = set([fw for fw in ecu_fw if ecu_fw.count(fw) > 1]) if len(duplicates): - print(car_name, ECU_NAME[ecu[0]], duplicates) + print(car_model, ECU_NAME[ecu[0]], duplicates) passed = False self.assertTrue(passed, "Duplicate FW versions found") From 31ea066acbe47062622b9711ef9337a375cae80a Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 23 Jun 2020 15:43:29 -0700 Subject: [PATCH 356/656] Revert "fix #1762, add timeout on ubloxRaw receive" This reverts commit 0842e98ad832ec5dbd1afe1bfda5893c21aa1ef6. --- selfdrive/locationd/ubloxd_main.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/ubloxd_main.cc b/selfdrive/locationd/ubloxd_main.cc index 690f4449f9..8e6007a75c 100644 --- a/selfdrive/locationd/ubloxd_main.cc +++ b/selfdrive/locationd/ubloxd_main.cc @@ -41,7 +41,7 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) PubMaster pm({"ubloxGnss", "gpsLocationExternal"}); while (!do_exit) { - Message * msg = subscriber->receive(100); + Message * msg = subscriber->receive(); if (!msg){ continue; } From 33f905b1ed131c26557c5429a9ba8af9f16110bd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 23 Jun 2020 15:41:33 -0700 Subject: [PATCH 357/656] fix CPU usage test for thermald and dmonitoringd --- common/manager_helpers.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/manager_helpers.py b/common/manager_helpers.py index 5f1c859648..ed3c4239df 100644 --- a/common/manager_helpers.py +++ b/common/manager_helpers.py @@ -15,11 +15,11 @@ def print_cpu_usage(first_proc, last_proc): ("selfdrive.locationd.locationd", 34.38), ("selfdrive.locationd.paramsd", 11.53), ("./_sensord", 6.17), - ("selfdrive.controls.dmonitoringd", 5.48), + ("selfdrive.monitoring.dmonitoringd", 5.48), ("./boardd", 3.63), ("./_dmonitoringmodeld", 2.67), ("selfdrive.logmessaged", 2.71), - ("selfdrive.thermald", 2.41), + ("selfdrive.thermald.thermald", 2.41), ("selfdrive.locationd.calibrationd", 6.81), ("./proclogd", 1.54), ("./_gpsd", 0.09), From 28110ea8801ce75835d59508dde4229454309b68 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 23 Jun 2020 15:56:00 -0700 Subject: [PATCH 358/656] Set timeouts on boardd and ubloxd receive sockets --- selfdrive/boardd/boardd.cc | 26 ++++++++++++++++---------- selfdrive/locationd/ubloxd_main.cc | 4 ++++ 2 files changed, 20 insertions(+), 10 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 9c8f6ebac7..d85aa00661 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -531,8 +531,8 @@ void can_send(cereal::Event::Reader &event) { //Older than 1 second. Dont send. return; } - - auto can_data_list = event.getSendcan(); + + auto can_data_list = event.getSendcan(); int msg_count = can_data_list.size(); uint32_t *send = (uint32_t*)malloc(msg_count*0x10); @@ -586,20 +586,26 @@ void *can_send_thread(void *crap) { Context * context = Context::create(); SubSocket * subscriber = SubSocket::create(context, "sendcan"); assert(subscriber != NULL); + subscriber->setTimeout(100); // run as fast as messages come in while (!do_exit) { Message * msg = subscriber->receive(); - if (msg){ - auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), msg->getData(), msg->getSize()); - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::Event::Reader event = cmsg.getRoot(); - can_send(event); - delete msg; + if (!msg){ + if (errno == EINTR) { + do_exit = true; + } + continue; } + + auto amsg = kj::heapArray((msg->getSize() / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), msg->getData(), msg->getSize()); + + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + can_send(event); + delete msg; } delete subscriber; diff --git a/selfdrive/locationd/ubloxd_main.cc b/selfdrive/locationd/ubloxd_main.cc index 8e6007a75c..b0b5bcd08c 100644 --- a/selfdrive/locationd/ubloxd_main.cc +++ b/selfdrive/locationd/ubloxd_main.cc @@ -37,12 +37,16 @@ int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) Context * context = Context::create(); SubSocket * subscriber = SubSocket::create(context, "ubloxRaw"); assert(subscriber != NULL); + subscriber->setTimeout(100); PubMaster pm({"ubloxGnss", "gpsLocationExternal"}); while (!do_exit) { Message * msg = subscriber->receive(); if (!msg){ + if (errno == EINTR) { + do_exit = true; + } continue; } From 16a23c98fae55585ae37a748416dc2514b8f1b89 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 23 Jun 2020 16:05:47 -0700 Subject: [PATCH 359/656] eon needs include for errno --- selfdrive/boardd/boardd.cc | 1 + selfdrive/locationd/ubloxd_main.cc | 1 + 2 files changed, 2 insertions(+) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index d85aa00661..a26a0729ed 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -5,6 +5,7 @@ #include #include #include +#include #include #include #include diff --git a/selfdrive/locationd/ubloxd_main.cc b/selfdrive/locationd/ubloxd_main.cc index b0b5bcd08c..ad895f8d3e 100644 --- a/selfdrive/locationd/ubloxd_main.cc +++ b/selfdrive/locationd/ubloxd_main.cc @@ -4,6 +4,7 @@ #include #include #include +#include #include #include #include From f8ce6502a9d66008d3a90b521707c4d1cbc51756 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 23 Jun 2020 15:55:58 -0700 Subject: [PATCH 360/656] better alert when controls takes too long to start --- selfdrive/ui/ui.cc | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index d622d61563..32c1543e5a 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -514,7 +514,6 @@ static void ui_update(UIState *s) { s->vision_connect_firstrun = false; - s->controls_timeout = 6 * UI_FREQ; s->alert_blinking_alpha = 1.0; s->alert_blinked = false; } @@ -813,6 +812,10 @@ int main(int argc, char* argv[]) { if (!s->started) { // always process events offroad check_messages(s); + + if (s->started) { + s->controls_timeout = 5 * UI_FREQ; + } } else { set_awake(s, true); // Car started, fetch a new rgb image from ipc @@ -860,11 +863,9 @@ int main(int argc, char* argv[]) { } else if (s->started) { if (!s->controls_seen) { // car is started, but controlsState hasn't been seen at all - LOGE("Controls failed to start"); s->scene.alert_text1 = "openpilot Unavailable"; - s->scene.alert_text2 = "Controls Failed to Start"; + s->scene.alert_text2 = "Waiting for controls to start"; s->scene.alert_size = cereal::ControlsState::AlertSize::MID; - update_status(s, STATUS_WARNING); } else { // car is started, but controls is lagging or died LOGE("Controls unresponsive"); From 09e7d4ab3a044fd5279cce43853f69465eac876f Mon Sep 17 00:00:00 2001 From: martinl Date: Wed, 24 Jun 2020 02:07:46 +0300 Subject: [PATCH 361/656] Subaru Forester 2019 (#1768) * Add initial Forester 2019 support * Add dgranger15 Forester 2019 FPv1 * fingerprint syntax fix * FPv1 syntax fix 2 * Add Forester 2019 to CAR * fix indent * Add Forester 2019 to test_car_models ignore list * Update Forester 2019 steering tuning (dgranger15) * Add Forester 2019 to README.md * Change lists to single value * Add test route for Forester 2019 * Remove model year * Remove Forester model year in test_car_models * Remove usernames, add Forester ACC speed mph unit value --- README.md | 1 + selfdrive/car/subaru/carstate.py | 4 ++-- selfdrive/car/subaru/interface.py | 12 +++++++++++- selfdrive/car/subaru/values.py | 11 +++++++++++ selfdrive/test/test_car_models.py | 4 ++++ 5 files changed, 29 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 7d29096bd5..66b659686f 100644 --- a/README.md +++ b/README.md @@ -158,6 +158,7 @@ Community Maintained Cars and Features | Nissan | Rogue 20192 | Propilot | Stock | 0mph | 0mph | | Nissan | X-Trail 20172 | Propilot | Stock | 0mph | 0mph | | Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | +| Subaru | Forester 2019 | EyeSight | Stock | 0mph | 0mph | | Subaru | Impreza 2017-20 | EyeSight | Stock | 0mph | 0mph | | Volkswagen| Golf 2015-19 | Driver Assistance | Stock | 0mph | 0mph | diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index 41bc129ebb..a1dc3b5cc2 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -51,8 +51,8 @@ class CarState(CarStateBase): ret.cruiseState.enabled = cp.vl["CruiseControl"]['Cruise_Activated'] != 0 ret.cruiseState.available = cp.vl["CruiseControl"]['Cruise_On'] != 0 ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]['Cruise_Set_Speed'] * CV.KPH_TO_MS - # 1 = imperial, 6 = metric - if cp.vl["Dash_State"]['Units'] == 1: + # EDM Impreza: 1 = mph, UDM Forester: 7 = mph + if cp.vl["Dash_State"]['Units'] in [1, 7]: ret.cruiseState.speed *= CV.MPH_TO_KPH ret.seatbeltUnlatched = cp.vl["Dashlights"]['SEATBELT_FL'] == 1 diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index a0cfdd0102..3bc13c76e1 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -28,7 +28,7 @@ class CarInterface(CarInterfaceBase): ret.steerRateCost = 0.7 ret.steerLimitTimer = 0.4 - if candidate in [CAR.IMPREZA]: + if candidate == CAR.IMPREZA: ret.mass = 1568. + STD_CARGO_KG ret.wheelbase = 2.67 ret.centerToFront = ret.wheelbase * 0.5 @@ -38,6 +38,16 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.3], [0.02, 0.03]] + if candidate == CAR.FORESTER: + ret.mass = 1568. + STD_CARGO_KG + ret.wheelbase = 2.67 + ret.centerToFront = ret.wheelbase * 0.5 + ret.steerRatio = 17 # learned, 14 stock + ret.steerActuatorDelay = 0.1 + ret.lateralTuning.pid.kf = 0.000038 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] + # TODO: get actual value, for now starting with reasonable value for # civic and scaling by mass and wheelbase ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 8d50b36ab4..791edcf6db 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -6,6 +6,7 @@ Ecu = car.CarParams.Ecu class CAR: IMPREZA = "SUBARU IMPREZA LIMITED 2019" + FORESTER = "SUBARU FORESTER 2019" FINGERPRINTS = { CAR.IMPREZA: [{ @@ -15,10 +16,19 @@ FINGERPRINTS = { { 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 256: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8 }], + CAR.FORESTER: [{ + # Forester Sport 2019 + 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 282: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 552: 8, 557: 8, 576: 8, 577: 8, 722: 8, 808: 8, 811: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1651: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1698: 8, 1722: 8, 1743: 8, 1759: 8, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8 + }, + # Forester 2019 + { + 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 282: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 803: 8, 805: 8, 808: 8, 811: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1651: 8, 1657: 8, 1658: 8, 1677: 8, 1722: 8, 1759: 8, 1787: 5, 1788: 8 + }], } STEER_THRESHOLD = { CAR.IMPREZA: 80, + CAR.FORESTER: 80, } ECU_FINGERPRINT = { @@ -27,4 +37,5 @@ ECU_FINGERPRINT = { DBC = { CAR.IMPREZA: dbc_dict('subaru_global_2017', None), + CAR.FORESTER: dbc_dict('subaru_global_2017', None), } diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 0a6cc6af4d..7c6e7b3303 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -356,6 +356,10 @@ routes = { 'carFingerprint': VOLKSWAGEN.GOLF, 'enableCamera': True, }, + "c321c6b697c5a5ff|2020-06-23--11-04-33": { + 'carFingerprint': SUBARU.FORESTER, + 'enableCamera': True, + }, "791340bc01ed993d|2019-03-10--16-28-08": { 'carFingerprint': SUBARU.IMPREZA, 'enableCamera': True, From b89d10c086a6d6b8d881af58f859db9e40c7ee67 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 23 Jun 2020 16:11:01 -0700 Subject: [PATCH 362/656] fail CPU usage test if can't get usage for a process --- common/manager_helpers.py | 1 + 1 file changed, 1 insertion(+) diff --git a/common/manager_helpers.py b/common/manager_helpers.py index ed3c4239df..3668ea112c 100644 --- a/common/manager_helpers.py +++ b/common/manager_helpers.py @@ -44,6 +44,7 @@ def print_cpu_usage(first_proc, last_proc): print(f"{proc_name.ljust(35)} {cpu_usage:.2f}%") except IndexError: print(f"{proc_name.ljust(35)} NO METRICS FOUND") + r = 1 print("------------------------------------------------") return r From 3c5c8c250887d013598f18d33c8e82e8dbeb84e7 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 23 Jun 2020 19:02:42 -0700 Subject: [PATCH 363/656] lower temperatures slightly until UI/modeld GPU interaction is improved --- selfdrive/thermald/thermald.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 9e4a26c001..84a26e7447 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -276,10 +276,10 @@ def thermald_thread(): if max_cpu_temp > 107. or bat_temp >= 63. or (has_relay and (started_ts is None) and max_cpu_temp > 75.0): # onroad not allowed thermal_status = ThermalStatus.danger - elif max_comp_temp > 100.0 or bat_temp > 60.: + elif max_comp_temp > 96.0 or bat_temp > 60.: # hysteresis between onroad not allowed and engage not allowed thermal_status = clip(thermal_status, ThermalStatus.red, ThermalStatus.danger) - elif max_cpu_temp > 97.0: + elif max_cpu_temp > 94.0: # hysteresis between engage not allowed and uploader not allowed thermal_status = clip(thermal_status, ThermalStatus.yellow, ThermalStatus.red) elif max_cpu_temp > 80.0: From 20e2185eda712cd66a8a66ebfda6228fc446cbaf Mon Sep 17 00:00:00 2001 From: Chris Souers Date: Wed, 24 Jun 2020 14:57:45 -0400 Subject: [PATCH 364/656] Add FW for CRV_EU (#1772) --- selfdrive/car/honda/values.py | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index ba2ce9ce19..32bc2d3783 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -624,12 +624,21 @@ FW_VERSIONS = { ], }, CAR.CRV_EU: { - (Ecu.programmedFuelInjection, 0x18da10f1, None): [b'37805-R5Z-G740\x00\x00'], + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-R5Z-G740\x00\x00', + b'37805-R5Z-G780\x00\x00', + ], (Ecu.vsa, 0x18da28f1, None): [b'57114-T1V-G920\x00\x00'], (Ecu.fwdRadar, 0x18dab0f1, None): [b'36161-T1V-G520\x00\x00'], (Ecu.shiftByWire, 0x18da0bf1, None): [b'54008-T1V-G010\x00\x00'], - (Ecu.transmission, 0x18da1ef1, None): [b'28101-5LH-E120\x00\x00'], - (Ecu.combinationMeter, 0x18da60f1, None): [b'78109-T1V-G020\x00\x00'], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5LH-E120\x00\x00', + b'28103-5LH-E100\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-T1V-G020\x00\x00', + b'78109-T1B-3050\x00\x00', + ], (Ecu.srs, 0x18da53f1, None): [b'77959-T1G-G940\x00\x00'], }, CAR.CRV_HYBRID: { From fd29c698221b5748c155dcf2acc56260a725bde1 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Wed, 24 Jun 2020 14:01:42 -0700 Subject: [PATCH 365/656] Add Lexus NXH fw --- selfdrive/car/toyota/values.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 2a1fa6e680..414904cfe6 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1029,21 +1029,27 @@ FW_VERSIONS = { CAR.LEXUS_NXH: { (Ecu.engine, 0x7e0, None): [ b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237841000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152678160\x00\x00\x00\x00\x00\x00', + b'F152678170\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'881517804300\x00\x00\x00\x00', + b'881517804100\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B78100\x00\x00\x00\x00\x00\x00', + b'8965B78060\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F4702300\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'8646F7801300\x00\x00\x00\x00', + b'8646F7801100\x00\x00\x00\x00', ], }, CAR.LEXUS_RX: { From 28b249559702d052cb4ddfdff2fa0975ab8ff3c5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Wed, 24 Jun 2020 14:55:58 -0700 Subject: [PATCH 366/656] Hyundai stock adas signals (#1775) * add stockAeb and stockFcw to carstate * bump opendbc * freq check * bump opendbc --- opendbc | 2 +- selfdrive/car/hyundai/carstate.py | 7 +++++++ 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/opendbc b/opendbc index df1bb08344..1dfdce9f69 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit df1bb083440804c07d93f84d117d9e625b8fdb5a +Subproject commit 1dfdce9f696b4a93c9e5c66dda8d2d64a80a8fb9 diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 6a7bc6bcf0..7dfc357aad 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -113,6 +113,9 @@ class CarState(CarStateBase): else: ret.gearShifter = GearShifter.unknown + ret.stockAeb = cp.vl["FCA11"]['FCA_CmdAct'] != 0 + ret.stockFcw = cp.vl["FCA11"]['CF_VSM_Warn'] == 2 + # save the entire LKAS11 and CLU11 self.lkas11 = cp_cam.vl["LKAS11"] self.clu11 = cp.vl["CLU11"] @@ -178,6 +181,9 @@ class CarState(CarStateBase): ("SAS_Angle", "SAS11", 0), ("SAS_Speed", "SAS11", 0), + ("FCA_CmdAct", "FCA11", 0), + ("CF_VSM_Warn", "FCA11", 0), + ("MainMode_ACC", "SCC11", 0), ("VSetDis", "SCC11", 0), ("SCCInfoDisplay", "SCC11", 0), @@ -198,6 +204,7 @@ class CarState(CarStateBase): ("SAS11", 100), ("SCC11", 50), ("SCC12", 50), + ("FCA11", 50), ] if CP.carFingerprint in EV_HYBRID: From a5cd52a1c6902bd87a9ebbdae3a71a7b11f275d1 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Wed, 24 Jun 2020 15:54:43 -0700 Subject: [PATCH 367/656] Add 2020 Prius fw --- README.md | 2 +- selfdrive/car/toyota/values.py | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 66b659686f..8066856c1a 100644 --- a/README.md +++ b/README.md @@ -107,7 +107,7 @@ Supported Cars | Toyota | Highlander 2020 | All | openpilot | 0mph | 0mph | | Toyota | Highlander Hybrid 2020 | All | openpilot | 0mph | 0mph | | Toyota | Prius 2016 | TSS-P | Stock3| 0mph | 0mph | -| Toyota | Prius 2017-19 | All | Stock3| 0mph | 0mph | +| Toyota | Prius 2017-20 | All | Stock3| 0mph | 0mph | | Toyota | Prius Prime 2017-20 | All | Stock3| 0mph | 0mph | | Toyota | Rav4 2016 | TSS-P | Stock3| 20mph1 | 0mph | | Toyota | Rav4 2017-18 | All | Stock3| 20mph1 | 0mph | diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 414904cfe6..5cfa05e292 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -750,6 +750,7 @@ FW_VERSIONS = { b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', b'\x03896634789000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707001\x00\x00\x00\x00', + b'\x038966347B6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', b'\x038966347B7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ From f1caed7299cdba5e45635d8377da6cc1e5fd7072 Mon Sep 17 00:00:00 2001 From: George Hotz Date: Wed, 24 Jun 2020 16:02:03 -0700 Subject: [PATCH 368/656] 0.8 is a lie --- selfdrive/common/version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index f9b22edef6..c9fc2a6ec5 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.8" +#define COMMA_VERSION "0.7.7" From 59cbaf88ef2d1477948bbd4f21c6f8398e38be74 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Wed, 24 Jun 2020 16:11:59 -0700 Subject: [PATCH 369/656] Add missing fp value for Jeep Grand Cherokee 2019 --- selfdrive/car/chrysler/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 5c91445da9..2f74226947 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -77,7 +77,7 @@ FINGERPRINTS = { CAR.JEEP_CHEROKEE_2019: [ # Jeep Grand Cherokee 2019 # 530: 8 is so far only in this Jeep. - {55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1543: 8, 2015: 8, 2016: 8, 2024: 8}, + {55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1543: 8, 2015: 8, 2016: 8, 2024: 8}, ], } From c4a3d7afb0a190ea0abcf3deb0ec754b31de2cb3 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Wed, 24 Jun 2020 17:31:09 -0700 Subject: [PATCH 370/656] Block lane change start on blindspot detection (#1712) * use BSM to block lane change start * remove duplicate entry * add approaching --- selfdrive/car/toyota/carstate.py | 6 ++++-- selfdrive/controls/controlsd.py | 11 ++++++++--- selfdrive/controls/lib/events.py | 10 ++++++++-- selfdrive/controls/lib/pathplanner.py | 5 ++++- selfdrive/test/process_replay/ref_commit | 2 +- 5 files changed, 25 insertions(+), 9 deletions(-) diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 02bd893eeb..d4cc71640f 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -104,8 +104,8 @@ class CarState(CarStateBase): self.steer_state = cp.vl["EPS_STATUS"]['LKA_STATE'] if self.CP.carFingerprint in TSS2_CAR: - ret.leftBlindspot = cp.vl["BSM"]['L_ADJACENT'] == 1 - ret.rightBlindspot = cp.vl["BSM"]['R_ADJACENT'] == 1 + ret.leftBlindspot = (cp.vl["BSM"]['L_ADJACENT'] == 1) or (cp.vl["BSM"]['L_APPROACHING'] == 1) + ret.rightBlindspot = (cp.vl["BSM"]['R_ADJACENT'] == 1) or (cp.vl["BSM"]['R_APPROACHING'] == 1) return ret @@ -173,7 +173,9 @@ class CarState(CarStateBase): if CP.carFingerprint in TSS2_CAR: signals += [("L_ADJACENT", "BSM", 0)] + signals += [("L_APPROACHING", "BSM", 0)] signals += [("R_ADJACENT", "BSM", 0)] + signals += [("R_APPROACHING", "BSM", 0)] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 9de1069169..86f6ff0f56 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -183,10 +183,15 @@ class Controls: # Handle lane change if self.sm['pathPlan'].laneChangeState == LaneChangeState.preLaneChange: - if self.sm['pathPlan'].laneChangeDirection == LaneChangeDirection.left: - self.events.add(EventName.preLaneChangeLeft) + direction = self.sm['pathPlan'].laneChangeDirection + if (CS.leftBlindspot and direction == LaneChangeDirection.left) or \ + (CS.rightBlindspot and direction == LaneChangeDirection.right): + self.events.add(EventName.laneChangeBlocked) else: - self.events.add(EventName.preLaneChangeRight) + if direction == LaneChangeDirection.left: + self.events.add(EventName.preLaneChangeLeft) + else: + self.events.add(EventName.preLaneChangeRight) elif self.sm['pathPlan'].laneChangeState in [LaneChangeState.laneChangeStarting, LaneChangeState.laneChangeFinishing]: self.events.add(EventName.laneChange) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 805471903c..afa18ee207 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -206,8 +206,6 @@ EVENTS = { EventName.gasPressed: {ET.PRE_ENABLE: None}, - EventName.laneChangeBlocked: {}, - # ********** events only containing alerts displayed in all states ********** EventName.debugAlert: { @@ -443,6 +441,14 @@ EVENTS = { Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .0, .1, .1, alert_rate=0.75), }, + EventName.laneChangeBlocked: { + ET.WARNING: Alert( + "Car Detected in Blindspot", + "Monitor Other Vehicles", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .0, .1, .1), + }, + EventName.laneChange: { ET.WARNING: Alert( "Changing Lane", diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index 40e6c38002..bfe8597df6 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -114,6 +114,9 @@ class PathPlanner(): ((sm['carState'].steeringTorque > 0 and self.lane_change_direction == LaneChangeDirection.left) or (sm['carState'].steeringTorque < 0 and self.lane_change_direction == LaneChangeDirection.right)) + blindspot_detected = ((sm['carState'].leftBlindspot and self.lane_change_direction == LaneChangeDirection.left) or + (sm['carState'].leftBlindspot and self.lane_change_direction == LaneChangeDirection.left)) + lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob # State transitions @@ -126,7 +129,7 @@ class PathPlanner(): elif self.lane_change_state == LaneChangeState.preLaneChange: if not one_blinker or below_lane_change_speed: self.lane_change_state = LaneChangeState.off - elif torque_applied: + elif torque_applied and not blindspot_detected: self.lane_change_state = LaneChangeState.laneChangeStarting # starting diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 31fdb6ce07..de32dae9b2 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -12861083f7fdcfd2876d7f8102f1853a3248e2a7 \ No newline at end of file +f0ff304da1765fd9cfd36d8c730f280315df91bf \ No newline at end of file From 5e254da8b39bff7b2710652b5a3c5ec0d96abb95 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 24 Jun 2020 18:20:30 -0700 Subject: [PATCH 371/656] fix wrong car mode alert --- selfdrive/controls/lib/events.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index afa18ee207..f49a0c2fdd 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -199,7 +199,7 @@ def wrong_car_mode_alert(CP, sm, metric): text = "Cruise Mode Disabled" if CP.carName == "honda": text = "Main Switch Off" - return NoEntryAlert(text, duration_hud_alert=0.), + return NoEntryAlert(text, duration_hud_alert=0.) EVENTS = { # ********** events with no alerts ********** From 611dc4c37f4a607c26542dce67d7568a8319cf55 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 24 Jun 2020 18:48:57 -0700 Subject: [PATCH 372/656] Honda Bosch, use proper non adaptive cruise mode alert --- selfdrive/car/honda/carstate.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index c8360d756e..4845e482f8 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -298,7 +298,8 @@ class CarState(CarStateBase): ret.brake = cp.vl["VSA_STATUS"]['USER_BRAKE'] ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]['ACC_STATUS'] != 0 - ret.cruiseState.available = bool(main_on) and self.cruise_mode == 0 + ret.cruiseState.available = bool(main_on) + ret.cruiseState.nonAdaptive = self.cruise_mode != 0 # Gets rid of Pedal Grinding noise when brake is pressed at slow speeds for some models if self.CP.carFingerprint in (CAR.PILOT, CAR.PILOT_2019, CAR.RIDGELINE): From 60fc1d2e52af45cd0bf013f4458d9952839fb3fd Mon Sep 17 00:00:00 2001 From: martinl Date: Thu, 25 Jun 2020 19:28:36 +0300 Subject: [PATCH 373/656] Fix Impreza supported model years (#1778) --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 8066856c1a..67dcec9e5f 100644 --- a/README.md +++ b/README.md @@ -159,7 +159,7 @@ Community Maintained Cars and Features | Nissan | X-Trail 20172 | Propilot | Stock | 0mph | 0mph | | Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | | Subaru | Forester 2019 | EyeSight | Stock | 0mph | 0mph | -| Subaru | Impreza 2017-20 | EyeSight | Stock | 0mph | 0mph | +| Subaru | Impreza 2017-19 | EyeSight | Stock | 0mph | 0mph | | Volkswagen| Golf 2015-19 | Driver Assistance | Stock | 0mph | 0mph | 1Requires an [OBD-II car harness](https://comma.ai/shop/products/comma-car-harness) and [community built giraffe](https://github.com/commaai/openpilot/wiki/GM). ***NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).***
From 52fdd8c3ff1892a6e120c14ad80df727a7004e17 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 25 Jun 2020 11:50:24 -0700 Subject: [PATCH 374/656] add discord link to new issue page --- .github/ISSUE_TEMPLATE/bug_report.md | 2 +- .github/ISSUE_TEMPLATE/config.yml | 3 +++ .github/ISSUE_TEMPLATE/enhancement.md | 2 +- .github/ISSUE_TEMPLATE/question.md | 2 +- 4 files changed, 6 insertions(+), 3 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md index eef3048994..34ddfe17b5 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -2,7 +2,7 @@ name: Bug report about: For issues with running openpilot on your comma device title: '' -labels: '' +labels: 'bug' assignees: '' --- diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml index 13c3f5b1ef..fcb4dcd2a6 100644 --- a/.github/ISSUE_TEMPLATE/config.yml +++ b/.github/ISSUE_TEMPLATE/config.yml @@ -3,3 +3,6 @@ contact_links: - name: Community Wiki url: https://github.com/commaai/openpilot/wiki about: Check out our community wiki + - name: Community Discord + urli: https://discord.comma.ai + about: Check out our community discord diff --git a/.github/ISSUE_TEMPLATE/enhancement.md b/.github/ISSUE_TEMPLATE/enhancement.md index bb3379d9ae..96a6047703 100644 --- a/.github/ISSUE_TEMPLATE/enhancement.md +++ b/.github/ISSUE_TEMPLATE/enhancement.md @@ -1,6 +1,6 @@ --- name: Enhancement -about: suggestions for openpilot enhancements +about: For suggestions for openpilot enhancements title: '' labels: 'enhancement' assignees: '' diff --git a/.github/ISSUE_TEMPLATE/question.md b/.github/ISSUE_TEMPLATE/question.md index eecd709edf..2cd62791f9 100644 --- a/.github/ISSUE_TEMPLATE/question.md +++ b/.github/ISSUE_TEMPLATE/question.md @@ -1,6 +1,6 @@ --- name: Question -about: questions about openpilot +about: For questions about openpilot title: '' labels: 'question' assignees: '' From d933bd3f4f10246977db87427fed6dc275e2ef71 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 25 Jun 2020 12:09:17 -0700 Subject: [PATCH 375/656] add 0.7.6.1 to release notes --- RELEASES.md | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 0c0bb519cb..7b6a4ec3c9 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,9 +1,13 @@ -Version 0.8 (2020-xx-xx) +Version 0.7.7 (2020-xx-xx) ======================== * White panda is no longer supported, upgrade to comma two or black panda * Improved vehicle model estimation using high precision localizer * Improved thermal management on comma two +Version 0.7.6.1 (2020-06-16) +======================== +* Hotfix: update kernel on some comma twos (orders #8570-#8680) + Version 0.7.6 (2020-06-05) ======================== * White panda is deprecated, upgrade to comma two or black panda From d08864572fd60465650150734c43565d7a5d27b0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 25 Jun 2020 13:05:12 -0700 Subject: [PATCH 376/656] support code for NEOS update alert --- apk/ai.comma.plus.offroad.apk | 4 ++-- common/params.py | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk index f633a75123..cb0c7224fa 100644 --- a/apk/ai.comma.plus.offroad.apk +++ b/apk/ai.comma.plus.offroad.apk @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3b29d0ce5a60f77f46a3124724b4d19095205bb7d0a9fc64d58685aa94cf81b1 -size 13700367 +oid sha256:7384496705c0e7af43b0a39a4d6fe0b9a39175455a5170008a02f7b7570799b9 +size 13701442 diff --git a/common/params.py b/common/params.py index ddaf56ae51..1b34bb1daa 100755 --- a/common/params.py +++ b/common/params.py @@ -106,6 +106,7 @@ keys = { "Offroad_PandaFirmwareMismatch": [TxType.CLEAR_ON_MANAGER_START, TxType.CLEAR_ON_PANDA_DISCONNECT], "Offroad_InvalidTime": [TxType.CLEAR_ON_MANAGER_START], "Offroad_IsTakingSnapshot": [TxType.CLEAR_ON_MANAGER_START], + "Offroad_NeosUpdate": [TxType.CLEAR_ON_MANAGER_START], } From c47daa1a222fbb56571078dde9bccf7930822a10 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 25 Jun 2020 13:54:48 -0700 Subject: [PATCH 377/656] update 0.7.7 release notes --- README.md | 4 ++-- RELEASES.md | 6 ++++++ 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 67dcec9e5f..cbda18af2d 100644 --- a/README.md +++ b/README.md @@ -141,9 +141,9 @@ Community Maintained Cars and Features | Holden | Astra 20171 | Adaptive Cruise | openpilot | 0mph | 7mph | | Hyundai | Elantra 2017-19 | SCC + LKAS | Stock | 19mph | 34mph | | Hyundai | Genesis 2015-16 | SCC + LKAS | Stock | 19mph | 37mph | -| Hyundai | Ioniq 2019 Electric | SCC + LKAS | Stock | 0mph | 32mph | +| Hyundai | Ioniq Electric Limited 2019 | SCC + LKAS | Stock | 0mph | 32mph | | Hyundai | Kona 2017-19 | SCC + LKAS | Stock | 22mph | 0mph | -| Hyundai | Kona 2019 EV | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Kona EV 2019 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Palisade 2020 | All | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2019-20 | All | Stock | 0mph | 0mph | diff --git a/RELEASES.md b/RELEASES.md index 7b6a4ec3c9..995ffbac31 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -3,6 +3,12 @@ Version 0.7.7 (2020-xx-xx) * White panda is no longer supported, upgrade to comma two or black panda * Improved vehicle model estimation using high precision localizer * Improved thermal management on comma two + * Improved autofocus for road-facing camera + * Fix GM ignition detection + * Block lane change start using blindspot monitor on Toyotas with TSS2 + * Code cleanup and smaller release sizes + * Hyundai Ioniq Electric Limited 2019 support + * Subaru Forester 2019 support thanks to martinl! Version 0.7.6.1 (2020-06-16) ======================== From 38b5f25da25c9b525233cf6c1d0ff36e3650dc04 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 25 Jun 2020 15:19:48 -0700 Subject: [PATCH 378/656] actually remove all old files --- release/build_devel.sh | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/release/build_devel.sh b/release/build_devel.sh index 9febb866df..8addd776ba 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -43,12 +43,9 @@ git checkout master-ci git reset --hard origin/devel git clean -xdf -# leave .git alone +# remove everything except .git echo "[-] erasing old openpilot T=$SECONDS" -rm -rf $TARGET_DIR/* $TARGET_DIR/.gitmodules - -# delete dotfiles in root -find . -maxdepth 1 -type f -delete +find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \; # reset tree and get version cd $SOURCE_DIR From 57f29968a2662bb49807f15165fd69254da0cc93 Mon Sep 17 00:00:00 2001 From: xps-genesis <65239463+xps-genesis@users.noreply.github.com> Date: Fri, 26 Jun 2020 15:16:06 -0400 Subject: [PATCH 379/656] Add Hyundai BSM signals (#1782) * Add Hyundai BSM signals to take advantage of BSM to block lane change when BSM active. * bug, added LCA11 to canparser previous check failed, fixed by adding LCA11 to canparser * update refs Co-authored-by: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> --- selfdrive/car/hyundai/carstate.py | 7 +++++++ selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 7dfc357aad..74b2e327df 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -115,6 +115,9 @@ class CarState(CarStateBase): ret.stockAeb = cp.vl["FCA11"]['FCA_CmdAct'] != 0 ret.stockFcw = cp.vl["FCA11"]['CF_VSM_Warn'] == 2 + + ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0 + ret.rightBlindspot = cp.vl["LCA11"]["CF_Lca_IndRight"] != 0 # save the entire LKAS11 and CLU11 self.lkas11 = cp_cam.vl["LKAS11"] @@ -171,6 +174,9 @@ class CarState(CarStateBase): ("ESC_Off_Step", "TCS15", 0), ("CF_Lvr_GearInf", "LVR11", 0), # Transmission Gear (0 = N or P, 1-8 = Fwd, 14 = Rev) + + ("CF_Lca_IndLeft", "LCA11", 0), + ("CF_Lca_IndRight", "LCA11", 0), ("CR_Mdps_StrColTq", "MDPS12", 0), ("CF_Mdps_ToiActive", "MDPS12", 0), @@ -205,6 +211,7 @@ class CarState(CarStateBase): ("SCC11", 50), ("SCC12", 50), ("FCA11", 50), + ("LCA11", 50), ] if CP.carFingerprint in EV_HYBRID: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index de32dae9b2..25c62148c0 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -f0ff304da1765fd9cfd36d8c730f280315df91bf \ No newline at end of file +98d3ab8081d04d481adb83980c7852dec8881de5 From 57deb3a8930c3fa9140b48338c599dfda0f59435 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 26 Jun 2020 12:25:09 -0700 Subject: [PATCH 380/656] Hyundai Ioniq SE 2020 (#1786) * Update values.py * Update carcontroller.py * Update values.py * Update interface.py * Update carcontroller.py * add test route * readme Co-authored-by: baldwalker --- README.md | 1 + selfdrive/car/hyundai/carcontroller.py | 2 +- selfdrive/car/hyundai/interface.py | 4 ++-- selfdrive/car/hyundai/values.py | 9 +++++++-- selfdrive/test/test_car_models.py | 4 ++++ 5 files changed, 15 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index cbda18af2d..45fdfc5106 100644 --- a/README.md +++ b/README.md @@ -141,6 +141,7 @@ Community Maintained Cars and Features | Holden | Astra 20171 | Adaptive Cruise | openpilot | 0mph | 7mph | | Hyundai | Elantra 2017-19 | SCC + LKAS | Stock | 19mph | 34mph | | Hyundai | Genesis 2015-16 | SCC + LKAS | Stock | 19mph | 37mph | +| Hyundai | Ioniq Electric Premium SE 2020| SCC + LKAS | Stock | 0mph | 32mph | | Hyundai | Ioniq Electric Limited 2019 | SCC + LKAS | Stock | 0mph | 32mph | | Hyundai | Kona 2017-19 | SCC + LKAS | Stock | 22mph | 0mph | | Hyundai | Kona EV 2019 | SCC + LKAS | Stock | 0mph | 0mph | diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 9026afbb3a..8a6492a883 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -95,7 +95,7 @@ class CarController(): self.last_lead_distance = 0 # 20 Hz LFA MFA message - if frame % 5 == 0 and self.car_fingerprint in [CAR.SONATA, CAR.PALISADE]: + if frame % 5 == 0 and self.car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.IONIQ]: can_sends.append(create_lfa_mfa(self.packer, frame, enabled)) return can_sends diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 07c339ffcb..4ea4fa70cb 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -126,7 +126,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate == CAR.IONIQ_EV_LTD: + elif candidate in [CAR.IONIQ, CAR.IONIQ_EV_LTD]: ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1490. + STD_CARGO_KG #weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx ret.wheelbase = 2.7 @@ -145,7 +145,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] # these cars require a special panda safety mode due to missing counters and checksums in the messages - if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD]: + if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ]: ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy ret.centerToFront = ret.wheelbase * 0.4 diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 6963a16c6c..a760c6de69 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -20,6 +20,7 @@ class CAR: GENESIS_G80 = "GENESIS G80 2017" GENESIS_G90 = "GENESIS G90 2017" HYUNDAI_GENESIS = "HYUNDAI GENESIS 2015-2016" + IONIQ = "HYUNDAI IONIQ ELECTRIC PREMIUM SE 2020" IONIQ_EV_LTD = "HYUNDAI IONIQ ELECTRIC LIMITED 2019" KIA_FORTE = "KIA FORTE E 2018" KIA_OPTIMA = "KIA OPTIMA SX 2019 & 2016" @@ -113,6 +114,9 @@ FINGERPRINTS = { CAR.IONIQ_EV_LTD: [{ 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1425: 2, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1507: 8, 1535: 8 }], + CAR.IONIQ: [{ + 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 + }], CAR.KONA: [{ 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 909: 8, 916: 8, 1040: 8, 1078: 4, 1107: 5, 1136: 8, 1156: 8, 1170: 8, 1173: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 2004: 8, 2009: 8, 2012: 8 }], @@ -204,10 +208,10 @@ CHECKSUM = { FEATURES = { "use_cluster_gears": [CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30], # Use Cluster for Gear Selection, rather than Transmission "use_tcu_gears": [CAR.KIA_OPTIMA, CAR.SONATA_2019], # Use TCU Message for Gear Selection - "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV], # Use TCU Message for Gear Selection + "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ], # Use TCU Message for Gear Selection } -EV_HYBRID = [CAR.IONIQ_EV_LTD] +EV_HYBRID = [CAR.IONIQ_EV_LTD, CAR.IONIQ] DBC = { CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None), @@ -216,6 +220,7 @@ DBC = { CAR.GENESIS_G90: dbc_dict('hyundai_kia_generic', None), CAR.HYUNDAI_GENESIS: dbc_dict('hyundai_kia_generic', None), CAR.IONIQ_EV_LTD: dbc_dict('hyundai_kia_generic', None), + CAR.IONIQ: dbc_dict('hyundai_kia_generic', None), CAR.KIA_FORTE: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 7c6e7b3303..40ff5d0352 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -196,6 +196,10 @@ routes = { 'carFingerprint': HYUNDAI.IONIQ_EV_LTD, 'enableCamera': True, }, + "2c5cf2dd6102e5da|2020-06-26--16-00-08": { + 'carFingerprint': HYUNDAI.IONIQ, + 'enableCamera': True, + }, "f7b6be73e3dfd36c|2019-05-12--18-07-16": { 'carFingerprint': TOYOTA.AVALON, 'enableCamera': False, From 97b494e043e154bc69e0a32dee3f01b23cc752f4 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 26 Jun 2020 12:26:55 -0700 Subject: [PATCH 381/656] add Ioniq SE to release notes --- RELEASES.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 995ffbac31..49250ed97c 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -7,7 +7,7 @@ Version 0.7.7 (2020-xx-xx) * Fix GM ignition detection * Block lane change start using blindspot monitor on Toyotas with TSS2 * Code cleanup and smaller release sizes - * Hyundai Ioniq Electric Limited 2019 support + * Hyundai Ioniq Electric Limited 2019 and Ioniq SE 2020 support thanks to baldwalker! * Subaru Forester 2019 support thanks to martinl! Version 0.7.6.1 (2020-06-16) From 55aee68ca0f3c5ba9fa5b100d21149cad79b732b Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Fri, 26 Jun 2020 18:11:36 -0700 Subject: [PATCH 382/656] camerad: don't crash zmq if get interrupt from msgq (#1790) * not crash zmq if get interrupt from msgq * also filter eagain --- selfdrive/camerad/cameras/camera_qcom.cc | 36 +++++++++++++----------- 1 file changed, 20 insertions(+), 16 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index d9baec2870..9382687e8e 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -2028,24 +2028,28 @@ static void* ops_thread(void* arg) { assert(err == 0); err = zmq_msg_recv(&msg, sockraw, 0); - assert(err >= 0); - - CameraMsg cmsg; - if (zmq_msg_size(&msg) == sizeof(cmsg)) { - memcpy(&cmsg, zmq_msg_data(&msg), zmq_msg_size(&msg)); - - //LOGD("cameraops %d", cmsg.type); - - if (cmsg.type == CAMERA_MSG_AUTOEXPOSE) { - if (cmsg.camera_num == 0) { - do_autoexposure(&s->rear, cmsg.grey_frac); - do_autofocus(&s->rear); - } else { - do_autoexposure(&s->front, cmsg.grey_frac); + if (err >= 0) { + CameraMsg cmsg; + if (zmq_msg_size(&msg) == sizeof(cmsg)) { + memcpy(&cmsg, zmq_msg_data(&msg), zmq_msg_size(&msg)); + + //LOGD("cameraops %d", cmsg.type); + + if (cmsg.type == CAMERA_MSG_AUTOEXPOSE) { + if (cmsg.camera_num == 0) { + do_autoexposure(&s->rear, cmsg.grey_frac); + do_autofocus(&s->rear); + } else { + do_autoexposure(&s->front, cmsg.grey_frac); + } + } else if (cmsg.type == -1) { + break; } - } else if (cmsg.type == -1) { - break; } + } else { + // skip if zmq is interrupted by msgq + int err_no = zmq_errno(); + assert(err_no == EINTR || err_no == EAGAIN); } zmq_msg_close(&msg); From 9fb4eeea96be03450678624b6f0670ba0f7342ca Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 26 Jun 2020 20:20:46 -0700 Subject: [PATCH 383/656] update replay segment --- selfdrive/test/process_replay/camera_replay.py | 2 +- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/test/process_replay/camera_replay.py b/selfdrive/test/process_replay/camera_replay.py index da277dd7cb..8abe2c1a15 100755 --- a/selfdrive/test/process_replay/camera_replay.py +++ b/selfdrive/test/process_replay/camera_replay.py @@ -20,7 +20,7 @@ from selfdrive.test.process_replay.compare_logs import compare_logs, save_log from selfdrive.test.process_replay.test_processes import format_diff from selfdrive.version import get_git_commit -TEST_ROUTE = "5b7c365c50084530|2020-04-15--16-13-24" +TEST_ROUTE = "99c94dc769b5d96e|2019-08-03--14-19-59" def camera_replay(lr, fr): diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index e98217b72a..40e490daf6 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -18e43945403c4022b1de72237d89736e1a8ab4c7 \ No newline at end of file +55aee68ca0f3c5ba9fa5b100d21149cad79b732b \ No newline at end of file From 491a02d5d6e991f4bf6f2cace7c83c13357a89ee Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 27 Jun 2020 17:46:59 -0700 Subject: [PATCH 384/656] bump submodules --- cereal | 2 +- opendbc | 2 +- selfdrive/debug/dump.py | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/cereal b/cereal index 8d5230e59b..4e3541ae43 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 8d5230e59b0ed7c93c66863d0cd19e5f180e417c +Subproject commit 4e3541ae432cf719ae67546c50e01ae580738a38 diff --git a/opendbc b/opendbc index 1dfdce9f69..1fd5a9b954 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 1dfdce9f696b4a93c9e5c66dda8d2d64a80a8fb9 +Subproject commit 1fd5a9b954b20b83d5b298e6cf46a19988470844 diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index 26ce350530..cfdb387b91 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -29,7 +29,7 @@ if __name__ == "__main__": poller = messaging.Poller() for m in args.socket if len(args.socket) > 0 else service_list: - sock = messaging.sub_sock(m, poller, addr=args.addr) + messaging.sub_sock(m, poller, addr=args.addr) values = None if args.values: From c6bf0f0b576804b5c63b053134add9a9c8bba8c3 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Sun, 28 Jun 2020 19:16:32 -0500 Subject: [PATCH 385/656] CAR.COROLLA_TSS2 engine and ESP f/w (#1794) @stevheng#6662's 2019 Australian Corolla HB DongleID/route 0a9995ae54acb892|2020-06-28--07-24-06 --- selfdrive/car/toyota/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 5cfa05e292..564cee1ef8 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -533,6 +533,7 @@ FW_VERSIONS = { b'\x018966312P9000\x00\x00\x00\x00', b'\x018966312P9100\x00\x00\x00\x00', b'\x018966312P9200\x00\x00\x00\x00', + b'\x018966312R0100\x00\x00\x00\x00', b'\x018966312R1000\x00\x00\x00\x00', b'\x018966312R1100\x00\x00\x00\x00', b'\x018966312R3100\x00\x00\x00\x00', @@ -555,6 +556,7 @@ FW_VERSIONS = { b'\x01F152602280\x00\x00\x00\x00\x00\x00', b'\x01F152602560\x00\x00\x00\x00\x00\x00', b'\x01F152612641\x00\x00\x00\x00\x00\x00', + b'\x01F152612651\x00\x00\x00\x00\x00\x00', b'\x01F152612B10\x00\x00\x00\x00\x00\x00', b'\x01F152612B60\x00\x00\x00\x00\x00\x00', b'\x01F152612B61\x00\x00\x00\x00\x00\x00', From ce80684f7ec6a61d8e4f08471611a30562707154 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Sun, 28 Jun 2020 20:29:42 -0700 Subject: [PATCH 386/656] Add alert while in preEnabled state (#1791) --- selfdrive/controls/controlsd.py | 2 ++ selfdrive/controls/lib/events.py | 10 ++++++++-- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 86f6ff0f56..731e8968d1 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -316,6 +316,8 @@ class Controls: elif self.state == State.preEnabled: if not self.events.any(ET.PRE_ENABLE): self.state = State.enabled + else: + self.current_alert_types.append(ET.PRE_ENABLE) # DISABLED elif self.state == State.disabled: diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index f49a0c2fdd..cffff8b7c1 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -204,8 +204,6 @@ def wrong_car_mode_alert(CP, sm, metric): EVENTS = { # ********** events with no alerts ********** - EventName.gasPressed: {ET.PRE_ENABLE: None}, - # ********** events only containing alerts displayed in all states ********** EventName.debugAlert: { @@ -333,6 +331,14 @@ EVENTS = { # ********** events only containing alerts that display while engaged ********** + EventName.gasPressed: { + ET.PRE_ENABLE: Alert( + "openpilot will not brake while gas pressed", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOWEST, VisualAlert.none, AudibleAlert.none, .0, .0, .1), + }, + EventName.vehicleModelInvalid: { ET.WARNING: Alert( "Vehicle Parameter Identification Failed", From df86c476c76f53d385d3c8df63d27588dde3dccd Mon Sep 17 00:00:00 2001 From: robbederks Date: Mon, 29 Jun 2020 12:47:48 +0200 Subject: [PATCH 387/656] Dos (#1795) --- cereal | 2 +- selfdrive/controls/controlsd.py | 2 +- selfdrive/controls/lib/events.py | 4 ++-- selfdrive/thermald/thermald.py | 2 +- tools/carcontrols/debug_controls.py | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/cereal b/cereal index 4e3541ae43..7f6df092ef 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 4e3541ae432cf719ae67546c50e01ae580738a38 +Subproject commit 7f6df092efdc64fbab56d1f8804ce40ccd77dee5 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 731e8968d1..1015a6f19a 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -62,7 +62,7 @@ class Controls: # wait for one health and one CAN packet hw_type = messaging.recv_one(self.sm.sock['health']).health.hwType - has_relay = hw_type in [HwType.blackPanda, HwType.uno] + has_relay = hw_type in [HwType.blackPanda, HwType.uno, HwType.dos] print("Waiting for CAN messages...") messaging.get_one_can(self.can_sock) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index cffff8b7c1..a89a008a0b 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -188,10 +188,10 @@ def calibration_incomplete_alert(CP, sm, metric): Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2) def no_gps_alert(CP, sm, metric): - two = sm['health'].hwType == log.HealthData.HwType.uno + gps_integrated = sm['health'].hwType in [log.HealthData.HwType.uno, log.HealthData.HwType.dos] return Alert( "Poor GPS reception", - "If sky is visible, contact support" if two else "Check GPS antenna placement", + "If sky is visible, contact support" if gps_integrated else "Check GPS antenna placement", AlertStatus.normal, AlertSize.mid, Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=300.) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 84a26e7447..5ffa8f94c8 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -213,7 +213,7 @@ def thermald_thread(): # Setup fan handler on first connect to panda if handle_fan is None and health.health.hwType != log.HealthData.HwType.unknown: is_uno = health.health.hwType == log.HealthData.HwType.uno - has_relay = health.health.hwType in [log.HealthData.HwType.blackPanda, log.HealthData.HwType.uno] + has_relay = health.health.hwType in [log.HealthData.HwType.blackPanda, log.HealthData.HwType.uno, log.HealthData.HwType.dos] if is_uno or not ANDROID: cloudlog.info("Setting up UNO fan handler") diff --git a/tools/carcontrols/debug_controls.py b/tools/carcontrols/debug_controls.py index 7d13a0b76b..1f353e0666 100755 --- a/tools/carcontrols/debug_controls.py +++ b/tools/carcontrols/debug_controls.py @@ -26,7 +26,7 @@ def steer_thread(): # wait for health and CAN packets hw_type = messaging.recv_one(health).health.hwType - has_relay = hw_type in [HwType.blackPanda, HwType.uno] + has_relay = hw_type in [HwType.blackPanda, HwType.uno, HwType.dos] print("Waiting for CAN messages...") messaging.get_one_can(logcan) From b62da571b4108487cfc4d2dbd1970a504ba0a317 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Mon, 29 Jun 2020 13:54:23 -0700 Subject: [PATCH 388/656] UI 10x speedup with hardware antialias (#1787) * enable MSAA, disable nvg antialias * less opaque and clean up Co-authored-by: Comma Device --- selfdrive/common/framebuffer.cc | 3 +++ selfdrive/ui/paint.cc | 20 +++++++++++++------- 2 files changed, 16 insertions(+), 7 deletions(-) diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc index d39fa8cb49..30604deb2e 100644 --- a/selfdrive/common/framebuffer.cc +++ b/selfdrive/common/framebuffer.cc @@ -102,6 +102,9 @@ extern "C" FramebufferState* framebuffer_init( EGL_DEPTH_SIZE, 0, EGL_STENCIL_SIZE, 8, EGL_RENDERABLE_TYPE, EGL_OPENGL_ES3_BIT_KHR, + // enable MSAA + EGL_SAMPLE_BUFFERS, 1, + EGL_SAMPLES, 4, EGL_NONE, }; diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 24f4a9d4af..a58425748f 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -289,7 +289,7 @@ static inline bool valid_frame_pt(UIState *s, float x, float y) { return x >= 0 && x <= s->rgb_width && y >= 0 && y <= s->rgb_height; } -static void update_lane_line_data(UIState *s, const float *points, float off, bool is_ghost, model_path_vertices_data *pvd, float valid_len) { +static void update_lane_line_data(UIState *s, const float *points, float off, model_path_vertices_data *pvd, float valid_len) { pvd->cnt = 0; int rcount = fmin(MODEL_PATH_MAX_VERTICES_CNT / 2, valid_len); for (int i = 0; i < rcount; i++) { @@ -305,7 +305,7 @@ static void update_lane_line_data(UIState *s, const float *points, float off, bo } for (int i = rcount; i > 0; i--) { float px = (float)i; - float py = is_ghost?(points[i]-off):(points[i]+off); + float py = points[i] + off; const vec4 p_car_space = (vec4){{px, py, 0., 1.}}; const vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); if(!valid_frame_pt(s, p_full_frame.v[0], p_full_frame.v[1])) @@ -317,16 +317,16 @@ static void update_lane_line_data(UIState *s, const float *points, float off, bo } static void update_all_lane_lines_data(UIState *s, const PathData &path, model_path_vertices_data *pstart) { - update_lane_line_data(s, path.points, 0.025*path.prob, false, pstart, path.validLen); + update_lane_line_data(s, path.points, 0.025*path.prob, pstart, path.validLen); float var = fmin(path.std, 0.7); - update_lane_line_data(s, path.points, -var, true, pstart + 1, path.validLen); - update_lane_line_data(s, path.points, var, true, pstart + 2, path.validLen); + update_lane_line_data(s, path.points, -var, pstart + 1, path.validLen); + update_lane_line_data(s, path.points, var, pstart + 2, path.validLen); } static void ui_draw_lane(UIState *s, const PathData *path, model_path_vertices_data *pstart, NVGcolor color) { ui_draw_lane_line(s, pstart, color); float var = fmin(path->std, 0.7); - color.a /= 4; + color.a /= 25; ui_draw_lane_line(s, pstart + 1, color); ui_draw_lane_line(s, pstart + 2, color); } @@ -758,7 +758,7 @@ void ui_draw(UIState *s) { nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); ui_draw_sidebar(s); if (s->started && s->active_app == cereal::UiLayoutState::App::NONE && s->status != STATUS_STOPPED && s->vision_seen) { - ui_draw_vision(s); + ui_draw_vision(s); } nvgEndFrame(s->vg); glDisable(GL_BLEND); @@ -858,7 +858,13 @@ static const mat4 full_to_wide_frame_transform = {{ void ui_nvg_init(UIState *s) { // init drawing +#ifdef QCOM + // on QCOM, we enable MSAA + s->vg = nvgCreate(0); +#else s->vg = nvgCreate(NVG_ANTIALIAS | NVG_STENCIL_STROKES | NVG_DEBUG); +#endif + assert(s->vg); s->font_courbd = nvgCreateFont(s->vg, "courbd", "../assets/fonts/courbd.ttf"); From e8259895f7d29b153aa2d5e9c86391f47413a133 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 29 Jun 2020 14:12:28 -0700 Subject: [PATCH 389/656] remove unused UI variables --- selfdrive/ui/paint.cc | 2 -- selfdrive/ui/sidebar.cc | 1 - selfdrive/ui/ui.cc | 3 +-- 3 files changed, 1 insertion(+), 5 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index a58425748f..d0b0425e8c 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -154,7 +154,6 @@ static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) const float *mpc_x_coords = &scene->mpc_x[0]; const float *mpc_y_coords = &scene->mpc_y[0]; - bool started = false; float off = is_mpc?0.3:0.5; float lead_d = scene->lead_data[0].getDRel()*2.; float path_height = is_mpc?(lead_d>5.)?fmin(lead_d, 25.)-fmin(lead_d*0.35, 10.):20. @@ -325,7 +324,6 @@ static void update_all_lane_lines_data(UIState *s, const PathData &path, model_p static void ui_draw_lane(UIState *s, const PathData *path, model_path_vertices_data *pstart, NVGcolor color) { ui_draw_lane_line(s, pstart, color); - float var = fmin(path->std, 0.7); color.a /= 25; ui_draw_lane_line(s, pstart + 1, color); ui_draw_lane_line(s, pstart + 2, color); diff --git a/selfdrive/ui/sidebar.cc b/selfdrive/ui/sidebar.cc index 890ea7e7ac..f4cb4f515b 100644 --- a/selfdrive/ui/sidebar.cc +++ b/selfdrive/ui/sidebar.cc @@ -63,7 +63,6 @@ static void ui_draw_sidebar_network_type(UIState *s) { const int network_x = !s->scene.uilayout_sidebarcollapsed ? 50 : -(sbr_w); const int network_y = 273; const int network_w = 100; - const int network_h = 100; const char *network_type = network_type_map[s->scene.thermal.getNetworkType()]; nvgFillColor(s->vg, COLOR_WHITE); nvgFontSize(s->vg, 48); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 32c1543e5a..1e39a9fab6 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -115,7 +115,7 @@ static void handle_sidebar_touch(UIState *s, int touch_x, int touch_y) { } static void handle_driver_view_touch(UIState *s, int touch_x, int touch_y) { - int err = write_db_value("IsDriverViewEnabled", "0", 1); + write_db_value("IsDriverViewEnabled", "0", 1); } static void handle_vision_touch(UIState *s, int touch_x, int touch_y) { @@ -633,7 +633,6 @@ static int vision_subscribe(int fd, VisionPacket *rp, VisionStreamType type) { } static void* vision_connect_thread(void *args) { - int err; set_thread_name("vision_connect"); UIState *s = (UIState*)args; From 3c48b5a3ed2e7c1f315caf4d6b868155e41c9bea Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 29 Jun 2020 15:05:47 -0700 Subject: [PATCH 390/656] remove duplicate key --- release/id_rsa_public | 28 ---------------------------- release/remote_build.py | 2 +- selfdrive/test/phone_ci.py | 2 +- tools/ssh/key/id_rsa | 4 ++-- 4 files changed, 4 insertions(+), 32 deletions(-) delete mode 100644 release/id_rsa_public diff --git a/release/id_rsa_public b/release/id_rsa_public deleted file mode 100644 index 3f269afe22..0000000000 --- a/release/id_rsa_public +++ /dev/null @@ -1,28 +0,0 @@ ------BEGIN RSA PRIVATE KEY----- -MIIEvAIBADANBgkqhkiG9w0BAQEFAASCBKYwggSiAgEAAoIBAQC+iXXq30Tq+J5N -Kat3KWHCzcmwZ55nGh6WggAqECa5CasBlM9VeROpVu3beA+5h0MibRgbD4DMtVXB -t6gEvZ8nd04E7eLA9LTZyFDZ7SkSOVj4oXOQsT0GnJmKrASW5KslTWqVzTfo2XCt -Z+004ikLxmyFeBO8NOcErW1pa8gFdQDToH9FrA7kgysic/XVESTOoe7XlzRoe/eZ -acEQ+jtnmFd21A4aEADkk00Ahjr0uKaJiLUAPatxs2icIXWpgYtfqqtaKF23wSt6 -1OTu6cAwXbOWr3m+IUSRUO0IRzEIQS3z1jfd1svgzSgSSwZ1Lhj4AoKxIEAIc8qJ -rO4uymCJAgMBAAECggEBAISFevxHGdoL3Z5xkw6oO5SQKO2GxEeVhRzNgmu/HA+q -x8OryqD6O1CWY4037kft6iWxlwiLOdwna2P25ueVM3LxqdQH2KS4DmlCx+kq6FwC -gv063fQPMhC9LpWimvaQSPEC7VUPjQlo4tPY6sTTYBUOh0A1ihRm/x7juKuQCWix -Cq8C/DVnB1X4mGj+W3nJc5TwVJtgJbbiBrq6PWrhvB/3qmkxHRL7dU2SBb2iNRF1 -LLY30dJx/cD73UDKNHrlrsjk3UJc29Mp4/MladKvUkRqNwlYxSuAtJV0nZ3+iFkL -s3adSTHdJpClQer45R51rFDlVsDz2ZBpb/hRNRoGDuECgYEA6A1EixLq7QYOh3cb -Xhyh3W4kpVvA/FPfKH1OMy3ONOD/Y9Oa+M/wthW1wSoRL2n+uuIW5OAhTIvIEivj -6bAZsTT3twrvOrvYu9rx9aln4p8BhyvdjeW4kS7T8FP5ol6LoOt2sTP3T1LOuJPO -uQvOjlKPKIMh3c3RFNWTnGzMPa0CgYEA0jNiPLxP3A2nrX0keKDI+VHuvOY88gdh -0W5BuLMLovOIDk9aQFIbBbMuW1OTjHKv9NK+Lrw+YbCFqOGf1dU/UN5gSyE8lX/Q -FsUGUqUZx574nJZnOIcy3ONOnQLcvHAQToLFAGUd7PWgP3CtHkt9hEv2koUwL4vo -ikTP1u9Gkc0CgYEA2apoWxPZrY963XLKBxNQecYxNbLFaWq67t3rFnKm9E8BAICi -4zUaE5J1tMVi7Vi9iks9Ml9SnNyZRQJKfQ+kaebHXbkyAaPmfv+26rqHKboA0uxA -nDOZVwXX45zBkp6g1sdHxJx8JLoGEnkC9eyvSi0C//tRLx86OhLErXwYcNkCf1it -VMRKrWYoXJTUNo6tRhvodM88UnnIo3u3CALjhgU4uC1RTMHV4ZCGBwiAOb8GozSl -s5YD1E1iKwEULloHnK6BIh6P5v8q7J6uf/xdqoKMjlWBHgq6/roxKvkSPA1DOZ3l -jTadcgKFnRUmc+JT9p/ZbCxkA/ALFg8++G+0ghECgYA8vG3M/utweLvq4RI7l7U7 -b+i2BajfK2OmzNi/xugfeLjY6k2tfQGRuv6ppTjehtji2uvgDWkgjJUgPfZpir3I -RsVMUiFgloWGHETOy0Qvc5AwtqTJFLTD1Wza2uBilSVIEsg6Y83Gickh+ejOmEsY -6co17RFaAZHwGfCFFjO76Q== ------END RSA PRIVATE KEY----- diff --git a/release/remote_build.py b/release/remote_build.py index 7db14b3892..c30a9ed446 100755 --- a/release/remote_build.py +++ b/release/remote_build.py @@ -11,7 +11,7 @@ def start_build(name): ssh = paramiko.SSHClient() ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy()) - key_file = open(os.path.join(os.path.dirname(__file__), "id_rsa_public")) + key_file = open(os.path.join(os.path.dirname(__file__), "../tools/ssh/key/id_rsa")) key = paramiko.RSAKey.from_private_key(key_file) print("SSH to phone {}".format(name)) diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py index 6ee2b396e7..735cace4e8 100755 --- a/selfdrive/test/phone_ci.py +++ b/selfdrive/test/phone_ci.py @@ -12,7 +12,7 @@ def run_test(name, test_func): ssh = paramiko.SSHClient() ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy()) - key_file = open(os.path.join(os.path.dirname(__file__), "../../release/id_rsa_public")) + key_file = open(os.path.join(os.path.dirname(__file__), "../../tools/ssh/key/id_rsa")) key = paramiko.RSAKey.from_private_key(key_file) print("SSH to phone {}".format(name)) diff --git a/tools/ssh/key/id_rsa b/tools/ssh/key/id_rsa index 6a8ecfcce9..3f269afe22 100644 --- a/tools/ssh/key/id_rsa +++ b/tools/ssh/key/id_rsa @@ -1,4 +1,4 @@ ------BEGIN PRIVATE KEY----- +-----BEGIN RSA PRIVATE KEY----- MIIEvAIBADANBgkqhkiG9w0BAQEFAASCBKYwggSiAgEAAoIBAQC+iXXq30Tq+J5N Kat3KWHCzcmwZ55nGh6WggAqECa5CasBlM9VeROpVu3beA+5h0MibRgbD4DMtVXB t6gEvZ8nd04E7eLA9LTZyFDZ7SkSOVj4oXOQsT0GnJmKrASW5KslTWqVzTfo2XCt @@ -25,4 +25,4 @@ jTadcgKFnRUmc+JT9p/ZbCxkA/ALFg8++G+0ghECgYA8vG3M/utweLvq4RI7l7U7 b+i2BajfK2OmzNi/xugfeLjY6k2tfQGRuv6ppTjehtji2uvgDWkgjJUgPfZpir3I RsVMUiFgloWGHETOy0Qvc5AwtqTJFLTD1Wza2uBilSVIEsg6Y83Gickh+ejOmEsY 6co17RFaAZHwGfCFFjO76Q== ------END PRIVATE KEY----- +-----END RSA PRIVATE KEY----- From 24fd38e391b018f043330ee4b18012450226ef7a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 29 Jun 2020 16:19:35 -0700 Subject: [PATCH 391/656] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index 1fd5a9b954..55e9af71fc 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 1fd5a9b954b20b83d5b298e6cf46a19988470844 +Subproject commit 55e9af71fcfc61fa061a1482d3fbb4da00441c35 From 83af35bf95e794f0968fc3a8e18333d96c786172 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Mon, 29 Jun 2020 18:39:50 -0700 Subject: [PATCH 392/656] Fix CAN Error on Kona EV (#1800) --- selfdrive/car/hyundai/interface.py | 2 +- selfdrive/car/hyundai/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 4ea4fa70cb..2042c1a37c 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -145,7 +145,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] # these cars require a special panda safety mode due to missing counters and checksums in the messages - if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ]: + if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV]: ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy ret.centerToFront = ret.wheelbase * 0.4 diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index a760c6de69..d0a089b416 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -211,7 +211,7 @@ FEATURES = { "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ], # Use TCU Message for Gear Selection } -EV_HYBRID = [CAR.IONIQ_EV_LTD, CAR.IONIQ] +EV_HYBRID = [CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV] DBC = { CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None), From 64aeb80dcc651de9836d46db08c2b4a17af364f0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 30 Jun 2020 13:44:56 -0700 Subject: [PATCH 393/656] fix blindspot detection --- selfdrive/controls/lib/pathplanner.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index bfe8597df6..375dea4735 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -115,7 +115,7 @@ class PathPlanner(): (sm['carState'].steeringTorque < 0 and self.lane_change_direction == LaneChangeDirection.right)) blindspot_detected = ((sm['carState'].leftBlindspot and self.lane_change_direction == LaneChangeDirection.left) or - (sm['carState'].leftBlindspot and self.lane_change_direction == LaneChangeDirection.left)) + (sm['carState'].rightBlindspot and self.lane_change_direction == LaneChangeDirection.right)) lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob From ec8b69cb14fa83c90e9f5388d52ced603613e9bf Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 30 Jun 2020 14:01:40 -0700 Subject: [PATCH 394/656] flippening is only for android --- selfdrive/manager.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index ee2e2f42d3..1ff62d93c2 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -546,11 +546,12 @@ def uninstall(): def main(): os.environ['PARAMS_PATH'] = PARAMS - # the flippening! - os.system('LD_LIBRARY_PATH="" content insert --uri content://settings/system --bind name:s:user_rotation --bind value:i:1') + if ANDROID: + # the flippening! + os.system('LD_LIBRARY_PATH="" content insert --uri content://settings/system --bind name:s:user_rotation --bind value:i:1') - # disable bluetooth - os.system('service call bluetooth_manager 8') + # disable bluetooth + os.system('service call bluetooth_manager 8') params = Params() params.manager_start() From 1036c68251706f49386e8b9a186e3d6871250047 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Tue, 30 Jun 2020 19:58:40 -0700 Subject: [PATCH 395/656] Reduce C2 dcamera noise at night (#1798) --- selfdrive/boardd/boardd.cc | 12 ++--- selfdrive/camerad/cameras/camera_qcom.cc | 69 ++++++++++++++++-------- 2 files changed, 53 insertions(+), 28 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index a26a0729ed..2b3ce95277 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -33,8 +33,8 @@ #define MAX_IR_POWER 0.5f #define MIN_IR_POWER 0.0f -#define CUTOFF_GAIN 0.015625f // iso400 -#define SATURATE_GAIN 0.0625f // iso1600 +#define CUTOFF_IL 200 +#define SATURATE_IL 1600 #define NIBBLE_TO_HEX(n) ((n) < 10 ? (n) + '0' : ((n) - 10) + 'a') #define VOLTAGE_K 0.091 // LPF gain for 5s tau (dt/tau / (dt/tau + 1)) @@ -690,15 +690,15 @@ void *hardware_control_thread(void *crap) { } if (sm.updated("frontFrame")){ auto event = sm["frontFrame"]; - float cur_front_gain = event.getFrontFrame().getGainFrac(); + int cur_integ_lines = event.getFrontFrame().getIntegLines(); last_front_frame_t = event.getLogMonoTime(); - if (cur_front_gain <= CUTOFF_GAIN) { + if (cur_integ_lines <= CUTOFF_IL) { ir_pwr = 100.0 * MIN_IR_POWER; - } else if (cur_front_gain > SATURATE_GAIN) { + } else if (cur_integ_lines > SATURATE_IL) { ir_pwr = 100.0 * MAX_IR_POWER; } else { - ir_pwr = 100.0 * (MIN_IR_POWER + ((cur_front_gain - CUTOFF_GAIN) * (MAX_IR_POWER - MIN_IR_POWER) / (SATURATE_GAIN - CUTOFF_GAIN))); + ir_pwr = 100.0 * (MIN_IR_POWER + ((cur_integ_lines - CUTOFF_IL) * (MAX_IR_POWER - MIN_IR_POWER) / (SATURATE_IL - CUTOFF_IL))); } } // Disable ir_pwr on front frame timeout diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index 9382687e8e..1a6d0ae2c9 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -203,23 +203,24 @@ static int imx298_apply_exposure(CameraState *s, int gain, int integ_lines, int return err; } -static inline int ov8865_get_coarse_gain(int gain) { - static const int gains[] = {0, 256, 384, 448, 480}; - int i; +static int ov8865_apply_exposure(CameraState *s, int gain, int integ_lines, int frame_length) { + //printf("front camera: %d %d %d\n", gain, integ_lines, frame_length); + int err, coarse_gain_bitmap, fine_gain_bitmap; + // get bitmaps from iso + static const int gains[] = {0, 100, 200, 400, 800}; + int i; for (i = 1; i < ARRAYSIZE(gains); i++) { if (gain >= gains[i - 1] && gain < gains[i]) break; } + int coarse_gain = i - 1; + float fine_gain = (gain - gains[coarse_gain])/(float)(gains[coarse_gain+1]-gains[coarse_gain]); + coarse_gain_bitmap = (1 << coarse_gain) - 1; + fine_gain_bitmap = ((int)(16*fine_gain) << 3) + 128; // 7th is always 1, 0-2nd are always 0 - return i - 1; -} - -static int ov8865_apply_exposure(CameraState *s, int gain, int integ_lines, int frame_length) { - //printf("front camera: %d %d %d\n", gain, integ_lines, frame_length); - int err, gain_bitmap; - gain_bitmap = (1 << ov8865_get_coarse_gain(gain)) - 1; integ_lines *= 16; // The exposure value in reg is in 16ths of a line + struct msm_camera_i2c_reg_array reg_array[] = { //{0x104,0x1,0}, @@ -230,7 +231,7 @@ static int ov8865_apply_exposure(CameraState *s, int gain, int integ_lines, int // AEC MANUAL {0x3503, 0x4, 0}, // AEC GAIN - {0x3508, (uint16_t)(gain_bitmap), 0}, {0x3509, 0xf8, 0}, + {0x3508, (uint16_t)(coarse_gain_bitmap), 0}, {0x3509, (uint16_t)(fine_gain_bitmap), 0}, //{0x104,0x0,0}, }; @@ -388,7 +389,10 @@ static void set_exposure(CameraState *s, float exposure_frac, float gain_frac) { || integ_lines != s->cur_integ_lines || frame_length != s->cur_frame_length) { - if (s->apply_exposure) { + if (s->apply_exposure == ov8865_apply_exposure) { + gain = 800 * gain_frac; // ISO + err = s->apply_exposure(s, gain, integ_lines, frame_length); + } else if (s->apply_exposure) { err = s->apply_exposure(s, gain, integ_lines, frame_length); } @@ -411,19 +415,40 @@ static void set_exposure(CameraState *s, float exposure_frac, float gain_frac) { static void do_autoexposure(CameraState *s, float grey_frac) { const float target_grey = 0.3; + if (s->apply_exposure == ov8865_apply_exposure) { + // gain limits downstream + const float gain_frac_min = 0.015625; + const float gain_frac_max = 1.0; + // exposure time limits + unsigned int frame_length = s->pixel_clock / s->line_length_pclk / s->fps; + const unsigned int exposure_time_min = 16; + const unsigned int exposure_time_max = frame_length - 11; // copied from set_exposure() + + float exposure_factor = pow(1.05, (target_grey - grey_frac) / 0.05); + if (s->cur_gain_frac > 0.125 && exposure_factor < 1) { + s->cur_gain_frac *= exposure_factor; + } else if (s->cur_integ_lines * exposure_factor <= exposure_time_max && s->cur_integ_lines * exposure_factor >= exposure_time_min) { // adjust exposure time first + s->cur_exposure_frac *= exposure_factor; + } else if (s->cur_gain_frac * exposure_factor <= gain_frac_max && s->cur_gain_frac * exposure_factor >= gain_frac_min) { + s->cur_gain_frac *= exposure_factor; + } - float new_exposure = s->cur_exposure_frac; - new_exposure *= pow(1.05, (target_grey - grey_frac) / 0.05 ); - //LOGD("diff %f: %f to %f", target_grey - grey_frac, s->cur_exposure_frac, new_exposure); + set_exposure(s, s->cur_exposure_frac, s->cur_gain_frac); - float new_gain = s->cur_gain_frac; - if (new_exposure < 0.10) { - new_gain *= 0.95; - } else if (new_exposure > 0.40) { - new_gain *= 1.05; - } + } else { // keep the old for others + float new_exposure = s->cur_exposure_frac; + new_exposure *= pow(1.05, (target_grey - grey_frac) / 0.05 ); + //LOGD("diff %f: %f to %f", target_grey - grey_frac, s->cur_exposure_frac, new_exposure); - set_exposure(s, new_exposure, new_gain); + float new_gain = s->cur_gain_frac; + if (new_exposure < 0.10) { + new_gain *= 0.95; + } else if (new_exposure > 0.40) { + new_gain *= 1.05; + } + + set_exposure(s, new_exposure, new_gain); + } } void camera_autoexposure(CameraState *s, float grey_frac) { From cb495bb8c9af8b9347bfe3cf4b59baf1f6d10482 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Wed, 1 Jul 2020 14:26:35 -0700 Subject: [PATCH 396/656] Add an SSH param to disable updates (#1807) * disable updates with optional param * dont create the alert * Revert "dont create the alert" This reverts commit 7179a6c8b4b4656e0b203b5a590b33d3388aa9c9. * keep alert, but allow engagement Co-authored-by: Adeeb Shihadeh --- common/params.py | 1 + selfdrive/controls/controlsd.py | 2 +- selfdrive/updated.py | 3 +++ 3 files changed, 5 insertions(+), 1 deletion(-) diff --git a/common/params.py b/common/params.py index 1b34bb1daa..7b90913e7d 100755 --- a/common/params.py +++ b/common/params.py @@ -60,6 +60,7 @@ keys = { "CompletedTrainingVersion": [TxType.PERSISTENT], "ControlsParams": [TxType.PERSISTENT], "DisablePowerDown": [TxType.PERSISTENT], + "DisableUpdates": [TxType.PERSISTENT], "DoUninstall": [TxType.CLEAR_ON_MANAGER_START], "DongleId": [TxType.PERSISTENT], "GitBranch": [TxType.PERSISTENT], diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 1015a6f19a..43ccc7acb1 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -72,7 +72,7 @@ class Controls: params = Params() self.is_metric = params.get("IsMetric", encoding='utf8') == "1" self.is_ldw_enabled = params.get("IsLdwEnabled", encoding='utf8') == "1" - internet_needed = params.get("Offroad_ConnectivityNeeded", encoding='utf8') is not None + internet_needed = (params.get("Offroad_ConnectivityNeeded", encoding='utf8') is not None) and (params.get("DisableUpdates") != b"1") community_feature_toggle = params.get("CommunityFeaturesToggle", encoding='utf8') == "1" openpilot_enabled_toggle = params.get("OpenpilotEnabledToggle", encoding='utf8') == "1" passive = params.get("Passive", encoding='utf8') == "1" or \ diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 47f2d55a59..7c7db0f323 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -319,6 +319,9 @@ def main(): wait_helper = WaitTimeHelper() params = Params() + if params.get("DisableUpdates") == b"1": + raise RuntimeError("updates are disabled by param") + if not os.geteuid() == 0: raise RuntimeError("updated must be launched as root!") From b1abf17752f7631014d855466c46f2aef71bc604 Mon Sep 17 00:00:00 2001 From: martinl Date: Thu, 2 Jul 2020 02:54:40 +0300 Subject: [PATCH 397/656] Support for 2019 Subaru Ascent (#1801) * Add support for Subaru Ascent 2019 * remove duplicate safetyModel * Add Ascent 2019 to README.md --- README.md | 1 + selfdrive/car/subaru/interface.py | 10 ++++++++++ selfdrive/car/subaru/values.py | 8 ++++++++ selfdrive/test/test_car_models.py | 4 ++++ 4 files changed, 23 insertions(+) diff --git a/README.md b/README.md index 45fdfc5106..1aef3664a0 100644 --- a/README.md +++ b/README.md @@ -158,6 +158,7 @@ Community Maintained Cars and Features | Nissan | Leaf 2018-192 | Propilot | Stock | 0mph | 0mph | | Nissan | Rogue 20192 | Propilot | Stock | 0mph | 0mph | | Nissan | X-Trail 20172 | Propilot | Stock | 0mph | 0mph | +| Subaru | Ascent 2019 | EyeSight | Stock | 0mph | 0mph | | Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | | Subaru | Forester 2019 | EyeSight | Stock | 0mph | 0mph | | Subaru | Impreza 2017-19 | EyeSight | Stock | 0mph | 0mph | diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index 3bc13c76e1..4a0438f620 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -28,6 +28,16 @@ class CarInterface(CarInterfaceBase): ret.steerRateCost = 0.7 ret.steerLimitTimer = 0.4 + if candidate == CAR.ASCENT: + ret.mass = 2031. + STD_CARGO_KG + ret.wheelbase = 2.89 + ret.centerToFront = ret.wheelbase * 0.5 + ret.steerRatio = 13.5 + ret.steerActuatorDelay = 0.3 # end-to-end angle controller + ret.lateralTuning.pid.kf = 0.00003 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.0025, 0.1], [0.00025, 0.01]] + if candidate == CAR.IMPREZA: ret.mass = 1568. + STD_CARGO_KG ret.wheelbase = 2.67 diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 791edcf6db..d31c5cfb08 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -5,10 +5,16 @@ from cereal import car Ecu = car.CarParams.Ecu class CAR: + ASCENT = "SUBARU ASCENT LIMITED 2019" IMPREZA = "SUBARU IMPREZA LIMITED 2019" FORESTER = "SUBARU FORESTER 2019" FINGERPRINTS = { + CAR.ASCENT: [ + # SUBARU ASCENT LIMITED 2019 + { + 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1722: 8, 1743: 8, 1759: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8 + }], CAR.IMPREZA: [{ 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1722: 8, 1743: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8 }, @@ -27,6 +33,7 @@ FINGERPRINTS = { } STEER_THRESHOLD = { + CAR.ASCENT: 80, CAR.IMPREZA: 80, CAR.FORESTER: 80, } @@ -36,6 +43,7 @@ ECU_FINGERPRINT = { } DBC = { + CAR.ASCENT: dbc_dict('subaru_global_2017', None), CAR.IMPREZA: dbc_dict('subaru_global_2017', None), CAR.FORESTER: dbc_dict('subaru_global_2017', None), } diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 40ff5d0352..f8e4e37454 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -360,6 +360,10 @@ routes = { 'carFingerprint': VOLKSWAGEN.GOLF, 'enableCamera': True, }, + "3c8f0c502e119c1c|2020-06-30--12-58-02": { + 'carFingerprint': SUBARU.ASCENT, + 'enableCamera': True, + }, "c321c6b697c5a5ff|2020-06-23--11-04-33": { 'carFingerprint': SUBARU.FORESTER, 'enableCamera': True, From 889bcc73c23f95e102fdc97dd9ebf4597f46ca6d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 1 Jul 2020 16:55:47 -0700 Subject: [PATCH 398/656] add subaru ascent to release notes --- RELEASES.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 49250ed97c..da18c65002 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -8,7 +8,7 @@ Version 0.7.7 (2020-xx-xx) * Block lane change start using blindspot monitor on Toyotas with TSS2 * Code cleanup and smaller release sizes * Hyundai Ioniq Electric Limited 2019 and Ioniq SE 2020 support thanks to baldwalker! - * Subaru Forester 2019 support thanks to martinl! + * Subaru Forester 2019 and Ascent 2019 support thanks to martinl! Version 0.7.6.1 (2020-06-16) ======================== From 30d6d77e26e2608ff9ad607a7353fadc0347d419 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Thu, 2 Jul 2020 13:37:53 -0700 Subject: [PATCH 399/656] Subaru cleanup (#1809) --- selfdrive/car/subaru/carcontroller.py | 6 +----- selfdrive/car/subaru/carstate.py | 7 +++---- selfdrive/car/subaru/interface.py | 5 ----- 3 files changed, 4 insertions(+), 14 deletions(-) diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py index 0997b1200c..06863b71cd 100644 --- a/selfdrive/car/subaru/carcontroller.py +++ b/selfdrive/car/subaru/carcontroller.py @@ -24,8 +24,6 @@ class CarController(): self.es_lkas_cnt = -1 self.steer_rate_limited = False - # Setup detection helper. Routes commands to - # an appropriate CAN bus number. self.params = CarControllerParams() self.packer = CANPacker(DBC[CP.carFingerprint]['pt']) @@ -50,9 +48,7 @@ class CarController(): apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, P) self.steer_rate_limited = new_steer != apply_steer - lkas_enabled = enabled - - if not lkas_enabled: + if not enabled: apply_steer = 0 can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, frame, P.STEER_STEP)) diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index a1dc3b5cc2..d7a34d3625 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -57,9 +57,9 @@ class CarState(CarStateBase): ret.seatbeltUnlatched = cp.vl["Dashlights"]['SEATBELT_FL'] == 1 ret.doorOpen = any([cp.vl["BodyInfo"]['DOOR_OPEN_RR'], - cp.vl["BodyInfo"]['DOOR_OPEN_RL'], - cp.vl["BodyInfo"]['DOOR_OPEN_FR'], - cp.vl["BodyInfo"]['DOOR_OPEN_FL']]) + cp.vl["BodyInfo"]['DOOR_OPEN_RL'], + cp.vl["BodyInfo"]['DOOR_OPEN_FR'], + cp.vl["BodyInfo"]['DOOR_OPEN_FL']]) self.es_distance_msg = copy.copy(cp_cam.vl["ES_Distance"]) self.es_lkas_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) @@ -137,7 +137,6 @@ class CarState(CarStateBase): ("Traffic_light_Ahead", "ES_LKAS_State", 0), ("Right_Depart", "ES_LKAS_State", 0), ("Signal5", "ES_LKAS_State", 0), - ] checks = [ diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index 4a0438f620..66a5d99513 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -78,11 +78,6 @@ class CarInterface(CarInterfaceBase): ret.canValid = self.cp.can_valid and self.cp_cam.can_valid ret.steeringRateLimited = self.CC.steer_rate_limited if self.CC is not None else False - buttonEvents = [] - be = car.CarState.ButtonEvent.new_message() - be.type = car.CarState.ButtonEvent.Type.accelCruise - buttonEvents.append(be) - ret.events = self.create_common_events(ret).to_msg() self.CS.out = ret.as_reader() From 2f16349c4cffe592d9b97a37ded37e8215ed8892 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 3 Jul 2020 12:30:47 -0700 Subject: [PATCH 400/656] fix hardcoded frequencies in UI --- selfdrive/ui/ui.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 1e39a9fab6..982bc976f7 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -40,8 +40,8 @@ static void enable_event_processing(bool yes) { static void set_awake(UIState *s, bool awake) { #ifdef QCOM if (awake) { - // 30 second timeout at 30 fps - s->awake_timeout = 30*30; + // 30 second timeout + s->awake_timeout = 30*UI_FREQ; } if (s->awake != awake) { s->awake = awake; @@ -395,7 +395,7 @@ void handle_message(UIState *s, SubMaster &sm) { } if (sm.updated("health")) { scene.hwType = sm["health"].getHealth().getHwType(); - s->hardware_timeout = 5*30; // 5 seconds at 30 fps + s->hardware_timeout = 5*UI_FREQ; // 5 seconds } if (sm.updated("driverState")) { scene.driver_state = sm["driverState"].getDriverState(); From 9de015f588352ef1a81be1139733eea0c927f19c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 4 Jul 2020 03:52:43 +0800 Subject: [PATCH 401/656] better update_offroad_layout_state (#1808) apply review suggestion --- selfdrive/ui/ui.cc | 78 +++++++++++++++------------------------------ selfdrive/ui/ui.hpp | 1 - 2 files changed, 25 insertions(+), 54 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 982bc976f7..d863da5af5 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -65,35 +65,26 @@ static void set_awake(UIState *s, bool awake) { } static void update_offroad_layout_state(UIState *s) { - capnp::MallocMessageBuilder msg; - auto event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto layout = event.initUiLayoutState(); - layout.setActiveApp(s->active_app); - layout.setSidebarCollapsed(s->scene.uilayout_sidebarcollapsed); - s->pm->send("offroadLayout", msg); - LOGD("setting active app to %d with sidebar %d", (int)s->active_app, s->scene.uilayout_sidebarcollapsed); -} - -static void navigate_to_settings(UIState *s) { -#ifdef QCOM - s->active_app = cereal::UiLayoutState::App::SETTINGS; - update_offroad_layout_state(s); -#else - // computer UI doesn't have offroad settings -#endif -} - -static void navigate_to_home(UIState *s) { #ifdef QCOM - if (s->started) { - s->active_app = cereal::UiLayoutState::App::NONE; - } else { - s->active_app = cereal::UiLayoutState::App::HOME; + static int timeout = 0; + static bool prev_collapsed = false; + static cereal::UiLayoutState::App prev_app = cereal::UiLayoutState::App::NONE; + if (timeout > 0) { + timeout--; + } + if (prev_collapsed != s->scene.uilayout_sidebarcollapsed || prev_app != s->active_app || timeout == 0) { + capnp::MallocMessageBuilder msg; + auto event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto layout = event.initUiLayoutState(); + layout.setActiveApp(s->active_app); + layout.setSidebarCollapsed(s->scene.uilayout_sidebarcollapsed); + s->pm->send("offroadLayout", msg); + LOGD("setting active app to %d with sidebar %d", (int)s->active_app, s->scene.uilayout_sidebarcollapsed); + prev_collapsed = s->scene.uilayout_sidebarcollapsed; + prev_app = s->active_app; + timeout = 2 * UI_FREQ; } - update_offroad_layout_state(s); -#else - // computer UI doesn't have offroad home #endif } @@ -101,32 +92,28 @@ static void handle_sidebar_touch(UIState *s, int touch_x, int touch_y) { if (!s->scene.uilayout_sidebarcollapsed && touch_x <= sbr_w) { if (touch_x >= settings_btn_x && touch_x < (settings_btn_x + settings_btn_w) && touch_y >= settings_btn_y && touch_y < (settings_btn_y + settings_btn_h)) { - navigate_to_settings(s); + s->active_app = cereal::UiLayoutState::App::SETTINGS; } - if (touch_x >= home_btn_x && touch_x < (home_btn_x + home_btn_w) + else if (touch_x >= home_btn_x && touch_x < (home_btn_x + home_btn_w) && touch_y >= home_btn_y && touch_y < (home_btn_y + home_btn_h)) { - navigate_to_home(s); if (s->started) { + s->active_app = cereal::UiLayoutState::App::NONE; s->scene.uilayout_sidebarcollapsed = true; - update_offroad_layout_state(s); + } else { + s->active_app = cereal::UiLayoutState::App::HOME; } } } } -static void handle_driver_view_touch(UIState *s, int touch_x, int touch_y) { - write_db_value("IsDriverViewEnabled", "0", 1); -} - static void handle_vision_touch(UIState *s, int touch_x, int touch_y) { if (s->started && (touch_x >= s->scene.ui_viz_rx - bdr_s) && (s->active_app != cereal::UiLayoutState::App::SETTINGS)) { if (!s->scene.frontview) { s->scene.uilayout_sidebarcollapsed = !s->scene.uilayout_sidebarcollapsed; } else { - handle_driver_view_touch(s, touch_x, touch_y); + write_db_value("IsDriverViewEnabled", "0", 1); } - update_offroad_layout_state(s); } } @@ -177,15 +164,6 @@ static int write_param_float(float param, const char* param_name, bool persisten return write_db_value(param_name, s, MIN(size, sizeof(s)), persistent_param); } -static void update_offroad_layout_timeout(UIState *s, int* timeout) { - if (*timeout > 0) { - (*timeout)--; - } else { - update_offroad_layout_state(s); - *timeout = 2 * UI_FREQ; - } -} - static void ui_init(UIState *s) { pthread_mutex_init(&s->lock, NULL); @@ -420,14 +398,10 @@ void handle_message(UIState *s, SubMaster &sm) { close(s->ipc_fd); s->ipc_fd = -1; #endif - - update_offroad_layout_state(s); } } else if (s->status == STATUS_STOPPED) { update_status(s, STATUS_DISENGAGED); - s->active_app = cereal::UiLayoutState::App::NONE; - update_offroad_layout_state(s); } } @@ -507,7 +481,6 @@ static void ui_update(UIState *s) { assert(glGetError() == GL_NO_ERROR); s->scene.uilayout_sidebarcollapsed = true; - update_offroad_layout_state(s); s->scene.ui_viz_rx = (box_x-sbr_w+bdr_s*2); s->scene.ui_viz_rw = (box_w+sbr_w-(bdr_s*2)); s->scene.ui_viz_ro = 0; @@ -827,7 +800,6 @@ int main(int argc, char* argv[]) { // Visiond process is just stopped, force a redraw to make screen blank again. if (!s->started) { s->scene.uilayout_sidebarcollapsed = false; - update_offroad_layout_state(s); ui_draw(s); glFinish(); should_swap = true; @@ -895,7 +867,7 @@ int main(int argc, char* argv[]) { s->scene.athenaStatus = NET_ERROR; } } - update_offroad_layout_timeout(s, &s->offroad_layout_timeout); + update_offroad_layout_state(s); pthread_mutex_unlock(&s->lock); diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 8ee48ed4d9..830d227e39 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -220,7 +220,6 @@ typedef struct UIState { int limit_set_speed_timeout; int hardware_timeout; int last_athena_ping_timeout; - int offroad_layout_timeout; bool controls_seen; From 6db7fa8c033841c82d1139119aad8a20645449f4 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 3 Jul 2020 15:40:13 -0700 Subject: [PATCH 402/656] Refactor CPU usage test (#1802) * pull CPU usage test out of manager * remove that * add to release files * cleanup * executable * this should work * check if car started procs are running * debug * add min cpu usage * remove debug prints * adjust min cpu threshold Co-authored-by: Comma Device --- common/manager_helpers.py | 49 ---------------- release/build_devel.sh | 2 +- release/files_common | 1 + selfdrive/manager.py | 27 --------- selfdrive/test/test_cpu_usage.py | 96 ++++++++++++++++++++++++++++++++ 5 files changed, 98 insertions(+), 77 deletions(-) create mode 100755 selfdrive/test/test_cpu_usage.py diff --git a/common/manager_helpers.py b/common/manager_helpers.py index 3668ea112c..8b13789179 100644 --- a/common/manager_helpers.py +++ b/common/manager_helpers.py @@ -1,50 +1 @@ -def cputime_total(ct): - return ct.cpuUser + ct.cpuSystem + ct.cpuChildrenUser + ct.cpuChildrenSystem - -def print_cpu_usage(first_proc, last_proc): - r = 0 - procs = [ - ("selfdrive.controls.controlsd", 59.46), - ("./_modeld", 12.74), - ("./loggerd", 28.49), - ("selfdrive.controls.plannerd", 19.77), - ("selfdrive.controls.radard", 9.54), - ("./_ui", 9.54), - ("./camerad", 7.07), - ("selfdrive.locationd.locationd", 34.38), - ("selfdrive.locationd.paramsd", 11.53), - ("./_sensord", 6.17), - ("selfdrive.monitoring.dmonitoringd", 5.48), - ("./boardd", 3.63), - ("./_dmonitoringmodeld", 2.67), - ("selfdrive.logmessaged", 2.71), - ("selfdrive.thermald.thermald", 2.41), - ("selfdrive.locationd.calibrationd", 6.81), - ("./proclogd", 1.54), - ("./_gpsd", 0.09), - ("./clocksd", 0.02), - ("./ubloxd", 0.02), - ("selfdrive.tombstoned", 0), - ("./logcatd", 0), - ] - - dt = (last_proc.logMonoTime - first_proc.logMonoTime) / 1e9 - print("------------------------------------------------") - for proc_name, normal_cpu_usage in procs: - try: - first = [p for p in first_proc.procLog.procs if proc_name in p.cmdline][0] - last = [p for p in last_proc.procLog.procs if proc_name in p.cmdline][0] - cpu_time = cputime_total(last) - cputime_total(first) - cpu_usage = cpu_time / dt * 100. - if cpu_usage > max(normal_cpu_usage * 1.1, normal_cpu_usage + 5.0): - print(f"Warning {proc_name} using more CPU than normal") - r = 1 - - print(f"{proc_name.ljust(35)} {cpu_usage:.2f}%") - except IndexError: - print(f"{proc_name.ljust(35)} NO METRICS FOUND") - r = 1 - print("------------------------------------------------") - - return r diff --git a/release/build_devel.sh b/release/build_devel.sh index 8addd776ba..6218336870 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -80,7 +80,7 @@ echo -n "1" > /data/params/d/HasCompletedSetup echo -n "1" > /data/params/d/CommunityFeaturesToggle PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" nosetests -s selfdrive/test/test_openpilot.py -PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" GET_CPU_USAGE=1 selfdrive/manager.py +PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" selfdrive/test/test_cpu_usage.py PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" selfdrive/car/tests/test_car_interfaces.py echo "[-] testing panda build T=$SECONDS" diff --git a/release/files_common b/release/files_common index c35df3976f..c68dcf1cfa 100644 --- a/release/files_common +++ b/release/files_common @@ -320,6 +320,7 @@ selfdrive/test/__init__.py selfdrive/test/test_openpilot.py selfdrive/test/test_fingerprints.py selfdrive/test/test_car_models.py +selfdrive/test/test_cpu_usage.py selfdrive/ui/SConscript selfdrive/ui/*.cc diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 1ff62d93c2..3e55841d06 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -161,7 +161,6 @@ from selfdrive.loggerd.config import ROOT from selfdrive.launcher import launcher from common import android from common.apk import update_apks, pm_apply_packages, start_offroad -from common.manager_helpers import print_cpu_usage ThermalStatus = cereal.log.ThermalData.ThermalStatus @@ -428,9 +427,6 @@ def manager_thread(): # now loop thermal_sock = messaging.sub_sock('thermal') - if os.getenv("GET_CPU_USAGE"): - proc_sock = messaging.sub_sock('procLog', conflate=True) - cloudlog.info("manager start") cloudlog.info({"environ": os.environ}) @@ -461,9 +457,6 @@ def manager_thread(): logger_dead = False - start_t = time.time() - first_proc = None - while 1: msg = messaging.recv_sock(thermal_sock, wait=True) @@ -504,26 +497,6 @@ def manager_thread(): if params.get("DoUninstall", encoding='utf8') == "1": break - if os.getenv("GET_CPU_USAGE"): - dt = time.time() - start_t - - # Get first sample - if dt > 30 and first_proc is None: - first_proc = messaging.recv_sock(proc_sock) - - # Get last sample and exit - if dt > 90: - last_proc = messaging.recv_sock(proc_sock, wait=True) - - all_running = all(running[p].is_alive() for p in car_started_processes) - - cleanup_all_processes(None, None) - return_code = print_cpu_usage(first_proc, last_proc) - - if not all_running: - return_code = 1 - sys.exit(return_code) - def manager_prepare(spinner=None): # build all processes os.chdir(os.path.dirname(os.path.abspath(__file__))) diff --git a/selfdrive/test/test_cpu_usage.py b/selfdrive/test/test_cpu_usage.py new file mode 100755 index 0000000000..0ed651ad4b --- /dev/null +++ b/selfdrive/test/test_cpu_usage.py @@ -0,0 +1,96 @@ +#!/usr/bin/env python3 +import time +import threading +import _thread +import signal +import sys + +import cereal.messaging as messaging +import selfdrive.manager as manager + + +def cputime_total(ct): + return ct.cpuUser + ct.cpuSystem + ct.cpuChildrenUser + ct.cpuChildrenSystem + + +def print_cpu_usage(first_proc, last_proc): + procs = [ + ("selfdrive.controls.controlsd", 59.46), + ("selfdrive.locationd.locationd", 34.38), + ("./loggerd", 28.49), + ("selfdrive.controls.plannerd", 19.77), + ("./_modeld", 12.74), + ("selfdrive.locationd.paramsd", 11.53), + ("selfdrive.controls.radard", 9.54), + ("./_ui", 9.54), + ("./camerad", 7.07), + ("selfdrive.locationd.calibrationd", 6.81), + ("./_sensord", 6.17), + ("selfdrive.monitoring.dmonitoringd", 5.48), + ("./boardd", 3.63), + ("./_dmonitoringmodeld", 2.67), + ("selfdrive.logmessaged", 2.71), + ("selfdrive.thermald.thermald", 2.41), + ("./proclogd", 1.54), + ("./_gpsd", 0.09), + ("./clocksd", 0.02), + ("./ubloxd", 0.02), + ("selfdrive.tombstoned", 0), + ("./logcatd", 0), + ] + + r = 0 + dt = (last_proc.logMonoTime - first_proc.logMonoTime) / 1e9 + result = "------------------------------------------------\n" + for proc_name, normal_cpu_usage in procs: + try: + first = [p for p in first_proc.procLog.procs if proc_name in p.cmdline][0] + last = [p for p in last_proc.procLog.procs if proc_name in p.cmdline][0] + cpu_time = cputime_total(last) - cputime_total(first) + cpu_usage = cpu_time / dt * 100. + if cpu_usage > max(normal_cpu_usage * 1.1, normal_cpu_usage + 5.0): + result += f"Warning {proc_name} using more CPU than normal\n" + r = 1 + elif cpu_usage < min(normal_cpu_usage * 0.3, max(normal_cpu_usage - 1.0, 0.0)): + result += f"Warning {proc_name} using less CPU than normal\n" + r = 1 + result += f"{proc_name.ljust(35)} {cpu_usage:.2f}%\n" + except IndexError: + result += f"{proc_name.ljust(35)} NO METRICS FOUND\n" + r = 1 + result += "------------------------------------------------\n" + print(result) + return r + +return_code = 1 +def test_thread(): + global return_code + proc_sock = messaging.sub_sock('procLog', conflate=True) + + # wait until everything's started and get first sample + time.sleep(30) + first_proc = messaging.recv_sock(proc_sock, wait=True) + + # run for a minute and get last sample + time.sleep(60) + last_proc = messaging.recv_sock(proc_sock, wait=True) + + running = manager.get_running() + all_running = all(p in running and running[p].is_alive() for p in manager.car_started_processes) + return_code = print_cpu_usage(first_proc, last_proc) + if not all_running: + return_code = 1 + _thread.interrupt_main() + +if __name__ == "__main__": + + # setup signal handler to exit with test status + def handle_exit(sig, frame): + sys.exit(return_code) + signal.signal(signal.SIGINT, handle_exit) + + # start manager and test thread + t = threading.Thread(target=test_thread) + t.daemon = True + t.start() + manager.main() From 1206409b2e83f7def11d9b8473fa30e16736f41f Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Fri, 3 Jul 2020 16:18:19 -0700 Subject: [PATCH 403/656] remove duplicate logging context --- common/logging_extra.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/common/logging_extra.py b/common/logging_extra.py index 7d9bcd7b6e..ce8889b410 100644 --- a/common/logging_extra.py +++ b/common/logging_extra.py @@ -115,9 +115,6 @@ class SwagLogger(logging.Logger): if args: evt['args'] = args evt.update(kwargs) - ctx = self.get_ctx() - if ctx: - evt['ctx'] = self.get_ctx() if 'error' in kwargs: self.error(evt) else: From d417481e2b7bc364342be29d2611bfb6dcec656b Mon Sep 17 00:00:00 2001 From: TK211X <33460783+TK211X@users.noreply.github.com> Date: Fri, 3 Jul 2020 19:29:31 -0400 Subject: [PATCH 404/656] Update 2020 Sonata Print (#1806) The Korean version has extra features. --- selfdrive/car/hyundai/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index d0a089b416..09c70f008c 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -80,7 +80,7 @@ FINGERPRINTS = { 67: 8, 68: 8, 80: 4, 160: 8, 161: 8, 272: 8, 288: 4, 339: 8, 356: 8, 357: 8, 399: 8, 544: 8, 608: 8, 672: 8, 688: 5, 704: 1, 790: 8, 809: 8, 848: 8, 880: 8, 898: 8, 900: 8, 901: 8, 904: 8, 1056: 8, 1064: 8, 1065: 8, 1072: 8, 1075: 8, 1087: 8, 1088: 8, 1151: 8, 1200: 8, 1201: 8, 1232: 4, 1264: 8, 1265: 8, 1266: 8, 1296: 8, 1306: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1348: 8, 1349: 8, 1369: 8, 1370: 8, 1371: 8, 1407: 8, 1415: 8, 1419: 8, 1440: 8, 1442: 4, 1461: 8, 1470: 8 }], CAR.SONATA: [ - {67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 549: 8, 550: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 8, 865: 8, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 908: 8, 909: 8, 912: 7, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1089: 5, 1107: 5, 1108: 8, 1114: 8, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1184: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1268: 8, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1330: 8, 1339: 8, 1342: 6, 1343: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1394: 8, 1407: 8, 1419: 8, 1427: 6, 1446: 8, 1456: 4, 1460: 8, 1470: 8, 1485: 8, 1504: 3}, + {67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 8, 865: 8, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 908: 8, 909: 8, 912: 7, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1089: 5, 1096: 8, 1107: 5, 1108: 8, 1114: 8, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1184: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1268: 8, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1330: 8, 1339: 8, 1342: 6, 1343: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1379: 8, 1384: 8, 1394: 8, 1407: 8, 1419: 8, 1427: 6, 1446: 8, 1456: 4, 1460: 8, 1470: 8, 1485: 8, 1504: 3, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8}, ], CAR.SONATA_2019: [ {66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1397: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2008: 8, 2009: 8, 2012: 8, 2013: 8, 2014: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8}, From 32f03ec8a52c7c5fa56d5cce19fbbd7ecf24b7dd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Fri, 3 Jul 2020 19:12:05 -0700 Subject: [PATCH 405/656] On-device CI framework (#1784) * let's see if this works * fix build_release actions job * does jenkins like this config * separate jenkinsfile for release build * fix devel build * devel build should work * always pass that for now * run modeld replay * release2 build will be a separate PR * pass env to phone shell * force checkout * run on real jenkins eons * add timeout * rsync * more timeout * trailing slash * fix branch detection * debug * not sure why paramiko doesn't pass it through * newline * CI_PUSH * still not passing it * test branch * should be good now --- Jenkinsfile | 22 +++++++----- SConstruct | 5 ++- release/build_devel.sh | 8 ++--- release/files_common | 10 +++--- release/remote_build.py | 73 -------------------------------------- selfdrive/test/phone_ci.py | 64 +++++++++++++++++++++------------ 6 files changed, 67 insertions(+), 115 deletions(-) delete mode 100755 release/remote_build.py diff --git a/Jenkinsfile b/Jenkinsfile index b7d58cfd64..1cd67ef483 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -4,38 +4,42 @@ pipeline { image 'python:3.7.3' args '--user=root' } - } environment { COMMA_JWT = credentials('athena-test-jwt') + CI_PUSH = "${env.BRANCH_NAME == 'master' ? 'master-ci' : ''}" } + stages { - stage('Device Tests') { + stage('On-device Tests') { parallel { - stage('Build/Test') { + + stage('Build') { steps { - lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_name', quantity: 1){ + lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ timeout(time: 30, unit: 'MINUTES') { - dir(path: 'release') { + dir(path: 'selfdrive/test') { sh 'pip install paramiko' - sh 'python remote_build.py' + sh 'python phone_ci.py "cd release && ./build_devel.sh"' } } } } } + stage('Replay Tests') { steps { - lock(resource: "", label: 'eon2', inversePrecedence: true, variable: 'eon_name', quantity: 1){ - timeout(time: 45, unit: 'MINUTES') { + lock(resource: "", label: 'eon2', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ + timeout(time: 60, unit: 'MINUTES') { dir(path: 'selfdrive/test') { sh 'pip install paramiko' - sh 'python phone_ci.py' + sh 'python phone_ci.py "cd selfdrive/test/process_replay && ./camera_replay.py"' } } } } } + } } } diff --git a/SConstruct b/SConstruct index 28f0be2e12..f4a3de32a9 100644 --- a/SConstruct +++ b/SConstruct @@ -161,7 +161,10 @@ env = Environment( ) if os.environ.get('SCONS_CACHE'): - CacheDir('/tmp/scons_cache') + if QCOM_REPLAY: + CacheDir('/tmp/scons_cache_qcom_replay') + else: + CacheDir('/tmp/scons_cache') node_interval = 5 node_count = 0 diff --git a/release/build_devel.sh b/release/build_devel.sh index 6218336870..d4f7dfa029 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -37,7 +37,7 @@ echo "[-] bringing master-ci and devel in sync T=$SECONDS" git fetch origin master-ci git fetch origin devel -git checkout --track origin/master-ci || true +git checkout -f --track origin/master-ci git reset --hard master-ci git checkout master-ci git reset --hard origin/devel @@ -93,9 +93,9 @@ pushd panda/board/pedal make obj/comma.bin popd -if [ ! -z "$PUSH" ]; then - echo "[-] Pushing to $PUSH T=$SECONDS" - git push -f origin master-ci:$PUSH +if [ ! -z "$CI_PUSH" ]; then + echo "[-] Pushing to $CI_PUSH T=$SECONDS" + git push -f origin master-ci:$CI_PUSH fi echo "[-] done pushing T=$SECONDS" diff --git a/release/files_common b/release/files_common index c68dcf1cfa..4f3ee40172 100644 --- a/release/files_common +++ b/release/files_common @@ -1,15 +1,15 @@ -README.md -SAFETY.md - .gitignore LICENSE launch_chffrplus.sh launch_openpilot.sh +Jenkinsfile +SConstruct + CONTRIBUTING.md +README.md RELEASES.md - -SConstruct +SAFETY.md apk/ai.comma*.apk diff --git a/release/remote_build.py b/release/remote_build.py deleted file mode 100755 index c30a9ed446..0000000000 --- a/release/remote_build.py +++ /dev/null @@ -1,73 +0,0 @@ -#!/usr/bin/env python2 -import paramiko # pylint: disable=import-error -import os -import sys -import re -import time -import socket - - -def start_build(name): - ssh = paramiko.SSHClient() - ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy()) - - key_file = open(os.path.join(os.path.dirname(__file__), "../tools/ssh/key/id_rsa")) - key = paramiko.RSAKey.from_private_key(key_file) - - print("SSH to phone {}".format(name)) - - # Try connecting for one minute - t_start = time.time() - while True: - try: - ssh.connect(hostname=name, port=8022, pkey=key, timeout=10) - except (paramiko.ssh_exception.SSHException, socket.timeout, paramiko.ssh_exception.NoValidConnectionsError): - print("Connection failed") - if time.time() - t_start > 60: - raise - else: - break - time.sleep(1) - - conn = ssh.invoke_shell() - branch = os.environ['GIT_BRANCH'] - commit = os.environ.get('GIT_COMMIT', branch) - - conn.send('uname -a\n') - - conn.send('cd /data/openpilot_source\n') - conn.send("git reset --hard\n") - conn.send("git fetch origin\n") - conn.send("git checkout %s\n" % commit) - conn.send("git clean -xdf\n") - conn.send("git submodule update --init\n") - conn.send("git submodule foreach --recursive git reset --hard\n") - conn.send("git submodule foreach --recursive git clean -xdf\n") - conn.send("echo \"git took $SECONDS seconds\"\n") - - push = "PUSH=master-ci" if branch == "master" else "" - - conn.send("%s /data/openpilot_source/release/build_devel.sh\n" % push) - conn.send('echo "RESULT:" $?\n') - conn.send("exit\n") - return conn - - -if __name__ == "__main__": - eon_name = os.environ.get('eon_name', None) - - conn = start_build(eon_name) - - dat = b"" - - while True: - recvd = conn.recv(4096) - if len(recvd) == 0: - break - - dat += recvd - sys.stdout.buffer.write(recvd) - sys.stdout.flush() - - returns = re.findall(rb'^RESULT: (\d+)', dat[-1024:], flags=re.MULTILINE) - sys.exit(int(returns[0])) diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py index 735cace4e8..a5e2dc6463 100755 --- a/selfdrive/test/phone_ci.py +++ b/selfdrive/test/phone_ci.py @@ -6,22 +6,29 @@ import re import time import socket -TEST_DIR = "/data/openpilotci" -def run_test(name, test_func): +SOURCE_DIR = "/data/openpilot_source/" +TEST_DIR = "/data/openpilot/" + +def run_on_phone(test_cmd): + + eon_ip = os.environ.get('eon_ip', None) + if eon_ip is None: + raise Exception("'eon_ip' not set") + ssh = paramiko.SSHClient() ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy()) key_file = open(os.path.join(os.path.dirname(__file__), "../../tools/ssh/key/id_rsa")) key = paramiko.RSAKey.from_private_key(key_file) - print("SSH to phone {}".format(name)) + print("SSH to phone at {}".format(eon_ip)) - # Try connecting for one minute + # try connecting for one minute t_start = time.time() while True: try: - ssh.connect(hostname=name, port=8022, pkey=key, timeout=10) + ssh.connect(hostname=eon_ip, port=8022, pkey=key, timeout=10) except (paramiko.ssh_exception.SSHException, socket.timeout, paramiko.ssh_exception.NoValidConnectionsError): print("Connection failed") if time.time() - t_start > 60: @@ -30,40 +37,47 @@ def run_test(name, test_func): break time.sleep(1) - conn = ssh.invoke_shell() branch = os.environ['GIT_BRANCH'] commit = os.environ.get('GIT_COMMIT', branch) - conn.send("uname -a\n") + conn = ssh.invoke_shell() + + # pass in all environment variables prefixed with 'CI_' + for k, v in os.environ.items(): + if k.startswith("CI_"): + conn.send(f"export {k}='{v}'\n") + conn.send("export CI=1\n") - conn.send(f"cd {TEST_DIR}\n") + # set up environment + conn.send(f"cd {SOURCE_DIR}\n") conn.send("git reset --hard\n") conn.send("git fetch origin\n") - conn.send("git checkout %s\n" % commit) + conn.send(f"git checkout {commit}\n") conn.send("git clean -xdf\n") conn.send("git submodule update --init\n") conn.send("git submodule foreach --recursive git reset --hard\n") conn.send("git submodule foreach --recursive git clean -xdf\n") - conn.send("echo \"git took $SECONDS seconds\"\n") + conn.send('echo "git took $SECONDS seconds"\n') - test_func(conn) + conn.send(f"rsync -a --delete {SOURCE_DIR} {TEST_DIR}\n") + # run the test + conn.send(test_cmd + "\n") + + # get the result and print it back out conn.send('echo "RESULT:" $?\n') conn.send("exit\n") - return conn - -def test_modeld(conn): - conn.send(f"cd selfdrive/test/process_replay && PYTHONPATH={TEST_DIR} ./camera_replay.py\n") - -if __name__ == "__main__": - eon_name = os.environ.get('eon_name', None) - - conn = run_test(eon_name, test_modeld) dat = b"" + conn.settimeout(120) while True: - recvd = conn.recv(4096) + try: + recvd = conn.recv(4096) + except socket.timeout: + print("connection to phone timed out") + sys.exit(1) + if len(recvd) == 0: break @@ -71,5 +85,9 @@ if __name__ == "__main__": sys.stdout.buffer.write(recvd) sys.stdout.flush() - returns = re.findall(rb'^RESULT: (\d+)', dat[-1024:], flags=re.MULTILINE) - sys.exit(int(returns[0])) + return_code = int(re.findall(rb'^RESULT: (\d+)', dat[-1024:], flags=re.MULTILINE)[0]) + sys.exit(return_code) + + +if __name__ == "__main__": + run_on_phone(sys.argv[1]) From ba20e91d1194014a25122793c49456a010413779 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 3 Jul 2020 19:40:39 -0700 Subject: [PATCH 406/656] phone CI: pull over https, push over ssh --- release/build_devel.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/release/build_devel.sh b/release/build_devel.sh index d4f7dfa029..5194bef9a4 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -95,7 +95,7 @@ popd if [ ! -z "$CI_PUSH" ]; then echo "[-] Pushing to $CI_PUSH T=$SECONDS" - git push -f origin master-ci:$CI_PUSH + git push -f git@github.com:commaai/openpilot.git master-ci:$CI_PUSH fi echo "[-] done pushing T=$SECONDS" From ff4f432f0fd2ca5cf592082914e3a3a7b091a3db Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 4 Jul 2020 10:42:26 +0800 Subject: [PATCH 407/656] paint.cc: Simplify drawing line (#1643) * simplify drawing line * remove space --- selfdrive/ui/paint.cc | 36 ++++++++++-------------------------- 1 file changed, 10 insertions(+), 26 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index d0b0425e8c..b577d78be8 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -128,20 +128,12 @@ static void draw_lead(UIState *s, const cereal::RadarState::LeadData::Reader &le } static void ui_draw_lane_line(UIState *s, const model_path_vertices_data *pvd, NVGcolor color) { + if (pvd->cnt == 0) return; + nvgBeginPath(s->vg); - bool started = false; - for (int i=0; icnt; i++) { - float x = pvd->v[i].x; - float y = pvd->v[i].y; - if (x < 0 || y < 0.) { - continue; - } - if (!started) { - nvgMoveTo(s->vg, x, y); - started = true; - } else { - nvgLineTo(s->vg, x, y); - } + nvgMoveTo(s->vg, pvd->v[0].x, pvd->v[0].y); + for (int i=1; icnt; i++) { + nvgLineTo(s->vg, pvd->v[i].x, pvd->v[i].y); } nvgClosePath(s->vg); nvgFillColor(s->vg, color); @@ -214,20 +206,12 @@ static void update_all_track_data(UIState *s) { static void ui_draw_track(UIState *s, bool is_mpc, track_vertices_data *pvd) { + if (pvd->cnt == 0) return; + nvgBeginPath(s->vg); - bool started = false; - for(int i = 0;i < pvd->cnt;i++) { - float x = pvd->v[i].x; - float y = pvd->v[i].y; - if (x < 0 || y < 0) { - continue; - } - if (!started) { - nvgMoveTo(s->vg, x, y); - started = true; - } else { - nvgLineTo(s->vg, x, y); - } + nvgMoveTo(s->vg, pvd->v[0].x, pvd->v[0].y); + for (int i=1; icnt; i++) { + nvgLineTo(s->vg, pvd->v[i].x, pvd->v[i].y); } nvgClosePath(s->vg); From 3f57b7ee7688efd38b2ba3581495b2c250409020 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 3 Jul 2020 20:34:31 -0700 Subject: [PATCH 408/656] increase jenkins timeout --- release/build_devel.sh | 3 ++- selfdrive/test/phone_ci.py | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/release/build_devel.sh b/release/build_devel.sh index 5194bef9a4..782ea0fae5 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -95,7 +95,8 @@ popd if [ ! -z "$CI_PUSH" ]; then echo "[-] Pushing to $CI_PUSH T=$SECONDS" - git push -f git@github.com:commaai/openpilot.git master-ci:$CI_PUSH + git remote set-url origin git@github.com:commaai/openpilot.git + git push -f origin master-ci:$CI_PUSH fi echo "[-] done pushing T=$SECONDS" diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py index a5e2dc6463..7040e8cb53 100755 --- a/selfdrive/test/phone_ci.py +++ b/selfdrive/test/phone_ci.py @@ -69,7 +69,7 @@ def run_on_phone(test_cmd): conn.send("exit\n") dat = b"" - conn.settimeout(120) + conn.settimeout(150) while True: try: From b23d7950e3d38d4b436801e35c76b66657b35c95 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 4 Jul 2020 00:10:58 -0700 Subject: [PATCH 409/656] remove manager_helpers.py after CPU usage test refactor --- common/manager_helpers.py | 1 - release/files_common | 1 - 2 files changed, 2 deletions(-) delete mode 100644 common/manager_helpers.py diff --git a/common/manager_helpers.py b/common/manager_helpers.py deleted file mode 100644 index 8b13789179..0000000000 --- a/common/manager_helpers.py +++ /dev/null @@ -1 +0,0 @@ - diff --git a/release/files_common b/release/files_common index 4f3ee40172..be4044285d 100644 --- a/release/files_common +++ b/release/files_common @@ -36,7 +36,6 @@ common/cython_hacks.py common/apk.py common/SConscript common/common_pyx_setup.py -common/manager_helpers.py common/kalman/.gitignore common/kalman/* From 8cadecae8f4d6d25deb84950779bc717d8e7ab46 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 4 Jul 2020 09:03:29 -0700 Subject: [PATCH 410/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index ca12a1c660..2fab502cad 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit ca12a1c6603328dcb3ddbef67f158fecf245f74b +Subproject commit 2fab502cad444ebabea51e0e0df447b4bbd45a21 From f1afb3e3ae4b95a1de0262d1408c49093c5ada6f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh <8762862+adeebshihadeh@users.noreply.github.com> Date: Sun, 5 Jul 2020 17:56:24 -0700 Subject: [PATCH 411/656] Sound test (#1820) * WIP sound test * it does something * refactor * phone only * update release files * test sound card init * add to CI * check writes * increase time * unused * only build cereal * small tolerance Co-authored-by: Comma Device --- Jenkinsfile | 13 ++++++ common/android.py | 4 ++ common/testing.py | 8 ---- release/files_common | 2 +- selfdrive/controls/controlsd.py | 5 +-- selfdrive/test/helpers.py | 56 ++++++++++++++++++++++++++ selfdrive/test/phone_ci.py | 2 +- selfdrive/test/test_openpilot.py | 59 +-------------------------- selfdrive/test/test_sounds.py | 68 ++++++++++++++++++++++++++++++++ 9 files changed, 147 insertions(+), 70 deletions(-) delete mode 100644 common/testing.py create mode 100644 selfdrive/test/helpers.py create mode 100755 selfdrive/test/test_sounds.py diff --git a/Jenkinsfile b/Jenkinsfile index 1cd67ef483..6afac3a236 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -40,6 +40,19 @@ pipeline { } } + stage('Sound Test') { + steps { + lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ + timeout(time: 30, unit: 'MINUTES') { + dir(path: 'selfdrive/test') { + sh 'pip install paramiko' + sh 'python phone_ci.py "SCONS_CACHE=1 scons -j3 cereal/ && cd selfdrive/test && nosetests -s test_sounds.py"' + } + } + } + } + } + } } } diff --git a/common/android.py b/common/android.py index e1b1098d39..43bb0f3c1e 100644 --- a/common/android.py +++ b/common/android.py @@ -12,6 +12,10 @@ NetworkStrength = log.ThermalData.NetworkStrength ANDROID = os.path.isfile('/EON') +def get_sound_card_online(): + return (os.path.isfile('/proc/asound/card0/state') and + open('/proc/asound/card0/state').read().strip() == 'ONLINE') + def getprop(key): if not ANDROID: return "" diff --git a/common/testing.py b/common/testing.py deleted file mode 100644 index 95c43b574d..0000000000 --- a/common/testing.py +++ /dev/null @@ -1,8 +0,0 @@ -import os -from nose.tools import nottest - -def phone_only(x): - if os.path.isfile("/init.qcom.rc"): - return x - else: - return nottest(x) diff --git a/release/files_common b/release/files_common index be4044285d..b963c6289a 100644 --- a/release/files_common +++ b/release/files_common @@ -26,7 +26,6 @@ common/numpy_fast.py common/params.py common/xattr.py common/profiler.py -common/testing.py common/basedir.py common/filter_simple.py common/stat_live.py @@ -316,6 +315,7 @@ selfdrive/thermald/thermald.py selfdrive/thermald/power_monitoring.py selfdrive/test/__init__.py +selfdrive/test/helpers.py selfdrive/test/test_openpilot.py selfdrive/test/test_fingerprints.py selfdrive/test/test_car_models.py diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 43ccc7acb1..f64acae101 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -2,7 +2,7 @@ import os import gc from cereal import car, log -from common.android import ANDROID +from common.android import ANDROID, get_sound_card_online from common.numpy_fast import clip from common.realtime import sec_since_boot, set_realtime_priority, set_core_affinity, Ratekeeper, DT_CTRL from common.profiler import Profiler @@ -79,8 +79,7 @@ class Controls: internet_needed or not openpilot_enabled_toggle # detect sound card presence and ensure successful init - sounds_available = (not ANDROID or (os.path.isfile('/proc/asound/card0/state') and - open('/proc/asound/card0/state').read().strip() == 'ONLINE')) + sounds_available = not ANDROID or get_sound_card_online() car_recognized = self.CP.carName != 'mock' # If stock camera is disconnected, we loaded car controls and it's not dashcam mode diff --git a/selfdrive/test/helpers.py b/selfdrive/test/helpers.py new file mode 100644 index 0000000000..2a6cf501a2 --- /dev/null +++ b/selfdrive/test/helpers.py @@ -0,0 +1,56 @@ +import subprocess +from functools import wraps +from nose.tools import nottest + +from common.android import ANDROID +from common.apk import update_apks, start_offroad, pm_apply_packages, android_packages +from selfdrive.manager import start_managed_process, kill_managed_process, get_running + +def phone_only(x): + if ANDROID: + return x + else: + return nottest(x) + +def with_processes(processes): + def wrapper(func): + @wraps(func) + def wrap(): + # start and assert started + [start_managed_process(p) for p in processes] + assert all(get_running()[name].exitcode is None for name in processes) + + # call the function + try: + func() + # assert processes are still started + assert all(get_running()[name].exitcode is None for name in processes) + finally: + # kill and assert all stopped + [kill_managed_process(p) for p in processes] + assert len(get_running()) == 0 + return wrap + return wrapper + +def with_apks(): + def wrapper(func): + @wraps(func) + def wrap(): + update_apks() + pm_apply_packages('enable') + start_offroad() + + func() + + try: + for package in android_packages: + apk_is_running = (subprocess.call(["pidof", package]) == 0) + assert apk_is_running, package + finally: + pm_apply_packages('disable') + for package in android_packages: + apk_is_not_running = (subprocess.call(["pidof", package]) == 1) + assert apk_is_not_running, package + return wrap + return wrapper + diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py index 7040e8cb53..1c84b9a50d 100755 --- a/selfdrive/test/phone_ci.py +++ b/selfdrive/test/phone_ci.py @@ -69,7 +69,7 @@ def run_on_phone(test_cmd): conn.send("exit\n") dat = b"" - conn.settimeout(150) + conn.settimeout(240) while True: try: diff --git a/selfdrive/test/test_openpilot.py b/selfdrive/test/test_openpilot.py index c03a2e41ff..fc3b17dded 100644 --- a/selfdrive/test/test_openpilot.py +++ b/selfdrive/test/test_openpilot.py @@ -2,77 +2,22 @@ import os os.environ['FAKEUPLOAD'] = "1" -from common.apk import update_apks, start_offroad, pm_apply_packages, android_packages from common.params import Params from common.realtime import sec_since_boot -from common.testing import phone_only -from selfdrive.manager import manager_init, manager_prepare -from selfdrive.manager import start_managed_process, kill_managed_process, get_running -from selfdrive.manager import start_daemon_process -from functools import wraps +from selfdrive.manager import manager_init, manager_prepare, start_daemon_process +from selfdrive.test.helpers import phone_only, with_processes import json import requests import signal import subprocess import time -DID_INIT = False # must run first @phone_only def test_manager_prepare(): - global DID_INIT manager_init() manager_prepare() - DID_INIT = True - -def with_processes(processes): - def wrapper(func): - @wraps(func) - def wrap(): - if not DID_INIT: - test_manager_prepare() - - # start and assert started - [start_managed_process(p) for p in processes] - assert all(get_running()[name].exitcode is None for name in processes) - - # call the function - try: - func() - # assert processes are still started - assert all(get_running()[name].exitcode is None for name in processes) - finally: - # kill and assert all stopped - [kill_managed_process(p) for p in processes] - assert len(get_running()) == 0 - return wrap - return wrapper - -def with_apks(): - def wrapper(func): - @wraps(func) - def wrap(): - if not DID_INIT: - test_manager_prepare() - - update_apks() - pm_apply_packages('enable') - start_offroad() - - func() - - try: - for package in android_packages: - apk_is_running = (subprocess.call(["pidof", package]) == 0) - assert apk_is_running, package - finally: - pm_apply_packages('disable') - for package in android_packages: - apk_is_not_running = (subprocess.call(["pidof", package]) == 1) - assert apk_is_not_running, package - return wrap - return wrapper @phone_only @with_processes(['loggerd', 'logmessaged', 'tombstoned', 'proclogd', 'logcatd']) diff --git a/selfdrive/test/test_sounds.py b/selfdrive/test/test_sounds.py new file mode 100755 index 0000000000..e7aedf4da7 --- /dev/null +++ b/selfdrive/test/test_sounds.py @@ -0,0 +1,68 @@ +#!/usr/bin/env python3 +import time +import subprocess + +from cereal import car +import cereal.messaging as messaging +from selfdrive.test.helpers import phone_only, with_processes +from common.android import get_sound_card_online +from common.realtime import DT_CTRL + +AudibleAlert = car.CarControl.HUDControl.AudibleAlert + +SOUNDS = { + # sound: total writes + AudibleAlert.none: 0, + AudibleAlert.chimeEngage: 85, + AudibleAlert.chimeDisengage: 85, + AudibleAlert.chimeError: 85, + AudibleAlert.chimePrompt: 85, + AudibleAlert.chimeWarning1: 80, + AudibleAlert.chimeWarning2: 107, + AudibleAlert.chimeWarningRepeat: 134, + AudibleAlert.chimeWarning2Repeat: 177, +} + +def get_total_writes(): + audio_flinger = subprocess.check_output('dumpsys media.audio_flinger', shell=True, encoding='utf-8').strip() + write_lines = [l for l in audio_flinger.split('\n') if l.strip().startswith('Total writes')] + return sum([int(l.split(':')[1]) for l in write_lines]) + +@phone_only +def test_sound_card_init(): + assert get_sound_card_online() + + +@phone_only +@with_processes(['ui', 'camerad']) +def test_alert_sounds(): + + pm = messaging.PubMaster(['thermal', 'controlsState']) + + # make sure they're all defined + alert_sounds = {v: k for k, v in car.CarControl.HUDControl.AudibleAlert.schema.enumerants.items()} + diff = set(SOUNDS.keys()).symmetric_difference(alert_sounds.keys()) + assert len(diff) == 0, f"not all sounds defined in test: {diff}" + + # wait for procs to init + time.sleep(5) + + msg = messaging.new_message('thermal') + msg.thermal.started = True + pm.send('thermal', msg) + + for sound, expected_writes in SOUNDS.items(): + print(f"testing {alert_sounds[sound]}") + start_writes = get_total_writes() + + for _ in range(int(9 / DT_CTRL)): + msg = messaging.new_message('controlsState') + msg.controlsState.enabled = True + msg.controlsState.active = True + msg.controlsState.alertSound = sound + msg.controlsState.alertType = str(sound) + pm.send('controlsState', msg) + time.sleep(DT_CTRL) + + actual_writes = get_total_writes() - start_writes + assert abs(expected_writes - actual_writes) <= 2, f"{alert_sounds[sound]}: expected {expected_writes} writes, got {actual_writes}" From 88f6fad3923a5f9adae1b30386a30671f5b276f2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 5 Jul 2020 18:04:25 -0700 Subject: [PATCH 412/656] remove Jenkinsfile from release files --- release/files_common | 1 - 1 file changed, 1 deletion(-) diff --git a/release/files_common b/release/files_common index b963c6289a..745026f6c5 100644 --- a/release/files_common +++ b/release/files_common @@ -3,7 +3,6 @@ LICENSE launch_chffrplus.sh launch_openpilot.sh -Jenkinsfile SConstruct CONTRIBUTING.md From c4674a3071539270109c71169f6b8b7b21928480 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 5 Jul 2020 19:52:47 -0700 Subject: [PATCH 413/656] only update README badge from tests triggered by push events --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 1aef3664a0..25bddc736f 100644 --- a/README.md +++ b/README.md @@ -331,7 +331,7 @@ NO WARRANTY EXPRESSED OR IMPLIED.** -[![openpilot tests](https://github.com/commaai/openpilot/workflows/openpilot%20tests/badge.svg)](https://github.com/commaai/openpilot/actions) +[![openpilot tests](https://github.com/commaai/openpilot/workflows/openpilot%20tests/badge.svg?event=push)](https://github.com/commaai/openpilot/actions) [![Total alerts](https://img.shields.io/lgtm/alerts/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/alerts/) [![Language grade: Python](https://img.shields.io/lgtm/grade/python/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/context:python) [![Language grade: C/C++](https://img.shields.io/lgtm/grade/cpp/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/context:cpp) From c4b5322b7fbabd37cfba4c93b5af70f1f3810826 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 5 Jul 2020 20:18:18 -0700 Subject: [PATCH 414/656] include subaru and hyundai BSM integration in release notes --- RELEASES.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index da18c65002..c5d7ebbc5f 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -5,7 +5,7 @@ Version 0.7.7 (2020-xx-xx) * Improved thermal management on comma two * Improved autofocus for road-facing camera * Fix GM ignition detection - * Block lane change start using blindspot monitor on Toyotas with TSS2 + * Block lane change start using blindspot monitor on select Toyota, Hyundai, and Subaru * Code cleanup and smaller release sizes * Hyundai Ioniq Electric Limited 2019 and Ioniq SE 2020 support thanks to baldwalker! * Subaru Forester 2019 and Ascent 2019 support thanks to martinl! From c2c00f65a70905ebc4d912cf5126bb18169e2cbd Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Mon, 6 Jul 2020 02:10:14 -0700 Subject: [PATCH 415/656] Fix gyro orientation offset for EONs with OP3T mainboards (#1738) * One-time zap of OP3T sensor registry * Bash, I wish I knew how to quit you * Better comment wording * Slight increase for sensor reset settle-time Co-authored-by: Comma Device --- launch_chffrplus.sh | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 60102fbd71..3ef93eb4ef 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -99,6 +99,18 @@ function launch { fi fi + # One-time fix for a subset of OP3T with gyro orientation offsets. + # Remove and regenerate qcom sensor registry. Only done on OP3T mainboards. + # Performed exactly once. The old registry is preserved just-in-case, and + # doubles as a flag denoting we've already done the reset. + # TODO: we should really grow per-platform detect and setup routines + if ! $(grep -q "letv" /proc/cmdline) && [ ! -f "/persist/comma/op3t-sns-reg-backup" ]; then + echo "Performing OP3T sensor registry reset" + mv /persist/sensors/sns.reg /persist/comma/op3t-sns-reg-backup && + rm -f /persist/sensors/sensors_settings /persist/sensors/error_log /persist/sensors/gyro_sensitity_cal && + echo "restart" > /sys/kernel/debug/msm_subsys/slpi && + sleep 5 # Give Android sensor subsystem a moment to recover + fi # handle pythonpath ln -sfn $(pwd) /data/pythonpath From 10bfbaff8ebf0c14cbf7109911dc5ea2af6b3619 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 6 Jul 2020 13:36:36 +0200 Subject: [PATCH 416/656] Lower max CPU temp to go onroad to 70 C --- selfdrive/thermald/thermald.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 5ffa8f94c8..65587ca9c9 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -273,7 +273,7 @@ def thermald_thread(): # If device is offroad we want to cool down before going onroad # since going onroad increases load and can make temps go over 107 # We only do this if there is a relay that prevents the car from faulting - if max_cpu_temp > 107. or bat_temp >= 63. or (has_relay and (started_ts is None) and max_cpu_temp > 75.0): + if max_cpu_temp > 107. or bat_temp >= 63. or (has_relay and (started_ts is None) and max_cpu_temp > 70.0): # onroad not allowed thermal_status = ThermalStatus.danger elif max_comp_temp > 96.0 or bat_temp > 60.: From c458f5a5d3587d0eb87abbebd86c4f399e28c63d Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Mon, 6 Jul 2020 09:33:16 -0700 Subject: [PATCH 417/656] k-line 5 init fault type (#1821) * k-line 5 baud fault type * update name * bump cereal * fix name * add missing event --- cereal | 2 +- selfdrive/boardd/boardd.cc | 2 +- selfdrive/controls/lib/events.py | 2 ++ 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 7f6df092ef..221c458e15 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 7f6df092efdc64fbab56d1f8804ce40ccd77dee5 +Subproject commit 221c458e15e223304500175981e7894f5c5c0e4f diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 2b3ce95277..0bdf207b7a 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -509,7 +509,7 @@ void can_health(PubMaster &pm) { size_t i = 0; for (size_t f = size_t(cereal::HealthData::FaultType::RELAY_MALFUNCTION); - f <= size_t(cereal::HealthData::FaultType::REGISTER_DIVERGENT); f++){ + f <= size_t(cereal::HealthData::FaultType::INTERRUPT_RATE_KLINE_INIT); f++){ if (fault_bits.test(f)) { faults.set(i, cereal::HealthData::FaultType(f)); i++; diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index a89a008a0b..6f184bbb36 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -204,6 +204,8 @@ def wrong_car_mode_alert(CP, sm, metric): EVENTS = { # ********** events with no alerts ********** + EventName.modeldLagging: {}, + # ********** events only containing alerts displayed in all states ********** EventName.debugAlert: { From d5d0e75070b3f39f9d1dba3306b2b9bbffe46911 Mon Sep 17 00:00:00 2001 From: Jafar Al-Gharaibeh Date: Mon, 6 Jul 2020 12:25:17 -0500 Subject: [PATCH 418/656] Mazda BSM (#1830) * Mazda BSM support Signed-off-by: Jafar Al-Gharaibeh * Add Mazda3 2017 and CX-9 2016 Fingerprints Signed-off-by: Jafar Al-Gharaibeh --- selfdrive/car/mazda/carstate.py | 6 ++++++ selfdrive/car/mazda/values.py | 12 +++++++++++- 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index e1c9030a04..18a26cc38a 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -56,6 +56,9 @@ class CarState(CarStateBase): ret.gas = cp.vl["ENGINE_DATA"]['PEDAL_GAS'] ret.gasPressed = ret.gas > 0 + ret.leftBlindspot = cp.vl["BSM"]['LEFT_BS1'] == 1 + ret.rightBlindspot = cp.vl["BSM"]['RIGHT_BS1'] == 1 + # LKAS is enabled at 52kph going up and disabled at 45kph going down if speed_kph > LKAS_LIMITS.ENABLE_SPEED: self.lkas_allowed = True @@ -139,6 +142,8 @@ class CarState(CarStateBase): ("SET_P", "CRZ_BTNS", 0), ("SET_M", "CRZ_BTNS", 0), ("CTR", "CRZ_BTNS", 0), + ("LEFT_BS1", "BSM", 0), + ("RIGHT_BS1", "BSM", 0), ] checks += [ @@ -150,6 +155,7 @@ class CarState(CarStateBase): ("SEATBELT", 10), ("DOORS", 10), ("GEAR", 20), + ("BSM", 10), ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index c6268e95a0..5759d431a8 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -48,10 +48,20 @@ FINGERPRINTS = { 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 628: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1182: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1456: 8, 1479: 8 }, - # CX-9 2017 Australia + # CX-9 2017 Australia - old CAM connector { 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 138: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 522: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 583: 8, 605: 8, 606: 8, 628: 8, 832: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1177: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1247: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8 }, + + # CX-9 2016 - old CAM connector + { + 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 583: 8, 605: 8, 606: 8, 608: 8, 628: 8, 832: 8, 836: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2004: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }, + + # Mazda 3 2017 + { + 19: 5, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 628: 8, 832: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1169: 8, 1170: 8, 1173: 8, 1177: 8, 1180: 8, 1182: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1456: 8, 1479: 8, 2015: 8, 2024: 8, 2025: 8 + }, ], } From a633191be4b9c1c168f2e53ded61d0e19e90196d Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Mon, 6 Jul 2020 11:31:29 -0700 Subject: [PATCH 419/656] add dcam to release note --- RELEASES.md | 1 + 1 file changed, 1 insertion(+) diff --git a/RELEASES.md b/RELEASES.md index c5d7ebbc5f..f575eb88ff 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -4,6 +4,7 @@ Version 0.7.7 (2020-xx-xx) * Improved vehicle model estimation using high precision localizer * Improved thermal management on comma two * Improved autofocus for road-facing camera + * Improved noise performance for driver-facing camera * Fix GM ignition detection * Block lane change start using blindspot monitor on select Toyota, Hyundai, and Subaru * Code cleanup and smaller release sizes From 4619401bfc8ce4f5a6fac5167e5e386ffbf36409 Mon Sep 17 00:00:00 2001 From: George Hotz Date: Mon, 6 Jul 2020 11:56:07 -0700 Subject: [PATCH 420/656] add calmodel --- common/transformations/model.py | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/common/transformations/model.py b/common/transformations/model.py index 1be827889d..070d174711 100644 --- a/common/transformations/model.py +++ b/common/transformations/model.py @@ -41,6 +41,17 @@ medmodel_intrinsics = np.array( [ 0. , eon_focal_length / medmodel_zoom, MEDMODEL_CY], [ 0. , 0. , 1.]]) +# CAL model +CALMODEL_INPUT_SIZE = (512, 256) +CALMODEL_YUV_SIZE = (CALMODEL_INPUT_SIZE[0], CALMODEL_INPUT_SIZE[1] * 3 // 2) +CALMODEL_CY = 47.6 + +calmodel_zoom = 1.5 +calmodel_intrinsics = np.array( + [[ eon_focal_length / calmodel_zoom, 0. , 0.5 * CALMODEL_INPUT_SIZE[0]], + [ 0. , eon_focal_length / calmodel_zoom, CALMODEL_CY], + [ 0. , 0. , 1.]]) + # BIG model From 9adfc83b23ff9973c7a5053f4b5d8cc5881600d7 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Mon, 6 Jul 2020 14:31:12 -0500 Subject: [PATCH 421/656] Added engine f/w for CAR.COROLLAH_TSS2 (#1832) Jordi#2212's 2020 Toyota Corolla Touring Sports 2.0 Hybrid (EU) DongleID 221a06e11b28330b https://discord.com/channels/469524606043160576/524327905937850394/729778471869612173 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 564cee1ef8..386c2b52b0 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -578,6 +578,7 @@ FW_VERSIONS = { }, CAR.COROLLAH_TSS2: { (Ecu.engine, 0x700, None): [ + b'\x01896630ZJ1000\x00\x00\x00\x00', b'\x018966342M5000\x00\x00\x00\x00', b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZR2000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', From fd504aa3f2067d403ca917efdf860b3b315bfd66 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 6 Jul 2020 19:43:42 -0700 Subject: [PATCH 422/656] show current sound name during sound test --- selfdrive/test/test_sounds.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/test/test_sounds.py b/selfdrive/test/test_sounds.py index e7aedf4da7..e9946efb0f 100755 --- a/selfdrive/test/test_sounds.py +++ b/selfdrive/test/test_sounds.py @@ -2,7 +2,7 @@ import time import subprocess -from cereal import car +from cereal import log, car import cereal.messaging as messaging from selfdrive.test.helpers import phone_only, with_processes from common.android import get_sound_card_online @@ -61,6 +61,9 @@ def test_alert_sounds(): msg.controlsState.active = True msg.controlsState.alertSound = sound msg.controlsState.alertType = str(sound) + msg.controlsState.alertText1 = "Testing Sounds" + msg.controlsState.alertText2 = f"playing {alert_sounds[sound]}" + msg.controlsState.alertSize = log.ControlsState.AlertSize.mid pm.send('controlsState', msg) time.sleep(DT_CTRL) From 975ab4078636d3769a3e500c8151416a99465379 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 6 Jul 2020 20:15:31 -0700 Subject: [PATCH 423/656] build script --- release/build_release2.sh | 64 ++++++++++++++++++++++++-------------- selfdrive/test/phone_ci.py | 2 ++ 2 files changed, 43 insertions(+), 23 deletions(-) diff --git a/release/build_release2.sh b/release/build_release2.sh index 08f727b1b2..7893c763d0 100755 --- a/release/build_release2.sh +++ b/release/build_release2.sh @@ -8,36 +8,45 @@ export GIT_AUTHOR_EMAIL="user@comma.ai" export GIT_SSH_COMMAND="ssh -i /data/gitkey" -# Create folders -rm -rf /data/openpilot -mkdir -p /data/openpilot -cd /data/openpilot - -# Create git repo -git init -git remote add origin git@github.com:commaai/openpilot.git -git fetch origin devel +# set CLEAN to build outside of CI +if [ ! -z "$CLEAN" ]; then + # Create folders + rm -rf /data/openpilot + mkdir -p /data/openpilot + cd /data/openpilot + + # Create git repo + git init + git remote add origin git@github.com:commaai/openpilot.git + git fetch origin devel-staging +else + cd /data/openpilot + git clean -xdf + git branch -D release2-staging || true +fi + git fetch origin release2-staging git fetch origin dashcam-staging -# Checkout devel -#git checkout origin/devel -#git clean -xdf - # Create release2 with no history -git checkout --orphan release2-staging origin/devel +if [ ! -z "$CLEAN" ]; then + git checkout --orphan release2-staging origin/devel-staging +else + git checkout --orphan release2-staging +fi VERSION=$(cat selfdrive/common/version.h | awk -F\" '{print $2}') git commit -m "openpilot v$VERSION" # Build signed panda firmware pushd panda/board/ -cp -r /tmp/pandaextra /data/openpilot/ -RELEASE=1 make obj/panda.bin +#cp -r /tmp/pandaextra /data/openpilot/ +#RELEASE=1 make obj/panda.bin +make obj/panda.bin mv obj/panda.bin /tmp/panda.bin make clean mv /tmp/panda.bin obj/panda.bin.signed -rm -rf /data/openpilot/pandaextra +#rm -rf /data/openpilot/pandaextra popd # Build stuff @@ -60,6 +69,9 @@ rm .sconsign.dblite # Restore phonelibs git checkout phonelibs/ +# Remove the stuff needed to build release +rm -rf release/ + # Mark as prebuilt release touch prebuilt @@ -70,11 +82,17 @@ git commit --amend -m "openpilot v$VERSION" # Print committed files that are normally gitignored #git status --ignored -# Push to release2-staging -git push -f origin release2-staging +if [ ! -z "$CI_PUSH" ]; then + git remote set-url origin git@github.com:commaai/openpilot.git + + # Push to release2-staging + #git push -f origin release2-staging + git push -f origin release2-staging:r2_staging_test -# Create dashcam release -git rm selfdrive/car/*/carcontroller.py + # Create dashcam release + git rm selfdrive/car/*/carcontroller.py -git commit -m "create dashcam release from release2" -git push -f origin release2-staging:dashcam-staging + git commit -m "create dashcam release from release2" + #git push -f origin release2-staging:dashcam-staging + git push -f origin release2-staging:d_staging_test +fi diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py index 1c84b9a50d..d7e6e8f0c4 100755 --- a/selfdrive/test/phone_ci.py +++ b/selfdrive/test/phone_ci.py @@ -52,6 +52,8 @@ def run_on_phone(test_cmd): conn.send(f"cd {SOURCE_DIR}\n") conn.send("git reset --hard\n") conn.send("git fetch origin\n") + conn.send("find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \\;\n") + conn.send(f"git reset --hard {commit}\n") conn.send(f"git checkout {commit}\n") conn.send("git clean -xdf\n") conn.send("git submodule update --init\n") From 6b942c94deed1467458b510215e51e263b6ba1ad Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 6 Jul 2020 20:16:16 -0700 Subject: [PATCH 424/656] Revert "build script", should've been on branch This reverts commit 975ab4078636d3769a3e500c8151416a99465379. --- release/build_release2.sh | 64 ++++++++++++++------------------------ selfdrive/test/phone_ci.py | 2 -- 2 files changed, 23 insertions(+), 43 deletions(-) diff --git a/release/build_release2.sh b/release/build_release2.sh index 7893c763d0..08f727b1b2 100755 --- a/release/build_release2.sh +++ b/release/build_release2.sh @@ -8,45 +8,36 @@ export GIT_AUTHOR_EMAIL="user@comma.ai" export GIT_SSH_COMMAND="ssh -i /data/gitkey" -# set CLEAN to build outside of CI -if [ ! -z "$CLEAN" ]; then - # Create folders - rm -rf /data/openpilot - mkdir -p /data/openpilot - cd /data/openpilot - - # Create git repo - git init - git remote add origin git@github.com:commaai/openpilot.git - git fetch origin devel-staging -else - cd /data/openpilot - git clean -xdf - git branch -D release2-staging || true -fi - +# Create folders +rm -rf /data/openpilot +mkdir -p /data/openpilot +cd /data/openpilot + +# Create git repo +git init +git remote add origin git@github.com:commaai/openpilot.git +git fetch origin devel git fetch origin release2-staging git fetch origin dashcam-staging +# Checkout devel +#git checkout origin/devel +#git clean -xdf + # Create release2 with no history -if [ ! -z "$CLEAN" ]; then - git checkout --orphan release2-staging origin/devel-staging -else - git checkout --orphan release2-staging -fi +git checkout --orphan release2-staging origin/devel VERSION=$(cat selfdrive/common/version.h | awk -F\" '{print $2}') git commit -m "openpilot v$VERSION" # Build signed panda firmware pushd panda/board/ -#cp -r /tmp/pandaextra /data/openpilot/ -#RELEASE=1 make obj/panda.bin -make obj/panda.bin +cp -r /tmp/pandaextra /data/openpilot/ +RELEASE=1 make obj/panda.bin mv obj/panda.bin /tmp/panda.bin make clean mv /tmp/panda.bin obj/panda.bin.signed -#rm -rf /data/openpilot/pandaextra +rm -rf /data/openpilot/pandaextra popd # Build stuff @@ -69,9 +60,6 @@ rm .sconsign.dblite # Restore phonelibs git checkout phonelibs/ -# Remove the stuff needed to build release -rm -rf release/ - # Mark as prebuilt release touch prebuilt @@ -82,17 +70,11 @@ git commit --amend -m "openpilot v$VERSION" # Print committed files that are normally gitignored #git status --ignored -if [ ! -z "$CI_PUSH" ]; then - git remote set-url origin git@github.com:commaai/openpilot.git - - # Push to release2-staging - #git push -f origin release2-staging - git push -f origin release2-staging:r2_staging_test +# Push to release2-staging +git push -f origin release2-staging - # Create dashcam release - git rm selfdrive/car/*/carcontroller.py +# Create dashcam release +git rm selfdrive/car/*/carcontroller.py - git commit -m "create dashcam release from release2" - #git push -f origin release2-staging:dashcam-staging - git push -f origin release2-staging:d_staging_test -fi +git commit -m "create dashcam release from release2" +git push -f origin release2-staging:dashcam-staging diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py index d7e6e8f0c4..1c84b9a50d 100755 --- a/selfdrive/test/phone_ci.py +++ b/selfdrive/test/phone_ci.py @@ -52,8 +52,6 @@ def run_on_phone(test_cmd): conn.send(f"cd {SOURCE_DIR}\n") conn.send("git reset --hard\n") conn.send("git fetch origin\n") - conn.send("find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \\;\n") - conn.send(f"git reset --hard {commit}\n") conn.send(f"git checkout {commit}\n") conn.send("git clean -xdf\n") conn.send("git submodule update --init\n") From bb1e3fc13a47ed3f1d437d474b29a386b5a9093b Mon Sep 17 00:00:00 2001 From: allenrobberson <67385929+allenrobberson@users.noreply.github.com> Date: Tue, 7 Jul 2020 12:16:44 -0700 Subject: [PATCH 425/656] Update README.md (#1837) Added 2020 Honda Accord Hybrid --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 25bddc736f..0d847b25f0 100644 --- a/README.md +++ b/README.md @@ -67,7 +67,7 @@ Supported Cars | Acura | ILX 2016-18 | AcuraWatch Plus | openpilot | 25mph1 | 25mph | | Acura | RDX 2016-18 | AcuraWatch Plus | openpilot | 25mph1 | 12mph | | Honda | Accord 2018-19 | All | Stock | 0mph | 3mph | -| Honda | Accord Hybrid 2018-19 | All | Stock | 0mph | 3mph | +| Honda | Accord Hybrid 2018-20 | All | Stock | 0mph | 3mph | | Honda | Civic Hatchback 2017-19 | Honda Sensing | Stock | 0mph | 12mph | | Honda | Civic Sedan/Coupe 2016-18 | Honda Sensing | openpilot | 0mph | 12mph | | Honda | Civic Sedan/Coupe 2019-20 | Honda Sensing | Stock | 0mph | 2mph2 | From d8ff1865450fe341f05dc6d8b6a8580eccb24f86 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 7 Jul 2020 12:36:02 -0700 Subject: [PATCH 426/656] Separate scons cache by branch (#1836) * separate scons cache by branch * debug * guess you can only call CacheDir once * remove another call * pass git branch and commit through * copytree * set CI --- SConstruct | 18 ++++++++++++++---- selfdrive/test/phone_ci.py | 2 +- 2 files changed, 15 insertions(+), 5 deletions(-) diff --git a/SConstruct b/SConstruct index f4a3de32a9..933a540020 100644 --- a/SConstruct +++ b/SConstruct @@ -1,4 +1,5 @@ import os +import shutil import subprocess import sys import platform @@ -161,10 +162,19 @@ env = Environment( ) if os.environ.get('SCONS_CACHE'): - if QCOM_REPLAY: - CacheDir('/tmp/scons_cache_qcom_replay') - else: - CacheDir('/tmp/scons_cache') + cache_dir = '/tmp/scons_cache' + + if os.getenv('CI'): + branch = os.getenv('GIT_BRANCH') + + if QCOM_REPLAY: + cache_dir = '/tmp/scons_cache_qcom_replay' + elif branch is not None and branch != 'master': + cache_dir_branch = '/tmp/scons_cache_' + branch + if not os.path.isdir(cache_dir_branch) and os.path.isdir(cache_dir): + shutil.copytree(cache_dir, cache_dir_branch) + cache_dir = cache_dir_branch + CacheDir(cache_dir) node_interval = 5 node_count = 0 diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py index 1c84b9a50d..3d2e6f0672 100755 --- a/selfdrive/test/phone_ci.py +++ b/selfdrive/test/phone_ci.py @@ -44,7 +44,7 @@ def run_on_phone(test_cmd): # pass in all environment variables prefixed with 'CI_' for k, v in os.environ.items(): - if k.startswith("CI_"): + if k.startswith("CI_") or k in ["GIT_BRANCH", "GIT_COMMIT"]: conn.send(f"export {k}='{v}'\n") conn.send("export CI=1\n") From de16043331cd5995daa60ea25b1f200c3c4b5a60 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Tue, 7 Jul 2020 13:25:54 -0700 Subject: [PATCH 427/656] Remove chffrplus mention from tools readme --- tools/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/README.md b/tools/README.md index badec0210c..22de4a9b7c 100644 --- a/tools/README.md +++ b/tools/README.md @@ -52,7 +52,7 @@ Replay driving data **Hardware needed**: none -`unlogger.py` replays data collected with [chffrplus](https://github.com/commaai/chffrplus) or [openpilot](https://github.com/commaai/openpilot). +`unlogger.py` replays data collected with [dashcam](https://github.com/commaai/openpilot/tree/dashcam) or [openpilot](https://github.com/commaai/openpilot). Unlogger with remote data: From 37d6edf4dfb8d28095c0efb366c5b7f671880757 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 7 Jul 2020 14:08:37 -0700 Subject: [PATCH 428/656] Temporarily disable allowing codecov to fail CI (#1839) * add verbose flag to codecov upload * temporarily disable codecov failure resulting in CI failure until bug in codecov is fixed --- .github/workflows/test.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 4f6bb66d02..fc851e62ac 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -125,7 +125,7 @@ jobs: - name: Upload coverage to Codecov run: | docker commit tmppilot tmppilotci - $CI_RUN "cd /tmp/openpilot && bash <(curl -s https://codecov.io/bash) -Z -F unit_tests" + $CI_RUN "cd /tmp/openpilot && bash <(curl -s https://codecov.io/bash) -v -F unit_tests" process_replay: name: process replay @@ -145,7 +145,7 @@ jobs: - name: Upload coverage to Codecov run: | docker commit tmppilot tmppilotci - $CI_RUN "cd /tmp/openpilot && bash <(curl -s https://codecov.io/bash) -Z -F process_replay" + $CI_RUN "cd /tmp/openpilot && bash <(curl -s https://codecov.io/bash) -v -F process_replay" - name: Print diff if: always() run: | @@ -205,4 +205,4 @@ jobs: - name: Upload coverage to Codecov run: | docker commit tmppilot tmppilotci - $CI_RUN "cd /tmp/openpilot && bash <(curl -s https://codecov.io/bash) -Z -F test_car_models" + $CI_RUN "cd /tmp/openpilot && bash <(curl -s https://codecov.io/bash) -v -F test_car_models" From c7156616568ce2fa780db3eafc5f912ab2ead14e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 7 Jul 2020 14:17:09 -0700 Subject: [PATCH 429/656] Build release2 and dashcam in CI (#1834) * start building release2 in CI * build script * bring over changes from test branch * fix build release test * remove references to test branches * ucnomment push * fix duplicate remove * two commits for dashcam * need the key --- .github/workflows/test.yaml | 2 +- Jenkinsfile | 30 ++++++++++++++++++++- release/build_release2.sh | 54 ++++++++++++++++++++++--------------- release/files_common | 5 +++- selfdrive/test/id_rsa | 28 +++++++++++++++++++ selfdrive/test/phone_ci.py | 4 ++- tools/ssh/key/id_rsa | 29 +------------------- 7 files changed, 99 insertions(+), 53 deletions(-) create mode 100644 selfdrive/test/id_rsa mode change 100644 => 120000 tools/ssh/key/id_rsa diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index fc851e62ac..55fc9e6e47 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -39,7 +39,7 @@ jobs: # need these so docker copy won't fail cp Pipfile Pipfile.lock .pylintrc .coveragerc-app .pre-commit-config.yaml $TEST_DIR cd $TEST_DIR - mkdir laika laika_repo tools release + mkdir laika laika_repo tools - name: Build Docker image run: cd $TEST_DIR && eval "$BUILD" - name: Build openpilot and run quick check diff --git a/Jenkinsfile b/Jenkinsfile index 6afac3a236..2029379229 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -7,14 +7,42 @@ pipeline { } environment { COMMA_JWT = credentials('athena-test-jwt') - CI_PUSH = "${env.BRANCH_NAME == 'master' ? 'master-ci' : ''}" } stages { + + stage('Release Build') { + when { + branch 'devel-staging' + } + steps { + lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ + timeout(time: 60, unit: 'MINUTES') { + dir(path: 'selfdrive/test') { + sh 'pip install paramiko' + sh 'python phone_ci.py "cd release && PUSH=1 ./build_release2.sh"' + } + } + } + } + } + stage('On-device Tests') { + when { + not { + anyOf { + branch 'master-ci'; branch 'devel'; branch 'devel-staging'; branch 'release2'; branch 'release2-staging'; branch 'dashcam'; branch 'dashcam-staging' + } + } + } + parallel { stage('Build') { + environment { + CI_PUSH = "${env.BRANCH_NAME == 'master' ? 'master-ci' : ''}" + } + steps { lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ timeout(time: 30, unit: 'MINUTES') { diff --git a/release/build_release2.sh b/release/build_release2.sh index 08f727b1b2..9378bb723b 100755 --- a/release/build_release2.sh +++ b/release/build_release2.sh @@ -8,24 +8,32 @@ export GIT_AUTHOR_EMAIL="user@comma.ai" export GIT_SSH_COMMAND="ssh -i /data/gitkey" -# Create folders -rm -rf /data/openpilot -mkdir -p /data/openpilot -cd /data/openpilot - -# Create git repo -git init -git remote add origin git@github.com:commaai/openpilot.git -git fetch origin devel +# set CLEAN to build outside of CI +if [ ! -z "$CLEAN" ]; then + # Create folders + rm -rf /data/openpilot + mkdir -p /data/openpilot + cd /data/openpilot + + # Create git repo + git init + git remote add origin git@github.com:commaai/openpilot.git + git fetch origin devel-staging +else + cd /data/openpilot + git clean -xdf + git branch -D release2-staging || true +fi + git fetch origin release2-staging git fetch origin dashcam-staging -# Checkout devel -#git checkout origin/devel -#git clean -xdf - # Create release2 with no history -git checkout --orphan release2-staging origin/devel +if [ ! -z "$CLEAN" ]; then + git checkout --orphan release2-staging origin/devel-staging +else + git checkout --orphan release2-staging +fi VERSION=$(cat selfdrive/common/version.h | awk -F\" '{print $2}') git commit -m "openpilot v$VERSION" @@ -55,7 +63,7 @@ find . -name '*.o' -delete find . -name '*.os' -delete find . -name '*.pyc' -delete find . -name '__pycache__' -delete -rm .sconsign.dblite +rm -rf .sconsign.dblite Jenkinsfile release/ # Restore phonelibs git checkout phonelibs/ @@ -70,11 +78,15 @@ git commit --amend -m "openpilot v$VERSION" # Print committed files that are normally gitignored #git status --ignored -# Push to release2-staging -git push -f origin release2-staging +if [ ! -z "$PUSH" ]; then + git remote set-url origin git@github.com:commaai/openpilot.git + + # Push to release2-staging + git push -f origin release2-staging -# Create dashcam release -git rm selfdrive/car/*/carcontroller.py + # Create dashcam release + git rm selfdrive/car/*/carcontroller.py -git commit -m "create dashcam release from release2" -git push -f origin release2-staging:dashcam-staging + git commit -m "create dashcam release from release2" + git push -f origin release2-staging:dashcam-staging +fi diff --git a/release/files_common b/release/files_common index 745026f6c5..5d7a9f28aa 100644 --- a/release/files_common +++ b/release/files_common @@ -58,6 +58,8 @@ common/api/__init__.py models/supercombo.dlc models/dmonitoring_model_q.dlc +release/build_release2.sh + selfdrive/version.py selfdrive/__init__.py @@ -314,10 +316,11 @@ selfdrive/thermald/thermald.py selfdrive/thermald/power_monitoring.py selfdrive/test/__init__.py +selfdrive/test/id_rsa selfdrive/test/helpers.py +selfdrive/test/phone_ci.py selfdrive/test/test_openpilot.py selfdrive/test/test_fingerprints.py -selfdrive/test/test_car_models.py selfdrive/test/test_cpu_usage.py selfdrive/ui/SConscript diff --git a/selfdrive/test/id_rsa b/selfdrive/test/id_rsa new file mode 100644 index 0000000000..3f269afe22 --- /dev/null +++ b/selfdrive/test/id_rsa @@ -0,0 +1,28 @@ +-----BEGIN RSA PRIVATE KEY----- +MIIEvAIBADANBgkqhkiG9w0BAQEFAASCBKYwggSiAgEAAoIBAQC+iXXq30Tq+J5N +Kat3KWHCzcmwZ55nGh6WggAqECa5CasBlM9VeROpVu3beA+5h0MibRgbD4DMtVXB +t6gEvZ8nd04E7eLA9LTZyFDZ7SkSOVj4oXOQsT0GnJmKrASW5KslTWqVzTfo2XCt +Z+004ikLxmyFeBO8NOcErW1pa8gFdQDToH9FrA7kgysic/XVESTOoe7XlzRoe/eZ +acEQ+jtnmFd21A4aEADkk00Ahjr0uKaJiLUAPatxs2icIXWpgYtfqqtaKF23wSt6 +1OTu6cAwXbOWr3m+IUSRUO0IRzEIQS3z1jfd1svgzSgSSwZ1Lhj4AoKxIEAIc8qJ +rO4uymCJAgMBAAECggEBAISFevxHGdoL3Z5xkw6oO5SQKO2GxEeVhRzNgmu/HA+q +x8OryqD6O1CWY4037kft6iWxlwiLOdwna2P25ueVM3LxqdQH2KS4DmlCx+kq6FwC +gv063fQPMhC9LpWimvaQSPEC7VUPjQlo4tPY6sTTYBUOh0A1ihRm/x7juKuQCWix +Cq8C/DVnB1X4mGj+W3nJc5TwVJtgJbbiBrq6PWrhvB/3qmkxHRL7dU2SBb2iNRF1 +LLY30dJx/cD73UDKNHrlrsjk3UJc29Mp4/MladKvUkRqNwlYxSuAtJV0nZ3+iFkL +s3adSTHdJpClQer45R51rFDlVsDz2ZBpb/hRNRoGDuECgYEA6A1EixLq7QYOh3cb +Xhyh3W4kpVvA/FPfKH1OMy3ONOD/Y9Oa+M/wthW1wSoRL2n+uuIW5OAhTIvIEivj +6bAZsTT3twrvOrvYu9rx9aln4p8BhyvdjeW4kS7T8FP5ol6LoOt2sTP3T1LOuJPO +uQvOjlKPKIMh3c3RFNWTnGzMPa0CgYEA0jNiPLxP3A2nrX0keKDI+VHuvOY88gdh +0W5BuLMLovOIDk9aQFIbBbMuW1OTjHKv9NK+Lrw+YbCFqOGf1dU/UN5gSyE8lX/Q +FsUGUqUZx574nJZnOIcy3ONOnQLcvHAQToLFAGUd7PWgP3CtHkt9hEv2koUwL4vo +ikTP1u9Gkc0CgYEA2apoWxPZrY963XLKBxNQecYxNbLFaWq67t3rFnKm9E8BAICi +4zUaE5J1tMVi7Vi9iks9Ml9SnNyZRQJKfQ+kaebHXbkyAaPmfv+26rqHKboA0uxA +nDOZVwXX45zBkp6g1sdHxJx8JLoGEnkC9eyvSi0C//tRLx86OhLErXwYcNkCf1it +VMRKrWYoXJTUNo6tRhvodM88UnnIo3u3CALjhgU4uC1RTMHV4ZCGBwiAOb8GozSl +s5YD1E1iKwEULloHnK6BIh6P5v8q7J6uf/xdqoKMjlWBHgq6/roxKvkSPA1DOZ3l +jTadcgKFnRUmc+JT9p/ZbCxkA/ALFg8++G+0ghECgYA8vG3M/utweLvq4RI7l7U7 +b+i2BajfK2OmzNi/xugfeLjY6k2tfQGRuv6ppTjehtji2uvgDWkgjJUgPfZpir3I +RsVMUiFgloWGHETOy0Qvc5AwtqTJFLTD1Wza2uBilSVIEsg6Y83Gickh+ejOmEsY +6co17RFaAZHwGfCFFjO76Q== +-----END RSA PRIVATE KEY----- diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py index 3d2e6f0672..b002547196 100755 --- a/selfdrive/test/phone_ci.py +++ b/selfdrive/test/phone_ci.py @@ -19,7 +19,7 @@ def run_on_phone(test_cmd): ssh = paramiko.SSHClient() ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy()) - key_file = open(os.path.join(os.path.dirname(__file__), "../../tools/ssh/key/id_rsa")) + key_file = open(os.path.join(os.path.dirname(__file__), "id_rsa")) key = paramiko.RSAKey.from_private_key(key_file) print("SSH to phone at {}".format(eon_ip)) @@ -52,6 +52,8 @@ def run_on_phone(test_cmd): conn.send(f"cd {SOURCE_DIR}\n") conn.send("git reset --hard\n") conn.send("git fetch origin\n") + conn.send("find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \\;\n") + conn.send(f"git reset --hard {commit}\n") conn.send(f"git checkout {commit}\n") conn.send("git clean -xdf\n") conn.send("git submodule update --init\n") diff --git a/tools/ssh/key/id_rsa b/tools/ssh/key/id_rsa deleted file mode 100644 index 3f269afe22..0000000000 --- a/tools/ssh/key/id_rsa +++ /dev/null @@ -1,28 +0,0 @@ ------BEGIN RSA PRIVATE KEY----- -MIIEvAIBADANBgkqhkiG9w0BAQEFAASCBKYwggSiAgEAAoIBAQC+iXXq30Tq+J5N -Kat3KWHCzcmwZ55nGh6WggAqECa5CasBlM9VeROpVu3beA+5h0MibRgbD4DMtVXB -t6gEvZ8nd04E7eLA9LTZyFDZ7SkSOVj4oXOQsT0GnJmKrASW5KslTWqVzTfo2XCt -Z+004ikLxmyFeBO8NOcErW1pa8gFdQDToH9FrA7kgysic/XVESTOoe7XlzRoe/eZ -acEQ+jtnmFd21A4aEADkk00Ahjr0uKaJiLUAPatxs2icIXWpgYtfqqtaKF23wSt6 -1OTu6cAwXbOWr3m+IUSRUO0IRzEIQS3z1jfd1svgzSgSSwZ1Lhj4AoKxIEAIc8qJ -rO4uymCJAgMBAAECggEBAISFevxHGdoL3Z5xkw6oO5SQKO2GxEeVhRzNgmu/HA+q -x8OryqD6O1CWY4037kft6iWxlwiLOdwna2P25ueVM3LxqdQH2KS4DmlCx+kq6FwC -gv063fQPMhC9LpWimvaQSPEC7VUPjQlo4tPY6sTTYBUOh0A1ihRm/x7juKuQCWix -Cq8C/DVnB1X4mGj+W3nJc5TwVJtgJbbiBrq6PWrhvB/3qmkxHRL7dU2SBb2iNRF1 -LLY30dJx/cD73UDKNHrlrsjk3UJc29Mp4/MladKvUkRqNwlYxSuAtJV0nZ3+iFkL -s3adSTHdJpClQer45R51rFDlVsDz2ZBpb/hRNRoGDuECgYEA6A1EixLq7QYOh3cb -Xhyh3W4kpVvA/FPfKH1OMy3ONOD/Y9Oa+M/wthW1wSoRL2n+uuIW5OAhTIvIEivj -6bAZsTT3twrvOrvYu9rx9aln4p8BhyvdjeW4kS7T8FP5ol6LoOt2sTP3T1LOuJPO -uQvOjlKPKIMh3c3RFNWTnGzMPa0CgYEA0jNiPLxP3A2nrX0keKDI+VHuvOY88gdh -0W5BuLMLovOIDk9aQFIbBbMuW1OTjHKv9NK+Lrw+YbCFqOGf1dU/UN5gSyE8lX/Q -FsUGUqUZx574nJZnOIcy3ONOnQLcvHAQToLFAGUd7PWgP3CtHkt9hEv2koUwL4vo -ikTP1u9Gkc0CgYEA2apoWxPZrY963XLKBxNQecYxNbLFaWq67t3rFnKm9E8BAICi -4zUaE5J1tMVi7Vi9iks9Ml9SnNyZRQJKfQ+kaebHXbkyAaPmfv+26rqHKboA0uxA -nDOZVwXX45zBkp6g1sdHxJx8JLoGEnkC9eyvSi0C//tRLx86OhLErXwYcNkCf1it -VMRKrWYoXJTUNo6tRhvodM88UnnIo3u3CALjhgU4uC1RTMHV4ZCGBwiAOb8GozSl -s5YD1E1iKwEULloHnK6BIh6P5v8q7J6uf/xdqoKMjlWBHgq6/roxKvkSPA1DOZ3l -jTadcgKFnRUmc+JT9p/ZbCxkA/ALFg8++G+0ghECgYA8vG3M/utweLvq4RI7l7U7 -b+i2BajfK2OmzNi/xugfeLjY6k2tfQGRuv6ppTjehtji2uvgDWkgjJUgPfZpir3I -RsVMUiFgloWGHETOy0Qvc5AwtqTJFLTD1Wza2uBilSVIEsg6Y83Gickh+ejOmEsY -6co17RFaAZHwGfCFFjO76Q== ------END RSA PRIVATE KEY----- diff --git a/tools/ssh/key/id_rsa b/tools/ssh/key/id_rsa new file mode 120000 index 0000000000..d4e6dd344a --- /dev/null +++ b/tools/ssh/key/id_rsa @@ -0,0 +1 @@ +../../../selfdrive/test/id_rsa \ No newline at end of file From 3983186700b85d5619adc8497de37dcd423b6451 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 7 Jul 2020 14:59:30 -0700 Subject: [PATCH 430/656] openpilot isn't capitalized --- selfdrive/manager.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 3e55841d06..a81f80e99f 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -143,7 +143,7 @@ if not prebuilt: # Show TextWindow error_s = "\n \n".join(["\n".join(textwrap.wrap(e, 65)) for e in errors]) - with TextWindow("Openpilot failed to build\n \n" + error_s) as t: + with TextWindow("openpilot failed to build\n \n" + error_s) as t: t.wait_for_exit() exit(1) From 65d800c4f5844b8167a0ae5421ece265dcc20863 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 7 Jul 2020 16:41:04 -0700 Subject: [PATCH 431/656] use special 'eon-build' device for release build --- Jenkinsfile | 2 +- release/files_common | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 2029379229..ffc0bd44ae 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -16,7 +16,7 @@ pipeline { branch 'devel-staging' } steps { - lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ + lock(resource: "", label: 'eon-build', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ timeout(time: 60, unit: 'MINUTES') { dir(path: 'selfdrive/test') { sh 'pip install paramiko' diff --git a/release/files_common b/release/files_common index 5d7a9f28aa..9c3fd1e260 100644 --- a/release/files_common +++ b/release/files_common @@ -3,6 +3,7 @@ LICENSE launch_chffrplus.sh launch_openpilot.sh +Jenkinsfile SConstruct CONTRIBUTING.md From 9170ffcad442c70ccf8804ed88630d9b1a0260dd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 8 Jul 2020 14:10:05 -0700 Subject: [PATCH 432/656] bump opendbc --- opendbc | 2 +- release/files_common | 3 +-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/opendbc b/opendbc index 55e9af71fc..2265c9c3dc 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 55e9af71fcfc61fa061a1482d3fbb4da00441c35 +Subproject commit 2265c9c3dcff4d58a9cc2cd434a6c704350a4729 diff --git a/release/files_common b/release/files_common index 9c3fd1e260..41ce1f2141 100644 --- a/release/files_common +++ b/release/files_common @@ -476,17 +476,16 @@ opendbc/can/common.cc opendbc/can/common.h opendbc/can/common.pxd opendbc/can/common_dbc.h +opendbc/can/common_pyx_setup.py opendbc/can/dbc.cc opendbc/can/dbc.py opendbc/can/dbc_template.cc opendbc/can/packer.cc opendbc/can/packer.py opendbc/can/packer_pyx.pyx -opendbc/can/packer_pyx_setup.py opendbc/can/parser.cc opendbc/can/parser.py opendbc/can/parser_pyx.pyx -opendbc/can/parser_pyx_setup.py opendbc/can/process_dbc.py opendbc/can/dbc_out/.gitkeep opendbc/can/dbc_out/.gitignore From beb130789fecadd40f4ac76d260bb686cbcf32b0 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Wed, 8 Jul 2020 17:38:51 -0500 Subject: [PATCH 433/656] Added COROLLAH_TSS2 engine f/w (#1845) Requious#7292 DongleID bfe8b7e3fabc420f https://discord.com/channels/469524606043160576/524327905937850394/730546409396240416 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 386c2b52b0..6755075d1e 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -583,6 +583,7 @@ FW_VERSIONS = { b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZR2000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966312Q4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x038966312L7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', b'\x038966312N1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ From 7c4fbb95de0cf1978d5cce0ea9a484f6c41776e9 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 8 Jul 2020 16:04:41 -0700 Subject: [PATCH 434/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 221c458e15..f35491f0c5 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 221c458e15e223304500175981e7894f5c5c0e4f +Subproject commit f35491f0c5bf21d7d8c0cae9b5761fdf64a8d350 From 3ab0b4965663bfae88885c503da0c7de2af37f74 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 8 Jul 2020 19:42:03 -0700 Subject: [PATCH 435/656] Boardd loopback test (#1840) * start boardd loopback test * let's try this in CI * fix jenkinsfile * remove old * rename * check msgs * should be reliable now * send more --- Jenkinsfile | 6 +- selfdrive/boardd/tests/boardd_old.py | 2 +- .../boardd/tests/test_boardd_loopback.py | 90 ++++++++++++------- selfdrive/debug/cpu_usage_stat.py | 2 +- 4 files changed, 65 insertions(+), 35 deletions(-) mode change 100755 => 100644 selfdrive/boardd/tests/test_boardd_loopback.py diff --git a/Jenkinsfile b/Jenkinsfile index ffc0bd44ae..a44b31e593 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -68,13 +68,15 @@ pipeline { } } - stage('Sound Test') { + stage('HW Tests') { steps { lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ timeout(time: 30, unit: 'MINUTES') { dir(path: 'selfdrive/test') { sh 'pip install paramiko' - sh 'python phone_ci.py "SCONS_CACHE=1 scons -j3 cereal/ && cd selfdrive/test && nosetests -s test_sounds.py"' + sh 'python phone_ci.py "SCONS_CACHE=1 scons -j3 cereal/ && \ + nosetests -s selfdrive/test/test_sounds.py && \ + nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"' } } } diff --git a/selfdrive/boardd/tests/boardd_old.py b/selfdrive/boardd/tests/boardd_old.py index 87e579023d..4fd2350bff 100755 --- a/selfdrive/boardd/tests/boardd_old.py +++ b/selfdrive/boardd/tests/boardd_old.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 # pylint: skip-file -# This file is not used by OpenPilot. Only boardd.cc is used. +# This file is not used by openpilot. Only boardd.cc is used. # The python version is slower, but has more options for development. # TODO: merge the extra functionalities of this file (like MOCK) in boardd.c and diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py old mode 100755 new mode 100644 index c3a636e476..cb81a045f7 --- a/selfdrive/boardd/tests/test_boardd_loopback.py +++ b/selfdrive/boardd/tests/test_boardd_loopback.py @@ -1,47 +1,75 @@ #!/usr/bin/env python3 -"""Run boardd with the BOARDD_LOOPBACK envvar before running this test.""" - import os import random import time +from collections import defaultdict +from functools import wraps +import cereal.messaging as messaging +from cereal import car +from common.basedir import PARAMS +from common.params import Params +from panda import Panda from selfdrive.boardd.boardd import can_list_to_can_capnp -from cereal.messaging import drain_sock, pub_sock, sub_sock - -def get_test_string(): - return b"test"+os.urandom(10) +from selfdrive.car import make_can_msg +from selfdrive.test.helpers import with_processes -BUS = 0 -def main(): - rcv = sub_sock('can') # port 8006 - snd = pub_sock('sendcan') # port 8017 - time.sleep(0.3) # wait to bind before send/recv +def reset_panda(fn): + @wraps(fn) + def wrapper(): + p = Panda() + for i in [0, 1, 2, 0xFFFF]: + p.can_clear(i) + p.reset() + p.close() + fn() + return wrapper - for i in range(10): - print("Loop %d" % i) - at = random.randint(1024, 2000) - st = get_test_string()[0:8] - snd.send(can_list_to_can_capnp([[at, 0, st, 0]], msgtype='sendcan').to_bytes()) - time.sleep(0.1) - res = drain_sock(rcv, True) - assert len(res) == 1 +os.environ['STARTED'] = '1' +os.environ['BOARDD_LOOPBACK'] = '1' +os.environ['PARAMS_PATH'] = PARAMS +@reset_panda +@with_processes(['boardd']) +def test_boardd_loopback(): - res = res[0].can - assert len(res) == 2 + # wait for boardd to init + time.sleep(2) - msg0, msg1 = res + # boardd blocks on CarVin and CarParams + cp = car.CarParams.new_message() + cp.safetyModel = car.CarParams.SafetyModel.allOutput + Params().put("CarVin", b"0"*17) + Params().put("CarParams", cp.to_bytes()) - assert msg0.dat == st - assert msg1.dat == st + sendcan = messaging.pub_sock('sendcan') + can = messaging.sub_sock('can', conflate=False, timeout=100) - assert msg0.address == at - assert msg1.address == at + time.sleep(1) - assert msg0.src == 0x80 | BUS - assert msg1.src == BUS + for i in range(1000): + sent_msgs = defaultdict(set) + for _ in range(random.randrange(10)): + to_send = [] + for __ in range(random.randrange(100)): + bus = random.randrange(3) + addr = random.randrange(1, 1<<29) + dat = bytes([random.getrandbits(8) for _ in range(random.randrange(1, 9))]) + sent_msgs[bus].add((addr, dat)) + to_send.append(make_can_msg(addr, dat, bus)) + sendcan.send(can_list_to_can_capnp(to_send, msgtype='sendcan')) - print("Success") + max_recv = 10 + while max_recv > 0 and any(len(sent_msgs[bus]) for bus in range(3)): + recvd = messaging.drain_sock(can, wait_for_one=True) + for msg in recvd: + for m in msg.can: + if m.src >= 128: + k = (m.address, m.dat) + assert k in sent_msgs[m.src-128] + sent_msgs[m.src-128].discard(k) + max_recv -= 1 -if __name__ == "__main__": - main() + # if a set isn't empty, messages got dropped + for bus in range(3): + assert not len(sent_msgs[bus]), f"loop {i}: bus {bus} missing {len(sent_msgs[bus])} messages" diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index 50307c228c..a890af9e67 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -3,7 +3,7 @@ ''' System tools like top/htop can only show current cpu usage values, so I write this script to do statistics jobs. Features: - Use psutil library to sample cpu usage(avergage for all cores) of OpenPilot processes, at a rate of 5 samples/sec. + Use psutil library to sample cpu usage(avergage for all cores) of openpilot processes, at a rate of 5 samples/sec. Do cpu usage statistics periodically, 5 seconds as a cycle. Caculate the average cpu usage within this cycle. Caculate minumium/maximium/accumulated_average cpu usage as long term inspections. From 11fbe85c1436c67bf9e42fdc5f7a6f36f9a837a0 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 9 Jul 2020 12:24:55 +0800 Subject: [PATCH 436/656] remove offroadLayout from sm (#1846) --- selfdrive/ui/ui.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index d863da5af5..cdea7b4538 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -168,7 +168,7 @@ static void ui_init(UIState *s) { pthread_mutex_init(&s->lock, NULL); s->sm = new SubMaster({"model", "controlsState", "uiLayoutState", "liveCalibration", "radarState", "thermal", - "health", "ubloxGnss", "driverState", "dMonitoringState", "offroadLayout" + "health", "ubloxGnss", "driverState", "dMonitoringState" #ifdef SHOW_SPEEDLIMIT , "liveMapData" #endif From 3754ddf9ba3329dce8b5a1c93111a33095439c87 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 9 Jul 2020 12:47:22 +0800 Subject: [PATCH 437/656] remove duplicate calls to visionstream_destroy (#1843) --- selfdrive/loggerd/loggerd.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index cb2e5d4753..d575db9900 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -162,7 +162,6 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { VIPCBuf* buf = visionstream_get(&stream, &extra); if (buf == NULL) { LOG("visionstream get failed"); - visionstream_destroy(&stream); break; } From 977a6ba46b23f0c1f52bbe59579d5c6908294f94 Mon Sep 17 00:00:00 2001 From: Andre Volmensky Date: Thu, 9 Jul 2020 20:50:50 +0900 Subject: [PATCH 438/656] Nissan: Increase steer pressed threshold (#1833) * Increasing steer threshold * Update ref commit --- selfdrive/car/nissan/values.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 0630a8cb94..4271b7f0e5 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -2,7 +2,7 @@ from selfdrive.car import dbc_dict -STEER_THRESHOLD = 1.0 +STEER_THRESHOLD = 1.75 class CAR: XTRAIL = "NISSAN X-TRAIL 2017" diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 25c62148c0..c30eed7619 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -98d3ab8081d04d481adb83980c7852dec8881de5 +520cf8bbbc7e37d3a54ce8d443f52eb232758be5 From eb1aa3d831fd0d7fffd9aacec1accb0a5bdb0304 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 9 Jul 2020 09:25:32 -0700 Subject: [PATCH 439/656] Wunused (#1841) * enable Wunused, first pass * unused stuff in snpe model * these are used on phone * handle sigint and sigterm in modeld * fix phone build * camera qcom * QCOM build works * delete unused camerad vars Co-authored-by: Comma Device --- SConstruct | 1 + selfdrive/boardd/boardd.cc | 13 ++++++++----- selfdrive/camerad/cameras/camera_frame_stream.cc | 6 +----- selfdrive/camerad/cameras/camera_qcom.cc | 10 ---------- selfdrive/camerad/main.cc | 8 ++------ selfdrive/common/clutil.c | 5 ++++- selfdrive/common/ipc.c | 2 -- selfdrive/locationd/paramsd.cc | 3 +-- selfdrive/loggerd/encoder.c | 7 ++++--- selfdrive/loggerd/loggerd.cc | 7 ++++--- selfdrive/modeld/dmonitoringmodeld.cc | 3 +++ selfdrive/modeld/modeld.cc | 5 ++++- selfdrive/modeld/models/commonmodel.c | 1 - selfdrive/modeld/runners/snpemodel.cc | 1 - selfdrive/modeld/runners/snpemodel.h | 2 ++ selfdrive/modeld/thneed/thneed.cc | 2 +- selfdrive/proclogd/proclogd.cc | 5 ++--- selfdrive/sensord/gpsd.cc | 1 - selfdrive/ui/paint.cc | 4 ++++ selfdrive/ui/ui.cc | 2 +- 20 files changed, 42 insertions(+), 46 deletions(-) diff --git a/SConstruct b/SConstruct index 933a540020..168e41bd0f 100644 --- a/SConstruct +++ b/SConstruct @@ -114,6 +114,7 @@ env = Environment( "-g", "-fPIC", "-O2", + "-Wunused", "-Werror", "-Wno-deprecated-register", "-Wno-inconsistent-missing-override", diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 0bdf207b7a..c44af47364 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -61,14 +61,17 @@ bool fake_send = false; bool loopback_can = false; cereal::HealthData::HwType hw_type = cereal::HealthData::HwType::UNKNOWN; bool is_pigeon = false; -const uint32_t NO_IGNITION_CNT_MAX = 2 * 60 * 60 * 30; // turn off charge after 30 hrs -const float VBATT_START_CHARGING = 11.5; -const float VBATT_PAUSE_CHARGING = 11.0; float voltage_f = 12.5; // filtered voltage uint32_t no_ignition_cnt = 0; bool connected_once = false; bool ignition_last = false; +#ifndef __x86_64__ +const uint32_t NO_IGNITION_CNT_MAX = 2 * 60 * 60 * 30; // turn off charge after 30 hrs +const float VBATT_START_CHARGING = 11.5; +const float VBATT_PAUSE_CHARGING = 11.0; +#endif + bool safety_setter_thread_initialized = false; pthread_t safety_setter_thread_handle; @@ -277,7 +280,6 @@ void can_recv(PubMaster &pm) { int err; uint32_t data[RECV_SIZE/4]; int recv; - uint32_t f1, f2; uint64_t start_time = nanos_since_boot(); @@ -455,7 +457,7 @@ void can_health(PubMaster &pm) { uint16_t fan_speed_rpm = 0; pthread_mutex_lock(&usb_lock); - int sz = libusb_control_transfer(dev_handle, 0xc0, 0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm), TIMEOUT); + libusb_control_transfer(dev_handle, 0xc0, 0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm), TIMEOUT); pthread_mutex_unlock(&usb_lock); // Write to rtc once per minute when no ignition present @@ -721,6 +723,7 @@ void *hardware_control_thread(void *crap) { #define pigeon_send(x) _pigeon_send(x, sizeof(x)-1) +void hexdump(unsigned char *d, int l) __attribute__((unused)); void hexdump(unsigned char *d, int l) { for (int i = 0; i < l; i++) { if (i!=0 && i%0x10 == 0) printf("\n"); diff --git a/selfdrive/camerad/cameras/camera_frame_stream.cc b/selfdrive/camerad/cameras/camera_frame_stream.cc index cea6272b4a..45e5013206 100644 --- a/selfdrive/camerad/cameras/camera_frame_stream.cc +++ b/selfdrive/camerad/cameras/camera_frame_stream.cc @@ -32,9 +32,7 @@ void camera_close(CameraState *s) { tbuffer_stop(&s->camera_tb); } -void camera_release_buffer(void *cookie, int buf_idx) { - CameraState *s = static_cast(cookie); -} +void camera_release_buffer(void *cookie, int buf_idx) {} void camera_init(CameraState *s, int camera_id, unsigned int fps) { assert(camera_id < ARRAYSIZE(cameras_supported)); @@ -48,7 +46,6 @@ void camera_init(CameraState *s, int camera_id, unsigned int fps) { } void run_frame_stream(DualCameraState *s) { - int err; SubMaster sm({"frame"}); CameraState *const rear_camera = &s->rear; @@ -121,7 +118,6 @@ void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_front) { assert(camera_bufs_rear); assert(camera_bufs_front); - int err; // LOG("*** open front ***"); camera_open(&s->front, camera_bufs_front, false); diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index 1a6d0ae2c9..79e6c8f097 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -163,16 +163,6 @@ static int imx298_apply_exposure(CameraState *s, int gain, int integ_lines, int //printf("%5d/%5d %5d %f\n", s->cur_integ_lines, s->cur_frame_length, analog_gain, s->digital_gain); - int digital_gain = 0x100; - - float white_balance[] = {0.4609375, 1.0, 0.546875}; - //float white_balance[] = {1.0, 1.0, 1.0}; - - int digital_gain_gr = digital_gain / white_balance[1]; - int digital_gain_gb = digital_gain / white_balance[1]; - int digital_gain_r = digital_gain / white_balance[0]; - int digital_gain_b = digital_gain / white_balance[2]; - struct msm_camera_i2c_reg_array reg_array[] = { // REG_HOLD {0x104,0x1,0}, diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index d1e659b465..4e1ce307c8 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -171,7 +171,7 @@ void* frontview_thread(void *arg) { int rgb_idx = ui_idx; FrameMetadata frame_data = s->cameras.front.camera_bufs_metadata[buf_idx]; - double t1 = millis_since_boot(); + //double t1 = millis_since_boot(); cl_event debayer_event; if (s->cameras.front.ci.bayer) { @@ -329,8 +329,7 @@ void* frontview_thread(void *arg) { tbuffer_dispatch(&s->ui_front_tb, ui_idx); - double t2 = millis_since_boot(); - + //double t2 = millis_since_boot(); //LOGD("front process: %.2fms", t2-t1); } @@ -514,8 +513,6 @@ void* processing_thread(void *arg) { s->yuv_metas[yuv_idx] = frame_data; uint8_t* yuv_ptr_y = s->yuv_bufs[yuv_idx].y; - uint8_t* yuv_ptr_u = s->yuv_bufs[yuv_idx].u; - uint8_t* yuv_ptr_v = s->yuv_bufs[yuv_idx].v; cl_mem yuv_cl = s->yuv_cl[yuv_idx]; rgb_to_yuv_queue(&s->rgb_to_yuv_state, q, s->rgb_bufs_cl[rgb_idx], yuv_cl); visionbuf_sync(&s->yuv_ion[yuv_idx], VISIONBUF_SYNC_FROM_DEVICE); @@ -1252,7 +1249,6 @@ void party(VisionState *s) { } int main(int argc, char *argv[]) { - int err; set_realtime_priority(51); zsys_handler_set(NULL); diff --git a/selfdrive/common/clutil.c b/selfdrive/common/clutil.c index 22c9b45de1..9a80c9067b 100644 --- a/selfdrive/common/clutil.c +++ b/selfdrive/common/clutil.c @@ -175,6 +175,7 @@ cl_program cl_cached_program_from_hash(cl_context ctx, cl_device_id device_id, u return prg; } +#ifndef CLU_NO_CACHE static uint8_t* get_program_binary(cl_program prg, size_t *out_size) { int err; @@ -199,6 +200,7 @@ static uint8_t* get_program_binary(cl_program prg, size_t *out_size) { *out_size = binary_size; return binary_buf; } +#endif cl_program cl_cached_program_from_string(cl_context ctx, cl_device_id device_id, const char* src, const char* args, @@ -265,13 +267,14 @@ cl_program cl_cached_program_from_file(cl_context ctx, cl_device_id device_id, c return ret; } +#ifndef CLU_NO_CACHE static void add_index(uint64_t index_hash, uint64_t src_hash) { FILE *f = fopen("/tmp/clcache/index.cli", "a"); assert(f); fprintf(f, "%016" PRIx64 " %016" PRIx64 "\n", index_hash, src_hash); fclose(f); } - +#endif cl_program cl_program_from_index(cl_context ctx, cl_device_id device_id, uint64_t index_hash) { int err; diff --git a/selfdrive/common/ipc.c b/selfdrive/common/ipc.c index 28a30d1a10..a5993598d2 100644 --- a/selfdrive/common/ipc.c +++ b/selfdrive/common/ipc.c @@ -60,8 +60,6 @@ int ipc_bind(const char* socket_path) { int ipc_sendrecv_with_fds(bool send, int fd, void *buf, size_t buf_size, int* fds, int num_fds, int *out_num_fds) { - int err; - char control_buf[CMSG_SPACE(sizeof(int) * num_fds)]; memset(control_buf, 0, CMSG_SPACE(sizeof(int) * num_fds)); diff --git a/selfdrive/locationd/paramsd.cc b/selfdrive/locationd/paramsd.cc index bb45ea2b4b..aee957bc81 100644 --- a/selfdrive/locationd/paramsd.cc +++ b/selfdrive/locationd/paramsd.cc @@ -43,7 +43,7 @@ int main(int argc, char *argv[]) { // make copy due to alignment issues auto amsg = kj::heapArray((params.size() / sizeof(capnp::word)) + 1); memcpy(amsg.begin(), params.data(), params.size()); - + capnp::FlatArrayMessageReader cmsg(amsg); cereal::CarParams::Reader car_params = cmsg.getRoot(); @@ -53,7 +53,6 @@ int main(int argc, char *argv[]) { double sR = car_params.getSteerRatio(); double x = 1.0; double ao = 0.0; - double posenet_invalid_count = 0; std::vector live_params = read_db_bytes("LiveParameters"); if (live_params.size() > 0){ std::string err; diff --git a/selfdrive/loggerd/encoder.c b/selfdrive/loggerd/encoder.c index 3b9beb4d61..297f65cf85 100644 --- a/selfdrive/loggerd/encoder.c +++ b/selfdrive/loggerd/encoder.c @@ -96,6 +96,7 @@ static OMX_CALLBACKTYPE omx_callbacks = { #define PORT_INDEX_IN 0 #define PORT_INDEX_OUT 1 +static const char* omx_color_fomat_name(uint32_t format) __attribute__((unused)); static const char* omx_color_fomat_name(uint32_t format) { switch (format) { case OMX_COLOR_FormatUnused: return "OMX_COLOR_FormatUnused"; @@ -397,9 +398,9 @@ static void handle_out_buf(EncoderState *s, OMX_BUFFERHEADERTYPE *out_buf) { } if (s->stream_sock_raw) { - uint64_t current_time = nanos_since_boot(); - uint64_t diff = current_time - out_buf->nTimeStamp*1000LL; - double msdiff = (double) diff / 1000000.0; + //uint64_t current_time = nanos_since_boot(); + //uint64_t diff = current_time - out_buf->nTimeStamp*1000LL; + //double msdiff = (double) diff / 1000000.0; // printf("encoded latency to tsEof: %f\n", msdiff); zmq_send(s->stream_sock_raw, &out_buf->nTimeStamp, sizeof(out_buf->nTimeStamp), ZMQ_SNDMORE); zmq_send(s->stream_sock_raw, buf_data, out_buf->nFilledLen, 0); diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index d575db9900..9cc3043a70 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -61,6 +61,7 @@ namespace { +double randrange(double a, double b) __attribute__((unused)); double randrange(double a, double b) { static std::mt19937 gen(millis_since_boot()); @@ -165,9 +166,9 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { break; } - uint64_t current_time = nanos_since_boot(); - uint64_t diff = current_time - extra.timestamp_eof; - double msdiff = (double) diff / 1000000.0; + //uint64_t current_time = nanos_since_boot(); + //uint64_t diff = current_time - extra.timestamp_eof; + //double msdiff = (double) diff / 1000000.0; // printf("logger latency to tsEof: %f\n", msdiff); uint8_t *y = (uint8_t*)buf->addr; diff --git a/selfdrive/modeld/dmonitoringmodeld.cc b/selfdrive/modeld/dmonitoringmodeld.cc index e39fba1689..140b567ad3 100644 --- a/selfdrive/modeld/dmonitoringmodeld.cc +++ b/selfdrive/modeld/dmonitoringmodeld.cc @@ -25,6 +25,9 @@ int main(int argc, char **argv) { int err; set_realtime_priority(51); + signal(SIGINT, (sighandler_t)set_do_exit); + signal(SIGTERM, (sighandler_t)set_do_exit); + // messaging SubMaster sm({"dMonitoringState"}); PubMaster pm({"driverState"}); diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 691d3f32e8..5cf8ae0881 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -1,5 +1,6 @@ #include #include +#include #include #include "common/visionbuf.h" @@ -20,7 +21,6 @@ mat3 cur_transform; pthread_mutex_t transform_lock; void* live_thread(void *arg) { - int err; set_thread_name("live"); SubMaster sm({"liveCalibration"}); @@ -75,6 +75,9 @@ int main(int argc, char **argv) { int err; set_realtime_priority(51); + signal(SIGINT, (sighandler_t)set_do_exit); + signal(SIGTERM, (sighandler_t)set_do_exit); + // start calibration thread pthread_t live_thread_handle; err = pthread_create(&live_thread_handle, NULL, live_thread, NULL); diff --git a/selfdrive/modeld/models/commonmodel.c b/selfdrive/modeld/models/commonmodel.c index 1b93718c88..93fceb3ad5 100644 --- a/selfdrive/modeld/models/commonmodel.c +++ b/selfdrive/modeld/models/commonmodel.c @@ -36,7 +36,6 @@ float *frame_prepare(ModelFrame* frame, cl_command_queue q, cl_mem yuv_cl, int width, int height, mat3 transform) { int err; - int i = 0; transform_queue(&frame->transform, q, yuv_cl, width, height, frame->transformed_y_cl, frame->transformed_u_cl, frame->transformed_v_cl, diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 19740f9a93..5a92d94bf4 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -6,7 +6,6 @@ #include "snpemodel.h" void PrintErrorStringAndExit() { - const char* const errStr = zdl::DlSystem::getLastErrorString(); std::cerr << zdl::DlSystem::getLastErrorString() << std::endl; std::exit(EXIT_FAILURE); } diff --git a/selfdrive/modeld/runners/snpemodel.h b/selfdrive/modeld/runners/snpemodel.h index 11aa14ccb5..f7f217cdc6 100644 --- a/selfdrive/modeld/runners/snpemodel.h +++ b/selfdrive/modeld/runners/snpemodel.h @@ -38,7 +38,9 @@ private: Thneed *thneed = NULL; #endif +#ifdef QCOM zdl::DlSystem::Runtime_t Runtime; +#endif // snpe model stuff std::unique_ptr snpe; diff --git a/selfdrive/modeld/thneed/thneed.cc b/selfdrive/modeld/thneed/thneed.cc index 9a593d9e04..11f10cfeb5 100644 --- a/selfdrive/modeld/thneed/thneed.cc +++ b/selfdrive/modeld/thneed/thneed.cc @@ -99,7 +99,7 @@ GPUMalloc::GPUMalloc(int size, int fd) { memset(&alloc, 0, sizeof(alloc)); alloc.size = size; alloc.flags = 0x10000a00; - int ret = ioctl(fd, IOCTL_KGSL_GPUOBJ_ALLOC, &alloc); + ioctl(fd, IOCTL_KGSL_GPUOBJ_ALLOC, &alloc); void *addr = mmap64(NULL, alloc.mmapsize, 0x3, 0x1, fd, alloc.id*0x1000); assert(addr != MAP_FAILED); diff --git a/selfdrive/proclogd/proclogd.cc b/selfdrive/proclogd/proclogd.cc index 7c77c12ceb..c8e5f65a50 100644 --- a/selfdrive/proclogd/proclogd.cc +++ b/selfdrive/proclogd/proclogd.cc @@ -29,7 +29,6 @@ struct ProcCache { } int main() { - int err; PubMaster publisher({"procLog"}); double jiffy = sysconf(_SC_CLK_TCK); @@ -61,8 +60,8 @@ int main() { unsigned long utime, ntime, stime, itime; unsigned long iowtime, irqtime, sirqtime; - int count = sscanf(stat_line.data(), "cpu%d %lu %lu %lu %lu %lu %lu %lu", - &id, &utime, &ntime, &stime, &itime, &iowtime, &irqtime, &sirqtime); + sscanf(stat_line.data(), "cpu%d %lu %lu %lu %lu %lu %lu %lu", + &id, &utime, &ntime, &stime, &itime, &iowtime, &irqtime, &sirqtime); auto ltimeo = orphanage.newOrphan(); auto ltime = ltimeo.get(); diff --git a/selfdrive/sensord/gpsd.cc b/selfdrive/sensord/gpsd.cc index 7fdad45c6b..4bf71faf61 100644 --- a/selfdrive/sensord/gpsd.cc +++ b/selfdrive/sensord/gpsd.cc @@ -155,7 +155,6 @@ void gps_destroy() { } int main() { - int err = 0; setpriority(PRIO_PROCESS, 0, -13); signal(SIGINT, (sighandler_t)set_do_exit); diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index b577d78be8..8c17b4cf98 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -437,6 +437,7 @@ static void ui_draw_vision_maxspeed(UIState *s) { } } +#ifdef SHOW_SPEEDLIMIT static void ui_draw_vision_speedlimit(UIState *s) { char speedlim_str[32]; float speedlimit = s->scene.speedlimit; @@ -493,6 +494,7 @@ static void ui_draw_vision_speedlimit(UIState *s) { ui_draw_text(s->vg, text_x, viz_speedlim_y + (is_speedlim_valid ? 170 : 165), "N/A", 42*2.5, color, s->font_sans_semibold); } } +#endif static void ui_draw_vision_speed(UIState *s) { const UIScene *scene = &s->scene; @@ -542,12 +544,14 @@ static void ui_draw_vision_event(UIState *s) { } } +#ifdef SHOW_SPEEDLIMIT static void ui_draw_vision_map(UIState *s) { const int map_size = 96; const int map_x = (s->scene.ui_viz_rx + (map_size * 3) + (bdr_s * 3)); const int map_y = (footer_y + ((footer_h - map_size) / 2)); ui_draw_circle_image(s->vg, map_x, map_y, map_size, s->img_map, s->scene.map_valid); } +#endif static void ui_draw_vision_face(UIState *s) { const int face_size = 96; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index cdea7b4538..4bd1fa20dc 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -664,7 +664,7 @@ static void* light_sensor_thread(void *args) { // need to do this struct sensor_t const* list; - int count = module->get_sensors_list(module, &list); + module->get_sensors_list(module, &list); int SENSOR_LIGHT = 7; From 63ab7930de371f3216adf75292f55e61a457e35a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 9 Jul 2020 10:43:19 -0700 Subject: [PATCH 440/656] increase Jenkins timeout, clean builds take a long time --- Jenkinsfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index a44b31e593..c362512038 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -45,7 +45,7 @@ pipeline { steps { lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ - timeout(time: 30, unit: 'MINUTES') { + timeout(time: 60, unit: 'MINUTES') { dir(path: 'selfdrive/test') { sh 'pip install paramiko' sh 'python phone_ci.py "cd release && ./build_devel.sh"' @@ -71,7 +71,7 @@ pipeline { stage('HW Tests') { steps { lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ - timeout(time: 30, unit: 'MINUTES') { + timeout(time: 60, unit: 'MINUTES') { dir(path: 'selfdrive/test') { sh 'pip install paramiko' sh 'python phone_ci.py "SCONS_CACHE=1 scons -j3 cereal/ && \ From 03e824a4b558daa15191408e88b73fee7ab1792f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 9 Jul 2020 17:02:21 -0700 Subject: [PATCH 441/656] Alert when modeld is lagging by more than a frame (#1823) * alert when modeld is lagging by more than 1 frame * log frameAge in modelData * set posenet valid * compute frame_age once --- cereal | 2 +- selfdrive/controls/controlsd.py | 2 ++ selfdrive/controls/lib/events.py | 7 +++++-- selfdrive/modeld/modeld.cc | 4 ++-- selfdrive/modeld/models/driving.cc | 16 +++++++++++----- selfdrive/modeld/models/driving.h | 6 +++--- 6 files changed, 24 insertions(+), 13 deletions(-) diff --git a/cereal b/cereal index f35491f0c5..80bbbd4bf7 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit f35491f0c5bf21d7d8c0cae9b5761fdf64a8d350 +Subproject commit 80bbbd4bf70698a3e7b7eaa1e463753c3db2ab5f diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index f64acae101..349a6cb840 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -227,6 +227,8 @@ class Controls: self.events.add(EventName.relayMalfunction) if self.sm['plan'].fcw: self.events.add(EventName.fcw) + if self.sm['model'].frameAge > 1: + self.events.add(EventName.modeldLagging) # Only allow engagement with brake pressed when stopped behind another stopped car if CS.brakePressed and self.sm['plan'].vTargetFuture >= STARTING_TARGET_SPEED \ diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 6f184bbb36..f576cf4d2b 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -204,8 +204,6 @@ def wrong_car_mode_alert(CP, sm, metric): EVENTS = { # ********** events with no alerts ********** - EventName.modeldLagging: {}, - # ********** events only containing alerts displayed in all states ********** EventName.debugAlert: { @@ -651,6 +649,11 @@ EVENTS = { ET.NO_ENTRY : NoEntryAlert("Radar Error: Restart the Car"), }, + EventName.modeldLagging: { + ET.SOFT_DISABLE: SoftDisableAlert("Driving model lagging"), + ET.NO_ENTRY : NoEntryAlert("Driving model lagging"), + }, + EventName.lowMemory: { ET.SOFT_DISABLE: SoftDisableAlert("Low Memory: Reboot Your Device"), ET.PERMANENT: Alert( diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 5cf8ae0881..e77a9cacfa 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -217,8 +217,8 @@ int main(int argc, char **argv) { model_transform, NULL, vec_desire); mt2 = millis_since_boot(); - model_publish(pm, extra.frame_id, frame_id, model_buf, extra.timestamp_eof); - posenet_publish(pm, extra.frame_id, frame_id, model_buf, extra.timestamp_eof); + model_publish(pm, extra.frame_id, frame_id, sm.allAliveAndValid(), model_buf, extra.timestamp_eof); + posenet_publish(pm, extra.frame_id, frame_id, sm.allAliveAndValid(), model_buf, extra.timestamp_eof); LOGD("model process: %.2fms, from last %.2fms, vipc_frame_id %zu, frame_id, %zu", mt2-mt1, mt1-last, extra.frame_id, frame_id); last = mt1; diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 7156b09733..8b17dd74f7 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -245,15 +245,18 @@ void fill_longi(cereal::ModelData::LongitudinalData::Builder longi, const float longi.setAccelerations(accel); } -void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, +void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, bool sm_alive_valid, const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { // make msg capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); event.setLogMonoTime(nanos_since_boot()); + uint32_t frame_age = (frame_id > vipc_frame_id) ? (frame_id - vipc_frame_id) : 0; + auto framed = event.initModel(); framed.setFrameId(vipc_frame_id); + framed.setFrameAge(frame_age); framed.setTimestampEof(timestamp_eof); auto lpath = framed.initPath(); @@ -290,13 +293,13 @@ void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, auto meta = framed.initMeta(); fill_meta(meta, net_outputs.meta); - event.setValid(frame_id < vipc_frame_id + MAX_FRAME_AGE); + event.setValid((frame_age < MAX_FRAME_AGE) && sm_alive_valid); pm.send("model", msg); } -void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, - const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { +void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, bool sm_alive_valid, + const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); event.setLogMonoTime(nanos_since_boot()); @@ -324,9 +327,12 @@ void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, kj::ArrayPtr rot_std_vs(&rot_std_arr[0], 3); posenetd.setRotStd(rot_std_vs); + posenetd.setTimestampEof(timestamp_eof); posenetd.setFrameId(vipc_frame_id); - event.setValid(frame_id < vipc_frame_id + MAX_FRAME_AGE); + + uint32_t frame_age = (frame_id > vipc_frame_id) ? (frame_id - vipc_frame_id) : 0; + event.setValid((frame_age < MAX_FRAME_AGE) && sm_alive_valid); pm.send("cameraOdometry", msg); } diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index 29d7a68f6a..dab8fc0faa 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -73,8 +73,8 @@ ModelDataRaw model_eval_frame(ModelState* s, cl_command_queue q, void model_free(ModelState* s); void poly_fit(float *in_pts, float *in_stds, float *out); -void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, - const ModelDataRaw &data, uint64_t timestamp_eof); -void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, +void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, bool sm_alive_valid, const ModelDataRaw &data, uint64_t timestamp_eof); +void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, bool sm_alive_valid, + const ModelDataRaw &data, uint64_t timestamp_eof); #endif From 7cfdeb1a3246267598ec50eed092ad02802eed3b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 9 Jul 2020 17:52:48 -0700 Subject: [PATCH 442/656] Hyundai: use SCC12 for stock ADAS signals on cars that don't have FCA11 (#1849) * some hyundai use SCC12 for AEB/FCW * add other cars from fingerprints * comment --- selfdrive/car/hyundai/carstate.py | 28 ++++++++++++++++++++-------- selfdrive/car/hyundai/values.py | 10 +++++++--- 2 files changed, 27 insertions(+), 11 deletions(-) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 74b2e327df..7865e4c956 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -113,9 +113,13 @@ class CarState(CarStateBase): else: ret.gearShifter = GearShifter.unknown - ret.stockAeb = cp.vl["FCA11"]['FCA_CmdAct'] != 0 - ret.stockFcw = cp.vl["FCA11"]['CF_VSM_Warn'] == 2 - + if self.CP.carFingerprint in FEATURES["use_fca"]: + ret.stockAeb = cp.vl["FCA11"]['FCA_CmdAct'] != 0 + ret.stockFcw = cp.vl["FCA11"]['CF_VSM_Warn'] == 2 + else: + ret.stockAeb = cp.vl["SCC12"]['AEB_CmdAct'] != 0 + ret.stockFcw = cp.vl["SCC12"]['CF_VSM_Warn'] == 2 + ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0 ret.rightBlindspot = cp.vl["LCA11"]["CF_Lca_IndRight"] != 0 @@ -174,7 +178,7 @@ class CarState(CarStateBase): ("ESC_Off_Step", "TCS15", 0), ("CF_Lvr_GearInf", "LVR11", 0), # Transmission Gear (0 = N or P, 1-8 = Fwd, 14 = Rev) - + ("CF_Lca_IndLeft", "LCA11", 0), ("CF_Lca_IndRight", "LCA11", 0), @@ -187,9 +191,6 @@ class CarState(CarStateBase): ("SAS_Angle", "SAS11", 0), ("SAS_Speed", "SAS11", 0), - ("FCA_CmdAct", "FCA11", 0), - ("CF_VSM_Warn", "FCA11", 0), - ("MainMode_ACC", "SCC11", 0), ("VSetDis", "SCC11", 0), ("SCCInfoDisplay", "SCC11", 0), @@ -210,7 +211,6 @@ class CarState(CarStateBase): ("SAS11", 100), ("SCC11", 50), ("SCC12", 50), - ("FCA11", 50), ("LCA11", 50), ] @@ -259,6 +259,18 @@ class CarState(CarStateBase): ("LVR12", 100) ] + if CP.carFingerprint in FEATURES["use_fca"]: + signals += [ + ("FCA_CmdAct", "FCA11", 0), + ("CF_VSM_Warn", "FCA11", 0), + ] + checks += [("FCA11", 50)] + else: + signals += [ + ("AEB_CmdAct", "SCC12", 0), + ("CF_VSM_Warn", "SCC12", 0), + ] + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) @staticmethod diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 09c70f008c..1e564f377c 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -206,9 +206,13 @@ CHECKSUM = { } FEATURES = { - "use_cluster_gears": [CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30], # Use Cluster for Gear Selection, rather than Transmission - "use_tcu_gears": [CAR.KIA_OPTIMA, CAR.SONATA_2019], # Use TCU Message for Gear Selection - "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ], # Use TCU Message for Gear Selection + # which message has the gear + "use_cluster_gears": [CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30], + "use_tcu_gears": [CAR.KIA_OPTIMA, CAR.SONATA_2019], + "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ], + + # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 + "use_fca": [CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE], } EV_HYBRID = [CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV] From 8bf198ba7de7f50274cb3b1ebca938031b71ced1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 9 Jul 2020 18:26:06 -0700 Subject: [PATCH 443/656] only check BSM on sonata for now, not equipped on all HKG --- selfdrive/car/hyundai/carstate.py | 16 ++++++++++------ selfdrive/car/hyundai/values.py | 2 ++ 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 7865e4c956..1e4ad4018e 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -120,8 +120,9 @@ class CarState(CarStateBase): ret.stockAeb = cp.vl["SCC12"]['AEB_CmdAct'] != 0 ret.stockFcw = cp.vl["SCC12"]['CF_VSM_Warn'] == 2 - ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0 - ret.rightBlindspot = cp.vl["LCA11"]["CF_Lca_IndRight"] != 0 + if self.CP.carFingerprint in FEATURES["use_bsm"]: + ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0 + ret.rightBlindspot = cp.vl["LCA11"]["CF_Lca_IndRight"] != 0 # save the entire LKAS11 and CLU11 self.lkas11 = cp_cam.vl["LKAS11"] @@ -179,9 +180,6 @@ class CarState(CarStateBase): ("CF_Lvr_GearInf", "LVR11", 0), # Transmission Gear (0 = N or P, 1-8 = Fwd, 14 = Rev) - ("CF_Lca_IndLeft", "LCA11", 0), - ("CF_Lca_IndRight", "LCA11", 0), - ("CR_Mdps_StrColTq", "MDPS12", 0), ("CF_Mdps_ToiActive", "MDPS12", 0), ("CF_Mdps_ToiUnavail", "MDPS12", 0), @@ -211,9 +209,15 @@ class CarState(CarStateBase): ("SAS11", 100), ("SCC11", 50), ("SCC12", 50), - ("LCA11", 50), ] + if CP.carFingerprint in FEATURES["use_bsm"]: + signals += [ + ("CF_Lca_IndLeft", "LCA11", 0), + ("CF_Lca_IndRight", "LCA11", 0), + ] + checks += [("LCA11", 50)] + if CP.carFingerprint in EV_HYBRID: signals += [ ("Accel_Pedal_Pos", "E_EMS11", 0), diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 1e564f377c..e19db60c89 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -213,6 +213,8 @@ FEATURES = { # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 "use_fca": [CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE], + + "use_bsm": [CAR.SONATA], } EV_HYBRID = [CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV] From c6caf061c7a2ad8b6b360c0c7698719fbb2dd628 Mon Sep 17 00:00:00 2001 From: Scott Adair Date: Thu, 9 Jul 2020 21:38:27 -0400 Subject: [PATCH 444/656] Add BSM Support for the Palisade (#1851) Us Palisade drivers love BSM as much as the Sonata drivers, maybe more because our blind spots are bigger... Anyway, BSM is standard across all trims so it's safe to enable support --- selfdrive/car/hyundai/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index e19db60c89..5f826f6668 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -214,7 +214,7 @@ FEATURES = { # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 "use_fca": [CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE], - "use_bsm": [CAR.SONATA], + "use_bsm": [CAR.SONATA, CAR.PALISADE], } EV_HYBRID = [CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV] From d2784f0ff07c95046c5a17a5b903877030b80e75 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 9 Jul 2020 18:42:05 -0700 Subject: [PATCH 445/656] all genesis have BSM standard --- selfdrive/car/hyundai/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 5f826f6668..b4784196a2 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -214,7 +214,7 @@ FEATURES = { # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 "use_fca": [CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE], - "use_bsm": [CAR.SONATA, CAR.PALISADE], + "use_bsm": [CAR.SONATA, CAR.PALISADE, CAR.HYUNDAI_GENESIS, CAR.GENESIS_G80, CAR.GENESIS_G90], } EV_HYBRID = [CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV] From 587bdf593799f9c6612c26703ffcfcd031f98f92 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 9 Jul 2020 20:37:28 -0700 Subject: [PATCH 446/656] only check frame age for model validity --- selfdrive/modeld/modeld.cc | 4 ++-- selfdrive/modeld/models/driving.cc | 6 +++--- selfdrive/modeld/models/driving.h | 4 ++-- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index e77a9cacfa..369c446141 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -217,8 +217,8 @@ int main(int argc, char **argv) { model_transform, NULL, vec_desire); mt2 = millis_since_boot(); - model_publish(pm, extra.frame_id, frame_id, sm.allAliveAndValid(), model_buf, extra.timestamp_eof); - posenet_publish(pm, extra.frame_id, frame_id, sm.allAliveAndValid(), model_buf, extra.timestamp_eof); + model_publish(pm, extra.frame_id, frame_id, model_buf, extra.timestamp_eof); + posenet_publish(pm, extra.frame_id, frame_id, model_buf, extra.timestamp_eof); LOGD("model process: %.2fms, from last %.2fms, vipc_frame_id %zu, frame_id, %zu", mt2-mt1, mt1-last, extra.frame_id, frame_id); last = mt1; diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 8b17dd74f7..9e0d1d3feb 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -245,7 +245,7 @@ void fill_longi(cereal::ModelData::LongitudinalData::Builder longi, const float longi.setAccelerations(accel); } -void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, bool sm_alive_valid, +void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { // make msg capnp::MallocMessageBuilder msg; @@ -293,12 +293,12 @@ void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, boo auto meta = framed.initMeta(); fill_meta(meta, net_outputs.meta); - event.setValid((frame_age < MAX_FRAME_AGE) && sm_alive_valid); + event.setValid(frame_age < MAX_FRAME_AGE); pm.send("model", msg); } -void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, bool sm_alive_valid, +void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index dab8fc0faa..97941db198 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -73,8 +73,8 @@ ModelDataRaw model_eval_frame(ModelState* s, cl_command_queue q, void model_free(ModelState* s); void poly_fit(float *in_pts, float *in_stds, float *out); -void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, bool sm_alive_valid, +void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, const ModelDataRaw &data, uint64_t timestamp_eof); -void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, bool sm_alive_valid, +void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, const ModelDataRaw &data, uint64_t timestamp_eof); #endif From c8f3ff8913ce7e18d755ae8015a27af3365029e9 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 9 Jul 2020 20:55:56 -0700 Subject: [PATCH 447/656] only check frame age for posenet too --- selfdrive/modeld/models/driving.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 9e0d1d3feb..9ac7604195 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -332,7 +332,7 @@ void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, posenetd.setFrameId(vipc_frame_id); uint32_t frame_age = (frame_id > vipc_frame_id) ? (frame_id - vipc_frame_id) : 0; - event.setValid((frame_age < MAX_FRAME_AGE) && sm_alive_valid); + event.setValid(frame_age < MAX_FRAME_AGE); pm.send("cameraOdometry", msg); } From c43df81214d34d90b318defbd7f43e240b0c8f45 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Fri, 10 Jul 2020 04:41:26 -0700 Subject: [PATCH 448/656] Make updated more resilient (#1853) * Add sleep at updated startup * Mitigate symlink-related FS damage --- launch_chffrplus.sh | 7 +++++-- selfdrive/updated.py | 5 +++++ 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 3ef93eb4ef..ae1660411b 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -41,9 +41,12 @@ function launch { mv $BASEDIR /data/safe_staging/old_openpilot mv "${STAGING_ROOT}/finalized" $BASEDIR + cd $BASEDIR - # The mv changed our working directory to /data/safe_staging/old_openpilot - cd "${BASEDIR}" + # Partial mitigation for symlink-related filesystem corruption + # Ensure all files match the repo versions after update + git reset --hard + git submodule foreach --recursive git reset --hard echo "Restarting launch script ${LAUNCHER_LOCATION}" exec "${LAUNCHER_LOCATION}" diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 7c7db0f323..6194bda9d2 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -32,6 +32,7 @@ import signal from pathlib import Path import fcntl import threading +import time from cffi import FFI from common.basedir import BASEDIR @@ -336,6 +337,10 @@ def main(): except IOError: raise RuntimeError("couldn't get overlay lock; is another updated running?") + # Wait a short time before our first update attempt + # Avoids race with IsOffroad not being set, reduces manager startup load + time.sleep(30) + while True: update_failed_count += 1 time_wrong = datetime.datetime.utcnow().year < 2019 From d0b7760731f1e310c7770dafee215ed2dee0d92d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 10 Jul 2020 11:48:55 -0700 Subject: [PATCH 449/656] promote sonata --- README.md | 3 ++- RELEASES.md | 3 ++- selfdrive/car/hyundai/interface.py | 4 ++-- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 0d847b25f0..2f8adbcc8a 100644 --- a/README.md +++ b/README.md @@ -82,6 +82,7 @@ Supported Cars | Honda | Pilot 2016-18 | Honda Sensing | openpilot | 25mph1 | 12mph | | Honda | Pilot 2019 | All | openpilot | 25mph1 | 12mph | | Honda | Ridgeline 2017-20 | Honda Sensing | openpilot | 25mph1 | 12mph | +| Hyundai | Sonata 2020 | All | Stock | 0mph | 0mph | | Lexus | CT Hybrid 2017-18 | All | Stock3| 0mph | 0mph | | Lexus | ES 2019 | All | openpilot | 0mph | 0mph | | Lexus | ES Hybrid 2019 | All | openpilot | 0mph | 0mph | @@ -147,7 +148,7 @@ Community Maintained Cars and Features | Hyundai | Kona EV 2019 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Palisade 2020 | All | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | -| Hyundai | Sonata 2019-20 | All | Stock | 0mph | 0mph | +| Hyundai | Sonata 2019 | All | Stock | 0mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019 | Adaptive Cruise | Stock | 0mph | 39mph | | Kia | Forte 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | diff --git a/RELEASES.md b/RELEASES.md index f575eb88ff..b0756eac31 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -5,9 +5,10 @@ Version 0.7.7 (2020-xx-xx) * Improved thermal management on comma two * Improved autofocus for road-facing camera * Improved noise performance for driver-facing camera - * Fix GM ignition detection * Block lane change start using blindspot monitor on select Toyota, Hyundai, and Subaru + * Fix GM ignition detection * Code cleanup and smaller release sizes + * Hyundai Sonata 2020 promoted to officially supported car * Hyundai Ioniq Electric Limited 2019 and Ioniq SE 2020 support thanks to baldwalker! * Subaru Forester 2019 and Ascent 2019 support thanks to martinl! diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 2042c1a37c..c6b4780ff4 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -19,8 +19,8 @@ class CarInterface(CarInterfaceBase): ret.safetyModel = car.CarParams.SafetyModel.hyundai ret.radarOffCan = True - # Hyundai port is a community feature for now - ret.communityFeature = True + # Most Hyundai car ports are community features for now + ret.communityFeature = candidate not in [CAR.SONATA] ret.steerActuatorDelay = 0.1 # Default delay ret.steerRateCost = 0.5 From 80aead479eb915ff3ad46413f05904a2ebb9ce8a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 10 Jul 2020 12:01:29 -0700 Subject: [PATCH 450/656] update refs due to carParams.communityFeature change for sonata --- selfdrive/test/process_replay/ref_commit | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index c30eed7619..5ba0101a8d 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -520cf8bbbc7e37d3a54ce8d443f52eb232758be5 +d0b7760731f1e310c7770dafee215ed2dee0d92d \ No newline at end of file From 36abf4a73ca3520ac68a9ce692de93fb8d1c517a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 10 Jul 2020 12:21:24 -0700 Subject: [PATCH 451/656] bump submodules and add date to release notes --- RELEASES.md | 2 +- laika_repo | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index b0756eac31..125f728f37 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,4 +1,4 @@ -Version 0.7.7 (2020-xx-xx) +Version 0.7.7 (2020-07-17) ======================== * White panda is no longer supported, upgrade to comma two or black panda * Improved vehicle model estimation using high precision localizer diff --git a/laika_repo b/laika_repo index fd77ad9ecc..765c6584c3 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit fd77ad9eccf6b62bae587bd2f2ac09352712e23f +Subproject commit 765c6584c3d7f27e1af0f1180cc29766d5319f09 From b81f404457b2bfeee1d9c18c86af2aeb167b9403 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 10 Jul 2020 12:53:14 -0700 Subject: [PATCH 452/656] Simplify hyundai resume logic (#1852) * simplify hyundai resume logic * more reliable * SCC doesn't resume under 3.7m --- selfdrive/car/hyundai/carcontroller.py | 25 ++++++------------------- 1 file changed, 6 insertions(+), 19 deletions(-) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 8a6492a883..787cc91b00 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -1,4 +1,5 @@ from cereal import car +from common.realtime import DT_CTRL from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.hyundai.hyundaican import create_lkas11, create_clu11, create_lfa_mfa from selfdrive.car.hyundai.values import Buttons, SteerLimitParams, CAR @@ -40,9 +41,7 @@ class CarController(): self.car_fingerprint = CP.carFingerprint self.packer = CANPacker(dbc_name) self.steer_rate_limited = False - self.resume_cnt = 0 self.last_resume_frame = 0 - self.last_lead_distance = 0 def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, left_lane, right_lane, left_lane_depart, right_lane_depart): @@ -56,7 +55,7 @@ class CarController(): # fix for Genesis hard fault at low speed if CS.out.vEgo < 16.7 and self.car_fingerprint == CAR.HYUNDAI_GENESIS: - lkas_active = 0 + lkas_active = False if not lkas_active: apply_steer = 0 @@ -75,24 +74,12 @@ class CarController(): if pcm_cancel_cmd: can_sends.append(create_clu11(self.packer, frame, CS.clu11, Buttons.CANCEL)) - elif CS.out.cruiseState.standstill: - # run only first time when the car stopped - if self.last_lead_distance == 0: - # get the lead distance from the Radar - self.last_lead_distance = CS.lead_distance - self.resume_cnt = 0 - # when lead car starts moving, create 6 RES msgs - elif CS.lead_distance != self.last_lead_distance and (frame - self.last_resume_frame) > 5: + # SCC won't resume anyway when the lead distace is less than 3.7m + # send resume at a max freq of 5Hz + if CS.lead_distance > 3.7 and (frame - self.last_resume_frame)*DT_CTRL > 0.2: can_sends.append(create_clu11(self.packer, frame, CS.clu11, Buttons.RES_ACCEL)) - self.resume_cnt += 1 - # interval after 6 msgs - if self.resume_cnt > 5: - self.last_resume_frame = frame - self.resume_cnt = 0 - # reset lead distnce after the car starts moving - elif self.last_lead_distance != 0: - self.last_lead_distance = 0 + self.last_resume_frame = frame # 20 Hz LFA MFA message if frame % 5 == 0 and self.car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.IONIQ]: From 704bc1b8834d3f98e0be1d37e72911e449d7dd6c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 10 Jul 2020 15:26:16 -0700 Subject: [PATCH 453/656] small scons cleanup (#1858) --- SConstruct | 36 ++++++++++++++++++++++-------------- selfdrive/modeld/SConscript | 7 +++++-- 2 files changed, 27 insertions(+), 16 deletions(-) diff --git a/SConstruct b/SConstruct index 168e41bd0f..7e5a412b56 100644 --- a/SConstruct +++ b/SConstruct @@ -45,15 +45,19 @@ if arch == "aarch64" or arch == "larch64": ] if arch == "larch64": - libpath += ["#phonelibs/snpe/larch64"] - libpath += ["#phonelibs/libyuv/larch64/lib"] - libpath += ["/usr/lib/aarch64-linux-gnu"] + libpath += [ + "#phonelibs/snpe/larch64", + "#phonelibs/libyuv/larch64/lib", + "/usr/lib/aarch64-linux-gnu" + ] cflags = ["-DQCOM2", "-mcpu=cortex-a57"] cxxflags = ["-DQCOM2", "-mcpu=cortex-a57"] rpath = ["/usr/local/lib"] else: - libpath += ["#phonelibs/snpe/aarch64"] - libpath += ["#phonelibs/libyuv/lib"] + libpath += [ + "#phonelibs/snpe/aarch64", + "#phonelibs/libyuv/lib" + ] cflags = ["-DQCOM", "-mcpu=cortex-a57"] cxxflags = ["-DQCOM", "-mcpu=cortex-a57"] rpath = ["/system/vendor/lib64"] @@ -81,8 +85,8 @@ else: "/usr/local/lib", "/System/Library/Frameworks/OpenGL.framework/Libraries", ] - cflags.append("-DGL_SILENCE_DEPRECATION") - cxxflags.append("-DGL_SILENCE_DEPRECATION") + cflags += ["-DGL_SILENCE_DEPRECATION"] + cxxflags += ["-DGL_SILENCE_DEPRECATION"] else: libpath = [ "#phonelibs/snpe/x86_64-linux-clang", @@ -95,15 +99,20 @@ else: ] rpath = [ - "external/tensorflow/lib", - "cereal", - "selfdrive/common"] + "external/tensorflow/lib", + "cereal", + "selfdrive/common" + ] # allows shared libraries to work globally rpath = [os.path.join(os.getcwd(), x) for x in rpath] -ccflags_asan = ["-fsanitize=address", "-fno-omit-frame-pointer"] if GetOption('asan') else [] -ldflags_asan = ["-fsanitize=address"] if GetOption('asan') else [] +if GetOption('asan'): + ccflags_asan = ["-fsanitize=address", "-fno-omit-frame-pointer"] + ldflags_asan = ["-fsanitize=address"] +else: + ccflags_asan = [] + ldflags_asan = [] # change pythonpath to this lenv["PYTHONPATH"] = Dir("#").path @@ -154,8 +163,7 @@ env = Environment( CFLAGS=["-std=gnu11"] + cflags, CXXFLAGS=["-std=c++14"] + cxxflags, - LIBPATH=libpath + - [ + LIBPATH=libpath + [ "#cereal", "#selfdrive/common", "#phonelibs", diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index c97500e7d1..6f9f6608e2 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -9,7 +9,8 @@ common_src = [ "models/commonmodel.c", "runners/snpemodel.cc", "transforms/loadyuv.c", - "transforms/transform.c"] + "transforms/transform.c" +] if arch == "aarch64": libs += ['gsl', 'CB', 'gnustl_shared'] @@ -24,9 +25,11 @@ else: # for tensorflow support common_src += ['runners/tfmodel.cc'] - # tell runners to use it + + # tell runners to use tensorflow lenv['CFLAGS'].append("-DUSE_TF_MODEL") lenv['CXXFLAGS'].append("-DUSE_TF_MODEL") + if arch == "Darwin": # fix OpenCL del libs[libs.index('OpenCL')] From 897548c7efcbcc1e00740ef262449c06f9c3228f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 10 Jul 2020 17:18:52 -0700 Subject: [PATCH 454/656] clear scons cache dirs older than a day in CI --- selfdrive/test/phone_ci.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py index b002547196..a3a966ce2f 100755 --- a/selfdrive/test/phone_ci.py +++ b/selfdrive/test/phone_ci.py @@ -48,6 +48,9 @@ def run_on_phone(test_cmd): conn.send(f"export {k}='{v}'\n") conn.send("export CI=1\n") + # clear scons cache dirs that haven't been written to in one day + conn.send("cd /tmp && find -name 'scons_cache_*' -type d -maxdepth 1 -mtime 1 -exec rm -rf '{}' \\;\n") + # set up environment conn.send(f"cd {SOURCE_DIR}\n") conn.send("git reset --hard\n") From b17a6e8f315acfef79e893ea1d804f91bbb60403 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 10 Jul 2020 17:58:04 -0700 Subject: [PATCH 455/656] default to a reasonable amount of segs in replay_drive_can.py --- selfdrive/debug/internal/replay_drive_can.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/debug/internal/replay_drive_can.py b/selfdrive/debug/internal/replay_drive_can.py index 7fc5dceeb0..0009cd637f 100755 --- a/selfdrive/debug/internal/replay_drive_can.py +++ b/selfdrive/debug/internal/replay_drive_can.py @@ -6,7 +6,7 @@ from tools.lib.logreader import LogReader import cereal.messaging as messaging ROUTE = "77611a1fac303767/2020-03-24--09-50-38" -NUM_SEGS = 82 +NUM_SEGS = 10 # route has 82 segments available # Get can messages from logs print("Loading...") From 1286b45bfeb1b62bf756e474cbe34dd3fd3e4a8d Mon Sep 17 00:00:00 2001 From: s70160 <67191334+s70160@users.noreply.github.com> Date: Sat, 11 Jul 2020 15:17:32 +0800 Subject: [PATCH 456/656] Add hyundai ioniq 2018 fingerprint (#1863) --- selfdrive/car/hyundai/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index b4784196a2..b993d62055 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -116,6 +116,9 @@ FINGERPRINTS = { }], CAR.IONIQ: [{ 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 + }, + { + 68:8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 8, 576:8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1473: 8, 1476: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 }], CAR.KONA: [{ 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 909: 8, 916: 8, 1040: 8, 1078: 4, 1107: 5, 1136: 8, 1156: 8, 1170: 8, 1173: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 2004: 8, 2009: 8, 2012: 8 From 7b2789aa3aa36611c06301de6e56d2cdf1af96a6 Mon Sep 17 00:00:00 2001 From: martinl Date: Sun, 12 Jul 2020 00:36:26 +0300 Subject: [PATCH 457/656] Add APPROACHING signals for Subaru blindspot monitoring (#1864) --- selfdrive/car/subaru/carstate.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index d7a34d3625..c2406f2ffe 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -38,8 +38,8 @@ class CarState(CarStateBase): self.right_blinker_cnt = 50 if cp.vl["Dashlights"]['RIGHT_BLINKER'] else max(self.right_blinker_cnt - 1, 0) ret.rightBlinker = self.right_blinker_cnt > 0 - ret.leftBlindspot = cp.vl["BSD_RCTA"]['L_ADJACENT'] == 1 - ret.rightBlindspot = cp.vl["BSD_RCTA"]['R_ADJACENT'] == 1 + ret.leftBlindspot = (cp.vl["BSD_RCTA"]['L_ADJACENT'] == 1) or (cp.vl["BSD_RCTA"]['L_APPROACHING'] == 1) + ret.rightBlindspot = (cp.vl["BSD_RCTA"]['R_ADJACENT'] == 1) or (cp.vl["BSD_RCTA"]['R_APPROACHING'] == 1) can_gear = int(cp.vl["Transmission"]['Gear']) ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) @@ -92,6 +92,8 @@ class CarState(CarStateBase): ("Gear", "Transmission", 0), ("L_ADJACENT", "BSD_RCTA", 0), ("R_ADJACENT", "BSD_RCTA", 0), + ("L_APPROACHING", "BSD_RCTA", 0), + ("R_APPROACHING", "BSD_RCTA", 0), ] checks = [ From 897ee6bd2b11f313455fd00baff7eee5d45afac5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 12 Jul 2020 01:46:02 -0700 Subject: [PATCH 458/656] Use a monotonic clock source for power monitoring (#1861) --- selfdrive/thermald/power_monitoring.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/thermald/power_monitoring.py b/selfdrive/thermald/power_monitoring.py index 0801cea559..6bf26ee0ea 100644 --- a/selfdrive/thermald/power_monitoring.py +++ b/selfdrive/thermald/power_monitoring.py @@ -5,6 +5,7 @@ import time from statistics import mean from cereal import log +from common.realtime import sec_since_boot from selfdrive.swaglog import cloudlog PANDA_OUTPUT_VOLTAGE = 5.28 @@ -67,7 +68,7 @@ class PowerMonitoring: # Calculation tick def calculate(self, health): try: - now = time.time() + now = sec_since_boot() # Check that time is valid if datetime.datetime.fromtimestamp(now).year < 2019: From 62a94eb0cda8bc2c0f2cc1a116b3d5a0cc6e4628 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 12 Jul 2020 01:46:18 -0700 Subject: [PATCH 459/656] fix blocking sleep in updated (#1860) --- selfdrive/updated.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 6194bda9d2..bb665180ed 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -317,7 +317,6 @@ def attempt_update(): def main(): update_failed_count = 0 overlay_init_done = False - wait_helper = WaitTimeHelper() params = Params() if params.get("DisableUpdates") == b"1": @@ -340,6 +339,7 @@ def main(): # Wait a short time before our first update attempt # Avoids race with IsOffroad not being set, reduces manager startup load time.sleep(30) + wait_helper = WaitTimeHelper() while True: update_failed_count += 1 From 2840427409a571201e2ec69b81122b2d75770488 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 12 Jul 2020 18:06:13 -0700 Subject: [PATCH 460/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 2fab502cad..b3e278755c 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 2fab502cad444ebabea51e0e0df447b4bbd45a21 +Subproject commit b3e278755c2fe345cf9fe2c735753cce1025bb7b From 1ef3b2095564518cd16190f1f4ed2c2d3030e7a2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 13 Jul 2020 17:00:27 -0700 Subject: [PATCH 461/656] 2020 Jeep Grand Cherokee fingerprint Squashed commit of the following: commit a1a14048375b4d9c9181b2797621e999738104f8 Author: Adeeb Shihadeh Date: Mon Jul 13 16:30:54 2020 -0700 cleanup commit cf7d4bb162c5018a05b81dd83f124b3ef7826714 Author: Tunder (Chris in RL) <34691234+Tundergit@users.noreply.github.com> Date: Sun Jul 12 21:08:59 2020 -0700 added missed value commit b91af6eef1b5d966cf4342475a37129ddb46e8de Author: Tunder (Chris in RL) <34691234+Tundergit@users.noreply.github.com> Date: Sun Jul 12 20:52:41 2020 -0700 Update values.py commit d3d564fc76db19eae1464d6d938fdc43aa9b6d4e Author: Tunder (Chris in RL) <34691234+Tundergit@users.noreply.github.com> Date: Fri Jul 10 00:23:35 2020 -0700 add support for 2020 Grand Cherokee --- selfdrive/car/chrysler/values.py | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 2f74226947..2070947cdc 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -16,10 +16,10 @@ class CAR: PACIFICA_2017_HYBRID = "CHRYSLER PACIFICA HYBRID 2017" PACIFICA_2018_HYBRID = "CHRYSLER PACIFICA HYBRID 2018" PACIFICA_2019_HYBRID = "CHRYSLER PACIFICA HYBRID 2019" - PACIFICA_2018 = "CHRYSLER PACIFICA 2018" # Also covers Pacifica 2017. + PACIFICA_2018 = "CHRYSLER PACIFICA 2018" # includes 2017 Pacifica PACIFICA_2020 = "CHRYSLER PACIFICA 2020" - JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # Also covers Tailhawk 2017. - JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" + JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # includes 2017 Trailhawk + JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" # includes 2020 Trailhawk # Unique can messages: # Only the hybrids have 270: 8 @@ -75,9 +75,8 @@ FINGERPRINTS = { {257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 658: 6, 660: 8, 671: 8, 672: 8, 680: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 783: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8}, ], CAR.JEEP_CHEROKEE_2019: [ - # Jeep Grand Cherokee 2019 - # 530: 8 is so far only in this Jeep. - {55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1543: 8, 2015: 8, 2016: 8, 2024: 8}, + # Jeep Grand Cherokee 2019, including most 2020 models + {55: 8, 168: 8, 179: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 960: 4, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1250: 8, 1251: 8, 1252: 8, 1254: 8, 1264: 8, 1284: 8, 1536: 8, 1537: 8, 1543: 8, 1545: 8, 1562: 8, 1568: 8, 1570: 8, 1572: 8, 1593: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1890: 8, 1891: 8, 1892: 8, 1894: 8, 1896: 8, 1904: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8}, ], } From d9adbae9a8ab87b8145f0a2617b3fa0af7ee4157 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Mon, 13 Jul 2020 17:37:08 -0700 Subject: [PATCH 462/656] Add 2020 Jeep Grand Cherokee to readme --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 2f8adbcc8a..052828cf17 100644 --- a/README.md +++ b/README.md @@ -150,7 +150,7 @@ Community Maintained Cars and Features | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2019 | All | Stock | 0mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | -| Jeep | Grand Cherokee 2019 | Adaptive Cruise | Stock | 0mph | 39mph | +| Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | | Kia | Forte 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Optima 2017 | SCC + LKAS/LDWS | Stock | 0mph | 32mph | | Kia | Optima 2019 | SCC + LKAS | Stock | 0mph | 0mph | From 58c3b5ba84f6c3da3c660770148cea98c708fce5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 14 Jul 2020 14:23:27 -0700 Subject: [PATCH 463/656] Revert modeld vipc conflate behavior and alert on dropped frame percent (#1877) * Revert "Fix modeld dropping frames if processing takes over 50 ms" This reverts commit a8e7a187ca115a5fe5f3a04923dbe50bd00871c7. * track frame drop * fix unused * alert on frame drop perc * reduce thresholds * posenet is invalid on non-consecutive frames * Refactor filter time constant * Use vipc_dropped_frames for posenet valid check * Actually set frame drop percentage * Add explicit cast just to be sure * Prevent frames dropped to go up to quickly on startup * bump cereal * reduce soft disable threshold to 1% Co-authored-by: Willem Melching --- cereal | 2 +- selfdrive/controls/controlsd.py | 2 +- selfdrive/modeld/modeld.cc | 21 +++++++++++++++++---- selfdrive/modeld/models/driving.cc | 10 +++++----- selfdrive/modeld/models/driving.h | 7 ++++--- selfdrive/test/test_cpu_usage.py | 2 +- 6 files changed, 29 insertions(+), 15 deletions(-) diff --git a/cereal b/cereal index 80bbbd4bf7..f725dcd617 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 80bbbd4bf70698a3e7b7eaa1e463753c3db2ab5f +Subproject commit f725dcd617b0ff577ad5caee8b9b3c861d6be4a8 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 349a6cb840..4c11c5e05a 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -227,7 +227,7 @@ class Controls: self.events.add(EventName.relayMalfunction) if self.sm['plan'].fcw: self.events.add(EventName.fcw) - if self.sm['model'].frameAge > 1: + if self.sm['model'].frameDropPerc > 1: self.events.add(EventName.modeldLagging) # Only allow engagement with brake pressed when stopped behind another stopped car diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 369c446141..68b370124c 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -163,7 +163,7 @@ int main(int argc, char **argv) { VisionStream stream; while (!do_exit) { VisionStreamBufs buf_info; - err = visionstream_init(&stream, VISION_STREAM_YUV, false, &buf_info); + err = visionstream_init(&stream, VISION_STREAM_YUV, true, &buf_info); if (err) { LOGW("visionstream connect failed"); usleep(100000); @@ -171,10 +171,17 @@ int main(int argc, char **argv) { } LOGW("connected with buffer size: %d", buf_info.buf_len); + // setup filter to track dropped frames + const float dt = 1. / MODEL_FREQ; + const float ts = 5.0; // 5 s filter time constant + const float frame_filter_k = (dt / ts) / (1. + dt / ts); + float frames_dropped = 0; + // one frame in memory cl_mem yuv_cl; VisionBuf yuv_ion = visionbuf_allocate_cl(buf_info.buf_len, device_id, context, &yuv_cl); + uint32_t last_vipc_frame_id = 0; double last = 0; int desire = -1; while (!do_exit) { @@ -217,11 +224,17 @@ int main(int argc, char **argv) { model_transform, NULL, vec_desire); mt2 = millis_since_boot(); - model_publish(pm, extra.frame_id, frame_id, model_buf, extra.timestamp_eof); - posenet_publish(pm, extra.frame_id, frame_id, model_buf, extra.timestamp_eof); + // tracked dropped frames + uint32_t vipc_dropped_frames = extra.frame_id - last_vipc_frame_id - 1; + frames_dropped = (1. - frame_filter_k) * frames_dropped + frame_filter_k * (float)std::min(vipc_dropped_frames, 10U); + float frame_drop_perc = frames_dropped / MODEL_FREQ; + + model_publish(pm, extra.frame_id, frame_id, vipc_dropped_frames, frame_drop_perc, model_buf, extra.timestamp_eof); + posenet_publish(pm, extra.frame_id, frame_id, vipc_dropped_frames, frame_drop_perc, model_buf, extra.timestamp_eof); - LOGD("model process: %.2fms, from last %.2fms, vipc_frame_id %zu, frame_id, %zu", mt2-mt1, mt1-last, extra.frame_id, frame_id); + LOGD("model process: %.2fms, from last %.2fms, vipc_frame_id %zu, frame_id, %zu, frame_drop %.3f%", mt2-mt1, mt1-last, extra.frame_id, frame_id, frame_drop_perc); last = mt1; + last_vipc_frame_id = extra.frame_id; } } diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 9ac7604195..af481712b1 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -246,7 +246,7 @@ void fill_longi(cereal::ModelData::LongitudinalData::Builder longi, const float } void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, - const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { + uint32_t vipc_dropped_frames, float frame_drop, const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { // make msg capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); @@ -257,6 +257,7 @@ void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, auto framed = event.initModel(); framed.setFrameId(vipc_frame_id); framed.setFrameAge(frame_age); + framed.setFrameDropPerc(frame_drop * 100); framed.setTimestampEof(timestamp_eof); auto lpath = framed.initPath(); @@ -293,13 +294,13 @@ void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, auto meta = framed.initMeta(); fill_meta(meta, net_outputs.meta); - event.setValid(frame_age < MAX_FRAME_AGE); + event.setValid(frame_drop < MAX_FRAME_DROP); pm.send("model", msg); } void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, - const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { + uint32_t vipc_dropped_frames, float frame_drop, const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); event.setLogMonoTime(nanos_since_boot()); @@ -331,8 +332,7 @@ void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, posenetd.setTimestampEof(timestamp_eof); posenetd.setFrameId(vipc_frame_id); - uint32_t frame_age = (frame_id > vipc_frame_id) ? (frame_id - vipc_frame_id) : 0; - event.setValid(frame_age < MAX_FRAME_AGE); + event.setValid(vipc_dropped_frames < 1); pm.send("cameraOdometry", msg); } diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index 97941db198..83d967d23a 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -35,7 +35,8 @@ #define TIME_DISTANCE 100 #define POSE_SIZE 12 -#define MAX_FRAME_AGE 5 +#define MODEL_FREQ 20 +#define MAX_FRAME_DROP 0.05 struct ModelDataRaw { float *path; @@ -74,7 +75,7 @@ void model_free(ModelState* s); void poly_fit(float *in_pts, float *in_stds, float *out); void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, - const ModelDataRaw &data, uint64_t timestamp_eof); + uint32_t vipc_dropped_frames, float frame_drop, const ModelDataRaw &data, uint64_t timestamp_eof); void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, - const ModelDataRaw &data, uint64_t timestamp_eof); + uint32_t vipc_dropped_frames, float frame_drop, const ModelDataRaw &data, uint64_t timestamp_eof); #endif diff --git a/selfdrive/test/test_cpu_usage.py b/selfdrive/test/test_cpu_usage.py index 0ed651ad4b..eba08fd872 100755 --- a/selfdrive/test/test_cpu_usage.py +++ b/selfdrive/test/test_cpu_usage.py @@ -17,7 +17,7 @@ def print_cpu_usage(first_proc, last_proc): procs = [ ("selfdrive.controls.controlsd", 59.46), ("selfdrive.locationd.locationd", 34.38), - ("./loggerd", 28.49), + ("./loggerd", 33.90), ("selfdrive.controls.plannerd", 19.77), ("./_modeld", 12.74), ("selfdrive.locationd.paramsd", 11.53), From 3ff373ed0d5349087a77b2a96af41e0e5cc9c15d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 14 Jul 2020 17:19:22 -0700 Subject: [PATCH 464/656] add UI for boardd loopback test --- selfdrive/boardd/tests/test_boardd_loopback.py | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py index cb81a045f7..39c33b127d 100644 --- a/selfdrive/boardd/tests/test_boardd_loopback.py +++ b/selfdrive/boardd/tests/test_boardd_loopback.py @@ -9,6 +9,7 @@ import cereal.messaging as messaging from cereal import car from common.basedir import PARAMS from common.params import Params +from common.spinner import Spinner from panda import Panda from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car import make_can_msg @@ -33,7 +34,9 @@ os.environ['PARAMS_PATH'] = PARAMS @with_processes(['boardd']) def test_boardd_loopback(): + # wait for boardd to init + spinner = Spinner() time.sleep(2) # boardd blocks on CarVin and CarParams @@ -47,7 +50,10 @@ def test_boardd_loopback(): time.sleep(1) - for i in range(1000): + n = 1000 + for i in range(n): + spinner.update(f"boardd loopback {i}/{n}") + sent_msgs = defaultdict(set) for _ in range(random.randrange(10)): to_send = [] @@ -73,3 +79,5 @@ def test_boardd_loopback(): # if a set isn't empty, messages got dropped for bus in range(3): assert not len(sent_msgs[bus]), f"loop {i}: bus {bus} missing {len(sent_msgs[bus])} messages" + + spinner.close() From d4c4d906eccc6db107564572c04b02e6328b3b42 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 15 Jul 2020 14:45:48 -0700 Subject: [PATCH 465/656] update offroad apk with remaining chffrplus references fixed --- apk/ai.comma.plus.offroad.apk | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk index cb0c7224fa..414e4cf5c1 100644 --- a/apk/ai.comma.plus.offroad.apk +++ b/apk/ai.comma.plus.offroad.apk @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:7384496705c0e7af43b0a39a4d6fe0b9a39175455a5170008a02f7b7570799b9 -size 13701442 +oid sha256:64e31350a4138675cb39703d070fec787c011fcbdee3fbae1cbbb21ce4ceb6be +size 13701989 From 165e14d10384a67777ec5ed787cf1ec82ec61ccb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 16 Jul 2020 13:59:32 -0700 Subject: [PATCH 466/656] Rebuild cython extensions when dependency version changes (#1886) * rebuild cython extensions when python/cython/distutils version changes * submodules and boardd * kalman and transformations --- SConstruct | 6 ++++++ cereal | 2 +- common/SConscript | 10 +++++----- common/kalman/SConscript | 6 +++--- common/transformations/SConscript | 11 +++++------ opendbc | 2 +- selfdrive/boardd/SConscript | 8 ++++---- 7 files changed, 25 insertions(+), 20 deletions(-) diff --git a/SConstruct b/SConstruct index 7e5a412b56..322bdd5f9f 100644 --- a/SConstruct +++ b/SConstruct @@ -1,3 +1,5 @@ +import Cython +import distutils import os import shutil import subprocess @@ -12,6 +14,10 @@ AddOption('--asan', action='store_true', help='turn on ASAN') +# Rebuild cython extensions if python, distutils, or cython change +cython_dependencies = [Value(v) for v in (sys.version, distutils.__version__, Cython.__version__)] +Export('cython_dependencies') + arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() if platform.system() == "Darwin": arch = "Darwin" diff --git a/cereal b/cereal index f725dcd617..7b78cda876 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit f725dcd617b0ff577ad5caee8b9b3c861d6be4a8 +Subproject commit 7b78cda8767a79c4ac6797d71fbd7bcb03e1f737 diff --git a/common/SConscript b/common/SConscript index 103d416f53..35abeb9ee4 100644 --- a/common/SConscript +++ b/common/SConscript @@ -1,6 +1,6 @@ -Import('env') +Import('env', 'cython_dependencies') -# parser -env.Command(['common_pyx.so'], - ['common_pyx_setup.py', 'clock.pyx'], - "cd common && python3 common_pyx_setup.py build_ext --inplace") +# Build cython clock module +env.Command(['common_pyx.so', 'clock.cpp'], + cython_dependencies + ['common_pyx_setup.py', 'clock.pyx'], + "cd common && python3 common_pyx_setup.py build_ext --inplace") diff --git a/common/kalman/SConscript b/common/kalman/SConscript index abd7e04375..3d7011fe29 100644 --- a/common/kalman/SConscript +++ b/common/kalman/SConscript @@ -1,6 +1,6 @@ -Import('env') +Import('env', 'cython_dependencies') env.Command(['simple_kalman_impl.so'], - ['simple_kalman_impl.pyx', 'simple_kalman_impl.pxd', 'simple_kalman_setup.py'], - "cd common/kalman && python3 simple_kalman_setup.py build_ext --inplace") + cython_dependencies + ['simple_kalman_impl.pyx', 'simple_kalman_impl.pxd', 'simple_kalman_setup.py'], + "cd common/kalman && python3 simple_kalman_setup.py build_ext --inplace") diff --git a/common/transformations/SConscript b/common/transformations/SConscript index 7c051746a3..0f72952259 100644 --- a/common/transformations/SConscript +++ b/common/transformations/SConscript @@ -1,9 +1,8 @@ -Import('env') +Import('env', 'cython_dependencies') d = Dir('.') -env.Command( - ['transformations.so'], - ['transformations.pxd', 'transformations.pyx', - 'coordinates.cc', 'orientation.cc', 'coordinates.hpp', 'orientation.hpp'], - 'cd ' + d.path + ' && python3 setup.py build_ext --inplace') +env.Command(['transformations.so'], + cython_dependencies + ['transformations.pxd', 'transformations.pyx', + 'coordinates.cc', 'orientation.cc', 'coordinates.hpp', 'orientation.hpp'], + 'cd ' + d.path + ' && python3 setup.py build_ext --inplace') diff --git a/opendbc b/opendbc index 2265c9c3dc..9ee0069ecc 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 2265c9c3dcff4d58a9cc2cd434a6c704350a4729 +Subproject commit 9ee0069ecc01c154a0b77130f0da02b10cacbdfa diff --git a/selfdrive/boardd/SConscript b/selfdrive/boardd/SConscript index d7e575d064..b29b886369 100644 --- a/selfdrive/boardd/SConscript +++ b/selfdrive/boardd/SConscript @@ -1,9 +1,9 @@ -Import('env', 'common', 'cereal', 'messaging') +Import('env', 'common', 'cereal', 'messaging', 'cython_dependencies') env.Program('boardd.cc', LIBS=['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj']) env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) -env.Command(['boardd_api_impl.so'], - ['libcan_list_to_can_capnp.a', 'boardd_api_impl.pyx', 'boardd_setup.py'], - "cd selfdrive/boardd && python3 boardd_setup.py build_ext --inplace") +env.Command(['boardd_api_impl.so', 'boardd_api_impl.cpp'], + cython_dependencies + ['libcan_list_to_can_capnp.a', 'boardd_api_impl.pyx', 'boardd_setup.py'], + "cd selfdrive/boardd && python3 boardd_setup.py build_ext --inplace") From eebb941b5a30055b0a909782bde412153a3e8cb0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 16 Jul 2020 14:44:58 -0700 Subject: [PATCH 467/656] fix release date --- RELEASES.md | 2 +- release/files_common | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 125f728f37..5559cd3c63 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,4 +1,4 @@ -Version 0.7.7 (2020-07-17) +Version 0.7.7 (2020-07-20) ======================== * White panda is no longer supported, upgrade to comma two or black panda * Improved vehicle model estimation using high precision localizer diff --git a/release/files_common b/release/files_common index 41ce1f2141..a457994112 100644 --- a/release/files_common +++ b/release/files_common @@ -1,5 +1,6 @@ .gitignore LICENSE +launch.sh launch_chffrplus.sh launch_openpilot.sh From cdd9eb32a2e0b1ea10d6634b4ff8e9f56b3350af Mon Sep 17 00:00:00 2001 From: Alfonso Hernandez Date: Fri, 17 Jul 2020 19:33:35 +0200 Subject: [PATCH 468/656] Adding fingerprinting values for Toyota Rav4 Hybrid TSS2 Germany (#1885) --- selfdrive/car/toyota/values.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 6755075d1e..ee0385cc64 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -932,6 +932,7 @@ FW_VERSIONS = { (Ecu.engine, 0x700, None): [ b'\x018966342M5000\x00\x00\x00\x00', b'\x018966342X6000\x00\x00\x00\x00', + b'\x018966342W8000\x00\x00\x00\x00', b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', ], @@ -951,15 +952,17 @@ FW_VERSIONS = { b'\x028965B0R01300\x00\x00\x00\x008965B0R02300\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', b'\x018821F3301200\x00\x00\x00\x00', b'\x018821F3301300\x00\x00\x00\x00', b'\x018821F3301400\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4203200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F4203300\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F4203500\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], }, CAR.LEXUS_ES_TSS2: { From 2d0e994674dcd1965bb28158d49428fb43df8902 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Fri, 17 Jul 2020 15:34:02 -0700 Subject: [PATCH 469/656] EfficientNet driver monitoring (#1866) * e96f9be6 * bump cereal * filter sunglasses * fix unittest * update refs Co-authored-by: Adeeb Shihadeh --- models/dmonitoring_model.current | 2 +- models/dmonitoring_model.keras | 4 ++-- models/dmonitoring_model_q.dlc | 4 ++-- selfdrive/modeld/models/dmonitoring.cc | 8 +++++--- selfdrive/modeld/models/dmonitoring.h | 3 ++- selfdrive/monitoring/driver_monitor.py | 7 ++++--- selfdrive/monitoring/test_monitoring.py | 1 + selfdrive/test/process_replay/ref_commit | 2 +- 8 files changed, 18 insertions(+), 13 deletions(-) diff --git a/models/dmonitoring_model.current b/models/dmonitoring_model.current index 9c95aff333..b0026f152a 100644 --- a/models/dmonitoring_model.current +++ b/models/dmonitoring_model.current @@ -1 +1 @@ -43221d85-46fd-40b9-bff0-2b1b18a86b07 \ No newline at end of file +e96f9be6-5741-42ea-bdcd-0be6515b4230 \ No newline at end of file diff --git a/models/dmonitoring_model.keras b/models/dmonitoring_model.keras index 9a835302ec..c3d58f6fc7 100644 --- a/models/dmonitoring_model.keras +++ b/models/dmonitoring_model.keras @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:5c39a2096f7058541b5339ec36bc4c468955e67285078080ed6d8802fed06c1d -size 814176 +oid sha256:09aa11a17a5a8173e231071898c499f9ea632e6e64285586122828b1bbc70d41 +size 4165968 diff --git a/models/dmonitoring_model_q.dlc b/models/dmonitoring_model_q.dlc index fc990411e9..558b359bfa 100644 --- a/models/dmonitoring_model_q.dlc +++ b/models/dmonitoring_model_q.dlc @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:29504dfd101ba2a0b48550fac2f86f9d0b8d1245af3d2d8d658247b4a73077a2 -size 230121 +oid sha256:beecf140ddc5da96cbdae3b869ebb3f5453dcd8e61e09d7d079c91e006b6df98 +size 1134208 diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 15b28dd8d6..4f4203a38a 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -5,9 +5,9 @@ #include -#define MODEL_WIDTH 160 -#define MODEL_HEIGHT 320 -#define FULL_W 426 +#define MODEL_WIDTH 320 +#define MODEL_HEIGHT 640 +#define FULL_W 852 #if defined(QCOM) || defined(QCOM2) #define input_lambda(x) (x - 128.f) * 0.0078125f @@ -136,6 +136,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ memcpy(&ret.right_eye_prob, &s->output[30], sizeof ret.right_eye_prob); memcpy(&ret.left_blink_prob, &s->output[31], sizeof ret.right_eye_prob); memcpy(&ret.right_blink_prob, &s->output[32], sizeof ret.right_eye_prob); + memcpy(&ret.sg_prob, &s->output[33], sizeof ret.sg_prob); ret.face_orientation_meta[0] = softplus(ret.face_orientation_meta[0]); ret.face_orientation_meta[1] = softplus(ret.face_orientation_meta[1]); ret.face_orientation_meta[2] = softplus(ret.face_orientation_meta[2]); @@ -166,6 +167,7 @@ void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResu framed.setRightEyeProb(res.right_eye_prob); framed.setLeftBlinkProb(res.left_blink_prob); framed.setRightBlinkProb(res.right_blink_prob); + framed.setSgProb(res.sg_prob); pm.send("driverState", msg); } diff --git a/selfdrive/modeld/models/dmonitoring.h b/selfdrive/modeld/models/dmonitoring.h index 83d014f8db..439b9c0051 100644 --- a/selfdrive/modeld/models/dmonitoring.h +++ b/selfdrive/modeld/models/dmonitoring.h @@ -9,7 +9,7 @@ extern "C" { #endif -#define OUTPUT_SIZE 33 +#define OUTPUT_SIZE 34 #define RHD_CHECK_INTERVAL 10 typedef struct DMonitoringResult { @@ -22,6 +22,7 @@ typedef struct DMonitoringResult { float right_eye_prob; float left_blink_prob; float right_blink_prob; + float sg_prob; } DMonitoringResult; typedef struct DMonitoringModelState { diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index 7cacd770ce..76487e24e3 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -21,8 +21,9 @@ _DISTRACTED_TIME = 11. _DISTRACTED_PRE_TIME_TILL_TERMINAL = 8. _DISTRACTED_PROMPT_TIME_TILL_TERMINAL = 6. -_FACE_THRESHOLD = 0.4 +_FACE_THRESHOLD = 0.6 _EYE_THRESHOLD = 0.6 +_SG_THRESHOLD = 0.5 _BLINK_THRESHOLD = 0.5 # 0.225 _BLINK_THRESHOLD_SLACK = 0.65 _BLINK_THRESHOLD_STRICT = 0.5 @@ -189,8 +190,8 @@ class DriverStatus(): # self.pose.roll_std = driver_state.faceOrientationStd[2] model_std_max = max(self.pose.pitch_std, self.pose.yaw_std) self.pose.low_std = model_std_max < _POSESTD_THRESHOLD - self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb > _EYE_THRESHOLD) - self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb > _EYE_THRESHOLD) + self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb > _EYE_THRESHOLD) * (driver_state.sgProb < _SG_THRESHOLD) + self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb > _EYE_THRESHOLD) * (driver_state.sgProb < _SG_THRESHOLD) self.face_detected = driver_state.faceProb > _FACE_THRESHOLD and \ abs(driver_state.facePosition[0]) <= 0.4 and abs(driver_state.facePosition[1]) <= 0.45 diff --git a/selfdrive/monitoring/test_monitoring.py b/selfdrive/monitoring/test_monitoring.py index a741115cae..270f6fe067 100644 --- a/selfdrive/monitoring/test_monitoring.py +++ b/selfdrive/monitoring/test_monitoring.py @@ -31,6 +31,7 @@ class fake_DM_msg(): self.rightBlinkProb = 1. * is_distracted self.faceOrientationStd = [1.*is_model_uncertain, 1.*is_model_uncertain, 1.*is_model_uncertain] self.facePositionStd = [1.*is_model_uncertain, 1.*is_model_uncertain] + self.sgProb = 0. # driver state from neural net, 10Hz diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 5ba0101a8d..545c1f0cbb 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -d0b7760731f1e310c7770dafee215ed2dee0d92d \ No newline at end of file +6d58be2d98e689d0c23d5210bd32394d506e66f8 \ No newline at end of file From c2be31c10be18893fbb1f45b37e34f291fa6b97d Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Fri, 17 Jul 2020 18:20:04 -0700 Subject: [PATCH 470/656] Revert "EfficientNet driver monitoring (#1866)" This reverts commit 2d0e994674dcd1965bb28158d49428fb43df8902. Need to fix test --- models/dmonitoring_model.current | 2 +- models/dmonitoring_model.keras | 4 ++-- models/dmonitoring_model_q.dlc | 4 ++-- selfdrive/modeld/models/dmonitoring.cc | 8 +++----- selfdrive/modeld/models/dmonitoring.h | 3 +-- selfdrive/monitoring/driver_monitor.py | 7 +++---- selfdrive/monitoring/test_monitoring.py | 1 - selfdrive/test/process_replay/ref_commit | 2 +- 8 files changed, 13 insertions(+), 18 deletions(-) diff --git a/models/dmonitoring_model.current b/models/dmonitoring_model.current index b0026f152a..9c95aff333 100644 --- a/models/dmonitoring_model.current +++ b/models/dmonitoring_model.current @@ -1 +1 @@ -e96f9be6-5741-42ea-bdcd-0be6515b4230 \ No newline at end of file +43221d85-46fd-40b9-bff0-2b1b18a86b07 \ No newline at end of file diff --git a/models/dmonitoring_model.keras b/models/dmonitoring_model.keras index c3d58f6fc7..9a835302ec 100644 --- a/models/dmonitoring_model.keras +++ b/models/dmonitoring_model.keras @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:09aa11a17a5a8173e231071898c499f9ea632e6e64285586122828b1bbc70d41 -size 4165968 +oid sha256:5c39a2096f7058541b5339ec36bc4c468955e67285078080ed6d8802fed06c1d +size 814176 diff --git a/models/dmonitoring_model_q.dlc b/models/dmonitoring_model_q.dlc index 558b359bfa..fc990411e9 100644 --- a/models/dmonitoring_model_q.dlc +++ b/models/dmonitoring_model_q.dlc @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:beecf140ddc5da96cbdae3b869ebb3f5453dcd8e61e09d7d079c91e006b6df98 -size 1134208 +oid sha256:29504dfd101ba2a0b48550fac2f86f9d0b8d1245af3d2d8d658247b4a73077a2 +size 230121 diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 4f4203a38a..15b28dd8d6 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -5,9 +5,9 @@ #include -#define MODEL_WIDTH 320 -#define MODEL_HEIGHT 640 -#define FULL_W 852 +#define MODEL_WIDTH 160 +#define MODEL_HEIGHT 320 +#define FULL_W 426 #if defined(QCOM) || defined(QCOM2) #define input_lambda(x) (x - 128.f) * 0.0078125f @@ -136,7 +136,6 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ memcpy(&ret.right_eye_prob, &s->output[30], sizeof ret.right_eye_prob); memcpy(&ret.left_blink_prob, &s->output[31], sizeof ret.right_eye_prob); memcpy(&ret.right_blink_prob, &s->output[32], sizeof ret.right_eye_prob); - memcpy(&ret.sg_prob, &s->output[33], sizeof ret.sg_prob); ret.face_orientation_meta[0] = softplus(ret.face_orientation_meta[0]); ret.face_orientation_meta[1] = softplus(ret.face_orientation_meta[1]); ret.face_orientation_meta[2] = softplus(ret.face_orientation_meta[2]); @@ -167,7 +166,6 @@ void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResu framed.setRightEyeProb(res.right_eye_prob); framed.setLeftBlinkProb(res.left_blink_prob); framed.setRightBlinkProb(res.right_blink_prob); - framed.setSgProb(res.sg_prob); pm.send("driverState", msg); } diff --git a/selfdrive/modeld/models/dmonitoring.h b/selfdrive/modeld/models/dmonitoring.h index 439b9c0051..83d014f8db 100644 --- a/selfdrive/modeld/models/dmonitoring.h +++ b/selfdrive/modeld/models/dmonitoring.h @@ -9,7 +9,7 @@ extern "C" { #endif -#define OUTPUT_SIZE 34 +#define OUTPUT_SIZE 33 #define RHD_CHECK_INTERVAL 10 typedef struct DMonitoringResult { @@ -22,7 +22,6 @@ typedef struct DMonitoringResult { float right_eye_prob; float left_blink_prob; float right_blink_prob; - float sg_prob; } DMonitoringResult; typedef struct DMonitoringModelState { diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index 76487e24e3..7cacd770ce 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -21,9 +21,8 @@ _DISTRACTED_TIME = 11. _DISTRACTED_PRE_TIME_TILL_TERMINAL = 8. _DISTRACTED_PROMPT_TIME_TILL_TERMINAL = 6. -_FACE_THRESHOLD = 0.6 +_FACE_THRESHOLD = 0.4 _EYE_THRESHOLD = 0.6 -_SG_THRESHOLD = 0.5 _BLINK_THRESHOLD = 0.5 # 0.225 _BLINK_THRESHOLD_SLACK = 0.65 _BLINK_THRESHOLD_STRICT = 0.5 @@ -190,8 +189,8 @@ class DriverStatus(): # self.pose.roll_std = driver_state.faceOrientationStd[2] model_std_max = max(self.pose.pitch_std, self.pose.yaw_std) self.pose.low_std = model_std_max < _POSESTD_THRESHOLD - self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb > _EYE_THRESHOLD) * (driver_state.sgProb < _SG_THRESHOLD) - self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb > _EYE_THRESHOLD) * (driver_state.sgProb < _SG_THRESHOLD) + self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb > _EYE_THRESHOLD) + self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb > _EYE_THRESHOLD) self.face_detected = driver_state.faceProb > _FACE_THRESHOLD and \ abs(driver_state.facePosition[0]) <= 0.4 and abs(driver_state.facePosition[1]) <= 0.45 diff --git a/selfdrive/monitoring/test_monitoring.py b/selfdrive/monitoring/test_monitoring.py index 270f6fe067..a741115cae 100644 --- a/selfdrive/monitoring/test_monitoring.py +++ b/selfdrive/monitoring/test_monitoring.py @@ -31,7 +31,6 @@ class fake_DM_msg(): self.rightBlinkProb = 1. * is_distracted self.faceOrientationStd = [1.*is_model_uncertain, 1.*is_model_uncertain, 1.*is_model_uncertain] self.facePositionStd = [1.*is_model_uncertain, 1.*is_model_uncertain] - self.sgProb = 0. # driver state from neural net, 10Hz diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 545c1f0cbb..5ba0101a8d 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -6d58be2d98e689d0c23d5210bd32394d506e66f8 \ No newline at end of file +d0b7760731f1e310c7770dafee215ed2dee0d92d \ No newline at end of file From 35a5b057c1ab6d3f77daae6a40d14c9bff28f08b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 17 Jul 2020 23:34:38 -0700 Subject: [PATCH 471/656] minor cleanups from LGTM --- common/transformations/orientation.py | 1 - selfdrive/car/chrysler/interface.py | 2 -- selfdrive/modeld/modeld.cc | 2 +- tools/replay/ui.py | 1 - 4 files changed, 1 insertion(+), 5 deletions(-) diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py index f0920942b6..415e247ab2 100644 --- a/common/transformations/orientation.py +++ b/common/transformations/orientation.py @@ -46,7 +46,6 @@ quats_from_rotations = rot2quat quat_from_rot = rot2quat rotations_from_quats = quat2rot rot_from_quat = quat2rot -rot_from_quat = quat2rot euler_from_rot = rot2euler euler_from_quat = quat2euler rot_from_euler = euler2rot diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 294b96c5ea..6cf5c85a6e 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -14,8 +14,6 @@ class CarInterface(CarInterfaceBase): def get_params(candidate, fingerprint=None, has_relay=False, car_fw=None): if fingerprint is None: fingerprint = gen_empty_fingerprint() - if car_fw is None: - car_fw = [] ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "chrysler" diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 68b370124c..ebfed713c2 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -232,7 +232,7 @@ int main(int argc, char **argv) { model_publish(pm, extra.frame_id, frame_id, vipc_dropped_frames, frame_drop_perc, model_buf, extra.timestamp_eof); posenet_publish(pm, extra.frame_id, frame_id, vipc_dropped_frames, frame_drop_perc, model_buf, extra.timestamp_eof); - LOGD("model process: %.2fms, from last %.2fms, vipc_frame_id %zu, frame_id, %zu, frame_drop %.3f%", mt2-mt1, mt1-last, extra.frame_id, frame_id, frame_drop_perc); + LOGD("model process: %.2fms, from last %.2fms, vipc_frame_id %zu, frame_id, %zu, frame_drop %.3f", mt2-mt1, mt1-last, extra.frame_id, frame_id, frame_drop_perc); last = mt1; last_vipc_frame_id = extra.frame_id; } diff --git a/tools/replay/ui.py b/tools/replay/ui.py index f0058989a7..37dfd5c18b 100755 --- a/tools/replay/ui.py +++ b/tools/replay/ui.py @@ -230,7 +230,6 @@ def ui_thread(addr, frame_address): pygame.surfarray.blit_array(*top_down) screen.blit(top_down[0], (640, 0)) - i = 0 SPACING = 25 lines = [ From a34b9f5cb5a691b2153f6a2ba905e6f1f84af341 Mon Sep 17 00:00:00 2001 From: Mufeed VH Date: Sat, 18 Jul 2020 12:19:57 +0530 Subject: [PATCH 472/656] Fix insecure temporary file creation (#1890) * Fix insecure temporary file creation * minor error fix tmp_path.name (NamedTemporaryFile().name) is required to return the filename string. --- common/params.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/common/params.py b/common/params.py index 7b90913e7d..fc387b6227 100755 --- a/common/params.py +++ b/common/params.py @@ -319,14 +319,14 @@ def write_db(params_path, key, value): lock.acquire() try: - tmp_path = tempfile.mktemp(prefix=".tmp", dir=params_path) - with open(tmp_path, "wb") as f: + tmp_path = tempfile.NamedTemporaryFile(mode="wb", prefix=".tmp", dir=params_path, delete=False) + with tmp_path as f: f.write(value) f.flush() os.fsync(f.fileno()) path = "%s/d/%s" % (params_path, key) - os.rename(tmp_path, path) + os.rename(tmp_path.name, path) fsync_dir(os.path.dirname(path)) finally: os.umask(prev_umask) From 8db641efec5d3c4df284afd9b8c8e9c2838ccabb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 18 Jul 2020 18:10:46 -0700 Subject: [PATCH 473/656] fix params permissions after #1890 --- common/params.py | 1 + 1 file changed, 1 insertion(+) diff --git a/common/params.py b/common/params.py index fc387b6227..985390faa9 100755 --- a/common/params.py +++ b/common/params.py @@ -324,6 +324,7 @@ def write_db(params_path, key, value): f.write(value) f.flush() os.fsync(f.fileno()) + os.chmod(tmp_path.name, 0o666) path = "%s/d/%s" % (params_path, key) os.rename(tmp_path.name, path) From 2ad9c50e3613674cb6170b46411d7dba0b1edff9 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 18 Jul 2020 18:30:29 -0700 Subject: [PATCH 474/656] add test for params permissions --- common/tests/test_params.py | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/common/tests/test_params.py b/common/tests/test_params.py index b0c7af828d..0a2ac4e12f 100644 --- a/common/tests/test_params.py +++ b/common/tests/test_params.py @@ -1,10 +1,12 @@ -from common.params import Params, UnknownKeyName +import os import threading import time import tempfile import shutil +import stat import unittest +from common.params import Params, UnknownKeyName class TestParams(unittest.TestCase): def setUp(self): @@ -58,6 +60,12 @@ class TestParams(unittest.TestCase): with self.assertRaises(UnknownKeyName): self.params.get("swag") + def test_params_permissions(self): + permissions = stat.S_IRUSR | stat.S_IWUSR | stat.S_IRGRP | stat.S_IWGRP | stat.S_IROTH | stat.S_IWOTH + + self.params.put("DongleId", "cb38263377b873ee") + st_mode = os.stat(f"{self.tmpdir}/d/DongleId").st_mode + assert (st_mode & permissions) == permissions if __name__ == "__main__": unittest.main() From b299a1b9bb2e14aef435337ca27f04447513809b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 19 Jul 2020 14:00:07 -0700 Subject: [PATCH 475/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index b3e278755c..4b576ab13d 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit b3e278755c2fe345cf9fe2c735753cce1025bb7b +Subproject commit 4b576ab13d5cc5182d7540fe0a719f3408fab0d1 From 5db81f60ca8fbc0ef28924b7e93f25a1d4bb3764 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 19 Jul 2020 16:12:22 -0700 Subject: [PATCH 476/656] Fix most remaining LGTM alerts (#1893) * fixups from LGTM * short globals * fix spinner and textwindow * total ordering * no spinner/text window when import from manager * not android --- common/spinner.py | 36 ++++++------------- common/text_window.py | 52 +++++++++------------------ common/transformations/coordinates.cc | 6 ++-- selfdrive/controls/lib/events.py | 7 +++- selfdrive/manager.py | 13 +++---- selfdrive/modeld/models/commonmodel.c | 6 ++-- selfdrive/ui/linux.cc | 2 +- 7 files changed, 45 insertions(+), 77 deletions(-) diff --git a/common/spinner.py b/common/spinner.py index c49b124c98..53e8ee5215 100644 --- a/common/spinner.py +++ b/common/spinner.py @@ -4,14 +4,17 @@ from common.basedir import BASEDIR class Spinner(): - def __init__(self): - try: - self.spinner_proc = subprocess.Popen(["./spinner"], - stdin=subprocess.PIPE, - cwd=os.path.join(BASEDIR, "selfdrive", "ui", "spinner"), - close_fds=True) - except OSError: - self.spinner_proc = None + def __init__(self, noop=False): + # spinner is currently only implemented for android + self.spinner_proc = None + if not noop: + try: + self.spinner_proc = subprocess.Popen(["./spinner"], + stdin=subprocess.PIPE, + cwd=os.path.join(BASEDIR, "selfdrive", "ui", "spinner"), + close_fds=True) + except OSError: + self.spinner_proc = None def __enter__(self): return self @@ -40,23 +43,6 @@ class Spinner(): self.close() -class FakeSpinner(Spinner): - def __init__(self): # pylint: disable=super-init-not-called - pass - - def __enter__(self): - return self - - def update(self, _): - pass - - def close(self): - pass - - def __exit__(self, exc_type, exc_value, traceback): - pass - - if __name__ == "__main__": import time with Spinner() as s: diff --git a/common/text_window.py b/common/text_window.py index 88da8e53f5..b815d8022a 100755 --- a/common/text_window.py +++ b/common/text_window.py @@ -6,20 +6,22 @@ from common.basedir import BASEDIR class TextWindow(): - def __init__(self, s): - try: - self.text_proc = subprocess.Popen(["./text", s], - stdin=subprocess.PIPE, - cwd=os.path.join(BASEDIR, "selfdrive", "ui", "text"), - close_fds=True) - except OSError: - self.text_proc = None + def __init__(self, s, noop=False): + # text window is only implemented for android currently + self.text_proc = None + if not noop: + try: + self.text_proc = subprocess.Popen(["./text", s], + stdin=subprocess.PIPE, + cwd=os.path.join(BASEDIR, "selfdrive", "ui", "text"), + close_fds=True) + except OSError: + self.text_proc = None def get_status(self): if self.text_proc is not None: self.text_proc.poll() return self.text_proc.returncode - return None def __enter__(self): @@ -31,10 +33,11 @@ class TextWindow(): self.text_proc = None def wait_for_exit(self): - while True: - if self.get_status() == 1: - return - time.sleep(0.1) + if self.text_proc is not None: + while True: + if self.get_status() == 1: + return + time.sleep(0.1) def __del__(self): self.close() @@ -43,29 +46,6 @@ class TextWindow(): self.close() -class FakeTextWindow(TextWindow): - def __init__(self, s): # pylint: disable=super-init-not-called - pass - - def get_status(self): - return 1 - - def wait_for_exit(self): - return - - def __enter__(self): - return self - - def update(self, _): - pass - - def close(self): - pass - - def __exit__(self, exc_type, exc_value, traceback): - pass - - if __name__ == "__main__": text = """Traceback (most recent call last): File "./controlsd.py", line 608, in diff --git a/common/transformations/coordinates.cc b/common/transformations/coordinates.cc index 313683b6f6..8a1aa0ad72 100644 --- a/common/transformations/coordinates.cc +++ b/common/transformations/coordinates.cc @@ -10,9 +10,9 @@ #define RAD2DEG(x) ((x) * 180.0 / M_PI) -double a = 6378137; -double b = 6356752.3142; -double esq = 6.69437999014 * 0.001; +double a = 6378137; // lgtm [cpp/short-global-name] +double b = 6356752.3142; // lgtm [cpp/short-global-name] +double esq = 6.69437999014 * 0.001; // lgtm [cpp/short-global-name] double e1sq = 6.73949674228 * 0.001; diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index f576cf4d2b..bb7ce16566 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -1,5 +1,6 @@ -from cereal import log, car +from functools import total_ordering +from cereal import log, car from common.realtime import DT_CTRL from selfdrive.config import Conversions as CV from selfdrive.locationd.calibration_helpers import Filter @@ -93,6 +94,7 @@ class Events: ret.append(event) return ret +@total_ordering class Alert: def __init__(self, alert_text_1, @@ -136,6 +138,9 @@ class Alert: def __gt__(self, alert2): return self.alert_priority > alert2.alert_priority + def __eq__(self, alert2): + return self.alert_priority == alert2.alert_priority + class NoEntryAlert(Alert): def __init__(self, alert_text_2, audible_alert=AudibleAlert.chimeError, visual_alert=VisualAlert.none, duration_hud_alert=2.): diff --git a/selfdrive/manager.py b/selfdrive/manager.py index a81f80e99f..b8917b02d3 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -70,19 +70,15 @@ def unblock_stdout(): if __name__ == "__main__": unblock_stdout() -if __name__ == "__main__" and ANDROID: - from common.spinner import Spinner - from common.text_window import TextWindow -else: - from common.spinner import FakeSpinner as Spinner - from common.text_window import FakeTextWindow as TextWindow +from common.spinner import Spinner +from common.text_window import TextWindow import importlib import traceback from multiprocessing import Process # Run scons -spinner = Spinner() +spinner = Spinner(noop=(__name__ != "main" or not ANDROID)) spinner.update("0") if not prebuilt: @@ -142,8 +138,9 @@ if not prebuilt: cloudlog.error("scons build failed\n" + error_s) # Show TextWindow + no_ui = __name__ != "__main__" or not ANDROID error_s = "\n \n".join(["\n".join(textwrap.wrap(e, 65)) for e in errors]) - with TextWindow("openpilot failed to build\n \n" + error_s) as t: + with TextWindow("openpilot failed to build\n \n" + error_s, noop=no_ui) as t: t.wait_for_exit() exit(1) diff --git a/selfdrive/modeld/models/commonmodel.c b/selfdrive/modeld/models/commonmodel.c index 93fceb3ad5..eebf4761af 100644 --- a/selfdrive/modeld/models/commonmodel.c +++ b/selfdrive/modeld/models/commonmodel.c @@ -15,13 +15,13 @@ void frame_init(ModelFrame* frame, int width, int height, frame->transformed_height = height; frame->transformed_y_cl = clCreateBuffer(frame->context, CL_MEM_READ_WRITE, - frame->transformed_width*frame->transformed_height, NULL, &err); + (size_t)frame->transformed_width*frame->transformed_height, NULL, &err); assert(err == 0); frame->transformed_u_cl = clCreateBuffer(frame->context, CL_MEM_READ_WRITE, - (frame->transformed_width/2)*(frame->transformed_height/2), NULL, &err); + (size_t)(frame->transformed_width/2)*(frame->transformed_height/2), NULL, &err); assert(err == 0); frame->transformed_v_cl = clCreateBuffer(frame->context, CL_MEM_READ_WRITE, - (frame->transformed_width/2)*(frame->transformed_height/2), NULL, &err); + (size_t)(frame->transformed_width/2)*(frame->transformed_height/2), NULL, &err); assert(err == 0); frame->net_input_size = ((width*height*3)/2)*sizeof(float); diff --git a/selfdrive/ui/linux.cc b/selfdrive/ui/linux.cc index 590a6de28f..5b370cc29f 100644 --- a/selfdrive/ui/linux.cc +++ b/selfdrive/ui/linux.cc @@ -83,7 +83,7 @@ int touch_read(TouchState *s, int* out_x, int* out_y) { #include "sound.hpp" bool Sound::init(int volume) { return true; } -bool Sound::play(AudibleAlert alert) { return true; } +bool Sound::play(AudibleAlert alert) { printf("play sound: %d\n", (int)alert); return true; } void Sound::stop() {} void Sound::setVolume(int volume) {} Sound::~Sound() {} From 75565b0635f7d1d659c77ed6dd99927e8c1b22a9 Mon Sep 17 00:00:00 2001 From: eFini Date: Mon, 20 Jul 2020 23:20:24 +1000 Subject: [PATCH 477/656] gas pressed treats as driver engaged (#1895) --- selfdrive/monitoring/dmonitoringd.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index 4939d604d7..a7fb78a729 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -35,6 +35,7 @@ def dmonitoringd_thread(sm=None, pm=None): sm['carState'].cruiseState.speed = 0. sm['carState'].buttonEvents = [] sm['carState'].steeringPressed = False + sm['carState'].gasPressed = False sm['carState'].standstill = True cal_rpy = [0, 0, 0] @@ -56,7 +57,8 @@ def dmonitoringd_thread(sm=None, pm=None): v_cruise = sm['carState'].cruiseState.speed driver_engaged = len(sm['carState'].buttonEvents) > 0 or \ v_cruise != v_cruise_last or \ - sm['carState'].steeringPressed + sm['carState'].steeringPressed or \ + sm['carState'].gasPressed if driver_engaged: driver_status.update(Events(), True, sm['carState'].cruiseState.enabled, sm['carState'].standstill) v_cruise_last = v_cruise From c8f880665a6331aaed7799b37b12ea639e899c77 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 20 Jul 2020 06:21:39 -0700 Subject: [PATCH 478/656] Disable raw upload while onroad (#1894) * disable raw upload while onroad * fix tests --- selfdrive/loggerd/tests/loggerd_tests_common.py | 1 + selfdrive/loggerd/uploader.py | 4 ++-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/loggerd/tests/loggerd_tests_common.py b/selfdrive/loggerd/tests/loggerd_tests_common.py index 72bd5e3b35..d3dc92a52a 100644 --- a/selfdrive/loggerd/tests/loggerd_tests_common.py +++ b/selfdrive/loggerd/tests/loggerd_tests_common.py @@ -57,6 +57,7 @@ class MockParams(): self.params = { "DongleId": b"0000000000000000", "IsUploadRawEnabled": b"1", + "IsOffroad": b"1", } def get(self, k): diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index 5b14bba8a8..34bfc78959 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -247,7 +247,8 @@ def uploader_fn(exit_event): backoff = 0.1 while True: - allow_raw_upload = (params.get("IsUploadRawEnabled") != b"0") + offroad = params.get("IsOffroad") == b'1' + allow_raw_upload = (params.get("IsUploadRawEnabled") != b"0") and offroad on_hotspot = is_on_hotspot() on_wifi = is_on_wifi() should_upload = on_wifi and not on_hotspot @@ -257,7 +258,6 @@ def uploader_fn(exit_event): d = uploader.next_file_to_upload(with_raw=allow_raw_upload and should_upload) if d is None: # Nothing to upload - offroad = params.get("IsOffroad") == b'1' time.sleep(60 if offroad else 5) continue From 1613abb0b15e24e3d0ddec3efdbd0d61581e6d2b Mon Sep 17 00:00:00 2001 From: cfranhonda <46506059+cfranhonda@users.noreply.github.com> Date: Mon, 20 Jul 2020 08:03:20 -0700 Subject: [PATCH 479/656] Update civic bosch longitudinal tuning (#1875) These are the correct values when i was testing visionradar. Things got messed when Civics were coded together and got split up again. --- selfdrive/car/honda/interface.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 7e5c46c895..7468e06353 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -189,9 +189,9 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 1. ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] ret.longitudinalTuning.kpBP = [0., 5., 35.] - ret.longitudinalTuning.kpV = [3.6, 2.4, 1.5] + ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5] ret.longitudinalTuning.kiBP = [0., 35.] - ret.longitudinalTuning.kiV = [0.54, 0.36] + ret.longitudinalTuning.kiV = [0.18, 0.12] elif candidate in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH): stop_and_go = True From ebadb39e42d8a39eaf3bc969157777d596e42012 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 20 Jul 2020 10:04:05 -0500 Subject: [PATCH 480/656] Fix hard deceleration after user accelerates above set cruise speed (#1880) * Fix hard deceleration after user accelerates above set cruise speed * 2nd required change --- selfdrive/controls/lib/longcontrol.py | 2 +- selfdrive/controls/lib/planner.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index d75f9db383..5262f480a7 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -85,7 +85,7 @@ class LongControl(): v_ego_pid = max(CS.vEgo, MIN_CAN_SPEED) # Without this we get jumps, CAN bus reports 0 when speed < 0.3 - if self.long_control_state == LongCtrlState.off: + if self.long_control_state == LongCtrlState.off or CS.gasPressed: self.v_pid = v_ego_pid self.pid.reset() output_gb = 0. diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index 88c4d694aa..553e5bb6fa 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -129,7 +129,7 @@ class Planner(): following = lead_1.status and lead_1.dRel < 45.0 and lead_1.vLeadK > v_ego and lead_1.aLeadK > 0.0 # Calculate speed for normal cruise control - if enabled and not self.first_loop: + if enabled and not self.first_loop and not sm['carState'].gasPressed: accel_limits = [float(x) for x in calc_cruise_accel_limits(v_ego, following)] jerk_limits = [min(-0.1, accel_limits[0]), max(0.1, accel_limits[1])] # TODO: make a separate lookup for jerk tuning accel_limits_turns = limit_accel_in_turns(v_ego, sm['carState'].steeringAngle, accel_limits, self.CP) From c70700758d9e3227a157d2e9fdcb9d3204b433c2 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 20 Jul 2020 17:10:08 +0200 Subject: [PATCH 481/656] Speedup URLFile (#1888) * add parallel download support to URLFile * make python 3.8 happy * Fix chunk size * Automatic number of threads * No daemon threads in unlogger * Cache length * dont touch old filereader * Remove debug info * remove debug script * Ignore type --- tools/lib/filereader.py | 8 ++- {common => tools/lib}/url_file.py | 0 tools/lib/url_file_parallel.py | 81 +++++++++++++++++++++++++++++++ tools/replay/unlogger.py | 3 -- 4 files changed, 88 insertions(+), 4 deletions(-) rename {common => tools/lib}/url_file.py (100%) create mode 100644 tools/lib/url_file_parallel.py diff --git a/tools/lib/filereader.py b/tools/lib/filereader.py index c68462a08c..826bce5fdf 100644 --- a/tools/lib/filereader.py +++ b/tools/lib/filereader.py @@ -1,4 +1,10 @@ -from common.url_file import URLFile +import os + +if "COMMA_PARALLEL_DOWNLOADS" in os.environ: + from tools.lib.url_file_parallel import URLFileParallel as URLFile +else: + from tools.lib.url_file import URLFile # type: ignore + def FileReader(fn, debug=False): if fn.startswith("http://") or fn.startswith("https://"): diff --git a/common/url_file.py b/tools/lib/url_file.py similarity index 100% rename from common/url_file.py rename to tools/lib/url_file.py diff --git a/tools/lib/url_file_parallel.py b/tools/lib/url_file_parallel.py new file mode 100644 index 0000000000..f6dc37a3b4 --- /dev/null +++ b/tools/lib/url_file_parallel.py @@ -0,0 +1,81 @@ +# pylint: skip-file + +import os +import pycurl +from tools.lib.url_file import URLFile +from io import BytesIO +from tenacity import retry, wait_random_exponential, stop_after_attempt + +from multiprocessing import Pool + + +class URLFileParallel(URLFile): + def __init__(self, url, debug=False): + self._length = None + self._url = url + self._pos = 0 + self._local_file = None + + def get_curl(self): + curl = pycurl.Curl() + curl.setopt(pycurl.NOSIGNAL, 1) + curl.setopt(pycurl.TIMEOUT_MS, 500000) + curl.setopt(pycurl.FOLLOWLOCATION, True) + return curl + + @retry(wait=wait_random_exponential(multiplier=1, max=5), stop=stop_after_attempt(3), reraise=True) + def get_length(self): + if self._length is not None: + return self._length + + c = self.get_curl() + c.setopt(pycurl.URL, self._url) + c.setopt(c.NOBODY, 1) + c.perform() + + length = int(c.getinfo(c.CONTENT_LENGTH_DOWNLOAD)) + self._length = length + return length + + @retry(wait=wait_random_exponential(multiplier=1, max=5), stop=stop_after_attempt(3), reraise=True) + def download_chunk(self, start, end=None): + if end is None: + trange = f'bytes={start}-' + else: + trange = f'bytes={start}-{end}' + + dats = BytesIO() + c = self.get_curl() + c.setopt(pycurl.URL, self._url) + c.setopt(pycurl.WRITEDATA, dats) + c.setopt(pycurl.HTTPHEADER, ["Range: " + trange, "Connection: keep-alive"]) + c.perform() + + response_code = c.getinfo(pycurl.RESPONSE_CODE) + if response_code != 206 and response_code != 200: + raise Exception("Error {} ({}): {}".format(response_code, self._url, repr(dats.getvalue())[:500])) + + return dats.getvalue() + + def read(self, ll=None): + start = self._pos + end = None if ll is None else self._pos + ll - 1 + max_threads = int(os.environ.get("COMMA_PARALLEL_DOWNLOADS", "0")) + + end = self.get_length() if end is None else end + threads = min((end - start) // (512 * 1024), max_threads) # At least 512k per thread + + if threads > 1: + chunk_size = (end - start) // threads + chunks = [ + (start + chunk_size * i, + start + chunk_size * (i + 1) - 1 if i != threads - 1 else end) + for i in range(threads)] + + with Pool(threads) as pool: + ret = b"".join(pool.starmap(self.download_chunk, chunks)) + else: + ret = self.download_chunk(start, end) + + self._pos += len(ret) + return ret diff --git a/tools/replay/unlogger.py b/tools/replay/unlogger.py index eebfe28203..2cef80b770 100755 --- a/tools/replay/unlogger.py +++ b/tools/replay/unlogger.py @@ -413,9 +413,6 @@ def main(argv): args=(command_address, forward_commands_address, data_address, args.realtime, _get_address_mapping(args), args.publish_time_length, args.bind_early, args.no_loop)) - for p in subprocesses.values(): - p.daemon = True - subprocesses["data"].start() subprocesses["control"].start() From 2189fe8741b635d8394d55dee28959425cfd5ad0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 20 Jul 2020 11:47:26 -0700 Subject: [PATCH 482/656] bump to 0.7.8 --- selfdrive/common/version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index c9fc2a6ec5..ad6f4b6d7a 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.7.7" +#define COMMA_VERSION "0.7.8" From ede5b632b58c55e4ff003f948efae07fe03c2280 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 20 Jul 2020 13:59:10 -0700 Subject: [PATCH 483/656] fix tested branch detection --- selfdrive/version.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/version.py b/selfdrive/version.py index 02416a90a0..0999e7511d 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -60,7 +60,7 @@ try: if (origin is not None) and (branch is not None): comma_remote = origin.startswith('git@github.com:commaai') or origin.startswith('https://github.com/commaai') - tested_branch = branch in ['devel', 'release2-staging', 'dashcam-staging', 'release2', 'dashcam'] + tested_branch = get_git_branch() in ['devel', 'release2-staging', 'dashcam-staging', 'release2', 'dashcam'] dirty = not comma_remote dirty = dirty or ('master' in branch) From 2052bd69f1ebb5133869f47cfeed60d63962138c Mon Sep 17 00:00:00 2001 From: s70160 <67191334+s70160@users.noreply.github.com> Date: Tue, 21 Jul 2020 05:10:21 +0800 Subject: [PATCH 484/656] Update values.py (#1824) CAR.IONIQ_EV_LTD: [{ 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576:8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1173: 8, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 }], --- selfdrive/car/hyundai/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index b993d62055..9f2cd78708 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -113,6 +113,9 @@ FINGERPRINTS = { }], CAR.IONIQ_EV_LTD: [{ 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1425: 2, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1507: 8, 1535: 8 + }, + { + 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576:8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1173: 8, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 }], CAR.IONIQ: [{ 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 From 2d4f0c49fa15c423be2ce25716fbc9c9e9c4f2b1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 20 Jul 2020 15:41:57 -0700 Subject: [PATCH 485/656] Revert "Update values.py (#1824)" This reverts commit 2052bd69f1ebb5133869f47cfeed60d63962138c. --- selfdrive/car/hyundai/values.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 9f2cd78708..b993d62055 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -113,9 +113,6 @@ FINGERPRINTS = { }], CAR.IONIQ_EV_LTD: [{ 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1425: 2, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1507: 8, 1535: 8 - }, - { - 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576:8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1173: 8, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 }], CAR.IONIQ: [{ 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 From da5dc7693edc12dd281ce365a655dab56fb62494 Mon Sep 17 00:00:00 2001 From: Andre Volmensky Date: Tue, 21 Jul 2020 08:30:40 +0900 Subject: [PATCH 486/656] Nissan: Tweaking steeringPressed/LKAS_MAX_TORQUE (#1865) * Tweaking steeringPressed/LKAS_MAX_TORQUE * Update ref commit --- selfdrive/car/nissan/carcontroller.py | 8 ++++++-- selfdrive/car/nissan/carstate.py | 7 ++++++- selfdrive/car/nissan/values.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 4 files changed, 14 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/nissan/carcontroller.py b/selfdrive/car/nissan/carcontroller.py index 5d988cb935..5838d67ae3 100644 --- a/selfdrive/car/nissan/carcontroller.py +++ b/selfdrive/car/nissan/carcontroller.py @@ -2,7 +2,7 @@ from cereal import car from common.numpy_fast import clip, interp from selfdrive.car.nissan import nissancan from opendbc.can.packer import CANPacker -from selfdrive.car.nissan.values import CAR +from selfdrive.car.nissan.values import CAR, STEER_THRESHOLD # Steer angle limits ANGLE_DELTA_BP = [0., 5., 15.] @@ -53,7 +53,11 @@ class CarController(): else: # Scale max torque based on how much torque the driver is applying to the wheel self.lkas_max_torque = max( - 0, LKAS_MAX_TORQUE - 0.4 * abs(CS.out.steeringTorque)) + # Scale max torque down to half LKAX_MAX_TORQUE as a minimum + LKAS_MAX_TORQUE * 0.5, + # Start scaling torque at STEER_THRESHOLD + LKAS_MAX_TORQUE - 0.6 * max(0, abs(CS.out.steeringTorque) - STEER_THRESHOLD) + ) else: apply_angle = CS.out.steeringAngle diff --git a/selfdrive/car/nissan/carstate.py b/selfdrive/car/nissan/carstate.py index d43db51b6b..f2076183d9 100644 --- a/selfdrive/car/nissan/carstate.py +++ b/selfdrive/car/nissan/carstate.py @@ -1,4 +1,5 @@ import copy +from collections import deque from cereal import car from opendbc.can.can_define import CANDefine from selfdrive.car.interfaces import CarStateBase @@ -6,12 +7,14 @@ from selfdrive.config import Conversions as CV from opendbc.can.parser import CANParser from selfdrive.car.nissan.values import CAR, DBC, STEER_THRESHOLD +TORQUE_SAMPLES = 12 class CarState(CarStateBase): def __init__(self, CP): super().__init__(CP) can_define = CANDefine(DBC[CP.carFingerprint]['pt']) + self.steeringTorqueSamples = deque(TORQUE_SAMPLES*[0], TORQUE_SAMPLES) self.shifter_values = can_define.dv["GEARBOX"]["GEAR_SHIFTER"] def update(self, cp, cp_adas, cp_cam): @@ -60,7 +63,9 @@ class CarState(CarStateBase): ret.cruiseState.speed = speed * conversion ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD + self.steeringTorqueSamples.append(ret.steeringTorque) + # Filtering driver torque to prevent steeringPressed false positives + ret.steeringPressed = bool(abs(sum(self.steeringTorqueSamples) / TORQUE_SAMPLES) > STEER_THRESHOLD) ret.steeringAngle = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 4271b7f0e5..0630a8cb94 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -2,7 +2,7 @@ from selfdrive.car import dbc_dict -STEER_THRESHOLD = 1.75 +STEER_THRESHOLD = 1.0 class CAR: XTRAIL = "NISSAN X-TRAIL 2017" diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 5ba0101a8d..39ccd58aae 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -d0b7760731f1e310c7770dafee215ed2dee0d92d \ No newline at end of file +e3ccebfa372cc2e85b742e86567899beb1233ced From 85000dd5cc4a5171789f970689dfb32dc31be4a1 Mon Sep 17 00:00:00 2001 From: Chris Souers Date: Tue, 21 Jul 2020 06:06:21 -0400 Subject: [PATCH 487/656] Add 2020 Insight FW (#1879) --- README.md | 2 +- selfdrive/car/honda/values.py | 13 +++++++++++++ 2 files changed, 14 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 052828cf17..d7bdad27b5 100644 --- a/README.md +++ b/README.md @@ -76,7 +76,7 @@ Supported Cars | Honda | CR-V Hybrid 2017-2019 | Honda Sensing | Stock | 0mph | 12mph | | Honda | Fit 2018-19 | Honda Sensing | openpilot | 25mph1 | 12mph | | Honda | HR-V 2019 | Honda Sensing | openpilot | 25mph1 | 12mph | -| Honda | Insight 2019 | Honda Sensing | Stock | 0mph | 3mph | +| Honda | Insight 2019-20 | Honda Sensing | Stock | 0mph | 3mph | | Honda | Odyssey 2018-20 | Honda Sensing | openpilot | 25mph1 | 0mph | | Honda | Passport 2019 | All | openpilot | 25mph1 | 12mph | | Honda | Pilot 2016-18 | Honda Sensing | openpilot | 25mph1 | 12mph | diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 32bc2d3783..803ded8a06 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -885,10 +885,23 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x18dab5f1, None): [ b'36161-TXM-A050\x00\x00', + b'36161-TXM-A060\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ b'77959-TXM-A230\x00\x00', ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TXM-A040\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TWA-A910\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TXM-A020\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TXM-A020\x00\x00', + ], }, CAR.HRV: { (Ecu.gateway, 0x18daeff1, None): [b'38897-T7A-A010\x00\x00'], From 4e14ef470c3d91961cdfc981d5dc70e69c250c4f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 21 Jul 2020 13:47:42 +0200 Subject: [PATCH 488/656] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index 9ee0069ecc..993f0cc650 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 9ee0069ecc01c154a0b77130f0da02b10cacbdfa +Subproject commit 993f0cc650a1cc4915de8cade1b278acf57f5483 From 825821f010db63c3498d3730069f3eac08ace789 Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Tue, 21 Jul 2020 08:41:45 -0700 Subject: [PATCH 489/656] Honda CRV BSM alert from B-CAN (#1867) --- release/files_common | 1 + selfdrive/car/__init__.py | 4 ++-- selfdrive/car/honda/carstate.py | 22 +++++++++++++++++++++- selfdrive/car/honda/interface.py | 8 +++++--- selfdrive/car/honda/values.py | 2 +- selfdrive/car/interfaces.py | 5 +++++ 6 files changed, 35 insertions(+), 7 deletions(-) diff --git a/release/files_common b/release/files_common index a457994112..f06e6db317 100644 --- a/release/files_common +++ b/release/files_common @@ -510,6 +510,7 @@ opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc opendbc/honda_civic_sedan_16_diesel_2019_can_generated.dbc opendbc/honda_crv_touring_2016_can_generated.dbc opendbc/honda_crv_ex_2017_can_generated.dbc +opendbc/honda_crv_ex_2017_body_generated.dbc opendbc/honda_crv_executive_2016_can_generated.dbc opendbc/honda_crv_hybrid_2019_can_generated.dbc opendbc/honda_fit_ex_2018_can_generated.dbc diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 09edb03156..7701f90a6d 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -40,8 +40,8 @@ def scale_tire_stiffness(mass, wheelbase, center_to_front, tire_stiffness_factor return tire_stiffness_front, tire_stiffness_rear -def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None): - return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc} +def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None, body_dbc=None): + return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc, 'body': body_dbc} def apply_std_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS): diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 4845e482f8..4aaa98aa66 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -172,7 +172,7 @@ class CarState(CarStateBase): self.v_cruise_pcm_prev = 0 self.cruise_mode = 0 - def update(self, cp, cp_cam): + def update(self, cp, cp_cam, cp_body): ret = car.CarState.new_message() # car params @@ -322,6 +322,12 @@ class CarState(CarStateBase): self.stock_hud = cp_cam.vl["ACC_HUD"] self.stock_brake = cp_cam.vl["BRAKE_COMMAND"] + if self.CP.carFingerprint in (CAR.CRV_5G, ): + # BSM messages are on B-CAN, requires a panda forwarding B-CAN messages to CAN 0 + # more info here: https://github.com/commaai/openpilot/pull/1867 + ret.leftBlindspot = cp_body.vl["BSM_STATUS_LEFT"]['BSM_ALERT'] == 1 + ret.rightBlindspot = cp_body.vl["BSM_STATUS_RIGHT"]['BSM_ALERT'] == 1 + return ret @staticmethod @@ -354,3 +360,17 @@ class CarState(CarStateBase): bus_cam = 1 if CP.carFingerprint in HONDA_BOSCH and not CP.isPandaBlack else 2 return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, bus_cam) + + @staticmethod + def get_body_can_parser(CP): + signals = [] + checks = [] + + if CP.carFingerprint == CAR.CRV_5G: + signals += [("BSM_ALERT", "BSM_STATUS_RIGHT", 0), + ("BSM_ALERT", "BSM_STATUS_LEFT", 0)] + + bus_body = 0 # B-CAN is forwarded to ACC-CAN radar side (CAN 0 on fake ethernet port) + return CANParser(DBC[CP.carFingerprint]['body'], signals, checks, bus_body) + + return None diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 7468e06353..ac8bfe3b9f 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -83,7 +83,7 @@ class CarInterface(CarInterfaceBase): self.compute_gb = compute_gb_honda @staticmethod - def compute_gb(accel, speed): + def compute_gb(accel, speed): # pylint: disable=method-hidden raise NotImplementedError @staticmethod @@ -426,10 +426,12 @@ class CarInterface(CarInterfaceBase): # ******************* do can recv ******************* self.cp.update_strings(can_strings) self.cp_cam.update_strings(can_strings) + if self.cp_body: + self.cp_body.update_strings(can_strings) - ret = self.CS.update(self.cp, self.cp_cam) + ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) - ret.canValid = self.cp.can_valid and self.cp_cam.can_valid + ret.canValid = self.cp.can_valid and self.cp_cam.can_valid and (self.cp_body is None or self.cp_body.can_valid) ret.yawRate = self.VM.yaw_rate(ret.steeringAngle * CV.DEG_TO_RAD, ret.vEgo) # FIXME: read sendcan for brakelights brakelights_threshold = 0.02 if self.CS.CP.carFingerprint == CAR.CIVIC else 0.1 diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 803ded8a06..c2aca11a21 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -922,7 +922,7 @@ DBC = { CAR.CIVIC_BOSCH: dbc_dict('honda_civic_hatchback_ex_2017_can_generated', None), CAR.CIVIC_BOSCH_DIESEL: dbc_dict('honda_civic_sedan_16_diesel_2019_can_generated', None), CAR.CRV: dbc_dict('honda_crv_touring_2016_can_generated', 'acura_ilx_2016_nidec'), - CAR.CRV_5G: dbc_dict('honda_crv_ex_2017_can_generated', None), + CAR.CRV_5G: dbc_dict('honda_crv_ex_2017_can_generated', None, body_dbc='honda_crv_ex_2017_body_generated'), CAR.CRV_EU: dbc_dict('honda_crv_executive_2016_can_generated', 'acura_ilx_2016_nidec'), CAR.CRV_HYBRID: dbc_dict('honda_crv_hybrid_2019_can_generated', None), CAR.FIT: dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index c73aa93847..287dc979bf 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -27,6 +27,7 @@ class CarInterfaceBase(): self.CS = CarState(CP) self.cp = self.CS.get_can_parser(CP) self.cp_cam = self.CS.get_cam_can_parser(CP) + self.cp_body = self.CS.get_body_can_parser(CP) self.CC = None if CarController is not None: @@ -175,3 +176,7 @@ class CarStateBase: @staticmethod def get_cam_can_parser(CP): return None + + @staticmethod + def get_body_can_parser(CP): + return None From 95b0c69c12cb859025b77d1ba9ed9433c78f1e9f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 21 Jul 2020 21:15:09 +0200 Subject: [PATCH 490/656] update pipfile.lock (#1896) * update pipfile * matrix is deprecated * Numpy almost equal * sympy 1.6 --- Pipfile | 2 +- Pipfile.lock | 1022 +++++++++++---------- common/kalman/simple_kalman_old.py | 2 +- common/kalman/tests/test_simple_kalman.py | 20 +- 4 files changed, 546 insertions(+), 500 deletions(-) diff --git a/Pipfile b/Pipfile index 5a0ef77d4e..a647cead9e 100644 --- a/Pipfile +++ b/Pipfile @@ -92,7 +92,7 @@ requests = "*" setproctitle = "*" six = "*" smbus2 = "*" -sympy = "*" +sympy = "!=1.6.1" tqdm = "*" Cython = "*" PyYAML = "*" diff --git a/Pipfile.lock b/Pipfile.lock index 138e3c42c3..1d5027371a 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "b65256d0b4dedee753a145abd1aff2f81d98ddb4015f69baa8ccb374121bb4c4" + "sha256": "484ec3309452d56769b732b3c5d3d49023fe696220c07f81862b8bbf8283cedf" }, "pipfile-spec": 6, "requires": { @@ -34,10 +34,10 @@ }, "certifi": { "hashes": [ - "sha256:5ad7e9a056d25ffa5082862e36f119f7f7cec6457fa07ee2f8c339814b80c9b1", - "sha256:9cd41137dc19af6a5e03b630eefe7d1f458d964d406342dd3edf625839b944cc" + "sha256:5930595817496dd21bb8dc35dad090f1c2cd0adfaf21204bf6732ca5d8ee34d3", + "sha256:8fc0819f1f30ba15bdb34cceffb9ef04d99f420f68eb75d901e9560b8749fc41" ], - "version": "==2020.4.5.2" + "version": "==2020.6.20" }, "cffi": { "hashes": [ @@ -100,28 +100,28 @@ }, "cryptography": { "hashes": [ - "sha256:091d31c42f444c6f519485ed528d8b451d1a0c7bf30e8ca583a0cac44b8a0df6", - "sha256:18452582a3c85b96014b45686af264563e3e5d99d226589f057ace56196ec78b", - "sha256:1dfa985f62b137909496e7fc182dac687206d8d089dd03eaeb28ae16eec8e7d5", - "sha256:1e4014639d3d73fbc5ceff206049c5a9a849cefd106a49fa7aaaa25cc0ce35cf", - "sha256:22e91636a51170df0ae4dcbd250d318fd28c9f491c4e50b625a49964b24fe46e", - "sha256:3b3eba865ea2754738616f87292b7f29448aec342a7c720956f8083d252bf28b", - "sha256:651448cd2e3a6bc2bb76c3663785133c40d5e1a8c1a9c5429e4354201c6024ae", - "sha256:726086c17f94747cedbee6efa77e99ae170caebeb1116353c6cf0ab67ea6829b", - "sha256:844a76bc04472e5135b909da6aed84360f522ff5dfa47f93e3dd2a0b84a89fa0", - "sha256:88c881dd5a147e08d1bdcf2315c04972381d026cdb803325c03fe2b4a8ed858b", - "sha256:96c080ae7118c10fcbe6229ab43eb8b090fccd31a09ef55f83f690d1ef619a1d", - "sha256:a0c30272fb4ddda5f5ffc1089d7405b7a71b0b0f51993cb4e5dbb4590b2fc229", - "sha256:bb1f0281887d89617b4c68e8db9a2c42b9efebf2702a3c5bf70599421a8623e3", - "sha256:c447cf087cf2dbddc1add6987bbe2f767ed5317adb2d08af940db517dd704365", - "sha256:c4fd17d92e9d55b84707f4fd09992081ba872d1a0c610c109c18e062e06a2e55", - "sha256:d0d5aeaedd29be304848f1c5059074a740fa9f6f26b84c5b63e8b29e73dfc270", - "sha256:daf54a4b07d67ad437ff239c8a4080cfd1cc7213df57d33c97de7b4738048d5e", - "sha256:e993468c859d084d5579e2ebee101de8f5a27ce8e2159959b6673b418fd8c785", - "sha256:f118a95c7480f5be0df8afeb9a11bd199aa20afab7a96bcf20409b411a3a85f0" - ], - "index": "pypi", - "version": "==2.9.2" + "sha256:0c608ff4d4adad9e39b5057de43657515c7da1ccb1807c3a27d4cf31fc923b4b", + "sha256:0cbfed8ea74631fe4de00630f4bb592dad564d57f73150d6f6796a24e76c76cd", + "sha256:124af7255ffc8e964d9ff26971b3a6153e1a8a220b9a685dc407976ecb27a06a", + "sha256:384d7c681b1ab904fff3400a6909261cae1d0939cc483a68bdedab282fb89a07", + "sha256:45741f5499150593178fc98d2c1a9c6722df88b99c821ad6ae298eff0ba1ae71", + "sha256:4b9303507254ccb1181d1803a2080a798910ba89b1a3c9f53639885c90f7a756", + "sha256:4d355f2aee4a29063c10164b032d9fa8a82e2c30768737a2fd56d256146ad559", + "sha256:51e40123083d2f946794f9fe4adeeee2922b581fa3602128ce85ff813d85b81f", + "sha256:8713ddb888119b0d2a1462357d5946b8911be01ddbf31451e1d07eaa5077a261", + "sha256:8e924dbc025206e97756e8903039662aa58aa9ba357d8e1d8fc29e3092322053", + "sha256:8ecef21ac982aa78309bb6f092d1677812927e8b5ef204a10c326fc29f1367e2", + "sha256:8ecf9400d0893836ff41b6f977a33972145a855b6efeb605b49ee273c5e6469f", + "sha256:9367d00e14dee8d02134c6c9524bb4bd39d4c162456343d07191e2a0b5ec8b3b", + "sha256:a09fd9c1cca9a46b6ad4bea0a1f86ab1de3c0c932364dbcf9a6c2a5eeb44fa77", + "sha256:ab49edd5bea8d8b39a44b3db618e4783ef84c19c8b47286bf05dfdb3efb01c83", + "sha256:bea0b0468f89cdea625bb3f692cd7a4222d80a6bdafd6fb923963f2b9da0e15f", + "sha256:bec7568c6970b865f2bcebbe84d547c52bb2abadf74cefce396ba07571109c67", + "sha256:ce82cc06588e5cbc2a7df3c8a9c778f2cb722f56835a23a68b5a7264726bb00c", + "sha256:dea0ba7fe6f9461d244679efa968d215ea1f989b9c1957d7f10c21e5c7c09ad6" + ], + "index": "pypi", + "version": "==3.0" }, "cysignals": { "hashes": [ @@ -132,42 +132,42 @@ }, "cython": { "hashes": [ - "sha256:0754ec9d45518d0dbb5da72db2c8b063d40c4c51779618c68431054de179387f", - "sha256:0bb201124f67b8d5e6a3e7c02257ca56a90204611971ecca76c02897096f097d", - "sha256:0f3488bf2a9e049d1907d35ad8834f542f8c03d858d1bca6d0cbc06b719163e0", - "sha256:1024714b0f7829b0f712db9cebec92c2782b1f42409b8575cacc340aa438d4ba", - "sha256:10b6d2e2125169158128b7f11dad8bb0d8f5fba031d5d4f8492f3afbd06491d7", - "sha256:16ed0260d031d90dda43997e9b0f0eebc3cf18e6ece91cad7b0fb17cd4bfb29b", - "sha256:22d91af5fc2253f717a1b80b8bb45acb655f643611983fd6f782b9423f8171c7", - "sha256:2d84e8d2a0c698c1bce7c2a4677f9f03b076e9f0af7095947ecd2a900ffceea5", - "sha256:34dd57f5ac5a0e3d53da964994fc1b7e7ee3f86172d7a1f0bde8a1f90739e04d", - "sha256:384582b5024007dfdabc9753e3e0f85d61837b0103b0ee3f8acf04a4bcfad175", - "sha256:4473f169d6dd02174eb76396cb38ce469f377c08b21965ddf4f88bbbebd5816e", - "sha256:57f32d1095ad7fad1e7f2ff6e8c6a7197fa532c8e6f4d044ff69212e0bf05461", - "sha256:5dfe519e400a1672a3ac5bdfb5e957a9c14c52caafb01f4a923998ec9ae77736", - "sha256:60def282839ed81a2ffae29d2df0a6777fd74478c6e82c6c3f4b54e698b9d11c", - "sha256:7089fb2be9a9869b9aa277bc6de401928954ce70e139c3cf9b244ae5f490b8f2", - "sha256:714b8926a84e3e39c5278e43fb8823598db82a4b015cff263b786dc609a5e7d6", - "sha256:7352b88f2213325c1e111561496a7d53b0326e7f07e6f81f9b8b21420e40851c", - "sha256:809f0a3f647052c4bcbc34a15f53a5dab90de1a83ebd77add37ed5d3e6ee5d97", - "sha256:8598b09f7973ccb15c03b21d3185dc129ae7c60d0a6caf8176b7099a4b83483e", - "sha256:8dc68f93b257718ea0e2bc9be8e3c61d70b6e49ab82391125ba0112a30a21025", - "sha256:9bfd42c1d40aa26bf76186cba0d89be66ba47e36fa7ea56d71f377585a53f7c4", - "sha256:a21cb3423acd6dbf383c9e41e8e60c93741987950434c85145864458d30099f3", - "sha256:a49d0f5c55ad0f4aacad32f058a71d0701cb8936d6883803e50698fa04cac8d2", - "sha256:a985a7e3c7f1663af398938029659a4381cfe9d1bd982cf19c46b01453e81775", - "sha256:b3233341c3fe352b1090168bd087686880b582b635d707b2c8f5d4f1cc1fa533", - "sha256:b32965445b8dbdc36c69fba47e024060f9b39b1b4ceb816da5028eea01924505", - "sha256:b553473c31297e4ca77fbaea2eb2329889d898c03941d90941679247c17e38fb", - "sha256:b56c02f14f1708411d95679962b742a1235d33a23535ce4a7f75425447701245", - "sha256:b7bb0d54ff453c7516d323c3c78b211719f39a506652b79b7e85ba447d5fa9e7", - "sha256:c5df2c42d4066cda175cd4d075225501e1842cfdbdaeeb388eb7685c367cc3ce", - "sha256:c5e29333c9e20df384645902bed7a67a287b979da1886c8f10f88e57b69e0f4b", - "sha256:d0b445def03b4cd33bd2d1ae6fbbe252b6d1ef7077b3b5ba3f2c698a190d26e5", - "sha256:d490a54814b69d814b157ac86ada98c15fd77fabafc23732818ed9b9f1f0af80" - ], - "index": "pypi", - "version": "==0.29.20" + "sha256:0ac10bf476476a9f7ef61ec6e44c280ef434473124ad31d3132b720f7b0e8d2a", + "sha256:0e25c209c75df8785480dcef85db3d36c165dbc0f4c503168e8763eb735704f2", + "sha256:171b9f70ceafcec5852089d0f9c1e75b0d554f46c882cd4e2e4acaba9bd7d148", + "sha256:23f3a00b843a19de8bb4468b087db5b413a903213f67188729782488d67040e0", + "sha256:2922e3031ba9ebbe7cb9200b585cc33b71d66023d78450dcb883f824f4969371", + "sha256:31c71a615f38401b0dc1f2a5a9a6c421ffd8908c4cd5bbedc4014c1b876488e8", + "sha256:473df5d5e400444a36ed81c6596f56a5b52a3481312d0a48d68b777790f730ae", + "sha256:497841897942f734b0abc2dead2d4009795ee992267a70a23485fd0e937edc0b", + "sha256:539e59949aab4955c143a468810123bf22d3e8556421e1ce2531ed4893914ca0", + "sha256:540b3bee0711aac2e99bda4fa0a46dbcd8c74941666bfc1ef9236b1a64eeffd9", + "sha256:57ead89128dee9609119c93d3926c7a2add451453063147900408a50144598c6", + "sha256:5c4276fdcbccdf1e3c1756c7aeb8395e9a36874fa4d30860e7694f43d325ae13", + "sha256:5da187bebe38030325e1c0b5b8a804d489410be2d384c0ef3ba39493c67eb51e", + "sha256:5e545a48f919e40079b0efe7b0e081c74b96f9ef25b9c1ff4cdbd95764426b58", + "sha256:603b9f1b8e93e8b494d3e89320c410679e21018e48b6cbc77280f5db71f17dc0", + "sha256:695a6bcaf9e12b1e471dfce96bbecf22a1487adc2ac6106b15960a2b51b97f5d", + "sha256:715294cd2246b39a8edca464a8366eb635f17213e4a6b9e74e52d8b877a8cb63", + "sha256:856c7fb31d247ce713d60116375e1f8153d0291ab5e92cca7d8833a524ba9991", + "sha256:8c6e25e9cc4961bb2abb1777c6fa9d0fa2d9b014beb3276cebe69996ff162b78", + "sha256:9207fdedc7e789a3dcaca628176b80c82fbed9ae0997210738cbb12536a56699", + "sha256:93f5fed1c9445fb7afe20450cdaf94b0e0356d47cc75008105be89c6a2e417b1", + "sha256:9ce5e5209f8406ffc2b058b1293cce7a954911bb7991e623564d489197c9ba30", + "sha256:a0674f246ad5e1571ef29d4c5ec1d6ecabe9e6c424ad0d6fee46b914d5d24d69", + "sha256:b2f9172e4d6358f33ecce6a4339b5960f9f83eab67ea244baa812737793826b7", + "sha256:b8a8a31b9e8860634adbca30fea1d0c7f08e208b3d7611f3e580e5f20992e5d7", + "sha256:b8d8497091c1dc8705d1575c71e908a93b1f127a174b2d472020f3d84263ac28", + "sha256:c4b78356074fcaac04ecb4de289f11d506e438859877670992ece11f9c90f37b", + "sha256:c541b2b49c6638f2b5beb9316726db84a8d1c132bf31b942dae1f9c7f6ad3b92", + "sha256:c8435959321cf8aec867bbad54b83b7fb8343204b530d85d9ea7a1f5329d5ac2", + "sha256:ccb77faeaad99e99c6c444d04862c6cf604204fe0a07d4c8f9cbf2c9012d7d5a", + "sha256:e272ed97d20b026f4f25a012b25d7d7672a60e4f72b9ca385239d693cd91b2d5", + "sha256:e57acb89bd55943c8d8bf813763d20b9099cc7165c0f16b707631a7654be9cad", + "sha256:e93acd1f603a0c1786e0841f066ae7cef014cf4750e3cd06fd03cfdf46361419" + ], + "index": "pypi", + "version": "==0.29.21" }, "flake8": { "hashes": [ @@ -202,11 +202,11 @@ }, "idna": { "hashes": [ - "sha256:7588d1c14ae4c77d74036e8c22ff447b26d0fde8f007354fd48a7814db15b7cb", - "sha256:a068a21ceac8a4d63dbfd964670474107f541babbd2250d61922f029858365fa" + "sha256:b307872f855b18632ce0c21c5e45be78c0ea7ae4c15c828c20788b26921eb3f6", + "sha256:b97d804b1e9b523befed77c48dacec60e6dcb0b5391d57af6a65a312a90648c0" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==2.9" + "version": "==2.10" }, "isort": { "hashes": [ @@ -342,76 +342,84 @@ }, "numpy": { "hashes": [ - "sha256:0172304e7d8d40e9e49553901903dc5f5a49a703363ed756796f5808a06fc233", - "sha256:34e96e9dae65c4839bd80012023aadd6ee2ccb73ce7fdf3074c62f301e63120b", - "sha256:3676abe3d621fc467c4c1469ee11e395c82b2d6b5463a9454e37fe9da07cd0d7", - "sha256:3dd6823d3e04b5f223e3e265b4a1eae15f104f4366edd409e5a5e413a98f911f", - "sha256:4064f53d4cce69e9ac613256dc2162e56f20a4e2d2086b1956dd2fcf77b7fac5", - "sha256:4674f7d27a6c1c52a4d1aa5f0881f1eff840d2206989bae6acb1c7668c02ebfb", - "sha256:7d42ab8cedd175b5ebcb39b5208b25ba104842489ed59fbb29356f671ac93583", - "sha256:965df25449305092b23d5145b9bdaeb0149b6e41a77a7d728b1644b3c99277c1", - "sha256:9c9d6531bc1886454f44aa8f809268bc481295cf9740827254f53c30104f074a", - "sha256:a78e438db8ec26d5d9d0e584b27ef25c7afa5a182d1bf4d05e313d2d6d515271", - "sha256:a7acefddf994af1aeba05bbbafe4ba983a187079f125146dc5859e6d817df824", - "sha256:a87f59508c2b7ceb8631c20630118cc546f1f815e034193dc72390db038a5cb3", - "sha256:ac792b385d81151bae2a5a8adb2b88261ceb4976dbfaaad9ce3a200e036753dc", - "sha256:b03b2c0badeb606d1232e5f78852c102c0a7989d3a534b3129e7856a52f3d161", - "sha256:b39321f1a74d1f9183bf1638a745b4fd6fe80efbb1f6b32b932a588b4bc7695f", - "sha256:cae14a01a159b1ed91a324722d746523ec757357260c6804d11d6147a9e53e3f", - "sha256:cd49930af1d1e49a812d987c2620ee63965b619257bd76eaaa95870ca08837cf", - "sha256:e15b382603c58f24265c9c931c9a45eebf44fe2e6b4eaedbb0d025ab3255228b", - "sha256:e91d31b34fc7c2c8f756b4e902f901f856ae53a93399368d9a0dc7be17ed2ca0", - "sha256:ef627986941b5edd1ed74ba89ca43196ed197f1a206a3f18cc9faf2fb84fd675", - "sha256:f718a7949d1c4f622ff548c572e0c03440b49b9531ff00e4ed5738b459f011e8" - ], - "index": "pypi", - "version": "==1.18.5" + "sha256:13af0184177469192d80db9bd02619f6fa8b922f9f327e077d6f2a6acb1ce1c0", + "sha256:26a45798ca2a4e168d00de75d4a524abf5907949231512f372b217ede3429e98", + "sha256:26f509450db547e4dfa3ec739419b31edad646d21fb8d0ed0734188b35ff6b27", + "sha256:30a59fb41bb6b8c465ab50d60a1b298d1cd7b85274e71f38af5a75d6c475d2d2", + "sha256:33c623ef9ca5e19e05991f127c1be5aeb1ab5cdf30cb1c5cf3960752e58b599b", + "sha256:356f96c9fbec59974a592452ab6a036cd6f180822a60b529a975c9467fcd5f23", + "sha256:3c40c827d36c6d1c3cf413694d7dc843d50997ebffbc7c87d888a203ed6403a7", + "sha256:4d054f013a1983551254e2379385e359884e5af105e3efe00418977d02f634a7", + "sha256:63d971bb211ad3ca37b2adecdd5365f40f3b741a455beecba70fd0dde8b2a4cb", + "sha256:658624a11f6e1c252b2cd170d94bf28c8f9410acab9f2fd4369e11e1cd4e1aaf", + "sha256:76766cc80d6128750075378d3bb7812cf146415bd29b588616f72c943c00d598", + "sha256:7b57f26e5e6ee2f14f960db46bd58ffdca25ca06dd997729b1b179fddd35f5a3", + "sha256:7b852817800eb02e109ae4a9cef2beda8dd50d98b76b6cfb7b5c0099d27b52d4", + "sha256:8cde829f14bd38f6da7b2954be0f2837043e8b8d7a9110ec5e318ae6bf706610", + "sha256:a2e3a39f43f0ce95204beb8fe0831199542ccab1e0c6e486a0b4947256215632", + "sha256:a86c962e211f37edd61d6e11bb4df7eddc4a519a38a856e20a6498c319efa6b0", + "sha256:a8705c5073fe3fcc297fb8e0b31aa794e05af6a329e81b7ca4ffecab7f2b95ef", + "sha256:b6aaeadf1e4866ca0fdf7bb4eed25e521ae21a7947c59f78154b24fc7abbe1dd", + "sha256:be62aeff8f2f054eff7725f502f6228298891fd648dc2630e03e44bf63e8cee0", + "sha256:c2edbb783c841e36ca0fa159f0ae97a88ce8137fb3a6cd82eae77349ba4b607b", + "sha256:cbe326f6d364375a8e5a8ccb7e9cd73f4b2f6dc3b2ed205633a0db8243e2a96a", + "sha256:d34fbb98ad0d6b563b95de852a284074514331e6b9da0a9fc894fb1cdae7a79e", + "sha256:d97a86937cf9970453c3b62abb55a6475f173347b4cde7f8dcdb48c8e1b9952d", + "sha256:dd53d7c4a69e766e4900f29db5872f5824a06827d594427cf1a4aa542818b796", + "sha256:df1889701e2dfd8ba4dc9b1a010f0a60950077fb5242bb92c8b5c7f1a6f2668a", + "sha256:fa1fe75b4a9e18b66ae7f0b122543c42debcf800aaafa0212aaff3ad273c2596" + ], + "index": "pypi", + "version": "==1.19.0" }, "pillow": { "hashes": [ - "sha256:04766c4930c174b46fd72d450674612ab44cca977ebbcc2dde722c6933290107", - "sha256:0e2a3bceb0fd4e0cb17192ae506d5f082b309ffe5fc370a5667959c9b2f85fa3", - "sha256:0f01e63c34f0e1e2580cc0b24e86a5ccbbfa8830909a52ee17624c4193224cd9", - "sha256:12e4bad6bddd8546a2f9771485c7e3d2b546b458ae8ff79621214119ac244523", - "sha256:1f694e28c169655c50bb89a3fa07f3b854d71eb47f50783621de813979ba87f3", - "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", - "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", - "sha256:70e3e0d99a0dcda66283a185f80697a9b08806963c6149c8e6c5f452b2aa59c0", - "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", - "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd", - "sha256:ae2b270f9a0b8822b98655cb3a59cdb1bd54a34807c6c56b76dd2e786c3b7db3", - "sha256:b37bb3bd35edf53125b0ff257822afa6962649995cbdfde2791ddb62b239f891", - "sha256:b532bcc2f008e96fd9241177ec580829dee817b090532f43e54074ecffdcd97f", - "sha256:b67a6c47ed963c709ed24566daa3f95a18f07d3831334da570c71da53d97d088", - "sha256:b943e71c2065ade6fef223358e56c167fc6ce31c50bc7a02dd5c17ee4338e8ac", - "sha256:ccc9ad2460eb5bee5642eaf75a0438d7f8887d484490d5117b98edd7f33118b7", - "sha256:d23e2aa9b969cf9c26edfb4b56307792b8b374202810bd949effd1c6e11ebd6d", - "sha256:eaa83729eab9c60884f362ada982d3a06beaa6cc8b084cf9f76cae7739481dfa", - "sha256:ee94fce8d003ac9fd206496f2707efe9eadcb278d94c271f129ab36aa7181344", - "sha256:f455efb7a98557412dc6f8e463c1faf1f1911ec2432059fa3e582b6000fc90e2", - "sha256:f46e0e024346e1474083c729d50de909974237c72daca05393ee32389dabe457", - "sha256:f54be399340aa602066adb63a86a6a5d4f395adfdd9da2b9a0162ea808c7b276", - "sha256:f784aad988f12c80aacfa5b381ec21fd3f38f851720f652b9f33facc5101cf4d" - ], - "index": "pypi", - "version": "==7.1.2" + "sha256:0295442429645fa16d05bd567ef5cff178482439c9aad0411d3f0ce9b88b3a6f", + "sha256:06aba4169e78c439d528fdeb34762c3b61a70813527a2c57f0540541e9f433a8", + "sha256:09d7f9e64289cb40c2c8d7ad674b2ed6105f55dc3b09aa8e4918e20a0311e7ad", + "sha256:0a80dd307a5d8440b0a08bd7b81617e04d870e40a3e46a32d9c246e54705e86f", + "sha256:1ca594126d3c4def54babee699c055a913efb01e106c309fa6b04405d474d5ae", + "sha256:25930fadde8019f374400f7986e8404c8b781ce519da27792cbe46eabec00c4d", + "sha256:431b15cffbf949e89df2f7b48528be18b78bfa5177cb3036284a5508159492b5", + "sha256:52125833b070791fcb5710fabc640fc1df07d087fc0c0f02d3661f76c23c5b8b", + "sha256:5e51ee2b8114def244384eda1c82b10e307ad9778dac5c83fb0943775a653cd8", + "sha256:612cfda94e9c8346f239bf1a4b082fdd5c8143cf82d685ba2dba76e7adeeb233", + "sha256:6d7741e65835716ceea0fd13a7d0192961212fd59e741a46bbed7a473c634ed6", + "sha256:6edb5446f44d901e8683ffb25ebdfc26988ee813da3bf91e12252b57ac163727", + "sha256:725aa6cfc66ce2857d585f06e9519a1cc0ef6d13f186ff3447ab6dff0a09bc7f", + "sha256:8dad18b69f710bf3a001d2bf3afab7c432785d94fcf819c16b5207b1cfd17d38", + "sha256:94cf49723928eb6070a892cb39d6c156f7b5a2db4e8971cb958f7b6b104fb4c4", + "sha256:97f9e7953a77d5a70f49b9a48da7776dc51e9b738151b22dacf101641594a626", + "sha256:9ad7f865eebde135d526bb3163d0b23ffff365cf87e767c649550964ad72785d", + "sha256:a060cf8aa332052df2158e5a119303965be92c3da6f2d93b6878f0ebca80b2f6", + "sha256:c79f9c5fb846285f943aafeafda3358992d64f0ef58566e23484132ecd8d7d63", + "sha256:c92302a33138409e8f1ad16731568c55c9053eee71bb05b6b744067e1b62380f", + "sha256:d08b23fdb388c0715990cbc06866db554e1822c4bdcf6d4166cf30ac82df8c41", + "sha256:d350f0f2c2421e65fbc62690f26b59b0bcda1b614beb318c81e38647e0f673a1", + "sha256:ec29604081f10f16a7aea809ad42e27764188fc258b02259a03a8ff7ded3808d", + "sha256:edf31f1150778abd4322444c393ab9c7bd2af271dd4dafb4208fb613b1f3cdc9", + "sha256:f7e30c27477dffc3e85c2463b3e649f751789e0f6c8456099eea7ddd53be4a8a", + "sha256:ffe538682dc19cc542ae7c3e504fdf54ca7f86fb8a135e59dd6bc8627eae6cce" + ], + "index": "pypi", + "version": "==7.2.0" }, "psutil": { "hashes": [ - "sha256:1413f4158eb50e110777c4f15d7c759521703bd6beb58926f1d562da40180058", - "sha256:298af2f14b635c3c7118fd9183843f4e73e681bb6f01e12284d4d70d48a60953", - "sha256:60b86f327c198561f101a92be1995f9ae0399736b6eced8f24af41ec64fb88d4", - "sha256:685ec16ca14d079455892f25bd124df26ff9137664af445563c1bd36629b5e0e", - "sha256:73f35ab66c6c7a9ce82ba44b1e9b1050be2a80cd4dcc3352cc108656b115c74f", - "sha256:75e22717d4dbc7ca529ec5063000b2b294fc9a367f9c9ede1f65846c7955fd38", - "sha256:a02f4ac50d4a23253b68233b07e7cdb567bd025b982d5cf0ee78296990c22d9e", - "sha256:d008ddc00c6906ec80040d26dc2d3e3962109e40ad07fd8a12d0284ce5e0e4f8", - "sha256:d84029b190c8a66a946e28b4d3934d2ca1528ec94764b180f7d6ea57b0e75e26", - "sha256:e2d0c5b07c6fe5a87fa27b7855017edb0d52ee73b71e6ee368fae268605cc3f5", - "sha256:f344ca230dd8e8d5eee16827596f1c22ec0876127c28e800d7ae20ed44c4b310" + "sha256:0ee3c36428f160d2d8fce3c583a0353e848abb7de9732c50cf3356dd49ad63f8", + "sha256:10512b46c95b02842c225f58fa00385c08fa00c68bac7da2d9a58ebe2c517498", + "sha256:4080869ed93cce662905b029a1770fe89c98787e543fa7347f075ade761b19d6", + "sha256:5e9d0f26d4194479a13d5f4b3798260c20cecf9ac9a461e718eb59ea520a360c", + "sha256:66c18ca7680a31bf16ee22b1d21b6397869dda8059dbdb57d9f27efa6615f195", + "sha256:68d36986ded5dac7c2dcd42f2682af1db80d4bce3faa126a6145c1637e1b559f", + "sha256:90990af1c3c67195c44c9a889184f84f5b2320dce3ee3acbd054e3ba0b4a7beb", + "sha256:a5b120bb3c0c71dfe27551f9da2f3209a8257a178ed6c628a819037a8df487f1", + "sha256:d8a82162f23c53b8525cf5f14a355f5d1eea86fa8edde27287dd3a98399e4fdf", + "sha256:f2018461733b23f308c298653c8903d32aaad7873d25e1d228765e91ae42c3f2", + "sha256:ff1977ba1a5f71f89166d5145c3da1cea89a0fdb044075a12c720ee9123ec818" ], "index": "pypi", - "version": "==5.7.0" + "version": "==5.7.2" }, "pycapnp": { "hashes": [ @@ -438,39 +446,39 @@ }, "pycryptodome": { "hashes": [ - "sha256:07024fc364869eae8d6ac0d316e089956e6aeffe42dbdcf44fe1320d96becf7f", - "sha256:09b6d6bcc01a4eb1a2b4deeff5aa602a108ec5aed8ac75ae554f97d1d7f0a5ad", - "sha256:0e10f352ccbbcb5bb2dc4ecaf106564e65702a717d72ab260f9ac4c19753cfc2", - "sha256:1f4752186298caf2e9ff5354f2e694d607ca7342aa313a62005235d46e28cf04", - "sha256:2fbc472e0b567318fe2052281d5a8c0ae70099b446679815f655e9fbc18c3a65", - "sha256:3ec3dc2f80f71fd0c955ce48b81bfaf8914c6f63a41a738f28885a1c4892968a", - "sha256:426c188c83c10df71f053e04b4003b1437bae5cb37606440e498b00f160d71d0", - "sha256:626c0a1d4d83ec6303f970a17158114f75c3ba1736f7f2983f7b40a265861bd8", - "sha256:767ad0fb5d23efc36a4d5c2fc608ac603f3de028909bcf59abc943e0d0bc5a36", - "sha256:7ac729d9091ed5478af2b4a4f44f5335a98febbc008af619e4569a59fe503e40", - "sha256:83295a3fb5cf50c48631eb5b440cb5e9832d8c14d81d1d45f4497b67a9987de8", - "sha256:8be56bde3312e022d9d1d6afa124556460ad5c844c2fc63642f6af723c098d35", - "sha256:8f06556a8f7ea7b1e42eff39726bb0dca1c251205debae64e6eebea3cd7b438a", - "sha256:9230fcb5d948c3fb40049bace4d33c5d254f8232c2c0bba05d2570aea3ba4520", - "sha256:9378c309aec1f8cd8bad361ed0816a440151b97a2a3f6ffdaba1d1a1fb76873a", - "sha256:9977086e0f93adb326379897437373871b80501e1d176fec63c7f46fb300c862", - "sha256:9a94fca11fdc161460bd8659c15b6adef45c1b20da86402256eaf3addfaab324", - "sha256:9c739b7795ccf2ef1fdad8d44e539a39ad300ee6786e804ea7f0c6a786eb5343", - "sha256:b1e332587b3b195542e77681389c296e1837ca01240399d88803a075447d3557", - "sha256:c109a26a21f21f695d369ff9b87f5d43e0d6c768d8384e10bc74142bed2e092e", - "sha256:c818dc1f3eace93ee50c2b6b5c2becf7c418fa5dd1ba6fc0ef7db279ea21d5e4", - "sha256:cff31f5a8977534f255f729d5d2467526f2b10563a30bbdade92223e0bf264bd", - "sha256:d4f94368ce2d65873a87ad867eb3bf63f4ba81eb97a9ee66d38c2b71ce5a7439", - "sha256:d61b012baa8c2b659e9890011358455c0019a4108536b811602d2f638c40802a", - "sha256:d6e1bc5c94873bec742afe2dfadce0d20445b18e75c47afc0c115b19e5dd38dd", - "sha256:ea83bcd9d6c03248ebd46e71ac313858e0afd5aa2fa81478c0e653242f3eb476", - "sha256:ed5761b37615a1f222c5345bbf45272ae2cf8c7dff88a4f53a1e9f977cbb6d95", - "sha256:f011cd0062e54658b7086a76f8cf0f4222812acc66e219e196ea2d0a8849d0ed", - "sha256:f1add21b6d179179b3c177c33d18a2186a09cc0d3af41ff5ed3f377360b869f2", - "sha256:f655addaaaa9974108d4808f4150652589cada96074c87115c52e575bfcd87d5" - ], - "index": "pypi", - "version": "==3.9.7" + "sha256:02e51e1d5828d58f154896ddfd003e2e7584869c275e5acbe290443575370fba", + "sha256:03d5cca8618620f45fd40f827423f82b86b3a202c8d44108601b0f5f56b04299", + "sha256:0e24171cf01021bc5dc17d6a9d4f33a048f09d62cc3f62541e95ef104588bda4", + "sha256:132a56abba24e2e06a479d8e5db7a48271a73a215f605017bbd476d31f8e71c1", + "sha256:1e655746f539421d923fd48df8f6f40b3443d80b75532501c0085b64afed9df5", + "sha256:2b998dc45ef5f4e5cf5248a6edfcd8d8e9fb5e35df8e4259b13a1b10eda7b16b", + "sha256:360955eece2cd0fa694a708d10303c6abd7b39614fa2547b6bd245da76198beb", + "sha256:39ef9fb52d6ec7728fce1f1693cb99d60ce302aeebd59bcedea70ca3203fda60", + "sha256:4350a42028240c344ee855f032c7d4ad6ff4f813bfbe7121547b7dc579ecc876", + "sha256:50348edd283afdccddc0938cdc674484533912ba8a99a27c7bfebb75030aa856", + "sha256:54bdedd28476dea8a3cd86cb67c0df1f0e3d71cae8022354b0f879c41a3d27b2", + "sha256:55eb61aca2c883db770999f50d091ff7c14016f2769ad7bca3d9b75d1d7c1b68", + "sha256:6276478ada411aca97c0d5104916354b3d740d368407912722bd4d11aa9ee4c2", + "sha256:67dcad1b8b201308586a8ca2ffe89df1e4f731d5a4cdd0610cc4ea790351c739", + "sha256:709b9f144d23e290b9863121d1ace14a72e01f66ea9c903fbdc690520dfdfcf0", + "sha256:8063a712fba642f78d3c506b0896846601b6de7f5c3d534e388ad0cc07f5a149", + "sha256:80d57177a0b7c14d4594c62bbb47fe2f6309ad3b0a34348a291d570925c97a82", + "sha256:a207231a52426de3ff20f5608f0687261a3329d97a036c51f7d4c606a6f30c23", + "sha256:abc2e126c9490e58a36a0f83516479e781d83adfb134576a5cbe5c6af2a3e93c", + "sha256:b56638d58a3a4be13229c6a815cd448f9e3ce40c00880a5398471b42ee86f50e", + "sha256:bcd5b8416e73e4b0d48afba3704d8c826414764dafaed7a1a93c442188d90ccc", + "sha256:bec2bcdf7c9ce7f04d718e51887f3b05dc5c1cfaf5d2c2e9065ecddd1b2f6c9a", + "sha256:c8bf40cf6e281a4378e25846924327e728a887e8bf0ee83b2604a0f4b61692e8", + "sha256:d8074c8448cfd0705dfa71ca333277fce9786d0b9cac75d120545de6253f996a", + "sha256:dd302b6ae3965afeb5ef1b0d92486f986c0e65183cd7835973f0b593800590e6", + "sha256:de6e1cd75677423ff64712c337521e62e3a7a4fc84caabbd93207752e831a85a", + "sha256:ef39c98d9b8c0736d91937d193653e47c3b19ddf4fc3bccdc5e09aaa4b0c5d21", + "sha256:f521178e5a991ffd04182ed08f552daca1affcb826aeda0e1945cd989a9d4345", + "sha256:f78a68c2c820e4731e510a2df3eef0322f24fde1781ced970bf497b6c7d92982", + "sha256:fbe65d5cfe04ff2f7684160d50f5118bdefb01e3af4718eeb618bfed40f19d94" + ], + "index": "pypi", + "version": "==3.9.8" }, "pyflakes": { "hashes": [ @@ -573,19 +581,19 @@ }, "requests": { "hashes": [ - "sha256:43999036bfa82904b6af1d99e4882b560e5e2c68e5c4b0aa03b655f3d7d73fee", - "sha256:b3f43d496c6daba4493e7c431722aeb7dbc6288f52a6e04e7b6023b0247817e6" + "sha256:b3559a131db72c33ee969480840fff4bb6dd111de7dd27c8ee1f820f4f00231b", + "sha256:fe75cc94a9443b9246fc7049224f75604b113c36acb93f87b80ed42c44cbb898" ], "index": "pypi", - "version": "==2.23.0" + "version": "==2.24.0" }, "scons": { "hashes": [ - "sha256:0f860678cd96fc943ff2294389b0f33cbe51080801591497bc652e72237f0176", - "sha256:8aaa483c303efeb678e6f7c776c8444a482f8ddc3ad891f8b6cdd35264da9a1f" + "sha256:722ed104b5c624ecdc89bd4e02b094d2b14d99d47b5d0501961e47f579a2007c", + "sha256:9b4696a806fb73f402fbf5e37ab0e8b6cd0dcef990a91210d7ed4aacbcc5231d" ], "index": "pypi", - "version": "==3.1.2" + "version": "==4.0.1" }, "setproctitle": { "hashes": [ @@ -627,11 +635,11 @@ }, "tqdm": { "hashes": [ - "sha256:07c06493f1403c1380b630ae3dcbe5ae62abcf369a93bbc052502279f189ab8c", - "sha256:cd140979c2bebd2311dfb14781d8f19bd5a9debb92dcab9f6ef899c987fcf71f" + "sha256:6baa75a88582b1db6d34ce4690da5501d2a1cb65c34664840a456b2c9f794d29", + "sha256:fcb7cb5b729b60a27f300b15c1ffd4744f080fb483b88f31dc8654b082cc8ea5" ], "index": "pypi", - "version": "==4.46.1" + "version": "==4.48.0" }, "urllib3": { "hashes": [ @@ -728,10 +736,10 @@ }, "argcomplete": { "hashes": [ - "sha256:5ae7b601be17bf38a749ec06aa07fb04e7b6b5fc17906948dc1866e7facf3740", - "sha256:890bdd1fcbb973ed73db241763e78b6d958580e588c2910b508c770a59ef37d7" + "sha256:2fbe5ed09fd2c1d727d4199feca96569a5b50d44c71b16da9c742201f7cc295c", + "sha256:91dc7f9c7f6281d5a0dce5e73d2e33283aaef083495c13974a7dd197a1cdc949" ], - "version": "==1.11.1" + "version": "==1.12.0" }, "astroid": { "hashes": [ @@ -766,11 +774,11 @@ }, "azure-cli-core": { "hashes": [ - "sha256:28f89203a61441916b442d423767e23d06b662d50ed19a850492ccaf992e4ef5", - "sha256:a9ff22a09fc5f546750d0735123320ff9841cfb1e1e36cdcb56005effe61cd4e" + "sha256:28bad5b4a8d90e98af4b556cbe560517a9be7187b0ea05bebe449c6838a03756", + "sha256:8618a30f7ea2188506f29801220c06396d731c26e4de92c327e6b0e8cc790db5" ], "index": "pypi", - "version": "==2.7.0" + "version": "==2.9.1" }, "azure-cli-nspkg": { "hashes": [ @@ -798,11 +806,11 @@ }, "azure-core": { "hashes": [ - "sha256:7bf695b017acea3da28e0390a2dea5b7e15a9fa3ef1af50ff020bcfe7dacb6a4", - "sha256:d10b74e783cff90d56360e61162afdd22276d62dc9467e657ae866449eae7648" + "sha256:2d1aade2795ea0ac2a903af940c3e0dfe75d25351ec4fc44edf747e97d703dfb", + "sha256:a66da240a287f447f9867f54ba09ea235895cec13ea38c5f490ce4eedefdd75c" ], "index": "pypi", - "version": "==1.6.0" + "version": "==1.7.0" }, "azure-mgmt-core": { "hashes": [ @@ -907,33 +915,33 @@ }, "boto3": { "hashes": [ - "sha256:aa8370f4ba58ffc1d68960fe42689dd716e8159f27f6b86b2211c130d19f9724", - "sha256:acaabe139ac605cfd4bf22f5edc15dbdcad20a020284d168421ab37df21a6319" + "sha256:542fa3499624dfa3312fd5a6f45bc221d0871c73c5d91c57e5c6435b6f4463cc", + "sha256:6bf841797d5ec9f7770a335d919c5ea20d1980c1eb39b009e58f6de2879ff2cd" ], "index": "pypi", - "version": "==1.14.1" + "version": "==1.14.24" }, "botocore": { "hashes": [ - "sha256:7dd59bc766d567ca83bc6113aa139d92ba447738ccdfcd40788848553d329a52", - "sha256:cd4bb2d96ff2ec6bf4fbcdb2f241d0fb6ba1e7955b4721cf1d81f13db02768b6" + "sha256:023e390e1caaf4aab55bd6b87738777d25e7b6f3098fb77e356e638c0baa491b", + "sha256:2e07c0b88563d793cca8186c7fa42cfd5b8ece4fed31c928e0676091f3bb815d" ], - "version": "==1.17.9" + "version": "==1.17.24" }, "cachetools": { "hashes": [ - "sha256:1d057645db16ca7fe1f3bd953558897603d6f0b9c51ed9d11eb4d071ec4e2aab", - "sha256:de5d88f87781602201cde465d3afe837546663b168e8b39df67411b0bf10cefc" + "sha256:513d4ff98dd27f85743a8dc0e92f55ddb1b49e060c2d5961512855cda2c01a98", + "sha256:bbaa39c3dede00175df2dc2b03d0cf18dd2d32a7de7beb68072d13043c9edb20" ], "markers": "python_version ~= '3.5'", - "version": "==4.1.0" + "version": "==4.1.1" }, "certifi": { "hashes": [ - "sha256:5ad7e9a056d25ffa5082862e36f119f7f7cec6457fa07ee2f8c339814b80c9b1", - "sha256:9cd41137dc19af6a5e03b630eefe7d1f458d964d406342dd3edf625839b944cc" + "sha256:5930595817496dd21bb8dc35dad090f1c2cd0adfaf21204bf6732ca5d8ee34d3", + "sha256:8fc0819f1f30ba15bdb34cceffb9ef04d99f420f68eb75d901e9560b8749fc41" ], - "version": "==2020.4.5.2" + "version": "==2020.6.20" }, "cffi": { "hashes": [ @@ -1009,65 +1017,68 @@ }, "coverage": { "hashes": [ - "sha256:00f1d23f4336efc3b311ed0d807feb45098fc86dee1ca13b3d6768cdab187c8a", - "sha256:01333e1bd22c59713ba8a79f088b3955946e293114479bbfc2e37d522be03355", - "sha256:0cb4be7e784dcdc050fc58ef05b71aa8e89b7e6636b99967fadbdba694cf2b65", - "sha256:0e61d9803d5851849c24f78227939c701ced6704f337cad0a91e0972c51c1ee7", - "sha256:1601e480b9b99697a570cea7ef749e88123c04b92d84cedaa01e117436b4a0a9", - "sha256:2742c7515b9eb368718cd091bad1a1b44135cc72468c731302b3d641895b83d1", - "sha256:2d27a3f742c98e5c6b461ee6ef7287400a1956c11421eb574d843d9ec1f772f0", - "sha256:402e1744733df483b93abbf209283898e9f0d67470707e3c7516d84f48524f55", - "sha256:5c542d1e62eece33c306d66fe0a5c4f7f7b3c08fecc46ead86d7916684b36d6c", - "sha256:5f2294dbf7875b991c381e3d5af2bcc3494d836affa52b809c91697449d0eda6", - "sha256:6402bd2fdedabbdb63a316308142597534ea8e1895f4e7d8bf7476c5e8751fef", - "sha256:66460ab1599d3cf894bb6baee8c684788819b71a5dc1e8fa2ecc152e5d752019", - "sha256:782caea581a6e9ff75eccda79287daefd1d2631cc09d642b6ee2d6da21fc0a4e", - "sha256:79a3cfd6346ce6c13145731d39db47b7a7b859c0272f02cdb89a3bdcbae233a0", - "sha256:7a5bdad4edec57b5fb8dae7d3ee58622d626fd3a0be0dfceda162a7035885ecf", - "sha256:8fa0cbc7ecad630e5b0f4f35b0f6ad419246b02bc750de7ac66db92667996d24", - "sha256:a027ef0492ede1e03a8054e3c37b8def89a1e3c471482e9f046906ba4f2aafd2", - "sha256:a3f3654d5734a3ece152636aad89f58afc9213c6520062db3978239db122f03c", - "sha256:a82b92b04a23d3c8a581fc049228bafde988abacba397d57ce95fe95e0338ab4", - "sha256:acf3763ed01af8410fc36afea23707d4ea58ba7e86a8ee915dfb9ceff9ef69d0", - "sha256:adeb4c5b608574a3d647011af36f7586811a2c1197c861aedb548dd2453b41cd", - "sha256:b83835506dfc185a319031cf853fa4bb1b3974b1f913f5bb1a0f3d98bdcded04", - "sha256:bb28a7245de68bf29f6fb199545d072d1036a1917dca17a1e75bbb919e14ee8e", - "sha256:bf9cb9a9fd8891e7efd2d44deb24b86d647394b9705b744ff6f8261e6f29a730", - "sha256:c317eaf5ff46a34305b202e73404f55f7389ef834b8dbf4da09b9b9b37f76dd2", - "sha256:dbe8c6ae7534b5b024296464f387d57c13caa942f6d8e6e0346f27e509f0f768", - "sha256:de807ae933cfb7f0c7d9d981a053772452217df2bf38e7e6267c9cbf9545a796", - "sha256:dead2ddede4c7ba6cb3a721870f5141c97dc7d85a079edb4bd8d88c3ad5b20c7", - "sha256:dec5202bfe6f672d4511086e125db035a52b00f1648d6407cc8e526912c0353a", - "sha256:e1ea316102ea1e1770724db01998d1603ed921c54a86a2efcb03428d5417e489", - "sha256:f90bfc4ad18450c80b024036eaf91e4a246ae287701aaa88eaebebf150868052" - ], - "index": "pypi", - "version": "==5.1" + "sha256:0fc4e0d91350d6f43ef6a61f64a48e917637e1dcfcba4b4b7d543c628ef82c2d", + "sha256:10f2a618a6e75adf64329f828a6a5b40244c1c50f5ef4ce4109e904e69c71bd2", + "sha256:12eaccd86d9a373aea59869bc9cfa0ab6ba8b1477752110cb4c10d165474f703", + "sha256:1874bdc943654ba46d28f179c1846f5710eda3aeb265ff029e0ac2b52daae404", + "sha256:1dcebae667b73fd4aa69237e6afb39abc2f27520f2358590c1b13dd90e32abe7", + "sha256:1e58fca3d9ec1a423f1b7f2aa34af4f733cbfa9020c8fe39ca451b6071237405", + "sha256:214eb2110217f2636a9329bc766507ab71a3a06a8ea30cdeebb47c24dce5972d", + "sha256:25fe74b5b2f1b4abb11e103bb7984daca8f8292683957d0738cd692f6a7cc64c", + "sha256:32ecee61a43be509b91a526819717d5e5650e009a8d5eda8631a59c721d5f3b6", + "sha256:3740b796015b889e46c260ff18b84683fa2e30f0f75a171fb10d2bf9fb91fc70", + "sha256:3b2c34690f613525672697910894b60d15800ac7e779fbd0fccf532486c1ba40", + "sha256:41d88736c42f4a22c494c32cc48a05828236e37c991bd9760f8923415e3169e4", + "sha256:42fa45a29f1059eda4d3c7b509589cc0343cd6bbf083d6118216830cd1a51613", + "sha256:4bb385a747e6ae8a65290b3df60d6c8a692a5599dc66c9fa3520e667886f2e10", + "sha256:509294f3e76d3f26b35083973fbc952e01e1727656d979b11182f273f08aa80b", + "sha256:5c74c5b6045969b07c9fb36b665c9cac84d6c174a809fc1b21bdc06c7836d9a0", + "sha256:60a3d36297b65c7f78329b80120f72947140f45b5c7a017ea730f9112b40f2ec", + "sha256:6f91b4492c5cde83bfe462f5b2b997cdf96a138f7c58b1140f05de5751623cf1", + "sha256:7403675df5e27745571aba1c957c7da2dacb537c21e14007ec3a417bf31f7f3d", + "sha256:87bdc8135b8ee739840eee19b184804e5d57f518578ffc797f5afa2c3c297913", + "sha256:8a3decd12e7934d0254939e2bf434bf04a5890c5bf91a982685021786a08087e", + "sha256:9702e2cb1c6dec01fb8e1a64c015817c0800a6eca287552c47a5ee0ebddccf62", + "sha256:a4d511012beb967a39580ba7d2549edf1e6865a33e5fe51e4dce550522b3ac0e", + "sha256:bbb387811f7a18bdc61a2ea3d102be0c7e239b0db9c83be7bfa50f095db5b92a", + "sha256:bfcc811883699ed49afc58b1ed9f80428a18eb9166422bce3c31a53dba00fd1d", + "sha256:c32aa13cc3fe86b0f744dfe35a7f879ee33ac0a560684fef0f3e1580352b818f", + "sha256:ca63dae130a2e788f2b249200f01d7fa240f24da0596501d387a50e57aa7075e", + "sha256:d54d7ea74cc00482a2410d63bf10aa34ebe1c49ac50779652106c867f9986d6b", + "sha256:d67599521dff98ec8c34cd9652cbcfe16ed076a2209625fca9dc7419b6370e5c", + "sha256:d82db1b9a92cb5c67661ca6616bdca6ff931deceebb98eecbd328812dab52032", + "sha256:d9ad0a988ae20face62520785ec3595a5e64f35a21762a57d115dae0b8fb894a", + "sha256:ebf2431b2d457ae5217f3a1179533c456f3272ded16f8ed0b32961a6d90e38ee", + "sha256:ed9a21502e9223f563e071759f769c3d6a2e1ba5328c31e86830368e8d78bc9c", + "sha256:f50632ef2d749f541ca8e6c07c9928a37f87505ce3a9f20c8446ad310f1aa87b" + ], + "index": "pypi", + "version": "==5.2" }, "cryptography": { "hashes": [ - "sha256:091d31c42f444c6f519485ed528d8b451d1a0c7bf30e8ca583a0cac44b8a0df6", - "sha256:18452582a3c85b96014b45686af264563e3e5d99d226589f057ace56196ec78b", - "sha256:1dfa985f62b137909496e7fc182dac687206d8d089dd03eaeb28ae16eec8e7d5", - "sha256:1e4014639d3d73fbc5ceff206049c5a9a849cefd106a49fa7aaaa25cc0ce35cf", - "sha256:22e91636a51170df0ae4dcbd250d318fd28c9f491c4e50b625a49964b24fe46e", - "sha256:3b3eba865ea2754738616f87292b7f29448aec342a7c720956f8083d252bf28b", - "sha256:651448cd2e3a6bc2bb76c3663785133c40d5e1a8c1a9c5429e4354201c6024ae", - "sha256:726086c17f94747cedbee6efa77e99ae170caebeb1116353c6cf0ab67ea6829b", - "sha256:844a76bc04472e5135b909da6aed84360f522ff5dfa47f93e3dd2a0b84a89fa0", - "sha256:88c881dd5a147e08d1bdcf2315c04972381d026cdb803325c03fe2b4a8ed858b", - "sha256:96c080ae7118c10fcbe6229ab43eb8b090fccd31a09ef55f83f690d1ef619a1d", - "sha256:a0c30272fb4ddda5f5ffc1089d7405b7a71b0b0f51993cb4e5dbb4590b2fc229", - "sha256:bb1f0281887d89617b4c68e8db9a2c42b9efebf2702a3c5bf70599421a8623e3", - "sha256:c447cf087cf2dbddc1add6987bbe2f767ed5317adb2d08af940db517dd704365", - "sha256:c4fd17d92e9d55b84707f4fd09992081ba872d1a0c610c109c18e062e06a2e55", - "sha256:d0d5aeaedd29be304848f1c5059074a740fa9f6f26b84c5b63e8b29e73dfc270", - "sha256:daf54a4b07d67ad437ff239c8a4080cfd1cc7213df57d33c97de7b4738048d5e", - "sha256:e993468c859d084d5579e2ebee101de8f5a27ce8e2159959b6673b418fd8c785", - "sha256:f118a95c7480f5be0df8afeb9a11bd199aa20afab7a96bcf20409b411a3a85f0" - ], - "index": "pypi", - "version": "==2.9.2" + "sha256:0c608ff4d4adad9e39b5057de43657515c7da1ccb1807c3a27d4cf31fc923b4b", + "sha256:0cbfed8ea74631fe4de00630f4bb592dad564d57f73150d6f6796a24e76c76cd", + "sha256:124af7255ffc8e964d9ff26971b3a6153e1a8a220b9a685dc407976ecb27a06a", + "sha256:384d7c681b1ab904fff3400a6909261cae1d0939cc483a68bdedab282fb89a07", + "sha256:45741f5499150593178fc98d2c1a9c6722df88b99c821ad6ae298eff0ba1ae71", + "sha256:4b9303507254ccb1181d1803a2080a798910ba89b1a3c9f53639885c90f7a756", + "sha256:4d355f2aee4a29063c10164b032d9fa8a82e2c30768737a2fd56d256146ad559", + "sha256:51e40123083d2f946794f9fe4adeeee2922b581fa3602128ce85ff813d85b81f", + "sha256:8713ddb888119b0d2a1462357d5946b8911be01ddbf31451e1d07eaa5077a261", + "sha256:8e924dbc025206e97756e8903039662aa58aa9ba357d8e1d8fc29e3092322053", + "sha256:8ecef21ac982aa78309bb6f092d1677812927e8b5ef204a10c326fc29f1367e2", + "sha256:8ecf9400d0893836ff41b6f977a33972145a855b6efeb605b49ee273c5e6469f", + "sha256:9367d00e14dee8d02134c6c9524bb4bd39d4c162456343d07191e2a0b5ec8b3b", + "sha256:a09fd9c1cca9a46b6ad4bea0a1f86ab1de3c0c932364dbcf9a6c2a5eeb44fa77", + "sha256:ab49edd5bea8d8b39a44b3db618e4783ef84c19c8b47286bf05dfdb3efb01c83", + "sha256:bea0b0468f89cdea625bb3f692cd7a4222d80a6bdafd6fb923963f2b9da0e15f", + "sha256:bec7568c6970b865f2bcebbe84d547c52bb2abadf74cefce396ba07571109c67", + "sha256:ce82cc06588e5cbc2a7df3c8a9c778f2cb722f56835a23a68b5a7264726bb00c", + "sha256:dea0ba7fe6f9461d244679efa968d215ea1f989b9c1957d7f10c21e5c7c09ad6" + ], + "index": "pypi", + "version": "==3.0" }, "cycler": { "hashes": [ @@ -1078,11 +1089,11 @@ }, "datadog": { "hashes": [ - "sha256:398c612f8fb8e1988be897fda920ffb3b8a1ec70d430730e3b71a269df31b486", - "sha256:3fe197587db49d808ba88e40f431fb2d256be3c428419ac2984609d67fd66bce" + "sha256:401cd1dcf2d5de05786016a1c790bff28d1428d12ae1dbe11485f9cb5502939b", + "sha256:b5ebf25e88cf6891ff26a4a82898ae5ff23d712ad5501e1043113bd0a1903c16" ], "index": "pypi", - "version": "==0.36.0" + "version": "==0.38.0" }, "decorator": { "hashes": [ @@ -1109,9 +1120,10 @@ }, "distlib": { "hashes": [ - "sha256:2e166e231a26b36d6dfe35a48c4464346620f8645ed0ace01ee31822b288de21" + "sha256:8c09de2c67b3e7deef7184574fc060ab8a793e7adbb183d942c389c8b13c52fb", + "sha256:edf6116872c863e1aa9d5bb7cb5e05a022c519a4594dc703843343a9ddd9bff1" ], - "version": "==0.3.0" + "version": "==0.3.1" }, "dlib": { "hashes": [ @@ -1131,11 +1143,11 @@ }, "elasticsearch": { "hashes": [ - "sha256:9bfcb2bd137d6d7ca123e252b9d7261cfe4f7723f7b749a99c52b47766cf387c", - "sha256:e9138aa9de7624a6c6fbf5d0300bb11617cfe0a056fc6731665748731961d693" + "sha256:6fb566dd23b91b5871ce12212888674b4cf33374e92b71b1080916c931e44dcb", + "sha256:e637d8cf4e27e279b5ff8ca8edc0c086f4b5df4bf2b48e2f950b7833aca3a792" ], "index": "pypi", - "version": "==7.7.1" + "version": "==7.8.0" }, "entrypoints": { "hashes": [ @@ -1199,11 +1211,11 @@ }, "flask-socketio": { "hashes": [ - "sha256:5969e1d4ead37ec9164f82779ec86239f0f394a08b20477d2056903010920f36", - "sha256:7f9b54ac9cd92e28a657c58f51943d97e76b988840c8795784e7b2bafb13103f" + "sha256:3668675bf7763c5b5f56689d439f07356e89c0a52e0c9e9cd3cc08563c07b252", + "sha256:36c1d5765010d1f4e4f05b4cc9c20c289d9dc70698c88d1addd0afcfedc5b062" ], "index": "pypi", - "version": "==4.3.0" + "version": "==4.3.1" }, "future": { "hashes": [ @@ -1237,11 +1249,11 @@ }, "google-auth": { "hashes": [ - "sha256:5e3f540b7b0b892000d542cea6b818b837c230e9a4db9337bb2973bcae0fc078", - "sha256:d6b390d3bb0969061ffec7e5766c45c1b39e13c302691e35029f1ad1ccd8ca3b" + "sha256:15b42d57d6c3d868d318e8273c06b2692fc5aad1bc45989a4f68f1fee05d41b2", + "sha256:f404448f3d3c91944b1d907427d4a0c48f465898e9dbacf1bdebf95c5fe03273" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.18.0" + "version": "==1.19.2" }, "google-auth-oauthlib": { "hashes": [ @@ -1354,43 +1366,43 @@ }, "identify": { "hashes": [ - "sha256:acf0712ab4042642e8f44e9532d95c26fbe60c0ab8b6e5b654dd1bc6512810e0", - "sha256:b2cd24dece806707e0b50517c1b3bcf3044e0b1cb13a72e7d34aa31c91f2a55a" + "sha256:06b4373546ae55eaaefdac54f006951dbd968fe2912846c00e565b09cfaed101", + "sha256:5519601b70c831011fb425ffd214101df7639ba3980f24dc283f7675b19127b3" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.4.20" + "version": "==1.4.24" }, "idna": { "hashes": [ - "sha256:7588d1c14ae4c77d74036e8c22ff447b26d0fde8f007354fd48a7814db15b7cb", - "sha256:a068a21ceac8a4d63dbfd964670474107f541babbd2250d61922f029858365fa" + "sha256:b307872f855b18632ce0c21c5e45be78c0ea7ae4c15c828c20788b26921eb3f6", + "sha256:b97d804b1e9b523befed77c48dacec60e6dcb0b5391d57af6a65a312a90648c0" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==2.9" + "version": "==2.10" }, "imageio": { "hashes": [ - "sha256:1e4ab29b3775bb093c7a35854a0412857145450183344678829b30e72263b001", - "sha256:fb5fd6d3d17126bbaac9af29fe340e2c97a196eb9416d4f28c0e543744a152cf" + "sha256:3604d751f03002e8e0e7650aa71d8d9148144a87daf17cb1f3228e80747f2e6b", + "sha256:52ddbaeca2dccf53ba2d6dec5676ca7bc3b2403ef8b37f7da78b7654bb3e10f0" ], "index": "pypi", - "version": "==2.8.0" + "version": "==2.9.0" }, "ipykernel": { "hashes": [ - "sha256:731adb3f2c4ebcaff52e10a855ddc87670359a89c9c784d711e62d66fccdafae", - "sha256:a8362e3ae365023ca458effe93b026b8cdadc0b73ff3031472128dd8a2cf0289" + "sha256:09bac6473a593f61a3ae036035b81a2d30457ff157163562796560516a2f67d8", + "sha256:d718d5f717e0818329d371313f99aabba1bf4ca13f1e9f80cc3c5f866ee8a9ad" ], "index": "pypi", - "version": "==5.3.0" + "version": "==5.3.3" }, "ipython": { "hashes": [ - "sha256:0ef1433879816a960cd3ae1ae1dc82c64732ca75cec8dab5a4e29783fb571d0e", - "sha256:1b85d65632211bf5d3e6f1406f3393c8c429a47d7b947b9a87812aa5bce6595c" + "sha256:2dbcc8c27ca7d3cfe4fcdff7f45b27f9a8d3edfa70ff8024a71c7a8eb5f09d64", + "sha256:9f4fcb31d3b2c533333893b9172264e4821c1ac91839500f31bd43f2c59b3ccf" ], "index": "pypi", - "version": "==7.15.0" + "version": "==7.16.1" }, "ipython-genutils": { "hashes": [ @@ -1431,11 +1443,11 @@ }, "jedi": { "hashes": [ - "sha256:1ddb0ec78059e8e27ec9eb5098360b4ea0a3dd840bedf21415ea820c21b40a22", - "sha256:807d5d4f96711a2bcfdd5dfa3b1ae6d09aa53832b182090b222b5efb81f52f63" + "sha256:86ed7d9b750603e4ba582ea8edc678657fb4007894a12bcf6f4bb97892f31d20", + "sha256:98cc583fa0f2f8304968199b01b6b4b94f469a1f4a74c1560506ca2a211378b5" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==0.17.1" + "version": "==0.17.2" }, "jinja2": { "hashes": [ @@ -1455,11 +1467,11 @@ }, "joblib": { "hashes": [ - "sha256:61e49189c84b3c5d99a969d314853f4d1d263316cc694bec17548ebaa9c47b6e", - "sha256:6825784ffda353cc8a1be573118085789e5b5d29401856b35b756645ab5aecb5" + "sha256:8f52bf24c64b608bf0b2563e0e47d6fcf516abc8cfafe10cfd98ad66d94f92d6", + "sha256:d348c5d4ae31496b2aa060d6d9b787864dd204f9480baaa52d18850cb43e9f49" ], "index": "pypi", - "version": "==0.15.1" + "version": "==0.16.0" }, "json-logging-py": { "hashes": [ @@ -1486,11 +1498,11 @@ }, "jupyter-client": { "hashes": [ - "sha256:3a32fa4d0b16d1c626b30c3002a62dfd86d6863ed39eaba3f537fade197bb756", - "sha256:cde8e83aab3ec1c614f221ae54713a9a46d3bf28292609d2db1b439bef5a8c8e" + "sha256:7ad9aa91505786420d77edc5f9fb170d51050c007338ba8d196f603223fd3b3a", + "sha256:b360f8d4638bc577a4656e93f86298db755f915098dc763f6fc05da0c5d7a595" ], "markers": "python_version >= '3.5'", - "version": "==6.1.3" + "version": "==6.1.6" }, "jupyter-console": { "hashes": [ @@ -1528,12 +1540,15 @@ "sha256:03662cbd3e6729f341a97dd2690b271e51a67a68322affab12a5b011344b973c", "sha256:18d749f3e56c0480dccd1714230da0f328e6e4accf188dd4e6884bdd06bf02dd", "sha256:247800260cd38160c362d211dcaf4ed0f7816afb5efe56544748b21d6ad6d17f", + "sha256:38d05c9ecb24eee1246391820ed7137ac42a50209c203c908154782fced90e44", "sha256:443c2320520eda0a5b930b2725b26f6175ca4453c61f739fef7a5847bd262f74", "sha256:4eadb361baf3069f278b055e3bb53fa189cea2fd02cb2c353b7a99ebb4477ef1", "sha256:556da0a5f60f6486ec4969abbc1dd83cf9b5c2deadc8288508e55c0f5f87d29c", "sha256:603162139684ee56bcd57acc74035fceed7dd8d732f38c0959c8bd157f913fec", "sha256:60a78858580761fe611d22127868f3dc9f98871e6fdf0a15cc4203ed9ba6179b", + "sha256:63f55f490b958b6299e4e5bdac66ac988c3d11b7fafa522800359075d4fa56d1", "sha256:7cc095a4661bdd8a5742aaf7c10ea9fac142d76ff1770a0f84394038126d8fc7", + "sha256:be046da49fbc3aa9491cc7296db7e8d27bcf0c3d5d1a40259c10471b014e4e0c", "sha256:c31bc3c8e903d60a1ea31a754c72559398d91b5929fcb329b1c3a3d3f6e72113", "sha256:c955791d80e464da3b471ab41eb65cf5a40c15ce9b001fdc5bbc241170de58ec", "sha256:d069ef4b20b1e6b19f790d00097a5d5d2c50871b66d10075dab78938dc2ee2cf", @@ -1642,23 +1657,30 @@ }, "matplotlib": { "hashes": [ - "sha256:2466d4dddeb0f5666fd1e6736cc5287a4f9f7ae6c1a9e0779deff798b28e1d35", - "sha256:282b3fc8023c4365bad924d1bb442ddc565c2d1635f210b700722776da466ca3", - "sha256:4bb50ee4755271a2017b070984bcb788d483a8ce3132fab68393d1555b62d4ba", - "sha256:56d3147714da5c7ac4bc452d041e70e0e0b07c763f604110bd4e2527f320b86d", - "sha256:7a9baefad265907c6f0b037c8c35a10cf437f7708c27415a5513cf09ac6d6ddd", - "sha256:aae7d107dc37b4bb72dcc45f70394e6df2e5e92ac4079761aacd0e2ad1d3b1f7", - "sha256:af14e77829c5b5d5be11858d042d6f2459878f8e296228c7ea13ec1fd308eb68", - "sha256:c1cf735970b7cd424502719b44288b21089863aaaab099f55e0283a721aaf781", - "sha256:ce378047902b7a05546b6485b14df77b2ff207a0054e60c10b5680132090c8ee", - "sha256:d35891a86a4388b6965c2d527b9a9f9e657d9e110b0575ca8a24ba0d4e34b8fc", - "sha256:e06304686209331f99640642dee08781a9d55c6e32abb45ed54f021f46ccae47", - "sha256:e20ba7fb37d4647ac38f3c6d8672dd8b62451ee16173a0711b37ba0ce42bf37d", - "sha256:f4412241e32d0f8d3713b68d3ca6430190a5e8a7c070f1c07d7833d8c5264398", - "sha256:ffe2f9cdcea1086fc414e82f42271ecf1976700b8edd16ca9d376189c6d93aee" - ], - "index": "pypi", - "version": "==3.2.1" + "sha256:09b4096748178bcc764b81587b00ab720eac24965d2bf44ecbe09dcf4e8ed253", + "sha256:19cf4db0272da286863a50406f6430101af129f288c421b1a7f33ddfc8d0180f", + "sha256:244a9088140a4c540e0a2db9c8ada5ad12520efded592a46e5bc43ff8f0fd0aa", + "sha256:24e8db94948019d531ce0bcd637ac24b1c8f6744ac86d2aa0eb6dbaeb1386f82", + "sha256:2a9d10930406748b50f60c5fa74c399a1c1080aa6ce6e3fe5f38473b02f6f06d", + "sha256:605e4d43b421524ad955a56535391e02866d07bce27c644e2c99e25fb59d63d1", + "sha256:695b4165520bdfe381d15a6db03778babb265fee7affdc43e169a881f3f329bc", + "sha256:6aa7ea00ad7d898704ffed46e83efd7ec985beba57f507c957979f080678b9ea", + "sha256:7c9adba58a67d23cc131c4189da56cb1d0f18a237c43188d831a44e4fc5df15a", + "sha256:7ce8f5364c74aac06abad84d8744d659bd86036e86c4ebf14c75ae4292597b46", + "sha256:855bb281f3cc8e23ef66064a2beb229674fdf785638091fc82a172e3e84c2780", + "sha256:9ccc651261b7044ffc3b1e2f9af17b1ef4c6a12fc080b5a7353ef0b53a50be28", + "sha256:b0786ac32983191fcd9cc0230b4ec2f8b3c25dee9beca46ca506c5d6cc5c593d", + "sha256:bf8d527a2eb9a5db1c9e5e405d1b1c4e66be983620c9ce80af6aae430d9a0c9c", + "sha256:c06ea133b44805d42f2507cb3503f6647b0c7918f1900b5063f5a8a69c63f6d2", + "sha256:c1f850908600efa60f81ad14eedbaf7cb17185a2c6d26586ae826ae5ce21f6e0", + "sha256:cef05e9a2302f96d6f0666ee70ac7715cbc12e3802d8b8eb80bacd6ab81a0a24", + "sha256:e3868686f3023644523df486fc224b0af4349f3cdb933b0a71f261a574d7b65f", + "sha256:ebb6168c9330309b1f3360d36c481d8cd621a490cf2a69c9d6625b2a76777c12", + "sha256:f74c39621b03cec7bc08498f140192ac26ca940ef20beac6dfad3714d2298b2a", + "sha256:f9753c6292d5a1fe46828feb38d1de1820e3ea109a5fea0b6ea1dca6e9d0b220" + ], + "index": "pypi", + "version": "==3.3.0" }, "mccabe": { "hashes": [ @@ -1684,10 +1706,10 @@ }, "mpld3": { "hashes": [ - "sha256:4d455884a211bf99b37ecc760759435c7bb6a5955de47d8daf4967e301878ab7" + "sha256:1677a314125ff2984e2f291d595188d5ee8ca66ac21b0c2c8633961bc33a7bf8" ], "index": "pypi", - "version": "==0.3" + "version": "==0.5.1" }, "msal": { "hashes": [ @@ -1712,17 +1734,17 @@ }, "msrest": { "hashes": [ - "sha256:214c5be98954cb45feb6a6a858a7ae6d41a664e80294b65db225bbaa33d9ca3c", - "sha256:88b31e937eba95bda5b9a910b28498fdc130718bb5f8dd98a6af0d333670c897" + "sha256:1345f73c178a7b445716590bc1346d44ac47c647ee83be57a48e2027d618f17c", + "sha256:c51ac6ce2d151b47dd4b3eed0fb8596b6e7c2067eff6bb82e874beaf7bfec531" ], - "version": "==0.6.16" + "version": "==0.6.17" }, "msrestazure": { "hashes": [ - "sha256:0ae7f903ff81631512beef39602c4104a8fe04cb7d166f28a1ec43c0f0985749", - "sha256:0ec9db93eeea6a6cf1240624a04f49cd8bbb26b98d84a63a8220cfda858c2a96" + "sha256:3de50f56147ef529b31e099a982496690468ecef33f0544cb0fa0cfe1e1de5b9", + "sha256:a06f0dabc9a6f5efe3b6add4bd8fb623aeadacf816b7a35b0f89107e0544d189" ], - "version": "==0.6.3" + "version": "==0.6.4" }, "multidict": { "hashes": [ @@ -1749,23 +1771,23 @@ }, "mypy": { "hashes": [ - "sha256:00cb1964a7476e871d6108341ac9c1a857d6bd20bf5877f4773ac5e9d92cd3cd", - "sha256:127de5a9b817a03a98c5ae8a0c46a20dc44442af6dcfa2ae7f96cb519b312efa", - "sha256:1f3976a945ad7f0a0727aafdc5651c2d3278e3c88dee94e2bf75cd3386b7b2f4", - "sha256:2f8c098f12b402c19b735aec724cc9105cc1a9eea405d08814eb4b14a6fb1a41", - "sha256:4ef13b619a289aa025f2273e05e755f8049bb4eaba6d703a425de37d495d178d", - "sha256:5d142f219bf8c7894dfa79ebfb7d352c4c63a325e75f10dfb4c3db9417dcd135", - "sha256:62eb5dd4ea86bda8ce386f26684f7f26e4bfe6283c9f2b6ca6d17faf704dcfad", - "sha256:64c36eb0936d0bfb7d8da49f92c18e312ad2e3ed46e5548ae4ca997b0d33bd59", - "sha256:75eed74d2faf2759f79c5f56f17388defd2fc994222312ec54ee921e37b31ad4", - "sha256:974bebe3699b9b46278a7f076635d219183da26e1a675c1f8243a69221758273", - "sha256:a5e5bb12b7982b179af513dddb06fca12285f0316d74f3964078acbfcf4c68f2", - "sha256:d31291df31bafb997952dc0a17ebb2737f802c754aed31dd155a8bfe75112c57", - "sha256:d3b4941de44341227ece1caaf5b08b23e42ad4eeb8b603219afb11e9d4cfb437", - "sha256:eadb865126da4e3c4c95bdb47fe1bb087a3e3ea14d39a3b13224b8a4d9f9a102" + "sha256:2c6cde8aa3426c1682d35190b59b71f661237d74b053822ea3d748e2c9578a7c", + "sha256:3fdda71c067d3ddfb21da4b80e2686b71e9e5c72cca65fa216d207a358827f86", + "sha256:5dd13ff1f2a97f94540fd37a49e5d255950ebcdf446fb597463a40d0df3fac8b", + "sha256:6731603dfe0ce4352c555c6284c6db0dc935b685e9ce2e4cf220abe1e14386fd", + "sha256:6bb93479caa6619d21d6e7160c552c1193f6952f0668cdda2f851156e85186fc", + "sha256:81c7908b94239c4010e16642c9102bfc958ab14e36048fa77d0be3289dda76ea", + "sha256:9c7a9a7ceb2871ba4bac1cf7217a7dd9ccd44c27c2950edbc6dc08530f32ad4e", + "sha256:a4a2cbcfc4cbf45cd126f531dedda8485671545b43107ded25ce952aac6fb308", + "sha256:b7fbfabdbcc78c4f6fc4712544b9b0d6bf171069c6e0e3cb82440dd10ced3406", + "sha256:c05b9e4fb1d8a41d41dec8786c94f3b95d3c5f528298d769eb8e73d293abc48d", + "sha256:d7df6eddb6054d21ca4d3c6249cae5578cb4602951fd2b6ee2f5510ffb098707", + "sha256:e0b61738ab504e656d1fe4ff0c0601387a5489ca122d55390ade31f9ca0e252d", + "sha256:eff7d4a85e9eea55afa34888dfeaccde99e7520b51f867ac28a48492c0b1130c", + "sha256:f05644db6779387ccdb468cc47a44b4356fc2ffa9287135d05b70a98dc83b89a" ], "index": "pypi", - "version": "==0.780" + "version": "==0.782" }, "mypy-extensions": { "hashes": [ @@ -1814,30 +1836,35 @@ }, "numpy": { "hashes": [ - "sha256:0172304e7d8d40e9e49553901903dc5f5a49a703363ed756796f5808a06fc233", - "sha256:34e96e9dae65c4839bd80012023aadd6ee2ccb73ce7fdf3074c62f301e63120b", - "sha256:3676abe3d621fc467c4c1469ee11e395c82b2d6b5463a9454e37fe9da07cd0d7", - "sha256:3dd6823d3e04b5f223e3e265b4a1eae15f104f4366edd409e5a5e413a98f911f", - "sha256:4064f53d4cce69e9ac613256dc2162e56f20a4e2d2086b1956dd2fcf77b7fac5", - "sha256:4674f7d27a6c1c52a4d1aa5f0881f1eff840d2206989bae6acb1c7668c02ebfb", - "sha256:7d42ab8cedd175b5ebcb39b5208b25ba104842489ed59fbb29356f671ac93583", - "sha256:965df25449305092b23d5145b9bdaeb0149b6e41a77a7d728b1644b3c99277c1", - "sha256:9c9d6531bc1886454f44aa8f809268bc481295cf9740827254f53c30104f074a", - "sha256:a78e438db8ec26d5d9d0e584b27ef25c7afa5a182d1bf4d05e313d2d6d515271", - "sha256:a7acefddf994af1aeba05bbbafe4ba983a187079f125146dc5859e6d817df824", - "sha256:a87f59508c2b7ceb8631c20630118cc546f1f815e034193dc72390db038a5cb3", - "sha256:ac792b385d81151bae2a5a8adb2b88261ceb4976dbfaaad9ce3a200e036753dc", - "sha256:b03b2c0badeb606d1232e5f78852c102c0a7989d3a534b3129e7856a52f3d161", - "sha256:b39321f1a74d1f9183bf1638a745b4fd6fe80efbb1f6b32b932a588b4bc7695f", - "sha256:cae14a01a159b1ed91a324722d746523ec757357260c6804d11d6147a9e53e3f", - "sha256:cd49930af1d1e49a812d987c2620ee63965b619257bd76eaaa95870ca08837cf", - "sha256:e15b382603c58f24265c9c931c9a45eebf44fe2e6b4eaedbb0d025ab3255228b", - "sha256:e91d31b34fc7c2c8f756b4e902f901f856ae53a93399368d9a0dc7be17ed2ca0", - "sha256:ef627986941b5edd1ed74ba89ca43196ed197f1a206a3f18cc9faf2fb84fd675", - "sha256:f718a7949d1c4f622ff548c572e0c03440b49b9531ff00e4ed5738b459f011e8" - ], - "index": "pypi", - "version": "==1.18.5" + "sha256:13af0184177469192d80db9bd02619f6fa8b922f9f327e077d6f2a6acb1ce1c0", + "sha256:26a45798ca2a4e168d00de75d4a524abf5907949231512f372b217ede3429e98", + "sha256:26f509450db547e4dfa3ec739419b31edad646d21fb8d0ed0734188b35ff6b27", + "sha256:30a59fb41bb6b8c465ab50d60a1b298d1cd7b85274e71f38af5a75d6c475d2d2", + "sha256:33c623ef9ca5e19e05991f127c1be5aeb1ab5cdf30cb1c5cf3960752e58b599b", + "sha256:356f96c9fbec59974a592452ab6a036cd6f180822a60b529a975c9467fcd5f23", + "sha256:3c40c827d36c6d1c3cf413694d7dc843d50997ebffbc7c87d888a203ed6403a7", + "sha256:4d054f013a1983551254e2379385e359884e5af105e3efe00418977d02f634a7", + "sha256:63d971bb211ad3ca37b2adecdd5365f40f3b741a455beecba70fd0dde8b2a4cb", + "sha256:658624a11f6e1c252b2cd170d94bf28c8f9410acab9f2fd4369e11e1cd4e1aaf", + "sha256:76766cc80d6128750075378d3bb7812cf146415bd29b588616f72c943c00d598", + "sha256:7b57f26e5e6ee2f14f960db46bd58ffdca25ca06dd997729b1b179fddd35f5a3", + "sha256:7b852817800eb02e109ae4a9cef2beda8dd50d98b76b6cfb7b5c0099d27b52d4", + "sha256:8cde829f14bd38f6da7b2954be0f2837043e8b8d7a9110ec5e318ae6bf706610", + "sha256:a2e3a39f43f0ce95204beb8fe0831199542ccab1e0c6e486a0b4947256215632", + "sha256:a86c962e211f37edd61d6e11bb4df7eddc4a519a38a856e20a6498c319efa6b0", + "sha256:a8705c5073fe3fcc297fb8e0b31aa794e05af6a329e81b7ca4ffecab7f2b95ef", + "sha256:b6aaeadf1e4866ca0fdf7bb4eed25e521ae21a7947c59f78154b24fc7abbe1dd", + "sha256:be62aeff8f2f054eff7725f502f6228298891fd648dc2630e03e44bf63e8cee0", + "sha256:c2edbb783c841e36ca0fa159f0ae97a88ce8137fb3a6cd82eae77349ba4b607b", + "sha256:cbe326f6d364375a8e5a8ccb7e9cd73f4b2f6dc3b2ed205633a0db8243e2a96a", + "sha256:d34fbb98ad0d6b563b95de852a284074514331e6b9da0a9fc894fb1cdae7a79e", + "sha256:d97a86937cf9970453c3b62abb55a6475f173347b4cde7f8dcdb48c8e1b9952d", + "sha256:dd53d7c4a69e766e4900f29db5872f5824a06827d594427cf1a4aa542818b796", + "sha256:df1889701e2dfd8ba4dc9b1a010f0a60950077fb5242bb92c8b5c7f1a6f2668a", + "sha256:fa1fe75b4a9e18b66ae7f0b122543c42debcf800aaafa0212aaff3ad273c2596" + ], + "index": "pypi", + "version": "==1.19.0" }, "oauthlib": { "hashes": [ @@ -1849,37 +1876,36 @@ }, "opencv-python": { "hashes": [ - "sha256:068928b9907b3d3acd53b129062557d6b0b8b324bfade77f028dbe4dfe482bf2", - "sha256:0e7c91718351449877c2d4141abd64eee1f9c8701bcfaf4e8627bd023e303368", - "sha256:1ab92d807427641ec45d28d5907426aa06b4ffd19c5b794729c74d91cd95090e", - "sha256:31d634dea1b47c231b88d384f90605c598214d0c596443c9bb808e11761829f5", - "sha256:5fdfc0bed37315f27d30ae5ae9bad47ec0a0a28c323739d39c8177b7e0929238", - "sha256:6fa8fac14dd5af4819d475f74af12d65fbbfa391d3110c3a972934a5e6507c24", - "sha256:78cc89ebc808886eb190626ee71ab65e47f374121975f86e4d5f7c0e3ce6bed9", - "sha256:7c7ba11720d01cb572b4b6945d115cb103462c0a28996b44d4e540d06e6a90fd", - "sha256:a37ee82f1b8ed4b4645619c504311e71ce845b78f40055e78d71add5fab7da82", - "sha256:aa3ca1f54054e1c6439fdf1edafa2a2b940a9eaac04a7b422a1cba9b2d7b9690", - "sha256:b9de3dd956574662712da8e285f0f54327959a4e95b96a2847d3c3f5ee7b96e2", - "sha256:c0087b428cef9a32d977390656d91b02245e0e91f909870492df7e39202645dd", - "sha256:d87e506ab205799727f0efa34b3888949bf029a3ada5eb000ff632606370ca6e", - "sha256:d8a55585631f9c9eca4b1a996e9732ae023169cf2f46f69e4518d67d96198226", - "sha256:dcb8da8c5ebaa6360c8555547a4c7beb6cd983dd95ba895bb78b86cc8cf3de2b", - "sha256:e2206bb8c17c0f212f1f356d82d72dd090ff4651994034416da9bf0c29732825", - "sha256:e3c57d6579e5bf85f564d6d48d8ee89868b92879a9232b9975d072c346625e92", - "sha256:ef89cbf332b9a735d8a82e9ff79cc743eeeb775ad1cd7100bc2aa2429b496f07", - "sha256:f45c1c3cdda1857bedd4dfe0bbd49c9419af0cc57f33490341edeae97d18f037", - "sha256:fb3c855347310788e4286b867997be354c55535597966ed5dac876d9166013a4" - ], - "index": "pypi", - "version": "==4.2.0.34" + "sha256:156e2954d5b38b676e8a24d66703cf15f252e24ec49db7e842a8b5eed46074ba", + "sha256:1bf486680a16d739f7852a62865b72eb7692df584694815774ba97b471b8bc3f", + "sha256:1ea08f22246ccd33174d59edfa3f13930bf2c28096568242090bd9d8770fb8a8", + "sha256:210ab40c8c9dadc7dc9ed7beebe2e0a2415a744f8d6857762a80c8e0fcc477c8", + "sha256:2ec6502bfac01b27ac06daf7bc9f7a4f482a6a0d8e1b30e15c411d478454a19f", + "sha256:2fe704e35808cf6b17b793e89fd00e9ef7779f85f274666a4e092671aedd09c0", + "sha256:4b93b5f8df187e4dba9fb25c46fa8cf342c257de144f7c86d75c06416566a199", + "sha256:55e1d7a2d11c40ea5b53aabe5c4122038803c7d492505c8f93af077aa7fe2ce1", + "sha256:677f61332436e22f83a1e4e6f6863a760734fbc8029ba6a8ef0af4554cde6f93", + "sha256:76ddc6daf8607eda1d866395dcf98526ef96f3e616d8c37ccc7629f9aaf6d4d4", + "sha256:c4f1e9d963c8f370284afa87fcf521cc8439a610a500bf8ede27fd64dd9050bd", + "sha256:c93b1198c85175a9fa9a9839c4da55c7ab9c5f57256f2e4211cd6c91d7d422e8", + "sha256:d765c44827778cbe6bc8f272cd61514e8509b93fd24dd3324cd4abddf2026b11", + "sha256:eb709245e56f6693d297f8818ff8e6c017fa80fdb5a923c64be623a678c7150e", + "sha256:ef4ac758a4e2caee80ef9c86b83a279d6f132c9e7ae77957cf74013928814e05", + "sha256:f67c1d92ff96c6c106f786b7ef9b9ab448fa03ef28cb7bb6f0f7b857b65bc158", + "sha256:f6fa2834d85c78865ca6e3de563916086cb8c83c3f2ef80924fcd07005f05df9", + "sha256:fa1a6d149a1a5e0bc54c737a59fe38d75384a092ae5e35f9b876fbb621f755c6", + "sha256:fd457deedcf153dd6805a2b4d891ac2a0969566d3755fbf48a3ffb53978c9ed1" + ], + "index": "pypi", + "version": "==4.3.0.36" }, "opt-einsum": { "hashes": [ - "sha256:83b76a98d18ae6a5cc7a0d88955a7f74881f0e567a0f4c949d24c942753eb998", - "sha256:96f819d46da2f937eaf326336a114aaeccbcbdb9de460d42e8b5f480a69adca7" + "sha256:2455e59e3947d3c275477df7f5205b30635e266fe6dc300e3d9f9646bfcea147", + "sha256:59f6475f77bbc37dcf7cd748519c0ec60722e91e63ca114e68821c0c54a46549" ], "markers": "python_version >= '3.5'", - "version": "==3.2.1" + "version": "==3.3.0" }, "osmium": { "hashes": [ @@ -1988,32 +2014,35 @@ }, "pillow": { "hashes": [ - "sha256:04766c4930c174b46fd72d450674612ab44cca977ebbcc2dde722c6933290107", - "sha256:0e2a3bceb0fd4e0cb17192ae506d5f082b309ffe5fc370a5667959c9b2f85fa3", - "sha256:0f01e63c34f0e1e2580cc0b24e86a5ccbbfa8830909a52ee17624c4193224cd9", - "sha256:12e4bad6bddd8546a2f9771485c7e3d2b546b458ae8ff79621214119ac244523", - "sha256:1f694e28c169655c50bb89a3fa07f3b854d71eb47f50783621de813979ba87f3", - "sha256:3d25dd8d688f7318dca6d8cd4f962a360ee40346c15893ae3b95c061cdbc4079", - "sha256:4b02b9c27fad2054932e89f39703646d0c543f21d3cc5b8e05434215121c28cd", - "sha256:70e3e0d99a0dcda66283a185f80697a9b08806963c6149c8e6c5f452b2aa59c0", - "sha256:9744350687459234867cbebfe9df8f35ef9e1538f3e729adbd8fde0761adb705", - "sha256:a0b49960110bc6ff5fead46013bcb8825d101026d466f3a4de3476defe0fb0dd", - "sha256:ae2b270f9a0b8822b98655cb3a59cdb1bd54a34807c6c56b76dd2e786c3b7db3", - "sha256:b37bb3bd35edf53125b0ff257822afa6962649995cbdfde2791ddb62b239f891", - "sha256:b532bcc2f008e96fd9241177ec580829dee817b090532f43e54074ecffdcd97f", - "sha256:b67a6c47ed963c709ed24566daa3f95a18f07d3831334da570c71da53d97d088", - "sha256:b943e71c2065ade6fef223358e56c167fc6ce31c50bc7a02dd5c17ee4338e8ac", - "sha256:ccc9ad2460eb5bee5642eaf75a0438d7f8887d484490d5117b98edd7f33118b7", - "sha256:d23e2aa9b969cf9c26edfb4b56307792b8b374202810bd949effd1c6e11ebd6d", - "sha256:eaa83729eab9c60884f362ada982d3a06beaa6cc8b084cf9f76cae7739481dfa", - "sha256:ee94fce8d003ac9fd206496f2707efe9eadcb278d94c271f129ab36aa7181344", - "sha256:f455efb7a98557412dc6f8e463c1faf1f1911ec2432059fa3e582b6000fc90e2", - "sha256:f46e0e024346e1474083c729d50de909974237c72daca05393ee32389dabe457", - "sha256:f54be399340aa602066adb63a86a6a5d4f395adfdd9da2b9a0162ea808c7b276", - "sha256:f784aad988f12c80aacfa5b381ec21fd3f38f851720f652b9f33facc5101cf4d" - ], - "index": "pypi", - "version": "==7.1.2" + "sha256:0295442429645fa16d05bd567ef5cff178482439c9aad0411d3f0ce9b88b3a6f", + "sha256:06aba4169e78c439d528fdeb34762c3b61a70813527a2c57f0540541e9f433a8", + "sha256:09d7f9e64289cb40c2c8d7ad674b2ed6105f55dc3b09aa8e4918e20a0311e7ad", + "sha256:0a80dd307a5d8440b0a08bd7b81617e04d870e40a3e46a32d9c246e54705e86f", + "sha256:1ca594126d3c4def54babee699c055a913efb01e106c309fa6b04405d474d5ae", + "sha256:25930fadde8019f374400f7986e8404c8b781ce519da27792cbe46eabec00c4d", + "sha256:431b15cffbf949e89df2f7b48528be18b78bfa5177cb3036284a5508159492b5", + "sha256:52125833b070791fcb5710fabc640fc1df07d087fc0c0f02d3661f76c23c5b8b", + "sha256:5e51ee2b8114def244384eda1c82b10e307ad9778dac5c83fb0943775a653cd8", + "sha256:612cfda94e9c8346f239bf1a4b082fdd5c8143cf82d685ba2dba76e7adeeb233", + "sha256:6d7741e65835716ceea0fd13a7d0192961212fd59e741a46bbed7a473c634ed6", + "sha256:6edb5446f44d901e8683ffb25ebdfc26988ee813da3bf91e12252b57ac163727", + "sha256:725aa6cfc66ce2857d585f06e9519a1cc0ef6d13f186ff3447ab6dff0a09bc7f", + "sha256:8dad18b69f710bf3a001d2bf3afab7c432785d94fcf819c16b5207b1cfd17d38", + "sha256:94cf49723928eb6070a892cb39d6c156f7b5a2db4e8971cb958f7b6b104fb4c4", + "sha256:97f9e7953a77d5a70f49b9a48da7776dc51e9b738151b22dacf101641594a626", + "sha256:9ad7f865eebde135d526bb3163d0b23ffff365cf87e767c649550964ad72785d", + "sha256:a060cf8aa332052df2158e5a119303965be92c3da6f2d93b6878f0ebca80b2f6", + "sha256:c79f9c5fb846285f943aafeafda3358992d64f0ef58566e23484132ecd8d7d63", + "sha256:c92302a33138409e8f1ad16731568c55c9053eee71bb05b6b744067e1b62380f", + "sha256:d08b23fdb388c0715990cbc06866db554e1822c4bdcf6d4166cf30ac82df8c41", + "sha256:d350f0f2c2421e65fbc62690f26b59b0bcda1b614beb318c81e38647e0f673a1", + "sha256:ec29604081f10f16a7aea809ad42e27764188fc258b02259a03a8ff7ded3808d", + "sha256:edf31f1150778abd4322444c393ab9c7bd2af271dd4dafb4208fb613b1f3cdc9", + "sha256:f7e30c27477dffc3e85c2463b3e649f751789e0f6c8456099eea7ddd53be4a8a", + "sha256:ffe538682dc19cc542ae7c3e504fdf54ca7f86fb8a135e59dd6bc8627eae6cce" + ], + "index": "pypi", + "version": "==7.2.0" }, "pkginfo": { "hashes": [ @@ -2024,25 +2053,25 @@ }, "portalocker": { "hashes": [ - "sha256:091364838ed6fbb68ea291c28982d1e56125c0d9e3fad5a4ac001db54dd862dc", - "sha256:874d6063c6ceb185fe4771da41b01872d2c56d292db746698f8ad7bf1833c905" + "sha256:34cb36c618d88bcd9079beb36dcdc1848a3e3d92ac4eac59055bdeafc39f9d4a", + "sha256:6d6f5de5a3e68c4dd65a98ec1babb26d28ccc5e770e07b672d65d5a35e4b2d8a" ], - "version": "==1.7.0" + "version": "==1.7.1" }, "pprofile": { "hashes": [ - "sha256:2036522d201188641ab6766b3fea105ddeb72d3b752a7d6da695be7e7ba21656" + "sha256:c2787af57c44c48e6c7e518d522fd0f93983892bfaae74ed340da02ed500ec5f" ], "index": "pypi", - "version": "==2.0.4" + "version": "==2.0.5" }, "pre-commit": { "hashes": [ - "sha256:c5c8fd4d0e1c363723aaf0a8f9cba0f434c160b48c4028f4bae6d219177945b3", - "sha256:da463cf8f0e257f9af49047ba514f6b90dbd9b4f92f4c8847a3ccd36834874c7" + "sha256:1657663fdd63a321a4a739915d7d03baedd555b25054449090f97bb0cb30a915", + "sha256:e8b1315c585052e729ab7e99dcca5698266bedce9067d21dc909c23e3ceed626" ], "index": "pypi", - "version": "==2.5.1" + "version": "==2.6.0" }, "prometheus-client": { "hashes": [ @@ -2292,11 +2321,11 @@ }, "pymysql": { "hashes": [ - "sha256:3943fbbbc1e902f41daf7f9165519f140c4451c179380677e6a848587042561a", - "sha256:d8c059dcd81dedb85a9f034d5e22dcb4442c0b201908bede99e306d65ea7c8e7" + "sha256:adef15ceccf1ff544a23a6f46609f65187261dc8b0cf94c9644189c173b0a451", + "sha256:e14070bc84e050e0f80bf6063e31d276f03a0bb4d46b9eca2854566c4ae19837" ], "index": "pypi", - "version": "==0.9.3" + "version": "==0.10.0" }, "pynacl": { "hashes": [ @@ -2395,10 +2424,10 @@ }, "python-engineio": { "hashes": [ - "sha256:2da5e1e5565e170a17169d1a76eb6a099cc96f0a25a5b1e0f9785f151485daea", - "sha256:5423045623f094df67ace05d53737b88e39395ac3b1129798a31be2dbc6011cf" + "sha256:133bdb5fb89f43a53f8612fb1ddbb3a453318713dea18a9ecf5346ed0c0f793c", + "sha256:41353c2539493e9e30e0e75e53f9cbb670f09a5ebcf82fe738081a9ba28fe55c" ], - "version": "==3.13.0" + "version": "==3.13.1" }, "python-logstash": { "hashes": [ @@ -2531,11 +2560,11 @@ }, "requests": { "hashes": [ - "sha256:43999036bfa82904b6af1d99e4882b560e5e2c68e5c4b0aa03b655f3d7d73fee", - "sha256:b3f43d496c6daba4493e7c431722aeb7dbc6288f52a6e04e7b6023b0247817e6" + "sha256:b3559a131db72c33ee969480840fff4bb6dd111de7dd27c8ee1f820f4f00231b", + "sha256:fe75cc94a9443b9246fc7049224f75604b113c36acb93f87b80ed42c44cbb898" ], "index": "pypi", - "version": "==2.23.0" + "version": "==2.24.0" }, "requests-oauthlib": { "hashes": [ @@ -2663,37 +2692,54 @@ }, "simplejson": { "hashes": [ - "sha256:0fe3994207485efb63d8f10a833ff31236ed27e3b23dadd0bf51c9900313f8f2", - "sha256:17163e643dbf125bb552de17c826b0161c68c970335d270e174363d19e7ea882", - "sha256:1d1e929cdd15151f3c0b2efe953b3281b2fd5ad5f234f77aca725f28486466f6", - "sha256:1d346c2c1d7dd79c118f0cc7ec5a1c4127e0c8ffc83e7b13fc5709ff78c9bb84", - "sha256:1ea59f570b9d4916ae5540a9181f9c978e16863383738b69a70363bc5e63c4cb", - "sha256:1fbba86098bbfc1f85c5b69dc9a6d009055104354e0d9880bb00b692e30e0078", - "sha256:229edb079d5dd81bf12da952d4d825bd68d1241381b37d3acf961b384c9934de", - "sha256:22a7acb81968a7c64eba7526af2cf566e7e2ded1cb5c83f0906b17ff1540f866", - "sha256:2b4b2b738b3b99819a17feaf118265d0753d5536049ea570b3c43b51c4701e81", - "sha256:4cf91aab51b02b3327c9d51897960c554f00891f9b31abd8a2f50fd4a0071ce8", - "sha256:4fd5f79590694ebff8dc980708e1c182d41ce1fda599a12189f0ca96bf41ad70", - "sha256:5cfd495527f8b85ce21db806567de52d98f5078a8e9427b18e251c68bd573a26", - "sha256:60aad424e47c5803276e332b2a861ed7a0d46560e8af53790c4c4fb3420c26c2", - "sha256:7739940d68b200877a15a5ff5149e1599737d6dd55e302625650629350466418", - "sha256:7cce4bac7e0d66f3a080b80212c2238e063211fe327f98d764c6acbc214497fc", - "sha256:8027bd5f1e633eb61b8239994e6fc3aba0346e76294beac22a892eb8faa92ba1", - "sha256:86afc5b5cbd42d706efd33f280fec7bd7e2772ef54e3f34cf6b30777cd19a614", - "sha256:87d349517b572964350cc1adc5a31b493bbcee284505e81637d0174b2758ba17", - "sha256:8de378d589eccbc75941e480b4d5b4db66f22e4232f87543b136b1f093fff342", - "sha256:926bcbef9eb60e798eabda9cd0bbcb0fca70d2779aa0aa56845749d973eb7ad5", - "sha256:9a126c3a91df5b1403e965ba63b304a50b53d8efc908a8c71545ed72535374a3", - "sha256:ad8dd3454d0c65c0f92945ac86f7b9efb67fa2040ba1b0189540e984df904378", - "sha256:d140e9376e7f73c1f9e0a8e3836caf5eec57bbafd99259d56979da05a6356388", - "sha256:da00675e5e483ead345429d4f1374ab8b949fba4429d60e71ee9d030ced64037", - "sha256:daaf4d11db982791be74b23ff4729af2c7da79316de0bebf880fa2d60bcc8c5a", - "sha256:f4b64a1031acf33e281fd9052336d6dad4d35eee3404c95431c8c6bc7a9c0588", - "sha256:fc046afda0ed8f5295212068266c92991ab1f4a50c6a7144b69364bdee4a0159", - "sha256:fc9051d249dd5512e541f20330a74592f7a65b2d62e18122ca89bf71f94db748" - ], - "index": "pypi", - "version": "==3.17.0" + "sha256:034550078a11664d77bc1a8364c90bb7eef0e44c2dbb1fd0a4d92e3997088667", + "sha256:05b43d568300c1cd43f95ff4bfcff984bc658aa001be91efb3bb21df9d6288d3", + "sha256:0dd9d9c738cb008bfc0862c9b8fa6743495c03a0ed543884bf92fb7d30f8d043", + "sha256:10fc250c3edea4abc15d930d77274ddb8df4803453dde7ad50c2f5565a18a4bb", + "sha256:2862beabfb9097a745a961426fe7daf66e1714151da8bb9a0c430dde3d59c7c0", + "sha256:292c2e3f53be314cc59853bd20a35bf1f965f3bc121e007ab6fd526ed412a85d", + "sha256:2d3eab2c3fe52007d703a26f71cf649a8c771fcdd949a3ae73041ba6797cfcf8", + "sha256:2e7b57c2c146f8e4dadf84977a83f7ee50da17c8861fd7faf694d55e3274784f", + "sha256:311f5dc2af07361725033b13cc3d0351de3da8bede3397d45650784c3f21fbcf", + "sha256:344e2d920a7f27b4023c087ab539877a1e39ce8e3e90b867e0bfa97829824748", + "sha256:3fabde09af43e0cbdee407555383063f8b45bfb52c361bc5da83fcffdb4fd278", + "sha256:42b8b8dd0799f78e067e2aaae97e60d58a8f63582939af60abce4c48631a0aa4", + "sha256:4b3442249d5e3893b90cb9f72c7d6ce4d2ea144d2c0d9f75b9ae1e5460f3121a", + "sha256:55d65f9cc1b733d85ef95ab11f559cce55c7649a2160da2ac7a078534da676c8", + "sha256:5c659a0efc80aaaba57fcd878855c8534ecb655a28ac8508885c50648e6e659d", + "sha256:72d8a3ffca19a901002d6b068cf746be85747571c6a7ba12cbcf427bfb4ed971", + "sha256:75ecc79f26d99222a084fbdd1ce5aad3ac3a8bd535cd9059528452da38b68841", + "sha256:76ac9605bf2f6d9b56abf6f9da9047a8782574ad3531c82eae774947ae99cc3f", + "sha256:7d276f69bfc8c7ba6c717ba8deaf28f9d3c8450ff0aa8713f5a3280e232be16b", + "sha256:7f10f8ba9c1b1430addc7dd385fc322e221559d3ae49b812aebf57470ce8de45", + "sha256:8042040af86a494a23c189b5aa0ea9433769cc029707833f261a79c98e3375f9", + "sha256:813846738277729d7db71b82176204abc7fdae2f566e2d9fcf874f9b6472e3e6", + "sha256:845a14f6deb124a3bcb98a62def067a67462a000e0508f256f9c18eff5847efc", + "sha256:869a183c8e44bc03be1b2bbcc9ec4338e37fa8557fc506bf6115887c1d3bb956", + "sha256:8acf76443cfb5c949b6e781c154278c059b09ac717d2757a830c869ba000cf8d", + "sha256:8f713ea65958ef40049b6c45c40c206ab363db9591ff5a49d89b448933fa5746", + "sha256:934115642c8ba9659b402c8bdbdedb48651fb94b576e3b3efd1ccb079609b04a", + "sha256:9551f23e09300a9a528f7af20e35c9f79686d46d646152a0c8fc41d2d074d9b0", + "sha256:9a2b7543559f8a1c9ed72724b549d8cc3515da7daf3e79813a15bdc4a769de25", + "sha256:a55c76254d7cf8d4494bc508e7abb993a82a192d0db4552421e5139235604625", + "sha256:ad8f41c2357b73bc9e8606d2fa226233bf4d55d85a8982ecdfd55823a6959995", + "sha256:af4868da7dd53296cd7630687161d53a7ebe2e63814234631445697bd7c29f46", + "sha256:afebfc3dd3520d37056f641969ce320b071bc7a0800639c71877b90d053e087f", + "sha256:b59aa298137ca74a744c1e6e22cfc0bf9dca3a2f41f51bc92eb05695155d905a", + "sha256:bc00d1210567a4cdd215ac6e17dc00cb9893ee521cee701adfd0fa43f7c73139", + "sha256:c1cb29b1fced01f97e6d5631c3edc2dadb424d1f4421dad079cb13fc97acb42f", + "sha256:c94dc64b1a389a416fc4218cd4799aa3756f25940cae33530a4f7f2f54f166da", + "sha256:ceaa28a5bce8a46a130cd223e895080e258a88d51bf6e8de2fc54a6ef7e38c34", + "sha256:cff6453e25204d3369c47b97dd34783ca820611bd334779d22192da23784194b", + "sha256:d0b64409df09edb4c365d95004775c988259efe9be39697d7315c42b7a5e7e94", + "sha256:d4813b30cb62d3b63ccc60dd12f2121780c7a3068db692daeb90f989877aaf04", + "sha256:da3c55cdc66cfc3fffb607db49a42448785ea2732f055ac1549b69dcb392663b", + "sha256:e058c7656c44fb494a11443191e381355388443d543f6fc1a245d5d238544396", + "sha256:fed0f22bf1313ff79c7fc318f7199d6c2f96d4de3234b2f12a1eab350e597c06", + "sha256:ffd4e4877a78c84d693e491b223385e0271278f5f4e1476a4962dca6824ecfeb" + ], + "index": "pypi", + "version": "==3.17.2" }, "six": { "hashes": [ @@ -2705,41 +2751,42 @@ }, "sqlalchemy": { "hashes": [ - "sha256:128bc917ed20d78143a45024455ff0aed7d3b96772eba13d5dbaf9cc57e5c41b", - "sha256:156a27548ba4e1fed944ff9fcdc150633e61d350d673ae7baaf6c25c04ac1f71", - "sha256:27e2efc8f77661c9af2681755974205e7462f1ae126f498f4fe12a8b24761d15", - "sha256:2a12f8be25b9ea3d1d5b165202181f2b7da4b3395289000284e5bb86154ce87c", - "sha256:31c043d5211aa0e0773821fcc318eb5cbe2ec916dfbc4c6eea0c5188971988eb", - "sha256:65eb3b03229f684af0cf0ad3bcc771970c1260a82a791a8d07bffb63d8c95bcc", - "sha256:6cd157ce74a911325e164441ff2d9b4e244659a25b3146310518d83202f15f7a", - "sha256:703c002277f0fbc3c04d0ae4989a174753a7554b2963c584ce2ec0cddcf2bc53", - "sha256:869bbb637de58ab0a912b7f20e9192132f9fbc47fc6b5111cd1e0f6cdf5cf9b0", - "sha256:8a0e0cd21da047ea10267c37caf12add400a92f0620c8bc09e4a6531a765d6d7", - "sha256:8d01e949a5d22e5c4800d59b50617c56125fc187fbeb8fa423e99858546de616", - "sha256:925b4fe5e7c03ed76912b75a9a41dfd682d59c0be43bce88d3b27f7f5ba028fb", - "sha256:9cb1819008f0225a7c066cac8bb0cf90847b2c4a6eb9ebb7431dbd00c56c06c5", - "sha256:a87d496884f40c94c85a647c385f4fd5887941d2609f71043e2b73f2436d9c65", - "sha256:a9030cd30caf848a13a192c5e45367e3c6f363726569a56e75dc1151ee26d859", - "sha256:a9e75e49a0f1583eee0ce93270232b8e7bb4b1edc89cc70b07600d525aef4f43", - "sha256:b50f45d0e82b4562f59f0e0ca511f65e412f2a97d790eea5f60e34e5f1aabc9a", - "sha256:b7878e59ec31f12d54b3797689402ee3b5cfcb5598f2ebf26491732758751908", - "sha256:ce1ddaadee913543ff0154021d31b134551f63428065168e756d90bdc4c686f5", - "sha256:ce2646e4c0807f3461be0653502bb48c6e91a5171d6e450367082c79e12868bf", - "sha256:ce6c3d18b2a8ce364013d47b9cad71db815df31d55918403f8db7d890c9d07ae", - "sha256:e4e2664232005bd306f878b0f167a31f944a07c4de0152c444f8c61bbe3cfb38", - "sha256:e8aa395482728de8bdcca9cc0faf3765ab483e81e01923aaa736b42f0294f570", - "sha256:eb4fcf7105bf071c71068c6eee47499ab8d4b8f5a11fc35147c934f0faa60f23", - "sha256:ed375a79f06cad285166e5be74745df1ed6845c5624aafadec4b7a29c25866ef", - "sha256:f35248f7e0d63b234a109dd72fbfb4b5cb6cb6840b221d0df0ecbf54ab087654", - "sha256:f502ef245c492b391e0e23e94cba030ab91722dcc56963c85bfd7f3441ea2bbe", - "sha256:fe01bac7226499aedf472c62fa3b85b2c619365f3f14dd222ffe4f3aa91e5f98" - ], - "index": "pypi", - "version": "==1.3.17" + "sha256:0942a3a0df3f6131580eddd26d99071b48cfe5aaf3eab2783076fbc5a1c1882e", + "sha256:0ec575db1b54909750332c2e335c2bb11257883914a03bc5a3306a4488ecc772", + "sha256:109581ccc8915001e8037b73c29590e78ce74be49ca0a3630a23831f9e3ed6c7", + "sha256:16593fd748944726540cd20f7e83afec816c2ac96b082e26ae226e8f7e9688cf", + "sha256:427273b08efc16a85aa2b39892817e78e3ed074fcb89b2a51c4979bae7e7ba98", + "sha256:50c4ee32f0e1581828843267d8de35c3298e86ceecd5e9017dc45788be70a864", + "sha256:512a85c3c8c3995cc91af3e90f38f460da5d3cade8dc3a229c8e0879037547c9", + "sha256:57aa843b783179ab72e863512e14bdcba186641daf69e4e3a5761d705dcc35b1", + "sha256:621f58cd921cd71ba6215c42954ffaa8a918eecd8c535d97befa1a8acad986dd", + "sha256:6ac2558631a81b85e7fb7a44e5035347938b0a73f5fdc27a8566777d0792a6a4", + "sha256:716754d0b5490bdcf68e1e4925edc02ac07209883314ad01a137642ddb2056f1", + "sha256:736d41cfebedecc6f159fc4ac0769dc89528a989471dc1d378ba07d29a60ba1c", + "sha256:8619b86cb68b185a778635be5b3e6018623c0761dde4df2f112896424aa27bd8", + "sha256:87fad64529cde4f1914a5b9c383628e1a8f9e3930304c09cf22c2ae118a1280e", + "sha256:89494df7f93b1836cae210c42864b292f9b31eeabca4810193761990dc689cce", + "sha256:8cac7bb373a5f1423e28de3fd5fc8063b9c8ffe8957dc1b1a59cb90453db6da1", + "sha256:8fd452dc3d49b3cc54483e033de6c006c304432e6f84b74d7b2c68afa2569ae5", + "sha256:adad60eea2c4c2a1875eb6305a0b6e61a83163f8e233586a4d6a55221ef984fe", + "sha256:c26f95e7609b821b5f08a72dab929baa0d685406b953efd7c89423a511d5c413", + "sha256:cbe1324ef52ff26ccde2cb84b8593c8bf930069dfc06c1e616f1bfd4e47f48a3", + "sha256:d05c4adae06bd0c7f696ae3ec8d993ed8ffcc4e11a76b1b35a5af8a099bd2284", + "sha256:d98bc827a1293ae767c8f2f18be3bb5151fd37ddcd7da2a5f9581baeeb7a3fa1", + "sha256:da2fb75f64792c1fc64c82313a00c728a7c301efe6a60b7a9fe35b16b4368ce7", + "sha256:e4624d7edb2576cd72bb83636cd71c8ce544d8e272f308bd80885056972ca299", + "sha256:e89e0d9e106f8a9180a4ca92a6adde60c58b1b0299e1b43bd5e0312f535fbf33", + "sha256:f11c2437fb5f812d020932119ba02d9e2bc29a6eca01a055233a8b449e3e1e7d", + "sha256:f57be5673e12763dd400fea568608700a63ce1c6bd5bdbc3cc3a2c5fdb045274", + "sha256:fc728ece3d5c772c196fd338a99798e7efac7a04f9cb6416299a3638ee9a94cd" + ], + "index": "pypi", + "version": "==1.3.18" }, "subprocess32": { "hashes": [ "sha256:88e37c1aac5388df41cc8a8456bb49ebffd321a3ad4d70358e3518176de3a56b", + "sha256:e45d985aef903c5b7444d34350b05da91a9e0ea015415ab45a21212786c649d0", "sha256:eb2937c80497978d181efa1b839ec2d9622cf9600a039a79d0e108d1f9aec79d" ], "index": "pypi", @@ -2769,10 +2816,9 @@ }, "tensorboard-plugin-wit": { "hashes": [ - "sha256:1fdf4ac343f1665453205aef8bb227b0204893bb5ffb792d2ed4509b1daf3d4f", - "sha256:243f117d117f9e81a21dc64b602b2bcb256ca5ba038867b96022d02271b17106" + "sha256:ee775f04821185c90d9a0e9c56970ee43d7c41403beb6629385b39517129685b" ], - "version": "==1.6.0.post3" + "version": "==1.7.0" }, "tensorflow": { "hashes": [ @@ -2821,11 +2867,11 @@ }, "tifffile": { "hashes": [ - "sha256:66d90f05eec5e62336d87d0d09e6a218012afdf834c22d66abc62ba88b355e39", - "sha256:e79403a8b98b0df7ade8d43469151b959fd56239001471fac62beabca6f56377" + "sha256:5bcad7e2e1d88c7923da662bf85ca2a1302ceaea04198d4ca696e0f7e7908576", + "sha256:9664322ba8d685905c43bf247c03b5c31fe1e9d7dc9b5b099ec6c52bab482151" ], "markers": "python_version >= '3.6'", - "version": "==2020.6.3" + "version": "==2020.7.17" }, "toml": { "hashes": [ @@ -2900,11 +2946,11 @@ }, "virtualenv": { "hashes": [ - "sha256:f332ba0b2dfbac9f6b1da9f11224f0036b05cdb4df23b228527c2a2d5504aeed", - "sha256:ffffcb3c78a671bb3d590ac3bc67c081ea2188befeeb058870cba13e7f82911b" + "sha256:26cdd725a57fef4c7c22060dba4647ebd8ca377e30d1c1cf547b30a0b79c43b4", + "sha256:c51f1ba727d1614ce8fd62457748b469fbedfdab2c7e5dd480c9ae3fbe1233f1" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==20.0.25" + "version": "==20.0.27" }, "wcwidth": { "hashes": [ diff --git a/common/kalman/simple_kalman_old.py b/common/kalman/simple_kalman_old.py index 3f7d049cc5..d11770faf6 100644 --- a/common/kalman/simple_kalman_old.py +++ b/common/kalman/simple_kalman_old.py @@ -8,7 +8,7 @@ class KF1D: def __init__(self, x0, A, C, K): self.x = x0 self.A = A - self.C = C + self.C = np.atleast_2d(C) self.K = K self.A_K = self.A - np.dot(self.K, self.C) diff --git a/common/kalman/tests/test_simple_kalman.py b/common/kalman/tests/test_simple_kalman.py index 9b947a4320..6308759984 100644 --- a/common/kalman/tests/test_simple_kalman.py +++ b/common/kalman/tests/test_simple_kalman.py @@ -21,10 +21,10 @@ class TestSimpleKalman(unittest.TestCase): K0_0 = 0.12287673 K1_0 = 0.29666309 - self.kf_old = KF1D_old(x0=np.matrix([[x0_0], [x1_0]]), - A=np.matrix([[A0_0, A0_1], [A1_0, A1_1]]), - C=np.matrix([C0_0, C0_1]), - K=np.matrix([[K0_0], [K1_0]])) + self.kf_old = KF1D_old(x0=np.array([[x0_0], [x1_0]]), + A=np.array([[A0_0, A0_1], [A1_0, A1_1]]), + C=np.array([C0_0, C0_1]), + K=np.array([[K0_0], [K1_0]])) self.kf = KF1D(x0=[[x0_0], [x1_0]], A=[[A0_0, A0_1], [A1_0, A1_1]], @@ -47,8 +47,8 @@ class TestSimpleKalman(unittest.TestCase): x = self.kf.update(v_wheel) # Compare the output x, verify that the error is less than 1e-4 - self.assertAlmostEqual(x_old[0], x[0]) - self.assertAlmostEqual(x_old[1], x[1]) + np.testing.assert_almost_equal(x_old[0], x[0]) + np.testing.assert_almost_equal(x_old[1], x[1]) def test_new_is_faster(self): setup = """ @@ -69,10 +69,10 @@ C0_1 = 0.0 K0_0 = 0.12287673 K1_0 = 0.29666309 -kf_old = KF1D_old(x0=np.matrix([[x0_0], [x1_0]]), - A=np.matrix([[A0_0, A0_1], [A1_0, A1_1]]), - C=np.matrix([C0_0, C0_1]), - K=np.matrix([[K0_0], [K1_0]])) +kf_old = KF1D_old(x0=np.array([[x0_0], [x1_0]]), + A=np.array([[A0_0, A0_1], [A1_0, A1_1]]), + C=np.array([C0_0, C0_1]), + K=np.array([[K0_0], [K1_0]])) kf = KF1D(x0=[[x0_0], [x1_0]], A=[[A0_0, A0_1], [A1_0, A1_1]], From 5139b827af21a71a5f07719486cb168773f838fa Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 22 Jul 2020 11:50:58 +0200 Subject: [PATCH 491/656] add tolerance to process replay compare (#1904) --- selfdrive/test/process_replay/compare_logs.py | 17 ++++++++++++++++- selfdrive/test/process_replay/process_replay.py | 8 +++++++- selfdrive/test/process_replay/test_processes.py | 2 +- 3 files changed, 24 insertions(+), 3 deletions(-) diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py index 39bf8690ac..4845575238 100755 --- a/selfdrive/test/process_replay/compare_logs.py +++ b/selfdrive/test/process_replay/compare_logs.py @@ -5,6 +5,7 @@ import sys import numbers import dictdiffer + if "CI" in os.environ: def tqdm(x): return x @@ -13,6 +14,8 @@ else: from tools.lib.logreader import LogReader +EPSILON = sys.float_info.epsilon + def save_log(dest, log_msgs): dat = b"" @@ -49,7 +52,7 @@ def remove_ignored_fields(msg, ignore): return msg.as_reader() -def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None): +def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=None): if ignore_fields is None: ignore_fields = [] @@ -70,7 +73,19 @@ def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None): if msg1_bytes != msg2_bytes: msg1_dict = msg1.to_dict(verbose=True) msg2_dict = msg2.to_dict(verbose=True) + + tolerance = EPSILON if tolerance is None else tolerance dd = dictdiffer.diff(msg1_dict, msg2_dict, ignore=ignore_fields) + + # Dictiffer only supports relative tolerance, we also want to check for absolute + def outside_tolerance(diff): + a, b = diff[2] + if isinstance(a, numbers.Number) and isinstance(b, numbers.Number): + return abs(a - b) > max(tolerance, tolerance * max(abs(a), abs(b))) + return True + + dd = list(filter(outside_tolerance, dd)) + diff.extend(dd) return diff diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 19e6301d3a..58ac4bab58 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -19,7 +19,7 @@ from common.params import Params from cereal.services import service_list from collections import namedtuple -ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'init_callback', 'should_recv_callback']) +ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'init_callback', 'should_recv_callback', 'tolerance']) def wait_for_event(evt): @@ -218,6 +218,7 @@ CONFIGS = [ ignore=["logMonoTime", "valid", "controlsState.startMonoTime", "controlsState.cumLagMs"], init_callback=fingerprint, should_recv_callback=None, + tolerance=None, ), ProcessConfig( proc_name="radard", @@ -228,6 +229,7 @@ CONFIGS = [ ignore=["logMonoTime", "valid", "radarState.cumLagMs"], init_callback=get_car_params, should_recv_callback=radar_rcv_callback, + tolerance=None, ), ProcessConfig( proc_name="plannerd", @@ -238,6 +240,7 @@ CONFIGS = [ ignore=["logMonoTime", "valid", "plan.processingDelay"], init_callback=get_car_params, should_recv_callback=None, + tolerance=None, ), ProcessConfig( proc_name="calibrationd", @@ -248,6 +251,7 @@ CONFIGS = [ ignore=["logMonoTime", "valid"], init_callback=get_car_params, should_recv_callback=calibration_rcv_callback, + tolerance=None, ), ProcessConfig( proc_name="dmonitoringd", @@ -258,6 +262,7 @@ CONFIGS = [ ignore=["logMonoTime", "valid"], init_callback=get_car_params, should_recv_callback=None, + tolerance=None, ), ProcessConfig( proc_name="locationd", @@ -268,6 +273,7 @@ CONFIGS = [ ignore=["logMonoTime", "valid"], init_callback=get_car_params, should_recv_callback=None, + tolerance=1e-7, # Numpy gives different results based on CPU features after version 19 ), ] diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index c40604aa00..8156269a8a 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -71,7 +71,7 @@ def test_process(cfg, lr, cmp_log_fn, ignore_fields=None, ignore_msgs=None): segment = cmp_log_fn.split("/")[-1].split("_")[0] raise Exception("Route never enabled: %s" % segment) - return compare_logs(cmp_log_msgs, log_msgs, ignore_fields+cfg.ignore, ignore_msgs) + return compare_logs(cmp_log_msgs, log_msgs, ignore_fields+cfg.ignore, ignore_msgs, cfg.tolerance) def format_diff(results, ref_commit): From 3b428fdebb3366a394b984b2778bc5a5bd8d8ed8 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 22 Jul 2020 20:17:27 -0700 Subject: [PATCH 492/656] fix modeld replay test --- selfdrive/test/process_replay/camera_replay.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/camera_replay.py b/selfdrive/test/process_replay/camera_replay.py index 8abe2c1a15..501f8f6111 100755 --- a/selfdrive/test/process_replay/camera_replay.py +++ b/selfdrive/test/process_replay/camera_replay.py @@ -93,7 +93,7 @@ if __name__ == "__main__": log_fn = "%s_%s_%s.bz2" % (TEST_ROUTE, "model", ref_commit) cmp_log = LogReader(BASE_URL + log_fn) results: Any = {TEST_ROUTE: {}} - results[TEST_ROUTE]["modeld"] = compare_logs(cmp_log, log_msgs, ignore_fields=['logMonoTime', 'valid']) + results[TEST_ROUTE]["modeld"] = compare_logs(cmp_log, log_msgs, ignore_fields=['logMonoTime', 'valid', 'model.frameDropPerc']) diff1, diff2, failed = format_diff(results, ref_commit) print(diff1) From 5f59fd4f40fda2dc07ab140253730058726ea753 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 22 Jul 2020 12:10:45 +0200 Subject: [PATCH 493/656] fix cppcheck on ubuntu 19.10 --- .pre-commit-config.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 3b4fa8a340..1cd805de4a 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -38,9 +38,10 @@ repos: entry: cppcheck language: system types: [c++] - exclude: '^(phonelibs)|(external)|(cereal)|(opendbc)|(panda)|(tools)|(selfdrive/modeld/thneed/debug)|(selfdrive/modeld/test)|(selfdrive/camerad/test)/' + exclude: '^(phonelibs)|(external)|(cereal)|(opendbc)|(panda)|(tools)|(selfdrive/modeld/thneed/debug)|(selfdrive/modeld/test)|(selfdrive/camerad/test)/|(installer)' args: - --error-exitcode=1 + - --language=c++ - --quiet - --force - -j8 From 0ac2f6c47052f50ebb6eb05381a74135c1cec885 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 23 Jul 2020 15:31:32 +0200 Subject: [PATCH 494/656] make sure boardd loopback test can run standalone --- selfdrive/boardd/tests/test_boardd_loopback.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) mode change 100644 => 100755 selfdrive/boardd/tests/test_boardd_loopback.py diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py old mode 100644 new mode 100755 index 39c33b127d..8081984b30 --- a/selfdrive/boardd/tests/test_boardd_loopback.py +++ b/selfdrive/boardd/tests/test_boardd_loopback.py @@ -30,11 +30,10 @@ def reset_panda(fn): os.environ['STARTED'] = '1' os.environ['BOARDD_LOOPBACK'] = '1' os.environ['PARAMS_PATH'] = PARAMS + @reset_panda @with_processes(['boardd']) def test_boardd_loopback(): - - # wait for boardd to init spinner = Spinner() time.sleep(2) @@ -81,3 +80,7 @@ def test_boardd_loopback(): assert not len(sent_msgs[bus]), f"loop {i}: bus {bus} missing {len(sent_msgs[bus])} messages" spinner.close() + + +if __name__ == "__main__": + test_boardd_loopback() From 2232efbcd4704dfe2713bb84b27056bbef5b1cac Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 23 Jul 2020 21:37:28 +0800 Subject: [PATCH 495/656] boardd: release claimed interface before closing usb (#1855) * release claimed interface * pass device handle by reference Co-authored-by: Willem Melching --- selfdrive/boardd/boardd.cc | 20 +++++++++++--------- 1 file changed, 11 insertions(+), 9 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index c44af47364..871092ab1f 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -142,6 +142,15 @@ void *safety_setter_thread(void *s) { return NULL; } +void usb_close(libusb_device_handle* &dev_handle) { + if (!dev_handle) { + return; + } + libusb_release_interface(dev_handle, 0); + libusb_close(dev_handle); + dev_handle = NULL; +} + // must be called before threads or with mutex bool usb_connect() { int err, err2; @@ -154,10 +163,7 @@ bool usb_connect() { ignition_last = false; - if (dev_handle != NULL){ - libusb_close(dev_handle); - dev_handle = NULL; - } + usb_close(dev_handle); dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); if (dev_handle == NULL) { goto fail; } @@ -931,7 +937,6 @@ int main() { assert(err == 0); // join threads - err = pthread_join(can_recv_thread_handle, NULL); assert(err == 0); @@ -941,10 +946,7 @@ int main() { err = pthread_join(can_health_thread_handle, NULL); assert(err == 0); - //while (!do_exit) usleep(1000); - // destruct libusb - - libusb_close(dev_handle); + usb_close(dev_handle); libusb_exit(ctx); } From c788aa99ddb78e3a01ad3685f5e8be84c7806481 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 23 Jul 2020 21:52:59 +0800 Subject: [PATCH 496/656] fix buffer overflow (#1871) --- selfdrive/boardd/boardd.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 871092ab1f..af86be7e05 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -740,7 +740,7 @@ void hexdump(unsigned char *d, int l) { void _pigeon_send(const char *dat, int len) { int sent; - unsigned char a[0x20]; + unsigned char a[0x20+1]; int err; a[0] = 1; for (int i=0; i Date: Thu, 23 Jul 2020 23:27:08 +0800 Subject: [PATCH 497/656] boardd: Add new functions usb_read, usb_write (#1856) * add func usb_write&usb_read * rename cnt to err * pass in device handle * use defines for flag values * consistent spaces Co-authored-by: Willem Melching --- selfdrive/boardd/boardd.cc | 127 +++++++++++++++++-------------------- 1 file changed, 59 insertions(+), 68 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index af86be7e05..45ddf0316a 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -80,14 +80,39 @@ pthread_t pigeon_thread_handle; bool pigeon_needs_init; +int usb_write(libusb_device_handle* dev_handle, uint8_t bRequest, uint16_t wValue, uint16_t wIndex, pthread_mutex_t *lock=NULL, unsigned int timeout=TIMEOUT) { + const uint8_t bmRequestType = LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; + + if (lock) pthread_mutex_lock(lock); + int err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, NULL, 0, timeout); + if (lock) pthread_mutex_unlock(lock); + return err; +} + +int usb_read(libusb_device_handle* dev_handle, uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned char *data, uint16_t wLength, pthread_mutex_t *lock=NULL, unsigned int timeout=TIMEOUT) { + const uint8_t bmRequestType = LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; + + if (lock) pthread_mutex_lock(lock); + int err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, data, wLength, timeout); + if (lock) pthread_mutex_unlock(lock); + return err; +} + +void usb_close(libusb_device_handle* &dev_handle) { + if (!dev_handle) { + return; + } + libusb_release_interface(dev_handle, 0); + libusb_close(dev_handle); + dev_handle = NULL; +} + void pigeon_init(); void *pigeon_thread(void *crap); void *safety_setter_thread(void *s) { // diagnostic only is the default, needed for VIN query - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0x40, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::ELM327), 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_write(dev_handle, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::ELM327), 0, &usb_lock); // switch to SILENT when CarVin param is read while (1) { @@ -104,9 +129,7 @@ void *safety_setter_thread(void *s) { } // VIN query done, stop listening to OBDII - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0x40, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::NO_OUTPUT), 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_write(dev_handle, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::NO_OUTPUT), 0, &usb_lock); std::vector params; LOGW("waiting for params to set safety model"); @@ -135,21 +158,13 @@ void *safety_setter_thread(void *s) { // set in the mutex to avoid race safety_setter_thread_initialized = false; - libusb_control_transfer(dev_handle, 0x40, 0xdc, safety_model, safety_param, NULL, 0, TIMEOUT); + usb_write(dev_handle, 0xdc, safety_model, safety_param); pthread_mutex_unlock(&usb_lock); return NULL; } -void usb_close(libusb_device_handle* &dev_handle) { - if (!dev_handle) { - return; - } - libusb_release_interface(dev_handle, 0); - libusb_close(dev_handle); - dev_handle = NULL; -} // must be called before threads or with mutex bool usb_connect() { @@ -175,12 +190,12 @@ bool usb_connect() { if (err != 0) { goto fail; } if (loopback_can) { - libusb_control_transfer(dev_handle, 0xc0, 0xe5, 1, 0, NULL, 0, TIMEOUT); + usb_write(dev_handle, 0xe5, 1, 0); } // get panda fw - err = libusb_control_transfer(dev_handle, 0xc0, 0xd3, 0, 0, fw_sig_buf, 64, TIMEOUT); - err2 = libusb_control_transfer(dev_handle, 0xc0, 0xd4, 0, 0, fw_sig_buf + 64, 64, TIMEOUT); + err = usb_read(dev_handle, 0xd3, 0, 0, fw_sig_buf, 64); + err2 = usb_read(dev_handle, 0xd4, 0, 0, fw_sig_buf + 64, 64); if ((err == 64) && (err2 == 64)) { printf("FW signature read\n"); write_db_value("PandaFirmware", (const char *)fw_sig_buf, 128); @@ -194,7 +209,7 @@ bool usb_connect() { else { goto fail; } // get panda serial - err = libusb_control_transfer(dev_handle, 0xc0, 0xd0, 0, 0, serial_buf, 16, TIMEOUT); + err = usb_read(dev_handle, 0xd0, 0, 0, serial_buf, 16); if (err > 0) { serial = (const char *)serial_buf; @@ -207,12 +222,12 @@ bool usb_connect() { // power on charging, only the first time. Panda can also change mode and it causes a brief disconneciton #ifndef __x86_64__ if (!connected_once) { - libusb_control_transfer(dev_handle, 0xc0, 0xe6, (uint16_t)(cereal::HealthData::UsbPowerMode::CDP), 0, NULL, 0, TIMEOUT); + usb_write(dev_handle, 0xe6, (uint16_t)(cereal::HealthData::UsbPowerMode::CDP), 0); } #endif connected_once = true; - libusb_control_transfer(dev_handle, 0xc0, 0xc1, 0, 0, hw_query, 1, TIMEOUT); + usb_read(dev_handle, 0xc1, 0, 0, hw_query, 1); hw_type = (cereal::HealthData::HwType)(hw_query[0]); is_pigeon = (hw_type == cereal::HealthData::HwType::GREY_PANDA) || @@ -238,7 +253,7 @@ bool usb_connect() { // Get time from RTC timestamp_t rtc_time; - libusb_control_transfer(dev_handle, 0xc0, 0xa0, 0, 0, (unsigned char*)&rtc_time, sizeof(rtc_time), TIMEOUT); + usb_read(dev_handle, 0xa0, 0, 0, (unsigned char*)&rtc_time, sizeof(rtc_time)); //printf("System: %d-%d-%d\t%d:%d:%d\n", 1900 + sys_time.tm_year, 1 + sys_time.tm_mon, sys_time.tm_mday, sys_time.tm_hour, sys_time.tm_min, sys_time.tm_sec); //printf("RTC: %d-%d-%d\t%d:%d:%d\n", rtc_time.year, rtc_time.month, rtc_time.day, rtc_time.hour, rtc_time.minute, rtc_time.second); @@ -371,10 +386,7 @@ void can_health(PubMaster &pm) { // recv from board if (dev_handle != NULL) { - pthread_mutex_lock(&usb_lock); - cnt = libusb_control_transfer(dev_handle, 0xc0, 0xd2, 0, 0, (unsigned char*)&health, sizeof(health), TIMEOUT); - pthread_mutex_unlock(&usb_lock); - + cnt = usb_read(dev_handle, 0xd2, 0, 0, (unsigned char*)&health, sizeof(health), &usb_lock); received = (cnt == sizeof(health)); } @@ -393,9 +405,7 @@ void can_health(PubMaster &pm) { // Make sure CAN buses are live: safety_setter_thread does not work if Panda CAN are silent and there is only one other CAN node if (health.safety_model == (uint8_t)(cereal::CarParams::SafetyModel::SILENT)) { - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0x40, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::NO_OUTPUT), 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_write(dev_handle, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::NO_OUTPUT), 0, &usb_lock); } bool ignition = ((health.ignition_line != 0) || (health.ignition_can != 0)); @@ -413,35 +423,25 @@ void can_health(PubMaster &pm) { std::vector disable_power_down = read_db_bytes("DisablePowerDown"); if (disable_power_down.size() != 1 || disable_power_down[0] != '1') { printf("TURN OFF CHARGING!\n"); - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0xc0, 0xe6, (uint16_t)(cereal::HealthData::UsbPowerMode::CLIENT), 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_write(dev_handle, 0xe6, (uint16_t)(cereal::HealthData::UsbPowerMode::CLIENT), 0, &usb_lock); printf("POWER DOWN DEVICE\n"); system("service call power 17 i32 0 i32 1"); } } if (!no_ignition_exp && (voltage_f > VBATT_START_CHARGING) && !cdp_mode) { printf("TURN ON CHARGING!\n"); - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0xc0, 0xe6, (uint16_t)(cereal::HealthData::UsbPowerMode::CDP), 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_write(dev_handle, 0xe6, (uint16_t)(cereal::HealthData::UsbPowerMode::CDP), 0, &usb_lock); } // set power save state enabled when car is off and viceversa when it's on if (ignition && (health.power_save_enabled == 1)) { - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0xc0, 0xe7, 0, 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_write(dev_handle, 0xe7, 0, 0, &usb_lock); } if (!ignition && (health.power_save_enabled == 0)) { - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0xc0, 0xe7, 1, 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_write(dev_handle, 0xe7, 1, 0, &usb_lock); } // set safety mode to NO_OUTPUT when car is off. ELM327 is an alternative if we want to leverage athenad/connect if (!ignition && (health.safety_model != (uint8_t)(cereal::CarParams::SafetyModel::NO_OUTPUT))) { - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0x40, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::NO_OUTPUT), 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_write(dev_handle, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::NO_OUTPUT), 0, &usb_lock); } #endif @@ -462,9 +462,7 @@ void can_health(PubMaster &pm) { // Get fan RPM uint16_t fan_speed_rpm = 0; - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0xc0, 0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm), TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_read(dev_handle, 0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm), &usb_lock); // Write to rtc once per minute when no ignition present if ((hw_type == cereal::HealthData::HwType::UNO) && !ignition && (no_ignition_cnt % 120 == 1)){ @@ -478,13 +476,13 @@ void can_health(PubMaster &pm) { // Write time to RTC if it looks reasonable if (1900 + sys_time.tm_year >= 2019){ pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0x40, 0xa1, (uint16_t)(1900 + sys_time.tm_year), 0, NULL, 0, TIMEOUT); - libusb_control_transfer(dev_handle, 0x40, 0xa2, (uint16_t)(1 + sys_time.tm_mon), 0, NULL, 0, TIMEOUT); - libusb_control_transfer(dev_handle, 0x40, 0xa3, (uint16_t)sys_time.tm_mday, 0, NULL, 0, TIMEOUT); - // libusb_control_transfer(dev_handle, 0x40, 0xa4, (uint16_t)(1 + sys_time.tm_wday), 0, NULL, 0, TIMEOUT); - libusb_control_transfer(dev_handle, 0x40, 0xa5, (uint16_t)sys_time.tm_hour, 0, NULL, 0, TIMEOUT); - libusb_control_transfer(dev_handle, 0x40, 0xa6, (uint16_t)sys_time.tm_min, 0, NULL, 0, TIMEOUT); - libusb_control_transfer(dev_handle, 0x40, 0xa7, (uint16_t)sys_time.tm_sec, 0, NULL, 0, TIMEOUT); + usb_write(dev_handle, 0xa1, (uint16_t)(1900 + sys_time.tm_year), 0); + usb_write(dev_handle, 0xa2, (uint16_t)(1 + sys_time.tm_mon), 0); + usb_write(dev_handle, 0xa3, (uint16_t)sys_time.tm_mday, 0); + // usb_write(dev_handle, 0xa4, (uint16_t)(1 + sys_time.tm_wday), 0); + usb_write(dev_handle, 0xa5, (uint16_t)sys_time.tm_hour, 0); + usb_write(dev_handle, 0xa6, (uint16_t)sys_time.tm_min, 0); + usb_write(dev_handle, 0xa7, (uint16_t)sys_time.tm_sec, 0); pthread_mutex_unlock(&usb_lock); } } @@ -527,9 +525,7 @@ void can_health(PubMaster &pm) { pm.send("health", msg); // send heartbeat back to panda - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0x40, 0xf3, 1, 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_write(dev_handle, 0xf3, 1, 0, &usb_lock); } @@ -689,10 +685,7 @@ void *hardware_control_thread(void *crap) { if (sm.updated("thermal")){ uint16_t fan_speed = sm["thermal"].getThermal().getFanSpeed(); if (fan_speed != prev_fan_speed || cnt % 100 == 0){ - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0x40, 0xb1, fan_speed, 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); - + usb_write(dev_handle, 0xb1, fan_speed, 0, &usb_lock); prev_fan_speed = fan_speed; } } @@ -716,9 +709,7 @@ void *hardware_control_thread(void *crap) { } if (ir_pwr != prev_ir_pwr || cnt % 100 == 0 || ir_pwr >= 50.0){ - pthread_mutex_lock(&usb_lock); - libusb_control_transfer(dev_handle, 0x40, 0xb0, ir_pwr, 0, NULL, 0, TIMEOUT); - pthread_mutex_unlock(&usb_lock); + usb_write(dev_handle, 0xb0, ir_pwr, 0, &usb_lock); prev_ir_pwr = ir_pwr; } @@ -758,7 +749,7 @@ void _pigeon_send(const char *dat, int len) { void pigeon_set_power(int power) { pthread_mutex_lock(&usb_lock); - int err = libusb_control_transfer(dev_handle, 0xc0, 0xd9, power, 0, NULL, 0, TIMEOUT); + int err = usb_write(dev_handle, 0xd9, power, 0); if (err < 0) { handle_usb_issue(err, __func__); } pthread_mutex_unlock(&usb_lock); } @@ -766,9 +757,9 @@ void pigeon_set_power(int power) { void pigeon_set_baud(int baud) { int err; pthread_mutex_lock(&usb_lock); - err = libusb_control_transfer(dev_handle, 0xc0, 0xe2, 1, 0, NULL, 0, TIMEOUT); + err = usb_write(dev_handle, 0xe2, 1, 0); if (err < 0) { handle_usb_issue(err, __func__); } - err = libusb_control_transfer(dev_handle, 0xc0, 0xe4, 1, baud/300, NULL, 0, TIMEOUT); + err = usb_write(dev_handle, 0xe4, 1, baud/300); if (err < 0) { handle_usb_issue(err, __func__); } pthread_mutex_unlock(&usb_lock); } @@ -848,7 +839,7 @@ void *pigeon_thread(void *crap) { int alen = 0; while (alen < 0xfc0) { pthread_mutex_lock(&usb_lock); - int len = libusb_control_transfer(dev_handle, 0xc0, 0xe0, 1, 0, dat+alen, 0x40, TIMEOUT); + int len = usb_read(dev_handle, 0xe0, 1, 0, dat+alen, 0x40); if (len < 0) { handle_usb_issue(len, __func__); } pthread_mutex_unlock(&usb_lock); if (len <= 0) break; From 8f6ea693963bfed8ccd27481c69dd6a7dd969458 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Thu, 23 Jul 2020 10:32:16 -0500 Subject: [PATCH 498/656] Add fwdCamera f/w for 2020 Corolla Hybrid ZR (AUS) (#1911) @iamty#6048 DongleID c4bfe655c9130ba4 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index ee0385cc64..35f744591d 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -614,6 +614,7 @@ FW_VERSIONS = { b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', ], }, From 7a1e229a9a692421fc038eec5be376b7f6bebc6d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 23 Jul 2020 17:51:45 +0200 Subject: [PATCH 499/656] fix spinner --- selfdrive/manager.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index b8917b02d3..4fe8f6c5ad 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -78,7 +78,7 @@ import traceback from multiprocessing import Process # Run scons -spinner = Spinner(noop=(__name__ != "main" or not ANDROID)) +spinner = Spinner(noop=(__name__ != "__main__" or not ANDROID)) spinner.update("0") if not prebuilt: From 74f95b8b26f39c61f91c83f46bbeb93bb43da968 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 23 Jul 2020 17:56:36 +0200 Subject: [PATCH 500/656] skip 1st segment in debug replay --- selfdrive/debug/internal/replay_drive_can.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/debug/internal/replay_drive_can.py b/selfdrive/debug/internal/replay_drive_can.py index 0009cd637f..05b7137977 100755 --- a/selfdrive/debug/internal/replay_drive_can.py +++ b/selfdrive/debug/internal/replay_drive_can.py @@ -11,7 +11,7 @@ NUM_SEGS = 10 # route has 82 segments available # Get can messages from logs print("Loading...") can_msgs = [] -for i in tqdm(list(range(NUM_SEGS))): +for i in tqdm(list(range(1, NUM_SEGS))): log_url = f"https://commadataci.blob.core.windows.net/openpilotci/{ROUTE}/{i}/rlog.bz2" lr = LogReader(log_url) can_msgs += [m for m in lr if m.which() == 'can'] From a086f52881f4a1f0d20486e7fa089a843d5d8b34 Mon Sep 17 00:00:00 2001 From: martinl Date: Thu, 23 Jul 2020 22:28:23 +0300 Subject: [PATCH 501/656] Subaru Global generated dbc and new signals (#1908) * Change carstate signals to use feature-subaru-long dbc * Add Conventional_Cruise signal to carstate * Fix Conventional_Cruise signal source * Use Cruise_Cancel signal in subarucan * switch to subaru-global-2020 opendbc branch * Update release file * bump opendbc * switch panda to subaru-global-carstate branch * bump panda * bump opendbc * revert submodules for upstream PR * switch panda and opendbc to upstream * bump opendbc --- opendbc | 2 +- release/files_common | 2 +- selfdrive/car/subaru/carstate.py | 43 +++++++++++++++++++++---------- selfdrive/car/subaru/subarucan.py | 2 +- selfdrive/car/subaru/values.py | 6 ++--- 5 files changed, 36 insertions(+), 19 deletions(-) diff --git a/opendbc b/opendbc index 993f0cc650..efb1e38aec 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 993f0cc650a1cc4915de8cade1b278acf57f5483 +Subproject commit efb1e38aec6949e738da5252f9a5839cb28ea2c8 diff --git a/release/files_common b/release/files_common index f06e6db317..d1ddced759 100644 --- a/release/files_common +++ b/release/files_common @@ -529,7 +529,7 @@ opendbc/mazda_2017.dbc opendbc/nissan_x_trail_2017.dbc opendbc/nissan_leaf_2018.dbc -opendbc/subaru_global_2017.dbc +opendbc/subaru_global_2017_generated.dbc opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc opendbc/toyota_rav4_2017_pt_generated.dbc diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index c2406f2ffe..b9b6eadbdc 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -48,11 +48,15 @@ class CarState(CarStateBase): ret.steeringTorque = cp.vl["Steering_Torque"]['Steer_Torque_Sensor'] ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD[self.car_fingerprint] + ret.steerError = cp.vl["Steering_Torque"]['Steer_Error_1'] == 1 + ret.steerWarning = cp.vl["Steering_Torque"]['Steer_Warning'] == 1 + ret.cruiseState.enabled = cp.vl["CruiseControl"]['Cruise_Activated'] != 0 ret.cruiseState.available = cp.vl["CruiseControl"]['Cruise_On'] != 0 ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]['Cruise_Set_Speed'] * CV.KPH_TO_MS - # EDM Impreza: 1 = mph, UDM Forester: 7 = mph - if cp.vl["Dash_State"]['Units'] in [1, 7]: + ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]['Conventional_Cruise'] == 1 + # EDM Impreza: 1,2 = mph, UDM Forester: 7 = mph + if cp.vl["Dash_State"]['Units'] in [1, 2, 7]: ret.cruiseState.speed *= CV.MPH_TO_KPH ret.seatbeltUnlatched = cp.vl["Dashlights"]['SEATBELT_FL'] == 1 @@ -73,6 +77,8 @@ class CarState(CarStateBase): # sig_name, sig_address, default ("Steer_Torque_Sensor", "Steering_Torque", 0), ("Steering_Angle", "Steering_Torque", 0), + ("Steer_Error_1", "Steering_Torque", 0), + ("Steer_Warning", "Steering_Torque", 0), ("Cruise_On", "CruiseControl", 0), ("Cruise_Activated", "CruiseControl", 0), ("Brake_Pedal", "Brake_Pedal", 0), @@ -111,12 +117,25 @@ class CarState(CarStateBase): def get_cam_can_parser(CP): signals = [ ("Cruise_Set_Speed", "ES_DashStatus", 0), + ("Conventional_Cruise", "ES_DashStatus", 0), ("Counter", "ES_Distance", 0), ("Signal1", "ES_Distance", 0), + ("Cruise_Fault", "ES_Distance", 0), + ("Cruise_Throttle", "ES_Distance", 0), ("Signal2", "ES_Distance", 0), - ("Main", "ES_Distance", 0), + ("Car_Follow", "ES_Distance", 0), ("Signal3", "ES_Distance", 0), + ("Cruise_Brake_Active", "ES_Distance", 0), + ("Distance_Swap", "ES_Distance", 0), + ("Cruise_EPB", "ES_Distance", 0), + ("Signal4", "ES_Distance", 0), + ("Close_Distance", "ES_Distance", 0), + ("Signal5", "ES_Distance", 0), + ("Cruise_Cancel", "ES_Distance", 0), + ("Cruise_Set", "ES_Distance", 0), + ("Cruise_Resume", "ES_Distance", 0), + ("Signal6", "ES_Distance", 0), ("Counter", "ES_LKAS_State", 0), ("Keep_Hands_On_Wheel", "ES_LKAS_State", 0), @@ -126,23 +145,21 @@ class CarState(CarStateBase): ("Signal2", "ES_LKAS_State", 0), ("Backward_Speed_Limit_Menu", "ES_LKAS_State", 0), ("LKAS_ENABLE_3", "ES_LKAS_State", 0), - ("Signal3", "ES_LKAS_State", 0), + ("LKAS_Left_Line_Light_Blink", "ES_LKAS_State", 0), ("LKAS_ENABLE_2", "ES_LKAS_State", 0), - ("Signal4", "ES_LKAS_State", 0), + ("LKAS_Right_Line_Light_Blink", "ES_LKAS_State", 0), ("LKAS_Left_Line_Visible", "ES_LKAS_State", 0), - ("Signal6", "ES_LKAS_State", 0), + ("LKAS_Left_Line_Green", "ES_LKAS_State", 0), ("LKAS_Right_Line_Visible", "ES_LKAS_State", 0), - ("Signal7", "ES_LKAS_State", 0), - ("FCW_Cont_Beep", "ES_LKAS_State", 0), - ("FCW_Repeated_Beep", "ES_LKAS_State", 0), - ("Throttle_Management_Activated", "ES_LKAS_State", 0), - ("Traffic_light_Ahead", "ES_LKAS_State", 0), - ("Right_Depart", "ES_LKAS_State", 0), - ("Signal5", "ES_LKAS_State", 0), + ("LKAS_Right_Line_Green", "ES_LKAS_State", 0), + ("LKAS_Alert", "ES_LKAS_State", 0), + ("Signal3", "ES_LKAS_State", 0), ] checks = [ ("ES_DashStatus", 10), + ("ES_Distance", 20), + ("ES_LKAS_State", 10), ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) diff --git a/selfdrive/car/subaru/subarucan.py b/selfdrive/car/subaru/subarucan.py index d0850afc9e..6f933bd7bb 100644 --- a/selfdrive/car/subaru/subarucan.py +++ b/selfdrive/car/subaru/subarucan.py @@ -24,7 +24,7 @@ def create_es_distance(packer, es_distance_msg, pcm_cancel_cmd): values = copy.copy(es_distance_msg) if pcm_cancel_cmd: - values["Main"] = 1 + values["Cruise_Cancel"] = 1 return packer.make_can_msg("ES_Distance", 0, values) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index d31c5cfb08..3959843783 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -43,7 +43,7 @@ ECU_FINGERPRINT = { } DBC = { - CAR.ASCENT: dbc_dict('subaru_global_2017', None), - CAR.IMPREZA: dbc_dict('subaru_global_2017', None), - CAR.FORESTER: dbc_dict('subaru_global_2017', None), + CAR.ASCENT: dbc_dict('subaru_global_2017_generated', None), + CAR.IMPREZA: dbc_dict('subaru_global_2017_generated', None), + CAR.FORESTER: dbc_dict('subaru_global_2017_generated', None), } From f753ca14ad1ab26eb81d48b50c6672e44c81334f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 23 Jul 2020 13:24:06 -0700 Subject: [PATCH 502/656] add HYUNDAI_GENESIS test route --- selfdrive/test/test_car_models.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index f8e4e37454..7ac72e170e 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -168,6 +168,10 @@ routes = { 'carFingerprint': HONDA.CIVIC_BOSCH, 'enableCamera': True, }, + "6fe86b4e410e4c37|2020-07-22--16-27-13": { + 'carFingerprint': HYUNDAI.HYUNDAI_GENESIS, + 'enableCamera': True, + }, "38bfd238edecbcd7|2018-08-22--09-45-44": { 'carFingerprint': HYUNDAI.SANTA_FE, 'enableCamera': False, From 61548f5a483e0fa7fba6f167017c3fbe73e3f684 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 23 Jul 2020 13:28:58 -0700 Subject: [PATCH 503/656] Only draw lead car indicators when controlling longitudinal (#1914) --- selfdrive/ui/paint.cc | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 8c17b4cf98..73d99755f6 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -368,11 +368,14 @@ static void ui_draw_world(UIState *s) { // Draw lane edges and vision/mpc tracks ui_draw_vision_lanes(s); - if (scene->lead_data[0].getStatus()) { - draw_lead(s, scene->lead_data[0]); - } - if (scene->lead_data[1].getStatus() && (std::abs(scene->lead_data[0].getDRel() - scene->lead_data[1].getDRel()) > 3.0)) { - draw_lead(s, scene->lead_data[1]); + // Draw lead indicators if openpilot is handling longitudinal + if (s->longitudinal_control) { + if (scene->lead_data[0].getStatus()) { + draw_lead(s, scene->lead_data[0]); + } + if (scene->lead_data[1].getStatus() && (std::abs(scene->lead_data[0].getDRel() - scene->lead_data[1].getDRel()) > 3.0)) { + draw_lead(s, scene->lead_data[1]); + } } nvgRestore(s->vg); } From 4bc90c578aa1e229c18b62aaec6668dee9b49a84 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 23 Jul 2020 15:44:14 -0700 Subject: [PATCH 504/656] add test route for HYUNDAI.KIA_SORENTO --- selfdrive/test/test_car_models.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 7ac72e170e..7b34b763c9 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -192,6 +192,10 @@ routes = { 'carFingerprint': HYUNDAI.SONATA_2019, 'enableCamera': True, }, + "5875672fc1d4bf57|2020-07-23--21-33-28": { + 'carFingerprint': HYUNDAI.KIA_SORENTO, + 'enableCamera': True, + }, "9c917ba0d42ffe78|2020-04-17--12-43-19": { 'carFingerprint': HYUNDAI.PALISADE, 'enableCamera': True, @@ -426,7 +430,6 @@ non_tested_cars = [ HYUNDAI.KIA_FORTE, HYUNDAI.KIA_OPTIMA, HYUNDAI.KIA_OPTIMA_H, - HYUNDAI.KIA_SORENTO, HYUNDAI.KIA_STINGER, HYUNDAI.KONA, HYUNDAI.KONA_EV, From 3a1b08eb9d0f82f4b15862431fe5164e752c1509 Mon Sep 17 00:00:00 2001 From: xps-genesis <65239463+xps-genesis@users.noreply.github.com> Date: Thu, 23 Jul 2020 18:45:19 -0400 Subject: [PATCH 505/656] Use hyundai legacy safety for Kia Sorento (#1912) confirmed kia sorento to use legacy safety checks --- selfdrive/car/hyundai/interface.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index c6b4780ff4..0245cf87b8 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -145,7 +145,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] # these cars require a special panda safety mode due to missing counters and checksums in the messages - if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV]: + if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO]: ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy ret.centerToFront = ret.wheelbase * 0.4 From 02d5b19d4defe6c0946b86881f27dee624f128bd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 23 Jul 2020 15:55:53 -0700 Subject: [PATCH 506/656] update refs --- selfdrive/test/process_replay/ref_commit | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 39ccd58aae..6431eab7b5 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -e3ccebfa372cc2e85b742e86567899beb1233ced +3a1b08eb9d0f82f4b15862431fe5164e752c1509 \ No newline at end of file From 9a78378b81a66b5ea6c5f0a9c211e24210233327 Mon Sep 17 00:00:00 2001 From: Comma Device Date: Thu, 23 Jul 2020 17:51:18 -0700 Subject: [PATCH 507/656] add timeout on procLog socket for CPU usage test --- selfdrive/test/test_cpu_usage.py | 36 +++++++++++++++++++------------- 1 file changed, 21 insertions(+), 15 deletions(-) diff --git a/selfdrive/test/test_cpu_usage.py b/selfdrive/test/test_cpu_usage.py index eba08fd872..b9bd374824 100755 --- a/selfdrive/test/test_cpu_usage.py +++ b/selfdrive/test/test_cpu_usage.py @@ -62,25 +62,31 @@ def print_cpu_usage(first_proc, last_proc): print(result) return r +def all_running(): + running = manager.get_running() + return all(p in running and running[p].is_alive() for p in manager.car_started_processes) + return_code = 1 def test_thread(): - global return_code - proc_sock = messaging.sub_sock('procLog', conflate=True) + try: + global return_code + proc_sock = messaging.sub_sock('procLog', conflate=True, timeout=1000) - # wait until everything's started and get first sample - time.sleep(30) - first_proc = messaging.recv_sock(proc_sock, wait=True) + # wait until everything's started and get first sample + time.sleep(30) + first_proc = messaging.recv_sock(proc_sock, wait=True) + if first_proc is None or not all_running(): + print("\n\nTEST FAILED: all car started processes not running\n\n") + raise Exception - # run for a minute and get last sample - time.sleep(60) - last_proc = messaging.recv_sock(proc_sock, wait=True) - - running = manager.get_running() - all_running = all(p in running and running[p].is_alive() for p in manager.car_started_processes) - return_code = print_cpu_usage(first_proc, last_proc) - if not all_running: - return_code = 1 - _thread.interrupt_main() + # run for a minute and get last sample + time.sleep(60) + last_proc = messaging.recv_sock(proc_sock, wait=True) + return_code = print_cpu_usage(first_proc, last_proc) + if not all_running(): + return_code = 1 + finally: + _thread.interrupt_main() if __name__ == "__main__": From b16e90c78172674fbb0f5206c75275a13b9f6926 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 24 Jul 2020 12:13:00 +0200 Subject: [PATCH 508/656] Update pip to 20.1.1 so python-opencv installation succeeds --- Dockerfile.openpilot | 1 + update_requirements.sh | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 865f6bdc20..e90eb47a24 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -53,6 +53,7 @@ COPY Pipfile Pipfile.lock /tmp/ RUN pyenv install 3.8.2 && \ pyenv global 3.8.2 && \ pyenv rehash && \ + pip install --no-cache-dir --upgrade pip==20.1.1 && \ pip install --no-cache-dir pipenv==2018.11.26 && \ cd /tmp && \ pipenv install --system --deploy --clear && \ diff --git a/update_requirements.sh b/update_requirements.sh index 2c9175ecdd..d1fdfd4633 100755 --- a/update_requirements.sh +++ b/update_requirements.sh @@ -3,4 +3,4 @@ DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" cd "$DIR" -sudo -- bash -c "source /etc/profile.d/comma_dev.sh; pip install pip==19.2.3 git+git://github.com/pypa/pipenv.git@7a12dbb5cacc71d1dd2d74d8cce8eb50ce2db121; pipenv install --dev --deploy --system" +sudo -- bash -c "source /etc/profile.d/comma_dev.sh; pip install pip==20.1.1 git+git://github.com/pypa/pipenv.git@7a12dbb5cacc71d1dd2d74d8cce8eb50ce2db121; pipenv install --dev --deploy --system" From e0e7c7486d653a550c596f9dca7e5b6424d4c05d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 24 Jul 2020 18:43:17 +0200 Subject: [PATCH 509/656] remove old params learner (#1918) --- release/files_common | 6 - selfdrive/locationd/SConscript | 8 +- selfdrive/locationd/liblocationd_py.py | 28 ---- selfdrive/locationd/locationd_yawrate.cc | 150 ------------------ selfdrive/locationd/locationd_yawrate.h | 33 ---- selfdrive/locationd/params_learner.cc | 118 -------------- selfdrive/locationd/params_learner.h | 35 ---- selfdrive/locationd/paramsd.cc | 135 ---------------- .../locationd/test/test_params_learner.py | 50 ------ 9 files changed, 1 insertion(+), 562 deletions(-) delete mode 100644 selfdrive/locationd/liblocationd_py.py delete mode 100644 selfdrive/locationd/locationd_yawrate.cc delete mode 100644 selfdrive/locationd/locationd_yawrate.h delete mode 100644 selfdrive/locationd/params_learner.cc delete mode 100644 selfdrive/locationd/params_learner.h delete mode 100644 selfdrive/locationd/paramsd.cc delete mode 100755 selfdrive/locationd/test/test_params_learner.py diff --git a/release/files_common b/release/files_common index d1ddced759..d297b550db 100644 --- a/release/files_common +++ b/release/files_common @@ -280,12 +280,6 @@ selfdrive/locationd/models/constants.py selfdrive/locationd/calibrationd.py selfdrive/locationd/calibration_helpers.py -selfdrive/locationd/locationd_yawrate.cc -selfdrive/locationd/locationd_yawrate.h -selfdrive/locationd/params_learner.cc -selfdrive/locationd/params_learner.h -selfdrive/locationd/paramsd.cc - selfdrive/logcatd/SConscript selfdrive/logcatd/logcatd.cc diff --git a/selfdrive/locationd/SConscript b/selfdrive/locationd/SConscript index fbecaa1bae..59516574d8 100644 --- a/selfdrive/locationd/SConscript +++ b/selfdrive/locationd/SConscript @@ -1,12 +1,6 @@ Import('env', 'common', 'cereal', 'messaging') -loc_objs = [ - "locationd_yawrate.cc", - "params_learner.cc", - "paramsd.cc"] -loc_libs = [cereal, messaging, 'zmq', common, 'capnp', 'kj', 'json11', 'pthread'] -env.Program("paramsd", loc_objs, LIBS=loc_libs) -env.SharedLibrary("locationd", loc_objs, LIBS=loc_libs) +loc_libs = [cereal, messaging, 'zmq', common, 'capnp', 'kj', 'pthread'] env.Program("ubloxd", [ "ubloxd.cc", diff --git a/selfdrive/locationd/liblocationd_py.py b/selfdrive/locationd/liblocationd_py.py deleted file mode 100644 index 09d2bb756c..0000000000 --- a/selfdrive/locationd/liblocationd_py.py +++ /dev/null @@ -1,28 +0,0 @@ -import os - -from cffi import FFI - -locationd_dir = os.path.dirname(os.path.abspath(__file__)) -liblocationd_fn = os.path.join(locationd_dir, "liblocationd.so") - - -ffi = FFI() -ffi.cdef(""" -void *localizer_init(void); -void localizer_handle_log(void * localizer, const unsigned char * data, size_t len); -double localizer_get_yaw(void * localizer); -double localizer_get_bias(void * localizer); -double localizer_get_t(void * localizer); -void *params_learner_init(size_t len, char * params, double angle_offset, double stiffness_factor, double steer_ratio, double learning_rate); -bool params_learner_update(void * params_learner, double psi, double u, double sa); -double params_learner_get_ao(void * params_learner); -double params_learner_get_slow_ao(void * params_learner); -double params_learner_get_x(void * params_learner); -double params_learner_get_sR(void * params_learner); -double * localizer_get_P(void * localizer); -void localizer_set_P(void * localizer, double * P); -double * localizer_get_state(void * localizer); -void localizer_set_state(void * localizer, double * state); -""") - -liblocationd = ffi.dlopen(liblocationd_fn) diff --git a/selfdrive/locationd/locationd_yawrate.cc b/selfdrive/locationd/locationd_yawrate.cc deleted file mode 100644 index e682ec3909..0000000000 --- a/selfdrive/locationd/locationd_yawrate.cc +++ /dev/null @@ -1,150 +0,0 @@ -#include -#include - -#include -#include -#include - -#include "cereal/gen/cpp/log.capnp.h" - -#include "locationd_yawrate.h" - - -void Localizer::update_state(const Eigen::Matrix &C, const double R, double current_time, double meas) { - double dt = current_time - prev_update_time; - - if (dt < 0) { - dt = 0; - } else { - prev_update_time = current_time; - } - - x = A * x; - P = A * P * A.transpose() + dt * Q; - - double y = meas - C * x; - double S = R + C * P * C.transpose(); - Eigen::Vector2d K = P * C.transpose() * (1.0 / S); - x = x + K * y; - P = (I - K * C) * P; -} - -void Localizer::handle_sensor_events(capnp::List::Reader sensor_events, double current_time) { - for (cereal::SensorEventData::Reader sensor_event : sensor_events){ - if (sensor_event.getSensor() == 5 && sensor_event.getType() == 16) { - double meas = -sensor_event.getGyroUncalibrated().getV()[0]; - update_state(C_gyro, R_gyro, current_time, meas); - } - } -} - -void Localizer::handle_camera_odometry(cereal::CameraOdometry::Reader camera_odometry, double current_time) { - double R = pow(5 * camera_odometry.getRotStd()[2], 2); - double meas = camera_odometry.getRot()[2]; - update_state(C_posenet, R, current_time, meas); -} - -void Localizer::handle_controls_state(cereal::ControlsState::Reader controls_state, double current_time) { - steering_angle = controls_state.getAngleSteers() * DEGREES_TO_RADIANS; - car_speed = controls_state.getVEgo(); -} - - -Localizer::Localizer() { - // States: [yaw rate, gyro bias] - A << - 1, 0, - 0, 1; - - Q << - pow(.1, 2.0), 0, - 0, pow(0.05/ 100.0, 2.0), - P << - pow(10000.0, 2.0), 0, - 0, pow(10000.0, 2.0); - - I << - 1, 0, - 0, 1; - - C_posenet << 1, 0; - C_gyro << 1, 1; - x << 0, 0; - - R_gyro = pow(0.025, 2.0); -} - -void Localizer::handle_log(cereal::Event::Reader event) { - double current_time = event.getLogMonoTime() / 1.0e9; - - // Initialize update_time on first update - if (prev_update_time < 0) { - prev_update_time = current_time; - } - - auto type = event.which(); - switch(type) { - case cereal::Event::CONTROLS_STATE: - handle_controls_state(event.getControlsState(), current_time); - break; - case cereal::Event::CAMERA_ODOMETRY: - handle_camera_odometry(event.getCameraOdometry(), current_time); - break; - case cereal::Event::SENSOR_EVENTS: - handle_sensor_events(event.getSensorEvents(), current_time); - break; - default: - break; - } -} - - -extern "C" { - void *localizer_init(void) { - Localizer * localizer = new Localizer; - return (void*)localizer; - } - - void localizer_handle_log(void * localizer, const unsigned char * data, size_t len) { - const kj::ArrayPtr view((const capnp::word*)data, len); - capnp::FlatArrayMessageReader msg(view); - cereal::Event::Reader event = msg.getRoot(); - - Localizer * loc = (Localizer*) localizer; - loc->handle_log(event); - } - - double localizer_get_yaw(void * localizer) { - Localizer * loc = (Localizer*) localizer; - return loc->x[0]; - } - double localizer_get_bias(void * localizer) { - Localizer * loc = (Localizer*) localizer; - return loc->x[1]; - } - - double * localizer_get_state(void * localizer) { - Localizer * loc = (Localizer*) localizer; - return loc->x.data(); - } - - void localizer_set_state(void * localizer, double * state) { - Localizer * loc = (Localizer*) localizer; - memcpy(loc->x.data(), state, 4 * sizeof(double)); - } - - double localizer_get_t(void * localizer) { - Localizer * loc = (Localizer*) localizer; - return loc->prev_update_time; - } - - double * localizer_get_P(void * localizer) { - Localizer * loc = (Localizer*) localizer; - return loc->P.data(); - } - - void localizer_set_P(void * localizer, double * P) { - Localizer * loc = (Localizer*) localizer; - memcpy(loc->P.data(), P, 16 * sizeof(double)); - } -} diff --git a/selfdrive/locationd/locationd_yawrate.h b/selfdrive/locationd/locationd_yawrate.h deleted file mode 100644 index 58999e5f37..0000000000 --- a/selfdrive/locationd/locationd_yawrate.h +++ /dev/null @@ -1,33 +0,0 @@ -#pragma once - -#include -#include "cereal/gen/cpp/log.capnp.h" - -#define DEGREES_TO_RADIANS 0.017453292519943295 - -class Localizer -{ - Eigen::Matrix2d A; - Eigen::Matrix2d I; - Eigen::Matrix2d Q; - Eigen::Matrix C_posenet; - Eigen::Matrix C_gyro; - - double R_gyro; - - void update_state(const Eigen::Matrix &C, const double R, double current_time, double meas); - void handle_sensor_events(capnp::List::Reader sensor_events, double current_time); - void handle_camera_odometry(cereal::CameraOdometry::Reader camera_odometry, double current_time); - void handle_controls_state(cereal::ControlsState::Reader controls_state, double current_time); - -public: - Eigen::Vector2d x; - Eigen::Matrix2d P; - double steering_angle = 0; - double car_speed = 0; - double prev_update_time = -1; - - Localizer(); - void handle_log(cereal::Event::Reader event); - -}; diff --git a/selfdrive/locationd/params_learner.cc b/selfdrive/locationd/params_learner.cc deleted file mode 100644 index 66f378a1da..0000000000 --- a/selfdrive/locationd/params_learner.cc +++ /dev/null @@ -1,118 +0,0 @@ -#include -#include -#include - -#include -#include -#include "cereal/gen/cpp/log.capnp.h" -#include "cereal/gen/cpp/car.capnp.h" -#include "params_learner.h" - -// #define DEBUG - -template -T clip(const T& n, const T& lower, const T& upper) { - return std::max(lower, std::min(n, upper)); -} - -ParamsLearner::ParamsLearner(cereal::CarParams::Reader car_params, - double angle_offset, - double stiffness_factor, - double steer_ratio, - double learning_rate) : - ao(angle_offset * DEGREES_TO_RADIANS), - slow_ao(angle_offset * DEGREES_TO_RADIANS), - x(stiffness_factor), - sR(steer_ratio) { - - cF0 = car_params.getTireStiffnessFront(); - cR0 = car_params.getTireStiffnessRear(); - - l = car_params.getWheelbase(); - m = car_params.getMass(); - - aF = car_params.getCenterToFront(); - aR = l - aF; - - min_sr = MIN_SR * car_params.getSteerRatio(); - max_sr = MAX_SR * car_params.getSteerRatio(); - min_sr_th = MIN_SR_TH * car_params.getSteerRatio(); - max_sr_th = MAX_SR_TH * car_params.getSteerRatio(); - alpha1 = 0.01 * learning_rate; - alpha2 = 0.0005 * learning_rate; - alpha3 = 0.1 * learning_rate; - alpha4 = 1.0 * learning_rate; -} - -bool ParamsLearner::update(double psi, double u, double sa) { - if (u > 10.0 && fabs(sa) < (DEGREES_TO_RADIANS * 90.)) { - double ao_diff = 2.0*cF0*cR0*l*u*x*(1.0*cF0*cR0*l*u*x*(ao - sa) + psi*sR*(cF0*cR0*pow(l, 2)*x - m*pow(u, 2)*(aF*cF0 - aR*cR0)))/(pow(sR, 2)*pow(cF0*cR0*pow(l, 2)*x - m*pow(u, 2)*(aF*cF0 - aR*cR0), 2)); - double new_ao = ao - alpha1 * ao_diff; - - double slow_ao_diff = 2.0*cF0*cR0*l*u*x*(1.0*cF0*cR0*l*u*x*(slow_ao - sa) + psi*sR*(cF0*cR0*pow(l, 2)*x - m*pow(u, 2)*(aF*cF0 - aR*cR0)))/(pow(sR, 2)*pow(cF0*cR0*pow(l, 2)*x - m*pow(u, 2)*(aF*cF0 - aR*cR0), 2)); - double new_slow_ao = slow_ao - alpha2 * slow_ao_diff; - - double new_x = x - alpha3 * (-2.0*cF0*cR0*l*m*pow(u, 3)*(slow_ao - sa)*(aF*cF0 - aR*cR0)*(1.0*cF0*cR0*l*u*x*(slow_ao - sa) + psi*sR*(cF0*cR0*pow(l, 2)*x - m*pow(u, 2)*(aF*cF0 - aR*cR0)))/(pow(sR, 2)*pow(cF0*cR0*pow(l, 2)*x - m*pow(u, 2)*(aF*cF0 - aR*cR0), 3))); - double new_sR = sR - alpha4 * (-2.0*cF0*cR0*l*u*x*(slow_ao - sa)*(1.0*cF0*cR0*l*u*x*(slow_ao - sa) + psi*sR*(cF0*cR0*pow(l, 2)*x - m*pow(u, 2)*(aF*cF0 - aR*cR0)))/(pow(sR, 3)*pow(cF0*cR0*pow(l, 2)*x - m*pow(u, 2)*(aF*cF0 - aR*cR0), 2))); - - ao = new_ao; - slow_ao = new_slow_ao; - x = new_x; - sR = new_sR; - } - -#ifdef DEBUG - std::cout << "Instant AO: " << (RADIANS_TO_DEGREES * ao) << "\tAverage AO: " << (RADIANS_TO_DEGREES * slow_ao); - std::cout << "\tStiffness: " << x << "\t sR: " << sR << std::endl; -#endif - - ao = clip(ao, -MAX_ANGLE_OFFSET, MAX_ANGLE_OFFSET); - slow_ao = clip(slow_ao, -MAX_ANGLE_OFFSET, MAX_ANGLE_OFFSET); - x = clip(x, MIN_STIFFNESS, MAX_STIFFNESS); - sR = clip(sR, min_sr, max_sr); - - bool valid = fabs(slow_ao) < MAX_ANGLE_OFFSET_TH; - valid = valid && sR > min_sr_th; - valid = valid && sR < max_sr_th; - return valid; -} - - -extern "C" { - void *params_learner_init(size_t len, char * params, double angle_offset, double stiffness_factor, double steer_ratio, double learning_rate) { - - auto amsg = kj::heapArray((len / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), params, len); - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::CarParams::Reader car_params = cmsg.getRoot(); - - ParamsLearner * p = new ParamsLearner(car_params, angle_offset, stiffness_factor, steer_ratio, learning_rate); - return (void*)p; - } - - bool params_learner_update(void * params_learner, double psi, double u, double sa) { - ParamsLearner * p = (ParamsLearner*) params_learner; - return p->update(psi, u, sa); - } - - double params_learner_get_ao(void * params_learner){ - ParamsLearner * p = (ParamsLearner*) params_learner; - return p->ao; - } - - double params_learner_get_x(void * params_learner){ - ParamsLearner * p = (ParamsLearner*) params_learner; - return p->x; - } - - double params_learner_get_slow_ao(void * params_learner){ - ParamsLearner * p = (ParamsLearner*) params_learner; - return p->slow_ao; - } - - double params_learner_get_sR(void * params_learner){ - ParamsLearner * p = (ParamsLearner*) params_learner; - return p->sR; - } -} diff --git a/selfdrive/locationd/params_learner.h b/selfdrive/locationd/params_learner.h deleted file mode 100644 index 4d97551b3b..0000000000 --- a/selfdrive/locationd/params_learner.h +++ /dev/null @@ -1,35 +0,0 @@ -#pragma once - -#define DEGREES_TO_RADIANS 0.017453292519943295 -#define RADIANS_TO_DEGREES (1.0 / DEGREES_TO_RADIANS) - -#define MAX_ANGLE_OFFSET (10.0 * DEGREES_TO_RADIANS) -#define MAX_ANGLE_OFFSET_TH (9.0 * DEGREES_TO_RADIANS) -#define MIN_STIFFNESS 0.5 -#define MAX_STIFFNESS 2.0 -#define MIN_SR 0.5 -#define MAX_SR 2.0 -#define MIN_SR_TH 0.55 -#define MAX_SR_TH 1.9 - -class ParamsLearner { - double cF0, cR0; - double aR, aF; - double l, m; - - double min_sr, max_sr, min_sr_th, max_sr_th; - double alpha1, alpha2, alpha3, alpha4; - -public: - double ao; - double slow_ao; - double x, sR; - - ParamsLearner(cereal::CarParams::Reader car_params, - double angle_offset, - double stiffness_factor, - double steer_ratio, - double learning_rate); - - bool update(double psi, double u, double sa); -}; diff --git a/selfdrive/locationd/paramsd.cc b/selfdrive/locationd/paramsd.cc deleted file mode 100644 index aee957bc81..0000000000 --- a/selfdrive/locationd/paramsd.cc +++ /dev/null @@ -1,135 +0,0 @@ -#include -#include -#include -#include -#include - -#include -#include "json11.hpp" - -#include "common/swaglog.h" -#include "common/params.h" -#include "common/timing.h" - -#include "messaging.hpp" -#include "locationd_yawrate.h" -#include "params_learner.h" - -#include "common/util.h" - -void sigpipe_handler(int sig) { - LOGE("SIGPIPE received"); -} - - -int main(int argc, char *argv[]) { - signal(SIGPIPE, (sighandler_t)sigpipe_handler); - - SubMaster sm({"controlsState", "sensorEvents", "cameraOdometry"}); - PubMaster pm({"liveParameters"}); - - Localizer localizer; - - // Read car params - std::vector params; - LOGW("waiting for params to set vehicle model"); - while (true) { - params = read_db_bytes("CarParams"); - if (params.size() > 0) break; - usleep(100*1000); - } - LOGW("got %d bytes CarParams", params.size()); - - // make copy due to alignment issues - auto amsg = kj::heapArray((params.size() / sizeof(capnp::word)) + 1); - memcpy(amsg.begin(), params.data(), params.size()); - - capnp::FlatArrayMessageReader cmsg(amsg); - cereal::CarParams::Reader car_params = cmsg.getRoot(); - - // Read params from previous run - std::string fingerprint = car_params.getCarFingerprint(); - std::string vin = car_params.getCarVin(); - double sR = car_params.getSteerRatio(); - double x = 1.0; - double ao = 0.0; - std::vector live_params = read_db_bytes("LiveParameters"); - if (live_params.size() > 0){ - std::string err; - std::string str(live_params.begin(), live_params.end()); - auto json = json11::Json::parse(str, err); - if (json.is_null() || !err.empty()) { - std::string log = "Error parsing json: " + err; - LOGW(log.c_str()); - } else { - std::string new_fingerprint = json["carFingerprint"].string_value(); - std::string new_vin = json["carVin"].string_value(); - - if (fingerprint == new_fingerprint && vin == new_vin) { - std::string log = "Parameter starting with: " + str; - LOGW(log.c_str()); - - sR = json["steerRatio"].number_value(); - x = json["stiffnessFactor"].number_value(); - ao = json["angleOffsetAverage"].number_value(); - } - } - } - - ParamsLearner learner(car_params, ao, x, sR, 1.0); - - // Main loop - int save_counter = 0; - while (true){ - if (sm.update(100) == 0) continue; - - if (sm.updated("controlsState")){ - localizer.handle_log(sm["controlsState"]); - save_counter++; - - double yaw_rate = -localizer.x[0]; - bool valid = learner.update(yaw_rate, localizer.car_speed, localizer.steering_angle); - - double angle_offset_degrees = RADIANS_TO_DEGREES * learner.ao; - double angle_offset_average_degrees = RADIANS_TO_DEGREES * learner.slow_ao; - - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto live_params = event.initLiveParameters(); - live_params.setValid(valid); - live_params.setYawRate(localizer.x[0]); - live_params.setGyroBias(localizer.x[1]); - live_params.setAngleOffset(angle_offset_degrees); - live_params.setAngleOffsetAverage(angle_offset_average_degrees); - live_params.setStiffnessFactor(learner.x); - live_params.setSteerRatio(learner.sR); - - pm.send("liveParameters", msg); - - // Save parameters every minute - if (save_counter % 6000 == 0) { - json11::Json json = json11::Json::object { - {"carVin", vin}, - {"carFingerprint", fingerprint}, - {"steerRatio", learner.sR}, - {"stiffnessFactor", learner.x}, - {"angleOffsetAverage", angle_offset_average_degrees}, - }; - - std::string out = json.dump(); - std::async(std::launch::async, - [out]{ - write_db_value("LiveParameters", out.c_str(), out.length()); - }); - } - } - if (sm.updated("sensorEvents")){ - localizer.handle_log(sm["sensorEvents"]); - } - if (sm.updated("cameraOdometry")){ - localizer.handle_log(sm["cameraOdometry"]); - } - } - return 0; -} diff --git a/selfdrive/locationd/test/test_params_learner.py b/selfdrive/locationd/test/test_params_learner.py deleted file mode 100755 index df0e851cd7..0000000000 --- a/selfdrive/locationd/test/test_params_learner.py +++ /dev/null @@ -1,50 +0,0 @@ -#!/usr/bin/env python3 - -import numpy as np -import unittest - -from selfdrive.car.honda.interface import CarInterface -from selfdrive.car.honda.values import CAR -from selfdrive.controls.lib.vehicle_model import VehicleModel -from selfdrive.locationd.liblocationd_py import liblocationd # pylint: disable=no-name-in-module, import-error - - -class TestParamsLearner(unittest.TestCase): - def setUp(self): - - self.CP = CarInterface.get_params(CAR.CIVIC) - bts = self.CP.to_bytes() - - self.params_learner = liblocationd.params_learner_init(len(bts), bts, 0.0, 1.0, self.CP.steerRatio, 1.0) - - def test_convergence(self): - # Setup vehicle model with wrong parameters - VM_sim = VehicleModel(self.CP) - x_target = 0.75 - sr_target = self.CP.steerRatio - 0.5 - ao_target = -1.0 - VM_sim.update_params(x_target, sr_target) - - # Run simulation - times = np.arange(0, 15*3600, 0.01) - angle_offset = np.radians(ao_target) - steering_angles = np.radians(10 * np.sin(2 * np.pi * times / 100.)) + angle_offset - speeds = 10 * np.sin(2 * np.pi * times / 1000.) + 25 - - for i, _ in enumerate(times): - u = speeds[i] - sa = steering_angles[i] - psi = VM_sim.yaw_rate(sa - angle_offset, u) - liblocationd.params_learner_update(self.params_learner, psi, u, sa) - - # Verify learned parameters - sr = liblocationd.params_learner_get_sR(self.params_learner) - ao_slow = np.degrees(liblocationd.params_learner_get_slow_ao(self.params_learner)) - x = liblocationd.params_learner_get_x(self.params_learner) - self.assertAlmostEqual(x_target, x, places=1) - self.assertAlmostEqual(ao_target, ao_slow, places=1) - self.assertAlmostEqual(sr_target, sr, places=1) - - -if __name__ == "__main__": - unittest.main() From 90fc1c602814b87c1a09fca02e3846a332bc5e03 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 25 Jul 2020 02:12:19 -0700 Subject: [PATCH 510/656] Improve on-device CI reliability (#1922) --- Jenkinsfile | 86 ++++++++++++++---------- release/build_devel.sh | 29 +------- release/files_common | 3 +- selfdrive/test/helpers.py | 11 ++++ selfdrive/test/phone_ci.py | 98 ---------------------------- selfdrive/test/setup_device_ci.sh | 35 ++++++++++ selfdrive/test/test_cpu_usage.py | 18 +++-- selfdrive/test/test_openpilot.py | 3 +- {selfdrive/test => tools/ssh}/id_rsa | 0 tools/ssh/key/id_rsa | 1 - 10 files changed, 115 insertions(+), 169 deletions(-) delete mode 100755 selfdrive/test/phone_ci.py create mode 100755 selfdrive/test/setup_device_ci.sh rename {selfdrive/test => tools/ssh}/id_rsa (100%) delete mode 120000 tools/ssh/key/id_rsa diff --git a/Jenkinsfile b/Jenkinsfile index c362512038..b77891bb75 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -1,3 +1,33 @@ +def phone(String ip, String step_label, String cmd) { + def ci_env = "CI=1 TEST_DIR=${env.TEST_DIR} GIT_BRANCH=${env.GIT_BRANCH} GIT_COMMIT=${env.GIT_COMMIT}" + + withCredentials([file(credentialsId: 'id_rsa_public', variable: 'key_file')]) { + sh label: step_label, + script: """ + ssh -tt -o StrictHostKeyChecking=no -i ${key_file} -p 8022 root@${ip} '${ci_env} /usr/bin/bash -le' <<'EOF' +echo \$\$ > /dev/cpuset/app/tasks || true +echo \$PPID > /dev/cpuset/app/tasks || true +mkdir -p /dev/shm +chmod 777 /dev/shm +cd ${env.TEST_DIR} || true +${cmd} +exit 0 +EOF""" + } +} + +def phone_steps(String device_type, steps) { + lock(resource: "", label: device_type, inversePrecedence: true, variable: 'device_ip', quantity: 1) { + timeout(time: 60, unit: 'MINUTES') { + phone(device_ip, "kill old processes", "pkill -f comma || true") + phone(device_ip, "git checkout", readFile("selfdrive/test/setup_device_ci.sh"),) + steps.each { item -> + phone(device_ip, item[0], item[1]) + } + } + } +} + pipeline { agent { docker { @@ -7,6 +37,7 @@ pipeline { } environment { COMMA_JWT = credentials('athena-test-jwt') + TEST_DIR = "/data/openpilot" } stages { @@ -16,14 +47,9 @@ pipeline { branch 'devel-staging' } steps { - lock(resource: "", label: 'eon-build', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ - timeout(time: 60, unit: 'MINUTES') { - dir(path: 'selfdrive/test') { - sh 'pip install paramiko' - sh 'python phone_ci.py "cd release && PUSH=1 ./build_release2.sh"' - } - } - } + phone_steps("eon-build", [ + ["build release2-staging and dashcam-staging", "cd release && PUSH=1 ./build_release2.sh"], + ]) } } @@ -40,50 +66,38 @@ pipeline { stage('Build') { environment { - CI_PUSH = "${env.BRANCH_NAME == 'master' ? 'master-ci' : ''}" + CI_PUSH = "${env.BRANCH_NAME == 'master' ? 'master-ci' : ' '}" } - steps { - lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ - timeout(time: 60, unit: 'MINUTES') { - dir(path: 'selfdrive/test') { - sh 'pip install paramiko' - sh 'python phone_ci.py "cd release && ./build_devel.sh"' - } - } - } + phone_steps("eon", [ + ["build devel", "cd release && CI_PUSH=${env.CI_PUSH} ./build_devel.sh"], + ["test openpilot", "nosetests -s selfdrive/test/test_openpilot.py"], + //["test cpu usage", "cd selfdrive/test/ && ./test_cpu_usage.py"], + ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], + ]) } } stage('Replay Tests') { steps { - lock(resource: "", label: 'eon2', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ - timeout(time: 60, unit: 'MINUTES') { - dir(path: 'selfdrive/test') { - sh 'pip install paramiko' - sh 'python phone_ci.py "cd selfdrive/test/process_replay && ./camera_replay.py"' - } - } - } + phone_steps("eon2", [ + ["camerad/modeld replay", "cd selfdrive/test/process_replay && ./camera_replay.py"], + ]) } } stage('HW Tests') { steps { - lock(resource: "", label: 'eon', inversePrecedence: true, variable: 'eon_ip', quantity: 1){ - timeout(time: 60, unit: 'MINUTES') { - dir(path: 'selfdrive/test') { - sh 'pip install paramiko' - sh 'python phone_ci.py "SCONS_CACHE=1 scons -j3 cereal/ && \ - nosetests -s selfdrive/test/test_sounds.py && \ - nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"' - } - } - } + phone_steps("eon", [ + ["build cereal", "SCONS_CACHE=1 scons -j4 cereal/"], + ["test sounds", "nosetests -s selfdrive/test/test_sounds.py"], + ["test boardd loopback", "nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"], + ]) } } } } + } } diff --git a/release/build_devel.sh b/release/build_devel.sh index 782ea0fae5..8e2e7ce7f6 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -1,13 +1,4 @@ -#!/usr/bin/env bash -set -e - -mkdir -p /dev/shm -chmod 777 /dev/shm - -# Write cpuset -echo $$ > /dev/cpuset/app/tasks -echo $PPID > /dev/cpuset/app/tasks - +#!/usr/bin/bash -e SOURCE_DIR=/data/openpilot_source TARGET_DIR=/data/openpilot @@ -18,7 +9,7 @@ export GIT_COMMITTER_NAME="Vehicle Researcher" export GIT_COMMITTER_EMAIL="user@comma.ai" export GIT_AUTHOR_NAME="Vehicle Researcher" export GIT_AUTHOR_EMAIL="user@comma.ai" -export GIT_SSH_COMMAND="ssh -i /tmp/deploy_key" +export GIT_SSH_COMMAND="ssh -i /data/gitkey" echo "[-] Setting up repo T=$SECONDS" if [ ! -d "$TARGET_DIR" ]; then @@ -73,16 +64,6 @@ git commit -a -m "openpilot v$VERSION release" # Run build SCONS_CACHE=1 scons -j3 -echo "[-] testing openpilot T=$SECONDS" -echo -n "0" > /data/params/d/Passive -echo -n "0.2.0" > /data/params/d/CompletedTrainingVersion -echo -n "1" > /data/params/d/HasCompletedSetup -echo -n "1" > /data/params/d/CommunityFeaturesToggle - -PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" nosetests -s selfdrive/test/test_openpilot.py -PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" selfdrive/test/test_cpu_usage.py -PYTHONPATH="$TARGET_DIR:$TARGET_DIR/pyextra" selfdrive/car/tests/test_car_interfaces.py - echo "[-] testing panda build T=$SECONDS" pushd panda/board/ make bin @@ -99,10 +80,4 @@ if [ ! -z "$CI_PUSH" ]; then git push -f origin master-ci:$CI_PUSH fi -echo "[-] done pushing T=$SECONDS" - -# reset version -cd $SOURCE_DIR -git checkout -- selfdrive/common/version.h - echo "[-] done T=$SECONDS" diff --git a/release/files_common b/release/files_common index d297b550db..01d743c482 100644 --- a/release/files_common +++ b/release/files_common @@ -312,9 +312,8 @@ selfdrive/thermald/thermald.py selfdrive/thermald/power_monitoring.py selfdrive/test/__init__.py -selfdrive/test/id_rsa selfdrive/test/helpers.py -selfdrive/test/phone_ci.py +selfdrive/test/setup_device_ci.sh selfdrive/test/test_openpilot.py selfdrive/test/test_fingerprints.py selfdrive/test/test_cpu_usage.py diff --git a/selfdrive/test/helpers.py b/selfdrive/test/helpers.py index 2a6cf501a2..733c09dc72 100644 --- a/selfdrive/test/helpers.py +++ b/selfdrive/test/helpers.py @@ -4,8 +4,19 @@ from nose.tools import nottest from common.android import ANDROID from common.apk import update_apks, start_offroad, pm_apply_packages, android_packages +from common.params import Params +from selfdrive.version import training_version from selfdrive.manager import start_managed_process, kill_managed_process, get_running +def set_params_enabled(): + params = Params() + params.put("HasAcceptedTerms", "1") + params.put("HasCompletedSetup", "1") + params.put("OpenpilotEnabledToggle", "1") + params.put("CommunityFeaturesToggle", "1") + params.put("Passive", "0") + params.put("CompletedTrainingVersion", training_version) + def phone_only(x): if ANDROID: return x diff --git a/selfdrive/test/phone_ci.py b/selfdrive/test/phone_ci.py deleted file mode 100755 index a3a966ce2f..0000000000 --- a/selfdrive/test/phone_ci.py +++ /dev/null @@ -1,98 +0,0 @@ -#!/usr/bin/env python3 -import paramiko # pylint: disable=import-error -import os -import sys -import re -import time -import socket - - -SOURCE_DIR = "/data/openpilot_source/" -TEST_DIR = "/data/openpilot/" - -def run_on_phone(test_cmd): - - eon_ip = os.environ.get('eon_ip', None) - if eon_ip is None: - raise Exception("'eon_ip' not set") - - ssh = paramiko.SSHClient() - ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy()) - - key_file = open(os.path.join(os.path.dirname(__file__), "id_rsa")) - key = paramiko.RSAKey.from_private_key(key_file) - - print("SSH to phone at {}".format(eon_ip)) - - # try connecting for one minute - t_start = time.time() - while True: - try: - ssh.connect(hostname=eon_ip, port=8022, pkey=key, timeout=10) - except (paramiko.ssh_exception.SSHException, socket.timeout, paramiko.ssh_exception.NoValidConnectionsError): - print("Connection failed") - if time.time() - t_start > 60: - raise - else: - break - time.sleep(1) - - branch = os.environ['GIT_BRANCH'] - commit = os.environ.get('GIT_COMMIT', branch) - - conn = ssh.invoke_shell() - - # pass in all environment variables prefixed with 'CI_' - for k, v in os.environ.items(): - if k.startswith("CI_") or k in ["GIT_BRANCH", "GIT_COMMIT"]: - conn.send(f"export {k}='{v}'\n") - conn.send("export CI=1\n") - - # clear scons cache dirs that haven't been written to in one day - conn.send("cd /tmp && find -name 'scons_cache_*' -type d -maxdepth 1 -mtime 1 -exec rm -rf '{}' \\;\n") - - # set up environment - conn.send(f"cd {SOURCE_DIR}\n") - conn.send("git reset --hard\n") - conn.send("git fetch origin\n") - conn.send("find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \\;\n") - conn.send(f"git reset --hard {commit}\n") - conn.send(f"git checkout {commit}\n") - conn.send("git clean -xdf\n") - conn.send("git submodule update --init\n") - conn.send("git submodule foreach --recursive git reset --hard\n") - conn.send("git submodule foreach --recursive git clean -xdf\n") - conn.send('echo "git took $SECONDS seconds"\n') - - conn.send(f"rsync -a --delete {SOURCE_DIR} {TEST_DIR}\n") - - # run the test - conn.send(test_cmd + "\n") - - # get the result and print it back out - conn.send('echo "RESULT:" $?\n') - conn.send("exit\n") - - dat = b"" - conn.settimeout(240) - - while True: - try: - recvd = conn.recv(4096) - except socket.timeout: - print("connection to phone timed out") - sys.exit(1) - - if len(recvd) == 0: - break - - dat += recvd - sys.stdout.buffer.write(recvd) - sys.stdout.flush() - - return_code = int(re.findall(rb'^RESULT: (\d+)', dat[-1024:], flags=re.MULTILINE)[0]) - sys.exit(return_code) - - -if __name__ == "__main__": - run_on_phone(sys.argv[1]) diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh new file mode 100755 index 0000000000..e8228ce7d4 --- /dev/null +++ b/selfdrive/test/setup_device_ci.sh @@ -0,0 +1,35 @@ +#!/usr/bin/bash -e + +export SOURCE_DIR="/data/openpilot_source/" + +if [ -z "$GIT_COMMIT" ]; then + echo "GIT_COMMIT must be set" + exit 1 +fi + +if [ -z "$TEST_DIR" ]; then + + echo "TEST_DIR must be set" + exit 1 +fi + +# TODO: never clear qcom_replay cache +# clear scons cache dirs that haven't been written to in one day +cd /tmp && find -name 'scons_cache_*' -type d -maxdepth 1 -mtime 1 -exec rm -rf '{}' \; + +# set up environment +cd $SOURCE_DIR +git reset --hard +git fetch origin +find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \; +git reset --hard $GIT_COMMIT +git checkout $GIT_COMMIT +git clean -xdf +git submodule update --init +git submodule foreach --recursive git reset --hard +git submodule foreach --recursive git clean -xdf +echo "git checkout took $SECONDS seconds" + +rsync -a --delete $SOURCE_DIR $TEST_DIR + +echo "$TEST_DIR synced with $GIT_COMMIT, took $SECONDS seconds" diff --git a/selfdrive/test/test_cpu_usage.py b/selfdrive/test/test_cpu_usage.py index b9bd374824..d6d2841c7e 100755 --- a/selfdrive/test/test_cpu_usage.py +++ b/selfdrive/test/test_cpu_usage.py @@ -6,8 +6,9 @@ import signal import sys import cereal.messaging as messaging +from common.params import Params import selfdrive.manager as manager - +from selfdrive.test.helpers import set_params_enabled def cputime_total(ct): return ct.cpuUser + ct.cpuSystem + ct.cpuChildrenUser + ct.cpuChildrenSystem @@ -70,13 +71,18 @@ return_code = 1 def test_thread(): try: global return_code - proc_sock = messaging.sub_sock('procLog', conflate=True, timeout=1000) + proc_sock = messaging.sub_sock('procLog', conflate=True, timeout=2000) # wait until everything's started and get first sample - time.sleep(30) + start_time = time.monotonic() + while time.monotonic() - start_time < 120: + if Params().get("CarParams") is not None: + break + time.sleep(2) first_proc = messaging.recv_sock(proc_sock, wait=True) if first_proc is None or not all_running(): - print("\n\nTEST FAILED: all car started processes not running\n\n") + err_msg = "procLog recv timed out" if first_proc is None else "all car started process not running" + print(f"\n\nTEST FAILED: {err_msg}\n\n") raise Exception # run for a minute and get last sample @@ -90,12 +96,16 @@ def test_thread(): if __name__ == "__main__": + # setup signal handler to exit with test status def handle_exit(sig, frame): sys.exit(return_code) signal.signal(signal.SIGINT, handle_exit) # start manager and test thread + set_params_enabled() + Params().delete("CarParams") + t = threading.Thread(target=test_thread) t.daemon = True t.start() diff --git a/selfdrive/test/test_openpilot.py b/selfdrive/test/test_openpilot.py index fc3b17dded..75e8192f4c 100644 --- a/selfdrive/test/test_openpilot.py +++ b/selfdrive/test/test_openpilot.py @@ -5,7 +5,7 @@ os.environ['FAKEUPLOAD'] = "1" from common.params import Params from common.realtime import sec_since_boot from selfdrive.manager import manager_init, manager_prepare, start_daemon_process -from selfdrive.test.helpers import phone_only, with_processes +from selfdrive.test.helpers import phone_only, with_processes, set_params_enabled import json import requests import signal @@ -16,6 +16,7 @@ import time # must run first @phone_only def test_manager_prepare(): + set_params_enabled() manager_init() manager_prepare() diff --git a/selfdrive/test/id_rsa b/tools/ssh/id_rsa similarity index 100% rename from selfdrive/test/id_rsa rename to tools/ssh/id_rsa diff --git a/tools/ssh/key/id_rsa b/tools/ssh/key/id_rsa deleted file mode 120000 index d4e6dd344a..0000000000 --- a/tools/ssh/key/id_rsa +++ /dev/null @@ -1 +0,0 @@ -../../../selfdrive/test/id_rsa \ No newline at end of file From 99106fd9c465b366c7c61b8a0452b73455a9b96d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 25 Jul 2020 02:27:56 -0700 Subject: [PATCH 511/656] Test Car Models 2.0 (#1903) * start with radar interface * car interface * panda safety rx check * check panda safety inits * check NO_RADAR_SLEEP in all radar interfaces * sonata 2019 and kia optima should use hyundai legacy safety * check radar errors * check radar can errors * real fingerprint * run in CI * it shoud pass now * ignore old openpilot msgs * ensure safety mode is set * sort can msgs * filter out openpilot msgs --- .github/workflows/test.yaml | 6 +- selfdrive/car/gm/radar_interface.py | 4 +- selfdrive/car/honda/radar_interface.py | 5 +- selfdrive/car/hyundai/interface.py | 2 +- selfdrive/car/hyundai/radar_interface.py | 7 +- selfdrive/car/interfaces.py | 5 +- selfdrive/car/toyota/radar_interface.py | 4 +- selfdrive/test/test_models.py | 132 +++++++++++++++++++++++ 8 files changed, 142 insertions(+), 23 deletions(-) create mode 100755 selfdrive/test/test_models.py diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 55fc9e6e47..d9892b2663 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -197,10 +197,10 @@ jobs: run: eval "$BUILD" - name: Test car models run: | - $PERSIST "mkdir -p /data/params && \ - cd /tmp/openpilot && \ + $PERSIST "cd /tmp/openpilot && \ scons -j$(nproc) && \ - coverage run --parallel-mode --concurrency=multiprocessing --rcfile=./.coveragerc-app selfdrive/test/test_car_models.py && \ + coverage run --parallel-mode --concurrency=multiprocessing \ + --rcfile=./.coveragerc-app selfdrive/test/test_models.py && \ coverage combine" - name: Upload coverage to Codecov run: | diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py index f2f8c3cec9..05991ce49c 100755 --- a/selfdrive/car/gm/radar_interface.py +++ b/selfdrive/car/gm/radar_interface.py @@ -1,7 +1,6 @@ #!/usr/bin/env python3 from __future__ import print_function import math -import time from cereal import car from opendbc.can.parser import CANParser from selfdrive.car.gm.values import DBC, CAR, CanBus @@ -53,8 +52,7 @@ class RadarInterface(RadarInterfaceBase): def update(self, can_strings): if self.rcp is None: - time.sleep(self.radar_ts) # nothing to do - return car.RadarData.new_message() + return super().update(None) vls = self.rcp.update_strings(can_strings) self.updated_messages.update(vls) diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py index a921534c5a..e910e753f7 100755 --- a/selfdrive/car/honda/radar_interface.py +++ b/selfdrive/car/honda/radar_interface.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 import os -import time from cereal import car from opendbc.can.parser import CANParser from selfdrive.car.interfaces import RadarInterfaceBase @@ -38,9 +37,7 @@ class RadarInterface(RadarInterfaceBase): # in Bosch radar and we are only steering for now, so sleep 0.05s to keep # radard at 20Hz and return no points if self.radar_off_can: - if 'NO_RADAR_SLEEP' not in os.environ: - time.sleep(self.radar_ts) - return car.RadarData.new_message() + return super().update(None) vls = self.rcp.update_strings(can_strings) self.updated_messages.update(vls) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 0245cf87b8..b68eeddbcc 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -145,7 +145,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] # these cars require a special panda safety mode due to missing counters and checksums in the messages - if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO]: + if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_2019, CAR.KIA_OPTIMA]: ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy ret.centerToFront = ret.wheelbase * 0.4 diff --git a/selfdrive/car/hyundai/radar_interface.py b/selfdrive/car/hyundai/radar_interface.py index b5bdcd8363..fdbe837af6 100644 --- a/selfdrive/car/hyundai/radar_interface.py +++ b/selfdrive/car/hyundai/radar_interface.py @@ -1,6 +1,4 @@ #!/usr/bin/env python3 -import os -import time from cereal import car from opendbc.can.parser import CANParser from selfdrive.car.interfaces import RadarInterfaceBase @@ -33,10 +31,7 @@ class RadarInterface(RadarInterfaceBase): def update(self, can_strings): if self.radar_off_can: - if 'NO_RADAR_SLEEP' not in os.environ: - time.sleep(0.05) # radard runs on RI updates - - return car.RadarData.new_message() + return super().update(None) vls = self.rcp.update_strings(can_strings) self.updated_messages.update(vls) diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 287dc979bf..85cc6d4d32 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -137,13 +137,12 @@ class RadarInterfaceBase(): self.pts = {} self.delay = 0 self.radar_ts = CP.radarTimeStep + self.no_radar_sleep = 'NO_RADAR_SLEEP' in os.environ def update(self, can_strings): ret = car.RadarData.new_message() - - if 'NO_RADAR_SLEEP' not in os.environ: + if not self.no_radar_sleep: time.sleep(self.radar_ts) # radard runs on RI updates - return ret class CarStateBase: diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py index 3a66beed0e..8407e71fcd 100755 --- a/selfdrive/car/toyota/radar_interface.py +++ b/selfdrive/car/toyota/radar_interface.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 import os -import time from opendbc.can.parser import CANParser from cereal import car from selfdrive.car.toyota.values import NO_DSU_CAR, DBC, TSS2_CAR @@ -53,8 +52,7 @@ class RadarInterface(RadarInterfaceBase): def update(self, can_strings): if self.no_radar: - time.sleep(self.radar_ts) - return car.RadarData.new_message() + return super().update(None) vls = self.rcp.update_strings(can_strings) self.updated_messages.update(vls) diff --git a/selfdrive/test/test_models.py b/selfdrive/test/test_models.py new file mode 100755 index 0000000000..b44f8e60b8 --- /dev/null +++ b/selfdrive/test/test_models.py @@ -0,0 +1,132 @@ +#!/usr/bin/env python3 +# pylint: disable=E1101 +import os +import importlib +import unittest +from collections import Counter +from parameterized import parameterized_class + +from cereal import log, car +import cereal.messaging as messaging +from selfdrive.car.fingerprints import all_known_cars +from selfdrive.car.car_helpers import interfaces +from selfdrive.test.test_car_models import routes +from selfdrive.test.openpilotci import get_url +from tools.lib.logreader import LogReader + +from panda.tests.safety import libpandasafety_py +from panda.tests.safety.common import package_can_msg + +HwType = log.HealthData.HwType + +ROUTES = {v['carFingerprint']: k for k, v in routes.items() if v['enableCamera']} + +@parameterized_class(('car_model'), [(car,) for car in all_known_cars()]) +class TestCarModel(unittest.TestCase): + + @classmethod + def setUpClass(cls): + if cls.car_model not in ROUTES: + print(f"Skipping tests for {cls.car_model}: missing route") + raise unittest.SkipTest + + try: + lr = LogReader(get_url(ROUTES[cls.car_model], 1)) + except Exception: + lr = LogReader(get_url(ROUTES[cls.car_model], 0)) + + has_relay = False + can_msgs = [] + fingerprint = {i: dict() for i in range(3)} + for msg in lr: + if msg.which() == "can": + for m in msg.can: + if m.src < 128: + fingerprint[m.src][m.address] = len(m.dat) + can_msgs.append(msg) + elif msg.which() == "health": + has_relay = msg.health.hwType in [HwType.blackPanda, HwType.uno, HwType.dos] + cls.can_msgs = sorted(can_msgs, key=lambda msg: msg.logMonoTime) + + CarInterface, CarController, CarState = interfaces[cls.car_model] + + # TODO: test with relay and without + cls.car_params = CarInterface.get_params(cls.car_model, fingerprint, has_relay, []) + assert cls.car_params + + cls.CI = CarInterface(cls.car_params, CarController, CarState) + assert cls.CI + + def test_car_params(self): + if self.car_params.dashcamOnly: + self.skipTest("no need to check carParams for dashcamOnly") + + # make sure car params are within a valid range + self.assertGreater(self.car_params.mass, 1) + self.assertGreater(self.car_params.steerRateCost, 1e-3) + + tuning = self.car_params.lateralTuning.which() + if tuning == 'pid': + self.assertTrue(len(self.car_params.lateralTuning.pid.kpV)) + elif tuning == 'lqr': + self.assertTrue(len(self.car_params.lateralTuning.lqr.a)) + elif tuning == 'indi': + self.assertGreater(self.car_params.lateralTuning.indi.outerLoopGain, 1e-3) + + self.assertTrue(self.car_params.enableCamera) + + # TODO: check safetyModel is in release panda build + safety = libpandasafety_py.libpandasafety + set_status = safety.set_safety_hooks(self.car_params.safetyModel.raw, self.car_params.safetyParam) + self.assertEqual(0, set_status, f"failed to set safetyModel {self.car_params.safetyModel}") + + def test_car_interface(self): + # TODO: also check for checkusm and counter violations from can parser + can_invalid_cnt = 0 + CC = car.CarControl.new_message() + for msg in self.can_msgs: + # filter out openpilot msgs + can = [m for m in msg.can if m.src < 128] + can_pkt = messaging.new_message('can', len(can)) + can_pkt.can = can + + CS = self.CI.update(CC, (can_pkt.to_bytes(),)) + self.CI.apply(CC) + can_invalid_cnt += CS.canValid + # TODO: add this back + #self.assertLess(can_invalid_cnt, 20) + + def test_radar_interface(self): + os.environ['NO_RADAR_SLEEP'] = "1" + RadarInterface = importlib.import_module('selfdrive.car.%s.radar_interface' % self.car_params.carName).RadarInterface + RI = RadarInterface(self.car_params) + assert RI + + error_cnt = 0 + for msg in self.can_msgs: + radar_data = RI.update((msg.as_builder().to_bytes(),)) + if radar_data is not None: + error_cnt += car.RadarData.Error.canError in radar_data.errors + self.assertLess(error_cnt, 20) + + def test_panda_safety_rx(self): + if self.car_params.dashcamOnly: + self.skipTest("no need to check panda safety for dashcamOnly") + + safety = libpandasafety_py.libpandasafety + set_status = safety.set_safety_hooks(self.car_params.safetyModel.raw, self.car_params.safetyParam) + self.assertEqual(0, set_status) + + failed_addrs = Counter() + for can in self.can_msgs: + for msg in can.can: + if msg.src >= 128: + continue + to_send = package_can_msg([msg.address, 0, msg.dat, msg.src]) + if not safety.safety_rx_hook(to_send): + failed_addrs[hex(msg.address)] += 1 + self.assertFalse(len(failed_addrs), f"panda safety RX check failed: {failed_addrs}") + + +if __name__ == "__main__": + unittest.main() From 892e1162c0bfa0970cbe262452a70745eccb8ba6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 25 Jul 2020 15:07:27 -0700 Subject: [PATCH 512/656] Car cleanup (#1924) * cleanup car code * more pruning * little more * less pylint disables * radar stuff * fix * udpate refs * fix honda bosch * fix test --- selfdrive/car/chrysler/carcontroller.py | 1 - selfdrive/car/chrysler/interface.py | 2 - selfdrive/car/chrysler/radar_interface.py | 9 ++-- selfdrive/car/chrysler/test_chryslercan.py | 56 ---------------------- selfdrive/car/chrysler/values.py | 31 ++++-------- selfdrive/car/ford/interface.py | 2 +- selfdrive/car/ford/radar_interface.py | 3 +- selfdrive/car/gm/interface.py | 6 +-- selfdrive/car/gm/radar_interface.py | 42 ++++++++-------- selfdrive/car/honda/radar_interface.py | 13 ++--- selfdrive/car/honda/values.py | 2 +- selfdrive/car/hyundai/carstate.py | 3 +- selfdrive/car/hyundai/interface.py | 3 -- selfdrive/car/hyundai/values.py | 12 ++--- selfdrive/car/interfaces.py | 2 +- selfdrive/car/mazda/carstate.py | 4 +- selfdrive/car/mazda/interface.py | 5 +- selfdrive/car/mock/interface.py | 2 +- selfdrive/car/nissan/interface.py | 2 +- selfdrive/car/subaru/interface.py | 2 +- selfdrive/car/tests/test_car_interfaces.py | 2 +- selfdrive/car/toyota/carstate.py | 9 +++- selfdrive/car/toyota/interface.py | 1 - selfdrive/car/toyota/radar_interface.py | 5 +- selfdrive/car/toyota/values.py | 6 +-- selfdrive/car/volkswagen/carcontroller.py | 4 +- selfdrive/car/volkswagen/carstate.py | 2 +- selfdrive/car/volkswagen/interface.py | 6 +-- selfdrive/car/volkswagen/values.py | 2 +- selfdrive/car/volkswagen/volkswagencan.py | 1 - selfdrive/test/process_replay/ref_commit | 2 +- 31 files changed, 77 insertions(+), 165 deletions(-) delete mode 100644 selfdrive/car/chrysler/test_chryslercan.py diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index f25cc69f7c..b81526e9c0 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -11,7 +11,6 @@ class CarController(): self.prev_frame = -1 self.hud_count = 0 self.car_fingerprint = CP.carFingerprint - self.alert_active = False self.gone_fast_yet = False self.steer_rate_limited = False diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 6cf5c85a6e..fbc469ebeb 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -70,8 +70,6 @@ class CarInterface(CarInterfaceBase): # speeds ret.steeringRateLimited = self.CC.steer_rate_limited if self.CC is not None else False - ret.buttonEvents = [] - # events events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low], gas_resume_speed=2.) diff --git a/selfdrive/car/chrysler/radar_interface.py b/selfdrive/car/chrysler/radar_interface.py index 40a7c5a742..3139efad34 100755 --- a/selfdrive/car/chrysler/radar_interface.py +++ b/selfdrive/car/chrysler/radar_interface.py @@ -1,16 +1,15 @@ #!/usr/bin/env python3 -import os from opendbc.can.parser import CANParser from cereal import car from selfdrive.car.interfaces import RadarInterfaceBase +from selfdrive.car.chrysler.values import DBC RADAR_MSGS_C = list(range(0x2c2, 0x2d4+2, 2)) # c_ messages 706,...,724 RADAR_MSGS_D = list(range(0x2a2, 0x2b4+2, 2)) # d_ messages LAST_MSG = max(RADAR_MSGS_C + RADAR_MSGS_D) NUMBER_MSGS = len(RADAR_MSGS_C) + len(RADAR_MSGS_D) -def _create_radar_can_parser(): - dbc_f = 'chrysler_pacifica_2017_hybrid_private_fusion.dbc' +def _create_radar_can_parser(car_fingerprint): msg_n = len(RADAR_MSGS_C) # list of [(signal name, message name or number, initial values), (...)] # [('RADAR_STATE', 1024, 0), @@ -37,7 +36,7 @@ def _create_radar_can_parser(): [20]*msg_n + # 20Hz (0.05s) [20]*msg_n)) # 20Hz (0.05s) - return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1) + return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) def _address_to_track(address): if address in RADAR_MSGS_C: @@ -49,7 +48,7 @@ def _address_to_track(address): class RadarInterface(RadarInterfaceBase): def __init__(self, CP): super().__init__(CP) - self.rcp = _create_radar_can_parser() + self.rcp = _create_radar_can_parser(CP.carFingerprint) self.updated_messages = set() self.trigger_msg = LAST_MSG diff --git a/selfdrive/car/chrysler/test_chryslercan.py b/selfdrive/car/chrysler/test_chryslercan.py deleted file mode 100644 index a172526189..0000000000 --- a/selfdrive/car/chrysler/test_chryslercan.py +++ /dev/null @@ -1,56 +0,0 @@ -import unittest - -from cereal import car -from opendbc.can.packer import CANPacker -from selfdrive.car.chrysler import chryslercan - -VisualAlert = car.CarControl.HUDControl.VisualAlert -GearShifter = car.CarState.GearShifter - - -class TestChryslerCan(unittest.TestCase): - - def test_hud(self): - packer = CANPacker('chrysler_pacifica_2017_hybrid') - self.assertEqual( - [0x2a6, 0, b'\x01\x00\x01\x01\x00\x00\x00\x00', 0], - chryslercan.create_lkas_hud( - packer, - GearShifter.park, False, False, 1, 0)) - self.assertEqual( - [0x2a6, 0, b'\x01\x00\x01\x00\x00\x00\x00\x00', 0], - chryslercan.create_lkas_hud( - packer, - GearShifter.park, False, False, 5*4, 0)) - self.assertEqual( - [0x2a6, 0, b'\x01\x00\x01\x00\x00\x00\x00\x00', 0], - chryslercan.create_lkas_hud( - packer, - GearShifter.park, False, False, 99999, 0)) - self.assertEqual( - [0x2a6, 0, b'\x02\x00\x06\x00\x00\x00\x00\x00', 0], - chryslercan.create_lkas_hud( - packer, - GearShifter.drive, True, False, 99999, 0)) - self.assertEqual( - [0x2a6, 0, b'\x02\x64\x06\x00\x00\x00\x00\x00', 0], - chryslercan.create_lkas_hud( - packer, - GearShifter.drive, True, False, 99999, 0x64)) - - def test_command(self): - packer = CANPacker('chrysler_pacifica_2017_hybrid') - self.assertEqual( - [0x292, 0, b'\x14\x00\x00\x00\x10\x86', 0], - chryslercan.create_lkas_command( - packer, - 0, True, 1)) - self.assertEqual( - [0x292, 0, b'\x04\x00\x00\x00\x80\x83', 0], - chryslercan.create_lkas_command( - packer, - 0, False, 8)) - - -if __name__ == '__main__': - unittest.main() diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 2070947cdc..b7fb53f530 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -4,7 +4,6 @@ from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu - class SteerLimitParams: STEER_MAX = 261 # 262 faults STEER_DELTA_UP = 3 # 3 is stock. 100 is fine. 200 is too much it seems @@ -82,32 +81,18 @@ FINGERPRINTS = { DBC = { - CAR.PACIFICA_2017_HYBRID: dbc_dict( - 'chrysler_pacifica_2017_hybrid', # 'pt' - 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' - CAR.PACIFICA_2018: dbc_dict( # Same DBC file works. - 'chrysler_pacifica_2017_hybrid', # 'pt' - 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' - CAR.PACIFICA_2020: dbc_dict( # Same DBC file works. - 'chrysler_pacifica_2017_hybrid', # 'pt' - 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' - CAR.PACIFICA_2018_HYBRID: dbc_dict( # Same DBC file works. - 'chrysler_pacifica_2017_hybrid', # 'pt' - 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' - CAR.PACIFICA_2019_HYBRID: dbc_dict( # Same DBC file works. - 'chrysler_pacifica_2017_hybrid', # 'pt' - 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' - CAR.JEEP_CHEROKEE: dbc_dict( # Same DBC file works. - 'chrysler_pacifica_2017_hybrid', # 'pt' - 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' - CAR.JEEP_CHEROKEE_2019: dbc_dict( # Same DBC file works. - 'chrysler_pacifica_2017_hybrid', # 'pt' - 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' + CAR.PACIFICA_2017_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.PACIFICA_2018: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.PACIFICA_2020: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.PACIFICA_2018_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.PACIFICA_2019_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.JEEP_CHEROKEE: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.JEEP_CHEROKEE_2019: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), } STEER_THRESHOLD = 120 ECU_FINGERPRINT = { - Ecu.fwdCamera: [0x292], # lkas cmd + Ecu.fwdCamera: [0x292], # lkas cmd } diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index 59e6191420..6d6c82f0b8 100755 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -14,7 +14,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 3.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=None): ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "ford" ret.safetyModel = car.CarParams.SafetyModel.ford diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index b01814bca6..20a435b082 100755 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -8,14 +8,13 @@ from selfdrive.car.interfaces import RadarInterfaceBase RADAR_MSGS = list(range(0x500, 0x540)) def _create_radar_can_parser(car_fingerprint): - dbc_f = DBC[car_fingerprint]['radar'] msg_n = len(RADAR_MSGS) signals = list(zip(['X_Rel'] * msg_n + ['Angle'] * msg_n + ['V_Rel'] * msg_n, RADAR_MSGS * 3, [0] * msg_n + [0] * msg_n + [0] * msg_n)) checks = list(zip(RADAR_MSGS, [20]*msg_n)) - return CANParser(dbc_f, signals, checks, 1) + return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) class RadarInterface(RadarInterfaceBase): def __init__(self, CP): diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 1328b11fe0..0fc3d278ce 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -16,13 +16,13 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=None): ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "gm" - ret.safetyModel = car.CarParams.SafetyModel.gm # default to gm + ret.safetyModel = car.CarParams.SafetyModel.gm ret.enableCruise = False # stock cruise control is kept off - # GM port is considered a community feature, since it disables AEB; + # GM port is a community feature # TODO: make a port that uses a car harness and it only intercepts the camera ret.communityFeature = True diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py index 05991ce49c..dc2c2f7b7c 100755 --- a/selfdrive/car/gm/radar_interface.py +++ b/selfdrive/car/gm/radar_interface.py @@ -16,30 +16,28 @@ NUM_SLOTS = 20 LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS def create_radar_can_parser(car_fingerprint): - - dbc_f = DBC[car_fingerprint]['radar'] - if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): - # C1A-ARS3-A by Continental - radar_targets = list(range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS)) - signals = list(zip(['FLRRNumValidTargets', - 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', - 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', - 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + - ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + - ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + - ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, - [RADAR_HEADER_MSG] * 7 + radar_targets * 6, - [0] * 7 + - [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + - [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + - [0.0] * NUM_SLOTS + [0] * NUM_SLOTS)) - - checks = [] - - return CANParser(dbc_f, signals, checks, CanBus.OBSTACLE) - else: + if car_fingerprint not in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): return None + # C1A-ARS3-A by Continental + radar_targets = list(range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS)) + signals = list(zip(['FLRRNumValidTargets', + 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', + 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', + 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + + ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + + ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + + ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, + [RADAR_HEADER_MSG] * 7 + radar_targets * 6, + [0] * 7 + + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + + [0.0] * NUM_SLOTS + [0] * NUM_SLOTS)) + + checks = [] + + return CANParser(DBC[car_fingerprint]['radar'], signals, checks, CanBus.OBSTACLE) + class RadarInterface(RadarInterfaceBase): def __init__(self, CP): super().__init__(CP) diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py index e910e753f7..6acec73d3c 100755 --- a/selfdrive/car/honda/radar_interface.py +++ b/selfdrive/car/honda/radar_interface.py @@ -1,11 +1,10 @@ #!/usr/bin/env python3 -import os from cereal import car from opendbc.can.parser import CANParser from selfdrive.car.interfaces import RadarInterfaceBase +from selfdrive.car.honda.values import DBC -def _create_nidec_can_parser(): - dbc_f = 'acura_ilx_2016_nidec.dbc' +def _create_nidec_can_parser(car_fingerprint): radar_messages = [0x400] + list(range(0x430, 0x43A)) + list(range(0x440, 0x446)) signals = list(zip(['RADAR_STATE'] + ['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 + @@ -13,8 +12,7 @@ def _create_nidec_can_parser(): [0x400] + radar_messages[1:] * 4, [0] + [255] * 16 + [1] * 16 + [0] * 16 + [0] * 16)) checks = list(zip([0x445], [20])) - fn = os.path.splitext(dbc_f)[0].encode('utf8') - return CANParser(fn, signals, checks, 1) + return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) class RadarInterface(RadarInterfaceBase): @@ -29,7 +27,10 @@ class RadarInterface(RadarInterfaceBase): self.delay = int(round(0.1 / CP.radarTimeStep)) # 0.1s delay of radar # Nidec - self.rcp = _create_nidec_can_parser() + if self.radar_off_can: + self.rcp = None + else: + self.rcp = _create_nidec_can_parser(CP.carFingerprint) self.trigger_msg = 0x445 self.updated_messages = set() diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index c2aca11a21..713c38ae1b 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -987,4 +987,4 @@ ECU_FINGERPRINT = { Ecu.fwdCamera: [0xE4, 0x194], # steer torque cmd } -HONDA_BOSCH = [CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, CAR.CRV_HYBRID, CAR.INSIGHT] +HONDA_BOSCH = set([CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, CAR.CRV_HYBRID, CAR.INSIGHT]) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 1e4ad4018e..1477ed274d 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -41,8 +41,7 @@ class CarState(CarStateBase): ret.cruiseState.standstill = cp.vl["SCC11"]['SCCInfoDisplay'] == 4. if ret.cruiseState.enabled: - is_set_speed_in_mph = int(cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"]) - speed_conv = CV.MPH_TO_MS if is_set_speed_in_mph else CV.KPH_TO_MS + speed_conv = CV.MPH_TO_MS if cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] else CV.KPH_TO_MS ret.cruiseState.speed = cp.vl["SCC11"]['VSetDis'] * speed_conv else: ret.cruiseState.speed = 0 diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index b68eeddbcc..e2d43cbf9b 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -170,9 +170,6 @@ class CarInterface(CarInterfaceBase): ret = self.CS.update(self.cp, self.cp_cam) ret.canValid = self.cp.can_valid and self.cp_cam.can_valid - # TODO: button presses - ret.buttonEvents = [] - events = self.create_common_events(ret) #TODO: addd abs(self.CS.angle_steers) > 90 to 'steerTempUnavailable' event diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index b993d62055..42e7ae1e2d 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -210,17 +210,17 @@ CHECKSUM = { FEATURES = { # which message has the gear - "use_cluster_gears": [CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30], - "use_tcu_gears": [CAR.KIA_OPTIMA, CAR.SONATA_2019], - "use_elect_gears": [CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ], + "use_cluster_gears": set([CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30]), + "use_tcu_gears": set([CAR.KIA_OPTIMA, CAR.SONATA_2019]), + "use_elect_gears": set([CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ]), # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - "use_fca": [CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE], + "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE]), - "use_bsm": [CAR.SONATA, CAR.PALISADE, CAR.HYUNDAI_GENESIS, CAR.GENESIS_G80, CAR.GENESIS_G90], + "use_bsm": set([CAR.SONATA, CAR.PALISADE, CAR.HYUNDAI_GENESIS, CAR.GENESIS_G80, CAR.GENESIS_G90]), } -EV_HYBRID = [CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV] +EV_HYBRID = set([CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV]) DBC = { CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 85cc6d4d32..bd5c8eb4b7 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -42,7 +42,7 @@ class CarInterfaceBase(): raise NotImplementedError @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=None): raise NotImplementedError # returns a set of default params to avoid repetition in car specific params diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index 18a26cc38a..03f3a026b5 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -162,8 +162,8 @@ class CarState(CarStateBase): @staticmethod def get_cam_can_parser(CP): - signals = [ ] - checks = [ ] + signals = [] + checks = [] if CP.carFingerprint == CAR.CX5: signals += [ diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 059d734153..dfa959da38 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -15,7 +15,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=None): ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "mazda" @@ -70,9 +70,6 @@ class CarInterface(CarInterfaceBase): ret = self.CS.update(self.cp, self.cp_cam) ret.canValid = self.cp.can_valid and self.cp_cam.can_valid - # TODO: button presses - ret.buttonEvents = [] - # events events = self.create_common_events(ret) diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index 617f7e23d2..d0298ec838 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -33,7 +33,7 @@ class CarInterface(CarInterfaceBase): return accel @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=None): ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "mock" ret.safetyModel = car.CarParams.SafetyModel.noOutput diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index cc9547aedd..9c419c5a8f 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -14,7 +14,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=None): ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "nissan" diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index 66a5d99513..a710ae20b7 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -11,7 +11,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=None): ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) ret.carName = "subaru" diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 1800a71d03..069d5af00b 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -63,7 +63,7 @@ class TestCarInterfaces(unittest.TestCase): # Run radar interface once radar_interface.update([]) - if hasattr(radar_interface, '_update') and hasattr(radar_interface, 'trigger_msg'): + if not car_params.radarOffCan and hasattr(radar_interface, '_update') and hasattr(radar_interface, 'trigger_msg'): radar_interface._update([radar_interface.trigger_msg]) if __name__ == "__main__": diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index d4cc71640f..4cf84904e7 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -182,9 +182,14 @@ class CarState(CarStateBase): @staticmethod def get_cam_can_parser(CP): - signals = [("FORCE", "PRE_COLLISION", 0), ("PRECOLLISION_ACTIVE", "PRE_COLLISION", 0)] + signals = [ + ("FORCE", "PRE_COLLISION", 0), + ("PRECOLLISION_ACTIVE", "PRE_COLLISION", 0) + ] # use steering message to check if panda is connected to frc - checks = [("STEERING_LKA", 42)] + checks = [ + ("STEERING_LKA", 42) + ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 7720e627f7..e31eaee4ff 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -313,7 +313,6 @@ class CarInterface(CarInterfaceBase): ret.canValid = self.cp.can_valid and self.cp_cam.can_valid ret.steeringRateLimited = self.CC.steer_rate_limited if self.CC is not None else False - ret.buttonEvents = [] # events events = self.create_common_events(ret) diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py index 8407e71fcd..a7d2ec37bb 100755 --- a/selfdrive/car/toyota/radar_interface.py +++ b/selfdrive/car/toyota/radar_interface.py @@ -1,13 +1,10 @@ #!/usr/bin/env python3 -import os from opendbc.can.parser import CANParser from cereal import car from selfdrive.car.toyota.values import NO_DSU_CAR, DBC, TSS2_CAR from selfdrive.car.interfaces import RadarInterfaceBase def _create_radar_can_parser(car_fingerprint): - dbc_f = DBC[car_fingerprint]['radar'] - if car_fingerprint in TSS2_CAR: RADAR_A_MSGS = list(range(0x180, 0x190)) RADAR_B_MSGS = list(range(0x190, 0x1a0)) @@ -25,7 +22,7 @@ def _create_radar_can_parser(car_fingerprint): checks = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20]*(msg_a_n + msg_b_n))) - return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1) + return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) class RadarInterface(RadarInterfaceBase): def __init__(self, CP): diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 35f744591d..ebb48b19e0 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1202,6 +1202,6 @@ DBC = { CAR.LEXUS_NXH: dbc_dict('lexus_nx300h_2018_pt_generated', 'toyota_adas'), } -NO_DSU_CAR = [CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH, CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2] -TSS2_CAR = [CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2] -NO_STOP_TIMER_CAR = [CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.SIENNA, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2] # no resume button press required +NO_DSU_CAR = set([CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH, CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2]) +TSS2_CAR = set([CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2]) +NO_STOP_TIMER_CAR = set([CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.SIENNA, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2]) # no resume button press required diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index a157805c13..5bb5dcc109 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -4,8 +4,6 @@ from selfdrive.car.volkswagen import volkswagencan from selfdrive.car.volkswagen.values import DBC, CANBUS, MQB_LDW_MESSAGES, BUTTON_STATES, CarControllerParams from opendbc.can.packer import CANPacker -VisualAlert = car.CarControl.HUDControl.VisualAlert - class CarController(): def __init__(self, dbc_name, CP, VM): @@ -114,7 +112,7 @@ class CarController(): if frame % P.LDW_STEP == 0: hcaEnabled = True if enabled and not CS.out.standstill else False - if visual_alert == VisualAlert.steerRequired: + if visual_alert == car.CarControl.HUDControl.VisualAlert.steerRequired: hud_alert = MQB_LDW_MESSAGES["laneAssistTakeOverSilent"] else: hud_alert = MQB_LDW_MESSAGES["none"] diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index 0ee8ce50e5..a994130929 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -53,7 +53,7 @@ class CarState(CarStateBase): pt_cp.vl["Gateway_72"]['ZV_HD_offen']]) # Update seatbelt fastened status. - ret.seatbeltUnlatched = False if pt_cp.vl["Airbag_02"]["AB_Gurtschloss_FA"] == 3 else True + ret.seatbeltUnlatched = pt_cp.vl["Airbag_02"]["AB_Gurtschloss_FA"] != 3 # Update driver preference for metric. VW stores many different unit # preferences, including separate units for for distance vs. speed. diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 3ec4b07000..c7082b57ce 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -19,7 +19,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=[]): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, car_fw=None): ret = CarInterfaceBase.get_std_params(candidate, fingerprint, has_relay) # VW port is a community feature, since we don't own one to test @@ -64,7 +64,6 @@ class CarInterface(CarInterfaceBase): # returns a car.CarState def update(self, c, can_strings): - canMonoTimes = [] buttonEvents = [] # Process the most recent CAN message traffic, and check for validity @@ -77,7 +76,7 @@ class CarInterface(CarInterfaceBase): ret.canValid = self.cp.can_valid and self.cp_cam.can_valid ret.steeringRateLimited = self.CC.steer_rate_limited if self.CC is not None else False - # Update the EON metric configuration to match the car at first startup, + # Update the device metric configuration to match the car at first startup, # or if there's been a change. if self.CS.displayMetricUnits != self.displayMetricUnitsPrev: put_nonblocking("IsMetric", "1" if self.CS.displayMetricUnits else "0") @@ -101,7 +100,6 @@ class CarInterface(CarInterfaceBase): ret.events = events.to_msg() ret.buttonEvents = buttonEvents - ret.canMonoTimes = canMonoTimes # update previous car states self.displayMetricUnitsPrev = self.CS.displayMetricUnits diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 3937a7c154..d99d781026 100644 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -46,7 +46,7 @@ MQB_LDW_MESSAGES = { } class CAR: - GOLF = "Volkswagen Golf" + GOLF = "VOLKSWAGEN GOLF" FINGERPRINTS = { CAR.GOLF: [ diff --git a/selfdrive/car/volkswagen/volkswagencan.py b/selfdrive/car/volkswagen/volkswagencan.py index 694673ea6b..3cd47a0957 100644 --- a/selfdrive/car/volkswagen/volkswagencan.py +++ b/selfdrive/car/volkswagen/volkswagencan.py @@ -48,5 +48,4 @@ def create_mqb_acc_buttons_control(packer, bus, buttonStatesToSend, CS, idx): "GRA_Tip_Stufe_2": CS.graTipStufe2, "GRA_ButtonTypeInfo": CS.graButtonTypeInfo } - return packer.make_can_msg("GRA_ACC_01", bus, values, idx) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 6431eab7b5..83a68c1d2a 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -3a1b08eb9d0f82f4b15862431fe5164e752c1509 \ No newline at end of file +b4cf3ec3c29ef22741d5a85d50abc0937b5d40bd \ No newline at end of file From 360cd7d8a86460fcc339ead89c0c6a439417eb66 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 26 Jul 2020 14:09:49 -0700 Subject: [PATCH 513/656] kia stinger: use hyundaiLegacy safety mode and add test route --- selfdrive/car/hyundai/interface.py | 2 +- selfdrive/test/test_car_models.py | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index e2d43cbf9b..787df32ff4 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -145,7 +145,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] # these cars require a special panda safety mode due to missing counters and checksums in the messages - if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_2019, CAR.KIA_OPTIMA]: + if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_2019, CAR.KIA_OPTIMA, CAR.KIA_STINGER]: ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy ret.centerToFront = ret.wheelbase * 0.4 diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 7b34b763c9..09f1586e1d 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -208,6 +208,10 @@ routes = { 'carFingerprint': HYUNDAI.IONIQ, 'enableCamera': True, }, + "5dddcbca6eb66c62|2020-07-26--13-24-19": { + 'carFingerprint': HYUNDAI.KIA_STINGER, + 'enableCamera': True, + }, "f7b6be73e3dfd36c|2019-05-12--18-07-16": { 'carFingerprint': TOYOTA.AVALON, 'enableCamera': False, From cf1ae581ed942ad01f94ba5fac76cc71b4677b2c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 27 Jul 2020 05:30:56 +0800 Subject: [PATCH 514/656] boardd: use enum instead of magic number (#1927) --- selfdrive/boardd/boardd.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 45ddf0316a..58f994e050 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -290,7 +290,7 @@ void usb_retry_connect() { void handle_usb_issue(int err, const char func[]) { LOGE_100("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func); - if (err == -4) { + if (err == LIBUSB_ERROR_NO_DEVICE) { LOGE("lost connection"); usb_retry_connect(); } @@ -310,10 +310,10 @@ void can_recv(PubMaster &pm) { 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_100("overflow got 0x%x", recv); }; + if (err == LIBUSB_ERROR_OVERFLOW) { LOGE_100("overflow got 0x%x", recv); }; // timeout is okay to exit, recv still happened - if (err == -7) { break; } + if (err == LIBUSB_ERROR_TIMEOUT) { break; } } while(err != 0); pthread_mutex_unlock(&usb_lock); From 5cbdaa19bbe3a44b5fadcf5dfc77b4e885295cf2 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 27 Jul 2020 12:00:24 +0800 Subject: [PATCH 515/656] sidebar: remove unnecessary checks on uilayout_sidebarcollapsed (#1928) * cleanup * keep local variables * done --- selfdrive/ui/sidebar.cc | 20 ++++++++------------ 1 file changed, 8 insertions(+), 12 deletions(-) diff --git a/selfdrive/ui/sidebar.cc b/selfdrive/ui/sidebar.cc index f4cb4f515b..e8eb894cc9 100644 --- a/selfdrive/ui/sidebar.cc +++ b/selfdrive/ui/sidebar.cc @@ -10,17 +10,13 @@ static void ui_draw_sidebar_background(UIState *s) { } static void ui_draw_sidebar_settings_button(UIState *s) { - bool settingsActive = s->active_app == cereal::UiLayoutState::App::SETTINGS; - const int settings_btn_xr = !s->scene.uilayout_sidebarcollapsed ? settings_btn_x : -(sbr_w); - - ui_draw_image(s->vg, settings_btn_xr, settings_btn_y, settings_btn_w, settings_btn_h, s->img_button_settings, settingsActive ? 1.0f : 0.65f); + const float alpha = s->active_app == cereal::UiLayoutState::App::SETTINGS ? 1.0f : 0.65f; + ui_draw_image(s->vg, settings_btn_x, settings_btn_y, settings_btn_w, settings_btn_h, s->img_button_settings, alpha); } static void ui_draw_sidebar_home_button(UIState *s) { - bool homeActive = s->active_app == cereal::UiLayoutState::App::HOME; - const int home_btn_xr = !s->scene.uilayout_sidebarcollapsed ? home_btn_x : -(sbr_w); - - ui_draw_image(s->vg, home_btn_xr, home_btn_y, home_btn_w, home_btn_h, s->img_button_home, homeActive ? 1.0f : 0.65f); + const float alpha = s->active_app == cereal::UiLayoutState::App::HOME ? 1.0f : 0.65f;; + ui_draw_image(s->vg, home_btn_x, home_btn_y, home_btn_w, home_btn_h, s->img_button_home, alpha); } static void ui_draw_sidebar_network_strength(UIState *s) { @@ -32,7 +28,7 @@ static void ui_draw_sidebar_network_strength(UIState *s) { {cereal::ThermalData::NetworkStrength::GREAT, 5}}; const int network_img_h = 27; const int network_img_w = 176; - const int network_img_x = !s->scene.uilayout_sidebarcollapsed ? 58 : -(sbr_w); + const int network_img_x = 58; const int network_img_y = 196; const int img_idx = s->scene.thermal.getNetworkType() == cereal::ThermalData::NetworkType::NONE ? 0 : network_strength_map[s->scene.thermal.getNetworkStrength()]; ui_draw_image(s->vg, network_img_x, network_img_y, network_img_w, network_img_h, s->img_network[img_idx], 1.0f); @@ -41,7 +37,7 @@ static void ui_draw_sidebar_network_strength(UIState *s) { static void ui_draw_sidebar_battery_icon(UIState *s) { const int battery_img_h = 36; const int battery_img_w = 76; - const int battery_img_x = !s->scene.uilayout_sidebarcollapsed ? 160 : -(sbr_w); + const int battery_img_x = 160; const int battery_img_y = 255; int battery_img = s->scene.thermal.getBatteryStatus() == "Charging" ? s->img_battery_charging : s->img_battery; @@ -60,7 +56,7 @@ static void ui_draw_sidebar_network_type(UIState *s) { {cereal::ThermalData::NetworkType::CELL3_G, "3G"}, {cereal::ThermalData::NetworkType::CELL4_G, "4G"}, {cereal::ThermalData::NetworkType::CELL5_G, "5G"}}; - const int network_x = !s->scene.uilayout_sidebarcollapsed ? 50 : -(sbr_w); + const int network_x = 50; const int network_y = 273; const int network_w = 100; const char *network_type = network_type_map[s->scene.thermal.getNetworkType()]; @@ -72,7 +68,7 @@ static void ui_draw_sidebar_network_type(UIState *s) { } static void ui_draw_sidebar_metric(UIState *s, const char* label_str, const char* value_str, const int severity, const int y_offset, const char* message_str) { - const int metric_x = !s->scene.uilayout_sidebarcollapsed ? 30 : -(sbr_w); + const int metric_x = 30; const int metric_y = 338 + y_offset; const int metric_w = 240; const int metric_h = message_str ? strchr(message_str, '\n') ? 124 : 100 : 148; From 405d94ec6d98727d9ffbfc4d469c92ca327dfa1a Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 27 Jul 2020 16:13:25 +0000 Subject: [PATCH 516/656] qcom2 build fixes --- selfdrive/camerad/cameras/camera_qcom2.c | 23 +++++++++++------------ selfdrive/camerad/main.cc | 2 ++ selfdrive/ui/sound.hpp | 4 ++-- 3 files changed, 15 insertions(+), 14 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_qcom2.c b/selfdrive/camerad/cameras/camera_qcom2.c index 060010de7b..259521ed98 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.c +++ b/selfdrive/camerad/cameras/camera_qcom2.c @@ -28,6 +28,7 @@ //#define FRAME_STRIDE 1936 // for 8 bit output #define FRAME_STRIDE 2416 // for 10 bit output +/* static void hexdump(uint8_t *data, int len) { for (int i = 0; i < len; i++) { if (i!=0&&i%0x10==0) printf("\n"); @@ -35,6 +36,7 @@ static void hexdump(uint8_t *data, int len) { } printf("\n"); } +*/ extern volatile sig_atomic_t do_exit; @@ -79,8 +81,6 @@ int device_control(int fd, int op_code, int session_handle, int dev_handle) { } void *alloc_w_mmu_hdl(int video0_fd, int len, int align, int flags, uint32_t *handle, int mmu_hdl, int mmu_hdl2) { - int ret; - static struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0}; mem_mgr_alloc_cmd.len = len; mem_mgr_alloc_cmd.align = align; @@ -141,7 +141,7 @@ void sensors_poke(struct CameraState *s, int request_id) { pkt->header.size = size; pkt->header.op_code = 0x7f; pkt->header.request_id = request_id; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; + //struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; static struct cam_config_dev_cmd config_dev_cmd = {}; config_dev_cmd.session_handle = s->session_handle; @@ -169,7 +169,7 @@ void sensors_i2c(struct CameraState *s, struct i2c_random_wr_payload* dat, int l buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_random_wr) + (len-1)*sizeof(struct i2c_random_wr_payload); buf_desc[0].type = CAM_CMD_BUF_I2C; - struct cam_cmd_power *power = alloc(s->video0_fd, buf_desc[0].size, 8, CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, &buf_desc[0].mem_handle); + struct cam_cmd_power *power = alloc(s->video0_fd, buf_desc[0].size, 8, CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, (uint32_t*)&buf_desc[0].mem_handle); struct cam_cmd_i2c_random_wr *i2c_random_wr = (void*)power; i2c_random_wr->header.count = len; i2c_random_wr->header.op_code = 1; @@ -204,7 +204,7 @@ void sensors_init(int video0_fd, int sensor_fd, int camera_num) { buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_info) + sizeof(struct cam_cmd_probe); buf_desc[0].type = CAM_CMD_BUF_LEGACY; - struct cam_cmd_i2c_info *i2c_info = alloc(video0_fd, buf_desc[0].size, 8, CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, &buf_desc[0].mem_handle); + struct cam_cmd_i2c_info *i2c_info = alloc(video0_fd, buf_desc[0].size, 8, CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, (uint32_t*)&buf_desc[0].mem_handle); struct cam_cmd_probe *probe = (struct cam_cmd_probe *)((uint8_t *)i2c_info) + sizeof(struct cam_cmd_i2c_info); switch (camera_num) { @@ -241,11 +241,11 @@ void sensors_init(int video0_fd, int sensor_fd, int camera_num) { //buf_desc[1].size = buf_desc[1].length = 148; buf_desc[1].size = buf_desc[1].length = 196; buf_desc[1].type = CAM_CMD_BUF_I2C; - struct cam_cmd_power *power = alloc(video0_fd, buf_desc[1].size, 8, CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, &buf_desc[1].mem_handle); + struct cam_cmd_power *power = alloc(video0_fd, buf_desc[1].size, 8, CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, (uint32_t*)&buf_desc[1].mem_handle); memset(power, 0, buf_desc[1].size); struct cam_cmd_unconditional_wait *unconditional_wait; - void *ptr = power; + //void *ptr = power; // 7750 /*power->count = 2; power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; @@ -350,7 +350,7 @@ void sensors_init(int video0_fd, int sensor_fd, int camera_num) { power = (void*)power + (sizeof(struct cam_cmd_power) + (power->count-1)*sizeof(struct cam_power_settings)); LOGD("probing the sensor"); - int ret = cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)cam_packet_handle, 0); + int ret = cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)(uintptr_t)cam_packet_handle, 0); assert(ret == 0); release_fd(video0_fd, buf_desc[0].mem_handle); @@ -401,7 +401,7 @@ void config_isp(struct CameraState *s, int io_mem_handle, int fence, int request } buf_desc[1].type = CAM_CMD_BUF_GENERIC; buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; - uint32_t *buf2 = alloc(s->video0_fd, buf_desc[1].size, 0x20, CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, &buf_desc[1].mem_handle); + uint32_t *buf2 = alloc(s->video0_fd, buf_desc[1].size, 0x20, CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, (uint32_t*)&buf_desc[1].mem_handle); // cam_isp_packet_generic_blob_handler uint32_t tmp[] = { @@ -526,7 +526,6 @@ void enqueue_buffer(struct CameraState *s, int i) { // ******************* camera ******************* static void camera_release_buffer(void* cookie, int i) { - int ret; CameraState *s = cookie; enqueue_buffer(s, i); } @@ -692,7 +691,7 @@ static void camera_open(CameraState *s, VisionBuf* b) { // acquires done // config ISP - void *buf0 = alloc_w_mmu_hdl(s->video0_fd, 984480, 0x20, CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, &s->buf0_handle, s->device_iommu, s->cdm_iommu); + alloc_w_mmu_hdl(s->video0_fd, 984480, 0x20, CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, (uint32_t*)&s->buf0_handle, s->device_iommu, s->cdm_iommu); config_isp(s, 0, 0, 1, s->buf0_handle, 0); LOG("-- Configuring sensor"); @@ -715,7 +714,7 @@ static void camera_open(CameraState *s, VisionBuf* b) { buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_csiphy_info); buf_desc[0].type = CAM_CMD_BUF_GENERIC; - struct cam_csiphy_info *csiphy_info = alloc(s->video0_fd, buf_desc[0].size, 8, CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, &buf_desc[0].mem_handle); + struct cam_csiphy_info *csiphy_info = alloc(s->video0_fd, buf_desc[0].size, 8, CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, (uint32_t*)&buf_desc[0].mem_handle); csiphy_info->lane_mask = 0x1f; csiphy_info->lane_assign = 0x3210;// skip clk. How is this 16 bit for 5 channels?? diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index 4e1ce307c8..6ad52880ef 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -504,7 +504,9 @@ void* processing_thread(void *arg) { double t2 = millis_since_boot(); +#ifndef QCOM2 uint8_t *bgr_ptr = (uint8_t*)s->rgb_bufs[rgb_idx].addr; +#endif double yt1 = millis_since_boot(); diff --git a/selfdrive/ui/sound.hpp b/selfdrive/ui/sound.hpp index c147f87b68..d565f846ff 100644 --- a/selfdrive/ui/sound.hpp +++ b/selfdrive/ui/sound.hpp @@ -2,7 +2,7 @@ #include #include "cereal/gen/cpp/log.capnp.h" -#if defined(QCOM) || defined(QCOM2) +#if defined(QCOM) #include #include #endif @@ -18,7 +18,7 @@ class Sound { void setVolume(int volume); ~Sound(); -#if defined(QCOM) || defined(QCOM2) +#if defined(QCOM) private: SLObjectItf engine_ = nullptr; SLObjectItf outputMix_ = nullptr; From cf8c848ddd9dddd4e1852df365513f73c67ed91c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 27 Jul 2020 13:02:24 -0700 Subject: [PATCH 517/656] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 7b78cda876..29099e87a1 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 7b78cda8767a79c4ac6797d71fbd7bcb03e1f737 +Subproject commit 29099e87a1372694fb81b426faaa57e832bbe87a From b677e89159d4c4fb3b9974adfa015cfb83ed11f8 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Mon, 27 Jul 2020 15:06:13 -0500 Subject: [PATCH 518/656] Local variable ARCH isn't used anymore (#1930) --- selfdrive/boardd/boardd_setup.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/selfdrive/boardd/boardd_setup.py b/selfdrive/boardd/boardd_setup.py index cf71901cb6..f8b43ee3a5 100644 --- a/selfdrive/boardd/boardd_setup.py +++ b/selfdrive/boardd/boardd_setup.py @@ -1,4 +1,3 @@ -import subprocess from distutils.core import Extension, setup from Cython.Build import cythonize @@ -9,7 +8,6 @@ import os PHONELIBS = os.path.join(BASEDIR, 'phonelibs') -ARCH = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() libraries = ['can_list_to_can_capnp', 'capnp', 'kj'] setup(name='Boardd API Implementation', From 967c1f1565fb72b462542748a83a2f9d05d8a18d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 27 Jul 2020 13:09:09 -0700 Subject: [PATCH 519/656] remove dead lines from boardd cython setup --- selfdrive/boardd/boardd_setup.py | 5 ----- 1 file changed, 5 deletions(-) diff --git a/selfdrive/boardd/boardd_setup.py b/selfdrive/boardd/boardd_setup.py index f8b43ee3a5..4b08590183 100644 --- a/selfdrive/boardd/boardd_setup.py +++ b/selfdrive/boardd/boardd_setup.py @@ -1,12 +1,7 @@ from distutils.core import Extension, setup - from Cython.Build import cythonize from common.cython_hacks import BuildExtWithoutPlatformSuffix -from common.basedir import BASEDIR -import os - -PHONELIBS = os.path.join(BASEDIR, 'phonelibs') libraries = ['can_list_to_can_capnp', 'capnp', 'kj'] From 5453d8dd302918bf1aa71c46cb067489b2f37a03 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 27 Jul 2020 15:59:59 -0700 Subject: [PATCH 520/656] Add Lexus RX300 2019 FW (#1838) * Add Lexus RX300 2019 fw * build tmp branch * Revert "build tmp branch" This reverts commit e487ca13458ac0c8c75d2fd3600567b3c22a5ab3. Co-authored-by: VirtuallyChris --- selfdrive/car/toyota/values.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index ebb48b19e0..0e4e717a62 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1067,30 +1067,36 @@ FW_VERSIONS = { b'\x01896630E41000\x00\x00\x00\x00', b'\x01896630E41200\x00\x00\x00\x00', b'\x01896630E37300\x00\x00\x00\x00', + b'\x018966348R8500\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152648472\x00\x00\x00\x00\x00\x00', b'F152648473\x00\x00\x00\x00\x00\x00', b'F152648492\x00\x00\x00\x00\x00\x00', b'F152648493\x00\x00\x00\x00\x00\x00', + b'F152648474\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'881514810300\x00\x00\x00\x00', b'881514810500\x00\x00\x00\x00', + b'881514810700\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B0E011\x00\x00\x00\x00\x00\x00', b'8965B0E012\x00\x00\x00\x00\x00\x00', + b'8965B48102\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F4701000\x00\x00\x00\x00', b'8821F4701100\x00\x00\x00\x00', + b'8821F4701300\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'8646F4801100\x00\x00\x00\x00', b'8646F4801200\x00\x00\x00\x00', b'8646F4802001\x00\x00\x00\x00', b'8646F4802100\x00\x00\x00\x00', + b'8646F4809000\x00\x00\x00\x00', ], }, CAR.LEXUS_RXH: { From 247ec73370a2a4675e6abd7bd25510990bbca6ae Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 27 Jul 2020 20:23:38 -0500 Subject: [PATCH 521/656] Update TOTAL_SCONS_NODES (#1938) --- selfdrive/manager.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 4fe8f6c5ad..e415dff50f 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -19,7 +19,7 @@ WEBCAM = os.getenv("WEBCAM") is not None sys.path.append(os.path.join(BASEDIR, "pyextra")) os.environ['BASEDIR'] = BASEDIR -TOTAL_SCONS_NODES = 1140 +TOTAL_SCONS_NODES = 1020 prebuilt = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) # Create folders needed for msgq From 2cfa0edb4ccc0f17fd926835de8fb966dd4d9fc3 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Mon, 27 Jul 2020 20:22:06 -0700 Subject: [PATCH 522/656] EfficientNet driver monitoring (#1907) * e96f9be6 * bump cereal * filter sunglasses * fix unittest * update refs * udpate refs * update refs * add tolerance for dmonitoringd Co-authored-by: Adeeb Shihadeh --- models/dmonitoring_model.current | 2 +- models/dmonitoring_model.keras | 4 ++-- models/dmonitoring_model_q.dlc | 4 ++-- selfdrive/modeld/models/dmonitoring.cc | 8 +++++--- selfdrive/modeld/models/dmonitoring.h | 3 ++- selfdrive/monitoring/driver_monitor.py | 7 ++++--- selfdrive/monitoring/test_monitoring.py | 1 + selfdrive/test/process_replay/process_replay.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 9 files changed, 19 insertions(+), 14 deletions(-) diff --git a/models/dmonitoring_model.current b/models/dmonitoring_model.current index 9c95aff333..b0026f152a 100644 --- a/models/dmonitoring_model.current +++ b/models/dmonitoring_model.current @@ -1 +1 @@ -43221d85-46fd-40b9-bff0-2b1b18a86b07 \ No newline at end of file +e96f9be6-5741-42ea-bdcd-0be6515b4230 \ No newline at end of file diff --git a/models/dmonitoring_model.keras b/models/dmonitoring_model.keras index 9a835302ec..c3d58f6fc7 100644 --- a/models/dmonitoring_model.keras +++ b/models/dmonitoring_model.keras @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:5c39a2096f7058541b5339ec36bc4c468955e67285078080ed6d8802fed06c1d -size 814176 +oid sha256:09aa11a17a5a8173e231071898c499f9ea632e6e64285586122828b1bbc70d41 +size 4165968 diff --git a/models/dmonitoring_model_q.dlc b/models/dmonitoring_model_q.dlc index fc990411e9..558b359bfa 100644 --- a/models/dmonitoring_model_q.dlc +++ b/models/dmonitoring_model_q.dlc @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:29504dfd101ba2a0b48550fac2f86f9d0b8d1245af3d2d8d658247b4a73077a2 -size 230121 +oid sha256:beecf140ddc5da96cbdae3b869ebb3f5453dcd8e61e09d7d079c91e006b6df98 +size 1134208 diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 15b28dd8d6..4f4203a38a 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -5,9 +5,9 @@ #include -#define MODEL_WIDTH 160 -#define MODEL_HEIGHT 320 -#define FULL_W 426 +#define MODEL_WIDTH 320 +#define MODEL_HEIGHT 640 +#define FULL_W 852 #if defined(QCOM) || defined(QCOM2) #define input_lambda(x) (x - 128.f) * 0.0078125f @@ -136,6 +136,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ memcpy(&ret.right_eye_prob, &s->output[30], sizeof ret.right_eye_prob); memcpy(&ret.left_blink_prob, &s->output[31], sizeof ret.right_eye_prob); memcpy(&ret.right_blink_prob, &s->output[32], sizeof ret.right_eye_prob); + memcpy(&ret.sg_prob, &s->output[33], sizeof ret.sg_prob); ret.face_orientation_meta[0] = softplus(ret.face_orientation_meta[0]); ret.face_orientation_meta[1] = softplus(ret.face_orientation_meta[1]); ret.face_orientation_meta[2] = softplus(ret.face_orientation_meta[2]); @@ -166,6 +167,7 @@ void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResu framed.setRightEyeProb(res.right_eye_prob); framed.setLeftBlinkProb(res.left_blink_prob); framed.setRightBlinkProb(res.right_blink_prob); + framed.setSgProb(res.sg_prob); pm.send("driverState", msg); } diff --git a/selfdrive/modeld/models/dmonitoring.h b/selfdrive/modeld/models/dmonitoring.h index 83d014f8db..439b9c0051 100644 --- a/selfdrive/modeld/models/dmonitoring.h +++ b/selfdrive/modeld/models/dmonitoring.h @@ -9,7 +9,7 @@ extern "C" { #endif -#define OUTPUT_SIZE 33 +#define OUTPUT_SIZE 34 #define RHD_CHECK_INTERVAL 10 typedef struct DMonitoringResult { @@ -22,6 +22,7 @@ typedef struct DMonitoringResult { float right_eye_prob; float left_blink_prob; float right_blink_prob; + float sg_prob; } DMonitoringResult; typedef struct DMonitoringModelState { diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index 7cacd770ce..76487e24e3 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -21,8 +21,9 @@ _DISTRACTED_TIME = 11. _DISTRACTED_PRE_TIME_TILL_TERMINAL = 8. _DISTRACTED_PROMPT_TIME_TILL_TERMINAL = 6. -_FACE_THRESHOLD = 0.4 +_FACE_THRESHOLD = 0.6 _EYE_THRESHOLD = 0.6 +_SG_THRESHOLD = 0.5 _BLINK_THRESHOLD = 0.5 # 0.225 _BLINK_THRESHOLD_SLACK = 0.65 _BLINK_THRESHOLD_STRICT = 0.5 @@ -189,8 +190,8 @@ class DriverStatus(): # self.pose.roll_std = driver_state.faceOrientationStd[2] model_std_max = max(self.pose.pitch_std, self.pose.yaw_std) self.pose.low_std = model_std_max < _POSESTD_THRESHOLD - self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb > _EYE_THRESHOLD) - self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb > _EYE_THRESHOLD) + self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb > _EYE_THRESHOLD) * (driver_state.sgProb < _SG_THRESHOLD) + self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb > _EYE_THRESHOLD) * (driver_state.sgProb < _SG_THRESHOLD) self.face_detected = driver_state.faceProb > _FACE_THRESHOLD and \ abs(driver_state.facePosition[0]) <= 0.4 and abs(driver_state.facePosition[1]) <= 0.45 diff --git a/selfdrive/monitoring/test_monitoring.py b/selfdrive/monitoring/test_monitoring.py index a741115cae..270f6fe067 100644 --- a/selfdrive/monitoring/test_monitoring.py +++ b/selfdrive/monitoring/test_monitoring.py @@ -31,6 +31,7 @@ class fake_DM_msg(): self.rightBlinkProb = 1. * is_distracted self.faceOrientationStd = [1.*is_model_uncertain, 1.*is_model_uncertain, 1.*is_model_uncertain] self.facePositionStd = [1.*is_model_uncertain, 1.*is_model_uncertain] + self.sgProb = 0. # driver state from neural net, 10Hz diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 58ac4bab58..946e13f609 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -262,7 +262,7 @@ CONFIGS = [ ignore=["logMonoTime", "valid"], init_callback=get_car_params, should_recv_callback=None, - tolerance=None, + tolerance=1e-7, ), ProcessConfig( proc_name="locationd", diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 83a68c1d2a..0c8b6156f5 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -b4cf3ec3c29ef22741d5a85d50abc0937b5d40bd \ No newline at end of file +f3261f36402ad9bc3003feb9de61a04a634f30e1 \ No newline at end of file From 02dfd4ca265bdb39fef48832e82ba1d0861faf6e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 27 Jul 2020 21:29:20 -0700 Subject: [PATCH 523/656] start 0.7.8 release notes --- RELEASES.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/RELEASES.md b/RELEASES.md index 5559cd3c63..c98405e564 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,7 @@ +Version 0.7.8 (2020-08-XX) +======================== + * New driver monitoring model + Version 0.7.7 (2020-07-20) ======================== * White panda is no longer supported, upgrade to comma two or black panda From 2953ae28104c3ccde59a7659c25b853ea0421adc Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 29 Jul 2020 02:13:37 +0800 Subject: [PATCH 524/656] UI cleanup (#1941) * remove unused variables * remove unused variables --- selfdrive/ui/paint.cc | 2 -- selfdrive/ui/ui.cc | 16 ---------------- selfdrive/ui/ui.hpp | 9 --------- 3 files changed, 27 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 73d99755f6..d0e88f4dd7 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -856,8 +856,6 @@ void ui_nvg_init(UIState *s) { assert(s->vg); - s->font_courbd = nvgCreateFont(s->vg, "courbd", "../assets/fonts/courbd.ttf"); - assert(s->font_courbd >= 0); s->font_sans_regular = nvgCreateFont(s->vg, "sans-regular", "../assets/fonts/opensans_regular.ttf"); assert(s->font_sans_regular >= 0); s->font_sans_semibold = nvgCreateFont(s->vg, "sans-semibold", "../assets/fonts/opensans_semibold.ttf"); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 4bd1fa20dc..0a1566c2ab 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -193,8 +193,6 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, int num_back_fds, const int *back_fds, const VisionStreamBufs front_bufs, int num_front_fds, const int *front_fds) { - const VisionUIInfo ui_info = back_bufs.buf_info.ui_info; - assert(num_back_fds == UI_BUF_COUNT); assert(num_front_fds == UI_BUF_COUNT); @@ -206,14 +204,7 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, s->scene.frontview = getenv("FRONTVIEW") != NULL; s->scene.fullview = getenv("FULLVIEW") != NULL; - s->scene.transformed_width = ui_info.transformed_width; - s->scene.transformed_height = ui_info.transformed_height; - s->scene.front_box_x = ui_info.front_box_x; - s->scene.front_box_y = ui_info.front_box_y; - s->scene.front_box_width = ui_info.front_box_width; - s->scene.front_box_height = ui_info.front_box_height; s->scene.world_objects_visible = false; // Invisible until we receive a calibration message. - s->scene.gps_planner_active = false; s->rgb_width = back_bufs.width; s->rgb_height = back_bufs.height; @@ -225,13 +216,6 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, s->rgb_front_stride = front_bufs.stride; s->rgb_front_buf_len = front_bufs.buf_len; - s->rgb_transform = (mat4){{ - 2.0f/s->rgb_width, 0.0f, 0.0f, -1.0f, - 0.0f, 2.0f/s->rgb_height, 0.0f, -1.0f, - 0.0f, 0.0f, 1.0f, 0.0f, - 0.0f, 0.0f, 0.0f, 1.0f, - }}; - read_param(&s->speed_lim_off, "SpeedLimitOffset"); read_param(&s->is_metric, "IsMetric"); read_param(&s->longitudinal_control, "LongitudinalControl"); diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 830d227e39..1094f7cca3 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -92,8 +92,6 @@ typedef struct UIScene { int frontview; int fullview; - int transformed_width, transformed_height; - ModelData model; float mpc_x[50]; @@ -114,16 +112,11 @@ typedef struct UIScene { int ui_viz_rw; int ui_viz_ro; - int front_box_x, front_box_y, front_box_width, front_box_height; - std::string alert_text1; std::string alert_text2; std::string alert_type; cereal::ControlsState::AlertSize alert_size; - // Used to show gps planner status - bool gps_planner_active; - cereal::HealthData::HwType hwType; int satelliteCount; uint8_t athenaStatus; @@ -160,7 +153,6 @@ typedef struct UIState { NVGcontext *vg; // fonts and images - int font_courbd; int font_sans_regular; int font_sans_semibold; int font_sans_bold; @@ -203,7 +195,6 @@ typedef struct UIState { int rgb_width, rgb_height, rgb_stride; size_t rgb_buf_len; - mat4 rgb_transform; int rgb_front_width, rgb_front_height, rgb_front_stride; size_t rgb_front_buf_len; From 2e59349b2e4bda54942cb96ba6bba9661ee89b4b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 28 Jul 2020 13:15:16 -0500 Subject: [PATCH 525/656] Add a minimal debugging tool to show the UI while device not in car (#1937) * add a minimal uiview file with alias from selfdrive/ui * make ui_debug executable * minimize uiview.py; remove os and functions. the processes exit normally when ctrl+c'ing out of the loop * violating E401 here, save 1 more line * kill on exit * forgot signal * new record! 15 lines * add comments and declare some common variables. don't need to redefine the messages every loop --- selfdrive/debug/uiview.py | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) create mode 100644 selfdrive/debug/uiview.py diff --git a/selfdrive/debug/uiview.py b/selfdrive/debug/uiview.py new file mode 100644 index 0000000000..899f932ad6 --- /dev/null +++ b/selfdrive/debug/uiview.py @@ -0,0 +1,21 @@ +#!/usr/bin/env python3 +import time +import cereal.messaging as messaging +from selfdrive.manager import start_managed_process, kill_managed_process + +services = ['controlsState', 'thermal'] # the services needed to be spoofed to start ui offroad +procs = ['camerad', 'ui'] +[start_managed_process(p) for p in procs] # start needed processes +pm = messaging.PubMaster(services) + +dat_cs, dat_thermal = [messaging.new_message(s) for s in services] +dat_cs.controlsState.rearViewCam = False # ui checks for these two messages +dat_thermal.thermal.started = True + +try: + while True: + pm.send('controlsState', dat_cs) + pm.send('thermal', dat_thermal) + time.sleep(1 / 100) # continually send, rate doesn't matter for thermal +except KeyboardInterrupt: + [kill_managed_process(p) for p in procs] From e03f9d7c7370ead66acf84e27e8361c6fd453379 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Tue, 28 Jul 2020 15:12:09 -0700 Subject: [PATCH 526/656] needed in pipeline --- common/transformations/camera.py | 7 +++++++ common/transformations/model.py | 4 ++++ 2 files changed, 11 insertions(+) diff --git a/common/transformations/camera.py b/common/transformations/camera.py index e56a6f34bf..b406c33fd7 100644 --- a/common/transformations/camera.py +++ b/common/transformations/camera.py @@ -52,6 +52,13 @@ def get_view_frame_from_road_frame(roll, pitch, yaw, height): return np.hstack((view_from_road, [[0], [height], [0]])) +# aka 'extrinsic_matrix' +def get_view_frame_from_calib_frame(roll, pitch, yaw, height): + device_from_calib= orient.rot_from_euler([roll, pitch, yaw]) + view_from_calib = view_frame_from_device_frame.dot(device_from_calib) + return np.hstack((view_from_calib, [[0], [height], [0]])) + + def vp_from_ke(m): """ Computes the vanishing point from the product of the intrinsic and extrinsic diff --git a/common/transformations/model.py b/common/transformations/model.py index 070d174711..221bebae69 100644 --- a/common/transformations/model.py +++ b/common/transformations/model.py @@ -2,6 +2,7 @@ import numpy as np from common.transformations.camera import (FULL_FRAME_SIZE, eon_focal_length, get_view_frame_from_road_frame, + get_view_frame_from_calib_frame, vp_from_ke) # segnet @@ -73,6 +74,9 @@ bigmodel_frame_from_road_frame = np.dot(bigmodel_intrinsics, medmodel_frame_from_road_frame = np.dot(medmodel_intrinsics, get_view_frame_from_road_frame(0, 0, 0, model_height)) +medmodel_frame_from_calib_frame = np.dot(medmodel_intrinsics, + get_view_frame_from_calib_frame(0, 0, 0, model_height)) + model_frame_from_bigmodel_frame = np.dot(model_intrinsics, np.linalg.inv(bigmodel_intrinsics)) medmodel_frame_from_bigmodel_frame = np.dot(medmodel_intrinsics, np.linalg.inv(bigmodel_intrinsics)) From 6acda96a163ad77f2f0b283712ac79b3d3d90d54 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 28 Jul 2020 18:37:16 -0700 Subject: [PATCH 527/656] can't directly access sockets anymore --- cereal | 2 +- selfdrive/controls/controlsd.py | 4 +++- selfdrive/test/process_replay/camera_replay.py | 4 ++-- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/cereal b/cereal index 29099e87a1..32300930f6 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 29099e87a1372694fb81b426faaa57e832bbe87a +Subproject commit 32300930f65425bbba136461446149af8f8b42d9 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 4c11c5e05a..fa9def2239 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -61,7 +61,9 @@ class Controls: self.can_sock = messaging.sub_sock('can', timeout=can_timeout) # wait for one health and one CAN packet - hw_type = messaging.recv_one(self.sm.sock['health']).health.hwType + while not sm.updated['health']: + sm.update() + hw_type = sm['health'].hwType has_relay = hw_type in [HwType.blackPanda, HwType.uno, HwType.dos] print("Waiting for CAN messages...") messaging.get_one_can(self.can_sock) diff --git a/selfdrive/test/process_replay/camera_replay.py b/selfdrive/test/process_replay/camera_replay.py index 501f8f6111..f2cc4a5461 100755 --- a/selfdrive/test/process_replay/camera_replay.py +++ b/selfdrive/test/process_replay/camera_replay.py @@ -27,7 +27,7 @@ def camera_replay(lr, fr): spinner = Spinner() pm = messaging.PubMaster(['frame', 'liveCalibration']) - sm = messaging.SubMaster(['model']) + model_sock = messaging.sub_sock("model", conflate=False) # TODO: add dmonitoringmodeld print("preparing procs") @@ -56,7 +56,7 @@ def camera_replay(lr, fr): frame_idx += 1 pm.send(msg.which(), f) - log_msgs.append(messaging.recv_one(sm.sock['model'])) + log_msgs.append(messaging.recv_one(model_sock)) spinner.update("modeld replay %d/%d" % (frame_idx, fr.frame_count)) From acb25751b75059a6e212192064528afe0ebd5e03 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 28 Jul 2020 18:41:39 -0700 Subject: [PATCH 528/656] Revert "can't directly access sockets anymore", was supposed to be on branch This reverts commit 6acda96a163ad77f2f0b283712ac79b3d3d90d54. --- cereal | 2 +- selfdrive/controls/controlsd.py | 4 +--- selfdrive/test/process_replay/camera_replay.py | 4 ++-- 3 files changed, 4 insertions(+), 6 deletions(-) diff --git a/cereal b/cereal index 32300930f6..29099e87a1 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 32300930f65425bbba136461446149af8f8b42d9 +Subproject commit 29099e87a1372694fb81b426faaa57e832bbe87a diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index fa9def2239..4c11c5e05a 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -61,9 +61,7 @@ class Controls: self.can_sock = messaging.sub_sock('can', timeout=can_timeout) # wait for one health and one CAN packet - while not sm.updated['health']: - sm.update() - hw_type = sm['health'].hwType + hw_type = messaging.recv_one(self.sm.sock['health']).health.hwType has_relay = hw_type in [HwType.blackPanda, HwType.uno, HwType.dos] print("Waiting for CAN messages...") messaging.get_one_can(self.can_sock) diff --git a/selfdrive/test/process_replay/camera_replay.py b/selfdrive/test/process_replay/camera_replay.py index f2cc4a5461..501f8f6111 100755 --- a/selfdrive/test/process_replay/camera_replay.py +++ b/selfdrive/test/process_replay/camera_replay.py @@ -27,7 +27,7 @@ def camera_replay(lr, fr): spinner = Spinner() pm = messaging.PubMaster(['frame', 'liveCalibration']) - model_sock = messaging.sub_sock("model", conflate=False) + sm = messaging.SubMaster(['model']) # TODO: add dmonitoringmodeld print("preparing procs") @@ -56,7 +56,7 @@ def camera_replay(lr, fr): frame_idx += 1 pm.send(msg.which(), f) - log_msgs.append(messaging.recv_one(model_sock)) + log_msgs.append(messaging.recv_one(sm.sock['model'])) spinner.update("modeld replay %d/%d" % (frame_idx, fr.frame_count)) From 9853b5b1dfff60afdadb95aebe5ad5b23d09a3b1 Mon Sep 17 00:00:00 2001 From: xps-genesis <65239463+xps-genesis@users.noreply.github.com> Date: Tue, 28 Jul 2020 23:22:43 -0400 Subject: [PATCH 529/656] new palisade fingerprint (#1945) * new palisade fingerprint * update 1 * FP2 added * spacing adjust * missed a syntax --- selfdrive/car/hyundai/values.py | 20 +++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 42e7ae1e2d..7dc60144ea 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -136,7 +136,7 @@ FINGERPRINTS = { 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576: 8, 593: 8, 688: 5, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 909: 8, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1265: 4, 1268: 8, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1420: 8, 1425: 2, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 }], CAR.PALISADE: [{ - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 549: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1123: 8, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 2000: 8, 2005: 8, 2008: 8 + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 549: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1123: 8, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8 }], } @@ -190,16 +190,26 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424',], (Ecu.transmission, 0x7e1, None): [b"\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PDE0G16NS2\xf4'\\\x91",], }, - CAR.PALISADE: { - (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 \xf1\xa01.04',], + CAR.PALISADE: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 \xf1\xa01.04', + b'\xf1\x00LX2 SCC FHCUP 1.00 1.04 99110-S8100 \xf1\xa01.04', + ], (Ecu.esp, 0x7d1, None): [ b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330', b'\xf1\x00LX ESC \v 102\x19\x05\a 58910-S8330\xf1\xa01.02', + b'\xf1\x00LX ESC \v 103\x19\t\x10 58910-S8360\xf1\xa01.03', ], (Ecu.engine, 0x7e0, None): [b'\xf1\x81640J0051\x00\x00\x00\x00\x00\x00\x00\x00',], (Ecu.eps, 0x7d4, None): [b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103',], - (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125',], - (Ecu.transmission, 0x7e1, None): [b'\xf1\x87LDKVBN424201KF26\xba\xaa\x9a\xa9\x99\x99\x89\x98\x89\x99\xa8\x99\x88\x99\x98\x89\x88\x99\xa8\x89v\x7f\xf7\xffwf_\xffq\xa6\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7',], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.05 99211-S8100 190909', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x87LDKVBN424201KF26\xba\xaa\x9a\xa9\x99\x99\x89\x98\x89\x99\xa8\x99\x88\x99\x98\x89\x88\x99\xa8\x89v\x7f\xf7\xffwf_\xffq\xa6\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', + b'\xf1\x87LDLVBN560098KF26\x86fff\x87vgfg\x88\x96xfw\x86gfw\x86g\x95\xf6\xffeU_\xff\x92c\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', + ], } } From 63e4aeac9f63fac4ab7679766ac2e655c1e98a8c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 28 Jul 2020 23:37:53 -0700 Subject: [PATCH 530/656] fail new car model unit tests if missing a test route --- selfdrive/test/test_car_models.py | 1 + selfdrive/test/test_models.py | 10 +++++++--- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 09f1586e1d..8c14339977 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -440,6 +440,7 @@ non_tested_cars = [ TOYOTA.CAMRYH, TOYOTA.CHR, TOYOTA.CHRH, + TOYOTA.HIGHLANDER, TOYOTA.HIGHLANDERH, TOYOTA.HIGHLANDERH_TSS2, ] diff --git a/selfdrive/test/test_models.py b/selfdrive/test/test_models.py index b44f8e60b8..a854953529 100755 --- a/selfdrive/test/test_models.py +++ b/selfdrive/test/test_models.py @@ -10,7 +10,7 @@ from cereal import log, car import cereal.messaging as messaging from selfdrive.car.fingerprints import all_known_cars from selfdrive.car.car_helpers import interfaces -from selfdrive.test.test_car_models import routes +from selfdrive.test.test_car_models import routes, non_tested_cars from selfdrive.test.openpilotci import get_url from tools.lib.logreader import LogReader @@ -27,8 +27,12 @@ class TestCarModel(unittest.TestCase): @classmethod def setUpClass(cls): if cls.car_model not in ROUTES: - print(f"Skipping tests for {cls.car_model}: missing route") - raise unittest.SkipTest + # TODO: get routes for missing cars and remove this + if cls.car_model in non_tested_cars: + print(f"Skipping tests for {cls.car_model}: missing route") + raise unittest.SkipTest + else: + raise Exception(f"missing test route for car {cls.car_model}") try: lr = LogReader(get_url(ROUTES[cls.car_model], 1)) From 714f8c3f0bf8fa98a4619763d46ecb3ea29bc9f6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 28 Jul 2020 23:52:18 -0700 Subject: [PATCH 531/656] Remove get_one_can from messaging (#1946) * move get_one_can into openpilot * bump cereal --- cereal | 2 +- selfdrive/car/car_helpers.py | 9 ++++++++- selfdrive/controls/controlsd.py | 4 ++-- tools/carcontrols/debug_controls.py | 4 ++-- 4 files changed, 13 insertions(+), 6 deletions(-) diff --git a/cereal b/cereal index 29099e87a1..430cc73a3b 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 29099e87a1372694fb81b426faaa57e832bbe87a +Subproject commit 430cc73a3b7c31de902bd0a62fbac7cd3a05cf3e diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 478db2375c..e79b03cc5c 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -27,6 +27,13 @@ def get_startup_event(car_recognized, controller_available): return event +def get_one_can(logcan): + while True: + can = messaging.recv_one_retry(logcan) + if len(can.can) > 0: + return can + + def load_interfaces(brand_names): ret = {} for brand_name in brand_names: @@ -114,7 +121,7 @@ def fingerprint(logcan, sendcan, has_relay): done = False while not done: - a = messaging.get_one_can(logcan) + a = get_one_can(logcan) for can in a.can: # need to independently try to fingerprint both bus 0 and 1 to work diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 4c11c5e05a..5443f8d382 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -10,7 +10,7 @@ from common.params import Params, put_nonblocking import cereal.messaging as messaging from selfdrive.config import Conversions as CV from selfdrive.boardd.boardd import can_list_to_can_capnp -from selfdrive.car.car_helpers import get_car, get_startup_event +from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can from selfdrive.controls.lib.lane_planner import CAMERA_OFFSET from selfdrive.controls.lib.drive_helpers import update_v_cruise, initialize_v_cruise from selfdrive.controls.lib.longcontrol import LongControl, STARTING_TARGET_SPEED @@ -64,7 +64,7 @@ class Controls: hw_type = messaging.recv_one(self.sm.sock['health']).health.hwType has_relay = hw_type in [HwType.blackPanda, HwType.uno, HwType.dos] print("Waiting for CAN messages...") - messaging.get_one_can(self.can_sock) + get_one_can(self.can_sock) self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan'], has_relay) diff --git a/tools/carcontrols/debug_controls.py b/tools/carcontrols/debug_controls.py index 1f353e0666..cdb5e3af87 100755 --- a/tools/carcontrols/debug_controls.py +++ b/tools/carcontrols/debug_controls.py @@ -4,7 +4,7 @@ from common.params import Params from copy import copy from cereal import car, log import cereal.messaging as messaging -from selfdrive.car.car_helpers import get_car +from selfdrive.car.car_helpers import get_car, get_one_can from selfdrive.boardd.boardd import can_list_to_can_capnp HwType = log.HealthData.HwType @@ -28,7 +28,7 @@ def steer_thread(): hw_type = messaging.recv_one(health).health.hwType has_relay = hw_type in [HwType.blackPanda, HwType.uno, HwType.dos] print("Waiting for CAN messages...") - messaging.get_one_can(logcan) + get_one_can(logcan) CI, CP = get_car(logcan, sendcan, has_relay) Params().put("CarParams", CP.to_bytes()) From b467f5777b544a53c7801ee5e0d00b366e5a089b Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Wed, 29 Jul 2020 10:21:37 -0700 Subject: [PATCH 532/656] not useful --- Pipfile | 1 - Pipfile.lock | 557 +++++++++++++++++++++++++-------------------------- 2 files changed, 275 insertions(+), 283 deletions(-) diff --git a/Pipfile b/Pipfile index a647cead9e..45cbec0b8c 100644 --- a/Pipfile +++ b/Pipfile @@ -17,7 +17,6 @@ boto = "*" "boto3" = "*" control = "*" datadog = "*" -dlib = "*" elasticsearch = "*" gunicorn = "*" "h5py" = "*" diff --git a/Pipfile.lock b/Pipfile.lock index 1d5027371a..7c707808e4 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "484ec3309452d56769b732b3c5d3d49023fe696220c07f81862b8bbf8283cedf" + "sha256": "b7a0486f1174e81a5a51b37a775d05633295dadbb478860f6f8586c4095421c2" }, "pipfile-spec": 6, "requires": { @@ -41,37 +41,37 @@ }, "cffi": { "hashes": [ - "sha256:001bf3242a1bb04d985d63e138230802c6c8d4db3668fb545fb5005ddf5bb5ff", - "sha256:00789914be39dffba161cfc5be31b55775de5ba2235fe49aa28c148236c4e06b", - "sha256:028a579fc9aed3af38f4892bdcc7390508adabc30c6af4a6e4f611b0c680e6ac", - "sha256:14491a910663bf9f13ddf2bc8f60562d6bc5315c1f09c704937ef17293fb85b0", - "sha256:1cae98a7054b5c9391eb3249b86e0e99ab1e02bb0cc0575da191aedadbdf4384", - "sha256:2089ed025da3919d2e75a4d963d008330c96751127dd6f73c8dc0c65041b4c26", - "sha256:2d384f4a127a15ba701207f7639d94106693b6cd64173d6c8988e2c25f3ac2b6", - "sha256:337d448e5a725bba2d8293c48d9353fc68d0e9e4088d62a9571def317797522b", - "sha256:399aed636c7d3749bbed55bc907c3288cb43c65c4389964ad5ff849b6370603e", - "sha256:3b911c2dbd4f423b4c4fcca138cadde747abdb20d196c4a48708b8a2d32b16dd", - "sha256:3d311bcc4a41408cf5854f06ef2c5cab88f9fded37a3b95936c9879c1640d4c2", - "sha256:62ae9af2d069ea2698bf536dcfe1e4eed9090211dbaafeeedf5cb6c41b352f66", - "sha256:66e41db66b47d0d8672d8ed2708ba91b2f2524ece3dee48b5dfb36be8c2f21dc", - "sha256:675686925a9fb403edba0114db74e741d8181683dcf216be697d208857e04ca8", - "sha256:7e63cbcf2429a8dbfe48dcc2322d5f2220b77b2e17b7ba023d6166d84655da55", - "sha256:8a6c688fefb4e1cd56feb6c511984a6c4f7ec7d2a1ff31a10254f3c817054ae4", - "sha256:8c0ffc886aea5df6a1762d0019e9cb05f825d0eec1f520c51be9d198701daee5", - "sha256:95cd16d3dee553f882540c1ffe331d085c9e629499ceadfbda4d4fde635f4b7d", - "sha256:99f748a7e71ff382613b4e1acc0ac83bf7ad167fb3802e35e90d9763daba4d78", - "sha256:b8c78301cefcf5fd914aad35d3c04c2b21ce8629b5e4f4e45ae6812e461910fa", - "sha256:c420917b188a5582a56d8b93bdd8e0f6eca08c84ff623a4c16e809152cd35793", - "sha256:c43866529f2f06fe0edc6246eb4faa34f03fe88b64a0a9a942561c8e22f4b71f", - "sha256:cab50b8c2250b46fe738c77dbd25ce017d5e6fb35d3407606e7a4180656a5a6a", - "sha256:cef128cb4d5e0b3493f058f10ce32365972c554572ff821e175dbc6f8ff6924f", - "sha256:cf16e3cf6c0a5fdd9bc10c21687e19d29ad1fe863372b5543deaec1039581a30", - "sha256:e56c744aa6ff427a607763346e4170629caf7e48ead6921745986db3692f987f", - "sha256:e577934fc5f8779c554639376beeaa5657d54349096ef24abe8c74c5d9c117c3", - "sha256:f2b0fa0c01d8a0c7483afd9f31d7ecf2d71760ca24499c8697aeb5ca37dc090c" - ], - "index": "pypi", - "version": "==1.14.0" + "sha256:267adcf6e68d77ba154334a3e4fc921b8e63cbb38ca00d33d40655d4228502bc", + "sha256:26f33e8f6a70c255767e3c3f957ccafc7f1f706b966e110b855bfe944511f1f9", + "sha256:3cd2c044517f38d1b577f05927fb9729d3396f1d44d0c659a445599e79519792", + "sha256:4a03416915b82b81af5502459a8a9dd62a3c299b295dcdf470877cb948d655f2", + "sha256:4ce1e995aeecf7cc32380bc11598bfdfa017d592259d5da00fc7ded11e61d022", + "sha256:4f53e4128c81ca3212ff4cf097c797ab44646a40b42ec02a891155cd7a2ba4d8", + "sha256:4fa72a52a906425416f41738728268072d5acfd48cbe7796af07a923236bcf96", + "sha256:66dd45eb9530e3dde8f7c009f84568bc7cac489b93d04ac86e3111fb46e470c2", + "sha256:6923d077d9ae9e8bacbdb1c07ae78405a9306c8fd1af13bfa06ca891095eb995", + "sha256:833401b15de1bb92791d7b6fb353d4af60dc688eaa521bd97203dcd2d124a7c1", + "sha256:8416ed88ddc057bab0526d4e4e9f3660f614ac2394b5e019a628cdfff3733849", + "sha256:892daa86384994fdf4856cb43c93f40cbe80f7f95bb5da94971b39c7f54b3a9c", + "sha256:98be759efdb5e5fa161e46d404f4e0ce388e72fbf7d9baf010aff16689e22abe", + "sha256:a6d28e7f14ecf3b2ad67c4f106841218c8ab12a0683b1528534a6c87d2307af3", + "sha256:b1d6ebc891607e71fd9da71688fcf332a6630b7f5b7f5549e6e631821c0e5d90", + "sha256:b2a2b0d276a136146e012154baefaea2758ef1f56ae9f4e01c612b0831e0bd2f", + "sha256:b87dfa9f10a470eee7f24234a37d1d5f51e5f5fa9eeffda7c282e2b8f5162eb1", + "sha256:bac0d6f7728a9cc3c1e06d4fcbac12aaa70e9379b3025b27ec1226f0e2d404cf", + "sha256:c991112622baee0ae4d55c008380c32ecfd0ad417bcd0417ba432e6ba7328caa", + "sha256:cda422d54ee7905bfc53ee6915ab68fe7b230cacf581110df4272ee10462aadc", + "sha256:d3148b6ba3923c5850ea197a91a42683f946dba7e8eb82dfa211ab7e708de939", + "sha256:d6033b4ffa34ef70f0b8086fd4c3df4bf801fee485a8a7d4519399818351aa8e", + "sha256:ddff0b2bd7edcc8c82d1adde6dbbf5e60d57ce985402541cd2985c27f7bec2a0", + "sha256:e23cb7f1d8e0f93addf0cae3c5b6f00324cccb4a7949ee558d7b6ca973ab8ae9", + "sha256:effd2ba52cee4ceff1a77f20d2a9f9bf8d50353c854a282b8760ac15b9833168", + "sha256:f90c2267101010de42f7273c94a1f026e56cbc043f9330acd8a80e64300aba33", + "sha256:f960375e9823ae6a07072ff7f8a85954e5a6434f97869f50d0e41649a1c8144f", + "sha256:fcf32bf76dc25e30ed793145a57426064520890d7c02866eb93d3e4abe516948" + ], + "index": "pypi", + "version": "==1.14.1" }, "chardet": { "hashes": [ @@ -342,35 +342,35 @@ }, "numpy": { "hashes": [ - "sha256:13af0184177469192d80db9bd02619f6fa8b922f9f327e077d6f2a6acb1ce1c0", - "sha256:26a45798ca2a4e168d00de75d4a524abf5907949231512f372b217ede3429e98", - "sha256:26f509450db547e4dfa3ec739419b31edad646d21fb8d0ed0734188b35ff6b27", - "sha256:30a59fb41bb6b8c465ab50d60a1b298d1cd7b85274e71f38af5a75d6c475d2d2", - "sha256:33c623ef9ca5e19e05991f127c1be5aeb1ab5cdf30cb1c5cf3960752e58b599b", - "sha256:356f96c9fbec59974a592452ab6a036cd6f180822a60b529a975c9467fcd5f23", - "sha256:3c40c827d36c6d1c3cf413694d7dc843d50997ebffbc7c87d888a203ed6403a7", - "sha256:4d054f013a1983551254e2379385e359884e5af105e3efe00418977d02f634a7", - "sha256:63d971bb211ad3ca37b2adecdd5365f40f3b741a455beecba70fd0dde8b2a4cb", - "sha256:658624a11f6e1c252b2cd170d94bf28c8f9410acab9f2fd4369e11e1cd4e1aaf", - "sha256:76766cc80d6128750075378d3bb7812cf146415bd29b588616f72c943c00d598", - "sha256:7b57f26e5e6ee2f14f960db46bd58ffdca25ca06dd997729b1b179fddd35f5a3", - "sha256:7b852817800eb02e109ae4a9cef2beda8dd50d98b76b6cfb7b5c0099d27b52d4", - "sha256:8cde829f14bd38f6da7b2954be0f2837043e8b8d7a9110ec5e318ae6bf706610", - "sha256:a2e3a39f43f0ce95204beb8fe0831199542ccab1e0c6e486a0b4947256215632", - "sha256:a86c962e211f37edd61d6e11bb4df7eddc4a519a38a856e20a6498c319efa6b0", - "sha256:a8705c5073fe3fcc297fb8e0b31aa794e05af6a329e81b7ca4ffecab7f2b95ef", - "sha256:b6aaeadf1e4866ca0fdf7bb4eed25e521ae21a7947c59f78154b24fc7abbe1dd", - "sha256:be62aeff8f2f054eff7725f502f6228298891fd648dc2630e03e44bf63e8cee0", - "sha256:c2edbb783c841e36ca0fa159f0ae97a88ce8137fb3a6cd82eae77349ba4b607b", - "sha256:cbe326f6d364375a8e5a8ccb7e9cd73f4b2f6dc3b2ed205633a0db8243e2a96a", - "sha256:d34fbb98ad0d6b563b95de852a284074514331e6b9da0a9fc894fb1cdae7a79e", - "sha256:d97a86937cf9970453c3b62abb55a6475f173347b4cde7f8dcdb48c8e1b9952d", - "sha256:dd53d7c4a69e766e4900f29db5872f5824a06827d594427cf1a4aa542818b796", - "sha256:df1889701e2dfd8ba4dc9b1a010f0a60950077fb5242bb92c8b5c7f1a6f2668a", - "sha256:fa1fe75b4a9e18b66ae7f0b122543c42debcf800aaafa0212aaff3ad273c2596" - ], - "index": "pypi", - "version": "==1.19.0" + "sha256:082f8d4dd69b6b688f64f509b91d482362124986d98dc7dc5f5e9f9b9c3bb983", + "sha256:1bc0145999e8cb8aed9d4e65dd8b139adf1919e521177f198529687dbf613065", + "sha256:309cbcfaa103fc9a33ec16d2d62569d541b79f828c382556ff072442226d1968", + "sha256:3673c8b2b29077f1b7b3a848794f8e11f401ba0b71c49fbd26fb40b71788b132", + "sha256:480fdd4dbda4dd6b638d3863da3be82873bba6d32d1fc12ea1b8486ac7b8d129", + "sha256:56ef7f56470c24bb67fb43dae442e946a6ce172f97c69f8d067ff8550cf782ff", + "sha256:5a936fd51049541d86ccdeef2833cc89a18e4d3808fe58a8abeb802665c5af93", + "sha256:5b6885c12784a27e957294b60f97e8b5b4174c7504665333c5e94fbf41ae5d6a", + "sha256:667c07063940e934287993366ad5f56766bc009017b4a0fe91dbd07960d0aba7", + "sha256:7ed448ff4eaffeb01094959b19cbaf998ecdee9ef9932381420d514e446601cd", + "sha256:8343bf67c72e09cfabfab55ad4a43ce3f6bf6e6ced7acf70f45ded9ebb425055", + "sha256:92feb989b47f83ebef246adabc7ff3b9a59ac30601c3f6819f8913458610bdcc", + "sha256:935c27ae2760c21cd7354402546f6be21d3d0c806fffe967f745d5f2de5005a7", + "sha256:aaf42a04b472d12515debc621c31cf16c215e332242e7a9f56403d814c744624", + "sha256:b12e639378c741add21fbffd16ba5ad25c0a1a17cf2b6fe4288feeb65144f35b", + "sha256:b1cca51512299841bf69add3b75361779962f9cee7d9ee3bb446d5982e925b69", + "sha256:b8456987b637232602ceb4d663cb34106f7eb780e247d51a260b84760fd8f491", + "sha256:b9792b0ac0130b277536ab8944e7b754c69560dac0415dd4b2dbd16b902c8954", + "sha256:c9591886fc9cbe5532d5df85cb8e0cc3b44ba8ce4367bd4cf1b93dc19713da72", + "sha256:cf1347450c0b7644ea142712619533553f02ef23f92f781312f6a3553d031fc7", + "sha256:de8b4a9b56255797cbddb93281ed92acbc510fb7b15df3f01bd28f46ebc4edae", + "sha256:e1b1dc0372f530f26a03578ac75d5e51b3868b9b76cd2facba4c9ee0eb252ab1", + "sha256:e45f8e981a0ab47103181773cc0a54e650b2aef8c7b6cd07405d0fa8d869444a", + "sha256:e4f6d3c53911a9d103d8ec9518190e52a8b945bab021745af4939cfc7c0d4a9e", + "sha256:ed8a311493cf5480a2ebc597d1e177231984c818a86875126cfd004241a73c3e", + "sha256:ef71a1d4fd4858596ae80ad1ec76404ad29701f8ca7cdcebc50300178db14dfc" + ], + "index": "pypi", + "version": "==1.19.1" }, "pillow": { "hashes": [ @@ -643,11 +643,11 @@ }, "urllib3": { "hashes": [ - "sha256:3018294ebefce6572a474f0604c2021e33b3fd8006ecd11d62107a5d2a963527", - "sha256:88206b0eb87e6d677d424843ac5209e3fb9d0190d0ee169599165ec25e9d9115" + "sha256:91056c15fa70756691db97756772bb1eb9678fa585d9184f24534b100dc60f4a", + "sha256:e7983572181f5e1522d9c98453462384ee92a0be7fac5f1413a1e35c56cc0461" ], "index": "pypi", - "version": "==1.25.9" + "version": "==1.25.10" }, "utm": { "hashes": [ @@ -695,12 +695,12 @@ }, "aenum": { "hashes": [ - "sha256:284ddb976413d97239a932d7e5202ba58d66e5dbd81531bf3033ebb36ec30b23", - "sha256:a4334cabf47c167d44ab5a6198837b80deec5d5bad1b5cf70c966c3a330260e8", - "sha256:d2bb6ea7586aaae889d3a5c332eafa851eeffe6e7068807c79b6c86c4326b938" + "sha256:81828d1fbe20b6b188d75b21a0fa936d7d929d839ef843ef385d9c2a97082864", + "sha256:85adabd63183d283250bf7acd9fa23c7e45b1c8d1efbb84b233160f3c438dc18", + "sha256:bcb4fd350d36af336b6b5898e5d89f76344621d9c1b2de69c81acf1d3e6b1145" ], "index": "pypi", - "version": "==2.2.3" + "version": "==2.2.4" }, "aiohttp": { "hashes": [ @@ -915,18 +915,18 @@ }, "boto3": { "hashes": [ - "sha256:542fa3499624dfa3312fd5a6f45bc221d0871c73c5d91c57e5c6435b6f4463cc", - "sha256:6bf841797d5ec9f7770a335d919c5ea20d1980c1eb39b009e58f6de2879ff2cd" + "sha256:4e357963ddd36a769e9a18ffe7517fed61f2b301a6e7d3c833cb5171146a5f53", + "sha256:859e29da7cce712f8fae8666fccb424bf3b42802d622b61b5219ea8a70e6a8f8" ], "index": "pypi", - "version": "==1.14.24" + "version": "==1.14.30" }, "botocore": { "hashes": [ - "sha256:023e390e1caaf4aab55bd6b87738777d25e7b6f3098fb77e356e638c0baa491b", - "sha256:2e07c0b88563d793cca8186c7fa42cfd5b8ece4fed31c928e0676091f3bb815d" + "sha256:8d5c40c2ab98223caa87cf1109d4449ee3022cb0ce9eb3b76696a231cf447888", + "sha256:d222643daa1a510f7e11e02b424689d69b49d6a88add13cbfd2a676daae6e200" ], - "version": "==1.17.24" + "version": "==1.17.30" }, "cachetools": { "hashes": [ @@ -945,37 +945,37 @@ }, "cffi": { "hashes": [ - "sha256:001bf3242a1bb04d985d63e138230802c6c8d4db3668fb545fb5005ddf5bb5ff", - "sha256:00789914be39dffba161cfc5be31b55775de5ba2235fe49aa28c148236c4e06b", - "sha256:028a579fc9aed3af38f4892bdcc7390508adabc30c6af4a6e4f611b0c680e6ac", - "sha256:14491a910663bf9f13ddf2bc8f60562d6bc5315c1f09c704937ef17293fb85b0", - "sha256:1cae98a7054b5c9391eb3249b86e0e99ab1e02bb0cc0575da191aedadbdf4384", - "sha256:2089ed025da3919d2e75a4d963d008330c96751127dd6f73c8dc0c65041b4c26", - "sha256:2d384f4a127a15ba701207f7639d94106693b6cd64173d6c8988e2c25f3ac2b6", - "sha256:337d448e5a725bba2d8293c48d9353fc68d0e9e4088d62a9571def317797522b", - "sha256:399aed636c7d3749bbed55bc907c3288cb43c65c4389964ad5ff849b6370603e", - "sha256:3b911c2dbd4f423b4c4fcca138cadde747abdb20d196c4a48708b8a2d32b16dd", - "sha256:3d311bcc4a41408cf5854f06ef2c5cab88f9fded37a3b95936c9879c1640d4c2", - "sha256:62ae9af2d069ea2698bf536dcfe1e4eed9090211dbaafeeedf5cb6c41b352f66", - "sha256:66e41db66b47d0d8672d8ed2708ba91b2f2524ece3dee48b5dfb36be8c2f21dc", - "sha256:675686925a9fb403edba0114db74e741d8181683dcf216be697d208857e04ca8", - "sha256:7e63cbcf2429a8dbfe48dcc2322d5f2220b77b2e17b7ba023d6166d84655da55", - "sha256:8a6c688fefb4e1cd56feb6c511984a6c4f7ec7d2a1ff31a10254f3c817054ae4", - "sha256:8c0ffc886aea5df6a1762d0019e9cb05f825d0eec1f520c51be9d198701daee5", - "sha256:95cd16d3dee553f882540c1ffe331d085c9e629499ceadfbda4d4fde635f4b7d", - "sha256:99f748a7e71ff382613b4e1acc0ac83bf7ad167fb3802e35e90d9763daba4d78", - "sha256:b8c78301cefcf5fd914aad35d3c04c2b21ce8629b5e4f4e45ae6812e461910fa", - "sha256:c420917b188a5582a56d8b93bdd8e0f6eca08c84ff623a4c16e809152cd35793", - "sha256:c43866529f2f06fe0edc6246eb4faa34f03fe88b64a0a9a942561c8e22f4b71f", - "sha256:cab50b8c2250b46fe738c77dbd25ce017d5e6fb35d3407606e7a4180656a5a6a", - "sha256:cef128cb4d5e0b3493f058f10ce32365972c554572ff821e175dbc6f8ff6924f", - "sha256:cf16e3cf6c0a5fdd9bc10c21687e19d29ad1fe863372b5543deaec1039581a30", - "sha256:e56c744aa6ff427a607763346e4170629caf7e48ead6921745986db3692f987f", - "sha256:e577934fc5f8779c554639376beeaa5657d54349096ef24abe8c74c5d9c117c3", - "sha256:f2b0fa0c01d8a0c7483afd9f31d7ecf2d71760ca24499c8697aeb5ca37dc090c" - ], - "index": "pypi", - "version": "==1.14.0" + "sha256:267adcf6e68d77ba154334a3e4fc921b8e63cbb38ca00d33d40655d4228502bc", + "sha256:26f33e8f6a70c255767e3c3f957ccafc7f1f706b966e110b855bfe944511f1f9", + "sha256:3cd2c044517f38d1b577f05927fb9729d3396f1d44d0c659a445599e79519792", + "sha256:4a03416915b82b81af5502459a8a9dd62a3c299b295dcdf470877cb948d655f2", + "sha256:4ce1e995aeecf7cc32380bc11598bfdfa017d592259d5da00fc7ded11e61d022", + "sha256:4f53e4128c81ca3212ff4cf097c797ab44646a40b42ec02a891155cd7a2ba4d8", + "sha256:4fa72a52a906425416f41738728268072d5acfd48cbe7796af07a923236bcf96", + "sha256:66dd45eb9530e3dde8f7c009f84568bc7cac489b93d04ac86e3111fb46e470c2", + "sha256:6923d077d9ae9e8bacbdb1c07ae78405a9306c8fd1af13bfa06ca891095eb995", + "sha256:833401b15de1bb92791d7b6fb353d4af60dc688eaa521bd97203dcd2d124a7c1", + "sha256:8416ed88ddc057bab0526d4e4e9f3660f614ac2394b5e019a628cdfff3733849", + "sha256:892daa86384994fdf4856cb43c93f40cbe80f7f95bb5da94971b39c7f54b3a9c", + "sha256:98be759efdb5e5fa161e46d404f4e0ce388e72fbf7d9baf010aff16689e22abe", + "sha256:a6d28e7f14ecf3b2ad67c4f106841218c8ab12a0683b1528534a6c87d2307af3", + "sha256:b1d6ebc891607e71fd9da71688fcf332a6630b7f5b7f5549e6e631821c0e5d90", + "sha256:b2a2b0d276a136146e012154baefaea2758ef1f56ae9f4e01c612b0831e0bd2f", + "sha256:b87dfa9f10a470eee7f24234a37d1d5f51e5f5fa9eeffda7c282e2b8f5162eb1", + "sha256:bac0d6f7728a9cc3c1e06d4fcbac12aaa70e9379b3025b27ec1226f0e2d404cf", + "sha256:c991112622baee0ae4d55c008380c32ecfd0ad417bcd0417ba432e6ba7328caa", + "sha256:cda422d54ee7905bfc53ee6915ab68fe7b230cacf581110df4272ee10462aadc", + "sha256:d3148b6ba3923c5850ea197a91a42683f946dba7e8eb82dfa211ab7e708de939", + "sha256:d6033b4ffa34ef70f0b8086fd4c3df4bf801fee485a8a7d4519399818351aa8e", + "sha256:ddff0b2bd7edcc8c82d1adde6dbbf5e60d57ce985402541cd2985c27f7bec2a0", + "sha256:e23cb7f1d8e0f93addf0cae3c5b6f00324cccb4a7949ee558d7b6ca973ab8ae9", + "sha256:effd2ba52cee4ceff1a77f20d2a9f9bf8d50353c854a282b8760ac15b9833168", + "sha256:f90c2267101010de42f7273c94a1f026e56cbc043f9330acd8a80e64300aba33", + "sha256:f960375e9823ae6a07072ff7f8a85954e5a6434f97869f50d0e41649a1c8144f", + "sha256:fcf32bf76dc25e30ed793145a57426064520890d7c02866eb93d3e4abe516948" + ], + "index": "pypi", + "version": "==1.14.1" }, "cfgv": { "hashes": [ @@ -1017,43 +1017,43 @@ }, "coverage": { "hashes": [ - "sha256:0fc4e0d91350d6f43ef6a61f64a48e917637e1dcfcba4b4b7d543c628ef82c2d", - "sha256:10f2a618a6e75adf64329f828a6a5b40244c1c50f5ef4ce4109e904e69c71bd2", - "sha256:12eaccd86d9a373aea59869bc9cfa0ab6ba8b1477752110cb4c10d165474f703", - "sha256:1874bdc943654ba46d28f179c1846f5710eda3aeb265ff029e0ac2b52daae404", - "sha256:1dcebae667b73fd4aa69237e6afb39abc2f27520f2358590c1b13dd90e32abe7", - "sha256:1e58fca3d9ec1a423f1b7f2aa34af4f733cbfa9020c8fe39ca451b6071237405", - "sha256:214eb2110217f2636a9329bc766507ab71a3a06a8ea30cdeebb47c24dce5972d", - "sha256:25fe74b5b2f1b4abb11e103bb7984daca8f8292683957d0738cd692f6a7cc64c", - "sha256:32ecee61a43be509b91a526819717d5e5650e009a8d5eda8631a59c721d5f3b6", - "sha256:3740b796015b889e46c260ff18b84683fa2e30f0f75a171fb10d2bf9fb91fc70", - "sha256:3b2c34690f613525672697910894b60d15800ac7e779fbd0fccf532486c1ba40", - "sha256:41d88736c42f4a22c494c32cc48a05828236e37c991bd9760f8923415e3169e4", - "sha256:42fa45a29f1059eda4d3c7b509589cc0343cd6bbf083d6118216830cd1a51613", - "sha256:4bb385a747e6ae8a65290b3df60d6c8a692a5599dc66c9fa3520e667886f2e10", - "sha256:509294f3e76d3f26b35083973fbc952e01e1727656d979b11182f273f08aa80b", - "sha256:5c74c5b6045969b07c9fb36b665c9cac84d6c174a809fc1b21bdc06c7836d9a0", - "sha256:60a3d36297b65c7f78329b80120f72947140f45b5c7a017ea730f9112b40f2ec", - "sha256:6f91b4492c5cde83bfe462f5b2b997cdf96a138f7c58b1140f05de5751623cf1", - "sha256:7403675df5e27745571aba1c957c7da2dacb537c21e14007ec3a417bf31f7f3d", - "sha256:87bdc8135b8ee739840eee19b184804e5d57f518578ffc797f5afa2c3c297913", - "sha256:8a3decd12e7934d0254939e2bf434bf04a5890c5bf91a982685021786a08087e", - "sha256:9702e2cb1c6dec01fb8e1a64c015817c0800a6eca287552c47a5ee0ebddccf62", - "sha256:a4d511012beb967a39580ba7d2549edf1e6865a33e5fe51e4dce550522b3ac0e", - "sha256:bbb387811f7a18bdc61a2ea3d102be0c7e239b0db9c83be7bfa50f095db5b92a", - "sha256:bfcc811883699ed49afc58b1ed9f80428a18eb9166422bce3c31a53dba00fd1d", - "sha256:c32aa13cc3fe86b0f744dfe35a7f879ee33ac0a560684fef0f3e1580352b818f", - "sha256:ca63dae130a2e788f2b249200f01d7fa240f24da0596501d387a50e57aa7075e", - "sha256:d54d7ea74cc00482a2410d63bf10aa34ebe1c49ac50779652106c867f9986d6b", - "sha256:d67599521dff98ec8c34cd9652cbcfe16ed076a2209625fca9dc7419b6370e5c", - "sha256:d82db1b9a92cb5c67661ca6616bdca6ff931deceebb98eecbd328812dab52032", - "sha256:d9ad0a988ae20face62520785ec3595a5e64f35a21762a57d115dae0b8fb894a", - "sha256:ebf2431b2d457ae5217f3a1179533c456f3272ded16f8ed0b32961a6d90e38ee", - "sha256:ed9a21502e9223f563e071759f769c3d6a2e1ba5328c31e86830368e8d78bc9c", - "sha256:f50632ef2d749f541ca8e6c07c9928a37f87505ce3a9f20c8446ad310f1aa87b" - ], - "index": "pypi", - "version": "==5.2" + "sha256:098a703d913be6fbd146a8c50cc76513d726b022d170e5e98dc56d958fd592fb", + "sha256:16042dc7f8e632e0dcd5206a5095ebd18cb1d005f4c89694f7f8aafd96dd43a3", + "sha256:1adb6be0dcef0cf9434619d3b892772fdb48e793300f9d762e480e043bd8e716", + "sha256:27ca5a2bc04d68f0776f2cdcb8bbd508bbe430a7bf9c02315cd05fb1d86d0034", + "sha256:28f42dc5172ebdc32622a2c3f7ead1b836cdbf253569ae5673f499e35db0bac3", + "sha256:2fcc8b58953d74d199a1a4d633df8146f0ac36c4e720b4a1997e9b6327af43a8", + "sha256:304fbe451698373dc6653772c72c5d5e883a4aadaf20343592a7abb2e643dae0", + "sha256:30bc103587e0d3df9e52cd9da1dd915265a22fad0b72afe54daf840c984b564f", + "sha256:40f70f81be4d34f8d491e55936904db5c527b0711b2a46513641a5729783c2e4", + "sha256:4186fc95c9febeab5681bc3248553d5ec8c2999b8424d4fc3a39c9cba5796962", + "sha256:46794c815e56f1431c66d81943fa90721bb858375fb36e5903697d5eef88627d", + "sha256:4869ab1c1ed33953bb2433ce7b894a28d724b7aa76c19b11e2878034a4e4680b", + "sha256:4f6428b55d2916a69f8d6453e48a505c07b2245653b0aa9f0dee38785939f5e4", + "sha256:52f185ffd3291196dc1aae506b42e178a592b0b60a8610b108e6ad892cfc1bb3", + "sha256:538f2fd5eb64366f37c97fdb3077d665fa946d2b6d95447622292f38407f9258", + "sha256:64c4f340338c68c463f1b56e3f2f0423f7b17ba6c3febae80b81f0e093077f59", + "sha256:675192fca634f0df69af3493a48224f211f8db4e84452b08d5fcebb9167adb01", + "sha256:700997b77cfab016533b3e7dbc03b71d33ee4df1d79f2463a318ca0263fc29dd", + "sha256:8505e614c983834239f865da2dd336dcf9d72776b951d5dfa5ac36b987726e1b", + "sha256:962c44070c281d86398aeb8f64e1bf37816a4dfc6f4c0f114756b14fc575621d", + "sha256:9e536783a5acee79a9b308be97d3952b662748c4037b6a24cbb339dc7ed8eb89", + "sha256:9ea749fd447ce7fb1ac71f7616371f04054d969d412d37611716721931e36efd", + "sha256:a34cb28e0747ea15e82d13e14de606747e9e484fb28d63c999483f5d5188e89b", + "sha256:a3ee9c793ffefe2944d3a2bd928a0e436cd0ac2d9e3723152d6fd5398838ce7d", + "sha256:aab75d99f3f2874733946a7648ce87a50019eb90baef931698f96b76b6769a46", + "sha256:b1ed2bdb27b4c9fc87058a1cb751c4df8752002143ed393899edb82b131e0546", + "sha256:b360d8fd88d2bad01cb953d81fd2edd4be539df7bfec41e8753fe9f4456a5082", + "sha256:b8f58c7db64d8f27078cbf2a4391af6aa4e4767cc08b37555c4ae064b8558d9b", + "sha256:c1bbb628ed5192124889b51204de27c575b3ffc05a5a91307e7640eff1d48da4", + "sha256:c2ff24df02a125b7b346c4c9078c8936da06964cc2d276292c357d64378158f8", + "sha256:c890728a93fffd0407d7d37c1e6083ff3f9f211c83b4316fae3778417eab9811", + "sha256:c96472b8ca5dc135fb0aa62f79b033f02aa434fb03a8b190600a5ae4102df1fd", + "sha256:ce7866f29d3025b5b34c2e944e66ebef0d92e4a4f2463f7266daa03a1332a651", + "sha256:e26c993bd4b220429d4ec8c1468eca445a4064a61c74ca08da7429af9bc53bb0" + ], + "index": "pypi", + "version": "==5.2.1" }, "cryptography": { "hashes": [ @@ -1125,13 +1125,6 @@ ], "version": "==0.3.1" }, - "dlib": { - "hashes": [ - "sha256:a3f5070df590c3f510dde2f4c84b1b20e3ef64a02932ed657da490834ecac7e4" - ], - "index": "pypi", - "version": "==19.20.0" - }, "docutils": { "hashes": [ "sha256:6c4f696463b79f1fb8ba0c594b63840ebd41f059e92b31957c46b74a4599b6d0", @@ -1249,11 +1242,11 @@ }, "google-auth": { "hashes": [ - "sha256:15b42d57d6c3d868d318e8273c06b2692fc5aad1bc45989a4f68f1fee05d41b2", - "sha256:f404448f3d3c91944b1d907427d4a0c48f465898e9dbacf1bdebf95c5fe03273" + "sha256:25c97cec5d4f6821f3ab67eb25b264fb00fda8fb9e2f05869bfa93dfcb8b50ee", + "sha256:c6e9735a2ee829a75b546702e460489db5cc35567a27fabd70b7c459f11efd58" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.19.2" + "version": "==1.20.0" }, "google-auth-oauthlib": { "hashes": [ @@ -1366,11 +1359,11 @@ }, "identify": { "hashes": [ - "sha256:06b4373546ae55eaaefdac54f006951dbd968fe2912846c00e565b09cfaed101", - "sha256:5519601b70c831011fb425ffd214101df7639ba3980f24dc283f7675b19127b3" + "sha256:110ed090fec6bce1aabe3c72d9258a9de82207adeaa5a05cd75c635880312f9a", + "sha256:ccd88716b890ecbe10920659450a635d2d25de499b9a638525a48b48261d989b" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.4.24" + "version": "==1.4.25" }, "idna": { "hashes": [ @@ -1390,11 +1383,11 @@ }, "ipykernel": { "hashes": [ - "sha256:09bac6473a593f61a3ae036035b81a2d30457ff157163562796560516a2f67d8", - "sha256:d718d5f717e0818329d371313f99aabba1bf4ca13f1e9f80cc3c5f866ee8a9ad" + "sha256:9b2652af1607986a1b231c62302d070bc0534f564c393a5d9d130db9abbbe89d", + "sha256:d6fbba26dba3cebd411382bc484f7bc2caa98427ae0ddb4ab37fe8bfeb5c7dd3" ], "index": "pypi", - "version": "==5.3.3" + "version": "==5.3.4" }, "ipython": { "hashes": [ @@ -1734,10 +1727,10 @@ }, "msrest": { "hashes": [ - "sha256:1345f73c178a7b445716590bc1346d44ac47c647ee83be57a48e2027d618f17c", - "sha256:c51ac6ce2d151b47dd4b3eed0fb8596b6e7c2067eff6bb82e874beaf7bfec531" + "sha256:4993023011663b4273f15432fab75cc747dfa0bca1816d8122a7d1f9fdd9288d", + "sha256:5f4ef9b8cc207d93978b1a58f055179686b9f30a5e28041872db97a4a1c49b96" ], - "version": "==0.6.17" + "version": "==0.6.18" }, "msrestazure": { "hashes": [ @@ -1836,35 +1829,35 @@ }, "numpy": { "hashes": [ - "sha256:13af0184177469192d80db9bd02619f6fa8b922f9f327e077d6f2a6acb1ce1c0", - "sha256:26a45798ca2a4e168d00de75d4a524abf5907949231512f372b217ede3429e98", - "sha256:26f509450db547e4dfa3ec739419b31edad646d21fb8d0ed0734188b35ff6b27", - "sha256:30a59fb41bb6b8c465ab50d60a1b298d1cd7b85274e71f38af5a75d6c475d2d2", - "sha256:33c623ef9ca5e19e05991f127c1be5aeb1ab5cdf30cb1c5cf3960752e58b599b", - "sha256:356f96c9fbec59974a592452ab6a036cd6f180822a60b529a975c9467fcd5f23", - "sha256:3c40c827d36c6d1c3cf413694d7dc843d50997ebffbc7c87d888a203ed6403a7", - "sha256:4d054f013a1983551254e2379385e359884e5af105e3efe00418977d02f634a7", - "sha256:63d971bb211ad3ca37b2adecdd5365f40f3b741a455beecba70fd0dde8b2a4cb", - "sha256:658624a11f6e1c252b2cd170d94bf28c8f9410acab9f2fd4369e11e1cd4e1aaf", - "sha256:76766cc80d6128750075378d3bb7812cf146415bd29b588616f72c943c00d598", - "sha256:7b57f26e5e6ee2f14f960db46bd58ffdca25ca06dd997729b1b179fddd35f5a3", - "sha256:7b852817800eb02e109ae4a9cef2beda8dd50d98b76b6cfb7b5c0099d27b52d4", - "sha256:8cde829f14bd38f6da7b2954be0f2837043e8b8d7a9110ec5e318ae6bf706610", - "sha256:a2e3a39f43f0ce95204beb8fe0831199542ccab1e0c6e486a0b4947256215632", - "sha256:a86c962e211f37edd61d6e11bb4df7eddc4a519a38a856e20a6498c319efa6b0", - "sha256:a8705c5073fe3fcc297fb8e0b31aa794e05af6a329e81b7ca4ffecab7f2b95ef", - "sha256:b6aaeadf1e4866ca0fdf7bb4eed25e521ae21a7947c59f78154b24fc7abbe1dd", - "sha256:be62aeff8f2f054eff7725f502f6228298891fd648dc2630e03e44bf63e8cee0", - "sha256:c2edbb783c841e36ca0fa159f0ae97a88ce8137fb3a6cd82eae77349ba4b607b", - "sha256:cbe326f6d364375a8e5a8ccb7e9cd73f4b2f6dc3b2ed205633a0db8243e2a96a", - "sha256:d34fbb98ad0d6b563b95de852a284074514331e6b9da0a9fc894fb1cdae7a79e", - "sha256:d97a86937cf9970453c3b62abb55a6475f173347b4cde7f8dcdb48c8e1b9952d", - "sha256:dd53d7c4a69e766e4900f29db5872f5824a06827d594427cf1a4aa542818b796", - "sha256:df1889701e2dfd8ba4dc9b1a010f0a60950077fb5242bb92c8b5c7f1a6f2668a", - "sha256:fa1fe75b4a9e18b66ae7f0b122543c42debcf800aaafa0212aaff3ad273c2596" - ], - "index": "pypi", - "version": "==1.19.0" + "sha256:082f8d4dd69b6b688f64f509b91d482362124986d98dc7dc5f5e9f9b9c3bb983", + "sha256:1bc0145999e8cb8aed9d4e65dd8b139adf1919e521177f198529687dbf613065", + "sha256:309cbcfaa103fc9a33ec16d2d62569d541b79f828c382556ff072442226d1968", + "sha256:3673c8b2b29077f1b7b3a848794f8e11f401ba0b71c49fbd26fb40b71788b132", + "sha256:480fdd4dbda4dd6b638d3863da3be82873bba6d32d1fc12ea1b8486ac7b8d129", + "sha256:56ef7f56470c24bb67fb43dae442e946a6ce172f97c69f8d067ff8550cf782ff", + "sha256:5a936fd51049541d86ccdeef2833cc89a18e4d3808fe58a8abeb802665c5af93", + "sha256:5b6885c12784a27e957294b60f97e8b5b4174c7504665333c5e94fbf41ae5d6a", + "sha256:667c07063940e934287993366ad5f56766bc009017b4a0fe91dbd07960d0aba7", + "sha256:7ed448ff4eaffeb01094959b19cbaf998ecdee9ef9932381420d514e446601cd", + "sha256:8343bf67c72e09cfabfab55ad4a43ce3f6bf6e6ced7acf70f45ded9ebb425055", + "sha256:92feb989b47f83ebef246adabc7ff3b9a59ac30601c3f6819f8913458610bdcc", + "sha256:935c27ae2760c21cd7354402546f6be21d3d0c806fffe967f745d5f2de5005a7", + "sha256:aaf42a04b472d12515debc621c31cf16c215e332242e7a9f56403d814c744624", + "sha256:b12e639378c741add21fbffd16ba5ad25c0a1a17cf2b6fe4288feeb65144f35b", + "sha256:b1cca51512299841bf69add3b75361779962f9cee7d9ee3bb446d5982e925b69", + "sha256:b8456987b637232602ceb4d663cb34106f7eb780e247d51a260b84760fd8f491", + "sha256:b9792b0ac0130b277536ab8944e7b754c69560dac0415dd4b2dbd16b902c8954", + "sha256:c9591886fc9cbe5532d5df85cb8e0cc3b44ba8ce4367bd4cf1b93dc19713da72", + "sha256:cf1347450c0b7644ea142712619533553f02ef23f92f781312f6a3553d031fc7", + "sha256:de8b4a9b56255797cbddb93281ed92acbc510fb7b15df3f01bd28f46ebc4edae", + "sha256:e1b1dc0372f530f26a03578ac75d5e51b3868b9b76cd2facba4c9ee0eb252ab1", + "sha256:e45f8e981a0ab47103181773cc0a54e650b2aef8c7b6cd07405d0fa8d869444a", + "sha256:e4f6d3c53911a9d103d8ec9518190e52a8b945bab021745af4939cfc7c0d4a9e", + "sha256:ed8a311493cf5480a2ebc597d1e177231984c818a86875126cfd004241a73c3e", + "sha256:ef71a1d4fd4858596ae80ad1ec76404ad29701f8ca7cdcebc50300178db14dfc" + ], + "index": "pypi", + "version": "==1.19.1" }, "oauthlib": { "hashes": [ @@ -1909,33 +1902,33 @@ }, "osmium": { "hashes": [ - "sha256:0d9cfeaad95c69c5d19036f2065514cf09705ebbcf2b941c05d2a39ebed82acd", - "sha256:1229bf453a20454ac0cd64f6fd72ba05560f6e1967d0c744fad28ae1f0789457", - "sha256:1b5af19fa354c8ab3425075db87d6a022aca2d83344b07acac5ab8be1a03c8d6", - "sha256:1eec17f65688aa8c093c626102dae49c901227e1043ec4894b1e1b718c8cc78c", - "sha256:2133fff59b7c8964f4d7cce44505c994d3a72203c056b2722ddbdce1c101444b", - "sha256:2c42280676c05267a264481c9c691cfb2cbb64c1ac40b38ec834568fae205aa6", - "sha256:2dade90a89a4afc2aba89fb3a6e160f660c577bc98f5765c6a4a7f8d7451019b", - "sha256:38feb096933ad93891b7268f1b0894eac0fdfb91bec638153ce43a74c05fe150", - "sha256:4744d5c36f566a617fdb5fa4955f124926c86ee61acf18c1d870ced71fde3f2c", - "sha256:50a6395a233a17af643c48a0a92bf6173a1eb84243dcaa9ed07f373a5e3bb941", - "sha256:512c3313cfcc1ccbaff0c7a5f618ff24d6dd7de9aceaa8c21c9cada232209708", - "sha256:516c71dcf343003f7910c54d902042dba228b3c55ae5875220d94216861b4fbe", - "sha256:65da41c65b40f3a86c34a24848fe015d94d6e2f202baaabf1aca345b166b8239", - "sha256:7fbcad84cbec60359110f517650a99bc79fc966daf509ecb69e070fa7ca223e7", - "sha256:8648692409fb88f6d545890e4fda6538ed74c366d9b722f5c54d9a7f154468f8", - "sha256:9cde2311893a3727472538b3029196ceee1a2c21965c9edfb15e5fc1c1b8d18d", - "sha256:a172ea24e69266be52f06bb8dc2c8670e36e2fd4e442e4227ec3de8110ed0152", - "sha256:a533f109ed17f298d094d50fc99bd16635163fc3efda9f6fa39bb6b387100f7b", - "sha256:aa65fcdb366a01aacdb049e12f53e73326372f2fbe8832af1e350652e6b20c07", - "sha256:aad4b3887e0744a1b8457b368df6319c013ee4e707e5b6bb799771b20328faa7", - "sha256:ab250ce243fd5507c36d3f93b8e01cef5cae42cddb80e2353b3fd1ea7f3d7478", - "sha256:b792ff0b1569507afec1f4beced42d3402bd3a082dc525d9f27289f1f329c3ae", - "sha256:bafbd0d57f4376cbab9c2901490fc021df2078cb8c89b8ffe250798e43d8bc82", - "sha256:cd4b8f484b99f11cfdf9c0da970282534e0cafcc6a3107879f06ebb41b9f64f9" - ], - "index": "pypi", - "version": "==3.0.0" + "sha256:04e2f3380525c9b100d7c9350e107ae0d75c378c4c36d17cc4999c5952b33960", + "sha256:0a5e9cccd9c376ab31fe79cdb1efcd1eb8175e7ff74a1f7ac218bd084d1a819d", + "sha256:32e0b94c9a6f24c3f86787a5e23d7289c00467a19d13ff2552feb2810d8b76c3", + "sha256:396557cc44f9655419060fb56623822b64af3f835df1f35ca0bb5aad2b5f33fe", + "sha256:44cd17932ef17c1c749ff5585a76e68b4615bfbe94828b7765bdebb39dfb2d85", + "sha256:6909a93173acd4111cc179bd7317e8a4e656c3b7b1a9041c5a5a8fcd01dbc3b5", + "sha256:7638dd47f667ab2f18e0092036851e4ead4a47fb5840ff138e20c02bd47d14d7", + "sha256:7c3782400d001229302bdffd6f410c460b270aef29a4a58c45fd479c897825b6", + "sha256:8451c8ebdb39b7f3d5bc038c0230f592d4dffa50ec6baef64ee8baa72e814e8a", + "sha256:84a7259ab1c2a37b399cfd53b82c402daf8df611ce9223dc443ccf3142b97223", + "sha256:8bf205bed661aa0ab7cb39f00981ced6b1f46d923c5aec246e89616b45f64dd2", + "sha256:97de71233b4741992008ca49e77c0a92999e9077cec9d6511759ba5d55faedde", + "sha256:a4a2a7c55696ad32f809dfb48f0eca1acffc6d447063d2062aaca6d6f9a26946", + "sha256:a60445b2122e159d7775d57f4958191ea5a32395b289c91156841ef04bdc2182", + "sha256:a8f4ecebe1d536ab7cdd02fa9f82ff745dd4aa8ed478ccf588f586b4c4af38a9", + "sha256:c3526f17eeb58eda0525888542ae14586745b0faaaf00dca2ccf2d376b75899f", + "sha256:c85c2bc37b118b93dc8eb6c141bf415eff34c35084613be29ced3b969b49c7f6", + "sha256:ce18818b7260113fcedb54e3167da0e9a07723a92f23a594318086d8c09645df", + "sha256:cf78640c5cd9b8e76ee37b5c0522c5130469d3db26ffdfd54e8fb751477787f5", + "sha256:d5da39de1c00d0c0ef8771df29424abb8bdc3fe093641c1df7448f0a22266f28", + "sha256:e25a2f8f495ff7d96c1c3a4c636ea5aa5176b58d5323350f913b30a6a1b67159", + "sha256:ede6fed48da8512415a4a895c2ded2777dacddfacc1b342f7938aa4271c97bd1", + "sha256:f247a74c6a02016c7f3749f5fc6fad3abaa5c7874ae2be9516ef1649dc276792", + "sha256:fe43969f2fb021051c2c202c28bd42bd7453f3f41d5d2499126b16437bb52f63" + ], + "index": "pypi", + "version": "==3.0.1" }, "packaging": { "hashes": [ @@ -1947,25 +1940,25 @@ }, "pandas": { "hashes": [ - "sha256:02f1e8f71cd994ed7fcb9a35b6ddddeb4314822a0e09a9c5b2d278f8cb5d4096", - "sha256:13f75fb18486759da3ff40f5345d9dd20e7d78f2a39c5884d013456cec9876f0", - "sha256:35b670b0abcfed7cad76f2834041dcf7ae47fd9b22b63622d67cdc933d79f453", - "sha256:4c73f373b0800eb3062ffd13d4a7a2a6d522792fa6eb204d67a4fad0a40f03dc", - "sha256:5759edf0b686b6f25a5d4a447ea588983a33afc8a0081a0954184a4a87fd0dd7", - "sha256:5a7cf6044467c1356b2b49ef69e50bf4d231e773c3ca0558807cdba56b76820b", - "sha256:69c5d920a0b2a9838e677f78f4dde506b95ea8e4d30da25859db6469ded84fa8", - "sha256:8778a5cc5a8437a561e3276b85367412e10ae9fff07db1eed986e427d9a674f8", - "sha256:9871ef5ee17f388f1cb35f76dc6106d40cb8165c562d573470672f4cdefa59ef", - "sha256:9c31d52f1a7dd2bb4681d9f62646c7aa554f19e8e9addc17e8b1b20011d7522d", - "sha256:ab8173a8efe5418bbe50e43f321994ac6673afc5c7c4839014cf6401bbdd0705", - "sha256:ae961f1f0e270f1e4e2273f6a539b2ea33248e0e3a11ffb479d757918a5e03a9", - "sha256:b3c4f93fcb6e97d993bf87cdd917883b7dab7d20c627699f360a8fb49e9e0b91", - "sha256:c9410ce8a3dee77653bc0684cfa1535a7f9c291663bd7ad79e39f5ab58f67ab3", - "sha256:f69e0f7b7c09f1f612b1f8f59e2df72faa8a6b41c5a436dde5b615aaf948f107", - "sha256:faa42a78d1350b02a7d2f0dbe3c80791cf785663d6997891549d0f86dc49125e" + "sha256:0210f8fe19c2667a3817adb6de2c4fd92b1b78e1975ca60c0efa908e0985cbdb", + "sha256:0227e3a6e3a22c0e283a5041f1e3064d78fbde811217668bb966ed05386d8a7e", + "sha256:0bc440493cf9dc5b36d5d46bbd5508f6547ba68b02a28234cd8e81fdce42744d", + "sha256:16504f915f1ae424052f1e9b7cd2d01786f098fbb00fa4e0f69d42b22952d798", + "sha256:182a5aeae319df391c3df4740bb17d5300dcd78034b17732c12e62e6dd79e4a4", + "sha256:35db623487f00d9392d8af44a24516d6cb9f274afaf73cfcfe180b9c54e007d2", + "sha256:40ec0a7f611a3d00d3c666c4cceb9aa3f5bf9fbd81392948a93663064f527203", + "sha256:47a03bfef80d6812c91ed6fae43f04f2fa80a4e1b82b35aa4d9002e39529e0b8", + "sha256:4b21d46728f8a6be537716035b445e7ef3a75dbd30bd31aa1b251323219d853e", + "sha256:4d1a806252001c5db7caecbe1a26e49a6c23421d85a700960f6ba093112f54a1", + "sha256:60e20a4ab4d4fec253557d0fc9a4e4095c37b664f78c72af24860c8adcd07088", + "sha256:9f61cca5262840ff46ef857d4f5f65679b82188709d0e5e086a9123791f721c8", + "sha256:a15835c8409d5edc50b4af93be3377b5dd3eb53517e7f785060df1f06f6da0e2", + "sha256:b39508562ad0bb3f384b0db24da7d68a2608b9ddc85b1d931ccaaa92d5e45273", + "sha256:ed60848caadeacecefd0b1de81b91beff23960032cded0ac1449242b506a3b3f", + "sha256:fc714895b6de6803ac9f661abb316853d0cd657f5d23985222255ad76ccedc25" ], "markers": "python_version >= '3.6.1'", - "version": "==1.0.5" + "version": "==1.1.0" }, "pandocfilters": { "hashes": [ @@ -1991,11 +1984,11 @@ }, "parso": { "hashes": [ - "sha256:158c140fc04112dc45bca311633ae5033c2c2a7b732fa33d0955bad8152a8dd0", - "sha256:908e9fae2144a076d72ae4e25539143d40b8e3eafbaeae03c1bfe226f4cdf12c" + "sha256:97218d9159b2520ff45eb78028ba8b50d2bc61dcc062a9682666f2dc4bd331ea", + "sha256:caba44724b994a8a5e086460bb212abc5a8bc46951bf4a9a1210745953622eb9" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==0.7.0" + "version": "==0.7.1" }, "pexpect": { "hashes": [ @@ -2586,7 +2579,7 @@ "sha256:109ea5a66744dd859bf16fe904b8d8b627adafb9408753161e766a92e7d681fa", "sha256:6166864e23d6b5195a5cfed6cd9fed0fe774e226d8f854fcb23b7bbef0350233" ], - "markers": "python_version >= '3'", + "markers": "python_version >= '3.5'", "version": "==4.6" }, "s2sphere": { @@ -2809,10 +2802,10 @@ }, "tensorboard": { "hashes": [ - "sha256:a3feb73e1221c0a512398ad2cd08570fb082d8a2ba364aa0562543ecbd3659ef" + "sha256:d34609ed83ff01dd5b49ef81031cfc9c166bba0dabd60197024f14df5e8eae5e" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==2.2.2" + "version": "==2.3.0" }, "tensorboard-plugin-wit": { "hashes": [ @@ -2822,27 +2815,27 @@ }, "tensorflow": { "hashes": [ - "sha256:267017724a49c367ca5df536e5f6d3d59643eaed946c82233d6b371e62b5ddc8", - "sha256:3ee8819732d8594913b7d22ded7b22e48a49aa015050d8dd8464eaa010ba2e41", - "sha256:572f69d2d0a3d3d83ebfb2c24e6d73d88b85a09f5da796974ef4a0ad83ff7cde", - "sha256:6735486ee9c3cb0807476e2b36ef7a4cd6c597cb24abf496e66b703360e1e54e", - "sha256:68ea22aee9c269a6a0c1061c141f1ec1cd1b1be7569390519c1bf4773f434a40", - "sha256:784ab8217e4b0eb4d121c28430c6cdc2ce56c02634a9720d84fb30598b338b8c", - "sha256:7ed67b47cdf6598a79583de5b57c595493eac2b8b6b3a828f912354716cb8149", - "sha256:8f364528f70d895b96a0de36c7c6002644bf4c5df1ee3fbfa775f5cee6571ad7", - "sha256:bbcfb04738099bd46822db91584db74703fdddacf4cd0a76acfc5e086956b5ba", - "sha256:c332c7fc5cfd54cb86d5da99787c9693e3a924848097c54df1b71ee595a39c93", - "sha256:dc5548562308acde7931f040e73d46ae31b398924cf675c3486fd3504e00a4af", - "sha256:f5f27528570fc0d7b90668be10c5dfd90d6ceb8fd2ed62d7d679554acb616bfe" + "sha256:0cfb0fbe875408cdbfc7677f12aa0b23656f3e6d8c5f568b3100450ec29262a7", + "sha256:2d9994157d6a222d9ffd956e99af4b5e46e47338428d2d197e325362283ec835", + "sha256:36a4ce9bbc9865385c1bb606fe34f0da96b0496ce3997e652d2b765a4382fe48", + "sha256:44c8d979b2d19ed56dbe6b03aef87616d6138a58fd80c43e7a758c90105e9adf", + "sha256:5c9f9a36d5b4d0ceb67b985486fe4cc6999a96e2bf89f3ba82ffd8317e5efadd", + "sha256:6f74ef59dc59cf8f2002738c65dffa591e2c332e9b1b4ced33ff8d39b6fb477c", + "sha256:797d6ca09d4f69570458180b7813dc12efe9166ba60454b0df7bed531bb5e4f4", + "sha256:92430b6e91f00f38a602c4f547bbbaca598a3a90376f90d5b2acd24bc18fa1d7", + "sha256:b1699903cf3a9f41c379d79ada2279a206a071b7e05671646d7b5e7fc37e2eae", + "sha256:bc9d761a857839344930eef86f0d6409840b1c9ada9cbe56b92287b2077ef752", + "sha256:c33a423eb1f39c4c6acc44c044a138979868f0d4c91e380c191bd8fddc7c2e9b", + "sha256:c6fad4e944e20199e963e158fe626352e349865ea4ca71655f5456193a6d3b9d" ], "index": "pypi", - "version": "==2.2.0" + "version": "==2.3.0" }, "tensorflow-estimator": { "hashes": [ - "sha256:d09dacdd127f2579cea8d5af21f4a918036b8ae246adc82f26b61f91cc247dc2" + "sha256:b75e034300ccb169403cf2695adf3368da68863aeb0c14c3760064c713d5c486" ], - "version": "==2.2.0" + "version": "==2.3.0" }, "termcolor": { "hashes": [ @@ -2867,11 +2860,11 @@ }, "tifffile": { "hashes": [ - "sha256:5bcad7e2e1d88c7923da662bf85ca2a1302ceaea04198d4ca696e0f7e7908576", - "sha256:9664322ba8d685905c43bf247c03b5c31fe1e9d7dc9b5b099ec6c52bab482151" + "sha256:73cd17d8df01fed38b9000c9b209eb7c894fde5abc616c5ff7b1f476e38cf07f", + "sha256:cd8549d6f0742c3c95a856744a26064a1aad1c132fbab95dc9e5dce891a62c17" ], "markers": "python_version >= '3.6'", - "version": "==2020.7.17" + "version": "==2020.7.24" }, "toml": { "hashes": [ @@ -2938,19 +2931,19 @@ }, "urllib3": { "hashes": [ - "sha256:3018294ebefce6572a474f0604c2021e33b3fd8006ecd11d62107a5d2a963527", - "sha256:88206b0eb87e6d677d424843ac5209e3fb9d0190d0ee169599165ec25e9d9115" + "sha256:91056c15fa70756691db97756772bb1eb9678fa585d9184f24534b100dc60f4a", + "sha256:e7983572181f5e1522d9c98453462384ee92a0be7fac5f1413a1e35c56cc0461" ], "index": "pypi", - "version": "==1.25.9" + "version": "==1.25.10" }, "virtualenv": { "hashes": [ - "sha256:26cdd725a57fef4c7c22060dba4647ebd8ca377e30d1c1cf547b30a0b79c43b4", - "sha256:c51f1ba727d1614ce8fd62457748b469fbedfdab2c7e5dd480c9ae3fbe1233f1" + "sha256:688a61d7976d82b92f7906c367e83bb4b3f0af96f8f75bfcd3da95608fe8ac6c", + "sha256:8f582a030156282a9ee9d319984b759a232b07f86048c1d6a9e394afa44e78c8" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==20.0.27" + "version": "==20.0.28" }, "wcwidth": { "hashes": [ @@ -2997,26 +2990,26 @@ }, "yarl": { "hashes": [ - "sha256:0c2ab325d33f1b824734b3ef51d4d54a54e0e7a23d13b86974507602334c2cce", - "sha256:0ca2f395591bbd85ddd50a82eb1fde9c1066fafe888c5c7cc1d810cf03fd3cc6", - "sha256:2098a4b4b9d75ee352807a95cdf5f10180db903bc5b7270715c6bbe2551f64ce", - "sha256:25e66e5e2007c7a39541ca13b559cd8ebc2ad8fe00ea94a2aad28a9b1e44e5ae", - "sha256:26d7c90cb04dee1665282a5d1a998defc1a9e012fdca0f33396f81508f49696d", - "sha256:308b98b0c8cd1dfef1a0311dc5e38ae8f9b58349226aa0533f15a16717ad702f", - "sha256:3ce3d4f7c6b69c4e4f0704b32eca8123b9c58ae91af740481aa57d7857b5e41b", - "sha256:58cd9c469eced558cd81aa3f484b2924e8897049e06889e8ff2510435b7ef74b", - "sha256:5b10eb0e7f044cf0b035112446b26a3a2946bca9d7d7edb5e54a2ad2f6652abb", - "sha256:6faa19d3824c21bcbfdfce5171e193c8b4ddafdf0ac3f129ccf0cdfcb083e462", - "sha256:944494be42fa630134bf907714d40207e646fd5a94423c90d5b514f7b0713fea", - "sha256:a161de7e50224e8e3de6e184707476b5a989037dcb24292b391a3d66ff158e70", - "sha256:a4844ebb2be14768f7994f2017f70aca39d658a96c786211be5ddbe1c68794c1", - "sha256:c2b509ac3d4b988ae8769901c66345425e361d518aecbe4acbfc2567e416626a", - "sha256:c9959d49a77b0e07559e579f38b2f3711c2b8716b8410b320bf9713013215a1b", - "sha256:d8cdee92bc930d8b09d8bd2043cedd544d9c8bd7436a77678dd602467a993080", - "sha256:e15199cdb423316e15f108f51249e44eb156ae5dba232cb73be555324a1d49c2" + "sha256:1707230e1ea48ea06a3e20acb4ce05a38d2465bd9566c21f48f6212a88e47536", + "sha256:1f269e8e6676193a94635399a77c9059e1826fb6265c9204c9e5a8ccd36006e1", + "sha256:2657716c1fc998f5f2675c0ee6ce91282e0da0ea9e4a94b584bb1917e11c1559", + "sha256:431faa6858f0ea323714d8b7b4a7da1db2eeb9403607f0eaa3800ab2c5a4b627", + "sha256:5bbcb195da7de57f4508b7508c33f7593e9516e27732d08b9aad8586c7b8c384", + "sha256:5c82f5b1499342339f22c83b97dbe2b8a09e47163fab86cd934a8dd46620e0fb", + "sha256:5d410f69b4f92c5e1e2a8ffb73337cd8a274388c6975091735795588a538e605", + "sha256:66b4f345e9573e004b1af184bc00431145cf5e089a4dcc1351505c1f5750192c", + "sha256:875b2a741ce0208f3b818008a859ab5d0f461e98a32bbdc6af82231a9e761c55", + "sha256:9a3266b047d15e78bba38c8455bf68b391c040231ca5965ef867f7cbbc60bde5", + "sha256:9a592c4aa642249e9bdaf76897d90feeb08118626b363a6be8788a9b300274b5", + "sha256:a1772068401d425e803999dada29a6babf041786e08be5e79ef63c9ecc4c9575", + "sha256:b065a5c3e050395ae563019253cc6c769a50fd82d7fa92d07476273521d56b7c", + "sha256:b325fefd574ebef50e391a1072d1712a60348ca29c183e1d546c9d87fec2cd32", + "sha256:cf5eb664910d759bbae0b76d060d6e21f8af5098242d66c448bbebaf2a7bfa70", + "sha256:f058b6541477022c7b54db37229f87dacf3b565de4f901ff5a0a78556a174fea", + "sha256:f5cfed0766837303f688196aa7002730d62c5cc802d98c6395ea1feb87252727" ], "markers": "python_version >= '3.5'", - "version": "==1.4.2" + "version": "==1.5.0" } } } From c1f8de9c9a2c45b14656b5d9d848409a512fbf8c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 29 Jul 2020 11:35:18 -0700 Subject: [PATCH 533/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 4b576ab13d..caf8670cff 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 4b576ab13d5cc5182d7540fe0a719f3408fab0d1 +Subproject commit caf8670cffdcbefafc4e6bb2fb61a4b8e81d64dd From 4658df7a668fc5565d2f4665523586ffdc8a5373 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 30 Jul 2020 15:28:58 -0700 Subject: [PATCH 534/656] add locationd, paramsd, dmonitoringd to CPU usage script --- selfdrive/debug/cpu_usage_stat.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index a890af9e67..28cabe6c8c 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -31,7 +31,7 @@ SLEEP_INTERVAL = 0.2 monitored_proc_names = [ 'ubloxd', 'thermald', 'uploader', 'deleter', 'controlsd', 'plannerd', 'radard', 'mapd', 'loggerd', 'logmessaged', 'tombstoned', - 'logcatd', 'proclogd', 'boardd', 'pandad', './ui', 'ui', 'calibrationd', 'params_learner', 'modeld', 'dmonitoringmodeld', 'camerad', 'sensord', 'updated', 'gpsd', 'athena'] + 'logcatd', 'proclogd', 'boardd', 'pandad', './ui', 'ui', 'calibrationd', 'params_learner', 'modeld', 'dmonitoringd', 'dmonitoringmodeld', 'camerad', 'sensord', 'updated', 'gpsd', 'athena', 'locationd', 'paramsd'] cpu_time_names = ['user', 'system', 'children_user', 'children_system'] timer = getattr(time, 'monotonic', time.time) From 8e2d344135b9a1102503432d651e6bf599d9fa42 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 30 Jul 2020 15:33:22 -0700 Subject: [PATCH 535/656] Misc locationd improvements (#1714) * I like this more * rewind less * bump rednose * falling off windshield detectopr * adjust thresholds * this is a soft disable now * move that * process replay fixes * update refs Co-authored-by: Comma Device Co-authored-by: Adeeb Shihadeh --- rednose_repo | 2 +- selfdrive/controls/lib/events.py | 14 ++--- selfdrive/locationd/locationd.py | 51 +++++++++++-------- selfdrive/locationd/models/live_kf.py | 2 +- selfdrive/test/process_replay/compare_logs.py | 14 ++--- selfdrive/test/process_replay/ref_commit | 2 +- .../test/process_replay/test_processes.py | 6 ++- 7 files changed, 49 insertions(+), 42 deletions(-) diff --git a/rednose_repo b/rednose_repo index 307c771fca..2e556b8219 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit 307c771fcaa5e301ccb18d3ab9fdedddd675c569 +Subproject commit 2e556b8219185708ed974a4b6502796607d7ce0d diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index bb7ce16566..eb943c1acc 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -530,15 +530,6 @@ EVENTS = { duration_hud_alert=0.), }, - EventName.posenetInvalid: { - ET.WARNING: Alert( - "TAKE CONTROL", - "Vision Model Output Uncertain", - AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimeWarning1, .4, 2., 3.), - ET.NO_ENTRY: NoEntryAlert("Vision Model Output Uncertain"), - }, - EventName.focusRecoverActive: { ET.WARNING: Alert( "TAKE CONTROL", @@ -659,6 +650,11 @@ EVENTS = { ET.NO_ENTRY : NoEntryAlert("Driving model lagging"), }, + EventName.posenetInvalid: { + ET.SOFT_DISABLE: SoftDisableAlert("Vision Model Output Uncertain"), + ET.NO_ENTRY: NoEntryAlert("Vision Model Output Uncertain"), + }, + EventName.lowMemory: { ET.SOFT_DISABLE: SoftDisableAlert("Low Memory: Reboot Your Device"), ET.PERMANENT: Alert( diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 3a5d515538..283d14732a 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -1,7 +1,6 @@ #!/usr/bin/env python3 import numpy as np import sympy as sp - import cereal.messaging as messaging import common.transformations.coordinates as coord from common.transformations.orientation import ecef_euler_from_ned, \ @@ -23,6 +22,7 @@ from rednose.helpers.sympy_helpers import euler_rotate VISION_DECIMATION = 2 SENSOR_DECIMATION = 10 +POSENET_STD_HIST = 40 def to_float(arr): @@ -52,7 +52,7 @@ class Localizer(): self.kf = LiveKalman(GENERATED_DIR) self.reset_kalman() - self.max_age = .2 # seconds + self.max_age = .1 # seconds self.disabled_logs = disabled_logs self.calib = np.zeros(3) self.device_from_calib = np.eye(3) @@ -63,6 +63,7 @@ class Localizer(): self.posenet_invalid_count = 0 self.posenet_speed = 0 self.car_speed = 0 + self.posenet_stds = 10*np.ones((POSENET_STD_HIST)) self.converter = coord.LocalCoord.from_ecef(self.kf.x[States.ECEF_POS]) @@ -113,8 +114,8 @@ class Localizer(): fix = messaging.log.LiveLocationKalman.new_message() fix.positionGeodetic.value = to_float(fix_pos_geo) - #fix.positionGeodetic.std = to_float(fix_pos_geo_std) - #fix.positionGeodetic.valid = True + fix.positionGeodetic.std = to_float(np.nan*np.zeros(3)) + fix.positionGeodetic.valid = True fix.positionECEF.value = to_float(fix_ecef) fix.positionECEF.std = to_float(fix_ecef_std) fix.positionECEF.valid = True @@ -122,8 +123,8 @@ class Localizer(): fix.velocityECEF.std = to_float(vel_ecef_std) fix.velocityECEF.valid = True fix.velocityNED.value = to_float(ned_vel) - #fix.velocityNED.std = to_float(ned_vel_std) - #fix.velocityNED.valid = True + fix.velocityNED.std = to_float(np.nan*np.zeros(3)) + fix.velocityNED.valid = True fix.velocityDevice.value = to_float(vel_device) fix.velocityDevice.std = to_float(vel_device_std) fix.velocityDevice.valid = True @@ -135,11 +136,11 @@ class Localizer(): fix.orientationECEF.std = to_float(orientation_ecef_std) fix.orientationECEF.valid = True fix.calibratedOrientationECEF.value = to_float(calibrated_orientation_ecef) - #fix.calibratedOrientationECEF.std = to_float(calibrated_orientation_ecef_std) - #fix.calibratedOrientationECEF.valid = True + fix.calibratedOrientationECEF.std = to_float(np.nan*np.zeros(3)) + fix.calibratedOrientationECEF.valid = True fix.orientationNED.value = to_float(orientation_ned) - #fix.orientationNED.std = to_float(orientation_ned_std) - #fix.orientationNED.valid = True + fix.orientationNED.std = to_float(np.nan*np.zeros(3)) + fix.orientationNED.valid = True fix.angularVelocityDevice.value = to_float(predicted_state[States.ANGULAR_VELOCITY]) fix.angularVelocityDevice.std = to_float(predicted_std[States.ANGULAR_VELOCITY_ERR]) fix.angularVelocityDevice.valid = True @@ -155,14 +156,23 @@ class Localizer(): fix.accelerationCalibrated.valid = True return fix - def liveLocationMsg(self, time): + def liveLocationMsg(self): fix = self.msg_from_state(self.converter, self.calib_from_device, self.H, self.kf.x, self.kf.P) - if abs(self.posenet_speed - self.car_speed) > max(0.4 * self.car_speed, 5.0): - self.posenet_invalid_count += 1 + #if abs(self.posenet_speed - self.car_speed) > max(0.4 * self.car_speed, 5.0): + # self.posenet_invalid_count += 1 + #else: + # self.posenet_invalid_count = 0 + #fix.posenetOK = self.posenet_invalid_count < 4 + + # experimentally found these values + old_mean, new_mean = np.mean(self.posenet_stds[:POSENET_STD_HIST//2]), np.mean(self.posenet_stds[POSENET_STD_HIST//2:]) + std_spike = new_mean/old_mean > 4 and new_mean > 5 + + if std_spike and self.car_speed > 5: + fix.posenetOK = False else: - self.posenet_invalid_count = 0 - fix.posenetOK = self.posenet_invalid_count < 4 + fix.posenetOK = True #fix.gpsWeek = self.time.week #fix.gpsTimeOfWeek = self.time.tow @@ -178,15 +188,10 @@ class Localizer(): def update_kalman(self, time, kind, meas, R=None): try: - self.kf.predict_and_observe(time, kind, meas, R=R) + self.kf.predict_and_observe(time, kind, meas, R) except KalmanError: cloudlog.error("Error in predict and observe, kalman reset") self.reset_kalman() - #idx = bisect_right([x[0] for x in self.observation_buffer], time) - #self.observation_buffer.insert(idx, (time, kind, meas)) - #while len(self.observation_buffer) > 0 and self.observation_buffer[-1][0] - self.observation_buffer[0][0] > self.max_age: - # else: - # self.observation_buffer.pop(0) def handle_gps(self, current_time, log): # ignore the message if the fix is invalid @@ -244,6 +249,8 @@ class Localizer(): trans_device = self.device_from_calib.dot(log.trans) trans_device_std = self.device_from_calib.dot(log.transStd) self.posenet_speed = np.linalg.norm(trans_device) + self.posenet_stds[:-1] = self.posenet_stds[1:] + self.posenet_stds[-1] = trans_device_std[0] self.update_kalman(current_time, ObservationKind.CAMERA_ODO_TRANSLATION, np.concatenate([trans_device, 10*trans_device_std])) @@ -322,7 +329,7 @@ def locationd_thread(sm, pm, disabled_logs=None): msg = messaging.new_message('liveLocationKalman') msg.logMonoTime = t - msg.liveLocationKalman = localizer.liveLocationMsg(t * 1e-9) + msg.liveLocationKalman = localizer.liveLocationMsg() msg.liveLocationKalman.inputsOK = sm.all_alive_and_valid() msg.liveLocationKalman.sensorsOK = sm.alive['sensorEvents'] and sm.valid['sensorEvents'] diff --git a/selfdrive/locationd/models/live_kf.py b/selfdrive/locationd/models/live_kf.py index a6a6eaf0b1..d2153487b2 100755 --- a/selfdrive/locationd/models/live_kf.py +++ b/selfdrive/locationd/models/live_kf.py @@ -206,7 +206,7 @@ class LiveKalman(): ObservationKind.ECEF_ORIENTATION_FROM_GPS: np.diag([.2**2, .2**2, .2**2, .2**2])} # init filter - self.filter = EKF_sym(generated_dir, self.name, self.Q, self.initial_x, np.diag(self.initial_P_diag), self.dim_state, self.dim_state_err) + self.filter = EKF_sym(generated_dir, self.name, self.Q, self.initial_x, np.diag(self.initial_P_diag), self.dim_state, self.dim_state_err, max_rewind_age=0.2) @property def x(self): diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py index 4845575238..8cb4b2453f 100755 --- a/selfdrive/test/process_replay/compare_logs.py +++ b/selfdrive/test/process_replay/compare_logs.py @@ -55,11 +55,12 @@ def remove_ignored_fields(msg, ignore): def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=None): if ignore_fields is None: ignore_fields = [] - if ignore_msgs is None: ignore_msgs = [] + log1, log2 = [list(filter(lambda m: m.which() not in ignore_msgs, log)) for log in (log1, log2)] - assert len(log1) == len(log2), "logs are not same length: " + str(len(log1)) + " VS " + str(len(log2)) + if len(log1) != len(log2): + raise Exception(f"logs are not same length: {len(log1)} VS {len(log2)}") diff = [] for msg1, msg2 in tqdm(zip(log1, log2)): @@ -77,11 +78,12 @@ def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=Non tolerance = EPSILON if tolerance is None else tolerance dd = dictdiffer.diff(msg1_dict, msg2_dict, ignore=ignore_fields) - # Dictiffer only supports relative tolerance, we also want to check for absolute + # Dictdiffer only supports relative tolerance, we also want to check for absolute def outside_tolerance(diff): - a, b = diff[2] - if isinstance(a, numbers.Number) and isinstance(b, numbers.Number): - return abs(a - b) > max(tolerance, tolerance * max(abs(a), abs(b))) + if diff[0] == "change": + a, b = diff[2] + if isinstance(a, numbers.Number) and isinstance(b, numbers.Number): + return abs(a - b) > max(tolerance, tolerance * max(abs(a), abs(b))) return True dd = list(filter(outside_tolerance, dd)) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 0c8b6156f5..479987e9fa 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -f3261f36402ad9bc3003feb9de61a04a634f30e1 \ No newline at end of file +d8944d6eb13c30c2fd5bcc1af5dbad07472c42c0 \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 8156269a8a..73939b0d97 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -71,8 +71,10 @@ def test_process(cfg, lr, cmp_log_fn, ignore_fields=None, ignore_msgs=None): segment = cmp_log_fn.split("/")[-1].split("_")[0] raise Exception("Route never enabled: %s" % segment) - return compare_logs(cmp_log_msgs, log_msgs, ignore_fields+cfg.ignore, ignore_msgs, cfg.tolerance) - + try: + return compare_logs(cmp_log_msgs, log_msgs, ignore_fields+cfg.ignore, ignore_msgs, cfg.tolerance) + except Exception as e: + return str(e) def format_diff(results, ref_commit): diff1, diff2 = "", "" From 1d7f4bc3b19d38464513c377511836221f77a95a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 30 Jul 2020 18:24:07 -0700 Subject: [PATCH 536/656] fix locationd profiling --- selfdrive/test/profiling/lib.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/test/profiling/lib.py b/selfdrive/test/profiling/lib.py index 997b48f673..017b9a2588 100644 --- a/selfdrive/test/profiling/lib.py +++ b/selfdrive/test/profiling/lib.py @@ -37,6 +37,7 @@ class PubSocket(): class SubMaster(messaging.SubMaster): def __init__(self, msgs, trigger, services): # pylint: disable=super-init-not-called + msgs = [m for m in msgs if m.which() in services] self.max_i = len(msgs) - 1 self.i = 0 self.frame = 0 From 0a01d88139dd35cd4d979dbac78e2f0ff69a7664 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Fri, 31 Jul 2020 13:11:59 -0700 Subject: [PATCH 537/656] dont init sound --- common/window.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/window.py b/common/window.py index fada132b81..62f8cb9e0b 100644 --- a/common/window.py +++ b/common/window.py @@ -6,7 +6,7 @@ class Window(): def __init__(self, w, h, caption="window", double=False): self.w = w self.h = h - pygame.init() + pygame.display.init() pygame.display.set_caption(caption) self.double = double if self.double: From 80acb328252d8ed80c18a98457c6d788073ed26e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 31 Jul 2020 23:14:31 +0200 Subject: [PATCH 538/656] Panda abstraction layer in boardd (#1919) * start on panda abstraction layer * handle bulk transfer in library * Safety model abstraction * Abstract hw type into library * Handle disconnect * RTC stuff * Fan control * Health * Panda fw version * Read serial * Power saving * Power mode * Cleanup pigeon thread init * Rename safety setter variable name * Remove comment * Unused global cleanup * malloc -> new * whitespace * Use std::thread * Use std::thread for safety setter * Cleanup igntion_last global * Heartbeat * logd * More global cleanup * Put back sleep * ir pwr * Always broadcast health * init struct with zeroes * Fix eon build * fix race condition * fix Adeebs comments * abstract can send and receive --- release/files_common | 2 + selfdrive/boardd/SConscript | 3 +- selfdrive/boardd/boardd.cc | 837 ++++++------------ selfdrive/boardd/panda.cc | 314 +++++++ selfdrive/boardd/panda.h | 78 ++ .../boardd/tests/test_boardd_loopback.py | 3 +- 6 files changed, 657 insertions(+), 580 deletions(-) create mode 100644 selfdrive/boardd/panda.cc create mode 100644 selfdrive/boardd/panda.h diff --git a/release/files_common b/release/files_common index 01d743c482..8f926ac3c3 100644 --- a/release/files_common +++ b/release/files_common @@ -88,6 +88,8 @@ selfdrive/boardd/boardd.py selfdrive/boardd/boardd_api_impl.pyx selfdrive/boardd/boardd_setup.py selfdrive/boardd/can_list_to_can_capnp.cc +selfdrive/boardd/panda.cc +selfdrive/boardd/panda.h selfdrive/car/__init__.py selfdrive/car/car_helpers.py diff --git a/selfdrive/boardd/SConscript b/selfdrive/boardd/SConscript index b29b886369..0ccbe6bd24 100644 --- a/selfdrive/boardd/SConscript +++ b/selfdrive/boardd/SConscript @@ -1,9 +1,8 @@ Import('env', 'common', 'cereal', 'messaging', 'cython_dependencies') -env.Program('boardd.cc', LIBS=['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj']) +env.Program('boardd', ['boardd.cc', 'panda.cc'], LIBS=['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj']) env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) env.Command(['boardd_api_impl.so', 'boardd_api_impl.cpp'], cython_dependencies + ['libcan_list_to_can_capnp.a', 'boardd_api_impl.pyx', 'boardd_setup.py'], "cd selfdrive/boardd && python3 boardd_setup.py build_ext --inplace") - diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 58f994e050..df865db27a 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -1,5 +1,4 @@ #include -#include #include #include #include @@ -8,11 +7,15 @@ #include #include #include -#include #include -#include -#include +#include +#include +#include +#include +#include +#include +#include #include @@ -24,12 +27,8 @@ #include "common/timing.h" #include "messaging.hpp" -#include -#include +#include "panda.h" -// double the FIFO size -#define RECV_SIZE (0x1000) -#define TIMEOUT 0 #define MAX_IR_POWER 0.5f #define MIN_IR_POWER 0.0f @@ -38,85 +37,47 @@ #define NIBBLE_TO_HEX(n) ((n) < 10 ? (n) + '0' : ((n) - 10) + 'a') #define VOLTAGE_K 0.091 // LPF gain for 5s tau (dt/tau / (dt/tau + 1)) -namespace { - -volatile sig_atomic_t do_exit = 0; - -struct __attribute__((packed)) timestamp_t { - uint16_t year; - uint8_t month; - uint8_t day; - uint8_t weekday; - uint8_t hour; - uint8_t minute; - uint8_t second; -}; - -libusb_context *ctx = NULL; -libusb_device_handle *dev_handle = NULL; -pthread_mutex_t usb_lock; - -bool spoofing_started = false; -bool fake_send = false; -bool loopback_can = false; -cereal::HealthData::HwType hw_type = cereal::HealthData::HwType::UNKNOWN; -bool is_pigeon = false; -float voltage_f = 12.5; // filtered voltage -uint32_t no_ignition_cnt = 0; -bool connected_once = false; -bool ignition_last = false; - #ifndef __x86_64__ const uint32_t NO_IGNITION_CNT_MAX = 2 * 60 * 60 * 30; // turn off charge after 30 hrs const float VBATT_START_CHARGING = 11.5; const float VBATT_PAUSE_CHARGING = 11.0; #endif -bool safety_setter_thread_initialized = false; -pthread_t safety_setter_thread_handle; - -bool pigeon_thread_initialized = false; -pthread_t pigeon_thread_handle; - -bool pigeon_needs_init; +namespace { -int usb_write(libusb_device_handle* dev_handle, uint8_t bRequest, uint16_t wValue, uint16_t wIndex, pthread_mutex_t *lock=NULL, unsigned int timeout=TIMEOUT) { - const uint8_t bmRequestType = LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; +Panda * panda = NULL; +std::atomic safety_setter_thread_running(false); +volatile sig_atomic_t do_exit = 0; +bool spoofing_started = false; +bool fake_send = false; +bool connected_once = false; - if (lock) pthread_mutex_lock(lock); - int err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, NULL, 0, timeout); - if (lock) pthread_mutex_unlock(lock); - return err; -} +struct tm get_time(){ + time_t rawtime; + time(&rawtime); -int usb_read(libusb_device_handle* dev_handle, uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned char *data, uint16_t wLength, pthread_mutex_t *lock=NULL, unsigned int timeout=TIMEOUT) { - const uint8_t bmRequestType = LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; + struct tm sys_time; + gmtime_r(&rawtime, &sys_time); - if (lock) pthread_mutex_lock(lock); - int err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, data, wLength, timeout); - if (lock) pthread_mutex_unlock(lock); - return err; + return sys_time; } -void usb_close(libusb_device_handle* &dev_handle) { - if (!dev_handle) { - return; - } - libusb_release_interface(dev_handle, 0); - libusb_close(dev_handle); - dev_handle = NULL; +bool time_valid(struct tm sys_time){ + return 1900 + sys_time.tm_year >= 2019; } -void pigeon_init(); -void *pigeon_thread(void *crap); - -void *safety_setter_thread(void *s) { +void safety_setter_thread() { + LOGD("Starting safety setter thread"); // diagnostic only is the default, needed for VIN query - usb_write(dev_handle, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::ELM327), 0, &usb_lock); + panda->set_safety_model(cereal::CarParams::SafetyModel::ELM327); // switch to SILENT when CarVin param is read while (1) { - if (do_exit) return NULL; + if (do_exit || !panda->connected){ + safety_setter_thread_running = false; + return; + }; + std::vector value_vin = read_db_bytes("CarVin"); if (value_vin.size() > 0) { // sanity check VIN format @@ -129,12 +90,15 @@ void *safety_setter_thread(void *s) { } // VIN query done, stop listening to OBDII - usb_write(dev_handle, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::NO_OUTPUT), 0, &usb_lock); + panda->set_safety_model(cereal::CarParams::SafetyModel::NO_OUTPUT); std::vector params; LOGW("waiting for params to set safety model"); while (1) { - if (do_exit) return NULL; + if (do_exit || !panda->connected){ + safety_setter_thread_running = false; + return; + }; params = read_db_bytes("CarParams"); if (params.size() > 0) break; @@ -148,444 +112,103 @@ void *safety_setter_thread(void *s) { capnp::FlatArrayMessageReader cmsg(amsg); cereal::CarParams::Reader car_params = cmsg.getRoot(); + cereal::CarParams::SafetyModel safety_model = car_params.getSafetyModel(); - int safety_model = int(car_params.getSafetyModel()); auto safety_param = car_params.getSafetyParam(); - LOGW("setting safety model: %d with param %d", safety_model, safety_param); - - pthread_mutex_lock(&usb_lock); - - // set in the mutex to avoid race - safety_setter_thread_initialized = false; + LOGW("setting safety model: %d with param %d", (int)safety_model, safety_param); - usb_write(dev_handle, 0xdc, safety_model, safety_param); + panda->set_safety_model(safety_model, safety_param); - pthread_mutex_unlock(&usb_lock); - - return NULL; + safety_setter_thread_running = false; } -// must be called before threads or with mutex bool usb_connect() { - int err, err2; - unsigned char hw_query[1] = {0}; - unsigned char fw_sig_buf[128]; - unsigned char fw_sig_hex_buf[16]; - unsigned char serial_buf[16]; - const char *serial; - int serial_sz = 0; - - ignition_last = false; - - usb_close(dev_handle); - - dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); - if (dev_handle == NULL) { goto fail; } - - err = libusb_set_configuration(dev_handle, 1); - if (err != 0) { goto fail; } - - err = libusb_claim_interface(dev_handle, 0); - if (err != 0) { goto fail; } + try { + assert(panda == NULL); + panda = new Panda(); + } catch (std::exception &e) { + return false; + } - if (loopback_can) { - usb_write(dev_handle, 0xe5, 1, 0); + if (getenv("BOARDD_LOOPBACK")) { + panda->set_loopback(true); } - // get panda fw - err = usb_read(dev_handle, 0xd3, 0, 0, fw_sig_buf, 64); - err2 = usb_read(dev_handle, 0xd4, 0, 0, fw_sig_buf + 64, 64); - if ((err == 64) && (err2 == 64)) { - printf("FW signature read\n"); - write_db_value("PandaFirmware", (const char *)fw_sig_buf, 128); + const char *fw_sig_buf = panda->get_firmware_version(); + if (fw_sig_buf){ + write_db_value("PandaFirmware", fw_sig_buf, 128); + // Convert to hex for offroad + char fw_sig_hex_buf[16] = {0}; for (size_t i = 0; i < 8; i++){ - fw_sig_hex_buf[2*i] = NIBBLE_TO_HEX(fw_sig_buf[i] >> 4); - fw_sig_hex_buf[2*i+1] = NIBBLE_TO_HEX(fw_sig_buf[i] & 0xF); + fw_sig_hex_buf[2*i] = NIBBLE_TO_HEX((uint8_t)fw_sig_buf[i] >> 4); + fw_sig_hex_buf[2*i+1] = NIBBLE_TO_HEX((uint8_t)fw_sig_buf[i] & 0xF); } - write_db_value("PandaFirmwareHex", (const char *)fw_sig_hex_buf, 16); - } - else { goto fail; } + + write_db_value("PandaFirmwareHex", fw_sig_hex_buf, 16); + LOGW("fw signature: %.*s", 16, fw_sig_hex_buf); + + delete[] fw_sig_buf; + } else { return false; } // get panda serial - err = usb_read(dev_handle, 0xd0, 0, 0, serial_buf, 16); + const char *serial_buf = panda->get_serial(); + if (serial_buf) { + size_t serial_sz = strnlen(serial_buf, 16); - if (err > 0) { - serial = (const char *)serial_buf; - serial_sz = strnlen(serial, err); - write_db_value("PandaDongleId", serial, serial_sz); - printf("panda serial: %.*s\n", serial_sz, serial); - } - else { goto fail; } + write_db_value("PandaDongleId", serial_buf, serial_sz); + LOGW("panda serial: %.*s", serial_sz, serial_buf); + + delete[] serial_buf; + } else { return false; } // power on charging, only the first time. Panda can also change mode and it causes a brief disconneciton #ifndef __x86_64__ if (!connected_once) { - usb_write(dev_handle, 0xe6, (uint16_t)(cereal::HealthData::UsbPowerMode::CDP), 0); + panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CDP); } #endif - connected_once = true; - - usb_read(dev_handle, 0xc1, 0, 0, hw_query, 1); - - hw_type = (cereal::HealthData::HwType)(hw_query[0]); - is_pigeon = (hw_type == cereal::HealthData::HwType::GREY_PANDA) || - (hw_type == cereal::HealthData::HwType::BLACK_PANDA) || - (hw_type == cereal::HealthData::HwType::UNO); - if (is_pigeon) { - LOGW("panda with gps detected"); - pigeon_needs_init = true; - if (!pigeon_thread_initialized) { - err = pthread_create(&pigeon_thread_handle, NULL, pigeon_thread, NULL); - assert(err == 0); - pigeon_thread_initialized = true; - } - } - - if (hw_type == cereal::HealthData::HwType::UNO){ - // Get time from system - time_t rawtime; - time(&rawtime); - struct tm sys_time; - gmtime_r(&rawtime, &sys_time); + if (panda->has_rtc){ + struct tm sys_time = get_time(); + struct tm rtc_time = panda->get_rtc(); - // Get time from RTC - timestamp_t rtc_time; - usb_read(dev_handle, 0xa0, 0, 0, (unsigned char*)&rtc_time, sizeof(rtc_time)); - - //printf("System: %d-%d-%d\t%d:%d:%d\n", 1900 + sys_time.tm_year, 1 + sys_time.tm_mon, sys_time.tm_mday, sys_time.tm_hour, sys_time.tm_min, sys_time.tm_sec); - //printf("RTC: %d-%d-%d\t%d:%d:%d\n", rtc_time.year, rtc_time.month, rtc_time.day, rtc_time.hour, rtc_time.minute, rtc_time.second); - - // Update system time from RTC if it looks off, and RTC time is good - if (1900 + sys_time.tm_year < 2019 && rtc_time.year >= 2019){ + if (!time_valid(sys_time) && time_valid(rtc_time)) { LOGE("System time wrong, setting from RTC"); - struct tm new_time = { 0 }; - new_time.tm_year = rtc_time.year - 1900; - new_time.tm_mon = rtc_time.month - 1; - new_time.tm_mday = rtc_time.day; - new_time.tm_hour = rtc_time.hour; - new_time.tm_min = rtc_time.minute; - new_time.tm_sec = rtc_time.second; - setenv("TZ","UTC",1); - const struct timeval tv = {mktime(&new_time), 0}; + const struct timeval tv = {mktime(&rtc_time), 0}; settimeofday(&tv, 0); } } + connected_once = true; return true; -fail: - return false; } // must be called before threads or with mutex void usb_retry_connect() { - LOG("attempting to connect"); + LOGW("attempting to connect"); while (!usb_connect()) { usleep(100*1000); } LOGW("connected to board"); } -void handle_usb_issue(int err, const char func[]) { - LOGE_100("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func); - if (err == LIBUSB_ERROR_NO_DEVICE) { - LOGE("lost connection"); - usb_retry_connect(); - } - // TODO: check other errors, is simply retrying okay? -} - void can_recv(PubMaster &pm) { - int err; - uint32_t data[RECV_SIZE/4]; - int recv; - uint64_t start_time = nanos_since_boot(); - // do recv - pthread_mutex_lock(&usb_lock); - - 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 == LIBUSB_ERROR_OVERFLOW) { LOGE_100("overflow got 0x%x", recv); }; - - // timeout is okay to exit, recv still happened - if (err == LIBUSB_ERROR_TIMEOUT) { break; } - } while(err != 0); - - pthread_mutex_unlock(&usb_lock); - - // return if length is 0 - if (recv <= 0) { - return; - } else if (recv == RECV_SIZE) { - LOGW("Receive buffer full"); - } - // create message capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); event.setLogMonoTime(start_time); - size_t num_msg = recv / 0x10; - auto canData = event.initCan(num_msg); - - // populate message - for (int i = 0; i < num_msg; i++) { - if (data[i*4] & 4) { - // extended - canData[i].setAddress(data[i*4] >> 3); - //printf("got extended: %x\n", data[i*4] >> 3); - } else { - // normal - canData[i].setAddress(data[i*4] >> 21); - } - canData[i].setBusTime(data[i*4+1] >> 16); - int len = data[i*4+1]&0xF; - canData[i].setDat(kj::arrayPtr((uint8_t*)&data[i*4+2], len)); - canData[i].setSrc((data[i*4+1] >> 4) & 0xff); - } - - pm.send("can", msg); -} -void can_health(PubMaster &pm) { - int cnt; - int err; - - // copied from panda/board/main.c - struct __attribute__((packed)) health { - uint32_t uptime; - uint32_t voltage; - uint32_t current; - uint32_t can_rx_errs; - uint32_t can_send_errs; - uint32_t can_fwd_errs; - uint32_t gmlan_send_errs; - uint32_t faults; - uint8_t ignition_line; - uint8_t ignition_can; - uint8_t controls_allowed; - uint8_t gas_interceptor_detected; - uint8_t car_harness_status; - uint8_t usb_power_mode; - uint8_t safety_model; - uint8_t fault_status; - uint8_t power_save_enabled; - } health; - - // create message - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto healthData = event.initHealth(); - - bool received = false; - - // recv from board - if (dev_handle != NULL) { - cnt = usb_read(dev_handle, 0xd2, 0, 0, (unsigned char*)&health, sizeof(health), &usb_lock); - received = (cnt == sizeof(health)); - } - - // No panda connected, send empty health packet - if (!received){ - healthData.setHwType(cereal::HealthData::HwType::UNKNOWN); - pm.send("health", msg); - return; - } - - if (spoofing_started) { - health.ignition_line = 1; - } - - voltage_f = VOLTAGE_K * (health.voltage / 1000.0) + (1.0 - VOLTAGE_K) * voltage_f; // LPF - - // Make sure CAN buses are live: safety_setter_thread does not work if Panda CAN are silent and there is only one other CAN node - if (health.safety_model == (uint8_t)(cereal::CarParams::SafetyModel::SILENT)) { - usb_write(dev_handle, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::NO_OUTPUT), 0, &usb_lock); - } - - bool ignition = ((health.ignition_line != 0) || (health.ignition_can != 0)); - - if (ignition) { - no_ignition_cnt = 0; - } else { - no_ignition_cnt += 1; - } - -#ifndef __x86_64__ - bool cdp_mode = health.usb_power_mode == (uint8_t)(cereal::HealthData::UsbPowerMode::CDP); - bool no_ignition_exp = no_ignition_cnt > NO_IGNITION_CNT_MAX; - if ((no_ignition_exp || (voltage_f < VBATT_PAUSE_CHARGING)) && cdp_mode && !ignition) { - std::vector disable_power_down = read_db_bytes("DisablePowerDown"); - if (disable_power_down.size() != 1 || disable_power_down[0] != '1') { - printf("TURN OFF CHARGING!\n"); - usb_write(dev_handle, 0xe6, (uint16_t)(cereal::HealthData::UsbPowerMode::CLIENT), 0, &usb_lock); - printf("POWER DOWN DEVICE\n"); - system("service call power 17 i32 0 i32 1"); - } - } - if (!no_ignition_exp && (voltage_f > VBATT_START_CHARGING) && !cdp_mode) { - printf("TURN ON CHARGING!\n"); - usb_write(dev_handle, 0xe6, (uint16_t)(cereal::HealthData::UsbPowerMode::CDP), 0, &usb_lock); - } - // set power save state enabled when car is off and viceversa when it's on - if (ignition && (health.power_save_enabled == 1)) { - usb_write(dev_handle, 0xe7, 0, 0, &usb_lock); - } - if (!ignition && (health.power_save_enabled == 0)) { - usb_write(dev_handle, 0xe7, 1, 0, &usb_lock); - } - // set safety mode to NO_OUTPUT when car is off. ELM327 is an alternative if we want to leverage athenad/connect - if (!ignition && (health.safety_model != (uint8_t)(cereal::CarParams::SafetyModel::NO_OUTPUT))) { - usb_write(dev_handle, 0xdc, (uint16_t)(cereal::CarParams::SafetyModel::NO_OUTPUT), 0, &usb_lock); + int recv = panda->can_receive(event); + if (recv){ + pm.send("can", msg); } -#endif - - // clear VIN, CarParams, and set new safety on car start - if (ignition && !ignition_last) { - int result = delete_db_value("CarVin"); - assert((result == 0) || (result == ERR_NO_VALUE)); - result = delete_db_value("CarParams"); - assert((result == 0) || (result == ERR_NO_VALUE)); - - if (!safety_setter_thread_initialized) { - err = pthread_create(&safety_setter_thread_handle, NULL, safety_setter_thread, NULL); - assert(err == 0); - safety_setter_thread_initialized = true; - } - } - - // Get fan RPM - uint16_t fan_speed_rpm = 0; - - usb_read(dev_handle, 0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm), &usb_lock); - - // Write to rtc once per minute when no ignition present - if ((hw_type == cereal::HealthData::HwType::UNO) && !ignition && (no_ignition_cnt % 120 == 1)){ - // Get time from system - time_t rawtime; - time(&rawtime); - - struct tm sys_time; - gmtime_r(&rawtime, &sys_time); - - // Write time to RTC if it looks reasonable - if (1900 + sys_time.tm_year >= 2019){ - pthread_mutex_lock(&usb_lock); - usb_write(dev_handle, 0xa1, (uint16_t)(1900 + sys_time.tm_year), 0); - usb_write(dev_handle, 0xa2, (uint16_t)(1 + sys_time.tm_mon), 0); - usb_write(dev_handle, 0xa3, (uint16_t)sys_time.tm_mday, 0); - // usb_write(dev_handle, 0xa4, (uint16_t)(1 + sys_time.tm_wday), 0); - usb_write(dev_handle, 0xa5, (uint16_t)sys_time.tm_hour, 0); - usb_write(dev_handle, 0xa6, (uint16_t)sys_time.tm_min, 0); - usb_write(dev_handle, 0xa7, (uint16_t)sys_time.tm_sec, 0); - pthread_mutex_unlock(&usb_lock); - } - } - - ignition_last = ignition; - - // set fields - healthData.setUptime(health.uptime); - healthData.setVoltage(health.voltage); - healthData.setCurrent(health.current); - healthData.setIgnitionLine(health.ignition_line); - healthData.setIgnitionCan(health.ignition_can); - healthData.setControlsAllowed(health.controls_allowed); - healthData.setGasInterceptorDetected(health.gas_interceptor_detected); - healthData.setHasGps(is_pigeon); - healthData.setCanRxErrs(health.can_rx_errs); - healthData.setCanSendErrs(health.can_send_errs); - healthData.setCanFwdErrs(health.can_fwd_errs); - healthData.setGmlanSendErrs(health.gmlan_send_errs); - healthData.setHwType(hw_type); - healthData.setUsbPowerMode(cereal::HealthData::UsbPowerMode(health.usb_power_mode)); - healthData.setSafetyModel(cereal::CarParams::SafetyModel(health.safety_model)); - healthData.setFanSpeedRpm(fan_speed_rpm); - healthData.setFaultStatus(cereal::HealthData::FaultStatus(health.fault_status)); - healthData.setPowerSaveEnabled((bool)(health.power_save_enabled)); - - // Convert faults bitset to capnp list - std::bitset fault_bits(health.faults); - auto faults = healthData.initFaults(fault_bits.count()); - - size_t i = 0; - for (size_t f = size_t(cereal::HealthData::FaultType::RELAY_MALFUNCTION); - f <= size_t(cereal::HealthData::FaultType::INTERRUPT_RATE_KLINE_INIT); f++){ - if (fault_bits.test(f)) { - faults.set(i, cereal::HealthData::FaultType(f)); - i++; - } - } - // send to health - pm.send("health", msg); - - // send heartbeat back to panda - usb_write(dev_handle, 0xf3, 1, 0, &usb_lock); } - -void can_send(cereal::Event::Reader &event) { - int err; - // recv from sendcan - if (nanos_since_boot() - event.getLogMonoTime() > 1e9) { - //Older than 1 second. Dont send. - return; - } - - auto can_data_list = event.getSendcan(); - int msg_count = can_data_list.size(); - - uint32_t *send = (uint32_t*)malloc(msg_count*0x10); - memset(send, 0, msg_count*0x10); - - for (int i = 0; i < msg_count; i++) { - auto cmsg = can_data_list[i]; - if (cmsg.getAddress() >= 0x800) { - // extended - send[i*4] = (cmsg.getAddress() << 3) | 5; - } else { - // normal - send[i*4] = (cmsg.getAddress() << 21) | 1; - } - auto can_data = cmsg.getDat(); - assert(can_data.size() <= 8); - send[i*4+1] = can_data.size() | (cmsg.getSrc() << 4); - memcpy(&send[i*4+2], can_data.begin(), can_data.size()); - } - - // send to board - int sent; - pthread_mutex_lock(&usb_lock); - - if (!fake_send) { - do { - // Try sending can messages. If the receive buffer on the panda is full it will NAK - // and libusb will try again. After 5ms, it will time out. We will drop the messages. - err = libusb_bulk_transfer(dev_handle, 3, (uint8_t*)send, msg_count*0x10, &sent, 5); - if (err == LIBUSB_ERROR_TIMEOUT) { - LOGW("Transmit buffer full"); - break; - } else if (err != 0 || msg_count*0x10 != sent) { - LOGW("Error"); - handle_usb_issue(err, __func__); - } - } while(err != 0); - } - - pthread_mutex_unlock(&usb_lock); - - // done - free(send); -} - -// **** threads **** - -void *can_send_thread(void *crap) { +void can_send_thread() { LOGD("start send thread"); Context * context = Context::create(); @@ -594,7 +217,7 @@ void *can_send_thread(void *crap) { subscriber->setTimeout(100); // run as fast as messages come in - while (!do_exit) { + while (!do_exit && panda->connected) { Message * msg = subscriber->receive(); if (!msg){ @@ -609,17 +232,22 @@ void *can_send_thread(void *crap) { capnp::FlatArrayMessageReader cmsg(amsg); cereal::Event::Reader event = cmsg.getRoot(); - can_send(event); + + //Dont send if older than 1 second + if (nanos_since_boot() - event.getLogMonoTime() < 1e9) { + if (!fake_send){ + panda->can_send(event.getSendcan()); + } + } + delete msg; } delete subscriber; delete context; - - return NULL; } -void *can_recv_thread(void *crap) { +void can_recv_thread() { LOGD("start recv thread"); // can = 8006 @@ -629,7 +257,7 @@ void *can_recv_thread(void *crap) { const uint64_t dt = 10000000ULL; uint64_t next_frame_time = nanos_since_boot() + dt; - while (!do_exit) { + while (!do_exit && panda->connected) { can_recv(pm); uint64_t cur_time = nanos_since_boot(); @@ -644,34 +272,157 @@ void *can_recv_thread(void *crap) { next_frame_time += dt; } - return NULL; } -void *can_health_thread(void *crap) { +void can_health_thread() { LOGD("start health thread"); - // health = 8011 PubMaster pm({"health"}); - // run at 2hz - while (!do_exit) { - can_health(pm); + uint32_t no_ignition_cnt = 0; + bool ignition_last = false; + float voltage_f = 12.5; // filtered voltage + + // Broadcast empty health message when panda is not yet connected + while (!panda){ + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto healthData = event.initHealth(); + + healthData.setHwType(cereal::HealthData::HwType::UNKNOWN); + pm.send("health", msg); usleep(500*1000); } - return NULL; + // run at 2hz + while (!do_exit && panda->connected) { + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto healthData = event.initHealth(); + + health_t health = panda->get_health(); + + if (spoofing_started) { + health.ignition_line = 1; + } + + voltage_f = VOLTAGE_K * (health.voltage / 1000.0) + (1.0 - VOLTAGE_K) * voltage_f; // LPF + + // Make sure CAN buses are live: safety_setter_thread does not work if Panda CAN are silent and there is only one other CAN node + if (health.safety_model == (uint8_t)(cereal::CarParams::SafetyModel::SILENT)) { + panda->set_safety_model(cereal::CarParams::SafetyModel::NO_OUTPUT); + } + + bool ignition = ((health.ignition_line != 0) || (health.ignition_can != 0)); + + if (ignition) { + no_ignition_cnt = 0; + } else { + no_ignition_cnt += 1; + } + +#ifdef QCOM + bool cdp_mode = health.usb_power_mode == (uint8_t)(cereal::HealthData::UsbPowerMode::CDP); + bool no_ignition_exp = no_ignition_cnt > NO_IGNITION_CNT_MAX; + if ((no_ignition_exp || (voltage_f < VBATT_PAUSE_CHARGING)) && cdp_mode && !ignition) { + std::vector disable_power_down = read_db_bytes("DisablePowerDown"); + if (disable_power_down.size() != 1 || disable_power_down[0] != '1') { + LOGW("TURN OFF CHARGING!\n"); + panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CLIENT); + LOGW("POWER DOWN DEVICE\n"); + system("service call power 17 i32 0 i32 1"); + } + } + if (!no_ignition_exp && (voltage_f > VBATT_START_CHARGING) && !cdp_mode) { + LOGW("TURN ON CHARGING!\n"); + panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CDP); + } +#endif + +#ifndef __x86_64__ + bool power_save_desired = !ignition; + if (health.power_save_enabled != power_save_desired){ + panda->set_power_saving(power_save_desired); + } + + // set safety mode to NO_OUTPUT when car is off. ELM327 is an alternative if we want to leverage athenad/connect + if (!ignition && (health.safety_model != (uint8_t)(cereal::CarParams::SafetyModel::NO_OUTPUT))) { + panda->set_safety_model(cereal::CarParams::SafetyModel::NO_OUTPUT); + } +#endif + + // clear VIN, CarParams, and set new safety on car start + if (ignition && !ignition_last) { + int result = delete_db_value("CarVin"); + assert((result == 0) || (result == ERR_NO_VALUE)); + result = delete_db_value("CarParams"); + assert((result == 0) || (result == ERR_NO_VALUE)); + + if (!safety_setter_thread_running) { + safety_setter_thread_running = true; + std::thread(safety_setter_thread).detach(); + } else { + LOGW("Safety setter thread already running"); + } + } + + // Write to rtc once per minute when no ignition present + if ((panda->has_rtc) && !ignition && (no_ignition_cnt % 120 == 1)){ + // Write time to RTC if it looks reasonable + struct tm sys_time = get_time(); + if (time_valid(sys_time)){ + panda->set_rtc(sys_time); + } + } + + ignition_last = ignition; + uint16_t fan_speed_rpm = panda->get_fan_speed(); + + // set fields + healthData.setUptime(health.uptime); + healthData.setVoltage(health.voltage); + healthData.setCurrent(health.current); + healthData.setIgnitionLine(health.ignition_line); + healthData.setIgnitionCan(health.ignition_can); + healthData.setControlsAllowed(health.controls_allowed); + healthData.setGasInterceptorDetected(health.gas_interceptor_detected); + healthData.setHasGps(panda->is_pigeon); + healthData.setCanRxErrs(health.can_rx_errs); + healthData.setCanSendErrs(health.can_send_errs); + healthData.setCanFwdErrs(health.can_fwd_errs); + healthData.setGmlanSendErrs(health.gmlan_send_errs); + healthData.setHwType(panda->hw_type); + healthData.setUsbPowerMode(cereal::HealthData::UsbPowerMode(health.usb_power_mode)); + healthData.setSafetyModel(cereal::CarParams::SafetyModel(health.safety_model)); + healthData.setFanSpeedRpm(fan_speed_rpm); + healthData.setFaultStatus(cereal::HealthData::FaultStatus(health.fault_status)); + healthData.setPowerSaveEnabled((bool)(health.power_save_enabled)); + + // Convert faults bitset to capnp list + std::bitset fault_bits(health.faults); + auto faults = healthData.initFaults(fault_bits.count()); + + size_t i = 0; + for (size_t f = size_t(cereal::HealthData::FaultType::RELAY_MALFUNCTION); + f <= size_t(cereal::HealthData::FaultType::INTERRUPT_RATE_KLINE_INIT); f++){ + if (fault_bits.test(f)) { + faults.set(i, cereal::HealthData::FaultType(f)); + i++; + } + } + pm.send("health", msg); + panda->send_heartbeat(); + usleep(500*1000); + } } -void *hardware_control_thread(void *crap) { +void hardware_control_thread() { LOGD("start hardware control thread"); SubMaster sm({"thermal", "frontFrame"}); - // Wait for hardware type to be set. - while (hw_type == cereal::HealthData::HwType::UNKNOWN){ - usleep(100*1000); - } // Only control fan speed on UNO - if (hw_type != cereal::HealthData::HwType::UNO) return NULL; - + if (panda->hw_type != cereal::HealthData::HwType::UNO) return; uint64_t last_front_frame_t = 0; uint16_t prev_fan_speed = 999; @@ -679,13 +430,14 @@ void *hardware_control_thread(void *crap) { uint16_t prev_ir_pwr = 999; unsigned int cnt = 0; - while (!do_exit) { + while (!do_exit && panda->connected) { cnt++; - sm.update(1000); + sm.update(1000); // TODO: what happens if EINTR is sent while in sm.update? + if (sm.updated("thermal")){ uint16_t fan_speed = sm["thermal"].getThermal().getFanSpeed(); if (fan_speed != prev_fan_speed || cnt % 100 == 0){ - usb_write(dev_handle, 0xb1, fan_speed, 0, &usb_lock); + panda->set_fan_speed(fan_speed); prev_fan_speed = fan_speed; } } @@ -709,59 +461,32 @@ void *hardware_control_thread(void *crap) { } if (ir_pwr != prev_ir_pwr || cnt % 100 == 0 || ir_pwr >= 50.0){ - usb_write(dev_handle, 0xb0, ir_pwr, 0, &usb_lock); + panda->set_ir_pwr(ir_pwr); prev_ir_pwr = ir_pwr; } } - - return NULL; } #define pigeon_send(x) _pigeon_send(x, sizeof(x)-1) - -void hexdump(unsigned char *d, int l) __attribute__((unused)); -void hexdump(unsigned char *d, int l) { - for (int i = 0; i < l; i++) { - if (i!=0 && i%0x10 == 0) printf("\n"); - printf("%2.2X ", d[i]); - } - printf("\n"); -} - void _pigeon_send(const char *dat, int len) { - int sent; unsigned char a[0x20+1]; - int err; a[0] = 1; for (int i=0; iusb_bulk_write(2, a, ll+1); } } void pigeon_set_power(int power) { - pthread_mutex_lock(&usb_lock); - int err = usb_write(dev_handle, 0xd9, power, 0); - if (err < 0) { handle_usb_issue(err, __func__); } - pthread_mutex_unlock(&usb_lock); + panda->usb_write(0xd9, power, 0); } void pigeon_set_baud(int baud) { - int err; - pthread_mutex_lock(&usb_lock); - err = usb_write(dev_handle, 0xe2, 1, 0); - if (err < 0) { handle_usb_issue(err, __func__); } - err = usb_write(dev_handle, 0xe4, 1, baud/300); - if (err < 0) { handle_usb_issue(err, __func__); } - pthread_mutex_unlock(&usb_lock); + panda->usb_write(0xe2, 1, 0); + panda->usb_write(0xe4, 1, baud/300); } void pigeon_init() { @@ -824,24 +549,22 @@ static void pigeon_publish_raw(PubMaster &pm, unsigned char *dat, int alen) { } -void *pigeon_thread(void *crap) { +void pigeon_thread() { + if (!panda->is_pigeon){ return; }; + // ubloxRaw = 8042 PubMaster pm({"ubloxRaw"}); // run at ~100hz unsigned char dat[0x1000]; uint64_t cnt = 0; - while (!do_exit) { - if (pigeon_needs_init) { - pigeon_needs_init = false; - pigeon_init(); - } + + pigeon_init(); + + while (!do_exit && panda->connected) { int alen = 0; while (alen < 0xfc0) { - pthread_mutex_lock(&usb_lock); - int len = usb_read(dev_handle, 0xe0, 1, 0, dat+alen, 0x40); - if (len < 0) { handle_usb_issue(len, __func__); } - pthread_mutex_unlock(&usb_lock); + int len = panda->usb_read(0xe0, 1, 0, dat+alen, 0x40); if (len <= 0) break; //printf("got %d\n", len); @@ -860,7 +583,6 @@ void *pigeon_thread(void *crap) { usleep(10*1000); cnt++; } - return NULL; } } @@ -884,60 +606,21 @@ int main() { fake_send = true; } - if (getenv("BOARDD_LOOPBACK")){ - loopback_can = true; - } + while (!do_exit){ + std::vector threads; + threads.push_back(std::thread(can_health_thread)); - err = pthread_mutex_init(&usb_lock, NULL); - assert(err == 0); + // connect to the board + usb_retry_connect(); - // init libusb - err = libusb_init(&ctx); - assert(err == 0); + threads.push_back(std::thread(can_send_thread)); + threads.push_back(std::thread(can_recv_thread)); + threads.push_back(std::thread(hardware_control_thread)); + threads.push_back(std::thread(pigeon_thread)); -#if LIBUSB_API_VERSION >= 0x01000106 - libusb_set_option(ctx, LIBUSB_OPTION_LOG_LEVEL, LIBUSB_LOG_LEVEL_INFO); -#else - libusb_set_debug(ctx, 3); -#endif + for (auto &t : threads) t.join(); - pthread_t can_health_thread_handle; - err = pthread_create(&can_health_thread_handle, NULL, - can_health_thread, NULL); - assert(err == 0); - - // connect to the board - pthread_mutex_lock(&usb_lock); - usb_retry_connect(); - pthread_mutex_unlock(&usb_lock); - - // create threads - pthread_t can_send_thread_handle; - err = pthread_create(&can_send_thread_handle, NULL, - can_send_thread, NULL); - assert(err == 0); - - pthread_t can_recv_thread_handle; - err = pthread_create(&can_recv_thread_handle, NULL, - can_recv_thread, NULL); - assert(err == 0); - - pthread_t hardware_control_thread_handle; - err = pthread_create(&hardware_control_thread_handle, NULL, - hardware_control_thread, NULL); - assert(err == 0); - - // join threads - err = pthread_join(can_recv_thread_handle, NULL); - assert(err == 0); - - err = pthread_join(can_send_thread_handle, NULL); - assert(err == 0); - - err = pthread_join(can_health_thread_handle, NULL); - assert(err == 0); - - // destruct libusb - usb_close(dev_handle); - libusb_exit(ctx); + delete panda; + panda = NULL; + } } diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc new file mode 100644 index 0000000000..8bec943457 --- /dev/null +++ b/selfdrive/boardd/panda.cc @@ -0,0 +1,314 @@ +#include +#include +#include + +#include "common/swaglog.h" + +#include "panda.h" + +Panda::Panda(){ + int err; + + err = pthread_mutex_init(&usb_lock, NULL); + if (err != 0) { goto fail; } + + // init libusb + err = libusb_init(&ctx); + if (err != 0) { goto fail; } + +#if LIBUSB_API_VERSION >= 0x01000106 + libusb_set_option(ctx, LIBUSB_OPTION_LOG_LEVEL, LIBUSB_LOG_LEVEL_INFO); +#else + libusb_set_debug(ctx, 3); +#endif + + dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); + if (dev_handle == NULL) { goto fail; } + + err = libusb_set_configuration(dev_handle, 1); + if (err != 0) { goto fail; } + + err = libusb_claim_interface(dev_handle, 0); + if (err != 0) { goto fail; } + + hw_type = get_hw_type(); + is_pigeon = + (hw_type == cereal::HealthData::HwType::GREY_PANDA) || + (hw_type == cereal::HealthData::HwType::BLACK_PANDA) || + (hw_type == cereal::HealthData::HwType::UNO); + has_rtc = (hw_type == cereal::HealthData::HwType::UNO); + + return; + +fail: + cleanup(); + throw std::runtime_error("Error connecting to panda"); +} + +Panda::~Panda(){ + pthread_mutex_lock(&usb_lock); + cleanup(); + connected = false; + pthread_mutex_unlock(&usb_lock); +} + +void Panda::cleanup(){ + if (dev_handle){ + libusb_release_interface(dev_handle, 0); + libusb_close(dev_handle); + } + + if (ctx) { + libusb_exit(ctx); + } +} + +void Panda::handle_usb_issue(int err, const char func[]) { + LOGE_100("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func); + if (err == LIBUSB_ERROR_NO_DEVICE) { + LOGE("lost connection"); + connected = false; + } + // TODO: check other errors, is simply retrying okay? +} + +int Panda::usb_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned int timeout) { + int err; + const uint8_t bmRequestType = LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; + + pthread_mutex_lock(&usb_lock); + do { + err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, NULL, 0, timeout); + if (err < 0) handle_usb_issue(err, __func__); + } while (err < 0 && connected); + + pthread_mutex_unlock(&usb_lock); + + return err; +} + +int Panda::usb_read(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned char *data, uint16_t wLength, unsigned int timeout) { + int err; + const uint8_t bmRequestType = LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; + + pthread_mutex_lock(&usb_lock); + do { + err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, data, wLength, timeout); + if (err < 0) handle_usb_issue(err, __func__); + } while (err < 0 && connected); + pthread_mutex_unlock(&usb_lock); + + return err; +} + +int Panda::usb_bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) { + int err; + int transferred = 0; + + pthread_mutex_lock(&usb_lock); + do { + // Try sending can messages. If the receive buffer on the panda is full it will NAK + // and libusb will try again. After 5ms, it will time out. We will drop the messages. + err = libusb_bulk_transfer(dev_handle, endpoint, data, length, &transferred, timeout); + + if (err == LIBUSB_ERROR_TIMEOUT) { + LOGW("Transmit buffer full"); + break; + } else if (err != 0 || length != transferred) { + handle_usb_issue(err, __func__); + } + } while(err != 0 && connected); + + pthread_mutex_unlock(&usb_lock); + return transferred; +} + +int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) { + int err; + int transferred = 0; + + pthread_mutex_lock(&usb_lock); + + do { + err = libusb_bulk_transfer(dev_handle, endpoint, data, length, &transferred, timeout); + + if (err == LIBUSB_ERROR_TIMEOUT) { + break; // timeout is okay to exit, recv still happened + } else if (err == LIBUSB_ERROR_OVERFLOW) { + LOGE_100("overflow got 0x%x", transferred); + } else if (err != 0) { + handle_usb_issue(err, __func__); + } + + } while(err != 0 && connected); + + pthread_mutex_unlock(&usb_lock); + + return transferred; +} + +void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, int safety_param){ + usb_write(0xdc, (uint16_t)safety_model, safety_param); +} + +cereal::HealthData::HwType Panda::get_hw_type() { + unsigned char hw_query[1] = {0}; + + usb_read(0xc1, 0, 0, hw_query, 1); + return (cereal::HealthData::HwType)(hw_query[0]); +} + +void Panda::set_rtc(struct tm sys_time){ + // tm struct has year defined as years since 1900 + usb_write(0xa1, (uint16_t)(1900 + sys_time.tm_year), 0); + usb_write(0xa2, (uint16_t)(1 + sys_time.tm_mon), 0); + usb_write(0xa3, (uint16_t)sys_time.tm_mday, 0); + // usb_write(0xa4, (uint16_t)(1 + sys_time.tm_wday), 0); + usb_write(0xa5, (uint16_t)sys_time.tm_hour, 0); + usb_write(0xa6, (uint16_t)sys_time.tm_min, 0); + usb_write(0xa7, (uint16_t)sys_time.tm_sec, 0); +} + +struct tm Panda::get_rtc(){ + struct __attribute__((packed)) timestamp_t { + uint16_t year; // Starts at 0 + uint8_t month; + uint8_t day; + uint8_t weekday; + uint8_t hour; + uint8_t minute; + uint8_t second; + } rtc_time = {0}; + + usb_read(0xa0, 0, 0, (unsigned char*)&rtc_time, sizeof(rtc_time)); + + struct tm new_time = { 0 }; + new_time.tm_year = rtc_time.year - 1900; // tm struct has year defined as years since 1900 + new_time.tm_mon = rtc_time.month - 1; + new_time.tm_mday = rtc_time.day; + new_time.tm_hour = rtc_time.hour; + new_time.tm_min = rtc_time.minute; + new_time.tm_sec = rtc_time.second; + + return new_time; +} + +void Panda::set_fan_speed(uint16_t fan_speed){ + usb_write(0xb1, fan_speed, 0); +} + +uint16_t Panda::get_fan_speed(){ + uint16_t fan_speed_rpm = 0; + usb_read(0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm)); + return fan_speed_rpm; +} + +void Panda::set_ir_pwr(uint16_t ir_pwr) { + usb_write(0xb0, ir_pwr, 0); +} + +health_t Panda::get_health(){ + health_t health {0}; + usb_read(0xd2, 0, 0, (unsigned char*)&health, sizeof(health)); + return health; +} + +void Panda::set_loopback(bool loopback){ + usb_write(0xe5, loopback, 0); +} + +const char* Panda::get_firmware_version(){ + const char* fw_sig_buf = new char[128](); + + int read_1 = usb_read(0xd3, 0, 0, (unsigned char*)fw_sig_buf, 64); + int read_2 = usb_read(0xd4, 0, 0, (unsigned char*)fw_sig_buf + 64, 64); + + if ((read_1 == 64) && (read_2 == 64)) { + return fw_sig_buf; + } + + delete[] fw_sig_buf; + return NULL; +} + +const char* Panda::get_serial(){ + const char* serial_buf = new char[16](); + + int err = usb_read(0xd0, 0, 0, (unsigned char*)serial_buf, 16); + + if (err >= 0) { + return serial_buf; + } + + delete[] serial_buf; + return NULL; + +} + +void Panda::set_power_saving(bool power_saving){ + usb_write(0xe7, power_saving, 0); +} + +void Panda::set_usb_power_mode(cereal::HealthData::UsbPowerMode power_mode){ + usb_write(0xe6, (uint16_t)power_mode, 0); +} + +void Panda::send_heartbeat(){ + usb_write(0xf3, 1, 0); +} + +void Panda::can_send(capnp::List::Reader can_data_list){ + int msg_count = can_data_list.size(); + + uint32_t *send = new uint32_t[msg_count*0x10](); + + for (int i = 0; i < msg_count; i++) { + auto cmsg = can_data_list[i]; + if (cmsg.getAddress() >= 0x800) { // extended + send[i*4] = (cmsg.getAddress() << 3) | 5; + } else { // normal + send[i*4] = (cmsg.getAddress() << 21) | 1; + } + auto can_data = cmsg.getDat(); + assert(can_data.size() <= 8); + send[i*4+1] = can_data.size() | (cmsg.getSrc() << 4); + memcpy(&send[i*4+2], can_data.begin(), can_data.size()); + } + + usb_bulk_write(3, (unsigned char*)send, msg_count*0x10, 5); + + delete[] send; +} + +int Panda::can_receive(cereal::Event::Builder &event){ + uint32_t data[RECV_SIZE/4]; + int recv = usb_bulk_read(0x81, (unsigned char*)data, RECV_SIZE); + + // return if length is 0 + if (recv <= 0) { + return 0; + } else if (recv == RECV_SIZE) { + LOGW("Receive buffer full"); + } + + size_t num_msg = recv / 0x10; + auto canData = event.initCan(num_msg); + + // populate message + for (int i = 0; i < num_msg; i++) { + if (data[i*4] & 4) { + // extended + canData[i].setAddress(data[i*4] >> 3); + //printf("got extended: %x\n", data[i*4] >> 3); + } else { + // normal + canData[i].setAddress(data[i*4] >> 21); + } + canData[i].setBusTime(data[i*4+1] >> 16); + int len = data[i*4+1]&0xF; + canData[i].setDat(kj::arrayPtr((uint8_t*)&data[i*4+2], len)); + canData[i].setSrc((data[i*4+1] >> 4) & 0xff); + } + + return recv; +} diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h new file mode 100644 index 0000000000..3586cda74f --- /dev/null +++ b/selfdrive/boardd/panda.h @@ -0,0 +1,78 @@ +#pragma once + +#include +#include +#include + +#include + +#include "cereal/gen/cpp/car.capnp.h" +#include "cereal/gen/cpp/log.capnp.h" + +// double the FIFO size +#define RECV_SIZE (0x1000) +#define TIMEOUT 0 + +// copied from panda/board/main.c +struct __attribute__((packed)) health_t { + uint32_t uptime; + uint32_t voltage; + uint32_t current; + uint32_t can_rx_errs; + uint32_t can_send_errs; + uint32_t can_fwd_errs; + uint32_t gmlan_send_errs; + uint32_t faults; + uint8_t ignition_line; + uint8_t ignition_can; + uint8_t controls_allowed; + uint8_t gas_interceptor_detected; + uint8_t car_harness_status; + uint8_t usb_power_mode; + uint8_t safety_model; + uint8_t fault_status; + uint8_t power_save_enabled; +}; + +class Panda { + private: + libusb_context *ctx = NULL; + libusb_device_handle *dev_handle = NULL; + pthread_mutex_t usb_lock; + void handle_usb_issue(int err, const char func[]); + void cleanup(); + + public: + Panda(); + ~Panda(); + + bool connected = true; + cereal::HealthData::HwType hw_type = cereal::HealthData::HwType::UNKNOWN; + bool is_pigeon = false; + bool has_rtc = false; + + // HW communication + int usb_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned int timeout=TIMEOUT); + int usb_read(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned char *data, uint16_t wLength, unsigned int timeout=TIMEOUT); + int usb_bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT); + int usb_bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT); + + // Panda functionality + cereal::HealthData::HwType get_hw_type(); + void set_safety_model(cereal::CarParams::SafetyModel safety_model, int safety_param=0); + void set_rtc(struct tm sys_time); + struct tm get_rtc(); + void set_fan_speed(uint16_t fan_speed); + uint16_t get_fan_speed(); + void set_ir_pwr(uint16_t ir_pwr); + health_t get_health(); + void set_loopback(bool loopback); + const char* get_firmware_version(); + const char* get_serial(); + void set_power_saving(bool power_saving); + void set_usb_power_mode(cereal::HealthData::UsbPowerMode power_mode); + void send_heartbeat(); + void can_send(capnp::List::Reader can_data_list); + int can_receive(cereal::Event::Builder &event); + +}; diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py index 8081984b30..d6c110bbbe 100755 --- a/selfdrive/boardd/tests/test_boardd_loopback.py +++ b/selfdrive/boardd/tests/test_boardd_loopback.py @@ -8,6 +8,7 @@ from functools import wraps import cereal.messaging as messaging from cereal import car from common.basedir import PARAMS +from common.android import ANDROID from common.params import Params from common.spinner import Spinner from panda import Panda @@ -35,7 +36,7 @@ os.environ['PARAMS_PATH'] = PARAMS @with_processes(['boardd']) def test_boardd_loopback(): # wait for boardd to init - spinner = Spinner() + spinner = Spinner(noop=(not ANDROID)) time.sleep(2) # boardd blocks on CarVin and CarParams From f80acad519d5edb8dc7bbcf881490f6f2e0f72fc Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 2 Aug 2020 02:01:43 +0800 Subject: [PATCH 539/656] modeld: read frame_id if sm.update(0)>0 (#1947) * read frameid if sm.update(0)>0 * move postion same line --- selfdrive/modeld/modeld.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index ebfed713c2..f367c99097 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -181,7 +181,7 @@ int main(int argc, char **argv) { cl_mem yuv_cl; VisionBuf yuv_ion = visionbuf_allocate_cl(buf_info.buf_len, device_id, context, &yuv_cl); - uint32_t last_vipc_frame_id = 0; + uint32_t frame_id = 0, last_vipc_frame_id = 0; double last = 0; int desire = -1; while (!do_exit) { @@ -202,6 +202,7 @@ int main(int argc, char **argv) { if (sm.update(0) > 0){ // TODO: path planner timeout? desire = ((int)sm["pathPlan"].getPathPlan().getDesire()) - 1; + frame_id = sm["frame"].getFrame().getFrameId(); } double mt1 = 0, mt2 = 0; @@ -212,8 +213,7 @@ int main(int argc, char **argv) { } mat3 model_transform = matmul3(yuv_transform, transform); - uint32_t frame_id = sm["frame"].getFrame().getFrameId(); - + mt1 = millis_since_boot(); // TODO: don't make copies! From a7ee2a53a8a832f3678171403471380a9a72b9cb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 1 Aug 2020 17:26:35 -0700 Subject: [PATCH 540/656] Driver view refactor (#1869) * quick driver view cleanup * send at correct freq * let manager handle that * don't block starting on driver view * fix UI hacks * ui cleanup * move driver view functionality into dmonitoringd * dmonitoring thresholds shouldnt be in UI * remove driver view file from release files * timeout on frontview * bump cereal --- cereal | 2 +- release/files_common | 1 - selfdrive/manager.py | 26 ++++++--- selfdrive/monitoring/dmonitoringd.py | 37 +++++++------ selfdrive/monitoring/driverview.py | 81 ---------------------------- selfdrive/ui/paint.cc | 25 ++++----- selfdrive/ui/ui.cc | 15 ++++-- selfdrive/ui/ui.hpp | 2 +- 8 files changed, 57 insertions(+), 132 deletions(-) delete mode 100755 selfdrive/monitoring/driverview.py diff --git a/cereal b/cereal index 430cc73a3b..10a25c8b98 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 430cc73a3b7c31de902bd0a62fbac7cd3a05cf3e +Subproject commit 10a25c8b98ad295308e6825cef7cf42dff6f4396 diff --git a/release/files_common b/release/files_common index 8f926ac3c3..a4417b3767 100644 --- a/release/files_common +++ b/release/files_common @@ -385,7 +385,6 @@ selfdrive/modeld/runners/run.h selfdrive/monitoring/dmonitoringd.py selfdrive/monitoring/driver_monitor.py -selfdrive/monitoring/driverview.py selfdrive/assets selfdrive/assets/fonts/*.ttf diff --git a/selfdrive/manager.py b/selfdrive/manager.py index e415dff50f..62d4827ca7 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -189,7 +189,6 @@ managed_processes = { "updated": "selfdrive.updated", "dmonitoringmodeld": ("selfdrive/modeld", ["./dmonitoringmodeld"]), "modeld": ("selfdrive/modeld", ["./modeld"]), - "driverview": "selfdrive.monitoring.driverview", } daemon_processes = { @@ -242,6 +241,12 @@ car_started_processes = [ 'locationd', ] +driver_view_processes = [ + 'camerad', + 'dmonitoringd', + 'dmonitoringmodeld' +] + if WEBCAM: car_started_processes += [ 'dmonitoringmodeld', @@ -470,7 +475,7 @@ def manager_thread(): if msg.thermal.freeSpace < 0.05: logger_dead = True - if msg.thermal.started and "driverview" not in running: + if msg.thermal.started: for p in car_started_processes: if p == "loggerd" and logger_dead: kill_managed_process(p) @@ -478,13 +483,18 @@ def manager_thread(): start_managed_process(p) else: logger_dead = False + driver_view = params.get("IsDriverViewEnabled") == b"1" + + # TODO: refactor how manager manages processes for p in reversed(car_started_processes): - kill_managed_process(p) - # this is ugly - if "driverview" not in running and params.get("IsDriverViewEnabled") == b"1": - start_managed_process("driverview") - elif "driverview" in running and params.get("IsDriverViewEnabled") == b"0": - kill_managed_process("driverview") + if p not in driver_view_processes or not driver_view: + kill_managed_process(p) + + for p in driver_view_processes: + if driver_view: + start_managed_process(p) + else: + kill_managed_process(p) # check the status of all processes, did any of them die? running_list = ["%s%s\u001b[0m" % ("\u001b[32m" if running[p].is_alive() else "\u001b[31m", p) for p in running] diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index a7fb78a729..a99d53ca1e 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -1,21 +1,18 @@ #!/usr/bin/env python3 import gc from cereal import car -from common.realtime import set_realtime_priority +from common.realtime import set_realtime_priority, DT_DMON from common.params import Params import cereal.messaging as messaging from selfdrive.controls.lib.events import Events from selfdrive.monitoring.driver_monitor import DriverStatus, MAX_TERMINAL_ALERTS, MAX_TERMINAL_DURATION from selfdrive.locationd.calibration_helpers import Calibration + def dmonitoringd_thread(sm=None, pm=None): gc.disable() - - # start the loop set_realtime_priority(53) - params = Params() - # Pub/Sub Sockets if pm is None: pm = messaging.PubMaster(['dMonitoringState']) @@ -23,13 +20,15 @@ def dmonitoringd_thread(sm=None, pm=None): if sm is None: sm = messaging.SubMaster(['driverState', 'liveCalibration', 'carState', 'model']) + params = Params() + driver_status = DriverStatus() is_rhd = params.get("IsRHD") - if is_rhd is not None: - driver_status.is_rhd_region = bool(int(is_rhd)) - driver_status.is_rhd_region_checked = True + driver_status.is_rhd_region = is_rhd == b"1" + driver_status.is_rhd_region_checked = is_rhd is not None sm['liveCalibration'].calStatus = Calibration.INVALID + sm['liveCalibration'].rpyCalib = [0, 0, 0] sm['carState'].vEgo = 0. sm['carState'].cruiseState.enabled = False sm['carState'].cruiseState.speed = 0. @@ -38,20 +37,14 @@ def dmonitoringd_thread(sm=None, pm=None): sm['carState'].gasPressed = False sm['carState'].standstill = True - cal_rpy = [0, 0, 0] v_cruise_last = 0 driver_engaged = False + offroad = params.get("IsOffroad") == b"1" # 10Hz <- dmonitoringmodeld while True: sm.update() - # Handle calibration - if sm.updated['liveCalibration']: - if sm['liveCalibration'].calStatus == Calibration.CALIBRATED: - if len(sm['liveCalibration'].rpyCalib) == 3: - cal_rpy = sm['liveCalibration'].rpyCalib - # Get interaction if sm.updated['carState']: v_cruise = sm['carState'].cruiseState.speed @@ -67,17 +60,23 @@ def dmonitoringd_thread(sm=None, pm=None): if sm.updated['model']: driver_status.set_policy(sm['model']) + # Check once a second if we're offroad + if sm.frame % 1/DT_DMON == 0: + offroad = params.get("IsOffroad") == b"1" + # Get data from dmonitoringmodeld if sm.updated['driverState']: events = Events() - driver_status.get_pose(sm['driverState'], cal_rpy, sm['carState'].vEgo, sm['carState'].cruiseState.enabled) - # Block any engage after certain distrations + driver_status.get_pose(sm['driverState'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['carState'].cruiseState.enabled) + + # Block engaging after max number of distrations if driver_status.terminal_alert_cnt >= MAX_TERMINAL_ALERTS or driver_status.terminal_time >= MAX_TERMINAL_DURATION: events.add(car.CarEvent.EventName.tooDistracted) + # Update events from driver state driver_status.update(events, driver_engaged, sm['carState'].cruiseState.enabled, sm['carState'].standstill) - # dMonitoringState packet + # build dMonitoringState packet dat = messaging.new_message('dMonitoringState') dat.dMonitoringState = { "events": events.to_msg(), @@ -95,7 +94,7 @@ def dmonitoringd_thread(sm=None, pm=None): "awarenessPassive": driver_status.awareness_passive, "isLowStd": driver_status.pose.low_std, "hiStdCount": driver_status.hi_stds, - "isPreview": False, + "isPreview": offroad, } pm.send('dMonitoringState', dat) diff --git a/selfdrive/monitoring/driverview.py b/selfdrive/monitoring/driverview.py deleted file mode 100755 index 4581a06549..0000000000 --- a/selfdrive/monitoring/driverview.py +++ /dev/null @@ -1,81 +0,0 @@ -#!/usr/bin/env python3 -import os -import subprocess -import multiprocessing -import signal -import time - -import cereal.messaging as messaging -from common.params import Params - -from common.basedir import BASEDIR - -KILL_TIMEOUT = 15 - - -def send_controls_packet(pm): - while True: - dat = messaging.new_message('controlsState') - dat.controlsState = { - "rearViewCam": True, - } - pm.send('controlsState', dat) - time.sleep(0.01) - - -def send_dmon_packet(pm, d): - dat = messaging.new_message('dMonitoringState') - dat.dMonitoringState = { - "isRHD": d[0], - "rhdChecked": d[1], - "isPreview": d[2], - } - pm.send('dMonitoringState', dat) - - -def main(): - pm = messaging.PubMaster(['controlsState', 'dMonitoringState']) - controls_sender = multiprocessing.Process(target=send_controls_packet, args=[pm]) - controls_sender.start() - - # TODO: refactor with manager start/kill - proc_cam = subprocess.Popen(os.path.join(BASEDIR, "selfdrive/camerad/camerad"), cwd=os.path.join(BASEDIR, "selfdrive/camerad")) - proc_mon = subprocess.Popen(os.path.join(BASEDIR, "selfdrive/modeld/dmonitoringmodeld"), cwd=os.path.join(BASEDIR, "selfdrive/modeld")) - - params = Params() - is_rhd = False - is_rhd_checked = False - should_exit = False - - def terminate(signalNumber, frame): - print('got SIGTERM, exiting..') - should_exit = True - send_dmon_packet(pm, [is_rhd, is_rhd_checked, not should_exit]) - proc_cam.send_signal(signal.SIGINT) - proc_mon.send_signal(signal.SIGINT) - kill_start = time.time() - while proc_cam.poll() is None: - if time.time() - kill_start > KILL_TIMEOUT: - from selfdrive.swaglog import cloudlog - cloudlog.critical("FORCE REBOOTING PHONE!") - os.system("date >> /sdcard/unkillable_reboot") - os.system("reboot") - raise RuntimeError - continue - controls_sender.terminate() - exit() - - signal.signal(signal.SIGTERM, terminate) - - while True: - send_dmon_packet(pm, [is_rhd, is_rhd_checked, not should_exit]) - - if not is_rhd_checked: - is_rhd = params.get("IsRHD") == b"1" - is_rhd_checked = True - - time.sleep(0.01) - - -if __name__ == '__main__': - main() diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index d0e88f4dd7..8802526cb8 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -560,7 +560,7 @@ static void ui_draw_vision_face(UIState *s) { const int face_size = 96; const int face_x = (s->scene.ui_viz_rx + face_size + (bdr_s * 2)); const int face_y = (footer_y + ((footer_h - face_size) / 2)); - ui_draw_circle_image(s->vg, face_x, face_y, face_size, s->img_face, s->scene.controls_state.getDriverMonitoringOn()); + ui_draw_circle_image(s->vg, face_x, face_y, face_size, s->img_face, s->scene.dmonitoring_state.getFaceDetected()); } static void ui_draw_driver_view(UIState *s) { @@ -572,19 +572,11 @@ static void ui_draw_driver_view(UIState *s) { const int valid_frame_x = frame_x + (frame_w - valid_frame_w) / 2 + ff_xoffset; // blackout - if (!scene->is_rhd) { - NVGpaint gradient = nvgLinearGradient(s->vg, valid_frame_x + valid_frame_w, - box_y, - valid_frame_x + box_h / 2, box_y, - nvgRGBAf(0,0,0,1), nvgRGBAf(0,0,0,0)); - ui_draw_rect(s->vg, valid_frame_x + box_h / 2, box_y, valid_frame_w - box_h / 2, box_h, gradient); - } else { - NVGpaint gradient = nvgLinearGradient(s->vg, valid_frame_x, - box_y, - valid_frame_w - box_h / 2, box_y, - nvgRGBAf(0,0,0,1), nvgRGBAf(0,0,0,0)); - ui_draw_rect(s->vg, valid_frame_x, box_y, valid_frame_w - box_h / 2, box_h, gradient); - } + NVGpaint gradient = nvgLinearGradient(s->vg, scene->is_rhd ? valid_frame_x : (valid_frame_x + valid_frame_w), + box_y, + scene->is_rhd ? (valid_frame_w - box_h / 2) : (valid_frame_x + box_h / 2), box_y, + COLOR_BLACK, COLOR_BLACK_ALPHA(0)); + ui_draw_rect(s->vg, scene->is_rhd ? valid_frame_x : (valid_frame_x + box_h / 2), box_y, valid_frame_w - box_h / 2, box_h, gradient); ui_draw_rect(s->vg, scene->is_rhd ? valid_frame_x : valid_frame_x + box_h / 2, box_y, valid_frame_w - box_h / 2, box_h, COLOR_BLACK_ALPHA(144)); // borders @@ -592,7 +584,7 @@ static void ui_draw_driver_view(UIState *s) { ui_draw_rect(s->vg, valid_frame_x + valid_frame_w, box_y, frame_w - valid_frame_w - (valid_frame_x - frame_x), box_h, nvgRGBA(23, 51, 73, 255)); // draw face box - if (scene->driver_state.getFaceProb() > 0.4) { + if (scene->dmonitoring_state.getFaceDetected()) { auto fxy_list = scene->driver_state.getFacePosition(); const float face_x = fxy_list[0]; const float face_y = fxy_list[1]; @@ -603,6 +595,7 @@ static void ui_draw_driver_view(UIState *s) { } else { fbox_x = valid_frame_x + valid_frame_w - box_h / 2 + (face_x + 0.5) * (box_h / 2) - 0.5 * 0.6 * box_h / 2; } + if (std::abs(face_x) <= 0.35 && std::abs(face_y) <= 0.4) { ui_draw_rect(s->vg, fbox_x, fbox_y, 0.6 * box_h / 2, 0.6 * box_h / 2, nvgRGBAf(1.0, 1.0, 1.0, 0.8 - ((std::abs(face_x) > std::abs(face_y) ? std::abs(face_x) : std::abs(face_y))) * 0.6 / 0.375), @@ -616,7 +609,7 @@ static void ui_draw_driver_view(UIState *s) { const int face_size = 85; const int x = (valid_frame_x + face_size + (bdr_s * 2)) + (scene->is_rhd ? valid_frame_w - box_h / 2:0); const int y = (box_y + box_h - face_size - bdr_s - (bdr_s * 1.5)); - ui_draw_circle_image(s->vg, x, y, face_size, s->img_face, scene->driver_state.getFaceProb() > 0.4); + ui_draw_circle_image(s->vg, x, y, face_size, s->img_face, scene->dmonitoring_state.getFaceDetected()); } static void ui_draw_vision_header(UIState *s) { diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 0a1566c2ab..0ddc306f87 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -269,8 +269,7 @@ void handle_message(UIState *s, SubMaster &sm) { auto event = sm["controlsState"]; scene.controls_state = event.getControlsState(); s->controls_timeout = 1 * UI_FREQ; - scene.frontview = scene.controls_state.getRearViewCam(); - if (!scene.frontview){ s->controls_seen = true; } + s->controls_seen = true; auto alert_sound = scene.controls_state.getAlertSound(); if (scene.alert_type.compare(scene.controls_state.getAlertType()) != 0) { @@ -364,11 +363,17 @@ void handle_message(UIState *s, SubMaster &sm) { } if (sm.updated("dMonitoringState")) { auto data = sm["dMonitoringState"].getDMonitoringState(); + scene.dmonitoring_state = sm["dMonitoringState"].getDMonitoringState(); scene.is_rhd = data.getIsRHD(); - s->preview_started = data.getIsPreview(); + scene.frontview = data.getIsPreview(); } - s->started = scene.thermal.getStarted() || s->preview_started; + // timeout on frontview + if ((sm.frame - sm.rcv_frame("dMonitoringState")) > 1*UI_FREQ) { + scene.frontview = false; + } + + s->started = scene.thermal.getStarted() || scene.frontview; // Handle onroad/offroad transition if (!s->started) { if (s->status != STATUS_STOPPED) { @@ -815,7 +820,7 @@ int main(int argc, char* argv[]) { if (s->controls_timeout > 0) { s->controls_timeout--; - } else if (s->started) { + } else if (s->started && !s->scene.frontview) { if (!s->controls_seen) { // car is started, but controlsState hasn't been seen at all s->scene.alert_text1 = "openpilot Unavailable"; diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 1094f7cca3..bf64ef27aa 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -125,6 +125,7 @@ typedef struct UIScene { cereal::RadarState::LeadData::Reader lead_data[2]; cereal::ControlsState::Reader controls_state; cereal::DriverState::Reader driver_state; + cereal::DMonitoringState::Reader dmonitoring_state; } UIScene; typedef struct { @@ -224,7 +225,6 @@ typedef struct UIState { float alert_blinking_alpha; bool alert_blinked; bool started; - bool preview_started; bool vision_seen; std::atomic light_sensor; From e89b2b84534e76d8965b22d2aa7451984fbf7229 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 1 Aug 2020 22:38:19 -0700 Subject: [PATCH 541/656] Test can valid in car unit tests (#1961) * check can invalid * remove bad lexus is route * blacklist routes from before cam forwarding * fix rav4 route with missing first segment --- selfdrive/test/test_car_models.py | 13 +++++++------ selfdrive/test/test_models.py | 16 +++++++++++++--- 2 files changed, 20 insertions(+), 9 deletions(-) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 8c14339977..57ba1c8a2b 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -92,7 +92,7 @@ routes = { 'carFingerprint': GM.BUICK_REGAL, 'enableCamera': True, }, - "7d44af5b7a1b2c8e|2017-09-16--01-50-07": { + "a74b011b32b51b56|2020-07-26--17-09-36": { 'carFingerprint': HONDA.CIVIC, 'enableCamera': True, }, @@ -270,6 +270,12 @@ routes = { 'enableDsu': True, 'enableGasInterceptor': True, }, + "b14c5b4742e6fc85|2020-07-28--19-50-11": { + 'carFingerprint': TOYOTA.RAV4, + 'enableCamera': True, + 'enableDsu': False, + 'enableGasInterceptor': True, + }, "32a7df20486b0f70|2020-02-06--16-06-50": { 'carFingerprint': TOYOTA.RAV4H, 'enableCamera': True, @@ -363,11 +369,6 @@ routes = { 'enableCamera': False, 'enableDsu': False, }, - "1dd19ceed0ee2b48|2018-12-22--17-36-49": { - 'carFingerprint': TOYOTA.LEXUS_IS, # 300 hybrid - 'enableCamera': True, - 'enableDsu': False, - }, "76b83eb0245de90e|2019-10-20--15-42-29": { 'carFingerprint': VOLKSWAGEN.GOLF, 'enableCamera': True, diff --git a/selfdrive/test/test_models.py b/selfdrive/test/test_models.py index a854953529..a318fbd972 100755 --- a/selfdrive/test/test_models.py +++ b/selfdrive/test/test_models.py @@ -21,6 +21,16 @@ HwType = log.HealthData.HwType ROUTES = {v['carFingerprint']: k for k, v in routes.items() if v['enableCamera']} +# TODO: get updated routes for these cars +ignore_can_valid = [ + "VOLKSWAGEN GOLF", + "ACURA ILX 2016 ACURAWATCH PLUS", + "TOYOTA PRIUS 2017", + "TOYOTA COROLLA 2017", + "LEXUS RX HYBRID 2017", + "TOYOTA AVALON 2016", +] + @parameterized_class(('car_model'), [(car,) for car in all_known_cars()]) class TestCarModel(unittest.TestCase): @@ -96,9 +106,9 @@ class TestCarModel(unittest.TestCase): CS = self.CI.update(CC, (can_pkt.to_bytes(),)) self.CI.apply(CC) - can_invalid_cnt += CS.canValid - # TODO: add this back - #self.assertLess(can_invalid_cnt, 20) + can_invalid_cnt += not CS.canValid + if self.car_model not in ignore_can_valid: + self.assertLess(can_invalid_cnt, 50) def test_radar_interface(self): os.environ['NO_RADAR_SLEEP'] = "1" From 58b167d75da2d7e5009c1ff7d599f6cb5359cc75 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 2 Aug 2020 00:00:19 -0700 Subject: [PATCH 542/656] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index efb1e38aec..c50d4bf1d5 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit efb1e38aec6949e738da5252f9a5839cb28ea2c8 +Subproject commit c50d4bf1d5c14bc5ae6290677a73d6bd9dc813b8 From 9ee1cc9b828e8018fa37443d90dba95f8a032260 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 2 Aug 2020 00:30:09 -0700 Subject: [PATCH 543/656] Run CI tests in parallel (#1962) * run car model unit tests in parallel * remove refs to deleted file * run with coverage * that wasn't necessary * as builder * need a new route for this one too --- .coveragerc-app | 3 --- .github/workflows/test.yaml | 6 +++--- Dockerfile.openpilot | 1 - selfdrive/car/volkswagen/interface.py | 6 +++--- selfdrive/test/test_models.py | 10 +++------- 5 files changed, 9 insertions(+), 17 deletions(-) delete mode 100644 .coveragerc-app diff --git a/.coveragerc-app b/.coveragerc-app deleted file mode 100644 index 18c81e3b48..0000000000 --- a/.coveragerc-app +++ /dev/null @@ -1,3 +0,0 @@ -[run] -concurrency=multiprocessing - diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index d9892b2663..02a3c11dde 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -37,7 +37,7 @@ jobs: external/bin selfdrive/modeld/runners $TEST_DIR # need these so docker copy won't fail - cp Pipfile Pipfile.lock .pylintrc .coveragerc-app .pre-commit-config.yaml $TEST_DIR + cp Pipfile Pipfile.lock .pylintrc .pre-commit-config.yaml $TEST_DIR cd $TEST_DIR mkdir laika laika_repo tools - name: Build Docker image @@ -199,8 +199,8 @@ jobs: run: | $PERSIST "cd /tmp/openpilot && \ scons -j$(nproc) && \ - coverage run --parallel-mode --concurrency=multiprocessing \ - --rcfile=./.coveragerc-app selfdrive/test/test_models.py && \ + coverage run --parallel-mode -m nose --processes=4 --process-timeout=60 \ + selfdrive/test/test_models.py && \ coverage combine" - name: Upload coverage to Codecov run: | diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index e90eb47a24..4de954141f 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -81,7 +81,6 @@ RUN mkdir -p /tmp/openpilot COPY SConstruct \ .pylintrc \ .pre-commit-config.yaml \ - .coveragerc-app \ /tmp/openpilot/ COPY ./pyextra /tmp/openpilot/pyextra diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index c7082b57ce..c041c6c44c 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -1,6 +1,5 @@ from cereal import car from selfdrive.car.volkswagen.values import CAR, BUTTON_STATES -from common.params import put_nonblocking from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint from selfdrive.car.interfaces import CarInterfaceBase @@ -76,10 +75,11 @@ class CarInterface(CarInterfaceBase): ret.canValid = self.cp.can_valid and self.cp_cam.can_valid ret.steeringRateLimited = self.CC.steer_rate_limited if self.CC is not None else False + # TODO: add a field for this to carState, car interface code shouldn't write params # Update the device metric configuration to match the car at first startup, # or if there's been a change. - if self.CS.displayMetricUnits != self.displayMetricUnitsPrev: - put_nonblocking("IsMetric", "1" if self.CS.displayMetricUnits else "0") + #if self.CS.displayMetricUnits != self.displayMetricUnitsPrev: + # put_nonblocking("IsMetric", "1" if self.CS.displayMetricUnits else "0") # Check for and process state-change events (button press or release) from # the turn stalk switch or ACC steering wheel/control stalk buttons. diff --git a/selfdrive/test/test_models.py b/selfdrive/test/test_models.py index a318fbd972..868b74f424 100755 --- a/selfdrive/test/test_models.py +++ b/selfdrive/test/test_models.py @@ -7,7 +7,6 @@ from collections import Counter from parameterized import parameterized_class from cereal import log, car -import cereal.messaging as messaging from selfdrive.car.fingerprints import all_known_cars from selfdrive.car.car_helpers import interfaces from selfdrive.test.test_car_models import routes, non_tested_cars @@ -29,6 +28,7 @@ ignore_can_valid = [ "TOYOTA COROLLA 2017", "LEXUS RX HYBRID 2017", "TOYOTA AVALON 2016", + "HONDA PILOT 2019 ELITE", ] @parameterized_class(('car_model'), [(car,) for car in all_known_cars()]) @@ -99,14 +99,10 @@ class TestCarModel(unittest.TestCase): can_invalid_cnt = 0 CC = car.CarControl.new_message() for msg in self.can_msgs: - # filter out openpilot msgs - can = [m for m in msg.can if m.src < 128] - can_pkt = messaging.new_message('can', len(can)) - can_pkt.can = can - - CS = self.CI.update(CC, (can_pkt.to_bytes(),)) + CS = self.CI.update(CC, (msg.as_builder().to_bytes(),)) self.CI.apply(CC) can_invalid_cnt += not CS.canValid + if self.car_model not in ignore_can_valid: self.assertLess(can_invalid_cnt, 50) From 56e63bafa87995eb6795bd77df931a29bf89c684 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 3 Aug 2020 01:55:24 +0800 Subject: [PATCH 544/656] remove duplicate call to getDMonitoringState (#1964) --- selfdrive/ui/ui.cc | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 0ddc306f87..b8edfc4e2e 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -362,10 +362,9 @@ void handle_message(UIState *s, SubMaster &sm) { scene.driver_state = sm["driverState"].getDriverState(); } if (sm.updated("dMonitoringState")) { - auto data = sm["dMonitoringState"].getDMonitoringState(); scene.dmonitoring_state = sm["dMonitoringState"].getDMonitoringState(); - scene.is_rhd = data.getIsRHD(); - scene.frontview = data.getIsPreview(); + scene.is_rhd = scene.dmonitoring_state.getIsRHD(); + scene.frontview = scene.dmonitoring_state.getIsPreview(); } // timeout on frontview From e10376f1aead6db2a40aa367dfccbb7b184abbcd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 2 Aug 2020 11:17:18 -0700 Subject: [PATCH 545/656] Add frequency check to hyundai camera can parser (#1965) --- selfdrive/car/hyundai/carstate.py | 4 +++- selfdrive/car/hyundai/values.py | 1 - selfdrive/test/test_models.py | 1 + 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 1477ed274d..8141056811 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -298,6 +298,8 @@ class CarState(CarStateBase): ("CF_Lkas_LdwsOpt_USM", "LKAS11", 0) ] - checks = [] + checks = [ + ("LKAS11", 100) + ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 7dc60144ea..6e694b977c 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -30,7 +30,6 @@ class CAR: KONA = "HYUNDAI KONA 2019" KONA_EV = "HYUNDAI KONA ELECTRIC 2019" SANTA_FE = "HYUNDAI SANTA FE LIMITED 2019" - SANTA_FE_1 = "HYUNDAI SANTA FE has no scc" SONATA = "HYUNDAI SONATA 2020" SONATA_2019 = "HYUNDAI SONATA 2019" PALISADE = "HYUNDAI PALISADE 2020" diff --git a/selfdrive/test/test_models.py b/selfdrive/test/test_models.py index 868b74f424..2fa1dc3167 100755 --- a/selfdrive/test/test_models.py +++ b/selfdrive/test/test_models.py @@ -29,6 +29,7 @@ ignore_can_valid = [ "LEXUS RX HYBRID 2017", "TOYOTA AVALON 2016", "HONDA PILOT 2019 ELITE", + "HYUNDAI SANTA FE LIMITED 2019", ] @parameterized_class(('car_model'), [(car,) for car in all_known_cars()]) From 3eafa8d8604407b344f2883ff02a6ce7326109be Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 2 Aug 2020 13:08:35 -0700 Subject: [PATCH 546/656] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index c50d4bf1d5..a59f03c179 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit c50d4bf1d5c14bc5ae6290677a73d6bd9dc813b8 +Subproject commit a59f03c179587573924edc03bacfc5aa3f77d83d From 059a27d12697e48b10c00fc345812704d7ba4640 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 2 Aug 2020 15:19:27 -0700 Subject: [PATCH 547/656] Update Hyundai DBC (#1968) * update for new DBC update * update to new DBC * Ioniq uses SCC12. Ioniq EV lim uses FCA11 * update elect gear to EV_PC5 signal * remove 'alt' from label * revert * update name to ev_pc5_gears * update name to use_ev_pc5_gears * Update values.py * Update carstate.py * bump opendbc Co-authored-by: xps-genesis <65239463+xps-genesis@users.noreply.github.com> --- opendbc | 2 +- selfdrive/car/hyundai/carstate.py | 2 +- selfdrive/car/hyundai/hyundaican.py | 6 +++--- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/opendbc b/opendbc index a59f03c179..b7cf1a67bc 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit a59f03c179587573924edc03bacfc5aa3f77d83d +Subproject commit b7cf1a67bc71b674e6793ba1f2fff5d29fee1e6b diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 8141056811..61d9de05bb 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -281,7 +281,7 @@ class CarState(CarStateBase): signals = [ # sig_name, sig_address, default - ("CF_Lkas_Bca_R", "LKAS11", 0), + ("CF_Lkas_LdwsActivemode", "LKAS11", 0), ("CF_Lkas_LdwsSysState", "LKAS11", 0), ("CF_Lkas_SysWarning", "LKAS11", 0), ("CF_Lkas_LdwsLHWarning", "LKAS11", 0), diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index b5969d018b..1e7b751018 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -20,7 +20,7 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, values["CF_Lkas_Chksum"] = 0 if car_fingerprint in [CAR.SONATA, CAR.PALISADE]: - values["CF_Lkas_Bca_R"] = int(left_lane) + (int(right_lane) << 1) + values["CF_Lkas_LdwsActivemode"] = int(left_lane) + (int(right_lane) << 1) values["CF_Lkas_LdwsOpt_USM"] = 2 # FcwOpt_USM 5 = Orange blinking car + lanes @@ -40,9 +40,9 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, elif car_fingerprint == CAR.HYUNDAI_GENESIS: # This field is actually LdwsActivemode # Genesis and Optima fault when forwarding while engaged - values["CF_Lkas_Bca_R"] = 2 + values["CF_Lkas_LdwsActivemode"] = 2 elif car_fingerprint == CAR.KIA_OPTIMA: - values["CF_Lkas_Bca_R"] = 0 + values["CF_Lkas_LdwsActivemode"] = 0 dat = packer.make_can_msg("LKAS11", 0, values)[2] From 433c9241f38d1167f0555e75902823b8a1f063be Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 2 Aug 2020 15:25:09 -0700 Subject: [PATCH 548/656] we have routes for these now --- selfdrive/test/test_car_models.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 57ba1c8a2b..1e27e7909a 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -431,11 +431,8 @@ non_tested_cars = [ HYUNDAI.ELANTRA_GT_I30, HYUNDAI.GENESIS_G80, HYUNDAI.GENESIS_G90, - HYUNDAI.HYUNDAI_GENESIS, HYUNDAI.KIA_FORTE, - HYUNDAI.KIA_OPTIMA, HYUNDAI.KIA_OPTIMA_H, - HYUNDAI.KIA_STINGER, HYUNDAI.KONA, HYUNDAI.KONA_EV, TOYOTA.CAMRYH, From 6e1bcdcb34d8361379cb2a21ea043ba331c3dabf Mon Sep 17 00:00:00 2001 From: xps-genesis <65239463+xps-genesis@users.noreply.github.com> Date: Sun, 2 Aug 2020 18:45:41 -0400 Subject: [PATCH 549/656] Add Hyundai Veloster 2019 (#1955) * Add Hyundai Veloster 2019 * Add Hyundai Veloster interface.py * add route for Hyundia Veloster * steer ratio fix * Update interface.py * new longer route * space * ignored fingerprint Co-authored-by: Adeeb Shihadeh --- selfdrive/car/hyundai/interface.py | 10 +++++++++- selfdrive/car/hyundai/values.py | 18 +++++++++++++++++- selfdrive/test/test_car_models.py | 4 ++++ 3 files changed, 30 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 787df32ff4..9ae6853a07 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -143,9 +143,17 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.5 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + elif candidate == CAR.VELOSTER: + ret.lateralTuning.pid.kf = 0.00005 + ret.mass = 3558. * CV.LB_TO_KG + ret.wheelbase = 2.80 + ret.steerRatio = 13.75 * 1.15 + tire_stiffness_factor = 0.5 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] # these cars require a special panda safety mode due to missing counters and checksums in the messages - if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_2019, CAR.KIA_OPTIMA, CAR.KIA_STINGER]: + if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_2019, CAR.KIA_OPTIMA, CAR.VELOSTER, CAR.KIA_STINGER]: ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy ret.centerToFront = ret.wheelbase * 0.4 diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 6e694b977c..ede420d0ea 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -33,6 +33,7 @@ class CAR: SONATA = "HYUNDAI SONATA 2020" SONATA_2019 = "HYUNDAI SONATA 2019" PALISADE = "HYUNDAI PALISADE 2020" + VELOSTER = "HYUNDAI VELOSTER 2019" class Buttons: @@ -137,12 +138,18 @@ FINGERPRINTS = { CAR.PALISADE: [{ 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 549: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1123: 8, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8 }], + CAR.VELOSTER: [{ + 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 558: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1170: 8, 1181: 5, 1186: 2, 1191: 2, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1378: 4, 1407: 8, 1414: 3, 1415: 8, 1419: 8, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 1872: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2004: 8, 2008: 8, 2009: 8, 2012: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }] } ECU_FINGERPRINT = { Ecu.fwdCamera: [832, 1156, 1191, 1342] } +# Don't use these fingerprints for fingerprinting, they are still used for ECU detection +IGNORED_FINGERPRINTS = [CAR.VELOSTER] + FW_VERSIONS = { CAR.SONATA: { (Ecu.fwdRadar, 0x7d0, None): [ @@ -209,6 +216,14 @@ FW_VERSIONS = { b'\xf1\x87LDKVBN424201KF26\xba\xaa\x9a\xa9\x99\x99\x89\x98\x89\x99\xa8\x99\x88\x99\x98\x89\x88\x99\xa8\x89v\x7f\xf7\xffwf_\xffq\xa6\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', b'\xf1\x87LDLVBN560098KF26\x86fff\x87vgfg\x88\x96xfw\x86gfw\x86g\x95\xf6\xffeU_\xff\x92c\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', ], + }, + CAR.VELOSTER: { + (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', ], + (Ecu.esp, 0x7d1, None): [b'\xf1\x00\x00\x00\x00\x00\x00\x00', ], + (Ecu.engine, 0x7e0, None): [b'\x01TJS-JNU06F200H0A', ], + (Ecu.eps, 0x7d4, None): [b'\xf1\x00JSL MDPS C 1.00 1.03 56340-J3000 8308', ], + (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', ], + (Ecu.transmission, 0x7e1, None): [b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16NS1\xba\x02\xb8\x80', ], } } @@ -220,7 +235,7 @@ CHECKSUM = { FEATURES = { # which message has the gear "use_cluster_gears": set([CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30]), - "use_tcu_gears": set([CAR.KIA_OPTIMA, CAR.SONATA_2019]), + "use_tcu_gears": set([CAR.KIA_OPTIMA, CAR.SONATA_2019, CAR.VELOSTER]), "use_elect_gears": set([CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ]), # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 @@ -250,6 +265,7 @@ DBC = { CAR.SONATA: dbc_dict('hyundai_kia_generic', None), CAR.SONATA_2019: dbc_dict('hyundai_kia_generic', None), CAR.PALISADE: dbc_dict('hyundai_kia_generic', None), + CAR.VELOSTER: dbc_dict('hyundai_kia_generic', None), } STEER_THRESHOLD = 150 diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 1e27e7909a..bdf0331d85 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -212,6 +212,10 @@ routes = { 'carFingerprint': HYUNDAI.KIA_STINGER, 'enableCamera': True, }, + "d624b3d19adce635|2020-08-01--14-59-12": { + 'carFingerprint': HYUNDAI.VELOSTER, + 'enableCamera': True, + }, "f7b6be73e3dfd36c|2019-05-12--18-07-16": { 'carFingerprint': TOYOTA.AVALON, 'enableCamera': False, From de95b7f0fb6170e45bf89a56ba59752c6067a9d7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 2 Aug 2020 16:02:11 -0700 Subject: [PATCH 550/656] add hyundai veloster to release notes --- README.md | 1 + RELEASES.md | 1 + 2 files changed, 2 insertions(+) diff --git a/README.md b/README.md index d7bdad27b5..f37d9df404 100644 --- a/README.md +++ b/README.md @@ -149,6 +149,7 @@ Community Maintained Cars and Features | Hyundai | Palisade 2020 | All | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2019 | All | Stock | 0mph | 0mph | +| Hyundai | Veloster 2019 | SCC + LKAS | Stock | 5mph | 40mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | | Kia | Forte 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | diff --git a/RELEASES.md b/RELEASES.md index c98405e564..e337bd5380 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,6 +1,7 @@ Version 0.7.8 (2020-08-XX) ======================== * New driver monitoring model + * Hyundai Veloster 2019 support thanks to xps-gensis! Version 0.7.7 (2020-07-20) ======================== From c8bc172316f23dcc22792171afde914f352f42d5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 2 Aug 2020 16:58:27 -0700 Subject: [PATCH 551/656] veloster steers down to zero --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index f37d9df404..5f51266b24 100644 --- a/README.md +++ b/README.md @@ -149,7 +149,7 @@ Community Maintained Cars and Features | Hyundai | Palisade 2020 | All | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2019 | All | Stock | 0mph | 0mph | -| Hyundai | Veloster 2019 | SCC + LKAS | Stock | 5mph | 40mph | +| Hyundai | Veloster 2019 | SCC + LKAS | Stock | 5mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | | Kia | Forte 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | From 1e44b99478e22d89e9b5077aa9e9d6b2aeee37dd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 2 Aug 2020 18:11:42 -0700 Subject: [PATCH 552/656] Add missing chrysler can parser checks (#1967) * add missing chrysler can parser checks * toyota * toyota cam * toyota freqs * chrysler freqs * doors * just chrysler for now * update refs * update again --- selfdrive/car/chrysler/carstate.py | 13 ++++++++++++- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/test_models.py | 7 +++++-- 3 files changed, 18 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index d935e8eaa0..b6fdb11314 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -103,6 +103,13 @@ class CarState(CarStateBase): ("WHEEL_SPEEDS", 50), ("STEERING", 100), ("ACC_2", 50), + ("GEAR", 50), + ("ACCEL_GAS_134", 50), + ("DASHBOARD", 15), + ("STEERING_LEVERS", 10), + ("SEATBELT_STATUS", 2), + ("DOORS", 1), + ("TRACTION_BUTTON", 1), ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) @@ -115,6 +122,10 @@ class CarState(CarStateBase): ("CAR_MODEL", "LKAS_HUD", -1), ("LKAS_STATUS_OK", "LKAS_HEARTBIT", -1) ] - checks = [] + checks = [ + ("LKAS_COMMAND", 100), + ("LKAS_HEARTBIT", 10), + ("LKAS_HUD", 4), + ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 479987e9fa..8b8abe7eca 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -d8944d6eb13c30c2fd5bcc1af5dbad07472c42c0 \ No newline at end of file +3e8932a5dc0281b00463d40a5435f659259591c4 \ No newline at end of file diff --git a/selfdrive/test/test_models.py b/selfdrive/test/test_models.py index 2fa1dc3167..c06bdf6e04 100755 --- a/selfdrive/test/test_models.py +++ b/selfdrive/test/test_models.py @@ -99,10 +99,13 @@ class TestCarModel(unittest.TestCase): # TODO: also check for checkusm and counter violations from can parser can_invalid_cnt = 0 CC = car.CarControl.new_message() - for msg in self.can_msgs: + for i, msg in enumerate(self.can_msgs): CS = self.CI.update(CC, (msg.as_builder().to_bytes(),)) self.CI.apply(CC) - can_invalid_cnt += not CS.canValid + + # wait 2s for low frequency msgs to be seen + if i > 200: + can_invalid_cnt += not CS.canValid if self.car_model not in ignore_can_valid: self.assertLess(can_invalid_cnt, 50) From 629898eb93753b5a65095807cafe061f644365ac Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 3 Aug 2020 14:17:22 -0700 Subject: [PATCH 553/656] Update bug_report.md --- .github/ISSUE_TEMPLATE/bug_report.md | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md index 34ddfe17b5..a16eacbc69 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -22,6 +22,7 @@ assignees: '' - Device: [e.g. EON/EON Gold/comma two] - Dongle ID: [e.g. 77611a1fac303767, can be found in Settings -> Device -> Dongle ID or my.comma.ai/useradmin] - Route: [e.g. 77611a1fac303767|2020-05-11--16-37-07, can be found in my.comma.ai/useradmin] + - Timestamp: [When in the route the bug occurs (e.g. 4min 30s into the drive)] - Version: [commit hash when on a non-release branch, or version number when on devel or release2 (e.g. 0.7.6)] - Car make/model: [e.g. Toyota Prius 2016] From 1208ac424d06e03da9f83fc1fa1824df7e32f80d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 3 Aug 2020 14:58:15 -0700 Subject: [PATCH 554/656] Cleanup locationd msg building (#1972) * cleanup locationd msg building * remove that --- selfdrive/locationd/locationd.py | 66 ++++++++++++-------------------- 1 file changed, 25 insertions(+), 41 deletions(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 283d14732a..ab5f06c0f2 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -113,47 +113,31 @@ class Localizer(): #ned_vel_std = self.converter.ecef2ned(fix_ecef + vel_ecef + vel_ecef_std) - self.converter.ecef2ned(fix_ecef + vel_ecef) fix = messaging.log.LiveLocationKalman.new_message() - fix.positionGeodetic.value = to_float(fix_pos_geo) - fix.positionGeodetic.std = to_float(np.nan*np.zeros(3)) - fix.positionGeodetic.valid = True - fix.positionECEF.value = to_float(fix_ecef) - fix.positionECEF.std = to_float(fix_ecef_std) - fix.positionECEF.valid = True - fix.velocityECEF.value = to_float(vel_ecef) - fix.velocityECEF.std = to_float(vel_ecef_std) - fix.velocityECEF.valid = True - fix.velocityNED.value = to_float(ned_vel) - fix.velocityNED.std = to_float(np.nan*np.zeros(3)) - fix.velocityNED.valid = True - fix.velocityDevice.value = to_float(vel_device) - fix.velocityDevice.std = to_float(vel_device_std) - fix.velocityDevice.valid = True - fix.accelerationDevice.value = to_float(predicted_state[States.ACCELERATION]) - fix.accelerationDevice.std = to_float(predicted_std[States.ACCELERATION_ERR]) - fix.accelerationDevice.valid = True - - fix.orientationECEF.value = to_float(orientation_ecef) - fix.orientationECEF.std = to_float(orientation_ecef_std) - fix.orientationECEF.valid = True - fix.calibratedOrientationECEF.value = to_float(calibrated_orientation_ecef) - fix.calibratedOrientationECEF.std = to_float(np.nan*np.zeros(3)) - fix.calibratedOrientationECEF.valid = True - fix.orientationNED.value = to_float(orientation_ned) - fix.orientationNED.std = to_float(np.nan*np.zeros(3)) - fix.orientationNED.valid = True - fix.angularVelocityDevice.value = to_float(predicted_state[States.ANGULAR_VELOCITY]) - fix.angularVelocityDevice.std = to_float(predicted_std[States.ANGULAR_VELOCITY_ERR]) - fix.angularVelocityDevice.valid = True - - fix.velocityCalibrated.value = to_float(vel_calib) - fix.velocityCalibrated.std = to_float(vel_calib_std) - fix.velocityCalibrated.valid = True - fix.angularVelocityCalibrated.value = to_float(ang_vel_calib) - fix.angularVelocityCalibrated.std = to_float(ang_vel_calib_std) - fix.angularVelocityCalibrated.valid = True - fix.accelerationCalibrated.value = to_float(acc_calib) - fix.accelerationCalibrated.std = to_float(acc_calib_std) - fix.accelerationCalibrated.valid = True + + # write measurements to msg + measurements = [ + # measurement field, value, std, valid + (fix.positionGeodetic, fix_pos_geo, np.nan*np.zeros(3), True), + (fix.positionECEF, fix_ecef, fix_ecef_std, True), + (fix.velocityECEF, vel_ecef, vel_ecef_std, True), + (fix.velocityNED, ned_vel, np.nan*np.zeros(3), True), + (fix.velocityDevice, vel_device, vel_device_std, True), + (fix.accelerationDevice, predicted_state[States.ACCELERATION], predicted_std[States.ACCELERATION_ERR], True), + (fix.orientationECEF, orientation_ecef, orientation_ecef_std, True), + (fix.calibratedOrientationECEF, calibrated_orientation_ecef, np.nan*np.zeros(3), True), + (fix.orientationNED, orientation_ned, np.nan*np.zeros(3), True), + (fix.angularVelocityDevice, predicted_state[States.ANGULAR_VELOCITY], predicted_std[States.ANGULAR_VELOCITY_ERR], True), + (fix.velocityCalibrated, vel_calib, vel_calib_std, True), + (fix.angularVelocityCalibrated, ang_vel_calib, ang_vel_calib_std, True), + (fix.accelerationCalibrated, acc_calib, acc_calib_std, True), + ] + + for field, value, std, valid in measurements: + # TODO: can we write the lists faster? + field.value = to_float(value) + field.std = to_float(std) + field.valid = valid + return fix def liveLocationMsg(self): From 490ee5268712c38f738161cab939c02573581ebf Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 3 Aug 2020 15:51:56 -0700 Subject: [PATCH 555/656] add fall filter and less FP on posenet (#1971) * add fall filter and less FP on posenet * add alert * list Co-authored-by: Adeeb Shihadeh --- cereal | 2 +- selfdrive/controls/controlsd.py | 2 ++ selfdrive/controls/lib/events.py | 5 +++++ selfdrive/locationd/locationd.py | 22 +++++++++------------- 4 files changed, 17 insertions(+), 14 deletions(-) diff --git a/cereal b/cereal index 10a25c8b98..61d7488e55 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 10a25c8b98ad295308e6825cef7cf42dff6f4396 +Subproject commit 61d7488e55fcaa3760d9ccc9d6589b30cbe4a6c1 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 5443f8d382..2546a598af 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -216,6 +216,8 @@ class Controls: self.events.add(EventName.vehicleModelInvalid) if not self.sm['liveLocationKalman'].posenetOK: self.events.add(EventName.posenetInvalid) + if not self.sm['liveLocationKalman'].deviceStable: + self.events.add(EventName.deviceFalling) if not self.sm['frame'].recoverState < 2: # counter>=2 is active self.events.add(EventName.focusRecoverActive) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index eb943c1acc..205c6a1722 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -655,6 +655,11 @@ EVENTS = { ET.NO_ENTRY: NoEntryAlert("Vision Model Output Uncertain"), }, + EventName.deviceFalling: { + ET.SOFT_DISABLE: SoftDisableAlert("Device Fell Off Mount"), + ET.NO_ENTRY: NoEntryAlert("Device Fell Off Mount"), + }, + EventName.lowMemory: { ET.SOFT_DISABLE: SoftDisableAlert("Low Memory: Reboot Your Device"), ET.PERMANENT: Alert( diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index ab5f06c0f2..369b68b887 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -69,6 +69,7 @@ class Localizer(): self.unix_timestamp_millis = 0 self.last_gps_fix = 0 + self.device_fell = False @staticmethod def msg_from_state(converter, calib_from_device, H, predicted_state, predicted_cov): @@ -142,21 +143,12 @@ class Localizer(): def liveLocationMsg(self): fix = self.msg_from_state(self.converter, self.calib_from_device, self.H, self.kf.x, self.kf.P) - - #if abs(self.posenet_speed - self.car_speed) > max(0.4 * self.car_speed, 5.0): - # self.posenet_invalid_count += 1 - #else: - # self.posenet_invalid_count = 0 - #fix.posenetOK = self.posenet_invalid_count < 4 - - # experimentally found these values + # experimentally found these values, no false positives in 20k minutes of driving old_mean, new_mean = np.mean(self.posenet_stds[:POSENET_STD_HIST//2]), np.mean(self.posenet_stds[POSENET_STD_HIST//2:]) - std_spike = new_mean/old_mean > 4 and new_mean > 5 + std_spike = new_mean/old_mean > 4 and new_mean > 7 - if std_spike and self.car_speed > 5: - fix.posenetOK = False - else: - fix.posenetOK = True + fix.posenetOK = not (std_spike and self.car_speed > 5) + fix.deviceStable = not self.device_fell #fix.gpsWeek = self.time.week #fix.gpsTimeOfWeek = self.time.tow @@ -251,6 +243,10 @@ class Localizer(): # Accelerometer if sensor_reading.sensor == 1 and sensor_reading.type == 1: + # check if device fell, estimate 10 for g + # 40g is a good filter for falling detection, no false positives in 20k minutes of driving + self.device_fell = abs(sensor_reading.acceleration.v[0] - 10) > 40 + self.acc_counter += 1 if self.acc_counter % SENSOR_DECIMATION == 0: v = sensor_reading.acceleration.v From 681ff41261eddc0962c9346e8aa7a019e293d691 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 4 Aug 2020 08:04:47 +0800 Subject: [PATCH 556/656] remove selfdrive/common/visionstream.c (#1931) --- selfdrive/common/visionstream.c | 124 -------------------------------- 1 file changed, 124 deletions(-) delete mode 100644 selfdrive/common/visionstream.c diff --git a/selfdrive/common/visionstream.c b/selfdrive/common/visionstream.c deleted file mode 100644 index 63cf4122c1..0000000000 --- a/selfdrive/common/visionstream.c +++ /dev/null @@ -1,124 +0,0 @@ - - -int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info) { - int err; - - memset(s, 0, sizeof(*s)); - - s->last_idx = -1; - - s->ipc_fd = vipc_connect(); - if (s->ipc_fd < 0) return -1; - - VisionPacket p = { - .type = VIPC_STREAM_SUBSCRIBE, - .d = { .stream_sub = { - .type = type, - .tbuffer = tbuffer, - }, }, - }; - err = vipc_send(s->ipc_fd, &p); - if (err < 0) { - close(s->ipc_fd); - return -1; - } - - VisionPacket rp; - err = vipc_recv(s->ipc_fd, &rp); - if (err <= 0) { - close(s->ipc_fd); - return -1; - } - assert(rp.type = VIPC_STREAM_BUFS); - assert(rp.d.stream_bufs.type == type); - - s->bufs_info = rp.d.stream_bufs; - - s->num_bufs = rp.num_fds; - s->bufs = calloc(s->num_bufs, sizeof(VIPCBuf)); - assert(s->bufs); - - vipc_bufs_load(s->bufs, &rp.d.stream_bufs, s->num_bufs, rp.fds); - - if (out_bufs_info) { - *out_bufs_info = s->bufs_info; - } - - return 0; -} - -void visionstream_release(VisionStream *s) { - int err; - if (s->last_idx >= 0) { - VisionPacket rep = { - .type = VIPC_STREAM_RELEASE, - .d = { .stream_rel = { - .type = s->last_type, - .idx = s->last_idx, - }} - }; - err = vipc_send(s->ipc_fd, &rep); - s->last_idx = -1; - } -} - -VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) { - int err; - - VisionPacket rp; - err = vipc_recv(s->ipc_fd, &rp); - if (err <= 0) { - return NULL; - } - assert(rp.type == VIPC_STREAM_ACQUIRE); - - if (s->last_idx >= 0) { - VisionPacket rep = { - .type = VIPC_STREAM_RELEASE, - .d = { .stream_rel = { - .type = s->last_type, - .idx = s->last_idx, - }} - }; - err = vipc_send(s->ipc_fd, &rep); - if (err <= 0) { - return NULL; - } - } - - s->last_type = rp.d.stream_acq.type; - s->last_idx = rp.d.stream_acq.idx; - assert(s->last_idx < s->num_bufs); - - if (out_extra) { - *out_extra = rp.d.stream_acq.extra; - } - - return &s->bufs[s->last_idx]; -} - -void visionstream_destroy(VisionStream *s) { - int err; - - if (s->last_idx >= 0) { - VisionPacket rep = { - .type = VIPC_STREAM_RELEASE, - .d = { .stream_rel = { - .type = s->last_type, - .idx = s->last_idx, - }} - }; - err = vipc_send(s->ipc_fd, &rep); - s->last_idx = -1; - } - - for (int i=0; inum_bufs; i++) { - if (s->bufs[i].addr) { - munmap(s->bufs[i].addr, s->bufs[i].len); - s->bufs[i].addr = NULL; - close(s->bufs[i].fd); - } - } - if (s->bufs) free(s->bufs); - close(s->ipc_fd); -} \ No newline at end of file From 85fc85b3c8e20d6b970e88774f84ac415c19f1ea Mon Sep 17 00:00:00 2001 From: Cruise Brantley Date: Tue, 4 Aug 2020 15:05:13 -0500 Subject: [PATCH 557/656] Add Kia Stinger transmission FW version (#1975) * new Stinger transmission fingerprint * Formatting --- selfdrive/car/hyundai/values.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index ede420d0ea..e9ff162cfb 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -187,7 +187,10 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\xf1\x81640E0051\x00\x00\x00\x00\x00\x00\x00\x00',], (Ecu.eps, 0x7d4, None): [b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104'], (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822'], - (Ecu.transmission, 0x7e1, None): [b'\xf1\x87VDHLG17118862DK2\x8awWwgu\x96wVfUVwv\x97xWvfvUTGTx\x87o\xff\xc9\xed\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0'], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x87VDHLG17118862DK2\x8awWwgu\x96wVfUVwv\x97xWvfvUTGTx\x87o\xff\xc9\xed\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', + b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', + ], }, CAR.KIA_OPTIMA_H: { (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ',], From 88c67e7e9f73ea5a0114b63598fd489a1e834a84 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 4 Aug 2020 13:48:19 -0700 Subject: [PATCH 558/656] improve updated responsiveness (#1973) --- selfdrive/updated.py | 80 +++++++++++++++++++++++--------------------- 1 file changed, 41 insertions(+), 39 deletions(-) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index bb665180ed..cca3d1b69c 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -76,12 +76,12 @@ class WaitTimeHelper: self.ready_event.set() -def wait_between_updates(ready_event): +def wait_between_updates(ready_event, t=60*10): ready_event.clear() if SHORT: ready_event.wait(timeout=10) else: - ready_event.wait(timeout=60 * 10) + ready_event.wait(timeout=t) def link(src, dest): @@ -341,50 +341,52 @@ def main(): time.sleep(30) wait_helper = WaitTimeHelper() - while True: + while not wait_helper.shutdown: update_failed_count += 1 + + # Check for internet every 30s time_wrong = datetime.datetime.utcnow().year < 2019 ping_failed = subprocess.call(["ping", "-W", "4", "-c", "1", "8.8.8.8"]) + if ping_failed or time_wrong: + wait_between_updates(wait_helper.ready_event, t=30) + continue - # Wait until we have a valid datetime to initialize the overlay - if not (ping_failed or time_wrong): - try: - # If the git directory has modifcations after we created the overlay - # we need to recreate the overlay - if overlay_init_done: - overlay_init_fn = os.path.join(BASEDIR, ".overlay_init") - git_dir_path = os.path.join(BASEDIR, ".git") - new_files = run(["find", git_dir_path, "-newer", overlay_init_fn]) - - if len(new_files.splitlines()): - cloudlog.info(".git directory changed, recreating overlay") - overlay_init_done = False - - if not overlay_init_done: - init_ovfs() - overlay_init_done = True - - if params.get("IsOffroad") == b"1": - attempt_update() - update_failed_count = 0 - else: - cloudlog.info("not running updater, openpilot running") - - except subprocess.CalledProcessError as e: - cloudlog.event( - "update process failed", - cmd=e.cmd, - output=e.output, - returncode=e.returncode - ) - overlay_init_done = False - except Exception: - cloudlog.exception("uncaught updated exception, shouldn't happen") + # Attempt an update + try: + # If the git directory has modifcations after we created the overlay + # we need to recreate the overlay + if overlay_init_done: + overlay_init_fn = os.path.join(BASEDIR, ".overlay_init") + git_dir_path = os.path.join(BASEDIR, ".git") + new_files = run(["find", git_dir_path, "-newer", overlay_init_fn]) + + if len(new_files.splitlines()): + cloudlog.info(".git directory changed, recreating overlay") + overlay_init_done = False + + if not overlay_init_done: + init_ovfs() + overlay_init_done = True + + if params.get("IsOffroad") == b"1": + attempt_update() + update_failed_count = 0 + else: + cloudlog.info("not running updater, openpilot running") + + except subprocess.CalledProcessError as e: + cloudlog.event( + "update process failed", + cmd=e.cmd, + output=e.output, + returncode=e.returncode + ) + overlay_init_done = False + except Exception: + cloudlog.exception("uncaught updated exception, shouldn't happen") params.put("UpdateFailedCount", str(update_failed_count)) wait_between_updates(wait_helper.ready_event) - if wait_helper.shutdown: - break # We've been signaled to shut down dismount_ovfs() From e704da0c28546fd9fc8ee53ea19793880d042059 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Tue, 4 Aug 2020 15:30:18 -0700 Subject: [PATCH 559/656] makes more sense --- common/transformations/model.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/transformations/model.py b/common/transformations/model.py index 221bebae69..a3b46858b1 100644 --- a/common/transformations/model.py +++ b/common/transformations/model.py @@ -75,7 +75,7 @@ medmodel_frame_from_road_frame = np.dot(medmodel_intrinsics, get_view_frame_from_road_frame(0, 0, 0, model_height)) medmodel_frame_from_calib_frame = np.dot(medmodel_intrinsics, - get_view_frame_from_calib_frame(0, 0, 0, model_height)) + get_view_frame_from_calib_frame(0, 0, 0, 0)) model_frame_from_bigmodel_frame = np.dot(model_intrinsics, np.linalg.inv(bigmodel_intrinsics)) medmodel_frame_from_bigmodel_frame = np.dot(medmodel_intrinsics, np.linalg.inv(bigmodel_intrinsics)) From ef435ef2ac14dd7f842d4f59909330ba57f6d177 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 5 Aug 2020 18:27:56 +0800 Subject: [PATCH 560/656] Make sure memory is released by using unique_ptr (#1958) --- selfdrive/modeld/models/driving.cc | 20 +++++--------------- selfdrive/modeld/models/driving.h | 7 ++++--- 2 files changed, 9 insertions(+), 18 deletions(-) diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index af481712b1..f58e7b1964 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -9,9 +9,6 @@ #include "common/params.h" #include "driving.h" - - - #define PATH_IDX 0 #define LL_IDX PATH_IDX + MODEL_PATH_DISTANCE*2 + 1 #define RL_IDX LL_IDX + MODEL_PATH_DISTANCE*2 + 2 @@ -48,17 +45,14 @@ void model_init(ModelState* s, cl_device_id device_id, cl_context context, int t #endif #ifdef DESIRE - s->prev_desire = (float*)malloc(DESIRE_LEN * sizeof(float)); - for (int i = 0; i < DESIRE_LEN; i++) s->prev_desire[i] = 0.0; - s->pulse_desire = (float*)malloc(DESIRE_LEN * sizeof(float)); - for (int i = 0; i < DESIRE_LEN; i++) s->pulse_desire[i] = 0.0; - s->m->addDesire(s->pulse_desire, DESIRE_LEN); + s->prev_desire = std::make_unique(DESIRE_LEN); + s->pulse_desire = std::make_unique(DESIRE_LEN); + s->m->addDesire(s->pulse_desire.get(), DESIRE_LEN); #endif #ifdef TRAFFIC_CONVENTION - s->traffic_convention = (float*)malloc(TRAFFIC_CONVENTION_LEN * sizeof(float)); - for (int i = 0; i < TRAFFIC_CONVENTION_LEN; i++) s->traffic_convention[i] = 0.0; - s->m->addTrafficConvention(s->traffic_convention, TRAFFIC_CONVENTION_LEN); + s->traffic_convention = std::make_unique(TRAFFIC_CONVENTION_LEN); + s->m->addTrafficConvention(s->traffic_convention.get(), TRAFFIC_CONVENTION_LEN); std::vector result = read_db_bytes("IsRHD"); if (result.size() > 0) { @@ -79,8 +73,6 @@ void model_init(ModelState* s, cl_device_id device_id, cl_context context, int t } } - - ModelDataRaw model_eval_frame(ModelState* s, cl_command_queue q, cl_mem yuv_cl, int width, int height, mat3 transform, void* sock, @@ -100,7 +92,6 @@ ModelDataRaw model_eval_frame(ModelState* s, cl_command_queue q, } #endif - //for (int i = 0; i < OUTPUT_SIZE + TEMPORAL_SIZE; i++) { printf("%f ", s->output[i]); } printf("\n"); float *new_frame_buf = frame_prepare(&s->frame, q, yuv_cl, width, height, transform); @@ -163,7 +154,6 @@ void poly_fit(float *in_pts, float *in_stds, float *out, int valid_len) { out[3] = y0; } - void fill_path(cereal::ModelData::PathData::Builder path, const float * data, bool has_prob, const float offset) { float points_arr[MODEL_PATH_DISTANCE]; float stds_arr[MODEL_PATH_DISTANCE]; diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index 83d967d23a..2bf4d61500 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -14,6 +14,7 @@ #include "runners/run.h" #include +#include #include "messaging.hpp" #define MODEL_WIDTH 512 @@ -58,11 +59,11 @@ typedef struct ModelState { float *input_frames; RunModel *m; #ifdef DESIRE - float *prev_desire; - float *pulse_desire; + std::unique_ptr prev_desire; + std::unique_ptr pulse_desire; #endif #ifdef TRAFFIC_CONVENTION - float *traffic_convention; + std::unique_ptr traffic_convention; #endif } ModelState; From 8cad9375d336ca5276f673296d0e64ff14efe0de Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Wed, 5 Aug 2020 10:44:40 -0700 Subject: [PATCH 561/656] persist falling test --- selfdrive/locationd/locationd.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 369b68b887..23ec56b879 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -149,6 +149,7 @@ class Localizer(): fix.posenetOK = not (std_spike and self.car_speed > 5) fix.deviceStable = not self.device_fell + self.device_fell = False #fix.gpsWeek = self.time.week #fix.gpsTimeOfWeek = self.time.tow @@ -245,7 +246,7 @@ class Localizer(): if sensor_reading.sensor == 1 and sensor_reading.type == 1: # check if device fell, estimate 10 for g # 40g is a good filter for falling detection, no false positives in 20k minutes of driving - self.device_fell = abs(sensor_reading.acceleration.v[0] - 10) > 40 + self.device_fell = self.device_fell or (np.linalg.norm(np.array(sensor_reading.acceleration.v) - np.array([10, 0, 0])) > 40) self.acc_counter += 1 if self.acc_counter % SENSOR_DECIMATION == 0: From 7032a40717f46675697f0ba049956a3e1788e6f6 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Wed, 5 Aug 2020 10:46:26 -0700 Subject: [PATCH 562/656] Revert "persist falling test" This reverts commit 8cad9375d336ca5276f673296d0e64ff14efe0de. --- selfdrive/locationd/locationd.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 23ec56b879..369b68b887 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -149,7 +149,6 @@ class Localizer(): fix.posenetOK = not (std_spike and self.car_speed > 5) fix.deviceStable = not self.device_fell - self.device_fell = False #fix.gpsWeek = self.time.week #fix.gpsTimeOfWeek = self.time.tow @@ -246,7 +245,7 @@ class Localizer(): if sensor_reading.sensor == 1 and sensor_reading.type == 1: # check if device fell, estimate 10 for g # 40g is a good filter for falling detection, no false positives in 20k minutes of driving - self.device_fell = self.device_fell or (np.linalg.norm(np.array(sensor_reading.acceleration.v) - np.array([10, 0, 0])) > 40) + self.device_fell = abs(sensor_reading.acceleration.v[0] - 10) > 40 self.acc_counter += 1 if self.acc_counter % SENSOR_DECIMATION == 0: From f61dcb6e12447de7a84b547230b748b59b7424a4 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 5 Aug 2020 13:29:03 -0700 Subject: [PATCH 563/656] Cleanup updated (#1981) * remove dead code from updated * no short * simpler * simplify that * move that into the class * little more --- selfdrive/updated.py | 147 ++++++++++--------------------------------- 1 file changed, 32 insertions(+), 115 deletions(-) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index cca3d1b69c..e8ed98a15b 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -26,13 +26,11 @@ import os import datetime import subprocess import psutil -from stat import S_ISREG, S_ISDIR, S_ISLNK, S_IMODE, ST_MODE, ST_INO, ST_UID, ST_GID, ST_ATIME, ST_MTIME import shutil import signal from pathlib import Path import fcntl import threading -import time from cffi import FFI from common.basedir import BASEDIR @@ -47,25 +45,25 @@ OVERLAY_MERGED = os.path.join(STAGING_ROOT, "merged") FINALIZED = os.path.join(STAGING_ROOT, "finalized") NICE_LOW_PRIORITY = ["nice", "-n", "19"] -SHORT = os.getenv("SHORT") is not None -# Workaround for the EON/termux build of Python having os.link removed. +# Workaround for lack of os.link in the NEOS/termux python ffi = FFI() ffi.cdef("int link(const char *oldpath, const char *newpath);") libc = ffi.dlopen(None) +def link(src, dest): + return libc.link(src.encode(), dest.encode()) class WaitTimeHelper: - ready_event = threading.Event() - shutdown = False - def __init__(self): + self.ready_event = threading.Event() + self.shutdown = False signal.signal(signal.SIGTERM, self.graceful_shutdown) signal.signal(signal.SIGINT, self.graceful_shutdown) signal.signal(signal.SIGHUP, self.update_now) def graceful_shutdown(self, signum, frame): - # umount -f doesn't appear effective in avoiding "device busy" on EON, + # umount -f doesn't appear effective in avoiding "device busy" on NEOS, # so don't actually die until the next convenient opportunity in main(). cloudlog.info("caught SIGINT/SIGTERM, dismounting overlay at next opportunity") self.shutdown = True @@ -75,18 +73,8 @@ class WaitTimeHelper: cloudlog.info("caught SIGHUP, running update check immediately") self.ready_event.set() - -def wait_between_updates(ready_event, t=60*10): - ready_event.clear() - if SHORT: - ready_event.wait(timeout=10) - else: - ready_event.wait(timeout=t) - - -def link(src, dest): - # Workaround for the EON/termux build of Python having os.link removed. - return libc.link(src.encode(), dest.encode()) + def sleep(self, t): + self.ready_event.wait(timeout=t) def run(cmd, cwd=None): @@ -134,32 +122,28 @@ def dismount_ovfs(): def setup_git_options(cwd): - # We sync FS object atimes (which EON doesn't use) and mtimes, but ctimes + # We sync FS object atimes (which NEOS doesn't use) and mtimes, but ctimes # are outside user control. Make sure Git is set up to ignore system ctimes, # because they change when we make hard links during finalize. Otherwise, # there is a lot of unnecessary churn. This appears to be a common need on # OSX as well: https://www.git-tower.com/blog/make-git-rebase-safe-on-osx/ - try: - trustctime = run(["git", "config", "--get", "core.trustctime"], cwd) - trustctime_set = (trustctime.strip() == "false") - except subprocess.CalledProcessError: - trustctime_set = False - - if not trustctime_set: - cloudlog.info("Setting core.trustctime false") - run(["git", "config", "core.trustctime", "false"], cwd) - # We are temporarily using copytree to copy the directory, which also changes + # We are using copytree to copy the directory, which also changes # inode numbers. Ignore those changes too. - try: - checkstat = run(["git", "config", "--get", "core.checkStat"], cwd) - checkstat_set = (checkstat.strip() == "minimal") - except subprocess.CalledProcessError: - checkstat_set = False + git_cfg = [ + ("core.trustctime", "false"), + ("core.checkStat", "minimal"), + ] + for option, value in git_cfg: + try: + ret = run(["git", "config", "--get", option], cwd) + config_ok = (ret.strip() == value) + except subprocess.CalledProcessError: + config_ok = False - if not checkstat_set: - cloudlog.info("Setting core.checkState minimal") - run(["git", "config", "core.checkStat", "minimal"], cwd) + if not config_ok: + cloudlog.info(f"Setting git '{option}' to '{value}'") + run(["git", "config", option, value], cwd) def init_ovfs(): @@ -181,7 +165,7 @@ def init_ovfs(): if os.path.isfile(os.path.join(BASEDIR, ".overlay_consistent")): os.remove(os.path.join(BASEDIR, ".overlay_consistent")) - # Leave a timestamped canary in BASEDIR to check at startup. The EON clock + # Leave a timestamped canary in BASEDIR to check at startup. The device clock # should be correct by the time we get here. If the init file disappears, or # critical mtimes in BASEDIR are newer than .overlay_init, continue.sh can # assume that BASEDIR has used for local development or otherwise modified, @@ -192,74 +176,7 @@ def init_ovfs(): run(["mount", "-t", "overlay", "-o", overlay_opts, "none", OVERLAY_MERGED]) -def inodes_in_tree(search_dir): - """Given a search root, produce a dictionary mapping of inodes to relative - pathnames of regular files (no directories, symlinks, or special files).""" - inode_map = {} - for root, _, files in os.walk(search_dir, topdown=True): - for file_name in files: - full_path_name = os.path.join(root, file_name) - st = os.lstat(full_path_name) - if S_ISREG(st[ST_MODE]): - inode_map[st[ST_INO]] = full_path_name - return inode_map - - -def dup_ovfs_object(inode_map, source_obj, target_dir): - """Given a relative pathname to copy, and a new target root, duplicate the - source object in the target root, using hardlinks for regular files.""" - - source_full_path = os.path.join(OVERLAY_MERGED, source_obj) - st = os.lstat(source_full_path) - target_full_path = os.path.join(target_dir, source_obj) - - if S_ISREG(st[ST_MODE]): - # Hardlink all regular files; ownership and permissions are shared. - link(inode_map[st[ST_INO]], target_full_path) - else: - # Recreate all directories and symlinks; copy ownership and permissions. - if S_ISDIR(st[ST_MODE]): - os.mkdir(os.path.join(FINALIZED, source_obj), S_IMODE(st[ST_MODE])) - elif S_ISLNK(st[ST_MODE]): - os.symlink(os.readlink(source_full_path), target_full_path) - os.chmod(target_full_path, S_IMODE(st[ST_MODE]), follow_symlinks=False) - else: - # Ran into a FIFO, socket, etc. Should not happen in OP install dir. - # Ignore without copying for the time being; revisit later if needed. - cloudlog.error("can't copy this file type: %s" % source_full_path) - os.chown(target_full_path, st[ST_UID], st[ST_GID], follow_symlinks=False) - - # Sync target mtimes to the cached lstat() value from each source object. - # Restores shared inode mtimes after linking, fixes symlinks and dirs. - os.utime(target_full_path, (st[ST_ATIME], st[ST_MTIME]), follow_symlinks=False) - - -def finalize_from_ovfs_hardlink(): - """Take the current OverlayFS merged view and finalize a copy outside of - OverlayFS, ready to be swapped-in at BASEDIR. Copy using hardlinks""" - - cloudlog.info("creating finalized version of the overlay") - - # The "copy" is done with hardlinks, but since the OverlayFS merge looks - # like a different filesystem, and hardlinks can't cross filesystems, we - # have to borrow a source pathname from the upper or lower layer. - inode_map = inodes_in_tree(BASEDIR) - inode_map.update(inodes_in_tree(OVERLAY_UPPER)) - - shutil.rmtree(FINALIZED) - os.umask(0o077) - os.mkdir(FINALIZED) - for root, dirs, files in os.walk(OVERLAY_MERGED, topdown=True): - for obj_name in dirs: - relative_path_name = os.path.relpath(os.path.join(root, obj_name), OVERLAY_MERGED) - dup_ovfs_object(inode_map, relative_path_name, FINALIZED) - for obj_name in files: - relative_path_name = os.path.relpath(os.path.join(root, obj_name), OVERLAY_MERGED) - dup_ovfs_object(inode_map, relative_path_name, FINALIZED) - cloudlog.info("done finalizing overlay") - - -def finalize_from_ovfs_copy(): +def finalize_from_ovfs(): """Take the current OverlayFS merged view and finalize a copy outside of OverlayFS, ready to be swapped-in at BASEDIR. Copy using shutil.copytree""" @@ -301,7 +218,7 @@ def attempt_update(): # activated later if the finalize step is interrupted remove_consistent_flag() - finalize_from_ovfs_copy() + finalize_from_ovfs() # Make sure the validity flag lands on disk LAST, only when the local git # repo and OP install are in a consistent state. @@ -322,7 +239,7 @@ def main(): if params.get("DisableUpdates") == b"1": raise RuntimeError("updates are disabled by param") - if not os.geteuid() == 0: + if os.geteuid() != 0: raise RuntimeError("updated must be launched as root!") # Set low io priority @@ -336,19 +253,19 @@ def main(): except IOError: raise RuntimeError("couldn't get overlay lock; is another updated running?") - # Wait a short time before our first update attempt - # Avoids race with IsOffroad not being set, reduces manager startup load - time.sleep(30) + # Wait for IsOffroad to be set before our first update attempt wait_helper = WaitTimeHelper() + wait_helper.sleep(30) while not wait_helper.shutdown: update_failed_count += 1 + wait_helper.ready_event.clear() # Check for internet every 30s time_wrong = datetime.datetime.utcnow().year < 2019 ping_failed = subprocess.call(["ping", "-W", "4", "-c", "1", "8.8.8.8"]) if ping_failed or time_wrong: - wait_between_updates(wait_helper.ready_event, t=30) + wait_helper.sleep(30) continue # Attempt an update @@ -386,7 +303,7 @@ def main(): cloudlog.exception("uncaught updated exception, shouldn't happen") params.put("UpdateFailedCount", str(update_failed_count)) - wait_between_updates(wait_helper.ready_event) + wait_helper.sleep(60*10) # We've been signaled to shut down dismount_ovfs() From c1e7b761a9dab798f5a678cf8317bae9e3b50d69 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 6 Aug 2020 04:39:03 +0800 Subject: [PATCH 564/656] camerad: cache rgb_roi_buf&conv_result (#1979) lgtm --- selfdrive/camerad/main.cc | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index 6ad52880ef..d9c7df042a 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -345,6 +345,11 @@ void* processing_thread(void *arg) { err = set_realtime_priority(51); LOG("setpriority returns %d", err); +#if defined(QCOM) && !defined(QCOM_REPLAY) + std::unique_ptr rgb_roi_buf = std::make_unique((s->rgb_width/NUM_SEGMENTS_X)*(s->rgb_height/NUM_SEGMENTS_Y)*3); + std::unique_ptr conv_result = std::make_unique((s->rgb_width/NUM_SEGMENTS_X)*(s->rgb_height/NUM_SEGMENTS_Y)); +#endif + // init cl stuff #ifdef __APPLE__ cl_command_queue q = clCreateCommandQueue(s->context, s->device_id, 0, &err); @@ -416,13 +421,12 @@ void* processing_thread(void *arg) { /*double t10 = millis_since_boot();*/ // cache rgb roi and write to cl - uint8_t *rgb_roi_buf = new uint8_t[(s->rgb_width/NUM_SEGMENTS_X)*(s->rgb_height/NUM_SEGMENTS_Y)*3]; int roi_id = cnt % ((ROI_X_MAX-ROI_X_MIN+1)*(ROI_Y_MAX-ROI_Y_MIN+1)); // rolling roi int roi_x_offset = roi_id % (ROI_X_MAX-ROI_X_MIN+1); int roi_y_offset = roi_id / (ROI_X_MAX-ROI_X_MIN+1); for (int r=0;r<(s->rgb_height/NUM_SEGMENTS_Y);r++) { - memcpy(rgb_roi_buf + r * (s->rgb_width/NUM_SEGMENTS_X) * 3, + memcpy(rgb_roi_buf.get() + r * (s->rgb_width/NUM_SEGMENTS_X) * 3, (uint8_t *) s->rgb_bufs[rgb_idx].addr + \ (ROI_Y_MIN + roi_y_offset) * s->rgb_height/NUM_SEGMENTS_Y * FULL_STRIDE_X * 3 + \ (ROI_X_MIN + roi_x_offset) * s->rgb_width/NUM_SEGMENTS_X * 3 + r * FULL_STRIDE_X * 3, @@ -430,7 +434,7 @@ void* processing_thread(void *arg) { } err = clEnqueueWriteBuffer (q, s->rgb_conv_roi_cl, true, 0, - s->rgb_width/NUM_SEGMENTS_X * s->rgb_height/NUM_SEGMENTS_Y * 3 * sizeof(uint8_t), rgb_roi_buf, 0, 0, 0); + s->rgb_width/NUM_SEGMENTS_X * s->rgb_height/NUM_SEGMENTS_Y * 3 * sizeof(uint8_t), rgb_roi_buf.get(), 0, 0, 0); assert(err == 0); /*double t11 = millis_since_boot(); @@ -453,24 +457,20 @@ void* processing_thread(void *arg) { clWaitForEvents(1, &conv_event); clReleaseEvent(conv_event); - int16_t *conv_result = new int16_t[(s->rgb_width/NUM_SEGMENTS_X)*(s->rgb_height/NUM_SEGMENTS_Y)]; err = clEnqueueReadBuffer(q, s->rgb_conv_result_cl, true, 0, - s->rgb_width/NUM_SEGMENTS_X * s->rgb_height/NUM_SEGMENTS_Y * sizeof(int16_t), conv_result, 0, 0, 0); + s->rgb_width/NUM_SEGMENTS_X * s->rgb_height/NUM_SEGMENTS_Y * sizeof(int16_t), conv_result.get(), 0, 0, 0); assert(err == 0); /*t11 = millis_since_boot(); printf("conv time: %f ms\n", t11 - t10); t10 = millis_since_boot();*/ - get_lapmap_one(conv_result, &s->lapres[roi_id], s->rgb_width/NUM_SEGMENTS_X, s->rgb_height/NUM_SEGMENTS_Y); + get_lapmap_one(conv_result.get(), &s->lapres[roi_id], s->rgb_width/NUM_SEGMENTS_X, s->rgb_height/NUM_SEGMENTS_Y); /*t11 = millis_since_boot(); printf("pool time: %f ms\n", t11 - t10); t10 = millis_since_boot();*/ - delete [] rgb_roi_buf; - delete [] conv_result; - /*t11 = millis_since_boot(); printf("process time: %f ms\n ----- \n", t11 - t10); t10 = millis_since_boot();*/ From 687afa9687c347fe1473d9d6ae3e2e3634b682df Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Wed, 5 Aug 2020 13:45:55 -0700 Subject: [PATCH 565/656] wrong units --- selfdrive/locationd/locationd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 369b68b887..c222e20e6e 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -244,7 +244,7 @@ class Localizer(): # Accelerometer if sensor_reading.sensor == 1 and sensor_reading.type == 1: # check if device fell, estimate 10 for g - # 40g is a good filter for falling detection, no false positives in 20k minutes of driving + # 40m/s**2 is a good filter for falling detection, no false positives in 20k minutes of driving self.device_fell = abs(sensor_reading.acceleration.v[0] - 10) > 40 self.acc_counter += 1 From 90d5383354365f58415cc5e99e92c4010394832c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 5 Aug 2020 20:21:04 -0700 Subject: [PATCH 566/656] Setup PC testing in Jenkins (#1984) * build openpilot docker container in jenkins * use cache * run all stages in parallel * move device tests * wrap in stages * it's docker * doesn't work, but jenkins should cache the image * steps * disable phone tests for now * we're root * enable everything * clean up our mess * skip checkout * need a plugin for that * remove that * parallel * Revert "parallel" This reverts commit e3e5af9dc9db692d1b5552012d62393a5b8520dd. * this is ugly * Revert "this is ugly" This reverts commit e83995935294584e264a8fcb3d08bcf7d9305434. --- Jenkinsfile | 117 ++++++++++++++++++++++++++++++++-------------------- 1 file changed, 72 insertions(+), 45 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index b77891bb75..0fd2b00a4d 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -29,75 +29,102 @@ def phone_steps(String device_type, steps) { } pipeline { - agent { - docker { - image 'python:3.7.3' - args '--user=root' - } - } + agent none environment { COMMA_JWT = credentials('athena-test-jwt') TEST_DIR = "/data/openpilot" } stages { - - stage('Release Build') { - when { - branch 'devel-staging' - } - steps { - phone_steps("eon-build", [ - ["build release2-staging and dashcam-staging", "cd release && PUSH=1 ./build_release2.sh"], - ]) - } - } - - stage('On-device Tests') { + stage('openpilot tests') { when { not { anyOf { - branch 'master-ci'; branch 'devel'; branch 'devel-staging'; branch 'release2'; branch 'release2-staging'; branch 'dashcam'; branch 'dashcam-staging' + branch 'master-ci'; branch 'devel'; branch 'release2'; branch 'release2-staging'; branch 'dashcam'; branch 'dashcam-staging' } } } - parallel { - stage('Build') { - environment { - CI_PUSH = "${env.BRANCH_NAME == 'master' ? 'master-ci' : ' '}" + stage('PC tests') { + agent { + dockerfile { + filename 'Dockerfile.openpilot' + args '--privileged --shm-size=1G --user=root' + } } - steps { - phone_steps("eon", [ - ["build devel", "cd release && CI_PUSH=${env.CI_PUSH} ./build_devel.sh"], - ["test openpilot", "nosetests -s selfdrive/test/test_openpilot.py"], - //["test cpu usage", "cd selfdrive/test/ && ./test_cpu_usage.py"], - ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], - ]) + stages { + stage('Build') { + steps { + sh 'scons -j$(nproc)' + } + } + } + post { + always { + // fix permissions since docker runs as another user + sh "chmod -R 777 ." + } } } - stage('Replay Tests') { - steps { - phone_steps("eon2", [ - ["camerad/modeld replay", "cd selfdrive/test/process_replay && ./camera_replay.py"], - ]) + stage('On-device Tests') { + agent { + docker { + image 'python:3.7.3' + args '--user=root' + } } - } + stages { + + stage('Release Build') { + when { + branch 'devel-staging' + } + steps { + phone_steps("eon-build", [ + ["build release2-staging and dashcam-staging", "cd release && PUSH=1 ./build_release2.sh"], + ]) + } + } + + stage('Devel Build') { + environment { + CI_PUSH = "${env.BRANCH_NAME == 'master' ? 'master-ci' : ' '}" + } + steps { + phone_steps("eon", [ + ["build devel", "cd release && CI_PUSH=${env.CI_PUSH} ./build_devel.sh"], + ["test openpilot", "nosetests -s selfdrive/test/test_openpilot.py"], + //["test cpu usage", "cd selfdrive/test/ && ./test_cpu_usage.py"], + ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], + ]) + } + } + + stage('Replay Tests') { + steps { + phone_steps("eon2", [ + ["camerad/modeld replay", "cd selfdrive/test/process_replay && ./camera_replay.py"], + ]) + } + } + + stage('HW Tests') { + steps { + phone_steps("eon", [ + ["build cereal", "SCONS_CACHE=1 scons -j4 cereal/"], + ["test sounds", "nosetests -s selfdrive/test/test_sounds.py"], + ["test boardd loopback", "nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"], + ]) + } + } - stage('HW Tests') { - steps { - phone_steps("eon", [ - ["build cereal", "SCONS_CACHE=1 scons -j4 cereal/"], - ["test sounds", "nosetests -s selfdrive/test/test_sounds.py"], - ["test boardd loopback", "nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"], - ]) } + } } } - } } From 9a8c43ac4a03c88ccb18aa9f3b7fcdfcab29539f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 6 Aug 2020 00:08:46 -0700 Subject: [PATCH 567/656] add CI dependency for new tests --- Dockerfile.openpilot | 1 + 1 file changed, 1 insertion(+) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 4de954141f..aff59903ba 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -14,6 +14,7 @@ RUN apt-get update && apt-get install -y --no-install-recommends \ curl \ ffmpeg \ git \ + iputils-ping \ libarchive-dev \ libbz2-dev \ libcurl4-openssl-dev \ From a115366dddc076bb186219d33a7565712465b226 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 6 Aug 2020 12:49:11 -0700 Subject: [PATCH 568/656] Improve update reliability and responsiveness (#1986) * handle orphaned git lock * trigger update after going offroad * git ping --- launch_chffrplus.sh | 6 +++++- selfdrive/manager.py | 15 +++++++++++++++ selfdrive/updated.py | 2 +- 3 files changed, 21 insertions(+), 2 deletions(-) diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index ae1660411b..1a1c41706f 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -14,12 +14,17 @@ if [ -z "$PASSIVE" ]; then export PASSIVE="1" fi +DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" + STAGING_ROOT="/data/safe_staging" function launch { # Wifi scan wpa_cli IFNAME=wlan0 SCAN + # Remove orphaned git lock if it exists on boot + [ -f "$DIR/.git/index.lock" ] && rm -f $DIR/.git/index.lock + # Check to see if there's a valid overlay-based update available. Conditions # are as follows: # @@ -75,7 +80,6 @@ function launch { [ -d "/proc/irq/733" ] && echo 3 > /proc/irq/733/smp_affinity_list # USB for LeEco [ -d "/proc/irq/736" ] && echo 3 > /proc/irq/736/smp_affinity_list # USB for OP3T - DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" # Remove old NEOS update file # TODO: move this code to the updater diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 62d4827ca7..9e08bece59 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -389,6 +389,14 @@ def cleanup_all_processes(signal, frame): kill_managed_process(name) cloudlog.info("everything is dead") + +def send_managed_process_signal(name, sig): + if name not in running or name not in managed_processes: + return + cloudlog.info(f"sending signal {sig} to {name}") + os.kill(running[name].pid, sig) + + # ****************** run loop ****************** def manager_init(should_register=True): @@ -457,6 +465,7 @@ def manager_thread(): for k in os.getenv("BLOCK").split(","): del managed_processes[k] + started_prev = False logger_dead = False while 1: @@ -496,6 +505,12 @@ def manager_thread(): else: kill_managed_process(p) + # trigger an update after going offroad + if started_prev: + send_managed_process_signal("updated", signal.SIGHUP) + + started_prev = msg.thermal.started + # check the status of all processes, did any of them die? running_list = ["%s%s\u001b[0m" % ("\u001b[32m" if running[p].is_alive() else "\u001b[31m", p) for p in running] cloudlog.debug(' '.join(running_list)) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index e8ed98a15b..21c0ec9806 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -263,7 +263,7 @@ def main(): # Check for internet every 30s time_wrong = datetime.datetime.utcnow().year < 2019 - ping_failed = subprocess.call(["ping", "-W", "4", "-c", "1", "8.8.8.8"]) + ping_failed = os.system("git ls-remote --tags --quiet") != 0 if ping_failed or time_wrong: wait_helper.sleep(30) continue From 20162f7a4a1d1054e816a67735b3a2cebf5498b9 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 6 Aug 2020 13:23:20 -0700 Subject: [PATCH 569/656] fix counter mismatch in sim --- tools/sim/lib/can.py | 1 - 1 file changed, 1 deletion(-) diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index 9bb205a126..7ae7f3f7e8 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -38,7 +38,6 @@ def can_function(pm, speed, angle, idx, cruise_button=0, is_engaged=False): msg.append(packer.make_can_msg("SEATBELT_STATUS", 0, {"SEATBELT_DRIVER_LATCHED": 1}, idx)) msg.append(packer.make_can_msg("STEER_STATUS", 0, {}, idx)) msg.append(packer.make_can_msg("STEERING_SENSORS", 0, {"STEER_ANGLE": angle_to_sangle(angle)}, idx)) - msg.append(packer.make_can_msg("POWERTRAIN_DATA", 0, {}, idx)) msg.append(packer.make_can_msg("VSA_STATUS", 0, {}, idx)) msg.append(packer.make_can_msg("STANDSTILL", 0, {}, idx)) msg.append(packer.make_can_msg("STEER_MOTOR_TORQUE", 0, {}, idx)) From 6d645b4ce9445e7aa9ef95b3c453eb811e7ca015 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 6 Aug 2020 13:26:25 -0700 Subject: [PATCH 570/656] Scripts for containerized CARLA (#1987) * run carla in container * launch script * fix launch script * update carla --- tools/sim/launch_openpilot.sh | 7 +++++++ tools/sim/start_carla_docker.sh | 5 +++++ 2 files changed, 12 insertions(+) create mode 100755 tools/sim/launch_openpilot.sh create mode 100755 tools/sim/start_carla_docker.sh diff --git a/tools/sim/launch_openpilot.sh b/tools/sim/launch_openpilot.sh new file mode 100755 index 0000000000..207997c867 --- /dev/null +++ b/tools/sim/launch_openpilot.sh @@ -0,0 +1,7 @@ +#!/bin/bash + +export PASSIVE="0" +export NOBOARD="1" + +DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" +cd ../../selfdrive && ./manager.py diff --git a/tools/sim/start_carla_docker.sh b/tools/sim/start_carla_docker.sh new file mode 100755 index 0000000000..46619d5d6a --- /dev/null +++ b/tools/sim/start_carla_docker.sh @@ -0,0 +1,5 @@ +#!/bin/bash + +# Requires nvidia docker - https://github.com/NVIDIA/nvidia-docker +docker pull carlasim/carla:0.9.7 +docker run -p 2000-2002:2000-2002 --runtime=nvidia --gpus all carlasim/carla:0.9.7 From df78c9d4dfe9cc5ed1409b46b1b11611ed5a721a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 6 Aug 2020 13:57:01 -0700 Subject: [PATCH 571/656] remove dead lines from calibrationd --- selfdrive/locationd/calibrationd.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index e95f00c2c9..9f02c59722 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -170,8 +170,6 @@ def calibrationd_thread(sm=None, pm=None): if DEBUG and new_vp is not None: print('got new vp', new_vp) - # decimate outputs for efficiency - def main(sm=None, pm=None): calibrationd_thread(sm, pm) From c8f5281c4d18ee68dbc5d194374bad7cd1a8a4ef Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 6 Aug 2020 14:34:42 -0700 Subject: [PATCH 572/656] second segment is ok for car unit tests --- selfdrive/test/test_models.py | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/selfdrive/test/test_models.py b/selfdrive/test/test_models.py index c06bdf6e04..3a95136b52 100755 --- a/selfdrive/test/test_models.py +++ b/selfdrive/test/test_models.py @@ -45,10 +45,13 @@ class TestCarModel(unittest.TestCase): else: raise Exception(f"missing test route for car {cls.car_model}") - try: - lr = LogReader(get_url(ROUTES[cls.car_model], 1)) - except Exception: - lr = LogReader(get_url(ROUTES[cls.car_model], 0)) + for seg in [2, 1, 0]: + try: + lr = LogReader(get_url(ROUTES[cls.car_model], seg)) + break + except Exception: + if seg == 0: + raise has_relay = False can_msgs = [] From 85a7ceaf079ed6c8cb804403f33706a386ca9b51 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 6 Aug 2020 14:46:19 -0700 Subject: [PATCH 573/656] persist falling until message sent (#1982) Co-authored-by: Adeeb Shihadeh --- selfdrive/locationd/locationd.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index c222e20e6e..be78176844 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -149,6 +149,7 @@ class Localizer(): fix.posenetOK = not (std_spike and self.car_speed > 5) fix.deviceStable = not self.device_fell + self.device_fell = False #fix.gpsWeek = self.time.week #fix.gpsTimeOfWeek = self.time.tow @@ -245,7 +246,7 @@ class Localizer(): if sensor_reading.sensor == 1 and sensor_reading.type == 1: # check if device fell, estimate 10 for g # 40m/s**2 is a good filter for falling detection, no false positives in 20k minutes of driving - self.device_fell = abs(sensor_reading.acceleration.v[0] - 10) > 40 + self.device_fell = self.device_fell or (np.linalg.norm(np.array(sensor_reading.acceleration.v) - np.array([10, 0, 0])) > 40) self.acc_counter += 1 if self.acc_counter % SENSOR_DECIMATION == 0: From d097abeb2130fc841571b14551eeea2acaa12296 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 6 Aug 2020 14:47:17 -0700 Subject: [PATCH 574/656] Track calib spread (#1988) * add calib spread metric * add field * needs to be array * update refs * log valid blocks too * update refs Co-authored-by: Adeeb Shihadeh --- cereal | 2 +- selfdrive/locationd/calibrationd.py | 8 ++++++++ selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 10 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 61d7488e55..d66afca4ac 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 61d7488e55fcaa3760d9ccc9d6589b30cbe4a6c1 +Subproject commit d66afca4ac316456711cb80c8e8e2fe91431e1e2 diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 9f02c59722..a27e284a9c 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -126,13 +126,21 @@ class Calibrator(): def send_data(self, pm): calib = get_calib_from_vp(self.vp) + if self.valid_blocks > 0: + max_vp_calib = np.array(get_calib_from_vp(np.max(self.vps[:self.valid_blocks], axis=0))) + min_vp_calib = np.array(get_calib_from_vp(np.min(self.vps[:self.valid_blocks], axis=0))) + calib_spread = np.abs(max_vp_calib - min_vp_calib) + else: + calib_spread = np.zeros(3) extrinsic_matrix = get_view_frame_from_road_frame(0, calib[1], calib[2], model_height) cal_send = messaging.new_message('liveCalibration') + cal_send.liveCalibration.validBlocks = self.valid_blocks cal_send.liveCalibration.calStatus = self.cal_status cal_send.liveCalibration.calPerc = min(100 * (self.valid_blocks * BLOCK_SIZE + self.idx) // (INPUTS_NEEDED * BLOCK_SIZE), 100) cal_send.liveCalibration.extrinsicMatrix = [float(x) for x in extrinsic_matrix.flatten()] cal_send.liveCalibration.rpyCalib = [float(x) for x in calib] + cal_send.liveCalibration.rpyCalibSpread = [float(x) for x in calib_spread] pm.send('liveCalibration', cal_send) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 8b8abe7eca..568aab2b73 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -3e8932a5dc0281b00463d40a5435f659259591c4 \ No newline at end of file +158743f002e82b62a67c6b91308db01d715f1643 \ No newline at end of file From fb41b984b0ed48da7c1c5d5687fd7485f66259e4 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 7 Aug 2020 06:44:26 +0800 Subject: [PATCH 575/656] release opencl objects (#1978) --- selfdrive/camerad/main.cc | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index d9c7df042a..aef7925536 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -332,6 +332,7 @@ void* frontview_thread(void *arg) { //double t2 = millis_since_boot(); //LOGD("front process: %.2fms", t2-t1); } + clReleaseCommandQueue(q); return NULL; } @@ -670,6 +671,7 @@ void* processing_thread(void *arg) { LOGD("queued: %.2fms, yuv: %.2f, | processing: %.3fms", (t2-t1), (yt2-yt1), (t5-t1)); } + clReleaseCommandQueue(q); return NULL; } @@ -1175,25 +1177,33 @@ void free_buffers(VisionState *s) { // free bufs for (int i=0; icamera_bufs[i]); + visionbuf_free(&s->front_camera_bufs[i]); visionbuf_free(&s->focus_bufs[i]); visionbuf_free(&s->stats_bufs[i]); } - for (int i=0; ifront_camera_bufs[i]); - } - for (int i=0; irgb_bufs[i]); - } - - for (int i=0; irgb_front_bufs[i]); } for (int i=0; iyuv_ion[i]); + visionbuf_free(&s->yuv_front_ion[i]); } + + clReleaseMemObject(s->rgb_conv_roi_cl); + clReleaseMemObject(s->rgb_conv_result_cl); + clReleaseMemObject(s->rgb_conv_filter_cl); + + clReleaseProgram(s->prg_debayer_rear); + clReleaseProgram(s->prg_debayer_front); + clReleaseKernel(s->krnl_debayer_rear); + clReleaseKernel(s->krnl_debayer_front); + + clReleaseProgram(s->prg_rgb_laplacian); + clReleaseKernel(s->krnl_rgb_laplacian); + } void party(VisionState *s) { From 0fd763f90256a7b1fce389bd69aff47e37e394a2 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Thu, 6 Aug 2020 16:39:06 -0700 Subject: [PATCH 576/656] Add Camry 2020 camera fw --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 0e4e717a62..93a98e9e67 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -341,6 +341,7 @@ FW_VERSIONS = { b'8646F0603400 ', b'8646F0605000 ', b'8646F0606000 ', + b'8646F0606100 ', ], }, CAR.CAMRYH: { From fe18a014c7845b5e81738b0be716d256aeb00d78 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 6 Aug 2020 21:49:05 -0700 Subject: [PATCH 577/656] Updater tests (#1974) * refactor exit handling * test update * more reliable? * better * init git in CI * testy tester * CI should work * test overlay reinit * only one * still need to fix loop test * more patience * more patience in CI * no ping in CI * this is cleaner * need to run these in jenkins * clean up * run in jenkins * fix test file path * it's a git repo now * no commit * reinit * remove duplicate * why not git * la * git status * pythonpath * fix * no CI fro now * check overlay consistent * more tests * make more changes in the update commit * sample * no k --- selfdrive/test/test_updated.py | 256 +++++++++++++++++++++++++++++++++ selfdrive/updated.py | 51 ++++--- 2 files changed, 280 insertions(+), 27 deletions(-) create mode 100755 selfdrive/test/test_updated.py diff --git a/selfdrive/test/test_updated.py b/selfdrive/test/test_updated.py new file mode 100755 index 0000000000..08eca5bd23 --- /dev/null +++ b/selfdrive/test/test_updated.py @@ -0,0 +1,256 @@ +#!/usr/bin/env python3 +import datetime +import os +import time +import tempfile +import unittest +import shutil +import signal +import subprocess +import random + +from common.basedir import BASEDIR +from common.params import Params + + +class TestUpdater(unittest.TestCase): + + def setUp(self): + self.updated_proc = None + + self.tmp_dir = tempfile.TemporaryDirectory() + org_dir = os.path.join(self.tmp_dir.name, "commaai") + + self.basedir = os.path.join(org_dir, "openpilot") + self.git_remote_dir = os.path.join(org_dir, "openpilot_remote") + self.staging_dir = os.path.join(org_dir, "safe_staging") + for d in [org_dir, self.basedir, self.git_remote_dir, self.staging_dir]: + os.mkdir(d) + + self.upper_dir = os.path.join(self.staging_dir, "upper") + self.merged_dir = os.path.join(self.staging_dir, "merged") + self.finalized_dir = os.path.join(self.staging_dir, "finalized") + + # setup local submodule remotes + submodules = subprocess.check_output("git submodule --quiet foreach 'echo $name'", + shell=True, cwd=BASEDIR, encoding='utf8').split() + for s in submodules: + sub_path = os.path.join(org_dir, s.split("_repo")[0]) + self._run(f"git clone {s} {sub_path}.git", cwd=BASEDIR) + + # setup two git repos, a remote and one we'll run updated in + self._run([ + f"git clone {BASEDIR} {self.git_remote_dir}", + f"git clone {self.git_remote_dir} {self.basedir}", + f"cd {self.basedir} && git submodule init && git submodule update", + f"cd {self.basedir} && scons -j{os.cpu_count()} cereal" + ]) + + self.params = Params(db=os.path.join(self.basedir, "persist/params")) + self.params.clear_all() + os.sync() + + def tearDown(self): + try: + if self.updated_proc is not None: + self.updated_proc.terminate() + self.updated_proc.wait(30) + except Exception as e: + print(e) + self.tmp_dir.cleanup() + + + # *** test helpers *** + + + def _run(self, cmd, cwd=None): + if not isinstance(cmd, list): + cmd = (cmd,) + + for c in cmd: + subprocess.check_output(c, cwd=cwd, shell=True) + + def _get_updated_proc(self): + os.environ["PYTHONPATH"] = self.basedir + os.environ["GIT_AUTHOR_NAME"] = "testy tester" + os.environ["GIT_COMMITTER_NAME"] = "testy tester" + os.environ["GIT_AUTHOR_EMAIL"] = "testy@tester.test" + os.environ["GIT_COMMITTER_EMAIL"] = "testy@tester.test" + os.environ["UPDATER_TEST_IP"] = "localhost" + os.environ["UPDATER_LOCK_FILE"] = os.path.join(self.tmp_dir.name, "updater.lock") + os.environ["UPDATER_STAGING_ROOT"] = self.staging_dir + updated_path = os.path.join(self.basedir, "selfdrive/updated.py") + return subprocess.Popen(updated_path, env=os.environ) + + def _start_updater(self, offroad=True, nosleep=False): + self.params.put("IsOffroad", "1" if offroad else "0") + self.updated_proc = self._get_updated_proc() + if not nosleep: + time.sleep(1) + + def _update_now(self): + self.updated_proc.send_signal(signal.SIGHUP) + + # TODO: this should be implemented in params + def _read_param(self, key, timeout=1): + ret = None + start_time = time.monotonic() + while ret is None: + ret = self.params.get(key, encoding='utf8') + if time.monotonic() - start_time > timeout: + break + time.sleep(0.01) + return ret + + def _wait_for_update(self, timeout=30, clear_param=False): + if clear_param: + self.params.delete("LastUpdateTime") + + self._update_now() + t = self._read_param("LastUpdateTime", timeout=timeout) + if t is None: + raise Exception("timed out waiting for update to complate") + + def _make_commit(self): + all_dirs, all_files = [], [] + for root, dirs, files in os.walk(self.git_remote_dir): + if ".git" in root: + continue + for d in dirs: + all_dirs.append(os.path.join(root, d)) + for f in files: + all_files.append(os.path.join(root, f)) + + # make a new dir and some new files + new_dir = os.path.join(self.git_remote_dir, "this_is_a_new_dir") + os.mkdir(new_dir) + for _ in range(random.randrange(5, 30)): + for d in (new_dir, random.choice(all_dirs)): + with tempfile.NamedTemporaryFile(dir=d, delete=False) as f: + f.write(os.urandom(random.randrange(1, 1000000))) + + # modify some files + for f in random.sample(all_files, random.randrange(5, 50)): + with open(f, "w+") as ff: + txt = ff.readlines() + ff.seek(0) + for line in txt: + ff.write(line[::-1]) + + # remove some files + for f in random.sample(all_files, random.randrange(5, 50)): + os.remove(f) + + # remove some dirs + for d in random.sample(all_dirs, random.randrange(1, 10)): + shutil.rmtree(d) + + # commit the changes + self._run([ + "git add -A", + "git commit -m 'an update'", + ], cwd=self.git_remote_dir) + + def _check_update_state(self, update_available): + # make sure LastUpdateTime is recent + t = self._read_param("LastUpdateTime") + last_update_time = datetime.datetime.fromisoformat(t) + td = datetime.datetime.utcnow() - last_update_time + self.assertLess(td.total_seconds(), 10) + self.params.delete("LastUpdateTime") + + # wait a bit for the rest of the params to be written + time.sleep(0.1) + + # check params + update = self._read_param("UpdateAvailable") + self.assertEqual(update == "1", update_available, f"UpdateAvailable: {repr(update)}") + self.assertEqual(self._read_param("UpdateFailedCount"), "0") + + # TODO: check that the finalized update actually matches remote + # check the .overlay_init and .overlay_consistent flags + self.assertTrue(os.path.isfile(os.path.join(self.basedir, ".overlay_init"))) + self.assertEqual(os.path.isfile(os.path.join(self.finalized_dir, ".overlay_consistent")), update_available) + + + # *** test cases *** + + + # Run updated for 100 cycles with no update + def test_no_update(self): + self._start_updater() + for _ in range(100): + self._wait_for_update(clear_param=True) + self._check_update_state(False) + + # Let the updater run with no update for a cycle, then write an update + def test_update(self): + self._start_updater() + + # run for a cycle with no update + self._wait_for_update(clear_param=True) + self._check_update_state(False) + + # write an update to our remote + self._make_commit() + + # run for a cycle to get the update + self._wait_for_update(timeout=60, clear_param=True) + self._check_update_state(True) + + # run another cycle with no update + self._wait_for_update(clear_param=True) + self._check_update_state(True) + + # Let the updater run for 10 cycles, and write an update every cycle + @unittest.skip("need to make this faster") + def test_update_loop(self): + self._start_updater() + + # run for a cycle with no update + self._wait_for_update(clear_param=True) + for _ in range(10): + time.sleep(0.5) + self._make_commit() + self._wait_for_update(timeout=90, clear_param=True) + self._check_update_state(True) + + # Test overlay re-creation after tracking a new file in basedir's git + def test_overlay_reinit(self): + self._start_updater() + + overlay_init_fn = os.path.join(self.basedir, ".overlay_init") + + # run for a cycle with no update + self._wait_for_update(clear_param=True) + self.params.delete("LastUpdateTime") + first_mtime = os.path.getmtime(overlay_init_fn) + + # touch a file in the basedir + self._run("touch new_file && git add new_file", cwd=self.basedir) + + # run another cycle, should have a new mtime + self._wait_for_update(clear_param=True) + second_mtime = os.path.getmtime(overlay_init_fn) + self.assertTrue(first_mtime != second_mtime) + + # run another cycle, mtime should be same as last cycle + self._wait_for_update(clear_param=True) + new_mtime = os.path.getmtime(overlay_init_fn) + self.assertTrue(second_mtime == new_mtime) + + # Make sure updated exits if another instance is running + def test_multiple_instances(self): + # start updated and let it run for a cycle + self._start_updater() + time.sleep(1) + self._wait_for_update(clear_param=True) + + # start another instance + second_updated = self._get_updated_proc() + ret_code = second_updated.wait(timeout=5) + self.assertTrue(ret_code is not None) + + +if __name__ == "__main__": + unittest.main() diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 21c0ec9806..59ec7d8802 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -28,16 +28,18 @@ import subprocess import psutil import shutil import signal -from pathlib import Path import fcntl import threading from cffi import FFI +from pathlib import Path from common.basedir import BASEDIR from common.params import Params from selfdrive.swaglog import cloudlog -STAGING_ROOT = "/data/safe_staging" +TEST_IP = os.getenv("UPDATER_TEST_IP", "8.8.8.8") +LOCK_FILE = os.getenv("UPDATER_LOCK_FILE", "/tmp/safe_staging_overlay.lock") +STAGING_ROOT = os.getenv("UPDATER_STAGING_ROOT", "/data/safe_staging") OVERLAY_UPPER = os.path.join(STAGING_ROOT, "upper") OVERLAY_METADATA = os.path.join(STAGING_ROOT, "metadata") @@ -81,20 +83,13 @@ def run(cmd, cwd=None): return subprocess.check_output(cmd, cwd=cwd, stderr=subprocess.STDOUT, encoding='utf8') -def remove_consistent_flag(): +def set_consistent_flag(consistent): os.system("sync") consistent_file = Path(os.path.join(FINALIZED, ".overlay_consistent")) - try: + if consistent: + consistent_file.touch() + elif not consistent and consistent_file.exists(): consistent_file.unlink() - except FileNotFoundError: - pass - os.system("sync") - - -def set_consistent_flag(): - consistent_file = Path(os.path.join(FINALIZED, ".overlay_consistent")) - os.system("sync") - consistent_file.touch() os.system("sync") @@ -150,7 +145,7 @@ def init_ovfs(): cloudlog.info("preparing new safe staging area") Params().put("UpdateAvailable", "0") - remove_consistent_flag() + set_consistent_flag(False) dismount_ovfs() if os.path.isdir(STAGING_ROOT): @@ -158,6 +153,7 @@ def init_ovfs(): for dirname in [STAGING_ROOT, OVERLAY_UPPER, OVERLAY_METADATA, OVERLAY_MERGED, FINALIZED]: os.mkdir(dirname, 0o755) + if not os.lstat(BASEDIR).st_dev == os.lstat(OVERLAY_MERGED).st_dev: raise RuntimeError("base and overlay merge directories are on different filesystems; not valid for overlay FS!") @@ -216,13 +212,13 @@ def attempt_update(): # Un-set the validity flag to prevent the finalized tree from being # activated later if the finalize step is interrupted - remove_consistent_flag() + set_consistent_flag(False) finalize_from_ovfs() # Make sure the validity flag lands on disk LAST, only when the local git # repo and OP install are in a consistent state. - set_consistent_flag() + set_consistent_flag(True) cloudlog.info("update successful!") else: @@ -232,8 +228,6 @@ def attempt_update(): def main(): - update_failed_count = 0 - overlay_init_done = False params = Params() if params.get("DisableUpdates") == b"1": @@ -247,7 +241,7 @@ def main(): if psutil.LINUX: p.ionice(psutil.IOPRIO_CLASS_BE, value=7) - ov_lock_fd = open('/tmp/safe_staging_overlay.lock', 'w') + ov_lock_fd = open(LOCK_FILE, 'w') try: fcntl.flock(ov_lock_fd, fcntl.LOCK_EX | fcntl.LOCK_NB) except IOError: @@ -257,33 +251,34 @@ def main(): wait_helper = WaitTimeHelper() wait_helper.sleep(30) + update_failed_count = 0 + overlay_initialized = False while not wait_helper.shutdown: update_failed_count += 1 wait_helper.ready_event.clear() # Check for internet every 30s time_wrong = datetime.datetime.utcnow().year < 2019 - ping_failed = os.system("git ls-remote --tags --quiet") != 0 + ping_failed = os.system(f"ping -W 4 -c 1 {TEST_IP}") != 0 if ping_failed or time_wrong: wait_helper.sleep(30) continue # Attempt an update try: - # If the git directory has modifcations after we created the overlay - # we need to recreate the overlay - if overlay_init_done: + # Re-create the overlay if BASEDIR/.git has changed since we created the overlay + if overlay_initialized: overlay_init_fn = os.path.join(BASEDIR, ".overlay_init") git_dir_path = os.path.join(BASEDIR, ".git") new_files = run(["find", git_dir_path, "-newer", overlay_init_fn]) if len(new_files.splitlines()): cloudlog.info(".git directory changed, recreating overlay") - overlay_init_done = False + overlay_initialized = False - if not overlay_init_done: + if not overlay_initialized: init_ovfs() - overlay_init_done = True + overlay_initialized = True if params.get("IsOffroad") == b"1": attempt_update() @@ -298,11 +293,13 @@ def main(): output=e.output, returncode=e.returncode ) - overlay_init_done = False + overlay_initialized = False except Exception: cloudlog.exception("uncaught updated exception, shouldn't happen") params.put("UpdateFailedCount", str(update_failed_count)) + + # Wait 10 minutes between update attempts wait_helper.sleep(60*10) # We've been signaled to shut down From e37b8e5d5632a7cc48326f7ca162ef87f259e526 Mon Sep 17 00:00:00 2001 From: martinl Date: Fri, 7 Aug 2020 07:55:13 +0300 Subject: [PATCH 578/656] Subaru pre-global: add support for Subaru Legacy 2015-18 (#1805) * Add support for Subaru Legacy 2015-18 * syntax fix * Add Legacy 2018 FPv1 * Add Subaru Ascent from upstream * Use GLOBAL_CAR and LEGACY_CAR lists * Change LEGACY_2015 to LEGACY_PREGLOBAL * Add LEGACY_CAR to carstate * Change LEGACY_2015 to LEGACY_PREGLOBAL in test_car_models * Add missing SafetyModel to Ascent * Use GLOBAL_CAR and LEGACY_CAR to set safetyModel * Change LEGACY_CAR to PREGLOBAL_CARS, remove GLOBAL_CAR * Fix PREGLOBAL_CARS in carstate and subarucan * Minor cleanups * Add accelCruise button event * Change Preglobal Driver Torque limit to match Global * Match comments to upstream * Use Steer_Warning and Steer_Error_1 only for Global * Change mph units to match upstream values * Increase Preglobal brakePressed threshold to 2 * Add DashcamOnly to LEGACY_PREGLOBAL * Fix typo in variable name * Update README, add create_preglobal_steering_control * cleanup carcontroller * cleanup values * missed that one * Update STEER_STEP * Update STEER_MAX * Add preglobal signal frequency checks * remove PREGLOBAL_CARS from subarucan * Remove whitespace * Use common frequency checks * cleanup carstate * cleanup subarucan Co-authored-by: Adeeb Shihadeh --- release/files_common | 1 + selfdrive/car/subaru/carcontroller.py | 61 ++++++--- selfdrive/car/subaru/carstate.py | 177 +++++++++++++++++--------- selfdrive/car/subaru/interface.py | 20 ++- selfdrive/car/subaru/subarucan.py | 31 ++++- selfdrive/car/subaru/values.py | 21 ++- selfdrive/test/test_car_models.py | 4 + 7 files changed, 229 insertions(+), 86 deletions(-) diff --git a/release/files_common b/release/files_common index a4417b3767..b1f6e2044d 100644 --- a/release/files_common +++ b/release/files_common @@ -524,6 +524,7 @@ opendbc/nissan_x_trail_2017.dbc opendbc/nissan_leaf_2018.dbc opendbc/subaru_global_2017_generated.dbc +opendbc/subaru_outback_2015_generated.dbc opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc opendbc/toyota_rav4_2017_pt_generated.dbc diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py index 06863b71cd..744fd0bcc9 100644 --- a/selfdrive/car/subaru/carcontroller.py +++ b/selfdrive/car/subaru/carcontroller.py @@ -1,7 +1,6 @@ -#from common.numpy_fast import clip from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.subaru import subarucan -from selfdrive.car.subaru.values import DBC +from selfdrive.car.subaru.values import DBC, PREGLOBAL_CARS from opendbc.can.packer import CANPacker @@ -18,49 +17,71 @@ class CarControllerParams(): class CarController(): def __init__(self, dbc_name, CP, VM): - self.lkas_active = False self.apply_steer_last = 0 self.es_distance_cnt = -1 + self.es_accel_cnt = -1 self.es_lkas_cnt = -1 + self.fake_button_prev = 0 self.steer_rate_limited = False self.params = CarControllerParams() self.packer = CANPacker(DBC[CP.carFingerprint]['pt']) def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, left_line, right_line): - """ Controls thread """ - P = self.params - - # Send CAN commands. can_sends = [] - ### STEER ### - - if (frame % P.STEER_STEP) == 0: + # *** steering *** + if (frame % self.params.STEER_STEP) == 0: - final_steer = actuators.steer if enabled else 0. - apply_steer = int(round(final_steer * P.STEER_MAX)) + apply_steer = int(round(actuators.steer * self.params.STEER_MAX)) # limits due to driver torque new_steer = int(round(apply_steer)) - apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, P) + apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) self.steer_rate_limited = new_steer != apply_steer if not enabled: apply_steer = 0 - can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, frame, P.STEER_STEP)) + if CS.CP.carFingerprint in PREGLOBAL_CARS: + can_sends.append(subarucan.create_preglobal_steering_control(self.packer, apply_steer, frame, self.params.STEER_STEP)) + else: + can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, frame, self.params.STEER_STEP)) self.apply_steer_last = apply_steer - if self.es_distance_cnt != CS.es_distance_msg["Counter"]: - can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg, pcm_cancel_cmd)) - self.es_distance_cnt = CS.es_distance_msg["Counter"] - if self.es_lkas_cnt != CS.es_lkas_msg["Counter"]: - can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, visual_alert, left_line, right_line)) - self.es_lkas_cnt = CS.es_lkas_msg["Counter"] + # *** alerts and pcm cancel *** + + if CS.CP.carFingerprint in PREGLOBAL_CARS: + if self.es_accel_cnt != CS.es_accel_msg["Counter"]: + # 1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 = resume deep + # disengage ACC when OP is disengaged + if pcm_cancel_cmd: + fake_button = 1 + # turn main on if off and past start-up state + elif not CS.out.cruiseState.available and CS.ready: + fake_button = 1 + else: + fake_button = CS.button + + # unstick previous mocked button press + if fake_button == 1 and self.fake_button_prev == 1: + fake_button = 0 + self.fake_button_prev = fake_button + + can_sends.append(subarucan.create_es_throttle_control(self.packer, fake_button, CS.es_accel_msg)) + self.es_accel_cnt = CS.es_accel_msg["Counter"] + + else: + if self.es_distance_cnt != CS.es_distance_msg["Counter"]: + can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg, pcm_cancel_cmd)) + self.es_distance_cnt = CS.es_distance_msg["Counter"] + + if self.es_lkas_cnt != CS.es_lkas_msg["Counter"]: + can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, visual_alert, left_line, right_line)) + self.es_lkas_cnt = CS.es_lkas_msg["Counter"] return can_sends diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index b9b6eadbdc..597b016207 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -4,7 +4,7 @@ from opendbc.can.can_define import CANDefine from selfdrive.config import Conversions as CV from selfdrive.car.interfaces import CarStateBase from opendbc.can.parser import CANParser -from selfdrive.car.subaru.values import DBC, STEER_THRESHOLD +from selfdrive.car.subaru.values import DBC, STEER_THRESHOLD, CAR, PREGLOBAL_CARS class CarState(CarStateBase): @@ -20,7 +20,10 @@ class CarState(CarStateBase): ret.gas = cp.vl["Throttle"]['Throttle_Pedal'] / 255. ret.gasPressed = ret.gas > 1e-5 - ret.brakePressed = cp.vl["Brake_Pedal"]['Brake_Pedal'] > 1e-5 + if self.car_fingerprint in PREGLOBAL_CARS: + ret.brakePressed = cp.vl["Brake_Pedal"]['Brake_Pedal'] > 2 + else: + ret.brakePressed = cp.vl["Brake_Pedal"]['Brake_Pedal'] > 1e-5 ret.brakeLights = ret.brakePressed ret.wheelSpeeds.fl = cp.vl["Wheel_Speeds"]['FL'] * CV.KPH_TO_MS @@ -48,15 +51,15 @@ class CarState(CarStateBase): ret.steeringTorque = cp.vl["Steering_Torque"]['Steer_Torque_Sensor'] ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD[self.car_fingerprint] - ret.steerError = cp.vl["Steering_Torque"]['Steer_Error_1'] == 1 - ret.steerWarning = cp.vl["Steering_Torque"]['Steer_Warning'] == 1 - ret.cruiseState.enabled = cp.vl["CruiseControl"]['Cruise_Activated'] != 0 ret.cruiseState.available = cp.vl["CruiseControl"]['Cruise_On'] != 0 ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]['Cruise_Set_Speed'] * CV.KPH_TO_MS - ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]['Conventional_Cruise'] == 1 - # EDM Impreza: 1,2 = mph, UDM Forester: 7 = mph - if cp.vl["Dash_State"]['Units'] in [1, 2, 7]: + + # UDM Legacy: mph = 0 + if self.car_fingerprint == CAR.LEGACY_PREGLOBAL and cp.vl["Dash_State"]['Units'] == 0: + ret.cruiseState.speed *= CV.MPH_TO_KPH + # EDM Global: mph = 1, 2; UDM Forester: 7 = mph + elif self.car_fingerprint != CAR.LEGACY_PREGLOBAL and cp.vl["Dash_State"]['Units'] in [1, 2, 7]: ret.cruiseState.speed *= CV.MPH_TO_KPH ret.seatbeltUnlatched = cp.vl["Dashlights"]['SEATBELT_FL'] == 1 @@ -65,8 +68,17 @@ class CarState(CarStateBase): cp.vl["BodyInfo"]['DOOR_OPEN_FR'], cp.vl["BodyInfo"]['DOOR_OPEN_FL']]) - self.es_distance_msg = copy.copy(cp_cam.vl["ES_Distance"]) - self.es_lkas_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) + if self.car_fingerprint in PREGLOBAL_CARS: + ret.steerError = cp.vl["Steering_Torque"]["LKA_Lockout"] == 1 + self.button = cp_cam.vl["ES_CruiseThrottle"]["Button"] + self.ready = not cp_cam.vl["ES_DashStatus"]["Not_Ready_Startup"] + self.es_accel_msg = copy.copy(cp_cam.vl["ES_CruiseThrottle"]) + else: + ret.steerError = cp.vl["Steering_Torque"]['Steer_Error_1'] == 1 + ret.steerWarning = cp.vl["Steering_Torque"]['Steer_Warning'] == 1 + ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]['Conventional_Cruise'] == 1 + self.es_distance_msg = copy.copy(cp_cam.vl["ES_Distance"]) + self.es_lkas_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) return ret @@ -77,8 +89,6 @@ class CarState(CarStateBase): # sig_name, sig_address, default ("Steer_Torque_Sensor", "Steering_Torque", 0), ("Steering_Angle", "Steering_Torque", 0), - ("Steer_Error_1", "Steering_Torque", 0), - ("Steer_Warning", "Steering_Torque", 0), ("Cruise_On", "CruiseControl", 0), ("Cruise_Activated", "CruiseControl", 0), ("Brake_Pedal", "Brake_Pedal", 0), @@ -104,62 +114,109 @@ class CarState(CarStateBase): checks = [ # sig_address, frequency + ("Throttle", 100), ("Dashlights", 10), - ("CruiseControl", 20), + ("Brake_Pedal", 50), ("Wheel_Speeds", 50), + ("Transmission", 100), ("Steering_Torque", 50), - ("BodyInfo", 10), ] + if CP.carFingerprint in PREGLOBAL_CARS: + signals += [ + ("LKA_Lockout", "Steering_Torque", 0), + ] + checks += [ + ("CruiseControl", 50), + ] + else: + signals += [ + ("Steer_Error_1", "Steering_Torque", 0), + ("Steer_Warning", "Steering_Torque", 0), + ] + checks += [ + ("BodyInfo", 10), + ("CruiseControl", 20), + ] + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) @staticmethod def get_cam_can_parser(CP): - signals = [ - ("Cruise_Set_Speed", "ES_DashStatus", 0), - ("Conventional_Cruise", "ES_DashStatus", 0), - - ("Counter", "ES_Distance", 0), - ("Signal1", "ES_Distance", 0), - ("Cruise_Fault", "ES_Distance", 0), - ("Cruise_Throttle", "ES_Distance", 0), - ("Signal2", "ES_Distance", 0), - ("Car_Follow", "ES_Distance", 0), - ("Signal3", "ES_Distance", 0), - ("Cruise_Brake_Active", "ES_Distance", 0), - ("Distance_Swap", "ES_Distance", 0), - ("Cruise_EPB", "ES_Distance", 0), - ("Signal4", "ES_Distance", 0), - ("Close_Distance", "ES_Distance", 0), - ("Signal5", "ES_Distance", 0), - ("Cruise_Cancel", "ES_Distance", 0), - ("Cruise_Set", "ES_Distance", 0), - ("Cruise_Resume", "ES_Distance", 0), - ("Signal6", "ES_Distance", 0), - - ("Counter", "ES_LKAS_State", 0), - ("Keep_Hands_On_Wheel", "ES_LKAS_State", 0), - ("Empty_Box", "ES_LKAS_State", 0), - ("Signal1", "ES_LKAS_State", 0), - ("LKAS_ACTIVE", "ES_LKAS_State", 0), - ("Signal2", "ES_LKAS_State", 0), - ("Backward_Speed_Limit_Menu", "ES_LKAS_State", 0), - ("LKAS_ENABLE_3", "ES_LKAS_State", 0), - ("LKAS_Left_Line_Light_Blink", "ES_LKAS_State", 0), - ("LKAS_ENABLE_2", "ES_LKAS_State", 0), - ("LKAS_Right_Line_Light_Blink", "ES_LKAS_State", 0), - ("LKAS_Left_Line_Visible", "ES_LKAS_State", 0), - ("LKAS_Left_Line_Green", "ES_LKAS_State", 0), - ("LKAS_Right_Line_Visible", "ES_LKAS_State", 0), - ("LKAS_Right_Line_Green", "ES_LKAS_State", 0), - ("LKAS_Alert", "ES_LKAS_State", 0), - ("Signal3", "ES_LKAS_State", 0), - ] - - checks = [ - ("ES_DashStatus", 10), - ("ES_Distance", 20), - ("ES_LKAS_State", 10), - ] + if CP.carFingerprint in PREGLOBAL_CARS: + signals = [ + ("Cruise_Set_Speed", "ES_DashStatus", 0), + ("Not_Ready_Startup", "ES_DashStatus", 0), + + ("Throttle_Cruise", "ES_CruiseThrottle", 0), + ("Signal1", "ES_CruiseThrottle", 0), + ("Cruise_Activated", "ES_CruiseThrottle", 0), + ("Signal2", "ES_CruiseThrottle", 0), + ("Brake_On", "ES_CruiseThrottle", 0), + ("DistanceSwap", "ES_CruiseThrottle", 0), + ("Standstill", "ES_CruiseThrottle", 0), + ("Signal3", "ES_CruiseThrottle", 0), + ("CloseDistance", "ES_CruiseThrottle", 0), + ("Signal4", "ES_CruiseThrottle", 0), + ("Standstill_2", "ES_CruiseThrottle", 0), + ("ES_Error", "ES_CruiseThrottle", 0), + ("Signal5", "ES_CruiseThrottle", 0), + ("Counter", "ES_CruiseThrottle", 0), + ("Signal6", "ES_CruiseThrottle", 0), + ("Button", "ES_CruiseThrottle", 0), + ("Signal7", "ES_CruiseThrottle", 0), + ] + + checks = [ + ("ES_DashStatus", 20), + ("ES_CruiseThrottle", 20), + ] + else: + signals = [ + ("Cruise_Set_Speed", "ES_DashStatus", 0), + ("Conventional_Cruise", "ES_DashStatus", 0), + + ("Counter", "ES_Distance", 0), + ("Signal1", "ES_Distance", 0), + ("Cruise_Fault", "ES_Distance", 0), + ("Cruise_Throttle", "ES_Distance", 0), + ("Signal2", "ES_Distance", 0), + ("Car_Follow", "ES_Distance", 0), + ("Signal3", "ES_Distance", 0), + ("Cruise_Brake_Active", "ES_Distance", 0), + ("Distance_Swap", "ES_Distance", 0), + ("Cruise_EPB", "ES_Distance", 0), + ("Signal4", "ES_Distance", 0), + ("Close_Distance", "ES_Distance", 0), + ("Signal5", "ES_Distance", 0), + ("Cruise_Cancel", "ES_Distance", 0), + ("Cruise_Set", "ES_Distance", 0), + ("Cruise_Resume", "ES_Distance", 0), + ("Signal6", "ES_Distance", 0), + + ("Counter", "ES_LKAS_State", 0), + ("Keep_Hands_On_Wheel", "ES_LKAS_State", 0), + ("Empty_Box", "ES_LKAS_State", 0), + ("Signal1", "ES_LKAS_State", 0), + ("LKAS_ACTIVE", "ES_LKAS_State", 0), + ("Signal2", "ES_LKAS_State", 0), + ("Backward_Speed_Limit_Menu", "ES_LKAS_State", 0), + ("LKAS_ENABLE_3", "ES_LKAS_State", 0), + ("LKAS_Left_Line_Light_Blink", "ES_LKAS_State", 0), + ("LKAS_ENABLE_2", "ES_LKAS_State", 0), + ("LKAS_Right_Line_Light_Blink", "ES_LKAS_State", 0), + ("LKAS_Left_Line_Visible", "ES_LKAS_State", 0), + ("LKAS_Left_Line_Green", "ES_LKAS_State", 0), + ("LKAS_Right_Line_Visible", "ES_LKAS_State", 0), + ("LKAS_Right_Line_Green", "ES_LKAS_State", 0), + ("LKAS_Alert", "ES_LKAS_State", 0), + ("Signal3", "ES_LKAS_State", 0), + ] + + checks = [ + ("ES_DashStatus", 10), + ("ES_Distance", 20), + ("ES_LKAS_State", 10), + ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index a710ae20b7..d9e1af213d 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 from cereal import car -from selfdrive.car.subaru.values import CAR +from selfdrive.car.subaru.values import CAR, PREGLOBAL_CARS from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint from selfdrive.car.interfaces import CarInterfaceBase @@ -16,11 +16,17 @@ class CarInterface(CarInterfaceBase): ret.carName = "subaru" ret.radarOffCan = True - ret.safetyModel = car.CarParams.SafetyModel.subaru + + if candidate in PREGLOBAL_CARS: + ret.safetyModel = car.CarParams.SafetyModel.subaruLegacy + else: + ret.safetyModel = car.CarParams.SafetyModel.subaru # Subaru port is a community feature, since we don't own one to test ret.communityFeature = True + ret.dashcamOnly = candidate in PREGLOBAL_CARS + # force openpilot to fake the stock camera, since car harness is not supported yet and old style giraffe (with switches) # was never released ret.enableCamera = True @@ -58,6 +64,16 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] + if candidate == CAR.LEGACY_PREGLOBAL: + ret.mass = 1568 + STD_CARGO_KG + ret.wheelbase = 2.67 + ret.centerToFront = ret.wheelbase * 0.5 + ret.steerRatio = 12.5 # 14.5 stock + ret.steerActuatorDelay = 0.15 + ret.lateralTuning.pid.kf = 0.00005 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.1, 0.2], [0.01, 0.02]] + # TODO: get actual value, for now starting with reasonable value for # civic and scaling by mass and wheelbase ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) diff --git a/selfdrive/car/subaru/subarucan.py b/selfdrive/car/subaru/subarucan.py index 6f933bd7bb..8249d36ba9 100644 --- a/selfdrive/car/subaru/subarucan.py +++ b/selfdrive/car/subaru/subarucan.py @@ -5,8 +5,7 @@ VisualAlert = car.CarControl.HUDControl.VisualAlert def create_steering_control(packer, apply_steer, frame, steer_step): - # counts from 0 to 15 then back to 0 + 16 for enable bit - idx = ((frame // steer_step) % 16) + idx = (frame / steer_step) % 16 values = { "Counter": idx, @@ -38,3 +37,31 @@ def create_es_lkas(packer, es_lkas_msg, visual_alert, left_line, right_line): values["LKAS_Right_Line_Visible"] = int(right_line) return packer.make_can_msg("ES_LKAS_State", 0, values) + +# *** Subaru Pre-global *** + +def subaru_preglobal_checksum(packer, values, addr): + dat = packer.make_can_msg(addr, 0, values)[2] + return (sum(dat[:7])) % 256 + +def create_preglobal_steering_control(packer, apply_steer, frame, steer_step): + + idx = (frame / steer_step) % 8 + + values = { + "Counter": idx, + "LKAS_Command": apply_steer, + "LKAS_Active": 1 if apply_steer != 0 else 0 + } + values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_LKAS") + + return packer.make_can_msg("ES_LKAS", 0, values) + +def create_es_throttle_control(packer, fake_button, es_accel_msg): + + values = copy.copy(es_accel_msg) + values["Button"] = fake_button + + values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_CruiseThrottle") + + return packer.make_can_msg("ES_CruiseThrottle", 0, values) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 3959843783..daf4634d4a 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -8,14 +8,15 @@ class CAR: ASCENT = "SUBARU ASCENT LIMITED 2019" IMPREZA = "SUBARU IMPREZA LIMITED 2019" FORESTER = "SUBARU FORESTER 2019" + LEGACY_PREGLOBAL = "SUBARU LEGACY 2015 - 2018" FINGERPRINTS = { - CAR.ASCENT: [ + CAR.ASCENT: [{ # SUBARU ASCENT LIMITED 2019 - { 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1722: 8, 1743: 8, 1759: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8 }], CAR.IMPREZA: [{ + # SUBARU IMPREZA LIMITED 2019 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1722: 8, 1743: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8 }, # Crosstrek 2018 (same platform as Impreza) @@ -30,12 +31,25 @@ FINGERPRINTS = { { 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 282: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 803: 8, 805: 8, 808: 8, 811: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1651: 8, 1657: 8, 1658: 8, 1677: 8, 1722: 8, 1759: 8, 1787: 5, 1788: 8 }], + CAR.LEGACY_PREGLOBAL: [{ + # LEGACY 2.5i 2017 + 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 392: 8, 604: 8, 640: 8, 642: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1632: 8, 1640: 8, 1736: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 644: 8 + }, + # LEGACY 2018 + { + 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 316: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 392: 8, 604: 8, 640: 8, 642: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1614: 8, 1632: 8, 1640: 8, 1657: 8, 1658: 8, 1672: 8, 1722: 8, 1743: 8, 1745: 8, 1778: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 2015: 8, 2016: 8, 2024: 8 + }, + # LEGACY 2018 + { + 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 316: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 392: 8, 554: 8, 604: 8, 640: 8, 642: 8, 805: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1614: 8, 1632: 8, 1640: 8, 1657: 8, 1658: 8, 1672: 8, 1722: 8, 1743: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 2015: 8, 2016: 8, 2024: 8 + }], } STEER_THRESHOLD = { CAR.ASCENT: 80, CAR.IMPREZA: 80, CAR.FORESTER: 80, + CAR.LEGACY_PREGLOBAL: 75, } ECU_FINGERPRINT = { @@ -46,4 +60,7 @@ DBC = { CAR.ASCENT: dbc_dict('subaru_global_2017_generated', None), CAR.IMPREZA: dbc_dict('subaru_global_2017_generated', None), CAR.FORESTER: dbc_dict('subaru_global_2017_generated', None), + CAR.LEGACY_PREGLOBAL: dbc_dict('subaru_outback_2015_generated', None), } + +PREGLOBAL_CARS = [CAR.LEGACY_PREGLOBAL] diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index bdf0331d85..539c330038 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -389,6 +389,10 @@ routes = { 'carFingerprint': SUBARU.IMPREZA, 'enableCamera': True, }, + "df5ca7660000fba8|2020-06-16--17-37-19": { + 'carFingerprint': SUBARU.LEGACY_PREGLOBAL, + 'enableCamera': True, + }, "fbbfa6af821552b9|2020-03-03--08-09-43": { 'carFingerprint': NISSAN.XTRAIL, 'enableCamera': True, From 31f57cb3a3b865ddc3f57be056ad302639ec61ba Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 7 Aug 2020 10:48:03 -0700 Subject: [PATCH 579/656] only check offroad in dmonitoringd on init --- selfdrive/monitoring/dmonitoringd.py | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index a99d53ca1e..66a1f2d879 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import gc from cereal import car -from common.realtime import set_realtime_priority, DT_DMON +from common.realtime import set_realtime_priority from common.params import Params import cereal.messaging as messaging from selfdrive.controls.lib.events import Events @@ -60,10 +60,6 @@ def dmonitoringd_thread(sm=None, pm=None): if sm.updated['model']: driver_status.set_policy(sm['model']) - # Check once a second if we're offroad - if sm.frame % 1/DT_DMON == 0: - offroad = params.get("IsOffroad") == b"1" - # Get data from dmonitoringmodeld if sm.updated['driverState']: events = Events() From 4170fcdc1c848efca03b047652f458e9d8426c41 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Fri, 7 Aug 2020 14:06:42 -0700 Subject: [PATCH 580/656] Add 2020 Accord Confirmed working by users on Discord --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 5f51266b24..4e94139637 100644 --- a/README.md +++ b/README.md @@ -66,7 +66,7 @@ Supported Cars | ----------| ------------------------------| ------------------| -----------------| -------------------| ------------------| | Acura | ILX 2016-18 | AcuraWatch Plus | openpilot | 25mph1 | 25mph | | Acura | RDX 2016-18 | AcuraWatch Plus | openpilot | 25mph1 | 12mph | -| Honda | Accord 2018-19 | All | Stock | 0mph | 3mph | +| Honda | Accord 2018-20 | All | Stock | 0mph | 3mph | | Honda | Accord Hybrid 2018-20 | All | Stock | 0mph | 3mph | | Honda | Civic Hatchback 2017-19 | Honda Sensing | Stock | 0mph | 12mph | | Honda | Civic Sedan/Coupe 2016-18 | Honda Sensing | openpilot | 0mph | 12mph | From c1482bebc05c44c79f8d8c0b4ee937777de338cc Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 8 Aug 2020 11:11:58 -0700 Subject: [PATCH 581/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index caf8670cff..3a8430b9d5 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit caf8670cffdcbefafc4e6bb2fb61a4b8e81d64dd +Subproject commit 3a8430b9d5921d09947a2f8ebe622b4a00eb30ac From 270880c70548f6979be7d97108bf19ae56724235 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Sat, 8 Aug 2020 11:17:33 -0700 Subject: [PATCH 582/656] tf 2.2. --- Pipfile | 2 +- Pipfile.lock | 520 +++++++++++++++++++++++++++------------------------ 2 files changed, 275 insertions(+), 247 deletions(-) diff --git a/Pipfile b/Pipfile index 45cbec0b8c..331be0c46f 100644 --- a/Pipfile +++ b/Pipfile @@ -39,7 +39,7 @@ redis = "*" "s2sphere" = "*" "subprocess32" = "*" tenacity = "*" -tensorflow = "~=2.2" +tensorflow = "==2.2" keras_applications = "*" PyMySQL = "~=0.9" Werkzeug = "*" diff --git a/Pipfile.lock b/Pipfile.lock index 7c707808e4..4a91f0a357 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "b7a0486f1174e81a5a51b37a775d05633295dadbb478860f6f8586c4095421c2" + "sha256": "d19d5f456b6901c49898a3f7d372874e59b09ac32a57c03a28b0a633fe5d6108" }, "pipfile-spec": 6, "requires": { @@ -539,37 +539,37 @@ }, "pyzmq": { "hashes": [ - "sha256:07fb8fe6826a229dada876956590135871de60dbc7de5a18c3bcce2ed1f03c98", - "sha256:13a5638ab24d628a6ade8f794195e1a1acd573496c3b85af2f1183603b7bf5e0", - "sha256:15b4cb21118f4589c4db8be4ac12b21c8b4d0d42b3ee435d47f686c32fe2e91f", - "sha256:21f7d91f3536f480cb2c10d0756bfa717927090b7fb863e6323f766e5461ee1c", - "sha256:2a88b8fabd9cc35bd59194a7723f3122166811ece8b74018147a4ed8489e6421", - "sha256:342fb8a1dddc569bc361387782e8088071593e7eaf3e3ecf7d6bd4976edff112", - "sha256:4ee0bfd82077a3ff11c985369529b12853a4064320523f8e5079b630f9551448", - "sha256:54aa24fd60c4262286fc64ca632f9e747c7cc3a3a1144827490e1dc9b8a3a960", - "sha256:58688a2dfa044fad608a8e70ba8d019d0b872ec2acd75b7b5e37da8905605891", - "sha256:5b99c2ae8089ef50223c28bac57510c163bfdff158c9e90764f812b94e69a0e6", - "sha256:5b9d21fc56c8aacd2e6d14738021a9d64f3f69b30578a99325a728e38a349f85", - "sha256:5f1f2eb22aab606f808163eb1d537ac9a0ba4283fbeb7a62eb48d9103cf015c2", - "sha256:6ca519309703e95d55965735a667809bbb65f52beda2fdb6312385d3e7a6d234", - "sha256:87c78f6936e2654397ca2979c1d323ee4a889eef536cc77a938c6b5be33351a7", - "sha256:8952f6ba6ae598e792703f3134af5a01af8f5c7cf07e9a148f05a12b02412cea", - "sha256:931339ac2000d12fe212e64f98ce291e81a7ec6c73b125f17cf08415b753c087", - "sha256:956775444d01331c7eb412c5fb9bb62130dfaac77e09f32764ea1865234e2ca9", - "sha256:97b6255ae77328d0e80593681826a0479cb7bac0ba8251b4dd882f5145a2293a", - "sha256:aaa8b40b676576fd7806839a5de8e6d5d1b74981e6376d862af6c117af2a3c10", - "sha256:af0c02cf49f4f9eedf38edb4f3b6bb621d83026e7e5d76eb5526cc5333782fd6", - "sha256:b08780e3a55215873b3b8e6e7ca8987f14c902a24b6ac081b344fd430d6ca7cd", - "sha256:ba6f24431b569aec674ede49cad197cad59571c12deed6ad8e3c596da8288217", - "sha256:bafd651b557dd81d89bd5f9c678872f3e7b7255c1c751b78d520df2caac80230", - "sha256:bfff5ffff051f5aa47ba3b379d87bd051c3196b0c8a603e8b7ed68a6b4f217ec", - "sha256:cf5d689ba9513b9753959164cf500079383bc18859f58bf8ce06d8d4bef2b054", - "sha256:dcbc3f30c11c60d709c30a213dc56e88ac016fe76ac6768e64717bd976072566", - "sha256:f9d7e742fb0196992477415bb34366c12e9bb9a0699b8b3f221ff93b213d7bec", - "sha256:faee2604f279d31312bc455f3d024f160b6168b9c1dde22bf62d8c88a4deca8e" - ], - "index": "pypi", - "version": "==19.0.1" + "sha256:00dca814469436455399660247d74045172955459c0bd49b54a540ce4d652185", + "sha256:046b92e860914e39612e84fa760fc3f16054d268c11e0e25dcb011fb1bc6a075", + "sha256:09d24a80ccb8cbda1af6ed8eb26b005b6743e58e9290566d2a6841f4e31fa8e0", + "sha256:0a422fc290d03958899743db091f8154958410fc76ce7ee0ceb66150f72c2c97", + "sha256:276ad604bffd70992a386a84bea34883e696a6b22e7378053e5d3227321d9702", + "sha256:296540a065c8c21b26d63e3cea2d1d57902373b16e4256afe46422691903a438", + "sha256:29d51279060d0a70f551663bc592418bcad7f4be4eea7b324f6dd81de05cb4c1", + "sha256:36ab114021c0cab1a423fe6689355e8f813979f2c750968833b318c1fa10a0fd", + "sha256:3fa6debf4bf9412e59353defad1f8035a1e68b66095a94ead8f7a61ae90b2675", + "sha256:5120c64646e75f6db20cc16b9a94203926ead5d633de9feba4f137004241221d", + "sha256:59f1e54627483dcf61c663941d94c4af9bf4163aec334171686cdaee67974fe5", + "sha256:5d9fc809aa8d636e757e4ced2302569d6e60e9b9c26114a83f0d9d6519c40493", + "sha256:654d3e06a4edc566b416c10293064732516cf8871a4522e0a2ba00cc2a2e600c", + "sha256:720d2b6083498a9281eaee3f2927486e9fe02cd16d13a844f2e95217f243efea", + "sha256:73483a2caaa0264ac717af33d6fb3f143d8379e60a422730ee8d010526ce1913", + "sha256:8a6ada5a3f719bf46a04ba38595073df8d6b067316c011180102ba2a1925f5b5", + "sha256:8b66b94fe6243d2d1d89bca336b2424399aac57932858b9a30309803ffc28112", + "sha256:99cc0e339a731c6a34109e5c4072aaa06d8e32c0b93dc2c2d90345dd45fa196c", + "sha256:a7e7f930039ee0c4c26e4dfee015f20bd6919cd8b97c9cd7afbde2923a5167b6", + "sha256:ab0d01148d13854de716786ca73701012e07dff4dfbbd68c4e06d8888743526e", + "sha256:c1a31cd42905b405530e92bdb70a8a56f048c8a371728b8acf9d746ecd4482c0", + "sha256:c20dd60b9428f532bc59f2ef6d3b1029a28fc790d408af82f871a7db03e722ff", + "sha256:c36ffe1e5aa35a1af6a96640d723d0d211c5f48841735c2aa8d034204e87eb87", + "sha256:c40fbb2b9933369e994b837ee72193d6a4c35dfb9a7c573257ef7ff28961272c", + "sha256:d46fb17f5693244de83e434648b3dbb4f4b0fec88415d6cbab1c1452b6f2ae17", + "sha256:e36f12f503511d72d9bdfae11cadbadca22ff632ff67c1b5459f69756a029c19", + "sha256:f1a25a61495b6f7bb986accc5b597a3541d9bd3ef0016f50be16dbb32025b302", + "sha256:fa411b1d8f371d3a49d31b0789eb6da2537dadbb2aef74a43aa99a78195c3f76" + ], + "index": "pypi", + "version": "==19.0.2" }, "raven": { "hashes": [ @@ -635,11 +635,11 @@ }, "tqdm": { "hashes": [ - "sha256:6baa75a88582b1db6d34ce4690da5501d2a1cb65c34664840a456b2c9f794d29", - "sha256:fcb7cb5b729b60a27f300b15c1ffd4744f080fb483b88f31dc8654b082cc8ea5" + "sha256:1a336d2b829be50e46b84668691e0a2719f26c97c62846298dd5ae2937e4d5cf", + "sha256:564d632ea2b9cb52979f7956e093e831c28d441c11751682f84c86fc46e4fd21" ], "index": "pypi", - "version": "==4.48.0" + "version": "==4.48.2" }, "urllib3": { "hashes": [ @@ -741,6 +741,27 @@ ], "version": "==1.12.0" }, + "argon2-cffi": { + "hashes": [ + "sha256:05a8ac07c7026542377e38389638a8a1e9b78f1cd8439cd7493b39f08dd75fbf", + "sha256:0bf066bc049332489bb2d75f69216416329d9dc65deee127152caeb16e5ce7d5", + "sha256:18dee20e25e4be86680b178b35ccfc5d495ebd5792cd00781548d50880fee5c5", + "sha256:392c3c2ef91d12da510cfb6f9bae52512a4552573a9e27600bdb800e05905d2b", + "sha256:57358570592c46c420300ec94f2ff3b32cbccd10d38bdc12dc6979c4a8484fbc", + "sha256:6678bb047373f52bcff02db8afab0d2a77d83bde61cfecea7c5c62e2335cb203", + "sha256:6ea92c980586931a816d61e4faf6c192b4abce89aa767ff6581e6ddc985ed003", + "sha256:77e909cc756ef81d6abb60524d259d959bab384832f0c651ed7dcb6e5ccdbb78", + "sha256:7d455c802727710e9dfa69b74ccaab04568386ca17b0ad36350b622cd34606fe", + "sha256:9bee3212ba4f560af397b6d7146848c32a800652301843df06b9e8f68f0f7361", + "sha256:9dfd5197852530294ecb5795c97a823839258dfd5eb9420233c7cfedec2058f2", + "sha256:b160416adc0f012fb1f12588a5e6954889510f82f698e23ed4f4fa57f12a0647", + "sha256:ba7209b608945b889457f949cc04c8e762bed4fe3fec88ae9a6b7765ae82e496", + "sha256:cc0e028b209a5483b6846053d5fd7165f460a1f14774d79e632e75e7ae64b82b", + "sha256:d8029b2d3e4b4cea770e9e5a0104dd8fa185c1724a0f01528ae4826a6d25f97d", + "sha256:da7f0445b71db6d3a72462e04f36544b0de871289b0bc8a7cc87c0f5ec7079fa" + ], + "version": "==20.1.0" + }, "astroid": { "hashes": [ "sha256:2f4078c2a41bf377eea06d71c9d2ba4eb8f6b1af2135bec27bbbb7d8f12bb703", @@ -774,11 +795,11 @@ }, "azure-cli-core": { "hashes": [ - "sha256:28bad5b4a8d90e98af4b556cbe560517a9be7187b0ea05bebe449c6838a03756", - "sha256:8618a30f7ea2188506f29801220c06396d731c26e4de92c327e6b0e8cc790db5" + "sha256:2f07ae6f4fa729398e2959f7f94424f753718f01c7301ae79156a5e72fb49a30", + "sha256:c81fc3fe245b183f7fb249f9dc46f1c3269d1621387c34a628c200d05c6593e2" ], "index": "pypi", - "version": "==2.9.1" + "version": "==2.10.1" }, "azure-cli-nspkg": { "hashes": [ @@ -821,10 +842,10 @@ }, "azure-mgmt-resource": { "hashes": [ - "sha256:bd9a3938f5423741329436d2da09693845c2fad96c35fadbd7c5ae5213208345", - "sha256:c1e2d834dee84953a4e25bef119008854a861d6d3fbe79b436589dc042e5a7c5" + "sha256:33ae072d0f60b804eda68c4396a73a7154005c88abf85d42c40a8991d0aa4eb9", + "sha256:9be7fcdf586f24acb799a799cf5e9363e9323ca0ce54cca63ab505f69fa0fddd" ], - "version": "==10.0.0" + "version": "==10.1.0" }, "azure-nspkg": { "hashes": [ @@ -878,6 +899,7 @@ "sha256:0258f143f3de96b7c14f762c770f5fc56ccd72f8a1857a451c1cd9a655d9ac89", "sha256:0b0069c752ec14172c5f78208f1863d7ad6755a6fae6fe76ec2c80d13be41e42", "sha256:19a4b72a6ae5bb467fea018b825f0a7d917789bcfe893e53f15c92805d187294", + "sha256:436a487dec749bca7e6e72498a75a5fa2433bda13bac91d023e18df9089ae0b8", "sha256:5432dd7b34107ae8ed6c10a71b4397f1c853bd39a4d6ffa7e35f40584cffd161", "sha256:6305557019906466fc42dbc53b46da004e72fd7a551c044a827e572c82191752", "sha256:69361315039878c0680be456640f8705d76cb4a3a3fe1e057e0f261b74be4b31", @@ -915,18 +937,18 @@ }, "boto3": { "hashes": [ - "sha256:4e357963ddd36a769e9a18ffe7517fed61f2b301a6e7d3c833cb5171146a5f53", - "sha256:859e29da7cce712f8fae8666fccb424bf3b42802d622b61b5219ea8a70e6a8f8" + "sha256:3aad418cb5a20f522f3d0267caefb5582324f5af60fe093ace12e69847cf72cd", + "sha256:d33af62c691c0078326970ec4f09bef4b8822bdfa7eca3a6c26b6b4c016c32d7" ], "index": "pypi", - "version": "==1.14.30" + "version": "==1.14.38" }, "botocore": { "hashes": [ - "sha256:8d5c40c2ab98223caa87cf1109d4449ee3022cb0ce9eb3b76696a231cf447888", - "sha256:d222643daa1a510f7e11e02b424689d69b49d6a88add13cbfd2a676daae6e200" + "sha256:37de221e9b9ba8a3225387d7a4d5313d55ff78e32a2986cce682cb21418b9ee3", + "sha256:e14b778d58640049d22c587c30d466bcc3432102f5715ffbe0bec2858b13a1b9" ], - "version": "==1.17.30" + "version": "==1.17.38" }, "cachetools": { "hashes": [ @@ -979,11 +1001,11 @@ }, "cfgv": { "hashes": [ - "sha256:1ccf53320421aeeb915275a196e23b3b8ae87dea8ac6698b1638001d4a486d53", - "sha256:c8e8f552ffcc6194f4e18dd4f68d9aef0c0d58ae7e7be8c82bee3c5e9edfa513" + "sha256:32e43d604bbe7896fe7c248a9c2276447dbef840feb28fe20494f62af110211d", + "sha256:cf22deb93d4bcf92f345a5c3cd39d3d41d6340adc60c78bbbd6588c384fda6a1" ], "markers": "python_version >= '3.6.1'", - "version": "==3.1.0" + "version": "==3.2.0" }, "chardet": { "hashes": [ @@ -1136,11 +1158,11 @@ }, "elasticsearch": { "hashes": [ - "sha256:6fb566dd23b91b5871ce12212888674b4cf33374e92b71b1080916c931e44dcb", - "sha256:e637d8cf4e27e279b5ff8ca8edc0c086f4b5df4bf2b48e2f950b7833aca3a792" + "sha256:2ffbd746fc7d2db08e5ede29c822483705f29c4bf43b0875c238637d5d843d44", + "sha256:92b534931865a186906873f75ae0b91808ff5036b0f2b9269eb5f6dc09644b55" ], "index": "pypi", - "version": "==7.8.0" + "version": "==7.8.1" }, "entrypoints": { "hashes": [ @@ -1242,11 +1264,11 @@ }, "google-auth": { "hashes": [ - "sha256:25c97cec5d4f6821f3ab67eb25b264fb00fda8fb9e2f05869bfa93dfcb8b50ee", - "sha256:c6e9735a2ee829a75b546702e460489db5cc35567a27fabd70b7c459f11efd58" + "sha256:2f34dd810090d0d4c9d5787c4ad7b4413d1fbfb941e13682c7a2298d3b6cdcc8", + "sha256:ce1fb80b5c6d3dd038babcc43e221edeafefc72d983b3dc28b67b996f76f00b9" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.20.0" + "version": "==1.20.1" }, "google-auth-oauthlib": { "hashes": [ @@ -1265,39 +1287,47 @@ }, "grpcio": { "hashes": [ - "sha256:08362b8b09562179b14db6ffce4b88e1a6a6edac8bccb85dd35f7b214fa5a0f5", - "sha256:09bea7902adc33620d68462671942e163ab12214073ffb613d2fef3df94254f6", - "sha256:0c334d6cbe27ebaa9e7211236dc99f3a9ca2ea4b3bf89b0d2544df2924343cc5", - "sha256:0c4e316e02fc227c6fba858707baee46f30d890754fc4acdf2cfec2ea0bf0aa1", - "sha256:14743e8fdfdabbab1a2075ffafd25e0a8b1a864505e3cccdf19793766cdc4624", - "sha256:1f45ec5003101f16673436b150bac73c2355cd9ae78cb14f3707be01a39b5450", - "sha256:2121afee4e3ebea7df1137bfb4dc396b1856aff4c517780108d9ce82f57bf2f8", - "sha256:2522f1808fe41bd8807feb5330025378553745b727eacb07562319205d1fd405", - "sha256:31e9891ac742e6866aec0cf67f1892618982cfbaf08bdcf3bb2e0f0828530c38", - "sha256:32fe6369143c262d096995ebdd55eeb77f0e1dbe8343a956462ef0607527c7bc", - "sha256:37da010e209289085d3362f371d9feefc152790859470f5e413d84a95a8d3998", - "sha256:38ab75168a9024d393bf43343960da425736038d249920955f223bc762587697", - "sha256:3cb78f8078ae583810c2eb47e536b0803a039656685144db43897e8beca4e203", - "sha256:474bb992355b4a3cb8d7cb783b2d81f628c16ea921cec54ff492420e11c896f5", - "sha256:74e8b6bd0f7ae64a7eecfe9bf10bc7a905d3b3eb2775cd3a9fdcdafd277469dd", - "sha256:795f351ef70a931f8f7be6a10a509714ec0a6e36c674a071abe5da8eb6b8bb35", - "sha256:7b47ec90cab0827679b511f7f9ef4fb0077cb5d7bb3d7b917154e718bb4d983b", - "sha256:7f264d740906655a147448d57e4422723639d2d3f891734b8d5eb1675cb47192", - "sha256:872d45a2e01f47db095bec032470a8c5c0a5ebd00fc930b5ae35c756b20d2cff", - "sha256:8d3249566b2d8b97925fbb2ae6c5b63c5ebdb919828230eae06a25e9614e051b", - "sha256:9ae898c15d122a046f04ea99327e3e0bd10593eb413c4810b931103da6311a21", - "sha256:ac97beab4a749c7faf6f267f7b149f6dff4f3ad64f6f6ac1d94d04019785d6a4", - "sha256:afe1f9173b51945e66c72002995eb6d4217384aaaee53215ae85d8543251fec2", - "sha256:b022cedea66b7d6774bbd7d32d5a8a374947fb572da1a6915210b09a6f51cbdf", - "sha256:b0f7bfba0ae7a97b802348aba4e08b1e84988103cc1eb887241e7b069010058a", - "sha256:b8e5194fb20f4365eacfc3c33d61662651e12e166978186faf378ee972eb0bab", - "sha256:b934542dd61746651f7907d2d7878f62ef42fdb46935088fc6a1d8266a406ba5", - "sha256:c8ad75925e87ed68d5f7d5e3ec4b9f2ed209fae67c0abbcbd17481cc474421ba", - "sha256:d18e7fb5c5c336cc349d06cde24582e0bfa5e067fdd6268bf1519c4eb4af0199", - "sha256:d5eee9d205518ee4feb9c424475ddad18a44fea97ff405780e7cd1d6df8ee96a", - "sha256:e8f2f5d16e0164c415f1b31a8d9a81f2e4645a43d1b261375d6bab7b0adf511f" - ], - "version": "==1.30.0" + "sha256:013287f99c99b201aa8a5f6bc7918f616739b9be031db132d9e3b8453e95e151", + "sha256:0397616355760cd8282ed5ea34d51830ae4cb6613b7e5f66bed3be5d041b8b9a", + "sha256:074871a184483d5cd0746fd01e7d214d3ee9d36e67e32a5786b0a21f29fb8304", + "sha256:08a9b648dbe8852ff94b73a1c96da126834c3057ba2301d13e8c4adff334c482", + "sha256:0fa86ac4452602c79774783aa68979a1a7625ebb7eaabee2b6550b975b9d61e6", + "sha256:220c46b1fc9c9a6fcca4caac398f08f0ed43cdd63c45b7458983c4a1575ef6df", + "sha256:259240aab2603891553e17ad5b2655693df79e02a9b887ff605bdeb2fcd3dcc9", + "sha256:292635f05b6ce33f87116951d0b3d8d330bdfc5cac74f739370d60981e8c256c", + "sha256:344b50865914cc8e6d023457bffee9a640abb18f75d0f2bb519041961c748da9", + "sha256:3c2aa6d7a5e5bf73fdb1715eee777efe06dd39df03383f1cc095b2fdb34883e6", + "sha256:43d44548ad6ee738b941abd9f09e3b83a5c13f3e1410321023c3c148ba50e796", + "sha256:5043440c45c0a031f387e7f48527541c65d672005fb24cf18ef6857483557d39", + "sha256:58d7121f48cb94535a4cedcce32921d0d0a78563c7372a143dedeec196d1c637", + "sha256:5d7faa89992e015d245750ca9ac916c161bbf72777b2c60abc61da3fae41339e", + "sha256:5fb0923b16590bac338e92d98c7d8effb3cfad1d2e18c71bf86bde32c49cd6dd", + "sha256:63ee8e02d04272c3d103f44b4bce5d43ea757dd288673cea212d2f7da27967d2", + "sha256:64077e3a9a7cf2f59e6c76d503c8de1f18a76428f41a5b000dc53c48a0b772ff", + "sha256:739a72abffbd36083ff7adbb862cf1afc1e311c35834bed9c0361d8e68b063e1", + "sha256:75e383053dccb610590aa53eed5278db5c09bf498d3b5105ce6c776478f59352", + "sha256:7a11b1ebb3210f34913b8be6995936bf9ebc541a65ab69e75db5ce1fe5047e8f", + "sha256:8002a89ea91c0078c15d3c0daf423fd4968946be78f08545e807ea9a5ff8054a", + "sha256:8b42f0ac76be07a5fa31117a3388d754ad35ef05e2e34be185ca9ccbcfac2069", + "sha256:8ca26b489b5dc1e3d31807d329c23d6cb06fe40fbae25b0649b718947936e26a", + "sha256:92e54ab65e782f227e751c7555918afaba8d1229601687e89b80c2b65d2f6642", + "sha256:a9a7ae74cb3108e6457cf15532d4c300324b48fbcf3ef290bcd2835745f20510", + "sha256:ba3e43cb984399064ffaa3c0997576e46a1e268f9da05f97cd9b272f0b59ee71", + "sha256:baaa036540d7ace433bdf38a3fe5e41cf9f84cdf10a88bac805f678a7ca8ddcc", + "sha256:bf00ab06ea4f89976288f4d6224d4aa120780e30c955d4f85c3214ada29b3ddf", + "sha256:bf39977282a79dc1b2765cc3402c0ada571c29a491caec6ed12c0993c1ec115e", + "sha256:c22b19abba63562a5a200e586b5bde39d26c8ec30c92e26d209d81182371693b", + "sha256:c9016ab1eaf4e054099303287195f3746bd4e69f2631d040f9dca43e910a5408", + "sha256:d2c5e05c257859febd03f5d81b5015e1946d6bcf475c7bf63ee99cea8ab0d590", + "sha256:e64bddd09842ef508d72ca354319b0eb126205d951e8ac3128fe9869bd563552", + "sha256:e8c3264b0fd728aadf3f0324471843f65bd3b38872bdab2a477e31ffb685dd5b", + "sha256:ea849210e7362559f326cbe603d5b8d8bb1e556e86a7393b5a8847057de5b084", + "sha256:ebb2ca09fa17537e35508a29dcb05575d4d9401138a68e83d1c605d65e8a1770", + "sha256:ef9fce98b6fe03874c2a6576b02aec1a0df25742cd67d1d7b75a49e30aa74225", + "sha256:f04c59d186af3157dc8811114130aaeae92e90a65283733f41de94eed484e1f7", + "sha256:f5b0870b733bcb7b6bf05a02035e7aaf20f599d3802b390282d4c2309f825f1d" + ], + "version": "==1.31.0" }, "gunicorn": { "hashes": [ @@ -1391,11 +1421,11 @@ }, "ipython": { "hashes": [ - "sha256:2dbcc8c27ca7d3cfe4fcdff7f45b27f9a8d3edfa70ff8024a71c7a8eb5f09d64", - "sha256:9f4fcb31d3b2c533333893b9172264e4821c1ac91839500f31bd43f2c59b3ccf" + "sha256:5a8f159ca8b22b9a0a1f2a28befe5ad2b703339afb58c2ffe0d7c8d7a3af5999", + "sha256:b70974aaa2674b05eb86a910c02ed09956a33f2dd6c71afc60f0b128a77e7f28" ], "index": "pypi", - "version": "==7.16.1" + "version": "==7.17.0" }, "ipython-genutils": { "hashes": [ @@ -1555,10 +1585,10 @@ }, "knack": { "hashes": [ - "sha256:1c4c1aa16df842caa862ce39c5f83aab79c0fcb4e992e1043f68add87250e9fd", - "sha256:fcef6040164ebe7d69629e4e089b398c9b980791446496301befcf8381dba0fc" + "sha256:d86a669f45e875fc5e49a85ac90e57c85338be89cb281cb99a9adb87f563761d", + "sha256:dfc6aef6760ea9a9620577e01540617678d78cab3111a0f03e8b9f987d0f08ca" ], - "version": "==0.7.1" + "version": "==0.7.2" }, "lazy-object-proxy": { "hashes": [ @@ -1821,11 +1851,11 @@ }, "notebook": { "hashes": [ - "sha256:3edc616c684214292994a3af05eaea4cc043f6b4247d830f3a2f209fa7639a80", - "sha256:47a9092975c9e7965ada00b9a20f0cf637d001db60d241d479f53c0be117ad48" + "sha256:42391d8f3b88676e774316527599e49c11f3a7e51c41035e9e44c1b58e1398d5", + "sha256:4cc4e44a43a83a7c2f5e85bfdbbfe1c68bed91b857741df9e593d213a6fc2d27" ], "markers": "python_version >= '3.5'", - "version": "==6.0.3" + "version": "==6.1.1" }, "numpy": { "hashes": [ @@ -2083,26 +2113,26 @@ }, "protobuf": { "hashes": [ - "sha256:304e08440c4a41a0f3592d2a38934aad6919d692bb0edfb355548786728f9a5e", - "sha256:49ef8ab4c27812a89a76fa894fe7a08f42f2147078392c0dee51d4a444ef6df5", - "sha256:50b5fee674878b14baea73b4568dc478c46a31dd50157a5b5d2f71138243b1a9", - "sha256:5524c7020eb1fb7319472cb75c4c3206ef18b34d6034d2ee420a60f99cddeb07", - "sha256:612bc97e42b22af10ba25e4140963fbaa4c5181487d163f4eb55b0b15b3dfcd2", - "sha256:6f349adabf1c004aba53f7b4633459f8ca8a09654bf7e69b509c95a454755776", - "sha256:85b94d2653b0fdf6d879e39d51018bf5ccd86c81c04e18a98e9888694b98226f", - "sha256:87535dc2d2ef007b9d44e309d2b8ea27a03d2fa09556a72364d706fcb7090828", - "sha256:a7ab28a8f1f043c58d157bceb64f80e4d2f7f1b934bc7ff5e7f7a55a337ea8b0", - "sha256:a96f8fc625e9ff568838e556f6f6ae8eca8b4837cdfb3f90efcb7c00e342a2eb", - "sha256:b5a114ea9b7fc90c2cc4867a866512672a47f66b154c6d7ee7e48ddb68b68122", - "sha256:be04fe14ceed7f8641e30f36077c1a654ff6f17d0c7a5283b699d057d150d82a", - "sha256:bff02030bab8b969f4de597543e55bd05e968567acb25c0a87495a31eb09e925", - "sha256:c9ca9f76805e5a637605f171f6c4772fc4a81eced4e2f708f79c75166a2c99ea", - "sha256:e1464a4a2cf12f58f662c8e6421772c07947266293fb701cb39cd9c1e183f63c", - "sha256:e72736dd822748b0721f41f9aaaf6a5b6d5cfc78f6c8690263aef8bba4457f0e", - "sha256:eafe9fa19fcefef424ee089fb01ac7177ff3691af7cc2ae8791ae523eb6ca907", - "sha256:f4b73736108a416c76c17a8a09bc73af3d91edaa26c682aaa460ef91a47168d3" - ], - "version": "==3.12.2" + "sha256:0b00429b87821f1e6f3d641327864e6f271763ae61799f7540bc58a352825fe2", + "sha256:2636c689a6a2441da9a2ef922a21f9b8bfd5dfe676abd77d788db4b36ea86bee", + "sha256:2becd0e238ae34caf96fa7365b87f65b88aebcf7864dfe5ab461c5005f4256d9", + "sha256:2db6940c1914fa3fbfabc0e7c8193d9e18b01dbb4650acac249b113be3ba8d9e", + "sha256:32f0bcdf85e0040f36b4f548c71177027f2a618cab00ba235197fa9e230b7289", + "sha256:3d59825cba9447e8f4fcacc1f3c892cafd28b964e152629b3f420a2fb5918b5a", + "sha256:4794a7748ee645d2ae305f3f4f0abd459e789c973b5bc338008960f83e0c554b", + "sha256:50b7bb2124f6a1fb0ddc6a44428ae3a21e619ad2cdf08130ac6c00534998ef07", + "sha256:6009f3ebe761fad319b52199a49f1efa7a3729302947a78a3f5ea8e7e89e3ac2", + "sha256:a7b6cf201e67132ca99b8a6c4812fab541fdce1ceb54bb6f66bc336ab7259138", + "sha256:b6842284bb15f1b19c50c5fd496f1e2a4cfefdbdfa5d25c02620cb82793295a7", + "sha256:c0c8d7c8f07eacd9e98a907941b56e57883cf83de069cfaeaa7e02c582f72ddb", + "sha256:c99e5aea75b6f2b29c8d8da5bdc5f5ed8d9a5b4f15115c8316a3f0a850f94656", + "sha256:e2bd5c98952db3f1bb1af2e81b6a208909d3b8a2d32f7525c5cc10a6338b6593", + "sha256:e77ca4e1403b363a88bde9e31c11d093565e925e1685f40b29385a52f2320794", + "sha256:ef991cbe34d7bb935ba6349406a210d3558b9379c21621c6ed7b99112af7350e", + "sha256:f10ba89f9cd508dc00e469918552925ef7cba38d101ca47af1e78f2f9982c6b3", + "sha256:f1796e0eb911bf5b08e76b753953effbeb6bc42c95c16597177f627eaa52c375" + ], + "version": "==3.12.4" }, "ptyprocess": { "hashes": [ @@ -2252,65 +2282,63 @@ }, "pymongo": { "hashes": [ - "sha256:01b4e10027aef5bb9ecefbc26f5df3368ce34aef81df43850f701e716e3fe16d", - "sha256:0fc5aa1b1acf7f61af46fe0414e6a4d0c234b339db4c03a63da48599acf1cbfc", - "sha256:1396eb7151e0558b1f817e4b9d7697d5599e5c40d839a9f7270bd90af994ad82", - "sha256:18e84a3ec5e73adcb4187b8e5541b2ad61d716026ed9863267e650300d8bea33", - "sha256:19adf2848b80cb349b9891cc854581bbf24c338be9a3260e73159bdeb2264464", - "sha256:20ee0475aa2ba437b0a14806f125d696f90a8433d820fb558fdd6f052acde103", - "sha256:26798795097bdeb571f13942beef7e0b60125397811c75b7aa9214d89880dd1d", - "sha256:26e707a4eb851ec27bb969b5f1413b9b2eac28fe34271fa72329100317ea7c73", - "sha256:2a3c7ad01553b27ec553688a1e6445e7f40355fb37d925c11fcb50b504e367f8", - "sha256:2f07b27dbf303ea53f4147a7922ce91a26b34a0011131471d8aaf73151fdee9a", - "sha256:316f0cf543013d0c085e15a2c8abe0db70f93c9722c0f99b6f3318ff69477d70", - "sha256:31d11a600eea0c60de22c8bdcb58cda63c762891facdcb74248c36713240987f", - "sha256:334ef3ffd0df87ea83a0054454336159f8ad9c1b389e19c0032d9cb8410660e6", - "sha256:358ba4693c01022d507b96a980ded855a32dbdccc3c9331d0667be5e967f30ed", - "sha256:3a6568bc53103df260f5c7d2da36dffc5202b9a36c85540bba1836a774943794", - "sha256:444bf2f44264578c4085bb04493bfed0e5c1b4fe7c2704504d769f955cc78fe4", - "sha256:47a00b22c52ee59dffc2aad02d0bbfb20c26ec5b8de8900492bf13ad6901cf35", - "sha256:4c067db43b331fc709080d441cb2e157114fec60749667d12186cc3fc8e7a951", - "sha256:4c092310f804a5d45a1bcaa4191d6d016c457b6ed3982a622c35f729ff1c7f6b", - "sha256:53b711b33134e292ef8499835a3df10909c58df53a2a0308f598c432e9a62892", - "sha256:568d6bee70652d8a5af1cd3eec48b4ca1696fb1773b80719ebbd2925b72cb8f6", - "sha256:56fa55032782b7f8e0bf6956420d11e2d4e9860598dfe9c504edec53af0fc372", - "sha256:5a2c492680c61b440272341294172fa3b3751797b1ab983533a770e4fb0a67ac", - "sha256:61235cc39b5b2f593086d1d38f3fc130b2d125bd8fc8621d35bc5b6bdeb92bd2", - "sha256:619ac9aaf681434b4d4718d1b31aa2f0fce64f2b3f8435688fcbdc0c818b6c54", - "sha256:6238ac1f483494011abde5286282afdfacd8926659e222ba9b74c67008d3a58c", - "sha256:63752a72ca4d4e1386278bd43d14232f51718b409e7ac86bcf8810826b531113", - "sha256:6fdc5ccb43864065d40dd838437952e9e3da9821b7eac605ba46ada77f846bdf", - "sha256:7abc3a6825a346fa4621a6f63e3b662bbb9e0f6ffc32d30a459d695f20fb1a8b", - "sha256:7aef381bb9ae8a3821abd7f9d4d93978dbd99072b48522e181baeffcd95b56ae", - "sha256:80df3caf251fe61a3f0c9614adc6e2bfcffd1cd3345280896766712fb4b4d6d7", - "sha256:95f970f34b59987dee6f360d2e7d30e181d58957b85dff929eee4423739bd151", - "sha256:993257f6ca3cde55332af1f62af3e04ca89ce63c08b56a387cdd46136c72f2fa", - "sha256:9c0a57390549affc2b5dda24a38de03a5c7cbc58750cd161ff5d106c3c6eec80", - "sha256:a0794e987d55d2f719cc95fcf980fc62d12b80e287e6a761c4be14c60bd9fecc", - "sha256:a3b98121e68bf370dd8ea09df67e916f93ea95b52fc010902312168c4d1aff5d", - "sha256:a60756d55f0887023b3899e6c2923ba5f0042fb11b1d17810b4e07395404f33e", - "sha256:a676bd2fbc2309092b9bbb0083d35718b5420af3a42135ebb1e4c3633f56604d", - "sha256:a732838c78554c1257ff2492f5c8c4c7312d0aecd7f732149e255f3749edd5ee", - "sha256:ad3dc88dfe61f0f1f9b99c6bc833ea2f45203a937a18f0d2faa57c6952656012", - "sha256:ae65d65fde4135ef423a2608587c9ef585a3551fc2e4e431e7c7e527047581be", - "sha256:b070a4f064a9edb70f921bfdc270725cff7a78c22036dd37a767c51393fb956f", - "sha256:b6da85949aa91e9f8c521681344bd2e163de894a5492337fba8b05c409225a4f", - "sha256:bbf47110765b2a999803a7de457567389253f8670f7daafb98e059c899ce9764", - "sha256:bd9c1e6f92b4888ae3ef7ae23262c513b962f09f3fb3b48581dde5df7d7a860a", - "sha256:c06b3f998d2d7160db58db69adfb807d2ec307e883e2f17f6b87a1ef6c723f11", - "sha256:c318fb70542be16d3d4063cde6010b1e4d328993a793529c15a619251f517c39", - "sha256:c4aef42e5fa4c9d5a99f751fb79caa880dac7eaf8a65121549318b984676a1b7", - "sha256:c9ca545e93a9c2a3bdaa2e6e21f7a43267ff0813e8055adf2b591c13164c0c57", - "sha256:da2c3220eb55c4239dd8b982e213da0b79023cac59fe54ca09365f2bc7e4ad32", - "sha256:dd8055da300535eefd446b30995c0813cc4394873c9509323762a93e97c04c03", - "sha256:e2b46e092ea54b732d98c476720386ff2ccd126de1e52076b470b117bff7e409", - "sha256:e334c4f39a2863a239d38b5829e442a87f241a92da9941861ee6ec5d6380b7fe", - "sha256:e5c54f04ca42bbb5153aec5d4f2e3d9f81e316945220ac318abd4083308143f5", - "sha256:f4d06764a06b137e48db6d569dc95614d9d225c89842c885669ee8abc9f28c7a", - "sha256:f96333f9d2517c752c20a35ff95de5fc2763ac8cdb1653df0f6f45d281620606" - ], - "index": "pypi", - "version": "==3.10.1" + "sha256:03dc64a9aa7a5d405aea5c56db95835f6a2fa31b3502c5af1760e0e99210be30", + "sha256:05fcc6f9c60e6efe5219fbb5a30258adb3d3e5cbd317068f3d73c09727f2abb6", + "sha256:076a7f2f7c251635cf6116ac8e45eefac77758ee5a77ab7bd2f63999e957613b", + "sha256:137e6fa718c7eff270dbd2fc4b90d94b1a69c9e9eb3f3de9e850a7fd33c822dc", + "sha256:1f865b1d1c191d785106f54df9abdc7d2f45a946b45fd1ea0a641b4f982a2a77", + "sha256:213c445fe7e654621c6309e874627c35354b46ef3ee807f5a1927dc4b30e1a67", + "sha256:25e617daf47d8dfd4e152c880cd0741cbdb48e51f54b8de9ddbfe74ecd87dd16", + "sha256:3d9bb1ba935a90ec4809a8031efd988bdb13cdba05d9e9a3e9bf151bf759ecde", + "sha256:40696a9a53faa7d85aaa6fd7bef1cae08f7882640bad08c350fb59dee7ad069b", + "sha256:421aa1b92c291c429668bd8d8d8ec2bd00f183483a756928e3afbf2b6f941f00", + "sha256:4437300eb3a5e9cc1a73b07d22c77302f872f339caca97e9bf8cf45eca8fa0d2", + "sha256:455f4deb00158d5ec8b1d3092df6abb681b225774ab8a59b3510293b4c8530e3", + "sha256:475a34a0745c456ceffaec4ce86b7e0983478f1b6140890dff7b161e7bcd895b", + "sha256:4797c0080f41eba90404335e5ded3aa66731d303293a675ff097ce4ea3025bb9", + "sha256:4ae23fbbe9eadf61279a26eba866bbf161a6f7e2ffad14a42cf20e9cb8e94166", + "sha256:4b32744901ee9990aa8cd488ec85634f443526def1e5190a407dc107148249d7", + "sha256:50127b13b38e8e586d5e97d342689405edbd74ad0bd891d97ee126a8c7b6e45f", + "sha256:50531caa7b4be1c4ed5e2d5793a4e51cc9bd62a919a6fd3299ef7c902e206eab", + "sha256:63a5387e496a98170ffe638b435c0832c0f2011a6f4ff7a2880f17669fff8c03", + "sha256:68220b81850de8e966d4667d5c325a96c6ac0d6adb3d18935d6e3d325d441f48", + "sha256:689142dc0c150e9cb7c012d84cac2c346d40beb891323afb6caf18ec4caafae0", + "sha256:6a15e2bee5c4188369a87ed6f02de804651152634a46cca91966a11c8abd2550", + "sha256:7122ffe597b531fb065d3314e704a6fe152b81820ca5f38543e70ffcc95ecfd4", + "sha256:7307024b18266b302f4265da84bb1effb5d18999ef35b30d17592959568d5c0a", + "sha256:7a4a6f5b818988a3917ec4baa91d1143242bdfece8d38305020463955961266a", + "sha256:83c5a3ecd96a9f3f11cfe6dfcbcec7323265340eb24cc996acaecea129865a3a", + "sha256:890b0f1e18dbd898aeb0ab9eae1ab159c6bcbe87f0abb065b0044581d8614062", + "sha256:8deda1f7b4c03242f2a8037706d9584e703f3d8c74d6d9cac5833db36fe16c42", + "sha256:8ea13d0348b4c96b437d944d7068d59ed4a6c98aaa6c40d8537a2981313f1c66", + "sha256:91e96bf85b7c07c827d339a386e8a3cf2e90ef098c42595227f729922d0851df", + "sha256:96782ebb3c9e91e174c333208b272ea144ed2a684413afb1038e3b3342230d72", + "sha256:9755c726aa6788f076114dfdc03b92b03ff8860316cca00902cce88bcdb5fedd", + "sha256:9dbab90c348c512e03f146e93a5e2610acec76df391043ecd46b6b775d5397e6", + "sha256:9ee0eef254e340cc11c379f797af3977992a7f2c176f1a658740c94bf677e13c", + "sha256:9fc17fdac8f1973850d42e51e8ba6149d93b1993ed6768a24f352f926dd3d587", + "sha256:a2787319dc69854acdfd6452e6a8ba8f929aeb20843c7f090e04159fc18e6245", + "sha256:b7c522292407fa04d8195032493aac937e253ad9ae524aab43b9d9d242571f03", + "sha256:bd312794f51e37dcf77f013d40650fe4fbb211dd55ef2863839c37480bd44369", + "sha256:c0d660a186e36c526366edf8a64391874fe53cf8b7039224137aee0163c046df", + "sha256:c4869141e20769b65d2d72686e7a7eb141ce9f3168106bed3e7dcced54eb2422", + "sha256:cc4057f692ac35bbe82a0a908d42ce3a281c9e913290fac37d7fa3bd01307dfb", + "sha256:cccf1e7806f12300e3a3b48f219e111000c2538483e85c869c35c1ae591e6ce9", + "sha256:ce208f80f398522e49d9db789065c8ad2cd37b21bd6b23d30053474b7416af11", + "sha256:d0565481dc196986c484a7fb13214fc6402201f7fb55c65fd215b3324962fe6c", + "sha256:d1b3366329c45a474b3bbc9b9c95d4c686e03f35da7fd12bc144626d1f2a7c04", + "sha256:d226e0d4b9192d95079a9a29c04dd81816b1ce8903b8c174a39224fe978547cb", + "sha256:d38b35f6eef4237b1d0d8e845fc1546dad85c55eba447e28c211da8c7ef9697c", + "sha256:d64c98277ea80e4484f1332ab107e8dfd173a7dcf1bdbf10a9cccc97aaab145f", + "sha256:d9de8427a5601799784eb0e7fa1b031aa64086ce04de29df775a8ca37eedac41", + "sha256:e6a15cf8f887d9f578dd49c6fb3a99d53e1d922fdd67a245a67488d77bf56eb2", + "sha256:e8c446882cbb3774cd78c738c9f58220606b702b7c1655f1423357dc51674054", + "sha256:e8d188ee39bd0ffe76603da887706e4e7b471f613625899ddf1e27867dc6a0d3", + "sha256:ef76535776c0708a85258f6dc51d36a2df12633c735f6d197ed7dfcaa7449b99", + "sha256:f6efca006a81e1197b925a7d7b16b8f61980697bb6746587aad8842865233218" + ], + "index": "pypi", + "version": "==3.11.0" }, "pymysql": { "hashes": [ @@ -2497,37 +2525,37 @@ }, "pyzmq": { "hashes": [ - "sha256:07fb8fe6826a229dada876956590135871de60dbc7de5a18c3bcce2ed1f03c98", - "sha256:13a5638ab24d628a6ade8f794195e1a1acd573496c3b85af2f1183603b7bf5e0", - "sha256:15b4cb21118f4589c4db8be4ac12b21c8b4d0d42b3ee435d47f686c32fe2e91f", - "sha256:21f7d91f3536f480cb2c10d0756bfa717927090b7fb863e6323f766e5461ee1c", - "sha256:2a88b8fabd9cc35bd59194a7723f3122166811ece8b74018147a4ed8489e6421", - "sha256:342fb8a1dddc569bc361387782e8088071593e7eaf3e3ecf7d6bd4976edff112", - "sha256:4ee0bfd82077a3ff11c985369529b12853a4064320523f8e5079b630f9551448", - "sha256:54aa24fd60c4262286fc64ca632f9e747c7cc3a3a1144827490e1dc9b8a3a960", - "sha256:58688a2dfa044fad608a8e70ba8d019d0b872ec2acd75b7b5e37da8905605891", - "sha256:5b99c2ae8089ef50223c28bac57510c163bfdff158c9e90764f812b94e69a0e6", - "sha256:5b9d21fc56c8aacd2e6d14738021a9d64f3f69b30578a99325a728e38a349f85", - "sha256:5f1f2eb22aab606f808163eb1d537ac9a0ba4283fbeb7a62eb48d9103cf015c2", - "sha256:6ca519309703e95d55965735a667809bbb65f52beda2fdb6312385d3e7a6d234", - "sha256:87c78f6936e2654397ca2979c1d323ee4a889eef536cc77a938c6b5be33351a7", - "sha256:8952f6ba6ae598e792703f3134af5a01af8f5c7cf07e9a148f05a12b02412cea", - "sha256:931339ac2000d12fe212e64f98ce291e81a7ec6c73b125f17cf08415b753c087", - "sha256:956775444d01331c7eb412c5fb9bb62130dfaac77e09f32764ea1865234e2ca9", - "sha256:97b6255ae77328d0e80593681826a0479cb7bac0ba8251b4dd882f5145a2293a", - "sha256:aaa8b40b676576fd7806839a5de8e6d5d1b74981e6376d862af6c117af2a3c10", - "sha256:af0c02cf49f4f9eedf38edb4f3b6bb621d83026e7e5d76eb5526cc5333782fd6", - "sha256:b08780e3a55215873b3b8e6e7ca8987f14c902a24b6ac081b344fd430d6ca7cd", - "sha256:ba6f24431b569aec674ede49cad197cad59571c12deed6ad8e3c596da8288217", - "sha256:bafd651b557dd81d89bd5f9c678872f3e7b7255c1c751b78d520df2caac80230", - "sha256:bfff5ffff051f5aa47ba3b379d87bd051c3196b0c8a603e8b7ed68a6b4f217ec", - "sha256:cf5d689ba9513b9753959164cf500079383bc18859f58bf8ce06d8d4bef2b054", - "sha256:dcbc3f30c11c60d709c30a213dc56e88ac016fe76ac6768e64717bd976072566", - "sha256:f9d7e742fb0196992477415bb34366c12e9bb9a0699b8b3f221ff93b213d7bec", - "sha256:faee2604f279d31312bc455f3d024f160b6168b9c1dde22bf62d8c88a4deca8e" - ], - "index": "pypi", - "version": "==19.0.1" + "sha256:00dca814469436455399660247d74045172955459c0bd49b54a540ce4d652185", + "sha256:046b92e860914e39612e84fa760fc3f16054d268c11e0e25dcb011fb1bc6a075", + "sha256:09d24a80ccb8cbda1af6ed8eb26b005b6743e58e9290566d2a6841f4e31fa8e0", + "sha256:0a422fc290d03958899743db091f8154958410fc76ce7ee0ceb66150f72c2c97", + "sha256:276ad604bffd70992a386a84bea34883e696a6b22e7378053e5d3227321d9702", + "sha256:296540a065c8c21b26d63e3cea2d1d57902373b16e4256afe46422691903a438", + "sha256:29d51279060d0a70f551663bc592418bcad7f4be4eea7b324f6dd81de05cb4c1", + "sha256:36ab114021c0cab1a423fe6689355e8f813979f2c750968833b318c1fa10a0fd", + "sha256:3fa6debf4bf9412e59353defad1f8035a1e68b66095a94ead8f7a61ae90b2675", + "sha256:5120c64646e75f6db20cc16b9a94203926ead5d633de9feba4f137004241221d", + "sha256:59f1e54627483dcf61c663941d94c4af9bf4163aec334171686cdaee67974fe5", + "sha256:5d9fc809aa8d636e757e4ced2302569d6e60e9b9c26114a83f0d9d6519c40493", + "sha256:654d3e06a4edc566b416c10293064732516cf8871a4522e0a2ba00cc2a2e600c", + "sha256:720d2b6083498a9281eaee3f2927486e9fe02cd16d13a844f2e95217f243efea", + "sha256:73483a2caaa0264ac717af33d6fb3f143d8379e60a422730ee8d010526ce1913", + "sha256:8a6ada5a3f719bf46a04ba38595073df8d6b067316c011180102ba2a1925f5b5", + "sha256:8b66b94fe6243d2d1d89bca336b2424399aac57932858b9a30309803ffc28112", + "sha256:99cc0e339a731c6a34109e5c4072aaa06d8e32c0b93dc2c2d90345dd45fa196c", + "sha256:a7e7f930039ee0c4c26e4dfee015f20bd6919cd8b97c9cd7afbde2923a5167b6", + "sha256:ab0d01148d13854de716786ca73701012e07dff4dfbbd68c4e06d8888743526e", + "sha256:c1a31cd42905b405530e92bdb70a8a56f048c8a371728b8acf9d746ecd4482c0", + "sha256:c20dd60b9428f532bc59f2ef6d3b1029a28fc790d408af82f871a7db03e722ff", + "sha256:c36ffe1e5aa35a1af6a96640d723d0d211c5f48841735c2aa8d034204e87eb87", + "sha256:c40fbb2b9933369e994b837ee72193d6a4c35dfb9a7c573257ef7ff28961272c", + "sha256:d46fb17f5693244de83e434648b3dbb4f4b0fec88415d6cbab1c1452b6f2ae17", + "sha256:e36f12f503511d72d9bdfae11cadbadca22ff632ff67c1b5459f69756a029c19", + "sha256:f1a25a61495b6f7bb986accc5b597a3541d9bd3ef0016f50be16dbb32025b302", + "sha256:fa411b1d8f371d3a49d31b0789eb6da2537dadbb2aef74a43aa99a78195c3f76" + ], + "index": "pypi", + "version": "==19.0.2" }, "qtconsole": { "hashes": [ @@ -2802,10 +2830,10 @@ }, "tensorboard": { "hashes": [ - "sha256:d34609ed83ff01dd5b49ef81031cfc9c166bba0dabd60197024f14df5e8eae5e" + "sha256:a3feb73e1221c0a512398ad2cd08570fb082d8a2ba364aa0562543ecbd3659ef" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==2.3.0" + "version": "==2.2.2" }, "tensorboard-plugin-wit": { "hashes": [ @@ -2815,27 +2843,27 @@ }, "tensorflow": { "hashes": [ - "sha256:0cfb0fbe875408cdbfc7677f12aa0b23656f3e6d8c5f568b3100450ec29262a7", - "sha256:2d9994157d6a222d9ffd956e99af4b5e46e47338428d2d197e325362283ec835", - "sha256:36a4ce9bbc9865385c1bb606fe34f0da96b0496ce3997e652d2b765a4382fe48", - "sha256:44c8d979b2d19ed56dbe6b03aef87616d6138a58fd80c43e7a758c90105e9adf", - "sha256:5c9f9a36d5b4d0ceb67b985486fe4cc6999a96e2bf89f3ba82ffd8317e5efadd", - "sha256:6f74ef59dc59cf8f2002738c65dffa591e2c332e9b1b4ced33ff8d39b6fb477c", - "sha256:797d6ca09d4f69570458180b7813dc12efe9166ba60454b0df7bed531bb5e4f4", - "sha256:92430b6e91f00f38a602c4f547bbbaca598a3a90376f90d5b2acd24bc18fa1d7", - "sha256:b1699903cf3a9f41c379d79ada2279a206a071b7e05671646d7b5e7fc37e2eae", - "sha256:bc9d761a857839344930eef86f0d6409840b1c9ada9cbe56b92287b2077ef752", - "sha256:c33a423eb1f39c4c6acc44c044a138979868f0d4c91e380c191bd8fddc7c2e9b", - "sha256:c6fad4e944e20199e963e158fe626352e349865ea4ca71655f5456193a6d3b9d" + "sha256:267017724a49c367ca5df536e5f6d3d59643eaed946c82233d6b371e62b5ddc8", + "sha256:3ee8819732d8594913b7d22ded7b22e48a49aa015050d8dd8464eaa010ba2e41", + "sha256:572f69d2d0a3d3d83ebfb2c24e6d73d88b85a09f5da796974ef4a0ad83ff7cde", + "sha256:6735486ee9c3cb0807476e2b36ef7a4cd6c597cb24abf496e66b703360e1e54e", + "sha256:68ea22aee9c269a6a0c1061c141f1ec1cd1b1be7569390519c1bf4773f434a40", + "sha256:784ab8217e4b0eb4d121c28430c6cdc2ce56c02634a9720d84fb30598b338b8c", + "sha256:7ed67b47cdf6598a79583de5b57c595493eac2b8b6b3a828f912354716cb8149", + "sha256:8f364528f70d895b96a0de36c7c6002644bf4c5df1ee3fbfa775f5cee6571ad7", + "sha256:bbcfb04738099bd46822db91584db74703fdddacf4cd0a76acfc5e086956b5ba", + "sha256:c332c7fc5cfd54cb86d5da99787c9693e3a924848097c54df1b71ee595a39c93", + "sha256:dc5548562308acde7931f040e73d46ae31b398924cf675c3486fd3504e00a4af", + "sha256:f5f27528570fc0d7b90668be10c5dfd90d6ceb8fd2ed62d7d679554acb616bfe" ], "index": "pypi", - "version": "==2.3.0" + "version": "==2.2" }, "tensorflow-estimator": { "hashes": [ - "sha256:b75e034300ccb169403cf2695adf3368da68863aeb0c14c3760064c713d5c486" + "sha256:d09dacdd127f2579cea8d5af21f4a918036b8ae246adc82f26b61f91cc247dc2" ], - "version": "==2.3.0" + "version": "==2.2.0" }, "termcolor": { "hashes": [ @@ -2939,11 +2967,11 @@ }, "virtualenv": { "hashes": [ - "sha256:688a61d7976d82b92f7906c367e83bb4b3f0af96f8f75bfcd3da95608fe8ac6c", - "sha256:8f582a030156282a9ee9d319984b759a232b07f86048c1d6a9e394afa44e78c8" + "sha256:7b54fd606a1b85f83de49ad8d80dbec08e983a2d2f96685045b262ebc7481ee5", + "sha256:8cd7b2a4850b003a11be2fc213e206419efab41115cc14bca20e69654f2ac08e" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==20.0.28" + "version": "==20.0.30" }, "wcwidth": { "hashes": [ @@ -2990,26 +3018,26 @@ }, "yarl": { "hashes": [ - "sha256:1707230e1ea48ea06a3e20acb4ce05a38d2465bd9566c21f48f6212a88e47536", - "sha256:1f269e8e6676193a94635399a77c9059e1826fb6265c9204c9e5a8ccd36006e1", - "sha256:2657716c1fc998f5f2675c0ee6ce91282e0da0ea9e4a94b584bb1917e11c1559", - "sha256:431faa6858f0ea323714d8b7b4a7da1db2eeb9403607f0eaa3800ab2c5a4b627", - "sha256:5bbcb195da7de57f4508b7508c33f7593e9516e27732d08b9aad8586c7b8c384", - "sha256:5c82f5b1499342339f22c83b97dbe2b8a09e47163fab86cd934a8dd46620e0fb", - "sha256:5d410f69b4f92c5e1e2a8ffb73337cd8a274388c6975091735795588a538e605", - "sha256:66b4f345e9573e004b1af184bc00431145cf5e089a4dcc1351505c1f5750192c", - "sha256:875b2a741ce0208f3b818008a859ab5d0f461e98a32bbdc6af82231a9e761c55", - "sha256:9a3266b047d15e78bba38c8455bf68b391c040231ca5965ef867f7cbbc60bde5", - "sha256:9a592c4aa642249e9bdaf76897d90feeb08118626b363a6be8788a9b300274b5", - "sha256:a1772068401d425e803999dada29a6babf041786e08be5e79ef63c9ecc4c9575", - "sha256:b065a5c3e050395ae563019253cc6c769a50fd82d7fa92d07476273521d56b7c", - "sha256:b325fefd574ebef50e391a1072d1712a60348ca29c183e1d546c9d87fec2cd32", - "sha256:cf5eb664910d759bbae0b76d060d6e21f8af5098242d66c448bbebaf2a7bfa70", - "sha256:f058b6541477022c7b54db37229f87dacf3b565de4f901ff5a0a78556a174fea", - "sha256:f5cfed0766837303f688196aa7002730d62c5cc802d98c6395ea1feb87252727" + "sha256:040b237f58ff7d800e6e0fd89c8439b841f777dd99b4a9cca04d6935564b9409", + "sha256:17668ec6722b1b7a3a05cc0167659f6c95b436d25a36c2d52db0eca7d3f72593", + "sha256:3a584b28086bc93c888a6c2aa5c92ed1ae20932f078c46509a66dce9ea5533f2", + "sha256:4439be27e4eee76c7632c2427ca5e73703151b22cae23e64adb243a9c2f565d8", + "sha256:48e918b05850fffb070a496d2b5f97fc31d15d94ca33d3d08a4f86e26d4e7c5d", + "sha256:9102b59e8337f9874638fcfc9ac3734a0cfadb100e47d55c20d0dc6087fb4692", + "sha256:9b930776c0ae0c691776f4d2891ebc5362af86f152dd0da463a6614074cb1b02", + "sha256:b3b9ad80f8b68519cc3372a6ca85ae02cc5a8807723ac366b53c0f089db19e4a", + "sha256:bc2f976c0e918659f723401c4f834deb8a8e7798a71be4382e024bcc3f7e23a8", + "sha256:c22c75b5f394f3d47105045ea551e08a3e804dc7e01b37800ca35b58f856c3d6", + "sha256:c52ce2883dc193824989a9b97a76ca86ecd1fa7955b14f87bf367a61b6232511", + "sha256:ce584af5de8830d8701b8979b18fcf450cef9a382b1a3c8ef189bedc408faf1e", + "sha256:da456eeec17fa8aa4594d9a9f27c0b1060b6a75f2419fe0c00609587b2695f4a", + "sha256:db6db0f45d2c63ddb1a9d18d1b9b22f308e52c83638c26b422d520a815c4b3fb", + "sha256:df89642981b94e7db5596818499c4b2219028f2a528c9c37cc1de45bf2fd3a3f", + "sha256:f18d68f2be6bf0e89f1521af2b1bb46e66ab0018faafa81d70f358153170a317", + "sha256:f379b7f83f23fe12823085cd6b906edc49df969eb99757f58ff382349a3303c6" ], "markers": "python_version >= '3.5'", - "version": "==1.5.0" + "version": "==1.5.1" } } } From 5e82578a1b66a1e13753d2258f32950aece48942 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 8 Aug 2020 11:48:16 -0700 Subject: [PATCH 583/656] Remove non-SCC Hyundai Kona port (#1997) --- README.md | 1 - selfdrive/car/hyundai/interface.py | 8 -------- selfdrive/car/hyundai/values.py | 9 ++------- selfdrive/test/test_car_models.py | 1 - 4 files changed, 2 insertions(+), 17 deletions(-) diff --git a/README.md b/README.md index 4e94139637..a1ac60958c 100644 --- a/README.md +++ b/README.md @@ -144,7 +144,6 @@ Community Maintained Cars and Features | Hyundai | Genesis 2015-16 | SCC + LKAS | Stock | 19mph | 37mph | | Hyundai | Ioniq Electric Premium SE 2020| SCC + LKAS | Stock | 0mph | 32mph | | Hyundai | Ioniq Electric Limited 2019 | SCC + LKAS | Stock | 0mph | 32mph | -| Hyundai | Kona 2017-19 | SCC + LKAS | Stock | 22mph | 0mph | | Hyundai | Kona EV 2019 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Palisade 2020 | All | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 9ae6853a07..3379eeb9ff 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -110,14 +110,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.4 * 1.15 # 15% higher at the center seems reasonable ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate == CAR.KONA: - ret.lateralTuning.pid.kf = 0.00006 - ret.mass = 1275. + STD_CARGO_KG - ret.wheelbase = 2.7 - ret.steerRatio = 13.73 # Spec - tire_stiffness_factor = 0.385 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KONA_EV: ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1685. + STD_CARGO_KG diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index e9ff162cfb..b6c7030eb6 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -27,7 +27,6 @@ class CAR: KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019" KIA_SORENTO = "KIA SORENTO GT LINE 2018" KIA_STINGER = "KIA STINGER GT2 2018" - KONA = "HYUNDAI KONA 2019" KONA_EV = "HYUNDAI KONA ELECTRIC 2019" SANTA_FE = "HYUNDAI SANTA FE LIMITED 2019" SONATA = "HYUNDAI SONATA 2020" @@ -119,9 +118,6 @@ FINGERPRINTS = { }, { 68:8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 8, 576:8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1473: 8, 1476: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 - }], - CAR.KONA: [{ - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 909: 8, 916: 8, 1040: 8, 1078: 4, 1107: 5, 1136: 8, 1156: 8, 1170: 8, 1173: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 2004: 8, 2009: 8, 2012: 8 }], CAR.KONA_EV: [{ 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 549: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1307: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1378: 4, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8 @@ -237,12 +233,12 @@ CHECKSUM = { FEATURES = { # which message has the gear - "use_cluster_gears": set([CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30]), + "use_cluster_gears": set([CAR.ELANTRA, CAR.ELANTRA_GT_I30]), "use_tcu_gears": set([CAR.KIA_OPTIMA, CAR.SONATA_2019, CAR.VELOSTER]), "use_elect_gears": set([CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ]), # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE]), + "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE]), "use_bsm": set([CAR.SONATA, CAR.PALISADE, CAR.HYUNDAI_GENESIS, CAR.GENESIS_G80, CAR.GENESIS_G90]), } @@ -262,7 +258,6 @@ DBC = { CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None), CAR.KIA_SORENTO: dbc_dict('hyundai_kia_generic', None), CAR.KIA_STINGER: dbc_dict('hyundai_kia_generic', None), - CAR.KONA: dbc_dict('hyundai_kia_generic', None), CAR.KONA_EV: dbc_dict('hyundai_kia_generic', None), CAR.SANTA_FE: dbc_dict('hyundai_kia_generic', None), CAR.SONATA: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 539c330038..9581454ee2 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -441,7 +441,6 @@ non_tested_cars = [ HYUNDAI.GENESIS_G90, HYUNDAI.KIA_FORTE, HYUNDAI.KIA_OPTIMA_H, - HYUNDAI.KONA, HYUNDAI.KONA_EV, TOYOTA.CAMRYH, TOYOTA.CHR, From ee99b59bade8d3b5057a5b3f22ad8b3edd102c78 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 8 Aug 2020 11:49:13 -0700 Subject: [PATCH 584/656] fix missing negative limit in pid controller (#2001) --- selfdrive/controls/lib/latcontrol_pid.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/latcontrol_pid.py b/selfdrive/controls/lib/latcontrol_pid.py index 5662942b8f..aa069e81fc 100644 --- a/selfdrive/controls/lib/latcontrol_pid.py +++ b/selfdrive/controls/lib/latcontrol_pid.py @@ -8,7 +8,8 @@ class LatControlPID(): def __init__(self, CP): self.pid = PIController((CP.lateralTuning.pid.kpBP, CP.lateralTuning.pid.kpV), (CP.lateralTuning.pid.kiBP, CP.lateralTuning.pid.kiV), - k_f=CP.lateralTuning.pid.kf, pos_limit=1.0, sat_limit=CP.steerLimitTimer) + k_f=CP.lateralTuning.pid.kf, pos_limit=1.0, neg_limit=-1.0, + sat_limit=CP.steerLimitTimer) self.angle_steers_des = 0. def reset(self): From cea8b9e67a34d39716f4be1e8be64e7aa8fca306 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 8 Aug 2020 14:30:31 -0700 Subject: [PATCH 585/656] update_ci_routes.py: upload route by arg --- selfdrive/test/update_ci_routes.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py index 7e5217738f..ee9dde6ee5 100755 --- a/selfdrive/test/update_ci_routes.py +++ b/selfdrive/test/update_ci_routes.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +import sys import subprocess from common.basedir import BASEDIR from azure.storage.blob import BlockBlobService @@ -54,17 +55,16 @@ def sync_to_ci_public(route): if __name__ == "__main__": failed_routes = [] - # sync process replay routes - for s in replay_segments: - route_name, _ = s[1].rsplit('--', 1) - if not sync_to_ci_public(route_name): - failed_routes.append(route_name) + to_sync = sys.argv[1:] - # sync test_car_models routes - for r in list(test_car_models_routes.keys()): + if not len(to_sync): + # sync routes from test_car_models and process replay + to_sync.extend(test_car_models_routes.keys()) + to_sync.extend([s[1].rsplit('--', 1)[0] for s in replay_segments]) + + for r in to_sync: if not sync_to_ci_public(r): failed_routes.append(r) if len(failed_routes): - print("failed routes:") - print(failed_routes) + print("failed routes:", failed_routes) From cccb63229d9b6d953bfa62b57327d345403c85b2 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 9 Aug 2020 06:50:36 +0800 Subject: [PATCH 586/656] fix bug that visionstream_destroy may be called twice (#1999) --- selfdrive/modeld/dmonitoringmodeld.cc | 5 +---- selfdrive/modeld/modeld.cc | 4 +--- 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/selfdrive/modeld/dmonitoringmodeld.cc b/selfdrive/modeld/dmonitoringmodeld.cc index 140b567ad3..28776f94ee 100644 --- a/selfdrive/modeld/dmonitoringmodeld.cc +++ b/selfdrive/modeld/dmonitoringmodeld.cc @@ -56,7 +56,6 @@ int main(int argc, char **argv) { buf = visionstream_get(&stream, &extra); if (buf == NULL) { printf("visionstream get failed\n"); - visionstream_destroy(&stream); break; } //printf("frame_id: %d %dx%d\n", extra.frame_id, buf_info.width, buf_info.height); @@ -84,11 +83,9 @@ int main(int argc, char **argv) { LOGD("dmonitoring process: %.2fms, from last %.2fms", t2-t1, t1-last); last = t1; } - + visionstream_destroy(&stream); } - visionstream_destroy(&stream); - dmonitoring_free(&dmonitoringmodel); return 0; diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index f367c99097..33dafc86cf 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -190,7 +190,6 @@ int main(int argc, char **argv) { buf = visionstream_get(&stream, &extra); if (buf == NULL) { LOGW("visionstream get failed"); - visionstream_destroy(&stream); break; } @@ -239,10 +238,9 @@ int main(int argc, char **argv) { } visionbuf_free(&yuv_ion); + visionstream_destroy(&stream); } - visionstream_destroy(&stream); - model_free(&model); LOG("joining live_thread"); From 55ece6991e1fdeb4b109e47c978c4da2a3b23594 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 9 Aug 2020 06:55:09 +0800 Subject: [PATCH 587/656] camerad: close ops_sock in camera_close (#1998) --- selfdrive/camerad/cameras/camera_qcom.cc | 11 ++++++----- selfdrive/camerad/cameras/camera_qcom.h | 4 +++- 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index 79e6c8f097..6e9c3e3a24 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -12,7 +12,6 @@ #include #include -#include #include #include "msmb_isp.h" #include "msmb_ispif.h" @@ -125,9 +124,9 @@ static void camera_init(CameraState *s, int camera_id, int camera_num, s->self_recover = 0; - zsock_t *ops_sock = zsock_new_push(">inproc://cameraops"); - assert(ops_sock); - s->ops_sock = zsock_resolve(ops_sock); + s->ops_sock = zsock_new_push(">inproc://cameraops"); + assert(s->ops_sock); + s->ops_sock_handle = zsock_resolve(s->ops_sock); tbuffer_init2(&s->camera_tb, FRAME_BUF_COUNT, "frame", camera_release_buffer, s); @@ -448,7 +447,7 @@ void camera_autoexposure(CameraState *s, float grey_frac) { .grey_frac = grey_frac, }; - zmq_send(s->ops_sock, &msg, sizeof(msg), ZMQ_DONTWAIT); + zmq_send(s->ops_sock_handle, &msg, sizeof(msg), ZMQ_DONTWAIT); } static uint8_t* get_eeprom(int eeprom_fd, size_t *out_len) { @@ -1956,6 +1955,8 @@ static void camera_close(CameraState *s) { } free(s->eeprom); + + zsock_destroy(&s->ops_sock); } diff --git a/selfdrive/camerad/cameras/camera_qcom.h b/selfdrive/camerad/cameras/camera_qcom.h index 063b813c7b..81c84b9ebf 100644 --- a/selfdrive/camerad/cameras/camera_qcom.h +++ b/selfdrive/camerad/cameras/camera_qcom.h @@ -4,6 +4,7 @@ #include #include #include +#include #include "messaging.hpp" #include "msmb_isp.h" @@ -61,7 +62,8 @@ typedef struct CameraState { int device; - void* ops_sock; + void* ops_sock_handle; + zsock_t * ops_sock; uint32_t pixel_clock; uint32_t line_length_pclk; From ecf0a8c8d49dddb18767d929d381f5bbf946c5d8 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 8 Aug 2020 20:59:32 -0700 Subject: [PATCH 588/656] Improve CPU usage test reliability (#2002) * run phone tests in parallel * better cpu test * re-enable test * no root * terms version * not one * yes * debug * that's coverd by min cpu percent --- Jenkinsfile | 91 ++++++++++++++++++-------------- selfdrive/test/helpers.py | 4 +- selfdrive/test/test_cpu_usage.py | 59 +++++++++------------ 3 files changed, 77 insertions(+), 77 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 0fd2b00a4d..ff8b4a9c01 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -36,16 +36,31 @@ pipeline { } stages { + + stage('Release Build') { + when { + branch 'devel-staging' + } + steps { + phone_steps("eon-build", [ + ["build release2-staging and dashcam-staging", "cd release && PUSH=1 ./build_release2.sh"], + ]) + } + } + stage('openpilot tests') { when { not { anyOf { - branch 'master-ci'; branch 'devel'; branch 'release2'; branch 'release2-staging'; branch 'dashcam'; branch 'dashcam-staging' + branch 'master-ci'; branch 'devel'; branch 'devel-staging'; branch 'release2'; branch 'release2-staging'; branch 'dashcam'; branch 'dashcam-staging' } } } - parallel { + + stages { + + /* stage('PC tests') { agent { dockerfile { @@ -67,6 +82,7 @@ pipeline { } } } + */ stage('On-device Tests') { agent { @@ -75,53 +91,46 @@ pipeline { args '--user=root' } } + stages { + stage('parallel tests') { + parallel { - stage('Release Build') { - when { - branch 'devel-staging' - } - steps { - phone_steps("eon-build", [ - ["build release2-staging and dashcam-staging", "cd release && PUSH=1 ./build_release2.sh"], - ]) - } - } + stage('Devel Build') { + environment { + CI_PUSH = "${env.BRANCH_NAME == 'master' ? 'master-ci' : ' '}" + } + steps { + phone_steps("eon", [ + ["build devel", "cd release && CI_PUSH=${env.CI_PUSH} ./build_devel.sh"], + ["test openpilot", "nosetests -s selfdrive/test/test_openpilot.py"], + ["test cpu usage", "cd selfdrive/test/ && ./test_cpu_usage.py"], + ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], + ]) + } + } - stage('Devel Build') { - environment { - CI_PUSH = "${env.BRANCH_NAME == 'master' ? 'master-ci' : ' '}" - } - steps { - phone_steps("eon", [ - ["build devel", "cd release && CI_PUSH=${env.CI_PUSH} ./build_devel.sh"], - ["test openpilot", "nosetests -s selfdrive/test/test_openpilot.py"], - //["test cpu usage", "cd selfdrive/test/ && ./test_cpu_usage.py"], - ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], - ]) - } - } + stage('Replay Tests') { + steps { + phone_steps("eon2", [ + ["camerad/modeld replay", "cd selfdrive/test/process_replay && ./camera_replay.py"], + ]) + } + } - stage('Replay Tests') { - steps { - phone_steps("eon2", [ - ["camerad/modeld replay", "cd selfdrive/test/process_replay && ./camera_replay.py"], - ]) - } - } + stage('HW Tests') { + steps { + phone_steps("eon", [ + ["build cereal", "SCONS_CACHE=1 scons -j4 cereal/"], + ["test sounds", "nosetests -s selfdrive/test/test_sounds.py"], + ["test boardd loopback", "nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"], + ]) + } + } - stage('HW Tests') { - steps { - phone_steps("eon", [ - ["build cereal", "SCONS_CACHE=1 scons -j4 cereal/"], - ["test sounds", "nosetests -s selfdrive/test/test_sounds.py"], - ["test boardd loopback", "nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"], - ]) } } - } - } } diff --git a/selfdrive/test/helpers.py b/selfdrive/test/helpers.py index 733c09dc72..1e53ef4245 100644 --- a/selfdrive/test/helpers.py +++ b/selfdrive/test/helpers.py @@ -5,12 +5,12 @@ from nose.tools import nottest from common.android import ANDROID from common.apk import update_apks, start_offroad, pm_apply_packages, android_packages from common.params import Params -from selfdrive.version import training_version +from selfdrive.version import training_version, terms_version from selfdrive.manager import start_managed_process, kill_managed_process, get_running def set_params_enabled(): params = Params() - params.put("HasAcceptedTerms", "1") + params.put("HasAcceptedTerms", terms_version) params.put("HasCompletedSetup", "1") params.put("OpenpilotEnabledToggle", "1") params.put("CommunityFeaturesToggle", "1") diff --git a/selfdrive/test/test_cpu_usage.py b/selfdrive/test/test_cpu_usage.py index d6d2841c7e..92f8de4ddc 100755 --- a/selfdrive/test/test_cpu_usage.py +++ b/selfdrive/test/test_cpu_usage.py @@ -1,13 +1,12 @@ #!/usr/bin/env python3 +import os import time -import threading -import _thread -import signal import sys +import subprocess import cereal.messaging as messaging +from common.basedir import BASEDIR from common.params import Params -import selfdrive.manager as manager from selfdrive.test.helpers import set_params_enabled def cputime_total(ct): @@ -40,7 +39,7 @@ def print_cpu_usage(first_proc, last_proc): ("./logcatd", 0), ] - r = 0 + r = True dt = (last_proc.logMonoTime - first_proc.logMonoTime) / 1e9 result = "------------------------------------------------\n" for proc_name, normal_cpu_usage in procs: @@ -51,26 +50,25 @@ def print_cpu_usage(first_proc, last_proc): cpu_usage = cpu_time / dt * 100. if cpu_usage > max(normal_cpu_usage * 1.1, normal_cpu_usage + 5.0): result += f"Warning {proc_name} using more CPU than normal\n" - r = 1 + r = False elif cpu_usage < min(normal_cpu_usage * 0.3, max(normal_cpu_usage - 1.0, 0.0)): result += f"Warning {proc_name} using less CPU than normal\n" - r = 1 + r = False result += f"{proc_name.ljust(35)} {cpu_usage:.2f}%\n" except IndexError: result += f"{proc_name.ljust(35)} NO METRICS FOUND\n" - r = 1 + r = False result += "------------------------------------------------\n" print(result) return r -def all_running(): - running = manager.get_running() - return all(p in running and running[p].is_alive() for p in manager.car_started_processes) +def test_cpu_usage(): + cpu_ok = False -return_code = 1 -def test_thread(): + # start manager + manager_path = os.path.join(BASEDIR, "selfdrive/manager.py") + manager_proc = subprocess.Popen(["python", manager_path]) try: - global return_code proc_sock = messaging.sub_sock('procLog', conflate=True, timeout=2000) # wait until everything's started and get first sample @@ -80,33 +78,26 @@ def test_thread(): break time.sleep(2) first_proc = messaging.recv_sock(proc_sock, wait=True) - if first_proc is None or not all_running(): - err_msg = "procLog recv timed out" if first_proc is None else "all car started process not running" - print(f"\n\nTEST FAILED: {err_msg}\n\n") - raise Exception + if first_proc is None: + raise Exception("\n\nTEST FAILED: progLog recv timed out\n\n") # run for a minute and get last sample time.sleep(60) last_proc = messaging.recv_sock(proc_sock, wait=True) - return_code = print_cpu_usage(first_proc, last_proc) - if not all_running(): - return_code = 1 + cpu_ok = print_cpu_usage(first_proc, last_proc) finally: - _thread.interrupt_main() + manager_proc.terminate() + ret = manager_proc.wait(20) + if ret is None: + manager_proc.kill() + return cpu_ok if __name__ == "__main__": - - - # setup signal handler to exit with test status - def handle_exit(sig, frame): - sys.exit(return_code) - signal.signal(signal.SIGINT, handle_exit) - - # start manager and test thread set_params_enabled() Params().delete("CarParams") - t = threading.Thread(target=test_thread) - t.daemon = True - t.start() - manager.main() + passed = False + try: + passed = test_cpu_usage() + finally: + sys.exit(int(not passed)) From a16a948f9ee434c69a72f8aac39405a14ba62073 Mon Sep 17 00:00:00 2001 From: xps-genesis <65239463+xps-genesis@users.noreply.github.com> Date: Sun, 9 Aug 2020 01:20:25 -0400 Subject: [PATCH 589/656] Car Port: Hyundai Genesis G70 2018 (#2000) * Car port Genesis G70 * Car port G70 * rebase * update G70 car port * Update README.md * no space * rebase mistake * Update values.py * Update values.py * Update values.py Co-authored-by: Adeeb Shihadeh --- README.md | 1 + selfdrive/car/hyundai/interface.py | 10 +++++++++- selfdrive/car/hyundai/values.py | 19 ++++++++++++++++--- selfdrive/test/test_car_models.py | 4 ++++ 4 files changed, 30 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index a1ac60958c..ba206e6b78 100644 --- a/README.md +++ b/README.md @@ -149,6 +149,7 @@ Community Maintained Cars and Features | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2019 | All | Stock | 0mph | 0mph | | Hyundai | Veloster 2019 | SCC + LKAS | Stock | 5mph | 0mph | +| Hyundai | Genesis G70 2018 | SCC + LKAS | Stock | 0mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | | Kia | Forte 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 3379eeb9ff..7d0d35c4cf 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -82,6 +82,13 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]] ret.minSteerSpeed = 60 * CV.KPH_TO_MS + elif candidate == CAR.GENESIS_G70: + ret.lateralTuning.pid.kf = 0.00005 + ret.mass = 1640. + STD_CARGO_KG + ret.wheelbase = 2.84 + ret.steerRatio = 16.5 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]] elif candidate == CAR.GENESIS_G80: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 2060. + STD_CARGO_KG @@ -145,7 +152,8 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] # these cars require a special panda safety mode due to missing counters and checksums in the messages - if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_2019, CAR.KIA_OPTIMA, CAR.VELOSTER, CAR.KIA_STINGER]: + if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_2019, + CAR.KIA_OPTIMA, CAR.VELOSTER, CAR.KIA_STINGER, CAR.GENESIS_G70]: ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy ret.centerToFront = ret.wheelbase * 0.4 diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index b6c7030eb6..0dd217112c 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -17,6 +17,7 @@ class SteerLimitParams: class CAR: ELANTRA = "HYUNDAI ELANTRA LIMITED ULTIMATE 2017" ELANTRA_GT_I30 = "HYUNDAI I30 N LINE 2019 & GT 2018 DCT" + GENESIS_G70 = "GENESIS G70 2018" GENESIS_G80 = "GENESIS G80 2017" GENESIS_G90 = "GENESIS G90 2017" HYUNDAI_GENESIS = "HYUNDAI GENESIS 2015-2016" @@ -98,6 +99,9 @@ FINGERPRINTS = { CAR.KIA_STINGER: [{ 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8 }], + CAR.GENESIS_G70: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832:8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1168: 7, 1170: 8, 1173:8, 1184: 8, 1186: 2, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1407: 8, 1419:8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8 + }], CAR.GENESIS_G80: [{ 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1024: 2, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8 }, @@ -144,7 +148,7 @@ ECU_FINGERPRINT = { } # Don't use these fingerprints for fingerprinting, they are still used for ECU detection -IGNORED_FINGERPRINTS = [CAR.VELOSTER] +IGNORED_FINGERPRINTS = [CAR.VELOSTER, CAR.GENESIS_G70] FW_VERSIONS = { CAR.SONATA: { @@ -223,6 +227,14 @@ FW_VERSIONS = { (Ecu.eps, 0x7d4, None): [b'\xf1\x00JSL MDPS C 1.00 1.03 56340-J3000 8308', ], (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', ], (Ecu.transmission, 0x7e1, None): [b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16NS1\xba\x02\xb8\x80', ], + }, + CAR.GENESIS_G70: { + (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 \xf1\xa01.02', ], + (Ecu.esp, 0x7d1, None): [b'\xf1\x00\x00\x00\x00\x00\x00\x00', ], + (Ecu.engine, 0x7e0, None): [b'\xf1\x81640F0051\x00\x00\x00\x00\x00\x00\x00\x00', ], + (Ecu.eps, 0x7d4, None): [b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9420 4I4VL106', ], + (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', ], + (Ecu.transmission, 0x7e1, None): [b'\xf1\x87VDJLT17895112DN4\x88fVf\x99\x88\x88\x88\x87fVe\x88vhwwUFU\x97eFex\x99\xff\xb7\x82\xf1\x81E25\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB2\x11\x1am\xda', ], } } @@ -238,9 +250,9 @@ FEATURES = { "use_elect_gears": set([CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ]), # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE]), + "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE, CAR.GENESIS_G70]), - "use_bsm": set([CAR.SONATA, CAR.PALISADE, CAR.HYUNDAI_GENESIS, CAR.GENESIS_G80, CAR.GENESIS_G90]), + "use_bsm": set([CAR.SONATA, CAR.PALISADE, CAR.HYUNDAI_GENESIS, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.GENESIS_G90]), } EV_HYBRID = set([CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV]) @@ -248,6 +260,7 @@ EV_HYBRID = set([CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV]) DBC = { CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None), CAR.ELANTRA_GT_I30: dbc_dict('hyundai_kia_generic', None), + CAR.GENESIS_G70: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G80: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G90: dbc_dict('hyundai_kia_generic', None), CAR.HYUNDAI_GENESIS: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 9581454ee2..e55f5fbd4f 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -172,6 +172,10 @@ routes = { 'carFingerprint': HYUNDAI.HYUNDAI_GENESIS, 'enableCamera': True, }, + "70c5bec28ec8e345|2020-08-08--12-22-23": { + 'carFingerprint': HYUNDAI.GENESIS_G70, + 'enableCamera': True, + }, "38bfd238edecbcd7|2018-08-22--09-45-44": { 'carFingerprint': HYUNDAI.SANTA_FE, 'enableCamera': False, From 424205325b239af3b6b3e25804ce53158146ace8 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 8 Aug 2020 22:36:26 -0700 Subject: [PATCH 590/656] add genesis g70 to release notes --- RELEASES.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index e337bd5380..d1c622b545 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,7 +1,8 @@ Version 0.7.8 (2020-08-XX) ======================== * New driver monitoring model - * Hyundai Veloster 2019 support thanks to xps-gensis! + * Improved updater reliability and responsiveness + * Hyundai Genesis G70 2018 and Veloster 2019 support thanks to xps-genesis! Version 0.7.7 (2020-07-20) ======================== From 4f0c75291b9c56b9eb219cbe74025c6897635d85 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Sun, 9 Aug 2020 11:08:09 +0300 Subject: [PATCH 591/656] fix for PC: detach panda kernel driver if active (#1950) --- selfdrive/boardd/panda.cc | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 8bec943457..5820fa4004 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -25,6 +25,10 @@ Panda::Panda(){ dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); if (dev_handle == NULL) { goto fail; } + if (libusb_kernel_driver_active(dev_handle, 0) == 1) { + libusb_detach_kernel_driver(dev_handle, 0); + } + err = libusb_set_configuration(dev_handle, 1); if (err != 0) { goto fail; } From 5bd20dbe38376aad697a155707a187ac693f59f2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 9 Aug 2020 15:05:43 -0700 Subject: [PATCH 592/656] default pull request template --- .github/pull_request_template.md | 52 ++++++++++++++++++++++++++++++++ 1 file changed, 52 insertions(+) create mode 100644 .github/pull_request_template.md diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md new file mode 100644 index 0000000000..0457bef9f4 --- /dev/null +++ b/.github/pull_request_template.md @@ -0,0 +1,52 @@ + + +**Description** + + + +**Verification** + + + +**Route** + +Route: [a route with the bug fix] + + + + +**Description** + + + +**Verification** + + + + + + +**Checklist** + +- [ ] added to README +- [ ] test route added to [test_car_models](../../selfdrive/test/test_car_models.py) +- [ ] route with openpilot: +- [ ] route with stock system: + + + + +**Description** + + + +**Verification** + + + +--> From d6288c1bb9796cb19571d1bc035d9a7d6014c559 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 9 Aug 2020 15:17:44 -0700 Subject: [PATCH 593/656] can't do nested html comments --- .github/pull_request_template.md | 42 +++++++++++--------------------- 1 file changed, 14 insertions(+), 28 deletions(-) diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index 0457bef9f4..d09fb55490 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -1,52 +1,38 @@ - -Please copy and paste the relevant template + - -**Description** - - - -**Verification** - - +**Verification** [](Explain how you tested this bug fix.) **Route** - Route: [a route with the bug fix] +--> - - -**Description** - - + +**Verification** [](Explain how you tested this bug fix.) +--> - + - - -**Description** - - + +**Verification** [](Explain how you tested the refactor for regressions.) --> From c450110f961173302bec7873b81939f01d5ad1ac Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 10 Aug 2020 00:44:24 -0700 Subject: [PATCH 594/656] Build openpilot on mac in CI (#1792) * build on mac in CI * coreutils * python stuff * pipenv * newer clang * init pyenv * verbose * init pyenv * install eigen * ffmpeg * sdl * libav * libtool * glfw * add pipfile as cache key * test cache * fix cache path * brew link * update tools readme * don't cache on pipfile * skip python install if installed * unlink * simpler cachingm * here's your key * cache pip too * cache pyenv --- .github/workflows/test.yaml | 25 +++++++++++++++++++++++++ tools/README.md | 14 +++----------- tools/mac_setup.sh | 26 ++++++++++++++++++++++++++ 3 files changed, 54 insertions(+), 11 deletions(-) create mode 100755 tools/mac_setup.sh diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 02a3c11dde..f8bbb1bc8d 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -48,6 +48,31 @@ jobs: scons -j$(nproc) && \ $UNIT_TEST selfdrive/car" + build_mac: + name: build macos + runs-on: macos-10.15 + timeout-minutes: 35 + steps: + - uses: actions/checkout@v2 + with: + submodules: true + - name: Cache dependencies + id: dependency-cache + uses: actions/cache@v2 + with: + path: | + ~/.pyenv + ~/Library/Caches/pip + ~/Library/Caches/pipenv + ~/Library/Caches/Homebrew + key: ${{ hashFiles('tools/mac_setup.sh') }} + - name: Install dependencies + run: ./tools/mac_setup.sh + - name: Build openpilot + run: eval "$(pyenv init -)" && scons -j$(nproc) + - name: Brew cleanup + run: brew cleanup # keeps our cache small + docker_push: name: docker push runs-on: ubuntu-16.04 diff --git a/tools/README.md b/tools/README.md index 22de4a9b7c..9e0965ff6a 100644 --- a/tools/README.md +++ b/tools/README.md @@ -24,23 +24,15 @@ Table of Contents Requirements ============ -openpilot tools and the following setup steps are developed and tested on Ubuntu 16.04, MacOS 10.14.2 and Python 3.7.3. +openpilot tools and the following setup steps are developed and tested on Ubuntu 16.04, MacOS 10.14.2 and Python 3.8.2. Setup ============ -1. Run ubuntu_setup.sh, make sure everything completed correctly +1. Run `ubuntu_setup.sh` or `mac_setup.sh`, make sure everything completed correctly 2. Compile openpilot by running ```scons``` in the openpilot directory -3. Add some folders to root - ```bash - sudo mkdir /data - sudo mkdir /data/params - sudo chown $USER /data/params - ``` - - -4. Try out some tools! +3. Try out some tools! Tool examples diff --git a/tools/mac_setup.sh b/tools/mac_setup.sh new file mode 100755 index 0000000000..5097000196 --- /dev/null +++ b/tools/mac_setup.sh @@ -0,0 +1,26 @@ +#!/bin/bash -e + +# install brew +/bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install.sh)" + +brew install capnp \ + czmq \ + coreutils \ + eigen \ + ffmpeg \ + glfw \ + libarchive \ + libtool \ + llvm \ + pyenv \ + zeromq + +# install python +pyenv install -s 3.8.2 +pyenv global 3.8.2 +pyenv rehash +eval "$(pyenv init -)" + +pip install pipenv==2018.11.26 +pipenv install --system --deploy + From cb064293a1ac6252583646324f6066f3a6dc50da Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 10 Aug 2020 11:58:32 +0200 Subject: [PATCH 595/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 3a8430b9d5..ed0621137e 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 3a8430b9d5921d09947a2f8ebe622b4a00eb30ac +Subproject commit ed0621137e65a08b8dcef120fa018a14e4c71a34 From ed470453cf9dab18a084ce33acacec76499d3dae Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Mon, 10 Aug 2020 11:58:33 -0700 Subject: [PATCH 596/656] update dm new model description --- RELEASES.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index d1c622b545..a0a12adb6f 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,6 +1,6 @@ Version 0.7.8 (2020-08-XX) ======================== - * New driver monitoring model + * New driver monitoring model: improved face detection and better compatibility with sunglasses * Improved updater reliability and responsiveness * Hyundai Genesis G70 2018 and Veloster 2019 support thanks to xps-genesis! From c9adc4900b2e26d0582cb264da2e547a513de831 Mon Sep 17 00:00:00 2001 From: martinl Date: Mon, 10 Aug 2020 22:31:40 +0300 Subject: [PATCH 597/656] Add preglobal Subaru Forester and Outback (#1993) * Add preglobal Forester and Outback * Tests and values cleanup * Update units in carstate * Remove () * Add OUTBACK_PREGLOBAL_2018 to non_tested_cars * Add replay route for OUTBACK_PREGLOBAL_2018 --- release/files_common | 2 ++ selfdrive/car/subaru/carstate.py | 26 ++++++++++++++++------ selfdrive/car/subaru/interface.py | 21 ++++++++++++++++++ selfdrive/car/subaru/values.py | 37 +++++++++++++++++++++++++++---- selfdrive/test/test_car_models.py | 16 +++++++++++++ 5 files changed, 91 insertions(+), 11 deletions(-) diff --git a/release/files_common b/release/files_common index b1f6e2044d..012ebd59b7 100644 --- a/release/files_common +++ b/release/files_common @@ -525,6 +525,8 @@ opendbc/nissan_leaf_2018.dbc opendbc/subaru_global_2017_generated.dbc opendbc/subaru_outback_2015_generated.dbc +opendbc/subaru_outback_2019_generated.dbc +opendbc/subaru_forester_2017_generated.dbc opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc opendbc/toyota_rav4_2017_pt_generated.dbc diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index 597b016207..5b5e23599c 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -55,11 +55,11 @@ class CarState(CarStateBase): ret.cruiseState.available = cp.vl["CruiseControl"]['Cruise_On'] != 0 ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]['Cruise_Set_Speed'] * CV.KPH_TO_MS - # UDM Legacy: mph = 0 - if self.car_fingerprint == CAR.LEGACY_PREGLOBAL and cp.vl["Dash_State"]['Units'] == 0: + # UDM Forester, Legacy: mph = 0 + if self.car_fingerprint in [CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL] and cp.vl["Dash_State"]['Units'] == 0: ret.cruiseState.speed *= CV.MPH_TO_KPH - # EDM Global: mph = 1, 2; UDM Forester: 7 = mph - elif self.car_fingerprint != CAR.LEGACY_PREGLOBAL and cp.vl["Dash_State"]['Units'] in [1, 2, 7]: + # EDM Global: mph = 1, 2; All Outback: mph = 1, UDM Forester: mph = 7 + elif self.car_fingerprint not in [CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL] and cp.vl["Dash_State"]['Units'] in [1, 2, 7]: ret.cruiseState.speed *= CV.MPH_TO_KPH ret.seatbeltUnlatched = cp.vl["Dashlights"]['SEATBELT_FL'] == 1 @@ -126,19 +126,31 @@ class CarState(CarStateBase): signals += [ ("LKA_Lockout", "Steering_Torque", 0), ] - checks += [ - ("CruiseControl", 50), - ] else: signals += [ ("Steer_Error_1", "Steering_Torque", 0), ("Steer_Warning", "Steering_Torque", 0), ] + checks += [ + ("Dashlights", 10), ("BodyInfo", 10), ("CruiseControl", 20), ] + if CP.carFingerprint == CAR.FORESTER_PREGLOBAL: + checks += [ + ("Dashlights", 20), + ("BodyInfo", 1), + ("CruiseControl", 50), + ] + + if CP.carFingerprint in [CAR.LEGACY_PREGLOBAL, CAR.OUTBACK_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018]: + checks += [ + ("Dashlights", 10), + ("CruiseControl", 50), + ] + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) @staticmethod diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index d9e1af213d..6d65f64f3d 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -64,6 +64,17 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] + if candidate in [CAR.FORESTER_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018]: + ret.safetyParam = 1 # Outback 2018-2019 and Forester have reversed driver torque signal + ret.mass = 1568 + STD_CARGO_KG + ret.wheelbase = 2.67 + ret.centerToFront = ret.wheelbase * 0.5 + ret.steerRatio = 20 # learned, 14 stock + ret.steerActuatorDelay = 0.1 + ret.lateralTuning.pid.kf = 0.000039 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 10., 20.], [0., 10., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.05, 0.2], [0.003, 0.018, 0.025]] + if candidate == CAR.LEGACY_PREGLOBAL: ret.mass = 1568 + STD_CARGO_KG ret.wheelbase = 2.67 @@ -74,6 +85,16 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.1, 0.2], [0.01, 0.02]] + if candidate == CAR.OUTBACK_PREGLOBAL: + ret.mass = 1568 + STD_CARGO_KG + ret.wheelbase = 2.67 + ret.centerToFront = ret.wheelbase * 0.5 + ret.steerRatio = 20 # learned, 14 stock + ret.steerActuatorDelay = 0.1 + ret.lateralTuning.pid.kf = 0.000039 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 10., 20.], [0., 10., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.05, 0.2], [0.003, 0.018, 0.025]] + # TODO: get actual value, for now starting with reasonable value for # civic and scaling by mass and wheelbase ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index daf4634d4a..8cbb6fe72d 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -8,7 +8,10 @@ class CAR: ASCENT = "SUBARU ASCENT LIMITED 2019" IMPREZA = "SUBARU IMPREZA LIMITED 2019" FORESTER = "SUBARU FORESTER 2019" + FORESTER_PREGLOBAL = "SUBARU FORESTER 2017 - 2018" LEGACY_PREGLOBAL = "SUBARU LEGACY 2015 - 2018" + OUTBACK_PREGLOBAL = "SUBARU OUTBACK 2015 - 2017" + OUTBACK_PREGLOBAL_2018 = "SUBARU OUTBACK 2018 - 2019" FINGERPRINTS = { CAR.ASCENT: [{ @@ -19,9 +22,9 @@ FINGERPRINTS = { # SUBARU IMPREZA LIMITED 2019 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1722: 8, 1743: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8 }, - # Crosstrek 2018 (same platform as Impreza) + # SUBARU CROSSTREK 2018 { - 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 256: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8 + 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8 }], CAR.FORESTER: [{ # Forester Sport 2019 @@ -31,6 +34,26 @@ FINGERPRINTS = { { 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 282: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 803: 8, 805: 8, 808: 8, 811: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1651: 8, 1657: 8, 1658: 8, 1677: 8, 1722: 8, 1759: 8, 1787: 5, 1788: 8 }], + CAR.OUTBACK_PREGLOBAL: [{ + # OUTBACK PREMIUM 2.5i 2015 + 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 346: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 392: 8, 640: 8, 642: 8, 644: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 977: 8, 1632: 8, 1745: 8, 1786: 5, 1882: 8, 2015: 8, 2016: 8, 2024: 8, 604: 8, 885: 8, 1788: 8, 316: 8, 1614: 8, 1640: 8, 1657: 8, 1658: 8, 1672: 8, 1743: 8, 1785: 5, 1787: 5 + }, + # OUTBACK PREMIUM 3.6i 2015 + { + 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 392: 8, 604: 8, 640: 8, 642: 8, 644: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 977: 8, 1632: 8, 1745: 8, 1779: 8, 1786: 5 + }, + # OUTBACK LIMITED 2.5i 2018 + { + 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 316: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 392: 8, 554: 8, 604: 8, 640: 8, 642: 8, 644: 8, 805: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1614: 8, 1632: 8, 1657: 8, 1658: 8, 1672: 8, 1722: 8, 1736: 8, 1743: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8 + }], + CAR.OUTBACK_PREGLOBAL_2018: [{ + # OUTBACK LIMITED 3.6R 2019 + 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 316: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 392: 8, 554: 8, 604: 8, 640: 8, 642: 8, 644: 8, 805: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 886: 2, 977: 8, 1614: 8, 1632: 8, 1657: 8, 1658: 8, 1672: 8, 1736: 8, 1743: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 1862: 8, 1870: 8, 1920: 8, 1927: 8, 1928: 8, 1935: 8, 1968: 8, 1976: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], + CAR.FORESTER_PREGLOBAL: [{ + # FORESTER PREMIUM 2.5i 2017 + 2: 8, 112: 8, 117: 8, 128: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 340: 7, 342: 8, 352: 8, 353: 8, 354: 8, 355: 8, 356: 8, 554: 8, 604: 8, 640: 8, 641: 8, 642: 8, 805: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 886: 1, 888: 8, 977: 8, 1398: 8, 1632: 8, 1743: 8, 1744: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 1882: 8, 1895: 8, 1903: 8, 1986: 8, 1994: 8, 2015: 8, 2016: 8, 2024: 8, 644:8, 890:8, 1736:8 + }], CAR.LEGACY_PREGLOBAL: [{ # LEGACY 2.5i 2017 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 392: 8, 604: 8, 640: 8, 642: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1632: 8, 1640: 8, 1736: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 644: 8 @@ -41,7 +64,7 @@ FINGERPRINTS = { }, # LEGACY 2018 { - 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 316: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 392: 8, 554: 8, 604: 8, 640: 8, 642: 8, 805: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1614: 8, 1632: 8, 1640: 8, 1657: 8, 1658: 8, 1672: 8, 1722: 8, 1743: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 2015: 8, 2016: 8, 2024: 8 + 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 316: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 392: 8, 554: 8, 604: 8, 640: 8, 642: 8, 805: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1614: 8, 1632: 8, 1640: 8, 1657: 8, 1658: 8, 1672: 8, 1722: 8, 1743: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 2015: 8, 2016: 8, 2024: 8 }], } @@ -49,7 +72,10 @@ STEER_THRESHOLD = { CAR.ASCENT: 80, CAR.IMPREZA: 80, CAR.FORESTER: 80, + CAR.FORESTER_PREGLOBAL: 75, CAR.LEGACY_PREGLOBAL: 75, + CAR.OUTBACK_PREGLOBAL: 75, + CAR.OUTBACK_PREGLOBAL_2018: 75, } ECU_FINGERPRINT = { @@ -60,7 +86,10 @@ DBC = { CAR.ASCENT: dbc_dict('subaru_global_2017_generated', None), CAR.IMPREZA: dbc_dict('subaru_global_2017_generated', None), CAR.FORESTER: dbc_dict('subaru_global_2017_generated', None), + CAR.FORESTER_PREGLOBAL: dbc_dict('subaru_forester_2017_generated', None), CAR.LEGACY_PREGLOBAL: dbc_dict('subaru_outback_2015_generated', None), + CAR.OUTBACK_PREGLOBAL: dbc_dict('subaru_outback_2015_generated', None), + CAR.OUTBACK_PREGLOBAL_2018: dbc_dict('subaru_outback_2019_generated', None), } -PREGLOBAL_CARS = [CAR.LEGACY_PREGLOBAL] +PREGLOBAL_CARS = [CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL, CAR.OUTBACK_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018] diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index e55f5fbd4f..2d6b68fe96 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -393,10 +393,26 @@ routes = { 'carFingerprint': SUBARU.IMPREZA, 'enableCamera': True, }, + # Dashcam + "95441c38ae8c130e|2020-06-08--12-10-17": { + 'carFingerprint': SUBARU.FORESTER_PREGLOBAL, + 'enableCamera': True, + }, + # Dashcam "df5ca7660000fba8|2020-06-16--17-37-19": { 'carFingerprint': SUBARU.LEGACY_PREGLOBAL, 'enableCamera': True, }, + # Dashcam + "5ab784f361e19b78|2020-06-08--16-30-41": { + 'carFingerprint': SUBARU.OUTBACK_PREGLOBAL, + 'enableCamera': True, + }, + # Dashcam + "e19eb5d5353b1ac1|2020-08-09--14-37-56": { + 'carFingerprint': SUBARU.OUTBACK_PREGLOBAL_2018, + 'enableCamera': True, + }, "fbbfa6af821552b9|2020-03-03--08-09-43": { 'carFingerprint': NISSAN.XTRAIL, 'enableCamera': True, From c2405a47b0fcc6f9eabbd7d26c019ebe6ce831f1 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Mon, 10 Aug 2020 13:47:13 -0700 Subject: [PATCH 598/656] Fix Readme --- RELEASES.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index a0a12adb6f..0d30068db5 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -2,7 +2,7 @@ Version 0.7.8 (2020-08-XX) ======================== * New driver monitoring model: improved face detection and better compatibility with sunglasses * Improved updater reliability and responsiveness - * Hyundai Genesis G70 2018 and Veloster 2019 support thanks to xps-genesis! + * Genesis G70 2018 and Hyundai Veloster 2019 support thanks to xps-genesis! Version 0.7.7 (2020-07-20) ======================== From c2a6ae6e540e2783ff17034a5cf8f62e5d275ebb Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Mon, 10 Aug 2020 13:50:14 -0700 Subject: [PATCH 599/656] Fix Genesis G70 in readme --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index ba206e6b78..8afe3fc6c3 100644 --- a/README.md +++ b/README.md @@ -136,6 +136,7 @@ Community Maintained Cars and Features | Chrysler | Pacifica 2020 | Adaptive Cruise | Stock | 0mph | 39mph | | Chrysler | Pacifica Hybrid 2017-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Chrysler | Pacifica Hybrid 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | +| Genesis | G70 2018 | All | Stock | 0mph | 0mph | | Genesis | G80 2018 | All | Stock | 0mph | 0mph | | Genesis | G90 2018 | All | Stock | 0mph | 0mph | | GMC | Acadia Denali 20182| Adaptive Cruise | openpilot | 0mph | 7mph | @@ -149,7 +150,6 @@ Community Maintained Cars and Features | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2019 | All | Stock | 0mph | 0mph | | Hyundai | Veloster 2019 | SCC + LKAS | Stock | 5mph | 0mph | -| Hyundai | Genesis G70 2018 | SCC + LKAS | Stock | 0mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | | Kia | Forte 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | From 1f4714ba9807e3b641154d06479c6ee76b684242 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 10 Aug 2020 21:52:26 -0700 Subject: [PATCH 600/656] Test standalone binary builds in CI (#2008) * test updater, spinner, and text window build in CI * we dont ship the libs for updater in release branches --- Jenkinsfile | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Jenkinsfile b/Jenkinsfile index ff8b4a9c01..83c9007f0a 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -106,6 +106,8 @@ pipeline { ["test openpilot", "nosetests -s selfdrive/test/test_openpilot.py"], ["test cpu usage", "cd selfdrive/test/ && ./test_cpu_usage.py"], ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], + ["test spinner build", "cd selfdrive/ui/spinner && make clean && make"], + ["test text window build", "cd selfdrive/ui/text && make clean && make"], ]) } } From 8c9378af794c49e1e1958863b5b0feef10dd771d Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Tue, 11 Aug 2020 13:29:19 -0500 Subject: [PATCH 601/656] Added additional IS 300 engine f/w (#2015) @Asochgelt#1815 DongleID|route 3da61f28d4ece0e8|2020-08-11--09-25-48 Also expanded the firmware layout to make additional f/w entries easier. --- selfdrive/car/toyota/values.py | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 93a98e9e67..da18bfba96 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -713,15 +713,24 @@ FW_VERSIONS = { (Ecu.engine, 0x700, None): [ b'\x018966353M7100\x00\x00\x00\x00', b'\x018966353Q2300\x00\x00\x00\x00', + b'\x018966353R8100\x00\x00\x00\x00', + ], + (Ecu.esp, 0x7b0, None): [ + b'F152653330\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [b'F152653330\x00\x00\x00\x00\x00\x00'], (Ecu.dsu, 0x791, None): [ b'881515306400\x00\x00\x00\x00', b'881515306500\x00\x00\x00\x00', ], - (Ecu.eps, 0x7a1, None): [b'8965B53271\x00\x00\x00\x00\x00\x00'], - (Ecu.fwdRadar, 0x750, 0xf): [b'8821F4702300\x00\x00\x00\x00'], - (Ecu.fwdCamera, 0x750, 0x6d): [b'8646F5301400\x00\x00\x00\x00'], + (Ecu.eps, 0x7a1, None): [ + b'8965B53271\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F5301400\x00\x00\x00\x00', + ], }, CAR.PRIUS: { (Ecu.engine, 0x700, None): [ From f3fb406eee85b072c727ccaf027bd2dacd3aa69a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 12 Aug 2020 02:40:11 +0800 Subject: [PATCH 602/656] camerad: protect concurrent access to shared variables and avoid race conditions (#1966) * Protect concurrent access for shared resources * fix --- .../camerad/cameras/camera_frame_stream.cc | 2 -- selfdrive/camerad/cameras/camera_qcom.cc | 29 ++++++++++--------- selfdrive/camerad/cameras/camera_qcom.h | 12 ++++---- selfdrive/camerad/cameras/camera_webcam.cc | 1 - selfdrive/camerad/main.cc | 19 ++++++------ selfdrive/camerad/test/camera/test.c | 2 +- 6 files changed, 32 insertions(+), 33 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_frame_stream.cc b/selfdrive/camerad/cameras/camera_frame_stream.cc index 45e5013206..aecca564a2 100644 --- a/selfdrive/camerad/cameras/camera_frame_stream.cc +++ b/selfdrive/camerad/cameras/camera_frame_stream.cc @@ -94,8 +94,6 @@ CameraInfo cameras_supported[CAMERA_ID_MAX] = { }; void cameras_init(DualCameraState *s) { - memset(s, 0, sizeof(*s)); - camera_init(&s->rear, CAMERA_ID_IMX298, 20); s->rear.transform = (mat3){{ 1.0, 0.0, 0.0, diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index 6e9c3e3a24..dfed65238c 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -107,8 +107,6 @@ static void camera_release_buffer(void* cookie, int buf_idx) { static void camera_init(CameraState *s, int camera_id, int camera_num, uint32_t pixel_clock, uint32_t line_length_pclk, unsigned int max_gain, unsigned int fps) { - memset(s, 0, sizeof(*s)); - s->camera_num = camera_num; s->camera_id = camera_id; @@ -261,8 +259,6 @@ static int imx179_s5k3p8sp_apply_exposure(CameraState *s, int gain, int integ_li } void cameras_init(DualCameraState *s) { - memset(s, 0, sizeof(*s)); - char project_name[1024] = {0}; property_get("ro.boot.project_name", project_name, ""); @@ -396,7 +392,9 @@ static void set_exposure(CameraState *s, float exposure_frac, float gain_frac) { if (err == 0) { s->cur_exposure_frac = exposure_frac; + pthread_mutex_lock(&s->frame_info_lock); s->cur_gain_frac = gain_frac; + pthread_mutex_unlock(&s->frame_info_lock); } //LOGD("set exposure: %f %f - %d", exposure_frac, gain_frac, err); @@ -413,16 +411,20 @@ static void do_autoexposure(CameraState *s, float grey_frac) { const unsigned int exposure_time_min = 16; const unsigned int exposure_time_max = frame_length - 11; // copied from set_exposure() + float cur_gain_frac = s->cur_gain_frac; float exposure_factor = pow(1.05, (target_grey - grey_frac) / 0.05); - if (s->cur_gain_frac > 0.125 && exposure_factor < 1) { - s->cur_gain_frac *= exposure_factor; + if (cur_gain_frac > 0.125 && exposure_factor < 1) { + cur_gain_frac *= exposure_factor; } else if (s->cur_integ_lines * exposure_factor <= exposure_time_max && s->cur_integ_lines * exposure_factor >= exposure_time_min) { // adjust exposure time first s->cur_exposure_frac *= exposure_factor; - } else if (s->cur_gain_frac * exposure_factor <= gain_frac_max && s->cur_gain_frac * exposure_factor >= gain_frac_min) { - s->cur_gain_frac *= exposure_factor; + } else if (cur_gain_frac * exposure_factor <= gain_frac_max && cur_gain_frac * exposure_factor >= gain_frac_min) { + cur_gain_frac *= exposure_factor; } + pthread_mutex_lock(&s->frame_info_lock); + s->cur_gain_frac = cur_gain_frac; + pthread_mutex_unlock(&s->frame_info_lock); - set_exposure(s, s->cur_exposure_frac, s->cur_gain_frac); + set_exposure(s, s->cur_exposure_frac, cur_gain_frac); } else { // keep the old for others float new_exposure = s->cur_exposure_frac; @@ -1794,15 +1796,16 @@ static void do_autofocus(CameraState *s) { const int dac_up = s->device == DEVICE_LP3? LP3_AF_DAC_UP:OP3T_AF_DAC_UP; const int dac_down = s->device == DEVICE_LP3? LP3_AF_DAC_DOWN:OP3T_AF_DAC_DOWN; + float lens_true_pos = s->lens_true_pos; if (!isnan(err)) { // learn lens_true_pos - s->lens_true_pos -= err*focus_kp; + lens_true_pos -= err*focus_kp; } // stay off the walls - s->lens_true_pos = clamp(s->lens_true_pos, dac_down, dac_up); - - int target = clamp(s->lens_true_pos - sag, dac_down, dac_up); + lens_true_pos = clamp(lens_true_pos, dac_down, dac_up); + int target = clamp(lens_true_pos - sag, dac_down, dac_up); + s->lens_true_pos = lens_true_pos; /*char debug[4096]; char *pdebug = debug; diff --git a/selfdrive/camerad/cameras/camera_qcom.h b/selfdrive/camerad/cameras/camera_qcom.h index 81c84b9ebf..812f1a5968 100644 --- a/selfdrive/camerad/cameras/camera_qcom.h +++ b/selfdrive/camerad/cameras/camera_qcom.h @@ -1,10 +1,10 @@ -#ifndef CAMERA_H -#define CAMERA_H +#pragma once #include #include #include #include +#include #include "messaging.hpp" #include "msmb_isp.h" @@ -96,7 +96,7 @@ typedef struct CameraState { int cur_frame_length; int cur_integ_lines; - float digital_gain; + std::atomic digital_gain; StreamState ss[3]; @@ -113,9 +113,9 @@ typedef struct CameraState { uint16_t cur_lens_pos; uint64_t last_sag_ts; float last_sag_acc_z; - float lens_true_pos; + std::atomic lens_true_pos; - int self_recover; // af recovery counter, neg is patience, pos is active + std::atomic self_recover; // af recovery counter, neg is patience, pos is active int fps; @@ -144,5 +144,3 @@ int sensor_write_regs(CameraState *s, struct msm_camera_i2c_reg_array* arr, size #ifdef __cplusplus } // extern "C" #endif - -#endif diff --git a/selfdrive/camerad/cameras/camera_webcam.cc b/selfdrive/camerad/cameras/camera_webcam.cc index 4ce1c442da..4a7c6626a6 100644 --- a/selfdrive/camerad/cameras/camera_webcam.cc +++ b/selfdrive/camerad/cameras/camera_webcam.cc @@ -222,7 +222,6 @@ CameraInfo cameras_supported[CAMERA_ID_MAX] = { }; void cameras_init(DualCameraState *s) { - memset(s, 0, sizeof(*s)); camera_init(&s->rear, CAMERA_ID_LGC920, 20); s->rear.transform = (mat3){{ diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index aef7925536..658ab55bae 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -477,25 +477,26 @@ void* processing_thread(void *arg) { t10 = millis_since_boot();*/ // setup self recover + const float lens_true_pos = s->cameras.rear.lens_true_pos; if (is_blur(&s->lapres[0]) && - (s->cameras.rear.lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_DOWN:OP3T_AF_DAC_DOWN)+1 || - s->cameras.rear.lens_true_pos > (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_UP:OP3T_AF_DAC_UP)-1) && + (lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_DOWN:OP3T_AF_DAC_DOWN)+1 || + lens_true_pos > (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_UP:OP3T_AF_DAC_UP)-1) && s->cameras.rear.self_recover < 2) { // truly stuck, needs help s->cameras.rear.self_recover -= 1; if (s->cameras.rear.self_recover < -FOCUS_RECOVER_PATIENCE) { LOGW("rear camera bad state detected. attempting recovery from %.1f, recover state is %d", - s->cameras.rear.lens_true_pos, s->cameras.rear.self_recover); - s->cameras.rear.self_recover = FOCUS_RECOVER_STEPS + ((s->cameras.rear.lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M:OP3T_AF_DAC_M))?1:0); // parity determined by which end is stuck at + lens_true_pos, s->cameras.rear.self_recover.load()); + s->cameras.rear.self_recover = FOCUS_RECOVER_STEPS + ((lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M:OP3T_AF_DAC_M))?1:0); // parity determined by which end is stuck at } - } else if ((s->cameras.rear.lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M - LP3_AF_DAC_3SIG:OP3T_AF_DAC_M - OP3T_AF_DAC_3SIG) || - s->cameras.rear.lens_true_pos > (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M + LP3_AF_DAC_3SIG:OP3T_AF_DAC_M + OP3T_AF_DAC_3SIG)) && + } else if ((lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M - LP3_AF_DAC_3SIG:OP3T_AF_DAC_M - OP3T_AF_DAC_3SIG) || + lens_true_pos > (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M + LP3_AF_DAC_3SIG:OP3T_AF_DAC_M + OP3T_AF_DAC_3SIG)) && s->cameras.rear.self_recover < 2) { // in suboptimal position with high prob, but may still recover by itself s->cameras.rear.self_recover -= 1; if (s->cameras.rear.self_recover < -(FOCUS_RECOVER_PATIENCE*3)) { - LOGW("rear camera bad state detected. attempting recovery from %.1f, recover state is %d", s->cameras.rear.lens_true_pos, s->cameras.rear.self_recover); - s->cameras.rear.self_recover = FOCUS_RECOVER_STEPS/2 + ((s->cameras.rear.lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M:OP3T_AF_DAC_M))?1:0); + LOGW("rear camera bad state detected. attempting recovery from %.1f, recover state is %d", lens_true_pos, s->cameras.rear.self_recover.load()); + s->cameras.rear.self_recover = FOCUS_RECOVER_STEPS/2 + ((lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M:OP3T_AF_DAC_M))?1:0); } } else if (s->cameras.rear.self_recover < 0) { s->cameras.rear.self_recover += 1; // reset if fine @@ -1267,7 +1268,7 @@ int main(int argc, char *argv[]) { signal(SIGINT, (sighandler_t)set_do_exit); signal(SIGTERM, (sighandler_t)set_do_exit); - VisionState state = {0}; + VisionState state = {}; VisionState *s = &state; clu_init(); diff --git a/selfdrive/camerad/test/camera/test.c b/selfdrive/camerad/test/camera/test.c index 8a7d44517b..2a7272cb9f 100644 --- a/selfdrive/camerad/test/camera/test.c +++ b/selfdrive/camerad/test/camera/test.c @@ -34,7 +34,7 @@ void tbuffer_stop(TBuffer *tb) { } int main() { - DualCameraState s; + DualCameraState s={}; cameras_init(&s); VisionBuf camera_bufs_rear[0x10] = {0}; VisionBuf camera_bufs_focus[0x10] = {0}; From 1c802e20013db3f7fb1a92811ee69b4e0a84f8d0 Mon Sep 17 00:00:00 2001 From: VirtuallyChris Date: Tue, 11 Aug 2020 13:42:03 -0700 Subject: [PATCH 603/656] Nissan harnesses for sale --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 8afe3fc6c3..949d3851cd 100644 --- a/README.md +++ b/README.md @@ -157,9 +157,9 @@ Community Maintained Cars and Features | Kia | Optima 2019 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Sorento 2018 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Stinger 2018 | SCC + LKAS | Stock | 0mph | 0mph | -| Nissan | Leaf 2018-192 | Propilot | Stock | 0mph | 0mph | -| Nissan | Rogue 20192 | Propilot | Stock | 0mph | 0mph | -| Nissan | X-Trail 20172 | Propilot | Stock | 0mph | 0mph | +| Nissan | Leaf 2018-19 | Propilot | Stock | 0mph | 0mph | +| Nissan | Rogue 2019 | Propilot | Stock | 0mph | 0mph | +| Nissan | X-Trail 2017 | Propilot | Stock | 0mph | 0mph | | Subaru | Ascent 2019 | EyeSight | Stock | 0mph | 0mph | | Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | | Subaru | Forester 2019 | EyeSight | Stock | 0mph | 0mph | From a3d754a8d88404ec7f8ef1f0c1d04dd65c1fa90a Mon Sep 17 00:00:00 2001 From: xps-genesis <65239463+xps-genesis@users.noreply.github.com> Date: Tue, 11 Aug 2020 16:42:19 -0400 Subject: [PATCH 604/656] Car Port: 2020 Hyundai Kona (#2010) * update KONA car port * update Kona Car Port * ignore kona EV * add Kona route * update readme for Hyundia Kona * remove electric for regular Kona --- README.md | 1 + selfdrive/car/hyundai/interface.py | 8 ++++++++ selfdrive/car/hyundai/values.py | 21 +++++++++++++++++---- selfdrive/test/test_car_models.py | 4 ++++ 4 files changed, 30 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 949d3851cd..f78a070883 100644 --- a/README.md +++ b/README.md @@ -145,6 +145,7 @@ Community Maintained Cars and Features | Hyundai | Genesis 2015-16 | SCC + LKAS | Stock | 19mph | 37mph | | Hyundai | Ioniq Electric Premium SE 2020| SCC + LKAS | Stock | 0mph | 32mph | | Hyundai | Ioniq Electric Limited 2019 | SCC + LKAS | Stock | 0mph | 32mph | +| Hyundai | Kona 2020 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Kona EV 2019 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Palisade 2020 | All | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 7d0d35c4cf..553d48a2b5 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -117,6 +117,14 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.4 * 1.15 # 15% higher at the center seems reasonable ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + elif candidate == CAR.KONA: + ret.lateralTuning.pid.kf = 0.00005 + ret.mass = 1275. + STD_CARGO_KG + ret.wheelbase = 2.7 + ret.steerRatio = 13.73 * 1.15 # Spec + tire_stiffness_factor = 0.385 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KONA_EV: ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1685. + STD_CARGO_KG diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 0dd217112c..1eb2d451e3 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -28,6 +28,7 @@ class CAR: KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019" KIA_SORENTO = "KIA SORENTO GT LINE 2018" KIA_STINGER = "KIA STINGER GT2 2018" + KONA = "HYUNDAI KONA 2020" KONA_EV = "HYUNDAI KONA ELECTRIC 2019" SANTA_FE = "HYUNDAI SANTA FE LIMITED 2019" SONATA = "HYUNDAI SONATA 2020" @@ -123,6 +124,9 @@ FINGERPRINTS = { { 68:8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 8, 576:8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1473: 8, 1476: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 }], + CAR.KONA: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832 : 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1170: 8, 1173: 8, 1186: 2, 1191: 2, 1193: 8, 1265: 4,1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1378: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2004: 8, 2008: 8, 2009: 8, 2012: 8 + }], CAR.KONA_EV: [{ 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 549: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1307: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1378: 4, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8 }], @@ -148,7 +152,7 @@ ECU_FINGERPRINT = { } # Don't use these fingerprints for fingerprinting, they are still used for ECU detection -IGNORED_FINGERPRINTS = [CAR.VELOSTER, CAR.GENESIS_G70] +IGNORED_FINGERPRINTS = [CAR.VELOSTER, CAR.GENESIS_G70, CAR.KONA] FW_VERSIONS = { CAR.SONATA: { @@ -235,6 +239,14 @@ FW_VERSIONS = { (Ecu.eps, 0x7d4, None): [b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9420 4I4VL106', ], (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', ], (Ecu.transmission, 0x7e1, None): [b'\xf1\x87VDJLT17895112DN4\x88fVf\x99\x88\x88\x88\x87fVe\x88vhwwUFU\x97eFex\x99\xff\xb7\x82\xf1\x81E25\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB2\x11\x1am\xda', ], + }, + CAR.KONA: { + (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00OS__ SCC F-CUP 1.00 1.00 95655-J9200 \xf1\xa01.00', ], + (Ecu.esp, 0x7d1, None): [b'\xf1\x816V5RAK00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00\xf1\xa01.05', ], + (Ecu.engine, 0x7e0, None): [b'"\x01TOS-0NU06F301J02', ], + (Ecu.eps, 0x7d4, None): [b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', ], + (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', ], + (Ecu.transmission, 0x7e1, None): [b'\xf1\x816U2VE051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VE051\x00\x00DOS4T16NS3\x00\x00\x00\x00', ], } } @@ -245,14 +257,14 @@ CHECKSUM = { FEATURES = { # which message has the gear - "use_cluster_gears": set([CAR.ELANTRA, CAR.ELANTRA_GT_I30]), + "use_cluster_gears": set([CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA]), "use_tcu_gears": set([CAR.KIA_OPTIMA, CAR.SONATA_2019, CAR.VELOSTER]), "use_elect_gears": set([CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ]), # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE, CAR.GENESIS_G70]), + "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_FORTE, CAR.PALISADE, CAR.GENESIS_G70, CAR.KONA]), - "use_bsm": set([CAR.SONATA, CAR.PALISADE, CAR.HYUNDAI_GENESIS, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.GENESIS_G90]), + "use_bsm": set([CAR.SONATA, CAR.PALISADE, CAR.HYUNDAI_GENESIS, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.KONA]), } EV_HYBRID = set([CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV]) @@ -271,6 +283,7 @@ DBC = { CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None), CAR.KIA_SORENTO: dbc_dict('hyundai_kia_generic', None), CAR.KIA_STINGER: dbc_dict('hyundai_kia_generic', None), + CAR.KONA: dbc_dict('hyundai_kia_generic', None), CAR.KONA_EV: dbc_dict('hyundai_kia_generic', None), CAR.SANTA_FE: dbc_dict('hyundai_kia_generic', None), CAR.SONATA: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 2d6b68fe96..fb7d89dbc4 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -212,6 +212,10 @@ routes = { 'carFingerprint': HYUNDAI.IONIQ, 'enableCamera': True, }, + "22d955b2cd499c22|2020-08-10--19-58-21": { + 'carFingerprint': HYUNDAI.KONA, + 'enableCamera': True, + }, "5dddcbca6eb66c62|2020-07-26--13-24-19": { 'carFingerprint': HYUNDAI.KIA_STINGER, 'enableCamera': True, From f3adedacb29bc4784e474d89a960364c7a4c24cd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 11 Aug 2020 13:43:19 -0700 Subject: [PATCH 605/656] increase controlsd CPU test threshold --- selfdrive/test/test_cpu_usage.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_cpu_usage.py b/selfdrive/test/test_cpu_usage.py index 92f8de4ddc..2f260ec8a3 100755 --- a/selfdrive/test/test_cpu_usage.py +++ b/selfdrive/test/test_cpu_usage.py @@ -15,7 +15,7 @@ def cputime_total(ct): def print_cpu_usage(first_proc, last_proc): procs = [ - ("selfdrive.controls.controlsd", 59.46), + ("selfdrive.controls.controlsd", 66.15), ("selfdrive.locationd.locationd", 34.38), ("./loggerd", 33.90), ("selfdrive.controls.plannerd", 19.77), From d946638fce4a781765fb7441d5bbc14e6f3e59b7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 11 Aug 2020 13:45:04 -0700 Subject: [PATCH 606/656] add kona to release notes --- RELEASES.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 0d30068db5..089e9dd69a 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -2,7 +2,7 @@ Version 0.7.8 (2020-08-XX) ======================== * New driver monitoring model: improved face detection and better compatibility with sunglasses * Improved updater reliability and responsiveness - * Genesis G70 2018 and Hyundai Veloster 2019 support thanks to xps-genesis! + * Hyundai Kona 2020, Veloster 2019, and Genesis G70 2018 support thanks to xps-genesis! Version 0.7.7 (2020-07-20) ======================== From 8e63f065400ea1868f077560ae89b2c17f5523f8 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 11 Aug 2020 16:23:57 -0700 Subject: [PATCH 607/656] Alert when updated consistently fails (#2013) * alert when update fails more than 10 times * bring over offroad alert refactor from other branch * and we have tests * use it in snapshot * bump apk * don't show exceptions on release branches * only write when changed * why does delete use so much cpu * clean that up * little more --- apk/ai.comma.plus.offroad.apk | 4 +- common/params.py | 2 + selfdrive/camerad/snapshot/snapshot.py | 9 +-- selfdrive/controls/lib/alertmanager.py | 24 ++++++- selfdrive/controls/lib/alerts_offroad.json | 5 ++ .../tests/{test_events.py => test_alerts.py} | 34 +++++++++ selfdrive/thermald/thermald.py | 72 ++++++++++--------- selfdrive/updated.py | 11 ++- 8 files changed, 117 insertions(+), 44 deletions(-) rename selfdrive/controls/tests/{test_events.py => test_alerts.py} (67%) diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk index 414e4cf5c1..75f3b219b6 100644 --- a/apk/ai.comma.plus.offroad.apk +++ b/apk/ai.comma.plus.offroad.apk @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:64e31350a4138675cb39703d070fec787c011fcbdee3fbae1cbbb21ce4ceb6be -size 13701989 +oid sha256:a198491887ed6029bffdf7f4dc28c4f9a6ba5f9d2235710fc11a1378893491d7 +size 13702777 diff --git a/common/params.py b/common/params.py index 985390faa9..e106705022 100755 --- a/common/params.py +++ b/common/params.py @@ -80,6 +80,7 @@ keys = { "IsUploadRawEnabled": [TxType.PERSISTENT], "LastAthenaPingTime": [TxType.PERSISTENT], "LastUpdateTime": [TxType.PERSISTENT], + "LastUpdateException": [TxType.PERSISTENT], "LimitSetSpeed": [TxType.PERSISTENT], "LimitSetSpeedNeural": [TxType.PERSISTENT], "LiveParameters": [TxType.PERSISTENT], @@ -108,6 +109,7 @@ keys = { "Offroad_InvalidTime": [TxType.CLEAR_ON_MANAGER_START], "Offroad_IsTakingSnapshot": [TxType.CLEAR_ON_MANAGER_START], "Offroad_NeosUpdate": [TxType.CLEAR_ON_MANAGER_START], + "Offroad_UpdateFailed": [TxType.CLEAR_ON_MANAGER_START], } diff --git a/selfdrive/camerad/snapshot/snapshot.py b/selfdrive/camerad/snapshot/snapshot.py index 4ba10bf4be..317618c0b2 100755 --- a/selfdrive/camerad/snapshot/snapshot.py +++ b/selfdrive/camerad/snapshot/snapshot.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 import os -import json import signal import subprocess import time @@ -8,9 +7,7 @@ from PIL import Image from common.basedir import BASEDIR from common.params import Params from selfdrive.camerad.snapshot.visionipc import VisionIPC - -with open(BASEDIR + "/selfdrive/controls/lib/alerts_offroad.json") as json_file: - OFFROAD_ALERTS = json.load(json_file) +from selfdrive.controls.lib.alertmanager import set_offroad_alert def jpeg_write(fn, dat): @@ -26,7 +23,7 @@ def snapshot(): return None params.put("IsTakingSnapshot", "1") - params.put("Offroad_IsTakingSnapshot", json.dumps(OFFROAD_ALERTS["Offroad_IsTakingSnapshot"])) + set_offroad_alert("Offroad_IsTakingSnapshot", True) time.sleep(2.0) # Give thermald time to read the param, or if just started give camerad time to start # Check if camerad is already started @@ -64,7 +61,7 @@ def snapshot(): proc.communicate() params.put("IsTakingSnapshot", "0") - params.delete("Offroad_IsTakingSnapshot") + set_offroad_alert("Offroad_IsTakingSnapshot", False) return ret diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index 42daff420f..870d8d4b7e 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -1,14 +1,34 @@ +import os +import copy +import json + from cereal import car, log +from common.basedir import BASEDIR +from common.params import Params from common.realtime import DT_CTRL from selfdrive.swaglog import cloudlog -import copy - AlertSize = log.ControlsState.AlertSize AlertStatus = log.ControlsState.AlertStatus VisualAlert = car.CarControl.HUDControl.VisualAlert AudibleAlert = car.CarControl.HUDControl.AudibleAlert + +with open(os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json")) as f: + OFFROAD_ALERTS = json.load(f) + + +def set_offroad_alert(alert, show_alert, extra_text=None): + if show_alert: + a = OFFROAD_ALERTS[alert] + if extra_text is not None: + a = copy.copy(OFFROAD_ALERTS[alert]) + a['text'] += extra_text + Params().put(alert, json.dumps(a)) + else: + Params().delete(alert) + + class AlertManager(): def __init__(self): diff --git a/selfdrive/controls/lib/alerts_offroad.json b/selfdrive/controls/lib/alerts_offroad.json index cebb1a2c26..7cf5d8229b 100644 --- a/selfdrive/controls/lib/alerts_offroad.json +++ b/selfdrive/controls/lib/alerts_offroad.json @@ -16,6 +16,11 @@ "text": "Connect to internet to check for updates. openpilot won't engage until it connects to internet to check for updates.", "severity": 1 }, + "Offroad_UpdateFailed": { + "text": "Unable to download updates\n", + "severity": 1, + "_comment": "Append the command and error to the text." + }, "Offroad_PandaFirmwareMismatch": { "text": "Unexpected panda firmware version. System won't start. Reboot your device to reflash panda.", "severity": 1 diff --git a/selfdrive/controls/tests/test_events.py b/selfdrive/controls/tests/test_alerts.py similarity index 67% rename from selfdrive/controls/tests/test_events.py rename to selfdrive/controls/tests/test_alerts.py index ef41eea91e..5f3a962cfa 100755 --- a/selfdrive/controls/tests/test_events.py +++ b/selfdrive/controls/tests/test_alerts.py @@ -1,16 +1,27 @@ #!/usr/bin/env python3 +import json import os import unittest +import random from PIL import Image, ImageDraw, ImageFont from cereal import log, car from common.basedir import BASEDIR +from common.params import Params from selfdrive.controls.lib.events import Alert, EVENTS +from selfdrive.controls.lib.alertmanager import set_offroad_alert AlertSize = log.ControlsState.AlertSize +OFFROAD_ALERTS_PATH = os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json") class TestAlerts(unittest.TestCase): + + @classmethod + def setUpClass(cls): + with open(OFFROAD_ALERTS_PATH) as f: + cls.offroad_alerts = json.loads(f.read()) + def test_events_defined(self): # Ensure all events in capnp schema are defined in events.py events = car.CarEvent.EventName.schema.enumerants @@ -60,6 +71,29 @@ class TestAlerts(unittest.TestCase): msg = "type: %s msg: %s" % (alert.alert_type, txt) self.assertLessEqual(w, max_text_width, msg=msg) + def test_offroad_alerts(self): + params = Params() + for a in self.offroad_alerts: + # set the alert + alert = self.offroad_alerts[a] + set_offroad_alert(a, True) + self.assertTrue(json.dumps(alert) == params.get(a, encoding='utf8')) + + # then delete it + set_offroad_alert(a, False) + self.assertTrue(params.get(a) is None) + + def test_offroad_alerts_extra_text(self): + params = Params() + for i in range(50): + # set the alert + a = random.choice(list(self.offroad_alerts)) + alert = self.offroad_alerts[a] + set_offroad_alert(a, True, extra_text="a"*i) + + expected_txt = alert['text'] + "a"*i + written_txt = json.loads(params.get(a, encoding='utf8'))['text'] + self.assertTrue(expected_txt == written_txt) if __name__ == "__main__": unittest.main() diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 65587ca9c9..db944bdd67 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -1,20 +1,18 @@ #!/usr/bin/env python3 import os -import json -import copy import datetime import psutil from smbus2 import SMBus from cereal import log from common.android import ANDROID, get_network_type, get_network_strength -from common.basedir import BASEDIR from common.params import Params, put_nonblocking from common.realtime import sec_since_boot, DT_TRML from common.numpy_fast import clip, interp from common.filter_simple import FirstOrderFilter -from selfdrive.version import terms_version, training_version +from selfdrive.version import terms_version, training_version, get_git_branch from selfdrive.swaglog import cloudlog import cereal.messaging as messaging +from selfdrive.controls.lib.alertmanager import set_offroad_alert from selfdrive.loggerd.config import get_available_percent from selfdrive.pandad import get_expected_signature from selfdrive.thermald.power_monitoring import PowerMonitoring, get_battery_capacity, get_battery_status, \ @@ -35,10 +33,6 @@ LEON = False last_eon_fan_val = None -with open(BASEDIR + "/selfdrive/controls/lib/alerts_offroad.json") as json_file: - OFFROAD_ALERTS = json.load(json_file) - - def read_tz(x, clip=True): if not ANDROID: # we don't monitor thermal on PC @@ -171,6 +165,7 @@ def thermald_thread(): thermal_status_prev = ThermalStatus.green usb_power = True usb_power_prev = True + current_branch = get_git_branch() network_type = NetworkType.none network_strength = NetworkStrength.unknown @@ -179,7 +174,7 @@ def thermald_thread(): cpu_temp_filter = FirstOrderFilter(0., CPU_TEMP_TAU, DT_TRML) health_prev = None fw_version_match_prev = True - current_connectivity_alert = None + current_update_alert = None time_valid_prev = True should_start_prev = False handle_fan = None @@ -300,9 +295,9 @@ def thermald_thread(): # show invalid date/time alert time_valid = now.year >= 2019 if time_valid and not time_valid_prev: - params.delete("Offroad_InvalidTime") + set_offroad_alert("Offroad_InvalidTime", False) if not time_valid and time_valid_prev: - put_nonblocking("Offroad_InvalidTime", json.dumps(OFFROAD_ALERTS["Offroad_InvalidTime"])) + set_offroad_alert("Offroad_InvalidTime", True) time_valid_prev = time_valid # Show update prompt @@ -314,24 +309,37 @@ def thermald_thread(): update_failed_count = params.get("UpdateFailedCount") update_failed_count = 0 if update_failed_count is None else int(update_failed_count) + last_update_exception = params.get("LastUpdateException", encoding='utf8') - if dt.days > DAYS_NO_CONNECTIVITY_MAX and update_failed_count > 1: - if current_connectivity_alert != "expired": - current_connectivity_alert = "expired" - params.delete("Offroad_ConnectivityNeededPrompt") - put_nonblocking("Offroad_ConnectivityNeeded", json.dumps(OFFROAD_ALERTS["Offroad_ConnectivityNeeded"])) + if update_failed_count > 15 and last_update_exception is not None: + if current_branch in ["release2", "dashcam"]: + extra_text = "Ensure the software is correctly installed" + else: + extra_text = last_update_exception + + if current_update_alert != "update" + extra_text: + current_update_alert = "update" + extra_text + set_offroad_alert("Offroad_ConnectivityNeeded", False) + set_offroad_alert("Offroad_ConnectivityNeededPrompt", False) + set_offroad_alert("Offroad_UpdateFailed", True, extra_text=extra_text) + elif dt.days > DAYS_NO_CONNECTIVITY_MAX and update_failed_count > 1: + if current_update_alert != "expired": + current_update_alert = "expired" + set_offroad_alert("Offroad_UpdateFailed", False) + set_offroad_alert("Offroad_ConnectivityNeededPrompt", False) + set_offroad_alert("Offroad_ConnectivityNeeded", True) elif dt.days > DAYS_NO_CONNECTIVITY_PROMPT: remaining_time = str(max(DAYS_NO_CONNECTIVITY_MAX - dt.days, 0)) - if current_connectivity_alert != "prompt" + remaining_time: - current_connectivity_alert = "prompt" + remaining_time - alert_connectivity_prompt = copy.copy(OFFROAD_ALERTS["Offroad_ConnectivityNeededPrompt"]) - alert_connectivity_prompt["text"] += remaining_time + " days." - params.delete("Offroad_ConnectivityNeeded") - put_nonblocking("Offroad_ConnectivityNeededPrompt", json.dumps(alert_connectivity_prompt)) - elif current_connectivity_alert is not None: - current_connectivity_alert = None - params.delete("Offroad_ConnectivityNeeded") - params.delete("Offroad_ConnectivityNeededPrompt") + if current_update_alert != "prompt" + remaining_time: + current_update_alert = "prompt" + remaining_time + set_offroad_alert("Offroad_UpdateFailed", False) + set_offroad_alert("Offroad_ConnectivityNeeded", False) + set_offroad_alert("Offroad_ConnectivityNeededPrompt", True, extra_text=f"{remaining_time} days.") + elif current_update_alert is not None: + current_update_alert = None + set_offroad_alert("Offroad_UpdateFailed", False) + set_offroad_alert("Offroad_ConnectivityNeeded", False) + set_offroad_alert("Offroad_ConnectivityNeededPrompt", False) do_uninstall = params.get("DoUninstall") == b"1" accepted_terms = params.get("HasAcceptedTerms") == terms_version @@ -361,19 +369,19 @@ def thermald_thread(): should_start = should_start and (not is_taking_snapshot) and (not is_viewing_driver) if fw_version_match and not fw_version_match_prev: - params.delete("Offroad_PandaFirmwareMismatch") + set_offroad_alert("Offroad_PandaFirmwareMismatch", False) if not fw_version_match and fw_version_match_prev: - put_nonblocking("Offroad_PandaFirmwareMismatch", json.dumps(OFFROAD_ALERTS["Offroad_PandaFirmwareMismatch"])) + set_offroad_alert("Offroad_PandaFirmwareMismatch", True) # if any CPU gets above 107 or the battery gets above 63, kill all processes # controls will warn with CPU above 95 or battery above 60 if thermal_status >= ThermalStatus.danger: should_start = False if thermal_status_prev < ThermalStatus.danger: - put_nonblocking("Offroad_TemperatureTooHigh", json.dumps(OFFROAD_ALERTS["Offroad_TemperatureTooHigh"])) + set_offroad_alert("Offroad_TemperatureTooHigh", True) else: if thermal_status_prev >= ThermalStatus.danger: - params.delete("Offroad_TemperatureTooHigh") + set_offroad_alert("Offroad_TemperatureTooHigh", False) if should_start: if not should_start_prev: @@ -411,9 +419,9 @@ def thermald_thread(): thermal_sock.send(msg.to_bytes()) if usb_power_prev and not usb_power: - put_nonblocking("Offroad_ChargeDisabled", json.dumps(OFFROAD_ALERTS["Offroad_ChargeDisabled"])) + set_offroad_alert("Offroad_ChargeDisabled", True) elif usb_power and not usb_power_prev: - params.delete("Offroad_ChargeDisabled") + set_offroad_alert("Offroad_ChargeDisabled", False) thermal_status_prev = thermal_status usb_power_prev = usb_power diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 59ec7d8802..f93d9855cc 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -254,7 +254,6 @@ def main(): update_failed_count = 0 overlay_initialized = False while not wait_helper.shutdown: - update_failed_count += 1 wait_helper.ready_event.clear() # Check for internet every 30s @@ -265,6 +264,8 @@ def main(): continue # Attempt an update + exception = None + update_failed_count += 1 try: # Re-create the overlay if BASEDIR/.git has changed since we created the overlay if overlay_initialized: @@ -293,11 +294,17 @@ def main(): output=e.output, returncode=e.returncode ) + exception = e overlay_initialized = False - except Exception: + except Exception as e: cloudlog.exception("uncaught updated exception, shouldn't happen") + exception = e params.put("UpdateFailedCount", str(update_failed_count)) + if exception is None: + params.delete("LastUpdateException") + else: + params.put("LastUpdateException", f"command failed: {exception.cmd}\n{exception.output}") # Wait 10 minutes between update attempts wait_helper.sleep(60*10) From 335aa318953b0ee2d1100a4e7ccc5000b00fd536 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 11 Aug 2020 16:24:53 -0700 Subject: [PATCH 608/656] update total scons nodes --- selfdrive/manager.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 9e08bece59..e9ef36a2fc 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -19,7 +19,7 @@ WEBCAM = os.getenv("WEBCAM") is not None sys.path.append(os.path.join(BASEDIR, "pyextra")) os.environ['BASEDIR'] = BASEDIR -TOTAL_SCONS_NODES = 1020 +TOTAL_SCONS_NODES = 1005 prebuilt = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) # Create folders needed for msgq From 5663c116edbea0235b2a439257ebc6c0d39f4435 Mon Sep 17 00:00:00 2001 From: xps-genesis <65239463+xps-genesis@users.noreply.github.com> Date: Tue, 11 Aug 2020 21:57:16 -0400 Subject: [PATCH 609/656] update optima fingerprint and Fw Fp (#2017) * update optima fingerprint and Fw Fp * Update values.py * fix indent * not ignored Co-authored-by: Adeeb Shihadeh --- selfdrive/car/hyundai/values.py | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 1eb2d451e3..9a39cb8f31 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -86,14 +86,9 @@ FINGERPRINTS = { CAR.SONATA_2019: [ {66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1397: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2008: 8, 2009: 8, 2012: 8, 2013: 8, 2014: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8}, ], - CAR.KIA_OPTIMA: [ - { - 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1186: 2, 1191: 2, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 1952: 8, 1960: 8, 1988: 8, 1996: 8, 2001: 8, 2004: 8, 2008: 8, 2009: 8, 2012: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }, - { - 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 897: 8, 899: 8, 902: 8, 903: 6, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1265: 4, 1268: 8, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1491: 8, 1492: 8 - }, - ], + CAR.KIA_OPTIMA: [{ + 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 558: 8, 593: 8, 608: 8, 640: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 909: 8, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1186: 2, 1191: 2, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1268: 8, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1492: 8, 1530: 8, 1532: 5, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2004: 8, 2008: 8, 2009: 8, 2012: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], CAR.KIA_SORENTO: [{ 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1384: 8, 1407: 8, 1411: 8, 1419: 8, 1425: 2, 1427: 6, 1444: 8, 1456: 4, 1470: 8, 1489: 1 }], @@ -247,6 +242,14 @@ FW_VERSIONS = { (Ecu.eps, 0x7d4, None): [b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', ], (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', ], (Ecu.transmission, 0x7e1, None): [b'\xf1\x816U2VE051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VE051\x00\x00DOS4T16NS3\x00\x00\x00\x00', ], + }, + CAR.KIA_OPTIMA: { + (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 '], + (Ecu.esp, 0x7d1, None): [b'\xf1\x00JF ESC \v 11 \x18\x030 58920-D5180',], + (Ecu.engine, 0x7e0, None): [b'\x01TJFAJNU06F201H03'], + (Ecu.eps, 0x7d4, None): [b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409'], + (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.02 95895-D5000 h31'], + (Ecu.transmission, 0x7e1, None): [b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJF0T16NL0\t\xd2GW'], } } From 60e2267f02b8c09666a73c6ea2dea1bf25cc8ce1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 11 Aug 2020 20:37:51 -0700 Subject: [PATCH 610/656] fix linter --- selfdrive/updated.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index f93d9855cc..f63da54475 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -296,9 +296,8 @@ def main(): ) exception = e overlay_initialized = False - except Exception as e: + except Exception: cloudlog.exception("uncaught updated exception, shouldn't happen") - exception = e params.put("UpdateFailedCount", str(update_failed_count)) if exception is None: From a228c4d0a077097cf14eb770570bec1727d57d0c Mon Sep 17 00:00:00 2001 From: Comma Device Date: Wed, 12 Aug 2020 09:02:13 +0000 Subject: [PATCH 611/656] fix boardd build --- selfdrive/boardd/boardd.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index df865db27a..a3bb2b0b4c 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -37,7 +37,7 @@ #define NIBBLE_TO_HEX(n) ((n) < 10 ? (n) + '0' : ((n) - 10) + 'a') #define VOLTAGE_K 0.091 // LPF gain for 5s tau (dt/tau / (dt/tau + 1)) -#ifndef __x86_64__ +#ifdef QCOM const uint32_t NO_IGNITION_CNT_MAX = 2 * 60 * 60 * 30; // turn off charge after 30 hrs const float VBATT_START_CHARGING = 11.5; const float VBATT_PAUSE_CHARGING = 11.0; From c3a45580265f2138e12c371966e28a81886ead75 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 12 Aug 2020 11:38:38 +0200 Subject: [PATCH 612/656] Don't check dirty on prebuilt release (#2014) * dont check dirty on prebuilt release * cleanup * Command cleanup * Only log dirty comma branch * Less whitespace * Consistentcy Co-authored-by: Adeeb Shihadeh --- selfdrive/version.py | 87 ++++++++++++++++++++++++-------------------- 1 file changed, 47 insertions(+), 40 deletions(-) diff --git a/selfdrive/version.py b/selfdrive/version.py index 0999e7511d..9ce31ddbe8 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -1,47 +1,47 @@ #!/usr/bin/env python3 import os import subprocess +from common.basedir import BASEDIR from selfdrive.swaglog import cloudlog -def get_git_commit(default=None): +def run_cmd(cmd): + return subprocess.check_output(cmd, encoding='utf8').strip() + + +def run_cmd_default(cmd, default=None): try: - return subprocess.check_output(["git", "rev-parse", "HEAD"], encoding='utf8').strip() + return run_cmd(cmd) except subprocess.CalledProcessError: return default +def get_git_commit(branch="HEAD", default=None): + return run_cmd_default(["git", "rev-parse", branch], default=default) + + def get_git_branch(default=None): - try: - return subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"], encoding='utf8').strip() - except subprocess.CalledProcessError: - return default + return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "HEAD"], default=default) def get_git_full_branchname(default=None): - try: - return subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "--symbolic-full-name", "@{u}"], encoding='utf8').strip() - except subprocess.CalledProcessError: - return default + return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "--symbolic-full-name", "@{u}"], default=default) def get_git_remote(default=None): try: - local_branch = subprocess.check_output(["git", "name-rev", "--name-only", "HEAD"], encoding='utf8').strip() - tracking_remote = subprocess.check_output(["git", "config", "branch." + local_branch + ".remote"], encoding='utf8').strip() - return subprocess.check_output(["git", "config", "remote." + tracking_remote + ".url"], encoding='utf8').strip() - - except subprocess.CalledProcessError: - try: - # Not on a branch, fallback - return subprocess.check_output(["git", "config", "--get", "remote.origin.url"], encoding='utf8').strip() - except subprocess.CalledProcessError: - return default + local_branch = run_cmd(["git", "name-rev", "--name-only", "HEAD"]) + tracking_remote = run_cmd(["git", "config", "branch." + local_branch + ".remote"]) + return run_cmd(["git", "config", "remote." + tracking_remote + ".url"]) + except subprocess.CalledProcessError: # Not on a branch, fallback + run_cmd_default(["git", "config", "--get", "remote.origin.url"], default=default) with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")) as _versionf: version = _versionf.read().split('"')[1] +prebuilt = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) + training_version = b"0.2.0" terms_version = b"2" @@ -51,35 +51,42 @@ tested_branch = False origin = get_git_remote() branch = get_git_full_branchname() -try: - # This is needed otherwise touched files might show up as modified +if (origin is not None) and (branch is not None): try: - subprocess.check_call(["git", "update-index", "--refresh"]) - except subprocess.CalledProcessError: - pass - - if (origin is not None) and (branch is not None): comma_remote = origin.startswith('git@github.com:commaai') or origin.startswith('https://github.com/commaai') tested_branch = get_git_branch() in ['devel', 'release2-staging', 'dashcam-staging', 'release2', 'dashcam'] - dirty = not comma_remote + dirty = False + + # Actually check dirty files + if not prebuilt: + # This is needed otherwise touched files might show up as modified + try: + subprocess.check_call(["git", "update-index", "--refresh"]) + except subprocess.CalledProcessError: + pass + dirty = (subprocess.call(["git", "diff-index", "--quiet", branch, "--"]) != 0) + + # Log dirty files + if dirty and comma_remote: + try: + dirty_files = run_cmd(["git", "diff-index", branch, "--"]) + cloudlog.event("dirty comma branch", version=version, dirty=dirty, origin=origin, branch=branch, + dirty_files=dirty_files, commit=get_git_commit(), origin_commit=get_git_commit(branch)) + except subprocess.CalledProcessError: + pass + + dirty = dirty or (not comma_remote) dirty = dirty or ('master' in branch) - dirty = dirty or (subprocess.call(["git", "diff-index", "--quiet", branch, "--"]) != 0) - if dirty: - dirty_files = subprocess.check_output(["git", "diff-index", branch, "--"], encoding='utf8') - commit = subprocess.check_output(["git", "rev-parse", "--verify", "HEAD"], encoding='utf8').rstrip() - origin_commit = subprocess.check_output(["git", "rev-parse", "--verify", branch], encoding='utf8').rstrip() - cloudlog.event("dirty comma branch", version=version, dirty=dirty, origin=origin, branch=branch, - dirty_files=dirty_files, commit=commit, origin_commit=origin_commit) - -except subprocess.CalledProcessError: - dirty = True - cloudlog.exception("git subprocess failed while checking dirty") + except subprocess.CalledProcessError: + dirty = True + cloudlog.exception("git subprocess failed while checking dirty") if __name__ == "__main__": print("Dirty: %s" % dirty) print("Version: %s" % version) print("Remote: %s" % origin) - print("Branch %s" % branch) + print("Branch: %s" % branch) + print("Prebuilt: %s" % prebuilt) From e909fddac06acb1a602e3f25578c61a9e2b3ec11 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 12 Aug 2020 16:36:17 +0200 Subject: [PATCH 613/656] Force battery temperature to 0 on comma two --- selfdrive/thermald/thermald.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index db944bdd67..093b832da0 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -248,6 +248,7 @@ def thermald_thread(): if is_uno: msg.thermal.batteryPercent = 100 msg.thermal.batteryStatus = "Charging" + msg.thermal.bat = 0 current_filter.update(msg.thermal.batteryCurrent / 1e6) From cb5a2996e75658ac61f057fb729c229a554c551e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Aug 2020 11:39:21 -0700 Subject: [PATCH 614/656] NEOS background updater (#1892) --- Jenkinsfile | 3 +- installer/updater/test_updater.py | 82 +++++++++ installer/updater/updater | Bin 2468632 -> 2505496 bytes installer/updater/updater.cc | 201 ++++++++++++--------- launch_chffrplus.sh | 31 +--- launch_env.sh | 17 ++ selfdrive/controls/lib/alerts_offroad.json | 4 + selfdrive/test/test_updated.py | 48 ++++- selfdrive/updated.py | 106 ++++++++--- 9 files changed, 353 insertions(+), 139 deletions(-) create mode 100755 installer/updater/test_updater.py create mode 100755 launch_env.sh diff --git a/Jenkinsfile b/Jenkinsfile index 83c9007f0a..bae3469b54 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -120,12 +120,13 @@ pipeline { } } - stage('HW Tests') { + stage('HW + Unit Tests') { steps { phone_steps("eon", [ ["build cereal", "SCONS_CACHE=1 scons -j4 cereal/"], ["test sounds", "nosetests -s selfdrive/test/test_sounds.py"], ["test boardd loopback", "nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"], + //["test updater", "python installer/updater/test_updater.py"], ]) } } diff --git a/installer/updater/test_updater.py b/installer/updater/test_updater.py new file mode 100755 index 0000000000..6e811921de --- /dev/null +++ b/installer/updater/test_updater.py @@ -0,0 +1,82 @@ +#!/usr/bin/env python3 +import os +import shutil +import subprocess +import tempfile +import time +import unittest + +from common.basedir import BASEDIR + +UPDATER_PATH = os.path.join(BASEDIR, "installer/updater") +UPDATER = os.path.join(UPDATER_PATH, "updater") +UPDATE_MANIFEST = os.path.join(UPDATER_PATH, "update.json") + + +class TestUpdater(unittest.TestCase): + + @classmethod + def setUpClass(cls): + # test that the updater builds + cls.assertTrue(f"cd {UPDATER_PATH} && make clean && make", "updater failed to build") + + # restore the checked-in version, since that's what actually runs on devices + os.system(f"git reset --hard {UPDATER_PATH}") + + def setUp(self): + self._clear_dir() + + def tearDown(self): + self._clear_dir() + + def _clear_dir(self): + if os.path.isdir("/data/neoupdate"): + shutil.rmtree("/data/neoupdate") + + def _assert_ok(self, cmd, msg=None): + self.assertTrue(os.system(cmd) == 0, msg) + + def _assert_fails(self, cmd): + self.assertFalse(os.system(cmd) == 0) + + def test_background_download(self): + self._assert_ok(f"{UPDATER} bgcache 'file://{UPDATE_MANIFEST}'") + + def test_background_download_bad_manifest(self): + # update with bad manifest should fail + with tempfile.NamedTemporaryFile(mode="w", suffix=".json") as f: + f.write("{}") + self._assert_fails(f"{UPDATER} bgcache 'file://{f.name}'") + + def test_cache_resume(self): + self._assert_ok(f"{UPDATER} bgcache 'file://{UPDATE_MANIFEST}'") + # a full download takes >1m, but resuming from fully cached should only be a few seconds + start_time = time.monotonic() + self._assert_ok(f"{UPDATER} bgcache 'file://{UPDATE_MANIFEST}'") + self.assertLess(time.monotonic() - start_time, 10) + + # make sure we can recover from corrupt downloads + def test_recover_from_corrupt(self): + # download the whole update + self._assert_ok(f"{UPDATER} bgcache 'file://{UPDATE_MANIFEST}'") + + # write some random bytes + for f in os.listdir("/data/neoupdate"): + with open(os.path.join("/data/neoupdate", f), "ab") as f: + f.write(b"\xab"*20) + + # this attempt should fail, then it unlinks + self._assert_fails(f"{UPDATER} bgcache 'file://{UPDATE_MANIFEST}'") + + # now it should pass + self._assert_ok(f"{UPDATER} bgcache 'file://{UPDATE_MANIFEST}'") + + # simple test that the updater doesn't crash in UI mode + def test_ui_init(self): + with subprocess.Popen(UPDATER) as proc: + time.sleep(5) + self.assertTrue(proc.poll() is None) + proc.terminate() + +if __name__ == "__main__": + unittest.main() diff --git a/installer/updater/updater b/installer/updater/updater index 15858eabb4d66e64e6fe5cfe559a7f905c2530a8..66047420c12d3413da84efc405bf0df895710fdf 100755 GIT binary patch delta 712245 zcmZ_X3EU$^oj33fmkn}cU|AVLt-pol?Pjmm0J7F$I+AZTP= zZ3s%EtOjM-xT3b=>jvd@1G?HCuiGfALC_5fZafLXY7kc6s;*xp=^s<^lS!WMzv|aV zRpqG}9%teoeWVosF)l^UPS%y1S@PlMzgkw~i2bfR=$}s9_RigM(63fm)l1@KEAjNd zrRx5Vi?7iepPe_H_tuow?bLi~eg0MR*&Fn0?|G$H?KL@XUH&z{o_}S|*7?0VOK0t6 zI>x9b&%&}sy#qG;diZYf#S6t(6Y+G#`xlAV9aIDH&a$?X?^nK-Ru|8|6VIx6?o72m z3zLs6R(!0;%Eaq!c)z!JeSXOb^DqA(e*Kkonp_bNb!De@jO#J zN8;&L~{_lW1OWkEdtBA)LO?uh3(;`w>;^@HMhta$22e*X^^MfrHU zczvyUYke87`=a)I@%4`4xf{Ng}`iq~Dm>xaej+u|u7&l0u=+I~iS{it~E zD87CXtSVmjQ8&l3{!J9$EMOywhl$re3VV}yo+_U5@w9lBgzqGt$B6f@7q2Ia*VDx7 z$HeP-;#EIhBi^4UzWA(oUM}8uP@L3kfq4C~c>axezomHnfOsAv-pj|`>cx7i`1*A5oQbb563=zw{Q=^6hIs!S@mwR` z*TwTr@m@aOA>QvNUVkZ`eR&V$qCZGH<>Mjoyjnb;EgHQ{ynaxp@!l7&2Z`rT#QVP$uXFKwuXz5ucQY!auf7Zdh2cLED&d13B zJYI~v%XG6Xc0Ngz*66x;JzhL(D%Cr2{T98Jy;j6+Q98KyZhL*{xxJh0{cm(z>+N0N zhODDjI`1OhZ|vP$T6fxOQI*9##q)XMd8)9cc$JS6R_gNWbH&$N$T#Bg67l{}_0~GM zcjDITwtk(EmkT+&cj4B1mX7RQx%I}qjuZA0VcVeP-;39a@m{`kd-saANB17vdVT4v z-geupKkW)s4-~Hh@jOZ-=*N5U=6bxIgxYgg+FXa)|LgtjHtWKRMCEcJE$A!6*RR3* z_lwupiRVA!>!0HFd7{k);{991^Jn6DKU}{22i~71Uf+uMKNPQzi|1Q#7H<&m|3^F@ zlOH&Hi8rqjg|CR$uZyRA{F8W|E}pLv&tHh=zl!Hw;(4iP_kYCe3&c}DUMb%ENj#4c zwf_{aUqj))d#`%-y6{axvP{4NL`5rN!b}C&de%-U@ zZEGL)YBUlh>&5bymB;pYe~M`HEAjpa@%)zPx&FrbEzjAabeN1f;A{kZR1~ig&j-YF zD4z0hpLiaN`Z>LS-}dP1x7(uR^|svZMWOuEU;UOLXNLU5*Rx38MmZ-}XSQ7PaweTD zp7NaJ3XmT{@&i_`MfvSXe(1=DJ}voPt^oNsN4(0FA-;cxIq2_y@{83EQ#twMos{!I zKIBc3A0YCM%1_1Bhg?kZyMi8JIfC*bKa})CPB{5_BR@6e<87s9t4SoM!#nRdZ~K>* zN`CJPJ2+)`gKB|aKixZQ$928g4o>Nfy%X22E8WuDtGuzaxzy5yz3arUNB6EQuPeR3 zckh~Yy`=1vex3K2hwOP+N`@5FU)FI|$lYhKcIK^t{cUHuiSNA>3#A>_L5zl(p~w1&+I)U zY7ge8`w4M#c9b`#=kMl}hWRPBcdM0NoZrr0%dsd$y*2x+E4`psTEDUMn!H7@qthGj z>xl167Yh48ehHi9x9;TL-9je4(jJb?@3|YC(iiii_IhWF;k+Wh7%^BIHulmDo)~{Q z3wFXymb2-q-if_Nq9&l9+Af{Pu5_UyZYeC$ePX{(0XI_15g> zrI~Hly1-O*VlSi?s;nIQ+bP5^d8!CqnNvE+>NE1^5jE$ zCyML5U$)%xm5X7V=VyFpes#z6?sZSy@McXzz`s-{<#! zLw-7UH0u|`*@{ZKK0kY_q@7x>m+Tr=cdO?2e+spIpxzBO7+;ee_KbNhxT)S4E@6LJpTk~Tk;?AC#pTm{; zLil+;6YlG+*>7Fx*|J^F-_H}D1(%4gML%&>Tla3+@6^)z{C@0^U&Ay%3vuS+4jrHO zY3^Su-I!nZYkPO^e`@K2dFyxPi~p(o3TI;0Y%D#H&(R0+F-|IuID-6~dA#?KsBMwI zFXh+cAK-{(CO>D^=1KpSAM1DdJ^75h`d%hl?3MTUO#bUf^K1Nnd24Z{;sfC9-1q5S zxs%ho?!b+ueS3EwxK8{k&-#b?b!^Pf-4)CIZTY>pw|DkIrRZmW1aflu836x%E5(-W1;-#f|2OLr2#8xfv7x>^2p2Os69BWHs4c3!ot ze-NMWdx`J3KZ{h(;qa}*tQI+;weR+u=OjKa^2gWn4r?v{p7r_H9mUr7ae$joQbGCv zuXf}C)>@6bRr?CspDMm<%MEipJiW9qU@kSPo!wKmFJc0w? z@K&_M6~9QFv25=+>HvKl;1}W!$rJK%LgM`L$A^)VUZQetkSf3bJ}D-+?9lwWx`Jxn zT>RD-9eldt6LwIy^zFE%N1**Hab-_f>V$B*;x}VzC@=Sw=%GAL?1Msi;3^KRZ{5xq z`}?rY=?Qwk~ovo%2O;g)--RkE`}i;}D+< z)iSW|+C`nI{L=#Y_y;|EX?5I(18;!q-`t$HGY){U*F*Uba?&T%fwx8eFL39=gE2Px z)@|*oTXe)L)h(Uprz7@?!sQ*xPAuM`6A;wJtoG4f{yCMr;%UCj)Sg+EZb186)uav= zV}Bkd#a$T7Z{SQD;ymOB$Ri(8Cv*r7aJ*PG@&NwR>dK~Q|8?>0Ou9>V=w$dQh2BKdCEFaboL^TXZSby&lUAIB*TF+Xwjpo;i7M6zf}_&>X8ke**3!+RKmji$spN z{^jz!1_!RbLPhIY`ZtCHd_nxiTn^107#jWA{s~ORXlHdN4#v=gxPZ$sSHuTse*FB8 zkmQ+ez&90rWuL(beedN;^zRyF%Z{@Ad1BQ5`Dy zCZU6F#Mqxpb7FrS_=dNwyuP4Zt_$t%N5VpZnvfQb#rUAz5#VnKz*}Cy@5Y6 z-W;nw>!^v-B!3#-Q65^lga2FH*|9i^cxZQisl3d7h`J#i^8VwheMD}*R<(}{F2>k9 z2Y2@V;(?>bRFF+xc>*Uy?!g`MD%>S+T`gvWIKEY(LLD7E@&>$0-h%t&ZFr45fY*h~ z<1cP?2ZaW8=)#-i5xhkn!`tM2c(C;R_|^c0&axoS%Szx~@*zATPvJ3n2Je$ko(R=g z4yZ6ghlG3%AClYuqjE;%4m>5Vz_XAFRTReLHTZ(54Euu_oAudG)AxuaJB zI}SV|FT+!E`*G~CGb&i;KC2K+!vJo4gAz zlgDtEybrHv5Ap4CfP$wB@C05ZAHsd|5xhp8!t3N=hC-7Hv%jiOv=;ds-X^z@6Oh~R z4tZI5XmzRJphHCN!ejCZyie}I2jo?FlDnAydinV%45>p6J|a(Tv6U2$l>GKo?I$ww zhwoE9UUj+tE<%UtYC(Aao2tW%eE5CkbMi}Z0PDfxT{Dl2`tqyhVQTqsrS4?v@{aIRx121=L|YR~&I+O11AV zTpi!q0%tT>6y(T?|7Ny@*ldeOLjLscRnXAj8Tr9ms+<{lCB!YAQ$b&`_0!^5>MOR% z^%Xnh`ifn0eZgUc3i^sYa(%^BgV)LR6}QQ&>(m?ylrQ)H6Zv~u@#s*8$~xs;@_2jY zF}bs|@;>>)J18F%T#Wx2IB-%Zh@VM7hoQkUau4li?6_k4XT_n6*N796^RG;W4G40` z>o`%D+{XbbJp4*H54Ia>(@^a>?}_ zs*vkDpN68c!ONuq1G>G|F3URL>)RWQ*jlnT~;>c6+n4Q@ZYGKu7w zqP=7AiorvV3hukrt!t83;1Rh8ACcGKGjbp9K9XO+a{u2%p{@#xW!Zpt$OCvn9>FK% zZFu>Yt9MR}e-{P6P!PZUhPTNRc%M9lXXI13_1~)p7XM}I3UR09{PUnQc@u8^dU4=9zZ0V1QK1iSl8@jKdG!(Xr)3Fw^Kx|o8F>pn3#rgXq5PZT znbuC0KWHrG3VDF`b@C3pO&+`pa|piJ|98aO5knsAv_`9+p0B?YLG_h_oNQxwo7~?IlZf2H2UkK~ zLHmr{emD02Gb)r3RDQI01rFRJAG}AMkWW5>x5(r7s`l+iY5#xjx7Ck&1=L~qE#)2Z z4c}4TCBHdU9+5Y{sXW%M_y4#4yDIc`0sH@_;Y0EZ>d<+=@&@@6|De1{9(_o8M1Jc>l*bFtuV4KCaIRH_{-Tgys8z**2jrJtquOWW z`ijTwxI=UDad?9Yvj0%Lb+_ZdW%A13tM(50xz{PLk?Rwxll!=UuuBEqAtKjfmXMEe z0V8sK0V%n@fK2&v|F5rLN*(l^n3L-{VLe{Fb9zqL1RzWjzJ*(&BdQw|Y6z`Cp)VA<^ z{_9UbJ*z$HpiijEj#=Gi$LB=Aj`qpY)%w#17%mI>EnZwP`QnPn7gzj0hASq&^qNrJ zQilq9j4R}Nj6HHa##QosjK!t2$n^!cLn`Pi9+2C&s1r@dFNIIZb^96lxUX_5e^hs9 zvHw39K^_WvPR!sf@~c0og4*Qg!z1$F-lp33iym5cp~Ik9u%_^Y{E1st(2)ELw9m++ zJ5>8I`Ej3?F6Q5a3fAXThbj5NpHXiAsW`c&UsPTuR|gRPKWB2C?@E{RU*BqdfC_bZ zc%Tm8lOKmGtFh--CVsGqTpzfx;`#d12M$&Wa{WDw19Zssm37JW0U~mppOD}1#qHGk zA5uXdU_`DDkdo^IWaRqJP05eDN8QocpJ@O8;7}Fj)Zu$yQf|$QW54g6%3boSN6IVY zI^WZ-_y76;Rb9aTUmu`BelQNuB-aOMk?Z_6d8iK%QQ<)xAZEuM>XYjO49InUO8#3l z1fi8tL0`d`TpwUUt`A^6Ssa>&?^Z)#lk5C)?qdGw<);tePzQa0D)|kVL_WDbK#g4I z*H>N6e|>=VYC-sY|E8`WAlC=zkn00<$#s52eyNz$`T84B;RxKigj^qZNUje&BG(6= zkbeOA(FuMaSz4*CFda(#fxpNnH(UaS6Z(H{9JJ1Va(Tz&pnx0Y4GUlio$pLl#i z{Z6RC-p3yxkay6&%Z~Pa_V80GXh?KrSMq!a{qr33Pb8}@a`&TM7}RPC0`4llAi&e62m(nscHijoU<#lA zrRerQtMgQ0>B6{`P71x4h+mzBrl5xh^{hY!dTcoI@!gu;+K zgOA9k@RZ#8S9PKpxdR`=7yJJz3KQy3gHOpD@ELgkpOZ&$YqP=-gjRxrT`X7`yi7iY zJLGe?OKuOK9>5#Y<^0#Pv5P{JI>hi6`2gM~ zAHoCj6y90!eEm&O=&lsx`kTWe^75VPmL}xm{6DFP|JNe<>?^AMi2MT^c2Mg-rNU&r z`2Q=4M@D{}qkK&6!6)RiT~+%jd4Tq_&9MIU5bTSBy?J4lT5Wil{ChjA132W>J(auU zE#y?R>;3T}^aszXA4`@YIYZq;($)GqA0519A)i$CnW{sTJi`$9bjZC2)Bz&$A=<~}Blv*)DC7)7DooH}L_URQP+ zle&O8e6jz30fOwUi({;R>ZMHXU#o&#@)sk=BcI^{sznbiU8ofc)=Lr8Ah(`S2X2zv z@HY7c$mx)$`JE8+uSI; zPTod)Yn$Rw2JrHV=j-n(1i32(x&C5ws2IFT{vPDi$ot5tlMkN2&;K;3a1Dam*5K1TbLd;%Yne-JrS?Rx(|M~9g% zVE=FZkDBe)vx{SS9fHc_4%$29F1$h>-hiMg74&ySpWRa@R42a?IZg5^4&2(bhgLv^ zk0Gc_?jtBNc%S@J$VtfS$QkA?=D%Kkx{y+b+YvM-Zy{)6@EQ64L5{WU%23Mn*FliI zT3B(1{A&oRkoS?}8QdrTmdMH1f1L_L1T_raBF}I_0XuR!29LI-{r~+4>Qjd?f(8a3 zl0Sr;lzfVuY~lI!i=P2SVX`R5j|cI0RwHOeK1cgGx%Ef2I_&LM##rP$iX4aB4$;A- zLJi+uJ@O|IbQn{I8GK5<3xek4_Mg<9vvw#BfdhA!uGU`# zh03y!FTX0hO1>Tku94T!zD{0;H_7*TQ1Ab#&_IWPyakWR19;!y33&wn}i1Wu+k3pN}AqybkxtuS8Cryp8q^^3ELl{}vUx2nxvi27NR5qTY+k$(m! zG$C)H{gga_&vO^^UoXD|LH16?i;^Ag4w?MEg2<8lupo!v7+u zO+H2YfP4<`l5h1>H8e4K`6=aLp9(Gt3Hc5P8j<^GpOV+%Q}QN!rhH}pkAk&xam*YX zxJ=$cdxyLOuaNJCoNB?v`1jGlFBHU&<-_abyCbMco}zt=d;$;1U6~{2UzZBj(`sxY z@-nrH$cHz z7V_nHFoG)NBeeI($8eu~BXa8G^QW=@Z&0E9ziJ3tA5y_b zhXHvFo|4z$8F>RfBX7dz@WuYWg@UuLIA(3QOCG>I^5_3l-8rAUgZ8zehgO6_qgb#` zLQspmkM?cy0X!m4;4%3qcQOBlRLIa_L_UUR6z!+vGx%J(od0_HorWOW zDGtFL9m)oG$+dWCb;y0R?~>QyG5Jf7GazsN1^fTx znT34)kH}w+pp3kY1CI?pC4U8S<__)u0|Z&S7KcE4nfz4
={MsgTF;s&>8qZz8Cs z3)ue;(4kH~gty64ctAde$K>G@g+3ML@DaKFS2c-JgOADIfD4eS&KIB=6(|Fm0++(%A8eg$&6t1j1H z9UY?8g77B1Pks%8#^i0ZpOAOpGxBRiPQL!F^~GBqqk~P}hdbmEPN+gYKzolof!Ej5 z{(p!iouB{5gz z{Hs#Ikp=Onkw1W-2Dy*+P4YUtP5uaSI>Ph$uRj3;bm&rtE<7fG6hQ;>0oo_z34FA4 zwf>$&P_``OcOXNDG5HuiCExsK>YLM?e2(_k9>t*)|In?v)nzJdhai{S-AuKwkbCed z`7X$*k=N0_9#Wx+LX&(~1hvTnv=7L;@GkiVCK6U8B6Y@O~G$J3OeM+9e z$3++a#ukF6#ey|OhZ*@CZtYnd%R`Y7QB z+lL6ss1TvUn7j|4lCML~oP3D();=_3@UTn;7eOxh6dfw$GkBH!K;+cOy(`sF)|D^! z|GLnm4$nnUo7~J zLcaW7ji4_10PQ341fGx&;Y0FtEA0PMD!d*C9+Qs|G$EhBXXGv9SkEaA*&OZdkP6nb zuv;a66M`z_HrjjSWw=k?Mot~R*#Eoe(4Y?5TjZA^C?KyOr(^J_=%IB5g8IdR__uM@ zofwc;;Y0HGA}1yH(LURxi}^R9!iNwvBd;T9Zg6|Q;uznA9EZG#99O!W|9bi9f=3-b zg&?22ji8#r8|0rwPHV;U_18gAd!-=PpY{&qouzd=xge2(@_ zgSW~5h@1|2Shm$N>rz2`OkSE`=R@uxCo%Yld|Q_DdPH0ZvMvhe} z4yE>T?qdGy<+nG2TeTMFSr>0yAV__ z6vY028#Ngl25*sn3poLK6*-+vxtxCy6@GxAK6xEM1A`CAe~O%xyp5bpcs~F2C!j7& zsKXRNGx7*QbA#Il6_@Md$Z?jg)?b1kcUj1npLUP@F9`CafBgZSc`1v0MRf~m%*T`Rlpayw@oTkCsu|fSek6XWL!W`maB;kgxwHd5oYo`2Z&r7`#jVDdfb5(EdL|P@g(zPsl%qpb_~D zIjOi4Vy5s>)C^C4Te1@DPcQOC;@{15Oqz>9s@~03qCQpzvG5BoN z<^133=jxk>wXrysDS~W+JLGGSQz4%q$J>PG>(8gc1_af~t?jWRGI)!8f8+$@E^;~> zY5%Va5p_5mL49%`K?8#i$&W`)x^VURV>JWAfXOGa#=aCt12$f4VSQ7V`D?Sp;R|bp(wK zJ|+JWa^~cX9q{M>*5SpmY~TQ8@~;?3_(@$DNe{Yc%A%7ATRww?Hjt}4ss%c z_g6e$e_JCcSt-c%S3%Iw;3@eU1|NnjjdDNkcpelI`uaRGeoCbM<_RWQ>&mU`qLVHn=pMREh z6M{PA8QOQrC-9j37UT@bXCXQyRG7m@R>#=jQ}Qn$C!ABkL6CKHaV)i$ z$?rsvOYR}3V(_Z+<^KO}1l6cR4MBB-H_5+^oHltAIYGh2`0GNqP_V3f5fqaL2 z6gj@Z>q}Sb?@0tTmj$`{ENdt1hzuT(mmbEBh}=O=^bE)TzfXm&5tNX72pSqZC0~P_ zF?kI+lh9C@k?)Ei>zLwLHW6eS+#%l!ITiR~{~sX8qYm1A@&gc5C+{MsVenSbL+daE z1;v6DBdBBWi2NAj^vM(C3^wUv{tc;c5`t3l3_+Q}C*&_e&WwD9oVj#4|Ml|I1^d|I z7@vzEhrGNNJ0gR7;Dm~hP8});vW_c`rS>xU-NHKiEV;uKzCi{RoQ5yEvh~!4vX_kTW`t_WykZrPM+DnEY1=nvxHZGc&k# zydKK@`Yr1*1eF&BdHv%58;T&u;1%*Gky9m~AjfA9QK(a)^oZKYG|6XZ-!gbWzBO{X zkW(iQkki3%Z-O9qS;z-dyGMQ=f_(BBa%u)|kYD(S{`ns& zl-H@{(KdL8{0%svh}=U?Z16!yg-Z}LB(EcAWblmq9mtuGw~#Z1FZTbsFsBYzBFOd^ zW0nt12SH_nyX5ajj#qT?^FIix77Ginkza?P26-PjO@p_|Z_0DT{OeF*h@h^)WAa;Y zLId&?If=nX(&hZu%kR?&%BaH_L1TkY$-jV{Ir$7Z)``oZRO`=Cv%S1hkb`_Df?RS3 z?JMLiyh?sIa%$uiNB{f}6?_CW$-j-DHhBx*6$A1Ha=PR{Ku&yOxV#neid*Q=rw(m+ zLjC}PM&uo|PswBWSi9c;Ka8NME@1yZM28vq2yUHJynx>!r%axqy+a;OP^eJhj|i%g z&(Yo|w|7-@s80S@#bjU9oL&hx}mVRLI*nu(t`%*S}8% z4?%VE4uTrw5xhlyBys}s1noN~)Bb;mLPQ;oMo^!8g!TjS6h0)cA}3wA`uwvpbjTKk zd@5LD_=Nme1kK1NXg?>P!R=FuLwtOQAcqRpZfZHXLM~5nT0wvkI=qJp2FM0^ZBno0bh@x z4t4PH$=D?yBPb@n1UUop`8DbTEm^u+f4Yz@3;Ft+-~eNCYrR?>Q}TD=z;kjJ?X4FU zhs<5C|Nb8;T!A2$+(S@>yb7<9Uxl0+c^&QRp`p+u|9b?r$(slY$OCwnyoa0^zS#fA z=+LJQ+7t4RA!tNCKu&7#anVETQwW+C3s!=l8F>n~PA!h*ZOAE;Pto2Xw>HQ*B<5d* z3ZF($mE6fYh(E3)ufXf%w-$qWo zM*IIEf*RC8dyD*D1O?g60OdPb-e`W5{vH?cMW_@X&HMU9ddzClTb65C2JhQ>hueL0`ziT($eEK@ zkYl}wh7vhpnF_B#kV{@gP=&k(uadtBIW_VI+SipY_x~*vn$+P^1hvTnv=7K5c$fU$ z$cYOs#(#hg{X#+fi^lMTyn~<-`55g}@;Q7={yv!_=iihH&Yo(r%*Z{sbw+V4KZp}5 zlLz~$Pddlo72)~(*PnnNMo^VH)No+m;C1qkAg4)QM^0<$YW?X#uq@=u?BmV+&tnkIfv5XL88{8rP3W6%+1LSxH z_u-5E|JM;zrw&5|H4NS&{~mGz@)S9pqKB3)M8$&jBLwxyrwAGtd`Lb)PD(z{bHx11 zHdzpVFA({!5i}#WT{Tzc2Di^F4)GJnaiq)nua{pLK`wRB?veimK|Z;QoSMNKE1s`E zdx|a5N_aF_g8;y)Zcru zsBiFu{Np&G5xIw))ZpVf@Ba}rr4CgD%?xgxU0jx5L{6E!{!8_rc$|f+&mT({DvN@+ z|Kf2Mf~w>-oRDwuI{7z|(XNt6J~DWp{3pl>6DkA<8X7z$e;7ey z@-A{F2A?Tk?*D&}AnPT?v5XO98{8qEBd0>1Ajd1X7=K;x3kA#C>{sdor%s+CsA2FH z`L@Uj$j35A&cDv43c@4uT@chKpW=iD1|O2U$Vr9g^Iv}gT6?PxqKrCdpO7Djpc#1? zIdg;C=PZU;t-m7>6H>glUP>bA0P}|@g@|Ped zBCjJS4h@9?`S}PMk~a}FGI&P*I^;~?i~WBaK~w6Wea?;```pD?=0ny+PTAmY(L?K< z2=a;rD@IV&;5G8Ak<%bgkkj0xi}}~4!Uqx5As->AYw(ynM$UkIjGRQeod0_H>B5LQ zd=fz!`3ym0gHOqCN6vi3^Yv%%qgH|S(&AWZFOz>6K`yzAoQlD#XMI< z6B)dpyO{ra`R#_FggQ(RG&FchzAtjd*d9(@E%M`#6TF=E{|y9nsDt*1{3HbR$=k>o z7<{xCNIMW?zlfMx;9r6e{UE%rs z*Pnp85L1UYBWOV0M^Iw$5&2t@lPz7XzXUuh(uaJKv&k^&lN`)4Je1q4? zKZ+A-l6R2PGI$_e&VRl9K8~O+b%+oY8N5&aN#rEtedG*RJYRphkggQu`nwH5WAY(_ zCI+98{|j=g^NT~7?WceK=b43k{X68JLr{f$iWBk-?vsBJIrZ~t|8MQDmPdm+Xm62! z89@QLgPe}RBkg+s{}lxFbpiW-4?zQi56QoVoRqwVoQyowg$WhzLC}o6iJ-Z`?N=4Y z_?yUa$ODxle*S0E1?zlm8kyorUMuFScL^>MjcT=g-1p^4}w9K;A@7V(=09 zA3_9WR0t3>Hu#kMkI0#mN64{WT^vg7VVMelMvzNBKv2ctRr0?er$#af{w)E~pQ$;Su^4BjQ*3ORAX#rV$<)Grj4o{(>Ypb@!!fLa}?!N=s=%N#lXrc`hd zG&8u>ERN-lIH59m6*-Q5V~;C=GFk&}?e2jI{DhtDWrEXnsn(3m{I2~7+>BR>#1R(N4?EJp~k4epR1 zil7Sl7&)H7efVPke>j5b)M198hQV9pM`eob+RUx*w>x}5)d`Lz(_QU~oG`RNGq z$veoY8N9LL`T9E(L9La7Tz@fw+6M2CzXUlEd4inynXcCVfC?`|(2zVu(8%B!`74k! zA)g>;`kJsfHo7pU4i_NEer>V+3_)dsyX3Dyj;CGk|Lud+@~G+p_W#;z;rN0wFE_sBYiovVoS0Jah>T>=M5L90+tay|BDg?F3N5}~b-X(vp$jR4V zOocIm`UX$Puf++C$Y;n&4L-hz_WvJ5(3CpZ2dmXFGr09P#btRta?0c`a-4;$&mT({ zDvN@+|Kjlx1Xana2=WbHC;upNn&kBmK`k!81M-g}s7u~L`^eyZ@=qcsOsLR7(9qy1 z`E3XqllPG`G5AdRa{vD?2(n&R9Lo`cY=b-GpF>WCe1aUW;9~q|DENhfWqlDrb#nU< zH5nV^4!lMFW#k0po@_7YUuRPV;Su>)5Y#8H;lKlf56QoVoK$!||Me$e13?*e&^{r* z2SGFP7INm~0o;E5Vu;oH`zC^%WkIe!D?$g?;2!yRkmHm0kyCqy>!1Ij!uJu>A|E2C zZSW5H50Dd)XUK^|Lt#MvBLoe}rwAGuJR|=JawhP_{@*%O&FU$2&^{;s8G`KAVl49^ zbC6RuxLfql`ZvAor2e+@y>7*QUa+5!4}XBB*QdnEdz18IT9a zNudO5#*Am$f+2-O8%GM z=%4?g!Wcny@+rJYzS(c_XGG-oMm4DegLmIR`~R&F6jKKmL49%$o{(>YoDq2q?NjY~ z|E~*UUBLc-djw6%n+Td2+`W^FLJR zBdBHYfP8P9P?vm&oXFt)+{OIY%Wr=KCDb89(9qy1`N7B;lTVQ|S@nGVd1{u|NH3B zp$48GJ&14svGX)?sRh=j|Dif{XFL7(tUlLHzBv=rA?-ocvPc*ne9b%06<+_&5HujKp?yMLhmV%7)?XJv*|LzYzW^P^ zjxP1wRSnvPuLy)5j*#DQ&!6kR$ z9{Ep^JDW$z9BUz5IrlbW`e}eNMg&g6y{zmurTcvccU|m+SA@2=Z17!Y2r- z8oWlnJ#rf4Q{*%^;raS+Q=yEY4*3j0U4zHuJ0WL4UOrMy#^kNE|JQ{Pby$y}jNC!c z*x*z0eUUR?cz*rj-+D!m^|s(82&z$`ilDl|o8-?&PMf@j zoWS5=mkKXLP)y!HP~YGQ`I*QWk++bODqrsZbzw{$UWTA4d4Qmq!L3V+LwNym$^{qW z-$js9C@j4~{yGFz$z$aB2CtL9S?0+3*QCM#K`ny^zj6G0An13|9AJ@W4($0u*)Ib#0RHd(N&2KkQ=)FKaX zLT!V0$R9vXBwfybz5Kceim8M40r><$L-H6oBZFrvp0B@05HwjS$mKUc(A3~_@?Rsz zetU5!hsY^E)7AQSsqiR*Jn|GlRfE^apFmE7e2kpt+iCx=3vKG~B!W8RQv`Jl9+UqC zIRou_|361iq6^snYafws{(H5H&B*Pe)d$ho;8XI@M$nuJ4uY(pIF{PWL4k&~~#G8MWAatvM}_i#d0@)$Y3!Rzm!{r`~& zYEp**f?5U-$d5%%mwbqvXyNMf$I^xVq98y2Eb9aWCFCiBh6Yc`PeIO@d>kTZ!Ugz@ z{4@kv?<|hx6zy$;JLG2~C#+Cmjv&wAKKVHas*~GQ?1&8BQoh{(HxLw12M0kNgGc1A zLQbE&f}BCY#rW&Ouu!n9*B~e*uOcWj_=NoR$eEGXWR9GF^Gy|m+wUrl@x=&o$Qw8z z*We!cCCKrG=ks5G0=5xUqYl~|f+pk{f~E$alV6J*`|{#YPLWd%4F#9{LkRN7tz*grE+&hn%j#&*5!y>sU2cf)&r# zUm1mXr68A|1Mic2@Pzz}IMES#4ee9%=CSzm|1lN*FM_7z0fJ`a5!||>I5a78%H#vI zcdnrQ{|JQ&b@(BIs^nv|_sM7QI{5?0X=>N|fBSiAY+Aa2{l5zj$bW&LE_oI0Bl0@D zPaggTK?xOF=rAPjz*F+akuxTb(SAanC=aa}6`n$nMMIM!$R?k_E97&yM_xWo-RXMn zV*cypS3#jc9ej8|-hg+=+weYl7d}{Zx&Hbnq^kwtLwH7>!Dr-C_?+B2UR|->DXxyq zAI1LPp@M@BF1ZKy$e%5O4@BgXXJY!$G);S1b&DPWh&I*F8RI)>X6sbzDwSO z$K(ehCmc|rjSdNU2RFL38Smpo4W)@z#ytW%84djX6?n&dA*PMf?e+spYEP@#gLF8M1E6qEaC-zTrb z6Y|$0XCyqI|N0ZKjSeYw&^{)=7(r9=E^=n%G2D93Vkp)6yA(m?Wg%aG19Wf_6(O}dzW zEh>B+K>>LiK^=ofQE6f--|o$R9w?Y{m2Smmp}q zQjmkG-M*$c#=k(2Lq0-|YjBVJH;>}y|9vWC2&x&pLH;;Ss6{?OPTSy}YiO(V6oMk^ zFhfvm@B#VeGqoccl3OQY-=JOZ|8*hL1?>N~MbL!2jG(E(=j1yh$9`{dC_@)PWh!WQ z$=4&uBlnO~HF%BORXL&6pn{K}CV30qCVvi2s6!s1eV2R)k8>CEUoXFd5Hz3;6Ld(( zXYdjEVaUnIt&`N)k5^r;KL>^BYC-tX2%3|7Xm7o*IF>%VOny9aT=Ir!pRfN46`BaD zlAnyA8hIP->*N8vNq!n~+V7+Ne-|AB>YzO)kI}wQK7c3WXW_u3h3D5V{;el;NEZe9 z`6vEeF!-4Kr3jjm&(MBGZlA2i-s%>I?3E#c%2aUC!6C20E94g@cMa~5e-$}?NQF9rY6fqR--DnQd4Qa@!8`E9{{Pzuil{>$L9xLH+jD98mtuL`b!X$7<@!tdJI35 zLOw>$_?fQO|C9bn$Z^R%SRYuEe#06~E+VE?bZOTI6HV)6(%eS;_D;Xw!*QDK0f)Zk>na2p_}y}H zcO$1yZk?`%X22ezFr-2UK`FU|_L;#a{eJ^NHR_*wa8n@X&by#a54TLLQqsFh(DG`P;Br4`Sr*dlE=syZOY~R z%c$^S1Wm|?2$~vvP97u2j*3H>BBv}opa1$3P#0Y4@G%5=>wpAuqp3Ewiq{WAa-c!{7fuph5*fiNQzY|BMsL$bICD4L%L2@Gl6O zlQ$7$T~{1S?Pc=MBF80fA*TXg?EiJ4N*xje)yUfjsvEpXeg|^eMGvhGf`VdU;a&1C zBPb^CBByWgg#6AtN6fzw6=DRX1|O5(g%g^R50Eo6xOKf4N;&`a^7}Ugm1SYYhX`^E zULn5+IaTruIsS_0>rWTzD+PH1|Bj$0`3ylVg9qd(a=PU98Tk31=$Qq1e5+6XT?8fM z?itwm7(6BaK61v_)BeATpb2%*J|n*uK~}FgWOd}&26wdU{r`Oks^|jt|4jsW2KUK- zjGQ`o8#xW~P#0QM_z8jn@-Bip29L;pikv=qU*&|>VABO_NIpSONX&!;36m{_uvEatwoT049R`8ACcGL*$uS+-w{C*>d-`osln&u>ycxBxHx11 za>@(OKmWx4*AoSIQOGaI+803{d5rc|@&UX?eh6|J(4$*O|Is$kgq=n-XizlUGf?{ zB5%SI^587|`Tvj#5ju>?2k;5`5I!Tn47b{fi+3(Xdpo4U7zKwsL{No%iuRttee(Ar zrw(82|K|v5PzUWT@(&>>Ah+vkC_4s^iZ1^C4+Qm#14HZc?n01H-at^z;0^MBM^0KSL^X5i~M*Mn1s_O~_;9ObtH2iT3}$LXiE@ z;#dw4R5rLv{s-iEP@^Fd{T`Fjg z$+tt$fV_ORTK9>;N94PxoY2asP({$#;8XGqIH5Ut6FJt$ibJWroV%F+dim{*AeTCH z5mYgFmArzS8hL`8`l`$Irwh&1g78BT)FvMzC@^@J{AlFFcaESKk+vmpo70CfcZiqsM3VnE&{04YL{vbRiza8Eu&*0&J3f60|j>*UHA^Fo9>J&NP56v_2A>yPjQ_#70_z`(lgmK|oBU#U znfz(E^ZyBZ7dW@7s{Q{Y(@WYyN$=s(HXRVs3K$EN6eyfdf#yZUQ2T0BUJZjv0ACG= z5Clm&MF=36Ks6&OhT)beg5f49Pzh7isGva+M?p=eRnu}Ya?Jo`{%fDTcCzyP?ECNM zGtE5Twf24OefHTolK>BK{(j(xD1Q}y0Wc&vqabh(XA}Z{GIJYvkn;%xzmj=`xD)?o z1zgXDC?wd)JOGZpZycSi_DW9uIJx_Y)E$u&itz|F946fpogjiyvn))-2Q?N z(ox{+C#SqlK`k%@|Ede{-O?Qs-nh;v2t585?H2)FJ4gG+fhW(^U={4S1AwonPDgf0I!Q5}2BLf7sm<&55~A&-sA2nEQcSmab@^o74Ay zu_4%Pu)NGezJQJ~O0G^T(c@bINN|G41J{4)s>!k`8>$_a|VjeiArqpmAb z2Ohapx3~qoQs?Wx@7C@X1UW$vcxJoyivUlse;jy-{WHLgf8o|tcfs);T9+U}dPwsM z@KG+f4*bjy&vIr*1NmCbEzYmU?Ego%>jJ#SV9x(p`+>K(;1KZUn9e5(JoGg^1PS0N zi))kx!{y9N!0X&YHQ-4upaDF(Q&-4yn|?LH9@YNz{l8#Ha{?Q9_%hvsDDdFlb;e2H z0rt-V_ppD-;S~R-MqW-(fdmJAOpjR=_>=229|a!xq~>+t&5vu|kldMnoRM`qbP?Co z3p~Ku54_9`2m!z7OkHpkxaV`T^z}aphVVahMKZwaT)-f3>vCSvfET#|72sjkwcBC; z@8^sfkf6d9^4!tgLpJ;Sfye%-{cPY-_K&u?)Bp4gC?`m^4bJqn(wra*{KKEuU0MPj z-=zz#08g{70Uu1g&TBpxM!7;Q;03Ob=g#h)sF|Js9^B160X+0|J!GjU80y@DByb-m z$O3P10VUuG_OAi=zN9Nu*Sxd;kG!l6)?M8#3o!Qsukz7t2zcd1ojwXY%KnKiPUD~C z0*zM(Jo3B%3)zsU)b#=!gk7V|W4|G_$=3~=uUbjz~9 zear`ervhv!fFZ=Z2t3TZ1U$;T3_Q-f0z9cX{rwLZGMu0WJj;9(c!7Bxc!_xfc!hb> z;S~R7`qkLbf&_Ku*1g?9*I@1e-eT?r?g{Fl@ky@cpN|cGX&@e89snL<9t0j{o&a7t zS{Gad9zSYCZ)z&%`{){kNTA7z8L)Ln4!ZLNdA zTg!Dt=gTOu9fHLq#id)bGgP&^} zxWBtXLFO^wapr@-N4Y{Z;34KI&jZ~BggGM{c#;z&fv4HO1iZq$0X)mx|DaQDXa8U2 z0>awRo|ZAzQQ)3q^w=kWAM)qfPVgpyzwjr`GhLjtOcjDjFsL2H+Ac1K? z8hDt8pa?wri8;;?lz<06u6d=y_53@C6O48YP6kn)HVxp`Pjr{IfQQ%UeS??nreTGz z=z@d5tv!7Gx4{s5SQiihKKeC2LIobaOc#&=UgHJ~0=GH;VhRkVfC_N$yShR(;8E6f z;P!{~>}Ub6a7BGwf%g92|Bfyozy{NG4bC70+*C9I+!T=53(t0Q`uPFdWSVw15{c*BN=sx~EJJ758Wz1Rnda9)d9N z#(Ua7uDFVSlTm;Zq#=Qy6BK|Kd5p`zM<;Xvqrj7#e@k#@{w28uo-I0|sZfOr4ge2W z2RYL-47|Y=iUCiue;Rn`BMbEW9|S{{6O@6cKdQU52HfAHE7SyDJ45?hk90T8zfN<{ zBe4GuvB3ukBFz23W6XoV6U;-vGt9$=oBjVF8zRQQ`~MR281O3dIPg*CN#G6UY2YdA zW4bG{VDK^@1ny^E1Rh{s0v=*s0Up+z_Wxjra)KssFOPi-c%1z`kHQ$UzZZCd{rwK7 z_%qQSnyN1z0Z0&w=pG6IPjW^!@C@?^a6cbfMI~49pXCH`X&_!;o&a8Co(5iGo&jEA zJ_x)@+?js`Fw{9g1$fM(-_fiBKa+U_cyzt)xhC*9bL%nK{|C8?JdbscrOn(2Ji^=$ zJjOf-Ji$EF=6e0H%t>arZEzMitH22&z)Q?yz$?t-z|BEs5_mJk3DRINCz)B`N$$Eq z;2Gvc;O6AB1U$&6Zm9|w%*kgJxH!?zVfN1gFMnL;Qvhy`c1m5G#^0RDRJsiGcY&Ny4Y)ZAsv~FrCU7602UtJt z?xC9USMlcsgE-p#71eK1#nSXxfHQ?r`rVf0NE7}Ae;C!sdyN4k3iIi@E7Yybo#Sh$L zj$VM)Cuu{?7De&~JirTA9e9@WX#qF+ zSleL#zt4Vp2s~Vn8Ja7Z`+=K`0>CGEbv{AhS2DNTT(3XYUpeR^ZG&3>=#4|36>;Eq zvwsq}Sy(c_L#&IyqbV++1O~J8mVuk4w+7r4JPO<_y>;NU^g0bpHNoJ`=_RuTJjUAd zWcP}hX6*&O&n#Vl5BQnP{hD|7|7Q9HAc2{FLEsN^Mj_xkXX}D(;AZ-TyEu)%nSPNj zLudL$fw#DT7;rQF;=m(wbcGVYofT8XUlI&ePLKf}<)O&}_wn>9Ape;jsw(ie9tCcOAeI7y8G<-)GXx3XW(bnN zn_O@jc>ROAq8aAx{l6K4EF>^PFbLc_S7%fJUSVDW{xT0ixtr7HfB&4LwA*0W%xl0C z=jnn+fv1_*ffvr#{te)@FDg#)*93zZn-*|0G!|FP1gRMs4{$RyUf^bS_!L+1Z!$8| z!w(6X|EpUN0B-YG27y~&(*7afe&%7po%!ebj-DP7VNh3x1nU^^hrg@+#2Gb# zSD3ee*O*(JU;Fw0IvYI3!25p_j9%a-7=6G^F#3U;UhB^vd#jpupV??DgMm#^XeK|1xVm$UIZRt zUIrdxUIqTa@99}kmt4hvqRPP~4T^I{P2g$fE#L*_7UyRgR$=Y|u42oXe_k-Og9~_* zGx7s(2N&>mYyoe_Ru%UD?cjn0?cf654ldx+d>;gE_7er*u@rA8ieNAsiV|?Mp(q14>qG^(8OkbfvreRHU@&7j3fzok z9k?0G25>W!P2grITbg(F|7JsB{Zh{c6TRt+^;mj=n~ReVIqw7fz|H<3(8X!|%?2UZ zWuTAcbT$a|x!%A{SKGi%SBHU{u8shAdRoO_6bz=TW57*U$AO!!P5?Juodj<72WjF? z{F|;0UZT4?3kfQ$2Z1NpzW_YVya>F+yxie>{#Dpe?HHWtx5X@(z!SgX6%%-k^JxOF zGj9R+CsVq`7H4RBB9_$L1H8%H3*6!x5+86g_I}`ImIYE^Fk>GCZpJE^q+>Ct~ zczeZU-roQFxdkyuaNzfOuLr!nVgjGc{%PP**4b{JvMLM)yA4*5D^vh(GcN*9FfRj7 zGp_#+rb6A9bCW*+<+MH?|y%-p8s($w1W%y)h4)rM_Ffq zS6B}MuV1Ezpzv$h{|7JEh9V@$GA{$KFs}mN$`!2xPdvr3Ww<&2uW?3AW8nRNop}p* z;p@7h7H4Q;D0l@27jSdY@&ZqptCkN8?cf4#a{&S1?cf65jxFFETPe#1Lp!*DN4Ve! z@HF!n@Wnsig$sB)wj56JXS!}0CrCqrDC_KA_#kjIlm*~sD2tM-_%~x&k_O^tEX%;n zSXO|Wp{xQoLsPBej=p=<#+Luow?`~M1$rT1w)P0Y~P ztbM>OzI^+ESC|KYXVZFigxXxMKUQReHiX*-wfiEPp(60$ev_RFmw?BZmw_jkrz&U|)6=F3JpJXVP60LG@oO|61s+am z-T;2`#hN!Y7yJJUw88pK_t>9&k>(!Y&4lKD;G3H2$V#kuC#0|IaOp z0yiy-12-+p05=sa0Cy^?;;#Y*Q}ZftGgLL;o*f4`Lo*6IGp2bRczRUx25~3;%`~&v z(1ZlV?K(jVc;$J`t>1PJS>grFJ;0mHy&bOSpZ~8qfv;n5T9o*U=6>J>_74E}|4sV` zf!COafJf>noge~+z(Rs5UjX9|cz0#iT@c$Nzo z1#Swc12_3M1b612DIoIu?iM7!vY#^zqre+!&11k%9?(1i+~ku4PWkBhp9X`;Xb^be zoBKEwDgeLzS2G-51fH#FUIHGeYF_?5?EmB6(FIf>L6mtFc>NMR#-qR+%p1VZ%p_iztofL9Kh>GbHJ!zupE z^m~d8MM$udc^P<FLQ+=z-`Va*2QW3&HRpc8R*k&&6mdm4|7Io;ATC@03YRivcMxM9~FNEFuZFP zBH#_qs02L96{-ODEYvGq6?lyOYs8)SH!EO*4RuIh#;gH6&Hhc`8Rpg>yJN`YVxXCC0yv+VKa1*>?;MF_$`@bS!sBuOy;HKa>@CN%QfVY^Zft%pX zq`=_4Q%{>La6j_`a1*>m;34)e0S_~;FmLbwP4reFL5vgBfG3#Oft%oM0MD?0vzycN z|7@^EyMv|m9^Vrpf0yqGfhPuavWC^ zywLzY$o>VzRs5Uj_vCkVf+8e%jCl$8?cdk_W#DD*i3;#TIG?KE&iuQQ4K-m<^Y7ie zbOEElOSfoV2VP^|0Pg*s_HP1@Zl0;kH!Lyto41AxT=!_!3gAZ$-06ytt&69?k{eO%N8Drq{{~vJ>Wr07& z{)52ho}vpV0^f9=<|W{%*Ev|qU|7#FQ30Oin5Y6@f4(lD2HXVoC~ywylvM|ViRuP$ z6V*-NCaPP&O;B5Z?v5c7)EItw#|i+iU!Zwdauxq3 zsw2`s+(dO0xQXf*a1+&W;3lXOz*SH?^DhYo6V++pCaN>Qvp49L6@Y(}7pNleB=gZf z!~Xwr4#qkpFhSY?Zi2K4+yrS0c)X}9YCUgaLa#rTiBeD7phnQL%+l)xZi3VY+yto~ zxCzn#@GDb1&4OSsQ5phng470Xf;0@=1Zf1g3DQ&)3})#~0yjaL25y2h1Kb2@7Ptx0 zLCrh+e-otzNMM%UB5)I=CEzAVYrst~j&^Yxe-n+q7fev-u`j>NcQC*U4{ARfxaS1z z9|msxBfxih=(J45Ula_XX?(l}{N1;8^rnF)pVNoQ8Q}K4x}rtkQT{ai5^*Q~+bdu} zC#XS!nECj8;J*8`e+zh={jI-fyU9O#tJdBQ*Yof2PwS6X@pTN&7?|z0AGm)X{qgxh z;7=9zb<%~9^Bt89+`kWh{(l4v_K?mf3fxpE2HaFA4ZO~u|DOR~;+`(1z|iCbCEzAO z4YQSE1g8MDBF{HYko**^^2&lQRQHx){BbNc%~ zPLS+2SSGNEDz_|f<6jconSZfE^%$3hLCqtRU=+9=)GJ*bxbe5@ z-8~d$e-Ci-*YiIBh6pDJ0yhOjfFC}f*Mlf)cU$Mq#=RlGR-r< z(&|ZS%zgz|E|&ws$wI)vJfh z13VS|v33lAA;tv+ftxiy0zA$BQQ#*3G;sf|PPr+o0EP@_R0M7ct^yxq{~B=P-vn-^ zcgx`ve`flb1;jVj-E~bazz^JXwGG_E--HkbUfZejjZ3cL-)p{`K^lmA?$HUd!2Rq$ z2;BIWfd|>Y0z5Fp*Z(>geDBliK?8V!5~zQk9o;bG`mpW{gX1gVWIVMW}}S%esd~ftMf91+;*h*4Llkl`*00Qa+h82BLjM}VifLJ8n;_D?0jV7hb=xM@KFxS8J-;HE-V;9jm! zQ}fRLzkHkSI_vM2l+c5n!wG%;{8W=&xP3E2fWD*4iR_a-$bL?x7(1w z?Av3&y<9*Xc;R+kkqmG%%d#D==b!1)Qpe!TzYv{ z{C^J^%(MvrH(eS8Zn`uAJj*>41wMMeu1GQkhBzlk0}tP!6BK|a*uMzew780#d$h*9 zz5h2|+Jpq{%O!9Vq`pRXmzryVAGqQuM7q=%__i60d?R_E}(&&rbNae>45e5CkEChrdcC1l;&Xfw!-g zz|GR07TlSC6|PZ67}We5<)AA9H}kjz+yq?>xw%>brv~Wx-vUE`TWsy_?z#e3$PYZo z{sG{|KMXv~{*m3V|2J2&1SE)Xf+TR`KZumt4hv z>@HnEMjD70IYAb$1cSh9TtFFkg#9bPO>EWMT(3V?fxqRZ(Kb;3)4vQy zyXO_?A@=tIH%oF5c!>Q&z+2|~f5K=ea!ddp-K2*g3;fJ)XmSi6JajE2fT5w_6q@zvcIi)Xa8>!#2`VE6U2d=uFe3Dvws%2$-mUaY5Yr^ zpxkAkb3txF6?lt>#?$QX2{SZa;AUuoz$=*ukGaPe+3L)PEZA2;1)N4``Nz<+%&-ZYIo1s?C(o~p?x_9 z9^nKwaC0q)0WWY5#etj4cZPX;|6kw&vXHE z(FK8z^1>AXo~oK}uLFZgkObaj|1@y3uoRH9e-Suu+v)TF!C+mbk5+5I%|5>l+A8#U)>q2_@WDGZ4?CRV&m;(QMp;OZ{fSO62>jUxG_L>;@YnBEft!`IA-RhG z2)DQ?4aCj0z{^2tD%xa!A8^w{A>baakPSRd4R+>V3=D&uAP(FVkO5v||15ChUjSa_ zo*sP@_Wv(Dth=-h2~I9+?%`?G?g`E)0{p2h+CL54m(j76X>+~)SlJ)zAS$*EYW<^Y z11Bf}H~tmifgkC7TEL5s=n7f9#G3|uGxex8gusyDf^Fa?h+@DC>>mei{4>DKS2(7! zV2E)G3cyV;R)PEfpc_yFUSjU!rP;LDoG1D<@9h6gu-K5m$KUN320q9YjRLPR9|ZpW z=XFI3U7W^0{zq;>mx0Ef3mye-D%t`bWPj^z9RsGtrsw>?8_W6g{{vt!Tc|K_^KEw# z;Kn}z+&l-61a96%A0+O?zp1HzlAa!gy(FjrA3aTfdVUpnp47lluIPk!OeErXW!8{R>1#T)@0&aS)4BYsS0yjNTPl3TC zu-@(NiI{nW0=V%H05=b>1%bC8Mq}RI|C^`RqI*e@1a4Z825u@;0B(k$*v(VzhfJ#7 z2FnaV4Y(;4=YZbUza2mi1?B5jJnSUmM_r2~eN^pgIz|GN12zYy10&h=C;N=hT z_kYE~U@DXWUga+s%L4ap(G@QNA2r{Q2HZ4Y^gY=B7r4cBNMM#&Yofb{Op86hO^XA- zL!5umaI^m}mUYGvW8m|Dn-fHVTkM|%-rk-AH$7Sao(gjTMKGA4s{)U(e+{_tZvxM- ze+xKoOj4GQzw6D+0`o0(e&BU(u?@V%V;lx#199^-jE8TlO-0S7)C=7B`+=wV4U8!8NOKPF|H06D zNk5L80UqR=$O`a--q8M4;IF@@c@wzFC*bD$f73FPQIPL?4S(TXolz9H$tVllWEAZ((C314Mp@wIo6QD+n+2x`+?)Z| zfEVUa162Htg27S-`sd{XN7Dk6Q3$w`5&7G|O+HEBCZ7UvC;m+VCZi%GFd5Z>n~Xes z(uw(aft!579j@n}$tck=I6Yu0lmu=vDgih7i~=|L)PY-bQo5^sd?ssJU^23Sn~cK1 zO@&&(ll&!h79Tj8{7tO*Q(#DQf&g%HycPy-&iNz2{af{{i2;u?A7tL%|DP~d_e22_ z?3|~06}ZXB;uB5NGLw%7xXCBj&FS<1cm<4h8?5iYsBg<-z{5UWp+Vp#p9*l3k2OP| z9h-`3e~P~V7)*lE`P~VE_vc(&?Hvf#3cG&0C7A_%}7Wh`(Uiv!J`+ zXA_H^+293ko^J60_n)N;@B=p=R1y%}nSU?btP=!lTNAXR4apz|H6WM1Y4T zY5yp2dho$1--?03ygMBS-dJ_0(-TSH<_tIud{R(d``o2OF;AwlH# zx&;N`vG3`gD*_Mmma7EZ%MUP>4LAG$(ob{&6=UH2zc;1}r~)sz^xq5AfSZTZMu87L zq4Tc;PgzrRMh!4LYoZr;fh*Jk9^9$_%--^K_h@bRG-t>>zxH*aq0I&Q^w>SvA`Az*76(NUH{F&+J=TEbBGxcM}@ByjWAOa?hWo}UF?k+7JSR^Kb~&Aq?EZ zLlXgBunXpt64E8iV{nEhSeM|rGX$E-d+j?4Nft$~O90YEjDJ^K; z+5bnM)-^3cf)ZcNO2Er}++GH5ZsRM!&HDn?E>7cr&?oiut92RZo^S{M=@sw_4_O^} z=5soq25_@6X##&%`K$PAf#Jc)x?t-76Qw#B&Es?);935w7BBECdBO1k|J)`$%L2rm z_%|z{dCor!2}&I85#Z+WyC`t;Cm1o{=JC6DhwJ%gK3*%)F*r?DPbjK?N#MSW?x8gB zBKKSdxH+oH0=XjK?nT%JT(4p zPS5||plcfFHdwE73xdEOd{}?(ZwR=@uPbf?H=ivV2A=u3YB0rL1PngTC<;8ze~K9c zUSFqI%mnbKKB+HGN#Gt{=+cU-_&3upc)A|r3?wk;cUj=-@AuTdLEydk{@20qZbZjK19*f_ zvzoxoBbhDWP2PZ52XzN^gKu~|2f_Y-?v=VHypX`W+3W+}`lB8KKk%cE)mO^^@KL@T zhYUCSfAhAxZ4A8sA9bRX_5r}XyfQ|BXP(j(iUIfYO==u?s{RH3#Bwm051~#1ul$vl zUf`wA>LJSj4>8XIKjb3kB1E761%?t|*9*W472UET@ZuEBOTZfi&C9?m9HbS8Q~a6f zH^}$pRY+i)TP@(`!)Zr>H@Tv9;I+xRLJi4P{6EGUho&?T_wdE01w8u$osqS$JF4wJ z>RT`m@Y3mef${=R_RiARe;*j0E%QgK1F!JV1b~nJT309t+&nEC0^Z;T*b8C*Kg#>_ zFeHfatyu)P^`tI13Ovi7h#m)S{)#Tq=6e0H65Mskwn43bbOg&|mIi(_-*{w!KlZHd z>OtV<4ax%W^{IYdlfh7{>#-~WH>cQT;IR#Q`c;5m#LpL1ftz=&)-=nWugOH%a_k;!D<~^Pw@Ya30LM7mrb5EB$T+hD@ zZ$2v>gERdid?H!}9{+$o*Q)_9@!CEL+?x%K>R0Z;II z$JXNR;5C02>;Z1xi1enwVBVMW0grP}_<`Gh(U;=@aL?O%{Rjd#f3gu`-roP8utP_? z4GA9P^Zzh#^9*MMxSxYA3OxLX&Og@8Q8zUe+a1V!M{gq~(4;O1{Y%ZjV`H`DLQdvzC8Ai+gu zyA9ktlu`r!7$4n^0ym$2Q5W2qfBS59JJYQp3<_j;1JVR;?q1C;mubMum*}@<>O2h% zKl#UeOb5Jn%RD{*%^izLP&-#2D%pG|V|clwyE+cM$|oRc;Jzn$r2`(hh7YYyOzB%C zQ$UOjB}fqbh0dr9Ji-1I;A!S{;8o72VYu1|l5EVs-9Ji`87;Bn^WwA|zqJzbv-2c^G?|H!j?MGHv- z@#>#6j{ra911F{z$;6rHiZ}2-M$kTkMggjN`cR0{s^T7l1 z=w7(_I$rcQU*(QGs!u{v78(+KM1tIWZ#VKNzZs1@u@`Q>%vSr;_?xbd@+S2E$!IU! zd~qrINBKqrx%pnvF0SIwd`o4Qfq0b9a*!wX!fifSME~qwc!XlhiGP(~w+eUu7ZpMG zD`KXHLL#^%kL`u~M36o$@-bh*Nadz1X();){k*9Sy_WXE%X{IKz3`FY*+!Vxo(Sv6nn3hCuRkYA=SGsOcM`Cu*XiU0hVOi;IeOajs}ewM-f! zqC%1v_QEZG4!}hlmMNm5VZrrhscK_FaJrY`{wG_Q->X#_9VRkL3x2rZMZrHHcunx5 zCFjkjYH){B`9XgBO%;5+NMH-TN^o4T;U5zGJi%?j&lkKTcxr<%nD=f}!IGCnf&t+l=i_!&p>GLZ7W`(xgM5&w z{7aha@sA3_Ln1+p506xWKMI}^{BME>__kd6zan@-@P7-QU6j)I>ng#U!eE}&P(2~J zm){#wJSqG=Gj%?0%156ZXrotfGPVEt3|ISqxghwBfw(?|)oB8P>xV5g4+^dyw9z~y z`1E$M^o*$B>I_BqKm8IG27McL!yxL0t!vDZf5e%yXF1ai&yiv$6YQ9$sef(Hd(CU{8j_X}>fIko=?VFyuC=%2JKS}UW!B-1j7ramK zhTv=3{Z9@}VK_x3XbFC*;Fh;D3)Twm5j-roSMdKbT#dg^7)~<=di4wbA;ANJe^~IK z;2#k@B>3rq+r*vtQ`7IG!Vne-B7#Q*KSS`S;OhjB3H~v`;~k!|)(bvjuN3PpPs0oG>&+g3k-y5?pRdty!H}5EuR)!Os=kEBF^X>mSVm zVfbH>z%Tfh1P=)QWx<1jCj<`(enFel_}jv8VcS4EBEi2Rctr4v1dj^-Rl#F|Uo3cB zaTR}R2rdzZgh(JanMuJf75-_#zb1G_@XG|x3ZA-L7zTym>w*^qze4b$;5?BWYf135 z@GlF#L35p~A`J2dqbm4Dkx@)&BpR!r(Io;@1oA7yJgn1A=D-4+@?WJS6yy#M{GW3&Tw!L0Irj zf=2}Zw%}30zaw}|@O+1-thg`?b_`ZR@b3zq6#RRFrv?AM;2FVxAb8f{)P6Pgw+O?a zNbp0!3xXE}FA9FE;3dI_1TPDITf6_sp&|^oiv(4{?-0Bu_??1}3VxU1b-|0wo$?#P zFf0-@1>Y=qOYpk|x8`(a!H)#@2!4;?-Z^6bf3Gn3M1mg+?iaiyctG&`1P=;+zu=)Z zr}jS}40hXKSq};x7W^lIM+ARZ@TlNr!DE7NQQVAwTo@h^2@--oDtJ=x#{^FczE$vy z;6D{Sl@*4^g<(+eir@vopAft#_=w;o!M6!s)?DxZpA?3QNbobktAhVr@S5Pi5PVed zs^E3Of7$MTa%c#{uSJ5U;7 zFL*%kX9W)m{s+NB#GUw4E8ug&V2cE!f`TCwN5g3BjX+Tds~F zrnrhfHT~3qviTPm3EYAw1n&_%DflG8(}GVHJR^8&iZEn_VXEMRf_nrn2tG~lqTtg7 zF9|+Fb3Omc!my7>P!W7z!K;GL6uc(*eu9q*?iIW~Pwf9^2}469m@Rly@Hv9F1fMIo z#ee&)hIpRf9>dlCf4(qyje+?|O?f+qw&MDV2G?-M*N_@RPl98T?5V{@1= zWJQ92;DdrM6}%w$GQo?2zhCf@;D@J#p)3qX2woBVNWrUue?ai&WseWn_OWWS+-t|Z z?oiI}Ui{o*f6pJxk7Jucw%$-KrHl@kPM}XaJ9;MRexYZR9uRsy=^>#HAUz`VBGO|* z_mXz6bSmTIe<S3BSL?M^qA27q}|7ND)0r;sa^rjBhV-Gmq_;u zeIe-qp)V#qB=pxvj|hDQ=`o=PNV`wyRN$($<0)^i0N0X3pU^ju?icz-(gQ+&hxCxp zH$^mC+#g#I(>k+v?)`YY)%p~pzOPcjuK%}V`) zK(7G1N%sl;3h92KUnM;t^qZuIgnpa!h|uqm9&2k_6Ktx0Whzih&6+}>w*zKPC*3FX zOw#>A&n7(}^nB7oLLWeSMCe7N$As=B?RJ?8q-wJcCD7XjwOPwZ_X&L@>3*S?lO7Oy z1?eH7k0U)I^ogX$gzh8lc5?+%v`n5#pw|G>r;+Xx`gGF$La!q|AoRyc4+;G#(j!8D zhV+=w{iNMJx&kS+PJe+wF9W5|Bi$$Tmq_;ueIe-qp)V#qB=pxvj|hDQ=`o=PNV_LF z6-YU2@l^zRHE{H`r2B-vfpovnHdh|sr?9us!kscG;y_zcE5!e4I1bRK43QQ;6C-h9x{X)+sJs|Xa(nCTYKzc;zMWn}s z?j`M>mg*FED1qK-9leZnpU_8=?iYGF=>efvkRB5HIMO3RpGbO4=swc!)bvh)rxNHD z`ZUsgLZ42$U+8tD2Za7O=^>#%MS4W&&yXGyx}S8)J)={BFA(Sz`aIHoLVt;Lzt9(w z9uWFs(nCUjjr54nSCAePdSEqO|K0m^DsUA!^a_0~={})vAl)zYjid*J{toFOp>HNV zBJ?e!$AlhQP1k?-zMTr(Ne;b2ZzkO*^u46}g}$HkfY3i7JtXuaq(_AQDd{nxM^Xgb zGdmUdIq6=Ze?_`a=--g;7y5Uk2ZVl(^pMbhCOsnbUrCP%of;$H-mg=Ee~|7KdN=7l zpQ!ThsNwmwefHCOstd*GP{DeFf<;t@ZVPfPi~$rvg`z?iKo4(tSeT zK)PS(8%Ylc{TAoNd2 z4+;GU=@FrSN_tFbbNwG7;GW;9z|Tqd3jHh6eM0|+bidHQBRwGWbEJoa{xj(jq5n#H zjCA|@KSsd4pi_Z=knR zU<&D8p{JAX6M81;exYZR9uRsy=^>#HAUz`VBGO|%asBTl;NHJefkR363cZYUpU_8= z?iYGF=>efvkRB5HIMO3RpGbNvB|skm_W_*>oJzV^=+j8|34J>0excWq9uWHDq=$t5 z6zLJ6KSO%Sm;n6*+y{0l@CDMn`Q2Z4f9cetr&+ank8AU$kwbHD^td-~@0q)K%89N` zbfEm;VPsQ!tbS-Nwc52Q*1v4!6f3=MhGorN;-s6md5Qn9+{)GYTdr`QcjC|J9>Z$c z<9D8U>i91#d%SL)^xRi_?cA-jM|^_b_k8~}s~L06$&Gx)wW;v7H9nQ{sZyFW#o)AS z@~5WUo97-%`Mx%T{OvipJ(q1Op7Igb+PHeND*>jnD zm;COL|>;!P@a((d%hjP93*g=iK67=sUgMlU}uZhBZDyysx=-dl^m_j^&ZdW54aIh)taet5-3cdzS%i)aK2 zw`^EPZCidd{k~*|y~QSdCHI_24jRtbr>B99x!Zl34 zUu0P;{Eux|w~&4}y>sK+d+E;PqTJo@=5M*$J>T`q{5{`rU+4Nqe&to}yFPfi3QMOn zYx&>lcT>qR`dwGjx9o59yRPJdWiRAsUF|;SeItZSB_D6QE?)Ln+ja4>E%_f@?Oxzo zn}6tP_wQY&=C8@P51hK&V>M5^b^rX`8TT-Y1M;7~#(e~f1M}ZfVi&nBz4f5{wrkug zU9%qEbB+6Kcgo+Qx~9|XE~Zxc{TtRLN!yoiSa$%u`oFYcT~@sgY*=>#y{hq39Y01t zG%c3jH$Fj6-K6O=v(vMu)9>~D7A)URKV$UMt9s2&uXB@4_4*j4w+6H8GUTUvSg}3h z6P|p7YGs}EME;-ObRRM6GL;Ki&T?L@<)6*J?|Szd*NypeuXis#Ou4E?sP=l6uGzD6 z$(lWHE)cSyfYQ}nGFihuXnF@J(mCX_3i^*_vQD!!F~L^0jK(lmpN6T z0(Q{P>iqxQ;6Cb;St`qn^?xb1|1@=OUzF>o7Nx1DObd4uvg__4f7N@2_1v0WS0t8> zZ&>$ceivmw?}E2fle#-@pNBvAE%*0auE|av-EY5@-<@?IH|y8RmHV)-vTLz#Yu$jX77ypOz;4DX2|@8{px%b0zCasJDL?p3GULy6Vc zZzRX~>FF(>nrh`f+v9oh{JSRBt4#NGGPjn`pjS1&E+s#EcFtKzK1JiLd=Ah5dytmL zS0A4CUH9=l3uvLJH9qC}-rV=Om%g;0Jsw|fkK0GAdHB=cckgn!7w+@$skgX$CoPye z!`f7Jr?;GYTzboS$JygAdaP3a1#9!EA@?fx#Po-MI^>@3c3(O@|J?2FuN~2Rl|p1X zU3Mt`SHGshMgM*x{l1;9Re=w$DaXmCCjHX<*Y9v2yK3s|)TCwhme@>t{GlmU?(vbp zi<|nb-1+ZKtUpL)vCJMnK)q7^eCm}dF<-s*+T(Nc|GvXLXZn7xO)OAbn*EdcnRmJm zb$=+CUva1VJ@*WHz019B-p|Q>`@wXL-IQCmjef6BUATN#{s(ut51ak`W!9#*XfL2H z!}Xr|n|EB2f9@{#GS`E7SJAy-WgoTYteN%}e=)c2wtrJZ)2nMZw{EOw9xan|mmNvD zoju#$Vk!Rp+`3*`y?0Vym-A;7-E*e>lg!GrA^*QcT5qq-UsH4+=BnlIE4mM!cGo4= zCUyP(Wd1M8_@(@K(S4HZUS*t<|M0Ne`{8ep$DYep4=bg_FU!~ z-m}Ka(UvXiaoJmF2eosTGsj}h%K?KT!q?eQx#}Cm(3T4-T$51w(m2GCs`Lf z?Y7n*HOU@-oi@1JX+W10{LWV5f2p}?H_dRxzPZFk<;X%b02$7PSt7VI_3Go>8A@`yjDcFM+C861A^lH6qGH%+(4b;j0mdfR`T*3ptR z+Dm)LIh$juQ+HZl-bHg@;x_lniHTXmM8+pl`wUO~(Hi&v`&%dMI>${FoqCV+`(gA} zfMWl2<^Q&sPC&H-y+NViVXoZkw;2a37oU_~r}#B=xZQZbwZ-pBuezq64zks2@8n!Y zow}>v)#*CDTJ%GYcpY7*JU-lGZEE!Rmr;dh|J7~Hy~%yW{c7mwn?N=-$lkNs%1t`M zO690EHOqTAwPr5u7ZxvDu#h6*Y-`;93_Sx$yWoE|se8|~9&AiZ)I1kV%k84q#`&&s zrPan*ZF+ap@4LS28Yf$`akXn)ZI0E3S#5?rv@U&J%k=XK{p|jVYn;+FcU`yM zHBLL|Y~v=%kfx#PO0~=8?Q%}-s%bavY@;X6A)jBnw=`y0%hi_p#YLY<(hHN=TGVQXSIJ#`Tx<{5<~yi+Hudc zQ^r&60uDLSDd0(!;CU+Gzgx#P9<{g72C3x#{1dBo-PX6#vt-{h8V|d+H2&$%Sv2Ak zb6i`_{jhZm-B~nGd*+0k>X(m)Pw6)c~r{kER_r>a;u(rm&uAN??Fz`&KmFO;OYx=&mTU7y#qpb0&t0z~_ zQ-&LK+Qv!5ZlxIhA?5eb+O4Y42Hh`JpCG^EDZfi~es4{+bJz5d-))rNH&Qyox2cQO z<*fcO%J3S_@K{PbnG%1CGQ3`A_?CM{uC>vVtKUQ!=5&Vp)0Xs88$Xb%e~&W!_S&tN z{q_U7XI-w`QdQ~eD8KKn-TK1kdvcA#D8D^F|>4h(qz;XUA(!kv@ExS zE<+EHe{3~n`W1UTv)X#7arWwQd=>ePH0fd$x%a)Ng!$MuRzUZ=!q5X1c2mR>E%wOJDT9G?@@W|XG>UPC?sZu@Eb86L~ zMyyoBdk0m-zi{~UCG^vK4E@*RJ#tZm)-NlaSvRCwP4oFly2!psuP-0`i6i6|NR9VL zF3ulUa`!Gi`C@C+?SESGnaT81pK2Y^*fx#E_pn7{`?)C1{QPAl_rjFxYc!uJBkQKV zdtBS9C%C`0<{oQ~MZa%6!M&gBp6wLP!Ar?!DiuV2?$ITmIhcOxl#$Bp<*)1XC#7hS zq8qutze3xjSbE)A^m9K|TD7R9hK$l~pYe&M7B%KdTF|(sQWt~+6aXG8d;Wb3bJx%# zl;@or4=tTG{W`yE@pI~;X}WNy>P8ypCB9IuZ&N6D_RiySS9*@meQKt)>4Po`J}RJo zo4s{kTA}jpB?n`4i%~b^zTVs;nkk>y56g()=teR^Ch&x9jR6~mG~}u z>pS0|TAqFK%3XQVkJ?)mr>DU#Y#gO~!R5N<=IuWuuDX==#;;vX{p-v#sT$Qb$zhhk11s-zreBCw2a`i6S{xN&2lc=~Vr!rkm3Dr2qdZOg`xgEEru=CSxEIf+dh9rsDoqQR$E7QN*#qwVQ#Vq@ zt@l5KQ(5yMUB~b!q`j-a4K*Kt(Gxv(8bgs`unQ6jU6=fciAaD=4)uo)p%2!v;#4G zJS{AXH($Bw_}tLG)}~9<3V0GlIr;Rv((9I#j?eA4ANBU}nvF~+RzE&Bo!ItcDW=Fz z4Uu)is@#thBdyj1b=9NM&__a0uIOTnwN^}0|@uw+`GmBC%jppz)+M~AGGz@AQ9Y+zZes=z}o^&f#d^b=xT`cRx<8CO^*;J!iNn_8N!T<0sLKa=EU(dHcrGj!*$VgJw}X zFPb@vjxw3il(bA{Ybdh^RA%}29&#^8Ko>`O5*wAzB&8kjymDlk)ubrIN7cQbY(K_a%^-QgC)2VanXWQe49AIr)OTT}p zLKiFR&KuTc$e}?Sp}aX7JU-~8gA^c;~=j%MMrY=5pVx-56L_5R%I&!pGwONC6(R`CDv2_Bw1yLEW( ztcB@ylhn$Kc_{l!hv!^mf0rxMRfe*MkH|f-Fr8ZW`raHykH{^d>HX5)>}MXC+d%f6 zWOs%jydt+RbAC{^^RJR_g9sr*Mn8J(v^D2D_@$(&mm{! zs0_2n!7cRu&*R(=f*+}UKKhhgU`e|77l^O(E2Kox4|LEV1eB&XXqpBbOD zDWCY4dr@GCHgSUr5t z>fh6R$xl2@w_SguWk)6cAF5b`oM|;!QKtkyqe{?SLha&5^gZ9i#6iOo|FXt?E(-b{ z-{z;Ou*J4@-^c~ldb(BLy!cG(-($2fd;8$2xyIKPf9#Vz_Wg~6r>?wYiuKS6>O}g^ zx#dCGuum?@S?50S#Z^nD+4o#~_&3+RPMKVL?~gA0Dz&iCGrP4oYptB_x33S)a2-yk^k*c zlNRMKeZoECs3~L#Qx(Ul)VF#T4mbX3jjO8Hd-kU{m3*7WdKPS6LQOpB{9{9ngV(Oy z^)EaB=o54;*}ccwv|&n`&Kgv)^Edy4^jZ6)*QwuW@mMxST1|<*D-X@B-g%|N|3d86 z$(=NRQrg`~^9PlOus=hZ0|gh$=cML zJDB?L@rk2`AMcsdYV4SjtCOFKUe&mr3)NlDu0bvUctINb`4$JWvy*L5f_PFl_;b~O+7*nW$b zZ>IrXss?+hGum^V(Y}M`X=9^v0b5aj-X7nVNBi|1_V|OY{4H_XxHQ8(z7O9*HBdD* z-SReR)eY5`rmm<{SG-C3?1_m5#h&%8*q1A-9#5&}&uul{p_+Xny-IbV=Z&ey4wFy5 zxsA3$srkbbkJ9CE$_P`PGTk z+~JA4)unp!%5&$;XiXe8d1cBesD}UDY8v|h6?ogpx@AAK$G@k#n+o*&;NaY}Gwc?vL*u8> zCe#$Rn+iL3$Fx>l7503muw8W1IZ8hl)9DT^_AmNrJySh7{dU^XsA!u(QMY7X`sRMR z_^YY#?R_XhM8RJ-E&T(x^t$VvmTrFP|G%a5fpMGYBa=79dg(Ai)~#mp<7_p{j?G6@{cdF9;~`4E@o5jQA6nUp;u_3bPmq0(^Kc^7sb?> zc1X^;^odo0f7`8Nm(Zo4eiL=|!Rb|=rqy!MC4g37XWqnVTBt>`v1U?kvE^~PZP%KU zSH5`n8To%bO~D&h-6ZDGlWJ8U2WOSI$sRwPny6My88nBfW>f3vnB-WsIrQw9x?(BS zc0Qd~{;kitZ{S30{Q`>azkSB~w_Dwx_e{xE=`s+a6{gWMW#z?_t%r`({wXIx->Oc6 z0hNHJO*;Wit2ZgZa#4W$gpR*^iYh?()6}@wTxV!1y-VGuD%to8&2QSIwMaXQ!e1sH zYQ2}5SWxY=a{Ir0`HgC|zkrMZx)QW#DQbM$H(aN=sV;Ea=?XALL3KTK=i>8MgjDOR zV^demp+!KZKdUSK{NXxHIhp?JCOyS~XXn%v3saE68C@C79j?<9k{SH3$$+9T^LOfY zN*}-39;Z`^2jjh~w^V8Ir}>;+`iDd4@UyaN>2JTW&O=v|U;gY4n$P}7y$^NNF=^X~OFIed~twf>s# z6LY`eiOba39Jsu`TeSLInwVduYuc^)npWRPtv-;hX9d2V#r3?rOjUlH=Wq13(B_^!LGT!RA1|L@dkJJ_aS(bvm> zi-u*Ry)v#|dseS3(rbo-szI-6ai@o6=GN)$yx*t>l3(LJTA2>C$A6_X`KO8syx$)G zIRTY0PC9lNyHuZ-GsI@ro`>89w^WMaQ5wG>&;pCU5H_8>Cn3y&^@gW|PyJ<*1 zP+8UZ7zJUE9+Efc%JVqI#>gz%s+0Y36B~3tQq*g7>i)(W_saj~;3$gav6l)8nC0;k z(}wBznuf$IkMlO4NJFyt{9|bAIdypAcx#;g@cq~-y-!qeQzh1r@8a~T{i*d%Ow6>_ zf0d?UJ0`Z7;7rj~V%vX?PPgi!c5qG|uB%K%Of2G<_^*4v`MYypy64qj-mCXc|8?ZQ zUY(ejJUl^X?2WTsD|g*AxixXMi{iqa+fFSXqr!KbO?Oii7jsf7Fx(UvZU~Ic92aCu z-N|u5?0=|IsUgbvv-Ws>^J8w*)ZTmo|A>b*E&~@H465I8+)fpks zHDdpLT}|j>+pRt&+pF}%@_Ct_K-s_O3AF9RQ&pI?QISKD-ovyf@p3ycE^H`8ek`*H z>9CcnO7?gSE9LY=edJ+K3ivpUl28)FGH*cz!i1lOiTxTTn1+e+KLRq(V;fX~;6O1t znT$HayZ|6+W3cv4fItGxXv7AV>Q$zMfCRU#!THzB(RyJdln07B}SK|5I1WNM%`2s87j)7&wZ8nl2jU(C3FnKDN3-(TF~pK{OiJ4fcbo;Yn&w zH&c3<$GWJ~2PtWlXp3aAbKo^J7!_dNe_B?mHo6ooks2*0^uZWGk|q`O)$9}#TJzTI z7ORk7XHijb$%6t9q>+v`5RYaY$fPZh(#c3bCLn5q-U$QM&;oCxcDxkl*?1>L@zOlM zjb46!#bzkb@C)dPffUgbk_pXS(LPWeJ?G|HQfV2;+H%;DW2vF{oE(*Mi}qoyqvL`c z#Co8k0$4yUG`j@_85A66HVQJ>cgh`28&VeXsh{S{0T~4jESsT}Kpj#7c!utXkAl3Q+h~94lfzUeuE28&&FeQ2ifT@=PGQYu+yBr$p zyf9O;pPMY(+eBBH2Z+UWvY&DQ@}DXLUenu#mGqk-k#w%oD#9wL5kY(3_Fy#*aqWCqU6(2>OaN zA2~^F((fqqm-tOwHRpB;6{WOzGef=OhEyb$^n$>_(kbJTR%rqNB0#cLKuqSA7E$$v zJY1gCDxQ8*j#Ak)Y@8~qW?OsN5)BA?9nnkhH|0LE#Z#ys@p8S;wvSS?+6y9J^~5q} zQ-C^h;JM2T;;{t3NKx{p94p`7qIS_kugxxdnm>*jd(q16r^IJ(%AX}S-wkar9(IWz z*uVmR)a|3&yDh4;J;%3Z}5O1Qh)6ZTZF-3Rhy3?<;LCk5Cy9XXZ21vv4 z@1Ml#Mmb&Chj;SZl1bacqD+pr)iM!|orQiI-DLrXF5ewv|NYMHcITWP_6sw6V$sFg z+gA2Mh*5xzl&IekxLs2wAEJ=>OPo7g2#I&%_rC(z#(e-d=Z6$qHS$lumIPXLJYax7 z$YX<2MqY;YRl~bGOZviga2YEU-tQVdL$i|2bY@`Guko9*_PU3v)-V@@aa@m-S;J?c zPW{Ll9_cKJE*VL2dast<ys>8l%sTL z;9D{3RIcBU&5bU#dNaqz3B{M%7H zQh<@yz>Hb~9azUOsW}D=Cc0!FGRycO-9%&O`G9<>$3)YNR;c71#FUWX*_Wm{KLb>% zR7Fw~gqe@Nc!Xw}Ey<@pS5zb~Yl3=CT}1%gtoamfH>5G%Hrvq7$d2+Af}E z_TNKcsziC*a=i5qdDq%jF1yy&9YAi~ zmZp-)1&o)}p97$^W}d6cRxQO=R|(uCWT{BvYpSwgp+9ngZKO2aRq%!OUI+xRhx$8w1%&8#^+w=G_G<6s5;zW^-qiC|UqZb3bv?g@ z@=cCc_55R0zo+Abf|0(YB_6`leK*{=*nkQ0Y=%xj)RJHI(xQvlBQV;Q&>Il;7>ikt zG}CAkG1?yhSO~~;lf;JZoz0e%!s^g`H?UFa{~KHc(-k?YweW&_x;v09`Pcvr)SpfL zmq&I_M`%!t;{>4+b9kYzweC`Jwq0cdpjYBg<*KZmYuS%y1jJfh%Z!2DV)VQGSr8Ukq$3{Cm*j}RpJcP*hAUO~ zD3!ybw32{JMqFAH7Tjd33->m*GrPGxJD6P(+0URFwJ#=Uvm3COJfd>E`E4@VVNJ!T zHkTO3Q~-qq`-*2x=~`{1($4S}0w|TbF$JV^5yN9RnWAy%%)LBnxkqxH=_JbqrSC0^ za+a$S>`Z4JIzSm`Gq^-!*{35~-X+bntG$LtJ4>LGlT~m&agkiB>m`&`vGd{$9SrVv zupnRNb`!93HX5c!&5uD0jsoQxu?=`LxP8DH_?y`Fg`B4BP`%U9js!wwu19Yo9!7Ip zL_7=6LU7?!&+m*R@F$Yb8;5{T0WvD9Du5WtO1x7Yn%hE@qdKGvCZWDMf+Kxxv(XP> zt<@F)$I+ zx(pJAw=IyonLGU1u6;jXhd|)Hilo?7Tk{DrGWB$f(|Gq%LIT<0kq#y=PMnkzmHc-4 zigplvsSN#uD#~Ou_O-e)Fu+%_f!1*OkO6!LevhS0+E5h+a+u?0c33w%ZPI3xzmKL7 ztFSMAx2?PtQo=2e7H)>rFdNdtEc@lVZ?Z$0upt;*IjpZ582BAvbmqNEmVG>AYb$n& zy^sb7bK~0rG7+g7O&BHq^e+BXBf>4Iwt1Clw(W@}`Sn<3v=Kk4I>EUO9&-qNvTYMR zL9ZL|ECi+~s87`az&^@@6_)uoErC|vW3*JUy7mM8bF}n%?fKE_Ci^gz0ftDUnxQv_ zIz@q=6-hcjSxcys{YDQ#5Atc_UTOoRSEE2n)fG(IU++eSy1$}vQjMt*+S#eYBC-Ks zO2`I4X^@Xhx;n0wL4y#KGa5ms!CD!0q@dSk45*)$7LF&SQ$I?xx;&>j-v;pzVb@^8 zPSgshgiba95c+Q9(^QlLFap5Sz>F*d-pQOsa*qxyDZADDMklG+REN^b)wG#T>YSJ> zr4=zIMxTgA-Tx8sk+B*vAj zWe9YD8SyHT(2UIhlqH5Q<=v4U!mSov1XLZ?;5o~;Uexp>qbU$pw^{^3N z2LPxugku!9UZztaCdX|mQ1PTEsz7}JplI~{=#)r0%SiVbM83};-az>~WjNw}M={rH z6bt{iQK*CH_J0f_>MDb{M)4WNCO}1oiE@%aAy?zMI}0(DWT4!i!gfKeJeZa^sNF+# z>4XHX>hV(1bnR6#p=HE?|3qia-(Y~J>X8w9r^RFumb#&@nq2wNeGr+CA+UvKa?Y6!O&5g)-tG*Lrqm^ zQLdn@bcDB44RVyp@jeFGP4-HmnvmDqv@cu&xPJln-I#@SONC>--mN$YP-2*-0 z)y1fT^mbZo@jsCb&*^xb7AI=7c!2sw7SUnjbynA4VAt*Tx4TJX!c_0{47#@Yc($|A z-?}pizEhkdaM9Erh$B>2M60O0|+Yc0;GxsFcjWZB}Sc;6hfryu<{P~WQ5N-@NVGk2ohlOL zbn}Qr2Yf`L!#*NWIgolBUa5H)P&K?#y0?;Mc9HkYUX!kqRF+Cps;3byOdoo37}aTo z?8K#x7zPd`zc9w5Ah&?mc@y{F2-PT{qPm~e^(lIVg(RIuPHEK`>3*aU!JF}%-h~ar z&T){II;%{#C7wyQT~8!|t%;m~WL-&xl2HUtq1=Vp`f3X#(=(d+p5@tw;dn(eQ6&mr zBe$g*#RQ+I9@Ru09|VxJLOl^pCdZ!kL3qN~hSDI)G+_|Nkge!URDQ~16zqT`z8#(m z6R^s)mJcBVq+zH5l7J zJpvFC_LE?P$?OR3jB58g>3#`n7!tj@=14~(F@Z*NggVVteNLGa;HjpQLk*qL{8VE= zv=dj};P={N@!mFC;7rP1%I zCUNShoDy8A0rA7lej7Kp%BJvO6e^UVYQpBtn6>Uf(Wg}&7=9NpNA>R0%HJdY)+%Ra z%vO^l9k*-AbJeHG@fwyz&W8bM9!&x^^ylT8-1CBYgw}rU( zH@(|hb)E9|BfgE{TpIV5-*UwHlIC#NebM!A|wE!P)Ln$AJT1J+kZOhh*0kN6~RAwxpn&xa}9%^tWnd zp9kFc65L*WM{d;zSJiRqk=yNjN#Ey+q)^7e2zP`wk+MNJonXpN@lJUN}hd#zCAf4icu| z9vsYKo>pTzpuOiRm^iBTWO7t`Vd6Q$#FdZ}CgNVwAa7ea1|*&fQqO@#mThki7<>7| zQjv!s_~?HgbBii0lQ!JH+{PK%We&0_DWak$?|$d$Ms=A&bT&DlG;b`$LDbdwON<@s z%6V@bNG!tf53DKLO6m7XG)BwtU$eoIy$)Ctdwvjk<)~}8W}M4_Q@ll3!K9YLUn=fi z!xP1OCcaC4>$vzwB+nSW7Ntpme@#6yKvCYF_`Vvj!~`A%CypoB=~=wbxtaY|fbEck z|I5e3sYpKD?|wHn_%)jM zkiYmt1jg``QJast1$C1O+u`3=Gdqp>;$`=493qY;d_Cp4)JBzGuvugjz%6D3h=jvi zXNg5Ie3Tq;T)Y&+qh#s0_#lQ4k9ipQrVt*gPxC@ik2bU;?tc)Y9n_r%%hQgEQQdi5 z!tARw{{cXv=6lSdV-WLrg4o)fJG;G1y~>fQbBv77JCBLydthX(-;1L?c+@B(dL7Oq zD;l96d6q@`^V7f#E=dn`qdbbz@L8dPK1gZL{OQHA{3 zFNnM|a=H{ER-KUtn*XhLxM_^KjS+1(!)J9!okvI-XjTPisyKWG7c2a|QT%a6&Kp|u zC-od!y<6JrjYG_kpDh9HipDdtNmTwO8-k}Gn>32%nb;X+Zt_?AfSdF;IV0pLw6S*w zbE(6bD&+slll)#n+Gabd7yVZ@Q2;k2?-?fR$ zhuO$VrT*SH%tiv6`Ws3(nb6eV1;cD4w5h)z9A@*^f8RCCM*dPY9g6wK=)HOz441#V zcfIal;?jTRt|32shvQYhyN6bf!|A?bBI+!5{FCbNBOMCHB^u8I-doPfy$v20TZBUl zlDJ81Ju3%G{=$A%zNBYWIN9GI8CC36S1xYFC41+t-H zF$nHX{QVQRXGfic@!)hKLo{OVKBjJ9W?>=x7`f}L^H-50YE;qV8v*Wykm zZ>C2RLK9&4WsED$F7nRH14eDdh}DS#u@tO^rJ5LF2y;D+M%4fk8TWW0fMn7!bl}B6 zH3E9=JP2s?F>&;~9F?*eZ6Dq|#$`%C&IB ziMiz>o%X`VX83J<4?6Gp&|Xe&8zaV1YZ`%x_(h~#l;ehZIw|t2D3Vc>`_At zlE6y9_8%tXKdhx?c+yIdMr{~2i3cv?P*&_wcQnC3{eO?PsP9~qc?G{uYLiRzbDgH+ zZv;%t%53{k&l|slKT3ZK@O#@zK{(L{<{=ydGgL6l*Q*_MMYL0nOnJelQY$K*oBR%> zWzY2@D!@}kzEe&b@T6DSbCdVge2uc+fKX>38r&dvn=@^y*x{7Tab@VxyFH&Wr<`(1 zx1~PqzVfX|a>+@u{aY~(&k#(0tvdNY)N|j8`&{xk`Sds99hW>n{`a@yS9-qtt%&_B0cZ9^0ek)Qg$(!Yg--&lFfhg_YiJvaX`Evj7#PG}D zH_N^e1KJR{G5K3DsZD-d-uJCI-X^~$JHLCq>JNF6Bo9SHZd6?R^`>rofE@SjrW`(7 zzVqwdPxIF#+4$Y-Gh{wPl0QEpUgG>w`Ckx7{rJ=4Jd^KX?S==L^TTgC<4@1038lqF zW!}MfyeIXQBO<8_&mYz2YtOdR`jxskYO&?iCYI#7a=!CyIWJRw=S5hn&P~UHR#qR; z39|Eoeh_^YU@>Qa7`^+x??~slRN+N?#CZs2V^ov}>*x03{knDF;Wn-D}W9Xr`+X@o{pO zFU5jx{FL%FF4c<17iiq?%7*3jElv-3ZIL@7ePFsNmYAbS(^g7L^yDHrisYr#-VHF8_5vWtG`5T1`KHL3oZ) zNF_A?hKy?N%v1v`5z`25!fZeq^TTaCJ;@H0YL4&Hb19v+LxbkA=$IObpeHm9C+}{i zjXDOMQ+fl^m&>d!2KC!k=Gk3vhn|}}0RtNk)$lr;f0R|zWxYYcsP6H%!J}N6GsS3w zSGjWDEddmZk-i6%ppM!%f0xl#3X6R0pXIMJ+Olz!u*Nt4h`*=(DFL=ZX#Ca4j}P+t z_>WlJi;tH!i@IJsUOFni?!}i$OT-OvJUX}rgDJ-iX~suN^2Opf-n)M%$nFpDv^>IK zYeLJ{Q_J2B?~3C?B_Uek_)NvSsZ_}@5dntjMQEPX=kpPSr(8QMVH$qC(6ijo-bo?M zxDj5R==zSKKSbOtGRhbnJuwGym}Kaz!}ObE0kl%d8UsD}E(o$c11~;Z06_S3qk;~# zH(LV-F{`6B1lzWwJekEmLFXWbT@bu06JHEQ~V-P6x)1P}ZToS_KQ(;Jd%ul_p zg5mB9fxJsdZ^2k8)PfXmf238*h*gDvNAJTiwBPY;E~5nzZ@&2v@H?spe1A*UeXa^$ zinD+lpq%z_T=mn^MYC@{I*3R9&1mrE9&Fck zRch_wcnxXwJ=m}v{yAyY6ghEwh;4hIoOTfDZ!XPAdo#+J`Bt=o%eBg+L(kyPqXDz@ zy}XC>&1J*VWQ^_&j0h)PusFIqmIA>$LUPh*L`_Je^0=rg{YQ+BCej4}p9FB^)*@Tr zJ`9KfC=W(r92W>%DAOH-P}9)PZwe)%v2Rh>fWkNqw`&j5s3J@w=2_?zJQ)Vuc=K#@ zGBb(|t4^`v$TPFuhdd`5d_709J)w5&;XBWwt;Y7Lh;|&&I(A|&EI~O6`u!YfPLxrO znAolwLeKX4k>mXy{*OVb|1TXRqcl29#-6JmX$W{YA7PAjlqSu}Zgb$-G=#Nf+v`Wd zH@~DAC!^B*9?mx`=`{_2I$Dwg(r|^%&N~2L^#I(!0RPqY)sk(;DbL zo~A`P!(I%v-Gz}=53ss+>_CJSp!)&A(I>D-KR^TZ-Eh8L9&6u@UD}9U6&A+djw9fW zqR}@~2g5xb5O9V=-E2mqwax(gq4rJyvs904a5%d78pCYa0Cs!Gb#^Lu9HA61QyqBQtc_*)Zy>J; zD?=r?*l=404Ge%W&q6*(3;9c=F)U2|DbOHJ)Zyw$K~C~pY~t3$j9GQ{E?7IHW+#m z53Q#~3-QHtgU9JboT3qD*=afah-osRY_3+1@)Vtg97QH^ko|`|4fvq}3knjyq{gq{ zr)cmH)j?;j>-{zkKv~)n;B=u25?pdu(#YcvcT$kTVeQB^+6-;S4AiDUW?eGMkthr) zJWDCTFJ?8`hG2~KZSJA!dqIHhSU61Bune<%u5*>5Od`@&<4G5ue*$pzdbiTpH8D<4 z+o*x~JFc4{@csfEBf--F&h2^=+y|V0{RKE%y}-HVD&X9%f%B0Dj<}^Sj~%fawTj5} zef~NZ-QzSLztg6Ub)6y{fme|hU|I>O4w|cd( zs&fkw39OD<*qq8ugY@0oTU?--(5DBtmYQjbz$`o{8Ij7zw4-DjhEd=(Llgf3C0Sl5 zIe_2a`^*s2P%;QaL{N#wR30mjHHkk`c@KjQrx?_a$J~^o53}oa9wcoV=b}heRcm3` z4{=Pj2sUy<3^sT`Pl#iNl99?E495YO%LwF^19`r}4atu&Vrv=?PD@4?GzaQ@pc^`j zOwAKA+yTr*7$oj#7l+b#w6Y(^A;=X^uJ>qoOlNpP?oIn4KIqZGfoKw&@++hiHInQ8 zTWTU&m3PQGp8^7NFUZJJyTpiE;5Tk8s~<5R$8lP)yr}zvz><-vfPT#+f_^MSvoVm# zbH$xz9^U^CTy5hqO-48h&={@B1?ZIIxpyXd(Atj3C(JxH=lg>miX%!hygk;H_EfIA z$|)dTr#Qj_D}nv*0cJn&sN^JZ?CwZ7FsaT%;)0o{#Aa%}Wox}{^6E{UGV5zvPt*&w ztWK9cRcMK($MDb?*L+Ny5!2QJBvCm9F?R^gvx~)P+~h~ltD0DCKOQ{$3AEWhM~6_C z*2@Zy+lb~T74-?(G-r_*K{KEya)?L!@#|$L){?8?VXJy1g(hH+KB`C&)t?VY1#^MN zF2d2Qk>-EVAK`MG*XUGIE$GiWdMDyrW5(@msj|I-MqABnL4c?g`|<=M zjojqehEb1Rj~m!PtfZD10jWB=NO82k_i}Ld=T9j5oRU=6A*b^%ec%6#>4B$b&{9x2 zU4lWiEK@r==gR;GW9|+{d_1%hBUU| zod7Di5}M?{tQ!6F@I`0W{(&04>u1dggxxsL=-?1$))6Xv7;uRh)f%>YwoNY#)hevO=sjn(tlDV%NCRj?IICSY*9i3@ z!m*+a>>Ad6Hguc|w5;0&0YbfV_)Sx$)07X*Tn&I*Yp(`?<0=5m`V#LMTAJXc5Z7BFs!V5%%tk>Wpqfq~fyz{9yv;yr8iuy|Di96+6Nq|xLGW7%-=7CoAvd0BDNEk1|hw$WCqY-I2A#!6?GCZD230snjaTLX} z2!jOu9)S-zyZYFwUuB1ya9ha_oSTi9Uh-(FdHXx^IMS&c2@fPRB#ZS!AS{%72@8=B z7QC--iBgXeML8Y>73@dkr|PvLVc~OT-;Sn8<{-y=HJaXw+gsEwOJZzgbn_g94?0nl zeg@147n0F|9{m=V_JcgRQlP37Hv=snife}Q%=rdP4Pl9b!T!+ zMHAF*mkAvribxp7``_-&m2IPY^Chi_=%=XDUMOjY!72ganNZLV8V>ZZH6n6aLLf84 zQ5S{_=ol`XQ-hds;T+uvLgS=OdjXMzCrnViZ(}XmYA&|6Z4UEGh@}EJ$6)>@fNd7NL>dxx(je;SA_|E*6emvc;;G{04F1odPoo*?E5V`-v;jxc zQ6zpHv#0~@V%<6Z#dZ1P7rnHUVu}rCq&;F?Ca)Yj3x|OTkYco;$wmhakYA~DNDvV0 zH2@%Bo&unO0Fd+xRkwi5r0Nx-FpKw8+A004)K2Mdfg#~T^Cny@V~a{;whI#hH*TsS z1oqMJ0b8Cq{ycCp*n^W?fI?lTK|~{v7T|Xt#559ysM|dJ{R~iy=$?e3KnO^!{U*$? z2LrYsNJ*dE>XD47vty72TXErkGa|GIVRXaI{++mCb^XqzbmW{6X^6mOK{I8G5nf#N zQW&J`WMCCjExhm0_Nus}vV7r7OYN}7Qq{HCKk`U5MH9wpZ25SosD_2A?o%sXw7>`) zE1J;2AiaU|Nss2&;DSr4yatuiw93?fDk?WG&?;vQM`f2-IGp$G=DXlpKM~Il=P9>e z4dbc6cqiVX%|;T^tMOaC4W}P-uvf$4a1!f}# zUCVD*9{U7zs@=cSI0WovW*7T*v__#KI0xz=q3PIyVIKA}1)tXPFj|~>=#@Sa%e$Su zZ7@cu$-y2jRwaV9bvD7~0DMMMS(P+f6-}?!7!e6n#eUq zkgiRbj*xIES==A)=yqbau3zWpXkvv?9_C^{8-aIp)6Virw zBQ3a>hbN;E;>mRL>QxYN1s-PO6qYxe`iF*)=C=dH*^&Gy|Bd))+J({Lvnf1D@z7C} z#z`@AAHypM_LXY(xQME7E>Y!BFXIBYYp@!zN;e_xOE7BERPha%@a~|A*>E1ri)Y=G za@?emLbut|4N3^F1<%ykA+f?oU8?yw{SxnC#w;ay0?08WTwP~$%0AX{A2nP&B1_-8Rp9pYw4J~w#0=gf zgEiXdbso1Vmu>|1>}*d_Aa$;GN@9rB^)_{it+zraGMJ)W#^*%`hdv@Y_;WJ&1sz>M2K{4IGEjaNALZ~@luc*@EU-3Vn92fc z4Y$U7Sm4$UnZWQ{wiB{|dd_J1Wp{L%5qJMcIS@iGkk)Keh2A)I(dgKt#q&KD{S7Eg)0r>2kKq%;eK)qhi+ji58lTDN zF1QWK6G=)z9;qM?X-fejP58OV%ryePH8V$TS|mc@AQcqBMrRCWt|kyF@sA0(PjQIX zu-*sSNN=EFW#~idFn!jh!Sso+w^4N@^>~Y0WI~&d#uLz(y5vY`*Z4yvhNZ53x@Ha= zYps|%mPdzOv5yvvgkBnsUjJ$zy#^3!`)F;>n4TT`DAxDhRywU4mHgKaM&?7_Wm6+D{v7`AG-_U~YZ!ehw^u z`bqchEtlNUQ0^SRK*JVj3^n;mum~JL#N6Y#tHmd z=@~J00`Dt5DHcv>U!5I=lEi@t2$cATXqmtVUeQFLNXz3r15ac8w8CG{6_fIKzSXnD zI~r-;kGaMbJKNjb(;G1{=dqS^0VmZFxqhgNj|PDk>!u4)sldj5CXYYZGrI?y{u+q( z@Tp|7)245NXKfGOWB%D&JT{Tvn6LtE*W(D~zT*ueWJq?T>X5`&gpGs@-LLyy&ts)g zW)zdltUD#>IFa?t68|1JB18rf1ofg253ui;9Dkq7EKj3+EA|S?GX#m-Zr~3{S>pQ} zc=VKXVD?@ZWou+eQ8>j0+sTS(q(R%PH7x9d(@^yzanRG^4q|oZ%WzCKpkyR9Gv1F4 zy9f2kQLh=dz`=5{;u_QwXKvv!p*N#Lv_xL;S~j>r+&zg8j+yA4II>}6HBOfAg56id zPDZqS{Uls*o{1u8$u%DGS-DKTK|U(8TDIjeOZhlvDd|=+f?T;RL#&oHw;?TE+N0VU z0GSSDlZJawko1(vJWNtV;bfi}))lQEL+jP>mec@tQ8Ss}KFD`|+g9en5Rd~eL$=+` zakb}%9doG~!v;;^v9V_nuW~#By5KX+a$+E>8_gh_!>hgY-TL`^G<>{ z0tF~qXL)zrO9eq1ml-wC8F$UnBPyryDfo1O4-m_^v$?1EJ)fs{|KS5KD1g|OWw{-N>`7i&2YKLnB>-6@;~h#R3}wu3U(R#gWz_v*^@Hl>?yW_T zN3Hmnmw`uDl>5`&5cMMqMAHmtJnG~PN@}0H6F+H_HwGi6$qR^2{|cvU^~r+*;cE1{ zP|OZKQa;yecfd$VM}5gqNmfZWG@kh|R0c{`OAze0*CTxn(kpNSTCo(p`5j0cd1L6*_NGj2Y}F+E%!(9%}pTdw$WJI z=-@f6gH*B|po8tA&nzBqdJ@S*m%pG``zADH7EegM462M~C6CiqLS(TC&RKU~L~vqd zA&@QocQ|KB7ZO`%@tDZ7Sd)Q3Ij$3LWw;0142@~6$ezukXK$H5KTD~=QN>=k8B1YH z?8sISde{KPifo%MSGG<=)D@C|PJH7)dXlCa~ zL9GdW#PHcXPT4YlL6-8Bv}8N3)OWkN{VufUMpPAnqhR*ef+A)}#@2VQWzz#8@>AOQ z$nvUV-Pmv6raw`oSQmm=XniDB1SQj~)%K1~=1_dif-lo9>-0(p1ef;2N<<(9p0Y2D41M_D3J=PZC@> zd)d_ZNNI@yV&)5&+u{Qz&$r!H6fM`k?dCy9uk;)ZA&DFldJIN1{;T^QH?l4HPz@dUE??_*+>KB~X(e0o={*te z&F*cF8#eC!uOY2RMT@fK@%h|XftXGQ%eKN=A=#<`^d-y+nX@-zkKB)SS%Vt{uy3vy z!kE%Nx=Iv8e5uP24x=c-_uS7h$D$=Dcn_-AHlt6xksEZ9i^q`J+FHu1#c2W>#3p%I)sMVMh zw}ROOP;0z9{9+CqogR2AZA%Wch-a`T$=0FhHmmi1+3V4)99S19G28(K+^Qjrs zq;A&6Aev|LPII2G&AHlDNwO`O6jQW7bN<5*KJ$1MvY9XzLPpeP@i1NHKmwr{R>-fN zTJDVxSS3%LwRXk_8X&LV75E@#39K*I$4~EAANPocLf*FrUHC>YU8GwbK#%9?iTAU| zg*=y=rCH*dxqP%VK`fk$-7Oo9(C)Trq}T5D#9TgIp7yi&buOF=6Mn||x_RBx@v&V~ z`2+c%OABKmGDSFYk=}&#(s98<=$*=p($fa`t7*gWzA1{SzafK~b!RL&aEJWdp$O0k z;Xz7olwJb{NuE^_R?@IdHAf?u7u(YTeAnbWu)G;mdieJ!8|11pvqMvCTku>tI>ojX z&#iq^Y){}B(=){;@VuCwVtW#o(!>ICrJOHm0K+!o;BZKJusx36 zE-Op6W51=Ll%jIt?I~)6fB~8D&&f-gyz@#@R0-@n4|HUxOM}ixbMraaCcxEAYryH_ zF@V&FHC256y;<`U*woSU@j*`P-)r$H(vKI+S5LxPaRQe5qk!{dhWkvE#n`01J380L z){CIOAC-THf{gj3yB1XX8;{X~T~gW`AoJtcrpQ1}4blZ~o`!om)LRqPPGT`wJw3)j z;SZiN(GI%zq%l_?Im76%1x*0q_)Z6X^_`}Jre&`TiNWcfo(=7i8rqG~i~75}B#1qK z<0CZZg2yXN;S^MaPSynN>zMZhmhgoxQ_-^#l9RXC?R$5e393WR_-SAL?s$j4p##Ni4pT z$6SYG<{nzNe#B?Sni@@tTuQ zI_6|24!J)8rXwgqh)1{9Lrw`|gmM{;yF%MB?%vOWzWjxD<0x9CtpVkh@ z)7+gPKNX((Tp^5DFx;ZvF~7(ZKNs^UN;8yB>MHRPRy9&}#Zx7hFH&q|E+KMp&Uvq9 zSz`yzedlq47PBZB&<*C8%-%*APl!@SLN4--zf$MN6W^$)fv9w9wGg~&2&63UCHhQ# zM~A+XY=W(vY=?yM?)8w80RRDEcn;y8i3kcn9+}Gt5b`4%$dYqe3k-nCoazPDE0Dwt zFifFh9#!5s#+4U2P8B4KkX|5AIHJ(NjrgNQ6b0A*FxBQR*%<)1v=@lQoe7v6N0in< zJnBWFjPj_zQ-S2XY<0Y|X!W)Bg4IutC|Laz{ zV_fP;KZWiH?x%-$Y?4=B^ElpJBH0RY$m4*Ru!v6_>1nEC34DO2baQ7x3c{LHE*$B& z*9?dG67q1^3Wick~f2UQ7e>rWTsygZny;ZxZi5f;v=A|MOm~ly; zl@z(AYA{C6P~N+fxJ#@_~-&{r@Wx0{VpRO@QAarPaM*=i`*xFVTCuJp;I zr?4*Jg9hm~tnsj6!T)6=JJyYntE-4uF9J@oGu#}SlQkb-R~rw>Ra7tGu_2|=Rruf{ zaYY=`eMfw>1h>kpeMbZ?<+Fpm`*{8KrF^RtPf5Pa1^nQkz6;R~a>XvxU97qXUY(^F zf-gNUe5dn~Wwk9Wnww}@XLhIm=s*?G^c>XF!JFc>yHT3&dKiz53uvCuF3e2vs!SEU zXNum(`{eu5zeu>3CnT`Mf;e^dKv2yAIhTD~QA;W9rDk5e6d6pmNsxOF3NSGT(QVB^G&*M+RY(kJcnDbp9P#+1FJ=2M?((hgvs47t6Hz68dJXTEl z!lVSU9`E^{u#sy&3uW$V22%pSdnokI*z!0%O@HdxKl66SOi)^**ESTNpjPeZ%braLHH3q^DnOm#Na1b7Vp&4bRVVB( z8@O8iuR2eq?-X)_wT`BYrb)@c;XHkw9@pk+7ck&GPt*UeDZ!{{L<|EV>|m62-dL*i z!H_Gor&GJVPOOaKUBxYb=fUIo+wI%88XSoI|6p30=ime_H9EzsyUSA_lbrFvvQzm( zw(pl!gG447y7xow5Ve2jV@5Q-1;trA*8+!z>)zG)#veG0ehI*3jMa@;GIc>C?2x33 zCvkp-F0@f^qf)-X)iER{5Mho0M(8;XFw%}#mDzdE_FmFziwJJ?hM(k>RP9P z6M$L-t)QR>u4+Y_-t?9T0!4cYu1@e=!SesxU@sNO2uG+7AxC>ngW9HsTpg(K5JJ`I zi@`19Zx86aYz$tN)n$Z`7w=T7e^0d2fktR`8@ds4MSdU?juQM%Qn> zH7gK*!RY7))sW4WzACM&>W}w@cvsNyF1#yHx8|mAtV%+}P%t{A^b%}>X&NAj03`J- zaoaz5O1t7k((pfB9mA)0@1b_W9VV7`=XTto-K}qR)Ft?@APybxT3sS;5Cg9H4zaq{ zgKoX4VGSDl9~)5XukxwC0`;%DAtLryrBG7O!XWEq2YI|<1|n54e??H6O>c@(t9VB2$u~Qu`UkJyH0_(|a*oPX z+%JVDm=u%L-c~yTpIX6hr$=5Mv!UjX`#(?hW4m#l(J}Q+@y06N<9Z2uXgBPkMUcgH zji(5T2RV33kk?PbC;lYn>IXs(>cU(f|KZ+Ml!(JxtLE%4hVv(ARq*~7-R@y$AcKi1 z(L6@#BL+XfC*SU?eprA+vw|PLz8IK29*DyfnP6q z$Za}gHt*$fi_av0#A^u{$pmzwV^xy{AS4)nk4T*lcW^Tf zZ#2Wt+ysd<6>~TmN@El3&E-HD3_>m}++F2(Z^C;C=B&3ET*Ax3bd1o`&E-R4O1a!i z0V6rj{T#S^0=^%q^+Xx7&=g@JIIN@QEya1H0P@NXj)x zn*hle_qs2&;C&lhy-y5zvg!#iwpX$1UBXU6c?D6Ms;FLJ^u{XsP|w6S)Vn%{mM~{# zKO(HrJhpWQ2+0NKWGcrY9RMCLMYlT9c>*l=pVP<1d4y0(d89(EQtQ-W0a~OU3ef|# zJQyuo190V80B&=E*XA5B6b;J6-D>o?7ZWwujB@l5C?h%=4azUU2aYK%uxn119V2@I zqv{WKJsNCzBfQ1l-s80GNQx z2EYgF5Z;A@Kh>BA@(VX$eU9c4tvd)KzyfuyVv#TgAn67`9bj6LZ7Z)s#LGB1wa1E^ zSMzW`+L1(M8Bdey#2aNi&QPsK%rutqv5Dvov#W;qmP7p6tcpMSojp;Gy>E$e5AsPp zHh=B;z5sOr6Q+w}Qc2yKIaIv#AWuovl{N}I$WRrw(yDV{^Mn^8CQ(O)xcnfG4YXpQ z6csYPP9#0VhY!$m2?>7(qKMxd$86GWycVRTBZqn%UMJQ*#M9MX*q1*;y|o)8!N=r}B@LXjd{OW=RL zE1Ml!Cq;g|e$|-IcXnanJG)r_+X&P8FTCr=1znGgK-$aJuG>Z^h%hR}%x-I7zx|B% zav}Q^NXJH4rEMb$q@&0mZMRA=AxYok_b5Bq{voUM)Cfh&?By)z`rQbnD|1<;tt0lz zL9M5Fu!99UMbasHHqqA7t0s`@V)Ek?I_-fZkW_7fb^29bm|KTbxP&DJ8kgk zl&%2vZl5~!X(#$Hb@~FJ*6sBqKqflHq;i~WAZG4+DP$VM_uT#HtfTBG#yU>bxS0%c zUjPnwJ>KVl{3#Y@4hw26gcZ0S%&J8C1(Bsy#l$c0n@G1Xazm9Jkr~IaJl25Bo4Mg* zvt+gOLm!B|P>M^jNkB%nk*ti^_?HtwV&r9+3%btPLp02Wl|YE}9wp4BW)dvD)AnMJ ziC80g*+S$KdHnU^OR;DTH^&>X3B`lKbq7$y5eyi78q!81EmJBNuj4x8ZdU9SRH!g| z1NMqYN6;Q|Y7OtvWiWufQ5e_qc;ltl=`v(oDI*52A4v%tX0?P4wpzk^D34!bVc|DOT`NK&tt&n= z*3UlEYx%4HlENx}Lo27z%D}joA;I0zVlS)ZvsGc!+>%s$`rXPN1EtWQ(}P*~0GSO9 z3%9Na3#^|V_CVOQuu;;qso4W7ScdZWV3}1UfrJM8TP;&#V}^{DrQ-0~Z3#U->%yiU z8_AXqltY6`!4xL_u`Pc9t6ut@0|8|?oPZJVtuqM>zR43ZtEvcNBnq=GlR!RN@;;SSpUM0Wu z{gV9btLN9wTb^V~Y$(aM)QNE$`H%p7liO@4L%z;^Gk#xNGO{rle`S67-7ldmy?9t~PqS1~SG+K`+gvFysGoIPK31?&+z+4ZHCpDo)?n4Kk@MkT zi%(AgV}tj_LE*Kpfeq*YMB^9??W^_q&dmM$5-NfJ}z$A{VydI)fBgah%KT7%Kv> z2+4EJ0(Po#Eat+i*1Be3=NQ&t!X&T^uxPLO97ywBJMXSJya!O()d%9~QhNJa+l3#Zq_$Lfmbi zfNoEt?iu{q1~XjTT=KXWx|w&I6XXarS+gEvF`1Nyqqq(dm=>cws<#e2a*h<-I`Ai! zm52pG2phC2Y)hEjwc;RFC$$-lw!+eJ?i4G`Dj71XrG!j^tB~3d+c)#*g@uvUtaui? zG{IClJCub64F*pR&52(gHk{eEN#UyMq&M9aO@E3xp{92N)DSdZi{_?CVVSj3YUX16 zrr{EJVYkI#p|glEIoy0&3WFNQOiM(f;HLhC@ymB&(QcDM)YgAOYro>}7yQvdB3uY& z#(ivN>gBj76mS<40KdTj(g=eLQQ{HF7!)~e(3ZM%tK~Jhe#LJ8`W0?Dq&N|L>?K6W zy^rq*K7xsTf6AaOkFemNllM#0{>j*iJ6VwW`vX4~UOk9eUNo>3F9fp{|MX)kXyf}3 zYVmt%8DOQ@F&D6Znf z=6V(2ATxY?CIUtWz>0UPPX{M~=)?dZ2Sa3Np~pJ+f~po&63{u927i_w8!Mo zil4etg)W#ai}^>1b^96?Klm~59%;V7{lK}nneMy_RjeCMgJh3`M5&$JK~_r+t6z}} zS>QC%sIAjo>R05jsGywtrHIqO>giQd1ksJ+T>u+H_`AS@-}~28ka)TT^99*p#oZWz z0xXqb&wkL)YPlV|35|@V1Yc7O{{cXq08q!Iz+!46=vQb^Si3)_vY{tID=nb015?tr zl!IPQfzAx8q-o~C%(4LNFep`GEB2$2pSZ!CM;Tq%ivC8nq8~=zjEeiGq;6?JB_k@x zC<}CkhoX!h%5apq0S@IJV14i^)CStdy-iPcKn+H#ZNy0i_G!b&W_+*Ph;Mrn6VX2> zc?oSdas|O*^O)1)3TLgBl5G4j<_%G)k)L+Lnh5g zkr&;V)ML`j?D`S;Nj)cBA8D<-C&hn}%RegQtbdP?VVNO|mS%)3a^^%YIu{kVX!rAB zp-%t6MfrGc>=iO8DmiMv?r#z&9ZrfGkdNo*NMDBMM#{&tIGp{q{JZo;v%VX)=u7WeK0H69TXMGn`AOXd48=$;Bt;L{hz6!7#$V3Q zj=TIyQiPh9FR`{6P3&@B6XqQsOg8_m=axLg2$PPT(=g}$+@?AA=R6x0I!3at8r#LX zY94;);LAD>;yDk`=kRD*@3 z`ozsOCdK8XCdWOP+9&RzekpNX41MBu^h=7fv#huise|H@3`uci{gUIjAvx~Ze!b&* z8+yl0Xoz1v0r?Y};+M~-C-}x1dV+7{VSj}3^IHQ#*J@;3Zb^b$G>-~ug*enYpl44K z;B>()M+(vfx8jc=66s=(NeXLO2ihjhb)4IQZOxI zi>wUU(uDKW3-Eq{N8{=_lY^Mg*6#*pCgA>Slg=KAv+c)@1=eW04x7&};CkS07RXsE zsElEiaZ5SA;6U6j7~C%i+>gFgb~Ry=L?+T?a3m~!;-9pEsQ9`Ve7ekOg2AXIIe+2L zW!ARVep461c5CkZHMdSu`27RgrS!xfOY*I+b++P?z4Br*LTYjS!nw)*I4cu?voiRG zrYdxIfza)Tdr9aTT?SL8?0|;kC47@>H_D-gUUR0<>aS}AOL=_?+xR-!xO!UY^R`Qx zd3ld!T=uz}(vmyUYLK>z(&9VP%8|CA3)1kRSiNpv;D$PaMv34oXJ#gJ=KT=74Gj>o zp}!cQzogyT-6Lfqc-~B%4eKZ*Mt{R2hfr@rI}$65P}K}j)pYTkDpK!=Wzt(0k9~uX zFQhd>bRetT#bi2eqFUx~)WmZGHR+*Y=X*`1oBY+C{Dagz?!dge7|4#g7 zxZ#>?GWwGg(x8}PgkHk&0°3 z`vV2~-a9QGg(;LqRtwThjkTY}OaY)y&OGtmc7B&35L!^bd*h~wDLW8GN8+yjXXsy2 zX8^E9%m@%!f!%6F8jzm`Wqu7rBO{b|{hel$%qqq-tA$--wIpB?G)tQrk3>}A{Z4&Q z`{N-oQ~UkUeo+^zqVL($AXW`6LI>JDJq-(fNg=pa5jvQU4oG@I%yF@`eoYVBpIc#O zBrViPOel=mif@Jf|MHxyg$;AE)}!nV4e@*KI)ryU?9XOOa zYW+I|Ivj3r zK@D;>BW%RbMIuETS1w>xq@u#LV7f&RxaLD5ydP4Zj?WRu!-3Ex4+dHPQGhcqE)q+6 zLJ)t1*~j~JSG9G$jr$-8eiUf6d>n$+hI${#K^50)EAIe+1M~6NjL;smj_FDloVjY~ z$)?k?oQP#f2Bp?;>}m$$z%Wy5TdI^7x~$zWf`Feg?pQMfqcr zsdypy!$g!P1(&w48z7+Xm4b?|fnvK7X`R{+VMBjL`?Q%CE2y+k3J%(d4*r!ke9IX$ z{3{v`flZ1UCdTsu%4|bppQ5oMH1;!qJp*7X(RsXVDt4gEi|CNb>;w^zf_5t0YH5um zEP&6*Arrx*g64E#gBgxHrBXd$pc-aQg~+wR#HQ~L>>y#HocM4YF$zU`NJqLMlnvXT zWVIYf@sRZ#$yj^}Q?ma9a|Nv@1IV4GazCb$&KZJUEECY#e0ZQvp-ltyYM4f+_Jg71 zE(|#6K!2rTAqp-+!Ix0*m=vR;a*c*c_ztG8#mK0mg&2JrMn(WN+KLDNkqYNV2m?3**C9wEZS2q2l;TY8@ z545T*%#6k65S)91$uAFFgfKD(7?A?l^iu<^b-x8!?M?6y<$=pkex5%Y7AQrU^9;@m zO8~Qx124A~UL&}($Pi5RN8_Wa^P1h$X;&nUQVzyp6!snb+5ls&$qbSZqrc;QQXz9s z|42iC9n9hrAb{#`!}dT(@Nmm`vsnDJjO({?y9KTKA`r!V5QPCO!k{WkMl;3u8DJMQ z&Z2ZH0AnWm1IC_d*l-T)ORGqIKefV`jl8iPyD5C%<{we7)5haB)P@5?XUJq&I;b@N z-B(qUA#F?w*%T{t)(vhi&@i?%|ILm9?fI(Bap(|RVQy*utACcib%?DL`7iugeto*F zVN_}UGsyR_GQ@`YTKn-OggW>|AOfl(8^emyt#$jc3(!{dkW2e46@C+ul;RyxRA$Qa zJ*HCihsPg7xId@ec1W1+)StNZSsp4cbcsdJ@?*xZ8 ze_xY`12cUvbG;1H(!iT0^jiGtTCBneApEshi7;C_=0oh0AQuHf+@2VoZ7Il$%(fJR zM2bNo3t-oTnp+2je^+2bTE)cf_$W@V&iQ%B=g2o8-pXWVI`hG-Da#9#$OX@`RJ_Kb{KhF)FHhJpd zisD19b!)gYBPa}}Vc^~ju9pU`M<~G3A*SOfh6O)3yI;k6@EJmRJNjpNp}!aI2-4AC z%9hk)Zvgsnhldybp%0slLs=c6ip06`m_y=rBqourYz21>;p2ZC|G#USowKorpsyr9}&zX~iGc!p@SVIy|W)hanWDx>F zB5EdyQeXgOu`caT!g9Y&GGI$wjasMPv;_oPGKklWHq(-8kZM6%Yc8#~ z?X@**ngs-E)kLBBeV#Kj5OKM^z4wn~&hnmjdEWPV-e-R=Z8ECwSHig@X=ox6N~s$w&h1e)&=8??2WaFYL~%T-jStv2svi?3OqadK9%*72p0m z2IbJ#ey;gOJo&*uC>I@*CTb%F*PU0fGSvPH&hsqZsU^8SfWslXc1!hTyXI9~7M|Bz z@bU@{#=anHgl^cWO-T+?iF_XZcov(tl#H5;;Cii5&AQkt35arsOF7100!g$PI%+WgD}1%&P+` z$b{a-Y09b>S&YJseh5&zwfrzi4W^A}icd}U^>=-1?L(67M3@!Xz6AkxZ&RAy!T-Yi zw~E_JpLQ=U9e{s$25i_`<}2Hcsv+{1&b>6;gBuNRSXZiY9>)JefzQ}=ZV_s$ab|!)J~l!VMOgjgp^mbPWLWQ9?7`0 zqG41t%D3iaD*RQf!gzfzQ|H_KeO{d>QChUUOyzI$x0eP!Yh)=j{8{h10`(C)tW`H7 zUX3y%f2bZ*5|yIYF&sUT#F}{z_6^8n0F@l4gm6Zoxc=T(Oc~wx!%9W=kL+e~WB`Lt^>94GiZA`Y_Zqopuu$x^Gf%FFH-xzsprq?|ny0_Acoc=4=!UWTy8%R%1WVSj>vq zMek)nbTjfE-WS|5qPaTJ*S13ZpVNJjfa;5!`i2rYIZf$5g#*$_7Q!~(!&V#Pn9pq_ zvw4bgSV}v#RWw}n)Ho%wd%n`KMODuJ8VHx06@}KsZ@y(pa}bI_0AyS5G++OzZ}=kj zrz?>lzNgaD+4G~EhI(#b(F@wBK3zj$lc=upGwGtycdWW>vMh+%P^H-xRl2w^0(8VP zy|%xFMd2#HXh@ejOw65ONfP$~$S*!F-m2&txQP{L9|Fmn=8Je)Wj^c{Vj5Ba?`-C? z9NO%Y&Ym1t)Z_P|Ld!LJUO^aPJ)CpcgS7}7uE%Dy^+HyACMf+PD)*pJ=*i`meOu}! zCfr2LndAM4PGD~$qXpYtfvw24X6?h#C<3;vJOzi5T%+{gB+{Th(m8=8{@&WdHY!9j z;Vt3$H(`f%uD5k;H3ane=)7gxMutbKzW#6GVkjEk7R>r~6u4VQ`Py`s%V;NS^Dk_s zLc&q}yGAJyDLnG;1AA1D$7pAf$s8V8rnKcF!FJJGQFV23Jk=JCsS^FzNY(D>V@;?- zqh&k621%~crDcWh(KvsL5WiCx-G*Zc{zj5AzZ>_~8ZaP#q#l$3>nz5d=2gn`Hm9#m z(^%=HdB)gMmryP%ksw>%Sye5W><@5((BwYtooE(gVDFyhx;P7v}+7H zCVozCqJ6Q?6p-v> zK`B|jwj;};BN??&X_Ar60xNO>oosuu<=NM5USNY;jc<3mSXlWiEI8B)3rn0IEQk#8 zwaJvqNQFD;>KoV-1{xmLmu!tl9=kdP{{<{^7PfSxYnjBS>fWEiE5$#~|6pLx5BM-b zZ~Hx##u|51I9V;%=v=I{<>mO=su@w>a?{JbJ;rsOvBq-vHkrl(*2+$P zdodR;Vi#)jx$=zrV%J-_9>=veSIC?cD09vC6(WjlXj_0iI< zGAgm`XrO3)DO7N@uPq-el5=F_eFc>9XkE=-p^#!dJW`jxSIXonLNaS>_KJDYRhz%p zg1~zNd){N-h4tx84jIpCUNa7|C|YJ(5OY)J)1LczK9A{XFN17nc#In%!#;Ph@uV%+ z7@D7N)W@Eua6JyjvD#f|oMOu2b-j4mQ}d2p_HXkBwWWod=7(N+Rx@lH=ZAXekP$Du z4(??;eAS@B;XCJtN}kiM{M1gzD_=5SavMsdQgkrwGTcnEjy5vD$%9@u z#ybH_S=YdxO$_c2(f zcD#{mxZjvyeBq68#&xnZ{#;XH)+ZWg>T35cg|5i6>i~Z) zYv9MMml^ta-j6qicqbTd*Ln8ZS#w1=OMQj1X=#PV8NNNK72r!T!NASUnPOMw&xX|R zQk{M_x35=23QlUt{<%=*bnkfMt^D!EU(LFednb8I3{itnXwuobqP;5HJ6^Y|mND-q zab*BY2h%lK3!yif+MNv*_jg663G=lZiXa`q-s z=gYi1OBs?3wIxyJ<^0LU4ECe9cs{#AX=*@=iup*6AD>{%p+&V9_!@&R2# zAX>>08gYY>ZaVCy0XHb@bowIskOTJO{@{3Lmaqjm=e1S(Gn+GK9xN!8%~ANsLyTN@ z>O>_6(#`xzL-Ifx-UAhdoJYFZ^nM>YwTEU$CQo}&vD9wQ}mT&3Xj3{{`X0$BFbUd zD1nut7knyQQFVsij%c2XqejE?ZMecujGPAJBPYd&HF6oTjQoEx>Str4?k)H^N-cHe z2iVTuzex+3Ki4LWxa+T^2A|jy#>Fr zB-!`^41FyF`Bp&j1fZFT(})aRhF8P2fI?G~{Be*8cm#~zPaooi5xzpYmCqYt@yAD4 z@xLCT6(ubi%WVC9`e)%s_AfNooL`;2xPoM|1Qt<-#>(zVk4G>k!%?(Gj|%*>CG{5! zBm%FfGV>?Y_>U75*#PPr zU$V=vy{`>b5)x7?&bfzyz%L8g?(0?L`SMRo9&w0l>A~&Bq~v; z&*Zg-Xxf^6xxp?ZG9pD*y_>6%bL+9pu3I&a5c@u2n3O+Oakddz1#P4J?=7%-I=#@- zVaj>0Tk#;(_m`t~0Pmh}Tstz$28$OptmSy`4@=Bi)Wsuy^rSyovxk!Zgq>&b&}CJ` zyb$&`oEvucl_NjtEzT;L?~B`r?b)u+K1) zt$C51SS(_u0?RI>E6eF@J}}-FsU2F;DvFevDy0kqc%Vc8yIJ(%I zyN6s>VrNkgcX^so$b~y6aG*W%2&TK|)zx>miqFDMn=ewK=}y@i@8u9M3A<9TPrp)G zdG6@D9D;oeW7u)_&lB6lm@WI~Xzu{Fh3ozXq~S}@9Y&6n``UyT@%_DAojQ;!y6Z9Cu8#($ zn4)YEb*?xh3GqMhb)`u==u1&Jo;rY%r3@uYwM{u+17nLO zujw002{+L6UO&O42v(7!Y$A%1>9l4AP98Nc8Nl@32GqO4`OEAH*V2>aJ8vCnmUI0q zrhg{O;0r8=87=3&%6TXIqioAXcN($7h$8AJKrZm2;ZPF%T_~Yy@b>9KgO$(jp{ogg zJ377Y?Hp2}`X1uQdp2Fw8(TPRwCpCpnM{ZCyK$GvMz4Fvjo(|a=*B%?|HWgEEogo$ z^7T&MM|BUQ!`oX1LW_qgt9A}YBZ9Q@^z7ZGO^p}>X4T$Zs-qBA)STD5;M?;@V-R3P zG>%5WD{2+S=uI>qI)ux_3T!xDl#sLeMRDw(iDklzMRP9ii_oq+2VG=~Nc+Hm!v(n2jcyqVt>R^_^L4t1ZRZcOIS?V?`in&+DX=a(EV z;Mz~8PMN%1$xBj9l910 z;&AqVsAJT>nYvBsanP#Vw(vr)F6oqv;6lenMmr{*cCN84l+FmKr9%QKk?jRiHJqg) zQ^z?g7pAU|247+7{1+i*UI0}g6@MI5zW`KA5BsB)TkoXNIhR1HU<{V2Pe3aA?H0}6 z3z#iP^*})!g!W=Kk9IIYI*6xlW6D1UvXjj5$2w>~oEe9hEUw$>ToIi+#OOp(Ak!FR zj%97F5NJ_erc@v%Ys`X}3CQNsBUZOp7E`%8G7!M!sg7qdkG)`hx90Q)9atKv$WKL5 z;laAP(f|z=#Mg^mNtZ@8Qn4)J8JB*qfBN_4g$h`y7b|$a*~2P5Sm!Oh;*yH|NuOTP zg?d<67wfSt92*@RMkQZ=U4rtw45A=5h*#=rO=}eX*eD8E1M=}EM&VfVi{{zP|0{K# zQW5?IGP~G)q{6|FIV3jN&w~tZTNgUS6v&{ufvVK!wcRR)T)S9{!xm8?h3Xtaf(mgC zjL-FxfLRBhllgc>t+!P4JG^&pp@JY*4RM)z9WR6~h_q#U)AT^^9|jg#?oNeqcPDoD zr(^nsrz?MVjqLtUFFRS@q`ud%;P*Spnz0@S$M#_f92l}wOEAkJ%SR#0vSl3+(p*SK z(H-YQin}1s`7A6U%U8j&2x-0>axG*T$;%?qLYf&AENKF^yv*P??=>GL(d_&Ykmiq$ zDNWt%>z(`xN$$b?F5><)=|-xus&QnLEI&BAEl!s2{1{o5L=E}~&<8NqjEUkmc6W;! zt^mhZKvU{i>AxX)>^$y;A_}>^T}uuBhN)dC~FK z3n(D?F2n^7M*jf{Iw@EXU_GcKgIjEl-rg8_-o=^_q9YxfIW*d_+u4BTu>sYLigr+@ zSTM{_hXPPki!{^5{j?#N^lLgRZHXr&q4`n#b*_2JqSuG$T`z@qQP}Ds9|Q-Lnair* zO~otOcm&6#BI%$->th`ja@{njqq-y7(E}XMAe-CZ4w}*n0g?3dday!3B@j6k>+Nsp zExw)>4Hs~Kmj-(;bjY?)I{a%oSpYcWo6#=H2+6jH5S@!dQpon&K^>c!*k@XE`xJZk z1MJ-gpyATH_!e9c1EEE-KL)}&3xq`i!V8@d2rfN*2(-Hh!6@+>T&4&z9*3aEZpJ}q z2ZT!x7X&~%=3GG7!=@63j(?jT$EoJ}SnqcVO=nTcIuNpcDOd%XbI}jUT+5ta=m4l4 zUy#2BN^|hVu)x2YUjd~s4gyL6X}n+@tU?zAq!1!j@5RL_V4X9llhUbMxEDzFLNkP{ z?}Dt)T9es)5-8504N14WnKsOLuJNL`>>=)>$nZaE-&~>rd3QZUHSkV^0PN42$RS)cX9ojD51XJQlz(KVA zwaR=YD%tterhVrc7To-kk4bL759K!`6o!0PK;v~^WuN$b_9AAATqd%XGgoZ66AVX8 zK7-B1%$^e#|L&vPqjK3O{Aq?Fn~8YZ8zuTs?dtAE5djSlo=cpGj+l&nRgx{>ca z_(@HX3NopH9mT4s^Q&T$7uoZ!RTx(oHxI#~sGPf{jet z{kTZum?=RdSc>N7;N(5)nPBFagSB_nB0h@Hdvu|#=~$Jm>G)(@(}}!z$UU;IU+G_o zU@W@gt{}2*C@RmokagQ*vaTi5iY)s(T*r}XMW(f^NFuX#5+}MbytcN6lsd~Z>mx^* z648jus%mgKn(Lmr*5hNoeRz{C;kQC(F30;kI;dh}4Tz(mO?CK%Q_;Y$6A0jC&h}e> zfCuw(v;kXmWfif=i{foay~{G|&4}nYs%fCX;q#P{(rY=Yf-*C0;b(mCvGQ26LyeV- zTW4{^OFjW|o7OFEEi6}t%X+G3F?tD-3o>OcI(=kx`_;mu=Myw1YsZC?LE%+qa;ihz zjEJHWSEU9%g88!?Lh5+F9dkvsC(m%%m9|by;T62E_qdGhT)R?~HVJsO-j9sFmv^0C z^+iO&AEiB-=^CT7H6r1Q^!^AE{ypD_O7VyAy+4I%8#eI+;x?59e>+8;&i=WdR{G9wNPfwq{QV#ldiC`~@ZX^asBD{+1VtC03 z&w*1czCmdUxn9+L=58_tOvGg;M@b75*_8;g$RYp{VHTTS1uJvZ4qPX2t@yTYacoV;?}Ap3Q0_9KE>|4IbCHK zm$hzbFj{w~E9TiPsuI~UMu}{0P@5{SmM&JEz36AeH_YFoc@XdQApS>xb+J@>sjMK; z*&LY9G1^-4AtB+w-RJ3OrDWWWmB^oo8U_~Xo1sES9gHe<* z8t!#4S-p^*lT2XId`I){^!msP(7OU4Rm}ZwQ^-4mIT*^Z2sg9vc--(tJO!9uqi1P< zuRN@<$B=s>oUZsD!s~fay{a7IH;8Jh_2kKD$rRm1oL*Mqjyt zCbM1bE6?WFm)Pg7*P6Dmhc!XA(m5qWv6;`RNxo;();gO9YA5zhjQyHv_r@N?e&1A6 zdfVyUZ?ASX6SUtX_X97feY*g!fLlzi6*$U}wtSTnP@BjLI=?Yai<}Fd@J>ycCe9MF zPA=!y{>`-yiA%2RVTcJLY}L2i^-HZC4gX(jvMt%!4&i*wuQ_=c^62rqe)YAES8^L=5mJuDH?>h$r@CPxt^S5Rw6X;r!%g4=%WyS;=O}cS%@^TmRQMZ&ieg1T$0+HfM}&`IgE)?3#M}?r_gNmjpkNEc zJ&uCKoJb~Um<$@e$~qP_%n!LbG>7R7AT})e%}ZB%e#;__V`ljv%yfS$W-5VRW~>ZI z%Pw?v4Dvau64-PBLzPcpXgcLShN0$?D2k#H3SNSypNgehKLtyD48X$DCC+BlR>9B1 z)a{hLfT>Fy&C5NSJ^1~ zhQG~~vCxeB2Zd(r85Ejv-=NTped?gSgp#iMlpbDQERAJko3TX(XRW#Iw z%B$Uvi$!r)UXp%ia!i#GNY3adB2 z7y9?j*fpD|o1n>nP*uW6;6$u29zoYS1Fui&?4?f00fiz)LIPn+M|mHpEV9B22Ywi> z^0!nuz*vq586i|?;6$|l5Wlj4$JA9@315`mY&UHX0cf=$WWfyNDv?t(a*{@#q>(3S zM4W8jp^@)a76&ENFz4}TBWGwtuB8#lES2+Uv=Iq2%=xyus*|J=2yacV(#Q+!VG@rd zG-w4}>^rn^iZ*^j8@p*kDDi2+ue}deULJ&6mX*gENhkWU{HM`I(uvY6|Bq-R=|pRm zA5~YmaIzC3d74IqP)Z|0 zMA|Ufd1)l)K(rATjpVd4CHTTg9+$LAC4E3mwHgr@<=cz@fkv_iHR6j7#A@TJL2b-o zO0Wo>M&|uQBSKJaFCoS~S($?JbjnF`{rrZ%0v+a`-)=_P#V94LsD@F>Hn6F3s-@vI zK?;do@-tQJ(AHG>nJV*0v~fREWr85EP1e?8zRn1RtP2>s%9Ro{HxV6Kr)DblpUNvP zMBtlOqW_WxV^Nwd!%#O=daS@qSOqH)Ss`ri7IxYtbYKOIuB0&uPJY3otlBZA;_hv% zo4Q0Cc_ki_%r|vcDyA?!XFYBuU9#71k|=3}B1x@aKZuC<8yRKBWaxfL%{59yY>|w% zqy=A>f$1ayLwFlZIyM50Pmqk1C`7Dax-n6RpnfWQf$IjDe=C}faIR|THX`T8qPb)$ zBr`xijA1-8K;PnPFJuSU1b=rUqv^uLypd}U*B@~m=2}LXjz7gAt^-_8;QA!jo4LN4 z>l8$x-6l5+xhdvGvd+~Gx;D9<>4qqd0}@1FNTJ~etH-&tXQvB<4Wd^b4c55HS0YTw*wvj=;$s%NWh3A<~(2`vgjn`C+DDX5Rk zLcwBBM!N%#OdNS&7dmp*N}#)d_%`Oa7Z!Oox{e<1YdND*%7mHYh0$q(U$qCEgq(D) zN7AHB&b7E^aD5rS68Z6Ph4?QHQCs9;M(pJ%eyfv`THILb#X$(8BCaw@$>u8Mk$tY{ zGx61tXW!vj!`N84$;lnrJh*IcL6iF3`UU^>_(e^};Oy#{_c1do;V;b~ zsRoJxB+ONv+Ll}8tTV*tvYZZemCArjgfQ!78*ClId0CF^uyQSwkd5OA^DKgz&f?5z z@U5z*lQ|VWD?5S+^VV~9xD|rl_{!vLX6ovg0wH&!k$prht{X3gKRqIZREPyi4F-TtPQ* zU(H|FLNPke1rl>$zhJ!(mM-;?a4ETliqfZ&U#mk1O0|loS$tu{+B{9%pmOcLHlntT zUqL<-a1|B5(K9vH;qTJLZR)l`4l|1Dp5p{k9Hq z#oYc4TgQ&|wvHFHk*!ZWZ0mSe8xnq@${f`y&Nie5w`}#D1@%|&;OILaWM!*%qvdOP zw4nWJ8TApAj^fzUvj4`I&*em8SJf9=#RpA-kE(fR7avXSi`IAYjg;@zoPG!XnAL;I zIb;5rT_%)OSW{skg~gLm=ctZ=51)o|)fwQ_$VDDC%a4lA-<_jGW~o`uI{v1sx?ikP z1jn}Air2@NG$n#&Ez*rjb_(xMqdz}|XLs@2g|1iU8bQp;?*khW5vWLj6IomC*qd$%_hzD(gjdjz^SL6X!9w zj!M3h!RV~I0^-PYl+1Tfx5Rpgdy2d}il30T=3B=+?+D;r&)>I9Yo{c8qWfv!33)*yPYkMF|K&W?{=h$`{_had-t)1;%h_p#*ea;$jTEu0~)3n0%kEcY?S>w4Q1FjiAWM9b?49U zri99OvoT)D`&kmdwQWY*OnyIh+P;z_KtT@$Wr8A*qaT<>e!nptM3I^j0N za@g{7jXnEE>^)N8wt|bjCaVyo+$tAJki{&(hD=s{#hZ5(um%t>11p}{lquOjlhzAu=$c-y4F{AZdnhv1dFc$+IQi3F?Txc2R<&rH8c8Lqe{7~{D={;P3D=dZ>a z_ldA}wK9x98I)<9r59UW1aSMFrv4t{+}Qw$f+raG=NexhGx z+;HVo@28^E4g=+T7`u@+?qSx=nZlB8^7q) zyft*Bi;5&1<^aFF#BNz-zOyA$8aVm0C~Nt9;|gPw>U4}|4VAK%3V^Uo-R(^2uNYKk z-UOq_giE&`GN18>_rZlf#XN4_cYo%0C@3I2g%_aA;TO1nYx;QOkcNPHfI$?^NUAD<>O=dH%9K*;;Qe)3Nc6@yx$I)oMV3 zb}Y^tk+H|NDRV67^c014l!cdQHGrCUFCHz09c2 zi#~IgU17+xT<~~~(?!JEHSGC>W)g?9-Ckr|3%!?+z5C}B896a@&JlDjP!`>Ex$^u{ zjd=SZa8T4A&+5n?a$BWIBUNN@tSt2y%S#K%(wJ+EC$eb!?|!`YrMvIkyPXK5YF81# zg32NZ{84x(p?MWtujAScL5X{jDz52<{>W9v$|sAAYY14BMy&=5EY|I|d9=0kl1`X2 zodl3hh!vzq*Gp&k^;5XseYvr2?&Zd@xrK(yU0{rzTVVXlT#r%jDmFIEDQ3ikV$aD3 zeT$8k=8mJI`Gz(Zh+zKNP+DX>;Tgxkij4L=QcTVmYixaaobk&qZPt4UMVy~{2FaV;^@{AjRz}w`p z9LM`4-U|^Emg{YDVY+!QP&xr-$XeJ3mhI%%mBW4lkI=;?q-2aUeuPS4#MdZ1pAXYm zfR|R5ls1Xy6KObF={lHg?FNVul{WzXb$sWBlq$TJ#VOSEJKW2(ZG-;H`p~{M!T6W# z?enB;LK+?Xh0<1;k!R$wmJ~A|j-J92O}2p^$)XaDzJ}gf_OL#A6 zH*nAOMbT}v{pwJu+xR~CFT1Jin6lN1i=8d4#DdZ`rb(tpAg439z%pOn2DU(`ITq|KKAp$6)gUg3Vi#b72F(qcLc~CJvOIE zP_ZAzR3IQw5$JpX6a^9j5gEBaO%|W<8q#^2xnsJKk7&PSy30tQfT9!A4R{;)%Oiv9 za;&E7_&vg}tc#bhu2$p&0e-hLJqp)LN+C|A*BEZTk?*CUZ4f01SicTxn9}YxgcvPj zH`Mc7Mu7H|ylA^-_4HChD=39S!E7syOG8xN$)B})ou#B1j`seSq?=XwTgOPHk%~`g z_;IV@+=~rE4Y$!?7i3%-?qnC00as6-W*qZQGe5K8V~%P6tA;&Xx{g!0wQse1jUzuZS@nRhp6xJSRwdw)`L~g&z{*wuYb^#}AMt!Tv6dUP zF;4MzDc3T48(+cW?P=KPV>3K)uf{{+fkn5T8yM{qtRhyjlHbb0aZObcD>;HxYvt<} zTo0PY&8gj5-p^Nts=rOvH<3sGhA0{jCzLcm@%St|Y7#kzvG8~_AV*@YaF!yZXEdg? zQDI?UPhehq3t3t6485(%A#Bkw9~JgP@)q?iCU;5R%PVr|UcC813W!82aw0@VvoGrb zwDlr5gl4|3Wsi>MlNzj*#Je+e&+D3752L~q(@AK@>)LXC^CU5f@L}42a$-aQ?_hc& za&|=vD$OuzP{}K)sE%N~<$?W)9XCr zON4Z+TSQ@~O&0k*UfxOfjd_tQ`@HSdn8X5UvrRr+~E* z$BwtiqOJ*OmcCLSK?m}AZa^25O*07@%tyEu*CPeyODA^;hc>iyVYR^6U4kadayJsC zQ&mEZkc>>Ehnv2-H5aF*5`A7IAHn?;n3y?byCu?bz|I+VO;D>kxtdh4o|l zrkZaPpM#QUr*?De*8R6YcXYpkSh=n0X3_Td~_4y z>(a9R7E8~8=Rm6HIDAkCg);Hj(r6ypsQN->D#RH?+*ytz@#PaZ6{`Ms;_V*RH0M2p z4?h3XEtw{MzjbiS-?Q1AFW3?SM^IhY!A0vhy=0(Z6D3_Iz1e6cWW^n1^nFu;Qo9UQ zB~6<+$y|@u&Jid6N{m9scSYu+3-4*uHYy<4x$s!dU9UgeoLR2v<9jPK<@^yUbvQh<^7fp&Zrq=9m!wDXA;jLgkT{-D`U_fCa(CVhD|_zo5e-Ei=QqqmmkAzQG0zqr z?^Okl&n)}C*5v+U!vcq_B=iG=kBJm>=w=@}YqYpx2N?~qsflTDm%zBx#1y!yT*nl+ z+t|2jVhY>}xxT2tz2brfSInDya6wxewRKdq$Vs_zT#93L=xe8K*$c!kP8L1++bq?V zin$#nv)70BubAQ|L55gE;wa{Q>m#z!trbNcj3 zb4o6k_v)v-hij5XC&>HI**|Jop|9<;>B~R4K2+}`lo3UHjxyXjb^OvPlyx(BN?mxa zu=)XnkiZ;o;|CWBxYR!=ALW0On=w1SLgcsa$R*XhacM^8Ife0{Jqg=%u^-_pA3n|= zB{}Slp=Uh-75-UwGz>7*epmVkS3JV|Pwzx)f9BO7qAzsyU-W*HGI`nhYmld9mF4-*4la&5yhw{8QBq;N|!c1_iI#)TrLMj>0QAA0~^D;JB%OCwKIx9?I$MfQ$cR8G& zlvDDp+Z-OVSm~E#C@N?|cs+GE;|0cJyK~#K>exwpvHPMMUA@9qQ6KTw7T)E+0Xk4J z+hd|Mt9hm|a|?#Nngtky*(hqhs6=Xt{hl0D2RbT-np-gpQ{F1OuQ9anFWS{9@6$t* z;YwiVO`#wDMVrRy7QTli3!e)EqsNZprCs3=x%#Uc=?pgD^hO{h9;flMW8t2QpYN}uB@@HZ@0=` zJU92fAys{~j}45zv{U*-bo75*(q~_CU!;648AR9=@YhUtEJ?()XNPRV-liuCP)5o* zgWgLk2%YTIvZJYM^&{k_yf6(wE)Fq)5Yx0b{%y!d$>=vqm_!A9T9nQWm3afur3wZ~^f4jc2Ma+|u7Qb)tFL&CZ{Zgl& z@=``&f0HuuKJ?&GE!%Y-wn85}&m-afeVPUvXCq^RoO-T?%R#8nua9c3%ENpwgrFJ% zqwKCKC zuXCLZb9rXTk`UiiCg9YqKnF&Z46N14?xj94$V5Z<#dR*n+t;H+-upUPBc9dD%)0#6 zcgf;f@*d_YTrs+Eq3a(1xy-C-orfp9+(q-L)9b|hKxc0xm#@E)calq3ESQo{xF*W+ zIu+c|EBVuS-sv!ks=4m`P-zp>s&sG-gBCCI&KQQQ=DsV2A)PS{x#Rn~%-ZPi*S{ZH za9k_atT}(V9n6j?BztyMU=YHRmy94>^gcJEGRrG;5>JUEuDqUchEy&r=Sdo)JuObpi<7_LRs6Gyvsin2$R z_0L&u>+or9B&}4}^#u7peFB#}@}6*VurlocN1Juo^r=VDTgH>hMq~2Dw=#!it30BT z5kY~ccX?cfloR)b&nnL$8;@A;NHHg1>AD^^lXP4l36$sCe*mcZSz8d^K{co1U08EC*j5(b#Q!-`Dn62>;AM&-XFa@#otd zw^<4lN#!8ZdGWr`5WQ!vZlZ6Xa+zZ>>4~(mm~&cW5*7UA6yD`8&R95$KS`GE;ZIjb zdp&A~7nu9)BQ`Cl1D=x3Rb0^HllDcT3||NJB($Jg($2A2+=-h_ZKZ030M;Jm7f%Pf zIdsE+5ZFqzoq3*ms z(>#1;+8mFK%1%$8>sf~P#Ikc0hyUfwn&-xzS#vn8c5G`(?YP#<`7P#GDzE&byY&c_ zNOJ#JC5PoZsU!YPypHtPx316n*6cGs_Hi-|4gR=*d-+%zJximLAZKUkx%)%&a4y+Q z6&g*h&225D14roGW}wpmR8nf)j6SzjKwr$Y?~jvOd-+~mQhWJ+Rlj+-`s|v+mC00) zR_kh=$aZs<3eq^(JpHdy!6ZiQV$_pb=lrptwJXNab@B0+hFF=ungp+w^n@He+B#(7 zS@>hU=ElrmDnN8LV3|{ll7S_1<kgKktObDX324H16VkAtMtf zl0u`J%7w%U6dfogd;ChsR~?-d<+IRdW`}=3_`s0@Qf*F`guz8d5hgXoRe%N4SLXb6fq}2bv`+N5 zl72*S6&lHNFiyF!FwXw7_}?faWF$JjQa}p2C{#!x#pR`p%V>_Rasi_|bl)lMt1R*_ zu*hfNV|3lhQ2W{h&fvJjJ!_y!>*&r)LPt3S9i43F|T)$AC>dTa0icsf@n&bYrG)bWVgGole@Xw$1jaHmAokYqlqaG^%4}&DM+T zvr#dcPQ7C0Z2dB2SmDfkVyz*U=@pR=VNm-~=SXfeVN8C8t-V}MfMJ8x*OO)(foar8 zd+;DQU5=xpxPBkZ^sO#;Ul|Yu(m_M6rvvYDxNvyhd5!PkdW`)e@I~#yOS8L* zgu!2(f~}r{$8vmb9hu$>P?TO8188c|7(m&eN1-Skz|*9mlTH$%AW2}wj;mnZi2HNl znMc@{?(hDRFXF&|OY-TN!T@O$ss;zMdDwZ=#Sayp=_pBsk&c%UrDzt5PG5E%d6;2i zKNwg9s}ats8qrj9&)!zy8QsG1vzyCCehlm&2*w-0@v)v=Qcv(jL;~u%g44>D-DgIA zfF5%T$!iLjA3}>pi_uSBK*8%Fh19G>A0N1z^nhapBY+kb_sJC6bO z;}+OQcu_ledvK`{3fK*`yKXvK$`n)#a1jSM66YLKc~wP1Q!;v3`%tqYqB|=rPuegG zM`3Xto%RLKu?fD2xDm>|ofBtr@RaT1xK3T&n5nM0=i!q$!*XIu#6X@=)}!;7$gvbd zDLF#tE~3p ze152y18dpx4(2MWUm4HYvkn?cROWBo=5cP?=5@x^PO?Z(u*g(43gL?i*et{Va;St; zb=745p{dI1UOx&IxxSJ}M|R0W)YYgdk>$ea!1-((>&P-i)jSK$*1_C*8mwO(V2>4f zrFNX7Sqce>Y(ZS{gL<3TV$q0pi1-3T%5q47Q4ihkMG{@XcPl~5&1+Jcb7~7qSJ232 zk28z?8YRrgK+eI!(q5)`3*S0Xh2KwIVby0oBo8X6T#PHPBq)14fW79*+Wy8r4?JIe zjU??BQ8C9WES1dvrE~r2m8g);4qVZRgZs(RzQ{Y^IA@VN-(mE`mduxWcdL#=JoBfj z&fuGL{Ht{CyG28@at@l8m%d3>nA>^qKv8N|0DOKyb@s|3wK)fiOB?7h>*D#G+Je$L z%FHUV^O2{t3qDm=zn>r(q4@(*h(r!u2EmCzQpfapR}7l=2~lWvLNi7KQTXHs)i#{R z(6c`%@{77}2FcVwHQaN19$`@-qv-7!hCs)UB_SLGy~A`gCz~U)b~%*!oQ<0$7!sQJ zu2z}pE!~C3wuFP6CY!(+rs6c-+t1W~tu)m6H*J!Mjs2uHMY6}tKZV%1ne&3>W8%U( z0ud;NA9mb}*u7*`Ze1(-lq5vulPd?5Lesnqwn&k^!A$+C*_CbN#BC z5hTHjCm^wk|L5Qol(-b6f+BH{UJ6bb#XEz*8NWYcOAWpXI3?!j(?*vLI3)%t{%*E_ zDL(WU)YRVeLEt=7cYA3X;7qd(^`}|oZs0uUAq!8}6_*Z>U}4Zg37@G8{RmY;^_jZM zO9x2KPkhk@@FBgFePFY|XF=~kZu@Elzs&>V+gC4fT(?q;Y_1hsQ>(qo`2*hAyJCKM z?px0DVzGD5z_WQ&IP}XUnkz#eL?eZBSQ|@%C}|ioOtA`ofVLg`Cf4ET0icT$lu6Z) z2lNX_h?a2x5|4QjRf6asI^G0X6!8~=5Q0GBK`Hyz5>8OiA&RoU8{E3JFedVo|kRJ1=kV}sqvU@LJ*kU{NakdmAnS+PwLwy6MPCj-u< z{E4@ReAQBqQ|3GNe;Z>!;3^c`)9TuU3vOL2z5b;nM}*5{j_ zUT6c}50aPprCi_nT)66Ogy}!=hO5|zpUCG{MHhm<=Ul+3?bV; ztih!ak%W{26>)3;vTf(@xfbrOs^$G59Nr@b_JnTk)3QVDBeaCHxW-6i9x)7r8vC@X z%zXCu{506+RZ;cTMl}ASRqejj-n$NHVV4z+USJBc27W zQC9otg(HzYW?Vg46*zYf!Nv(U_A#X$T$!jmbU3rv;a~GCZ5tA=I_QP(0CO4eRI-Qy*Z;XD4J#b)60Uyn*z+3q!aT@d-{QRp4sxPv zDD%fQ$MVvxRV_L2d8HY!OYCSeKcf2-5gCX7lG*Hpv*F8f)Qnz*_h=)^{IyFTgA*fu|bHQ%~9*!EBc?FuPP;8^gK>-Lx{Fx9aJp=M~oF{JT?o571JL* zaCVLP+)7j+PI$URjB@MAGQX~_c(1dzXs@HTc&{j#yl6h+6%DR{k1u>H-!=Rb-__Td z|LlkVd`II0JjLJ~=AcnJ02iE6QypNM4VY#Frn!uA1rQP!S%Ff0T_Gba+M7^Yc6dvsp@=uO5$LZkCQ&-94hA1@E+F2j81uD+!$(&^DN5oM~H4T-8!ysl>BboN;CQQCZ&N zV_PMhZGIug78QaD=EHF{sPwdu-dt3FW(5_{z*bvm!5sDH-a1YhtZy$ZG360&pR zB-+K9=kXoh9@Ac;lL__O5^~j5p;RqlyeX`W%3dY52{*!tn}E6(k%+A4Y$NgK6+GV` zf8HN`F2YPT&*K(WX%|<93vD`LZL*bLutViL`=;6Nh^p&fagcq`j*Uzh4q-NC;oBgL z#w-lpLH7Jy7z$x^Dv_XsFOz%|c)2t?c{jT@(CT!-P_P+?(ROMKLOQ*Sfh1tmSw;}i zc=nP_yp!khUfwN(hbZEC*xEDAi@T}DXwR_0_3%PIi0`y8jEm&mS>D-FZY!#SUz7I< zlB`=7zwTUPJ(W7C^yBY|X&m%k3=Q(#G4_;dcr&SUS-eLImHGgs257}Ixq=GCnb;Kr z?}d*BjY28KIsDRZ*yW|3!BY}Cmyi%U=k>0{g#3%f#Px&oP>$c4i}q%$&r?pmpBta% zKyc0omEG`4w0!|2MR{K54!xC_@SrIt%Z#){_O01y%hqOQDPU;Z18m0G%Jbh!s<$@b zH$}KbE)^+xHM)i`gGe9zR&9A#%M3Sa8HWzqd=E((38Cx4IQQP=IAi>m(t?L*KbGJ{ zlnHi`$pg2RXsvpzxRlh{*byq_-#c? z*MIq14iGCyRuNyntoFxl%Wf7Q)`r}SW~qENl`qyVcET0wgp%x$E9c{(nDC8=A8~kvdhTYVVz#bM(lJyiC03Tg5%DaA@eM$J#VH}X9=|k6DoOnk96{e9}Zg7^-$8WPHUx(dsdy8!9&}-6VuIsWw__PMU29BwXBoMI6sAtMl+^SjA?|o3my7<+f!TK zW7b3<>?9Gc083w88EG7@OwnQbx>??GUfv@JgXKhdgh5^`h9iE*bGZ)?Xd|uyo1uaC zuhE-(sdrWFJrB9pDP~9Ux$6$UhRVmrmQtPQduX1LdT8hx$zMM*%=3;@cs>-t!*x$n zTfnpV32W?G;_SQoMUsSQ%Ar$O6QpukwFRjhkV^3G7imNs+~3i>-c->zuSv~Xj~V*} z_v_ba&53HFvkPr>#Aa$iVZML1#?jnoa|Sb2E%+8Q*1RUQ`Kfz{X1z^Af8qVTq{$Ku zWq`QIE$ft3OBo>w-LSAD@7$Z*d<-RFqLv!0;qL+dw%fGeQ#^aZmKfZLRB0-y9O{`9 zwoST@!~n{oBdnfdT3Yx3FM`+c!KEUV` z@6w9HBzq*^Ci~$Dh~t5p+e@EFP@X9Y++O;dn&Q&@Kyj(0Op;W8X0md2KRdz!I$9(h zCGn?5j;AO1OGJsgoj;9yK2PwMh`xS1f0~_p{u1rn^QWb7&!34lG%eozvu)a-4D~ODwjMh(u!wUIpYM7X!(OjX zq9**EZ0KF<^+W3U>W9hSQF6m(LAsIQsP}vv|NlGu(%ao68jCA8ZQ)LqeCPI|Em4#Z zuV)RE5ZB{G@4Ng-u!o?I7qn;}gc3EN!~vKlL5H0-pBX{@e#OJ!fkZ!bVdjtH!U}L< zqlF8@EnLW5r*zDVp@Ie~ECCg6kDt< z5+L|+61SA7M&CL+vP2eq963Ia4TOzEjDGdd zdwstvbSN{yVS)_$+k^L!kME7Lk9+`9-8A_E!aOK@$R!B#PveXEe}gdpG`^VsHweR$ z`seV)jP4)*TZH+i@x}bVL70CUU&jAW5Qe0aB$kS%ixtWrjcb8J%1dbxD&Lux+|rpR zd8VNB5Ld|^N2&s1X6Ah?VdaJ0rAq6-EfAarZYyCQY^SrOdhnm9sdcFBJ-C08=H>^o(KFCgXaE-lL zRQ!Kpr}J=X=?_rXzo!iipP8WapRvlPInS_lCh}Zg^CUHTqFxNDA4%V>NxBO{G1_-2LKE{!+_#>lI2<`;hY8WlnZAVvJrK%3tcbC)AT=wGK3{alxssmMs7sLHfa_Gt#)!073?*)#@j<{HHp!AUSurYMmy*nh7{;691_1nzO`x&{dq z17oC2=RTGDWMAalGm56YE5*_VfW$uMN`z5T|RX`>Uth$n9&~H)3d<$OfG$8pqpnILw{~E3x!k2xCmHamI zof@EHM7Y(#S;a$7@N!%eA4fXKB4s z{^+DZ>=_IDw3229U#4K14G%dHG2qXRBCf>wvrfbn;m?jDt_6))u{8>}rYo%vv zCYF9TFtHTh5=&f(^Jnxl*d!et1{H@l8;|$KTkvLMahx~~Z#Eu}jkjRU#^RiD9M)_+ zk+5&UnvHdE4{J7_XxJ@kTJKx1W@A&M;)<|mZ;Qb87k23%@P|In5?4+$U%SQY23!@p z;1i1OH*us9ab*lBH+ZofCUjGH_{l6h(L2l3Ax}Sux%iA{pVlN!?DF2rds&dLkaPZF z;!yWM>}pWrmFObr=RrXEuwmD~;Iy`{uUEuTHWFW#ino z8rFr7>MkuC@4b;;SW4<*H3xYI?0h2{pYH>`_gJvq><8!A1GfxO z%vHNsOk7y0V&&vN@jVikz#OtV?m|I1iFdiMnrCfnKue!9diGv!HZ|d)!wpTj*3WKT19hK!eRCD2*`ak9GmHPIG1j>|V zP-hoYZ0)YoWX|!d6y5PcDwPaIa(x5W7v`~cNRz!x?H3Q5o&q0%og<=NHVFg!i2_Q_ zPRN*ffe(kx==zRLlsT_;u5Y-?QsNBt_5Zhgc;Nr%?ac$CI?u)bb7s!SEUb!(fWrWy zFgPki6cVg6payYCTza#%fFvo4q$NwUnB)MOxL^_|N$<3wt!R=~Fr?{vV0(i9fr7ZT@TV6TT*JRlb&`6Jb!yS;ld=(dMjatyr63 zS=gAiU1DQe|JiPxqq~JiBW9vW5^tcB@FzxBL?wX3%+B8LYPAx<-419*K=MY;C@SI5|DTKo&etNq zS@QY7L81$vCWuIL@;kgbpnw?HUCGn9JUptbF;D#PzKD~TOzvgcZ3l(A{)MEt%*Sv@FQb7rd_+W(WZICalC_=PRg zCKZlH8p60c{~Bda;*(eg`C=Ge1)MV5%t-+*To6{< zvtBVLm){z2<`T*;^1^{=oeWKq58Q}qj;vRc53UK^o~ya_oOC6D&2G1TYq%ou+&BoI zv5z!#oQ5Lx*e%kyX%#zbDI!eTz z1f_8)rc^qYeEcg)LEQ{*2b$Z7or)63&DFBpk;x0^=e*$n@n8jSPlG`o2a=Qo$W2Lb_TC@ZT zCJcXI+B2-1I>g{99bTJtAbI-gfGLv>^HH~yl}b+%06d3|fD$Vj2-;Eqpn27Nm4tUA zWn${47p_N-4S^zkKyeMnSL&W1wnefs8}Wj`y2`mfno=Bnf9AHKR={W1856CAzo~^D@n=H1;m%_zKEyjwrlL zqjcO&$L-4mg{B1lbH9!LI@)}5aZY( zbf4l`8d=TzqqZk+vLnc%g&laTTrWC+54!S>a!opytb429?jJa){KU3dwwlacifZbz zWyN<4?6>^H_NY8lc_s?0*42JYxkj}_b*YvyT$V25`vf~%T}qc>z@WbLZFawjAnmWw zfu5_vo$8b4@pkB!BPIXWyg+d%`1e4}RBfUu_bOQ-?!dKEHLE^)Sy@^0a>_jNjHS?6 z&zh|R^eCAL%TU#p+PqJ^G+8;jk93}r+Tzd*<>x|>?q{?EG)hpsH_AWC^2;+fV%{b! zCEwwl-1p}zv+s}fo|9#D(?q2Z%+%S4OYFQA)CFbTY3I$2(NM6PW(>}i1Fsc0UhZf9 zYxBL`_s1&dHqTIISK!%fk_XgOhY%xK+kN1R ztVbsU?#UXQi(vbrwQ-!^hC*xoL**WKf^xXx)^PhqzZ%E;b7^<+eYJb+{8p$oqy4qa z)LOSvuy&3&aCMI6F^Gqq1_a5YaU0y4{z~#%b-KNtj^cK-WRprVAl}=!A`q1AZoD^6 z985>d2ilAG7jxvmdSWpHj6l5Bg%uk}Z#Iv29KQf!!A$`Mq*`ksamMjZ!Nf-Asj% zchEhaU%a_VLR)0VoBPUi$TF9EvQqTjOr=pe(5%A^ix|O{iON`y%BdYjKxUkSi_I~d zg^NKUj#;vm=gXkgFEEm=jIPIm!3*2ePD}*tmib*>Z0m@9NjmxJvEkX`8ZD>FY^h3t zaLssc)>0R#W0x?%J3>TC)A7_eD08ljjBJHt6*g^_$Qr4_Iw zB9^@&gew$hJV}NvjY-{4=rANUk0^gEQ+dX@&F0Dtq)Q=5p)d;h&u{#k5Ldxm{qr zm5M;bAMXIE>KiAI%}IxQs*VffeKX6g+`tWcr{IAJi_8x}I*CkU5T?mCe>U&oId2%m za7TteVf6ijS^gOADX)h=xFOpwEcwC*BdWff#=h|Eoyl-fuo~VlF8nboO)63H<>;c( zuqDec2M>(@i?aMYC5(PQdusUo$*KOT!_6yCU;h4lX83*26o2zu%`4yIeMG4UxIEgF?BBG6 z)rC#_3P!05WAh{G0_sx7SMlQy-0ad^rU%yt9`k4`vv-YrbztAzQD2Q8Q8E(UAM@4R z3t#=ydeJk|0*hy86Vn&>WP%i7Z>J;El#Z}|V&&5`x9BHHf#w-nZdfOg9>&*S*26$( zhL))P_0ve7CK-Lo49uIU#bx~M+KEB;Y2fymn%gTtkjYdYyyy^Q+&5pm|0r(q;D^_! z7zRuoLy)}i)=oI)P~gx^&1-E&XEe5L5@%`GU%Wf>uc*~xfRm+don%_Idn^K5mSt5m zr;y=cOV;w+i569E-EoKHKAz6~X82q5gPm<#hbrHcH0PTvWsbGnySc1L<>fpVv4+K2 zRAyQ1kaBXsRNmEK;@o6e;xPWlyg9V4B#@b>B?QXywWKOBpI~@+Lktg*lqkCdQ8+U% zTHbx@hXW|@Z(L%C_>Ey0+BVt{5itzO5e{MhVLzft`JupTle84a$lBN@cAz)&w7e}Th{7TXbsPt_8Mhor^(3jVm{{kMxflv{k*mde3gUA1(#j=06 zF@RqX_)75?113QbMF1|?gk!P4Ch&*i(b#mpSSu?&U?TFU*pR0<4V3Q3SkuFf^199F zU)lIR5xd8Vfk|9dY%0O2&?@m%UNUG-=?pZ@)3T%F33q`X&BI!H0aby;2;%h2!z6j( zIo+Ne*!CrD*2PC(RCLyS?b>Ut6WQCN?OIx~(!LC64H*D;v8)c@t}ol)KKIKW!exCvA$@*hzBZ*+`Yd-M6xXO2upw3lSY>~}82Nxo?qAGQ2;+^M za9n+P>ltE70GxH;Zw}(5)Po}zwiA1&^iCxF$one;U-4@5i{!Pn*VQTl!Z80!u}s8o z*)Nj&w@LQb&z{5E;s!vcv+2?R_xA;U=hbEg9x#nbN|&-?Ci&vB^L*M>S)W%;WaXLA zO^luezUR{_#(!SX`vM6iT8h3)@>gF5b@{pi<)IgJf>3rRnJ2ol-ybeWGpF9MfdJ4w z_$LVFgin2nr>c>cwex42Ag)`63tri|q(jg^vWWltKE?khV9j>&wj%7tU^TZp(SQz{fjY?THn1Zh%rPE7;1)XoZX7;b&Yw_(_&c0R!LRkwyk#7#~o^SZQyh`Hw*SrOaO* zkf_7x*J5so^8Ta*+}p8UJuL5b>w*7Ms!eqo-*{cLg(ENDo#XmY4}a%M4E%Sg=1di- zR6tce3RL1TY=ElLrzPGT0ae-sP$gXe)o1Vn&=rm-N)p%FhO)H zvS>^!n#kG;tBUr{XzD>#)ZO;*KYv$+Cma|y=y07nIlm%{cyi>zcoiHYbo9^c$Y!Fv zMoTi5(cFzAbOv{0FfwVcg3uLosub|_n{*B(PrEpBfs3(!1}e#@V;Hr8VvIbWj_Mvn z08Bb39OAFQncVb)$*s-JE3qHfxp*#}>4b(Eox#Aql+`!7GdW<&=+2yytY2cJL@je? zXDR+U{EwDmkSXb<3A|qn*^ z$-+;ECram~?hDhUjHXqoox04GR9coMXH}GZhilt!b6xF!DNldx>0G7fFO2MXC6+lE z*{hL}0p_)rjci~9%!Bwo2n53oCxKRIR}83zb|SRt6#tKKh2#_aBIJ#SMI-1dNYfI? zE3k~yZ$Lc%0~W>KP|xL6=yOH3qUpaC+eg0NuFH}j8pKH(F91E z-w)tvPw&Q-aA9FY8tj3ENrU!L4T|b04Tufne`-Jmbsz38($MJfN0zTKei%}&B`~MJ z602WN`Tqb29P|Dkfsiz+PXYv4tWw`-AY8J5M=;|5cOb~1lCW$`=Q2hi!Ih(s08jGO z#TH%h&-gn=o_yKJg%?QWk|Q@V{qpR8njHgLYWR?z$W* z5l4{=m167@VITrdSzqL?oLy0hTmqjIUR=efIxvyUuOcBl|J$(^l)qN!$E72FDf=T!-zUq5e?E+)`eXg#H?0HSOHV<1|vl8lW^~r7H?Ox zsb?NiPyU(~0{Lz!>01AUud8y4sY}kYRX?G2RhgRRRX(<9-Us({tnf-s0dlrhI;%(+ zUqba(en}ZR$-A4DYU%n>{%OJ_$BtIG&`{}+q2f9w+PSk2Rl~IYhU??2t zI5D5IWkYYu`?16o=ESk_-m+k*X#&B=?Fr`?P`>ErciA(#m!Yp4?+^FRvzBgHSy{KM zxW?`ce7aOi$PhD)?D-ArW--}xd8a6G{0?CsDjL?+j;OxCjAh!Q$+rR-k@u>N-^9); zesvm>M(P6oWm;NEWVWr=HQi|shWEQJPj6sj(}oj^tHp7%C7o@-43l5UF}0=VWVE$B z7`jj=9QdIQBS+k&BRM@{ElM1wc}@8$nKV=(zPpRNts zX6;&OYh*t}MoRz!`Bi;U=hI^r45>am_!&XuIGh6ZT$&CTR4(KwE^F}=7;=|=#kr?o z!c7=~0|xCn^f9-A=aP0Dm)fN?)FH6z%bkrAv+eP+4H3xW`v$~LTQ2cacE_eapw z4++p6Xs3mF(#PRa_3$V3;p6K}tatjbP9xYNLAyb#&7c*hklMslW}6c3yV`r*pviar zAXyl$)%NQ(`D?mui^7q6v;R=AXBSyN(hy|s%FpQ5OES7eRI7P4yH(04oVCR$PBgpm zOT_Wkga9L(w$UsUi3TJQf{chj1O%d6Mi5l#qLvhHx@iP#Y^aParX8P_~rSe_?zV%XP@HK z>{(8W9c9PPL3=wXqwE>ZOgo(;s)R(f)kgySUFLdzY90 zEfV00gqIy~+f2d)q!UD_nn(cBu*8Zs6AMA%xd8>e5ODr#QBZE;Us)9F;YFk&7nMcD ze~EiW;>vcq4!QW9<-C=Os|ZXb98(&q0);mS9i)zg*A@|rG|$-#B;Oe+=em;bXjF~Q zbSCiIO#V98^>moQ=)LqvdVPSK^rcgsc{JvtvGmsg=}2RZBaOLetZ`IhV`&cY$DC7K$Dv0 zjYiPOdlT=KcnM$zRVRn_=rRh?9H1^U6|Zt$C4aSIRfaCS*JGLiALl&(0j8*-b?i%&LMWr~#31gC z5GSjm3_UMInL29rDdz*BFGB<_luWT1u7i~7{ywE-=tj#hqRN&g2;*m4Q#7w9BiidR zGfz_zeV(bnKgwI;kvPKXM9)}3BEl!Evsi;9CnUHQ@xe$b#$P}rZ#>hnlG#?1H<&jx-Y%_`PgoC~ehbpO`C+t+E6EXId{q3f`I zQPgGi8lOoIjbi++m(Tg6y|D6PGhi})SD#7VQKEQ*rB-jSL?{~sMIctnl&%3XCT69C z+4AzPgc%WCMc-b< zC8%Y3w6x)e+tyb+x9ypVYEVzmGW}1Pw?DG2rDDUjofRcKQ~s23`#xx6{KCba^(+TL zL)D#;=Tw^47rWfxzG}M!7cU0^X!W9?RiH<@EmDd!TeYn@&bzHCP6C(RO3v^FTnpdI zilzEkHOo7+;jPSA*ITYwi{IP;5HC`!5g?ByT9M(8qwWaty5*kXzz&F42;!9i`c^+t z+HmW(COxi+Mw@AT&9;`f9W>^p5fh!Law`25N+`!|T$XLk70Nb!M@1$NML@Wkhmyej78+3iFzJ(m zy{!42VDXv~$m}A>?3a{aGm!X4I*=df0Fx-t%>uFtlPT?G>MWIX{`mool<-0tucqOh zjPf=bl_j!+_mwo<#ItldM$V?8DmrsH1R`KJrZnbi&pQYsVpu5u-g&_rwbaH+{7KBP&F^#;W}fi(JZH?MtQ0zBve;0YmCL}F^$45714imqe}Ds zV)C`fd69Fj&*6-t6)qt0budwXQM4q@Kfep@Xi!55niAGYUeub?&QB3GswzR%0xPu< zOeqGgm%#ma?k90SSqW+=Oc&|G#g*>jG_%6H^iAF_SI_?9%;=tZW|Sq9C{1W*YV-F| zy7YA(?OUY{J3v5F%mW@l#xav0^a$2BgOEG7t&e+V+s3$bK;N?Mk+>4(-pp!H9-h}w z$up(dX~+o?QZO1CGD0zm$a>Sz_R@Tl_h@K-qVZ{{l?xcCruQa?N9jx1t2U?XHT9KY6c)YAB-|-GDJdo?kLTR7Fu6mFDjjtG(YTRvvD=IKW5m2oLak zcU~CatS=m4Z_;@gq3WA-Ug@25VU&T;N2bJo!WpCU6?`7WLM!$SH!cx!&lZVsR>9qD z>V{L`5N>iuga1A3{q>Pn>EnObQ9KV8-ji#y9BQh>EJNu@rDT` zZhDR*ygWBO=jiBLMTd}wjC^Nw==kJtEE6v_4{2P^q4%@>a@0|hvsP1Vjjv$>UHU+D zO5n^_p`54KsUz5J<3WVZ<*!U{J&mRL42Gh!hbszuxI%~13J-Ig?c<&+)W<#7*|Xep zh0b!%br$<#4;N?E&W08$g@?KNun@~h%q~?t=1fc2lRWVZCctm8;-ov9V!eTl720Ie zUEd7+phC-78bLt$z1#;y0Bjx61euV|BTU3mCV~_bM#QgO?1+h4Eb8$)<9s;*Yb6^o zs|#JuyHQhG?6aNEkVajYdI|Y@WlF|^+H?NAD0sFMIZyPl-u1;^*Bs~A#cJ2s#Y)#- zuJL&uMP7d@IfESUA|AxA0O%e4!%{87b#ufNKirtmtbAx`;Y#I+N8+V}z2oTY4!CsZgGh zvMJ8A#Y(p-jiiSgH_>5X!Vzi|Pen!}ycbF)-ilme&G) z;)QjVqrv8)(WWJEp8IY|-0SmTXNnV3LJMqnOESvDW~UN-vRvtI8bb$Q*!}1Nn@W`K zO>iDU(gp`IOB$NdI-1ZNnp$w6ouC9y0{u4K(3lg zD47O?BBqiOE6=%v90MKQSp_(RE*mr%zWKvHO`Y)w*T%P|#lDPW5|yJ2MWhpvOvZSy znAO4*8t8CdSVECTV({G-GhYX0zNvTnf}+`GAGY{!Wi^lPP^2>*NG+ZO-Qu5-XYv0^ z^$xikE&g1;#XtSW7Sbk%d-*KSJu57JnMdiUbW%Dy=5snKo!mkBt5s#_HZJKbK0QNh zg$Fb5Qw;@0pzs0>zd~Dwzv2u2Ra6ZlN9`0}4pW!@Xzt5TCxZfGe(v81zo%4@q z9ZJSJ=P9%fdG<%N4!OUT`^V@=mm1p^*j24X>yjaS5<|K-?cbIM$V82>p4cCkc0MKk zcISgB-*84scdfAaU!(^qW1_$M5G|(BgS}u}isK>Ycc(<({@qX8XMA^ERqP(eea<3> z?p$}(ea`PZ`R8kPIo3J<&2bM0Id$hJ_J^EB^;NOgU3HK1UwM{Px<+@V`qnttm9BAK z$JHO@JAb9U(D{`ozEkn9xmP+LD?XSZ=d z>t^k3k@RW2+sUuYyr|5*{O^L^wAbbBJ;T@*0rYqdrzDUz^xw^9?->V4MS%e!39yXE zJLKTDC? z2+|Di7X%AC_V$}i;qr7MQvOJs$#ZO?*;8VChbeylMPxG&bU%UZA{A&}@6eGrvqvg& zq5n%IYxu4C^0!u&z4OC6)EF(+^47B`;5%cVBZGj#wE?y#`mxbb8a}pOX_)o}jfERj z55MnFhE82!B8!w6K|$A$6fW*fS|7lj6pxxsNDCqnh~%KgU+ZZsn&ON{_#2bDCYWW< zb1p8N?yM`!bzW_AJH>3M*s+D775)kvotT_mHc93%&1qeY0Umic0!`V$lVvD_J2_MJ zoY((*I53d8py7Rocj!cJDS53*8iv*_VgqF%;0o_tTusAku;L!IPIImV_wRswnz7!` z!kS-=Ix1wCeaF?+N%@8~_c{KTaJphGj$z66VX%!yW~;<%EalA37njSswYX3$eV4^{ zHP=+=a|=CwnUR$+vi*#tgvMk6dKr;M=0Okd9^>5(o5#7&h7icR3`AhePTSOX*fDvl zPV>%BM}jg^Hdxc0zrTwB29pe1{x)?0qZE|=BQCEXETh^ zfye8$bW_6}fuGcCGxVxEh66E7Lb)&9Df_IFm&`}>`kQ#JiC8!J`Q=rUcQ2PD^v_K0 zS}t%DcnY8eo+86v4pWUa5}~2;d-|$>0q$zU`Aqzgb4_4{xnZ!v!lCvtf$P3wiV0M% z)igb{QSme(awmZzD)OHdW+hu6GW|#6kb0k&9;)v7R`SjObpcBBS=j)X?sVfsAmx7r zDyTdYwAz|O$~Lw{e#w~(Ire~Lye-2hPx37OuV<#BPb~_HZJ%#-=P4ejJQ)4)AwHHR zZ%DX+NGddDjQx{@&(!~@Sl29aVJYEfCoR$Ne6MnTl`8899vuP5k+nBHR zH5r`;2VLJ!CKCC9V zEYD^{yPP=3H4d_>D-UHmIc87%&ounm(I;qFN%A?DQ0j)}{Y(Da{VLAWt@?|w4#^f6*%dDEfy2%#`+w)rJ|`T0zo zVslHtFdr+sjFo*gn6-#_6AL>|U-in`zs0q!)?F)iu-kFOtmyf>_NVPRY{X``NP!Ka zHi~My6p$x=*GkcFI4Y3ek3(JvR-K*TbZpD3W?*f30l7-EUqb_dU;z5$SP#q)W_$n&7&-+JK+ znF>}=@a*GOPc`@Na{nGHTSG0yWaD`*2{k4%jAWYNe%YzgmdjP=~gvkknf=6a3`pY`s3(&P45 zaBbAXU~aKAtrYMQ>ZW_3l&hZWNu~S9+jj6l@w^w6;5qVSjOX2rV?Ck3IG!bX`hR42 zh5GT$MtoS(!Tev4IWHoi37oLvFktcvCCsv19sCBSSB<3{#gvxl+*lCxr!ox*JS<@} zp%l&YUSJF|hRKsvI16r)=@jw7=y@)^zM88#+;QAeSrIAu()nZH(R&-CJZDot;5Lir z7^8o0q77tb5OEIA*~gcgd`OM1=yB|V-(j~Ac~o9SE@Js!iA z!T;~lP{`r%Yy_n7aB)8!pTh6o)6t`JG&E8398EL%JZF%k&IT-=ceju6ygSb3IqR@{ z&a_5*jsotZj6iyOaHO}FcUHhGCv#GDQ5w`q;lS8zlWkL$PV>J3v8};%g#?n4Y0?O3 zFTq5{^Zw^QndYC!?_%N($|-->8@RbKbHi+p!^ybz9^AXAYt~89@3vU3*(fto|3}uQMAzavADLYH|%jJ z4o7fnU!iql;2CdEM{uoYd+WI&!%H_%{4iQHRo_ROjkJ^6?kj5Bioz;5tin~ zv~As?_#ag(_B{4*>7Lybs#jwj<(O#+`H>)HrDBJiISuT%Tbp=^&?R%jvCngXZPk{< z<%wYBCh{Z65w7V|30#7ZB{L(~xEqyH#Dr>%e$;Kjx-XrS1XbCV`Rg_wT9N~=1@aIZsU=U5!U z9WbfZQqFB7tEsAVPxKH&g|ZkP60%Y2Wt<}ESQqE8XvP_f1{BI~dQf=^JtCj@Te^d= zW!*2CtVWm$0ptKGx9c5jtN^enwrL*L$km87XG##$CE=9_=whj6FTHaBz{4ZviY0BY)awf?%CJu4&G9KQ=v7kFI6X_NaMlxLRm<3-pvD+O6}O8)ONC-9kau-Z?uTDsqkWyPc zu>-`f#A&^fP9~IjJyPewkve}VZD8cu07E*)|MBiA>>4s6&5ryH=#_9$h(`*%S3 zTmc!WlQR>IW*qtzjm|FK~3Hs~f<60#gVFDkKLbLPOcyHIS ziAon6DgIx||KppVe`lPxE6tQ}g2oR2Dj{5P7nQsu3k?G>(bwI#Vz}JE^&Hyv5B`)j zbcpJDfoDW-+A=%0JTGCYKb8H04{Ug}zA5LD>;AwYFaXyRt(1v^^xPg_{ z!~HM0e>nMS&xScXV+9&z4pD|pT`6|o`%Za=96EGqY>)7-l{n&6~*z4)#9+Cv*q2N zwkprAB&>mo$D2%!c+(h1JybYv-}Ypwyh>3W>G!6s0znh*2~?S2YK{aR^AIqOFkhcvFIds1FI?L_#_${XsQmguFW(^P$)ft<@)? z2kxBcw(>m1zqGkx&oZdHB&n;XY?m#@aXa5X&%Jc~kR{r&6>6Wu6t(`UHJsWbuw$Jz zaYpTsIicVyNn>|B^uUvS-@tu((g;0dmt{OOu1QgT{%ZiNB(U9<6nJ+X)~HsZ^D+r; z1@e@RT9|?Nomd>joB>JOW-B7Mk*9RXo|@?##}3V3zNW?*d;uvwH#NgK9Zyz?f=za+7s#yTv=i5t)3&+8*0%!()!$mOp3AXoymVn*QvX zk%>iW%3JNYhh)UA$Jn2a#mdERwOJVgi}EEFVzbY8zKJy^sZ^W)j5UirkyBS zVp`XYi)}q+j_%yr%z0jV7AjC0RCYV@dP*GWY3B(Rt8l$dpe^W0cx0th&VDT;m}-T^ z`bS`HM?!rkT; zy|86@UQN^TTWeaDFLM55`PZC3T|UdMME}yJL`$ssbjT1h-&zmY)>=vi!6g4$4p7L* z*Oe+{9=4xY0>6JAkaH0Epn$r5Xu+GDO6zWAFs~uy$N)m-l+JaS#Fqg28lWxdvgMhs z(kmRd{P7-TY0VwpqBM*14le>nB_=C-o{HDe>H5 z!&DZFP|5E^0_cv5R)%iD3XlaZRdR{tpaf#B;AB;aSq&{PsNra5!Z#62{BlqMR2)%F zkobgmwn$=cTfLB>8nc{ZRL;oA)OZKP>u+bTA2yo~4`f;}NODkOT@?Cp*m*i}WW!EGRvTMfcDA@&;Es<=A&+Xh zSVO@dHP07R26xO*pw~8Imn26P%^8;!16vH#FhTRH*M}`vitlw1eRV_j%_LijZH4AH z`F>M8h5s#!d*+FdU}X>H9pvC6$iPR(sa>jTO;Aba88c#5vyWmhCLA~c5uY4RPZNYWWrvHGLX0d2!=hVkL@5;c9^|sLu0sn~Hqh^6dh4HDsG*^Kx5T22!|)RU(Dg%m_>2 znTTgo5Us>@S)_19M+~p0P|b)KegcH7TYgatUppd(%RY|8GjYHSMl*s(t4#j0a4?a= zMe?4Z#5zO@w<~r-A{R-!oY-d~d6OM^1qr8DAdR1mCyBL4*-1GG&|y~9t5}tebJ76`*0QjM<3G!5`lJ!-$JOfQ3qkAB8AvUF}u_-O;2)LR#1MV#_Yr2u_ zmbnT|1gn#nGpMLoVUu8mlD<~oe$&%j)IO7#q4;e_vXS6nWuMs zHx$0doc$H%Egz+8;~gdN&`ds-Z>p8;$uIGn&NoM4?5CNl>T7K&$Eb^>9CgBnx=1xIG=D+#mV$<6TOKip3El0~@ofdAqWLx;{K!j~nH zFIs!zc=&R`LOj}1&|4td2Nw|VfKXbJ{I_qSHyD}^cEOKBQT&oBP{<7GL(oN5uh4Zo z!yYY|WrI(DDk{cJiXIGI#S3&0UTh1c@IQXnQYaSZFL@RRbLR|TCzTEjq8<)hHKxHa zLTeY#Olh-1hv%bExz(obBosS$y0>UP+@*ldpCJ75@tI2ZmULxy8D&!~h>jCeNmzsO z2$m%^>&oFz*!$XUO07T6nb`wy7zw~K$XP4lG(7+u{B3N8x4LHgJPz!^vAI6a@d_mv zjjgbk5%t}p1UG5cx&4-;xyr^8&ylOV#>S)#+jJ&m?A9FixO3Rco@n*FbBz*|Fwash z-J0z*>2Y4q`X)72YN*+U=a$< zl8tb&n@A?UkMCEWk|;6+4oEz?N(ovWNpscK63-&)mByq)({rXeZ(*Nd2U{!0qO2bM zBzB{l_&|ES0}HwoGB(q*bDb^{L5C>h<+;LrFTWv1;F39Bf)fi{Ej!p^Sq=}rr+zqK zN1zVf;|=yseqs5Y+%tV|$mWL1pcI$eDaSLU;dJW4Iuz`i>(z%^cu+!8)gz2Fy3p5~zc^2@0E)|Y#lAVIPrAtWetg?A_f#O9l=^*KM?lq}>3y)}OVn-~X}u2yu_ z7?AS)x!$2qnd?drFtV@UWjaFROxRpZ{wL~nHWk);gDT*u1T3Lg)85cVZ&0S>#8i{# z^vJZh_-GwMz}u#j`Vbv$MjaH=C8OzsJsBe^#j^_NnW)Rh^XWwy#txS84ydJb-v`uo zfHTv9j%;H2bZ&Y8S9SzkZ0Cf*-YunvVl||km~yzkkSu=+0lS1w$S4|PT>f+LRSEyOpXU8O?UPnC!GK? z?Lc7>9qlu(@C*Qj({$$e2!sT|1WHvvF#@SR6CDFmau8OgB2>Wuzz;!mDGyHRAOqVt zV>HkEoShtyd5v1^kzilanb0*5l?w#bnS3iV3%sbK8MeNm)e`{iuf<6dK3Jo4|dOcD|iSl|*K?hnHscf!FgCgfd8j}X3 zlb1KrMI$m8X+&WaNF#8S)nyaHZQM*7eITjJ$^ej^vfr8L4ZcLi%nUI07Or=ryhA?# z5>3)D2=)vGpQB(Pbu&jH+R@`(NXst(^dB%WKV(vNpvUiIH9reRJj0@GXTi!ub}$M5 z!X!u(hFd}N`NWs_5L)X1<7C56{+A8EzWKl}iJ^hMvcN;Dz&uRrop?w6piVaZR(c)- z)3(kr>7K{wnt?jZcr_xui1itaS+TmEEv$uhx?O_NUjcRt!3Norn{S?2-(pfcPcgC0 zC`~Sgxr6Upa$L@5K-b7nrPBe*NMn=_u4h1;@C`OIpv|=Vp;=e*1(jM~C+sL&=<)0mza#`L)8fQwO8u@y26*-{qhd~;&GPzvdQOpicSIEw6I z3q%LVRv?Pi;%O;)ZT+V42St<0Mw1eOQ&MPG5DE4pcwp{JqE9Wuk7Fr&t4kVAUsc}l z&+(dTx_lkE*!w%T?(oI)YI47O)V;VoUGKwCYvslGyPLXM9E}GNXD8-)&*3gATNa&( zL{T-8dNvCm8Q1wo0RtLIIG5-66S+v_;!_~yWEdY30$Ad*{d0#YF&Zru9Sf6^rsM^d zZq+8`Rz2KJVA;l#5DbE@B-pDg-BuiP5S{W(2^PbPOFoc&;lMYN%t^P1kFvO6RngB) z92TBPKZoh(3HmvSeu|405hFS$(0=y1dj}PxpW{29rJpXWm`02q^F*VcA0XT%(nl%# zB>#)&0c6h|II~rAxx!zL>wKIq#r`SVD%(xrFQrd`2R4|KZhm`=lILQ~+xZQlyX^YU zZw}f8XWD=2CXu@@FJ5XzkzL!YKdz{Ke^SuvU`)++IG)4i~rs$ zEdCQF?@+YaJ7k}-CMZgsD1DNVPOw4x+QRJ0M%}`-!+~FzlvZi8>>6vE)$bE=KF>=y zoXS7v&S?Jg^sx0nECwUi1FQybWb9a^8x&eW$Pi|%nhU7@s|dEw`HbU2#k9ocB=>N79s>RYdN$v1~7*E5#wPRt)xGPTrXTKv1# zCk;j*ESpv9N-h4>6&8PTmBruRMwl7_c`xi=%oM-FOo6sF`)&)l#OxzSbe7rLl-~a+ zHu<2pY>fSW9~1N+h9U_@~J3qwF*u=-je$S7+xPyB^AJ z%Yhb&O~E##ziBn%XWAUKE7x=r4Z=~gGNb#*#*(g(V-#f4fJ~GHsQ7@6W<((!4&oR>L1kPi-~V{Lj)HfAVuHP>pq zkPC#@W@kC|r?O`|KgupJ&KiVx*!tUo*19Y;=Od19-lZx*rh=0edCpT;l;%`sDM2sC zyM!UHz}?_Q81x#Bg!!}caFNS!HnQKbCS3{MmB)7lO0X^~DyMOU5^Tsb=QLzla_aJI zISqM^oJt?!6W^Z6o;A(+jqytG8()SAQ)%TwtdAFvPw{^Vuzk$5gx(K4^n`YsZvFoh z7e=GP1OpXnKn2-ttYP{=i2?&B4uBJ1gbV$5BD|rG4rH!||E_8{`6RN`cVDx(TtYuD zIe7^6G_CM<+in=i#r@qUG+$u+Q`&s%P8^#AApDHFi{%12YLPs<=Dw%!9ya!Oj+pJtE_D? zSUn~sjPX0N-Oi;s;@qaVlW~xF2{wWGd-bQx>3P2Yy`qerJ4dz7{aB5k(}V&cl9@Fy z^et^7G8W=~j?3BX@DdXyu~Tetgl-RnaEMC>i)H=h@cz5cD1J08V^4n9nk(DX=C2M) z-y{8w^!YCOD*dSZbhzMS`ah6a#uQzRh_nb(;c`rc%Wywiiu>7;j=z4bT<~E8CI8bY3=iS zWVTy#9Bo_S3nt2mmbIpK`rb@zNxL9zGrjnmX$TN zIeYregL7XcWbfj;(acm^eO(39v>0w~WiyD-{)4tg@3~iyv&`G3;Qoq^Nl&q`{A>yg z&ve!cjo>+>$zTIvU*!2m7oV5#e1GKmId3q~AJFdAj}h`y;5yopKMuHx0ah0&Y8p;5 zz-H5pVGF+%7`uV5gX_T5H9;FlJ4k#biMu4}saj~^CFHU`WXM@WniHGQzFLkB!sq2V z6l}Hk&+Zvj@OO3w^jO0mcZ9iPr+LxDq(vI+VZ{k=x7T#;Ifa1<+Uyssi|~En_mb*d zc>hsWhw%OZ;rASf*dlzM2{tib!tcdCWM_ql4arsO-m4h=UUxa|2E*sU2*clEFnsr3 zE0feNA5oF;`b|vK6}8!We*GrAc;lk3P%a#Y4jtLg@|-9fM}v95K+NVY>3Hp1>=HP` zyjXa8htvg6exBdmTtDJ^LFdmdE(tCs@#Vy~N&JzpegIAaQnD+^nmI?%&~trwOP)$2 ze852=SSg(c)WJDMEGE{Zh{Q*t7IcLsj_Opd2nb{7P$?a=7@b-`r=;UYuIQO3tT0u2 z-nV{{!6!pA$twJBpx=570uFOm;NGW^^eWkSNSmviRgq(KlXA8nLvuwgrbwQXJY|kl zlZFhFHqq4Bj?R|0-qh%2_IaLvCx;+IyJ7p7DqbQDDSE={Bc(P8d#EA# z630;9@1PASf9e@;&`KGsPI~aj72e=-Za%$pS;wcqVJ83I%Lf?R+|&6LSbYF}l4ln> zIG5BgY>vskPUP8fjI|VPHmSNo$%Z=#r!+5l8!TskXXek|#Nn@h&H(`o=jO%f(RWvT6k&X(K z1Pb#VNQ*%5C6m&4oZnCB#C+9W=a`)9JUMx~vv%B5PZO)8-~d{j417Qb6f)`(K0d+Q)_RUvkf-F?8U%q6bmxo8>LjOlHw9##hXaeFRQ+QI_$3}*@Ro6@Ls3}B>} z=~EcF90)bhIef5Dq?CH~LMkBq8>4Nd)tg)tF^> zM>m|m2RE^v?-9w|m8xl)5YoW0?`hL@L2Mz7ADP4X>^KN*s6G;`y(C8YnXXJY(H`@~ zYR+g%Xhk&=*&{*;FQ8kUt-!&n4s#7FC`^fS?f)C|e^!0Z9(jX*`1p z%Cpf_(1qDej47ij;an(T!*3xbBjU4IBQA>1de6L{gMUwzKpK&urS}oFC7M}NBt|O2 zc$k8LN^Gba6zuO1P+L=_S>zm(eRmH$v#jA{H78wmF9iW680qrP-y^ZQF63Y&W_>&K(1jm{ z1T`DTRM`)|7}P8xfvkZuau~~yKo-EvMDnO6aD@?&0O_LyW>aJ3&}>_nVmSm| zO68?!wIYeg|Dx3z_e`(ci&k3(CzWUG(V|7O6{$od8`;iTjFu~s$p^6ZGNhBE_@R1V z9}d`3liHWBf~q$$r6S~2kzjO9zT*G!TY)d_&?Zb*z?FeaIZsfEK*zx`obx>}rsdBfbR7IpQ#rr6eaD6kw4KTt&K@D3Ua+F(OS%H$|fE zAN(|oxj*)>~HP>0&Uao*_zt28t6dJ?(lYg|l z7Jrt0e(U(1!$+buyz793qfLmvpm_I$CUV-v>d*4y@(Zsmk1c zSFCg8|G+n%!N@Vq*_(}l{86tb2glrM_T5UjGO}d~GM(OZ(0>_nSvnfUYw6BrPRocl zhjkfp8~>lqnd0o>{&n7=jh(H+I%^W+lAnGzQlm zusy4#%#v}*_+*?i-igfGod~UU8H%U&O4T!vS&mk+80udJ^}o6yFzY3AQuHw4MN6mgYvGmCwO)w;m-)1U)5&j0=R5~^@w?vOWCoW|(6Rr*lZ4$+Y2Zv6U*JI1oVke-KEP%8Q~lIeOVwALit1ZY|`^q}%}qGSXF~sT1q#aM2yW>s6i~ zH&4#ra8s?mcK}DW(5K#Dj=JUPmipSg19(I%RyRMrp8p@dsb;Sl<3ci;fQflrXT{e^ zuyuv9T0$K>3sP919FlPD#C&hJbmTZ4aYt=&=!jrN<}JwxlnJ?4iKn*GSoh;C$vH7w za*wS=wnQ=7&F}DhUFkOXH6wjedQP_Y`f76EA=yZyB1eCWCyRIELxx9n$>X|bLBQ)N z)|987N>==vCMXFvf+=b0gnIE{-2^9*k(O66P50|hG_9-M+sq)=#IipQhRWHUZ0LmW z+B&>lEA=rZ&+$BEcAYbv@a$uAN@rwl>XCl!tk-hnxLT*uT{l(ASnFl}M!&0>$~(NU zDj3z;(cdI1-L)BFJ+vCnZPbN9pr9s$@?@D?N1k^5LBJ=1r5L}(_JP!Kzk*x8kkgC$BVoj9c}(|g_-7o;S?|Bcg!t4N#s9WxV!fO#kVZZx zL&0&WglTA9jxK$0ZmZf`u~&E}1`*@=!DZp+3eRP=2m`*Ice4L_V75}Q>-*mBvf1eA zUml#>Q7-8?yhZwPH<6(ULQ34ivCaAPm<`s3T-mts7A+wW2*)$>1?kFpHhnR)04T`4 zn|sg5eHZ2aNjk^sIn8{_@$7o=W*}KvaoiwM&V291IggFLIOY0R8<=y!fk&D12Il-F zHQJcl80KmjbG4Q^Z(z<}8o`Cg^LpmIfjO7*GPjZEYnk)4%=u?~88TY0|zrn`8t*I@vZpQtd>9g{jWO>`_yH)>YNOWCo zO<|7B-s%z(?Zgjlp12+Rf+0tR=NLwF!409F`f&#jL6%I^u@mEb!IN>mU=%&eWV=z?&k`ah;FVPFDP z3~sBXPF1JE2qzOGgREz1F> za0zNU=?4k96)qp)DQiLUT9CX3B-cT5y$mduifX`ethkB8bJzf6ZHJ;NJV!y4BZ4&a z_#N=#7`QSp(HA@po}5SnS5kbzQ`3CG_cMLLb#yp_FJj>pe5nRseu*IY94h!CaAtTa zNS-YaqRwd*oJsQOK|v__P%4)XBS=^Z;+>*__i6AJDtG0$VV^Uc7TnaNyf|wKVy>Z) z{WS6{jd-My84LjHpbS7dFN2Wtl~TV9Vis(8Kn6g)?`7+9yd}$doQ6&^qIh>MCrop= z+&rJ|9J|luJlo@PzRL*Xi2?H-jk_}PjSjqaXqq$j^{LKzBO{lC`*KiUJh<1>IqA@^ z=$MsGoxonOJ7;jN*pAX*M$2+Af`Qa^I+m=A+WNvmKra}5oVgY9>i8Xrk-3-ubNOHV zN67(a+;fC#^^6hHE0WGhkZBsOc3&W z${g!nV#wG{W824+bxh=V;Sq%0qi90yV-|G0X;Sp3FvD~p^yl}dDaM|^gS5?WgD8hM zDA6~rXPy|KCXNUkP3!L2D>g&*55FkxUtiK8_QCdyMIF)X<{fel&V3$hmyL8fZaOZ4 zhO8(#Y$0?+c+7lwh0u}cvIrf~aV_NK7OY=uW13c0d}Ul?!=p_rpYPq8-05nygt8_bCfv7aT>}+TKi1bs5Oeo4^D;%*NjwsSgJ-xmly}%Lc z;fOl&-stDGaKw5z;%B5CIAR?f@iX!v98s?y#S+&-KO!%0Rhu7U@h+smH z=7HU#>nJD1sMO&dsYA&6<==0}rGkg4Tqv1TGM!5Pi_RG0xH-x%@f9Mm6#}kbn3MF= zSG~GcR7eEqVC5E{M~t}5bY;y1w$k{&346L=PaP8>XE-~-qKI}O*z$QA#pvh%gEpam zp*kUpxCWKN4sL%QE4rNZ2Cn2D@c8EZ01L3gj$F$Ih7}56hXS0SVp$`gFe|>k5RY=s7_erz7w+G} z#>cgEHcWSgW^xh+B~A!}{C}MPts~#Ic}=Q7GpsbDQ5mTb85 zp(K5T19Wh2?a6KRJy`jsoQaikVwRG+<-G**99q}AOYrQnsnAEw1xe1Bic1PSl@oq{ zz1zRzdrd3zzUcifx4)P7IhVhGYkK(mZ65!QZA~lFd2b=kw6@9TX*UpEC%R7}`^zqp z4uI($V7Oh8^D|*gx2J~boPp6=Sa&7|LbrWNSa%-%+&YElNu%guq>4!tpIR2620f_vo007F2{6oSp=oig7MZ_O1C#V970e!E;LfnOdhcc zD4Ob#<@&b?+??qw1ky$`n4!$>4-h(uHo274=> zC_?=ga3XCnztN1ahF>kw{YxT;NqJdLON|e#^{A(-1u3FO zfinhh#()#i;DqSHj~2wWokmj-i^7ZW(ih;RyKPt&VwC$j5|sN$UVY!D5xkJ)#%W=< z11Lxb-RwLPbJlHV^N1HjoHTnOt_wMmgS9kvZ=QA^r znF-;RKp+7o0jFXeOXFBnkp)yJBlV+BIRoZfY+m!Y6?30t2n1*x5?I8`<(MW z@B90Gi~)~d>#nb5pbcYOGXcA{koQWJX9ya@HD)oEytVZH7dRG;g-b`Jyfdq(TW2d(z z-XQv~WfWh~^O>|i*G$H%CZw?2jX-wCux?qJt|#kCTHIMdQiy}$)aagK%DUedc~#@x zp9|8CJ!7;p*GyL1cRF+!oI_I`IigBV9QeH(k4b02 zH$`zOTC$uoDGwoQ?_WuMqlmfX5N1m>hH;PY9=?M!|JI)jG{oW352ERH5AX&;iUSk4|8rxPb-@Ko# z-r~*;ZY7LsG`nSiRkyID2F!GGqvjU)HJDnA%jj~pP#Lqb#c#x)VkCYZ)(h)c+ihG! zhK?@e-E~>UfVEje2Q=<-*DJyPheKxETF}4pJqaFqpZYe{(#Pb77($`HEhEZ{bv={o zwqU}v1{*Oqn_%Uz6hgHEp`g_DasbNZ`WiZHqGNU1cp>5{Kxx^8n4{TB_j4~?x1gkz zU8Lm_wl6dXL-huQ_w$UNeHY@Bco&-DLb758$YZf`f@W^jG&8pYF}!F3qadjPwn{T2 zO7OB0Qhd86MJm9HloHk?A)^uVWecaiCjdqvn6frT_)b_u(|Y7@WWngmibJ_|;*LkL zrGs<{Nk6y(le5rnsX#){=O3x_<}(V94YT@#7tWUQk1j8smZE@H3m_;Uq#YuYBwk*& zvUr9DB>h{QvRV88Fw>$N3(%Fbcs9ERa!p>VHb3+b7s6#u|8-{qOU zHmz7#!t*mii^wF3|j(T3HJn|+^L zRB{Bar*(6b@wH6lMv!O^xskp3?g2k6^j!?`)f&-S(_gg;HP?{~arN4ga1GB$<{Ooo z0nQSLEdOY^(E2FBu!~%{f@e|drz_?!g6mvJKuO_D@F12 z+(Ofrxpt|Uy{<60;Q?&o4`TX$j_2EHOELjlccy&)TYaI@2WDhZCV`u;aPujqHlj6w z-5$X}rw)DnP(E@nLGa8p(+gKL?W(e{;%JfKtt$Ez2Yk_qK_>+~6T2qEonvh#-S^&s zT;+;daZt1iiFtjC!7I^h$FQczSvi0YeTAPNWZ>U;~s z>1sX|{Q1UR=C*S&lu2M5NlMUsFOdx1S))0&V)OL-NE=rA$+OVC1Mc!|Dx2Ml&h`V? zAxuGY`K@asbRGxLy8$S~eb;X{^^x`MOI(9$^nd&^qdwN~Zv+LjZ2HWi!=n_AaRqY{ z;y|QnFvkk&yLKye=63BndWpH{`*4##IrK-=bRnhLRz`vRAaX`Eu{>;S7;`sELcM-Bfrkpj14!E_akVZ23*eKcb)8m@$)q>r7l zsrY*-9Q^P9%=Ir77Y~o{d3o`;;cN6sl=ZK1b>GhSFEek?@cBAM%75eYY5u-VyU+6Z zBienA&tGGBd}EmP;Pj`MOF8oo;G-5)kcsO12+mzeF5H(&#|*!sboB5?c3=P4r%Lgq zdnvc-O_nBJN$AKAi8r5*B(DR8?6Zt^&KrK^#lhjPdMV9H8#6iSYd+Ve6wSA*sp{Et zsU53lb^Qjb=mzSzjvfBc%IhD~&G|byDkyYAXGbKCg{Xhn8y-{ZYKVUw2l|#i-bnE@ zV~m%LRqIlC@8v9uDoiG8#~!^zQ6b5S0MwJ{aHqGggwx~ke&_R&e>j+LNye7g{vT5; zplkyE4}zpvprCLyhEP(w%$)6;`LhkRFdcf@=bxFoq2U}3s>$HMBK~AaNqoLBFGOBq zE1zN0Um1287b#CMab;s3o`*_#m0Pn{-BZcCA&N>=QFttoErUkGr3L&R#qX;Ah7}J{ z|7t%+3$$iq8|!bx3;5mO+Ii`k0i5BS_Ck;s)(kM>4V?Sg{rT0ij40CeIOU#3T=?F1 z{qN+3q{<&oy?-wq-p~6BcLjFL-Sw}N^?ri>w)T&`{v+zntet5@H!`pSDp_DIP}PX-&f_3r5#d+NuY5xwS-_xEe>`LW|a_KdOSQ>tngkt7Pm zwj)9eeC-~izZ?IKMm7(qLo`|p*WHQm%r)7Uo}cpaB}uw^|7FqgWy@#1@dYBw)Vck9 z;qWHNSdY)|xHP()=l|P&zA)Cf*)z=Q@xcZfwwBM@%Yz{R!T-{8gD+hg-9>}D?B_-f z-wSUO;LXf}-rKBC%m^D9sAB5|g9-vPY~LR_y!Ci{Z0Z({f>p9;Ie#)Nn}n=P<)t6; z(n|KWqW%6QCswwGu=H7JRt@x<>r!I|}%+#&i7d{|3l?F=9dZ`AhFpLC#g}}}7NfcPcY1HEG z75aq3d-;?pai`njWYJ5_`U1p&z&^9S9EztG0#BOw-njOfS-+7r)ysih+}C#+P~!)< zpKJutLGK`9lygnbda2E(=k~aqj#AIeH0ukI1nlA{Qi zAOXlr9WL+AB1%GdP-@(E1(b^i8~tOenmp%z$?MxWCx2kyo3 zBseYpNlRby6(CY*?U5ZWZ=T~Hwai+{-$TZ&8)%G|aBgxlORy zZ{5SKRyIoDtM2+&u_Vi$(y#U_CEJ#IW^eQ5k9!;w+C~7(GWv3g(U5W5=<6%A*-o2< zT+d|C=>sh1S~0bysUQ=bPi4MWQ9=u$_WQvyp{#?t&RKzcTB#dJb4J>Yzv%V!z4G3T zzaZ(ygtO>)UQVEPYCe1WVHjj5hhZW9(V=3jifz4Fn!(_KbFlZjDIHMrlr(Ahg-f$G9EcTeBSq?2BoKU)35Af=^dkP0 zrQ0$HpiwNgg4;#pf|em|v=B5`WUk7)_Z-SQ0HC?Fc*EvFoDq2)$5T-BAT-F>z8Rsy z=g!T{GV{WSpw*cSw9*RQb=Vz51xwKCrQ7 z#{;IJ;F+y+8C7P6Hxh2MUbvqZ)|#1-bv(C@=hpGuI-YZ`hc7htty|8$1A)cs%4>EI zH?t3WKw{m-z>d)jNKEdvEB?-#T;WEo*%{Z%OcZhnbZbaAk(CW;0xs;g8f`Y7D62d5v%_ zz{e^c@SIz`5H_#{9#V{eBLg1cH`UWhvo_qs-*Z%2de#@Z<avC)pr3dP6HGj?nlfL)iyV=q16DZ0jV?YyO*f9Eax0i&PG%gu;OZNWUG<=+sDEUl zf5W1Ip<5OK&Z2pt9gAY$deAen0JC9aEg&rdBsTjkivVd6AZ-OCMiq_idC+sNnHf9s zpyzx$P0>LE|D zH8r?T!OLwlvp?5tBh2;rn^z2p5_k6edRK82sr~s!r;Lv7-{g%R-+OM`iRaFx9wps~ z1-)=?+XvX#*j`Np{;e zc-R2$so=XajJ6N{+uZUVWst0A&3JpSbKBb8{7vF-JbyRxH=n;4e|MeR_UeVk`nf+d zC)D2XnbH8(XYw_wTQ~r^?uK(p;dnX0-N@7%D77?|&%5}1flo4!gKrp7^>rLNaLFOp zkmw}0J34Wb5gmPq2O>rrF8znry9%SRdk=dC7t0FQx*^n72^Lj?Va<23J6Gy-wcbr$ zlhThE!$xrLRBYG7o@^@-fw}D}h#aOCiEqpe+jJ7c0 zy^#esm(;*)4nPoY#x_R1^kY7Z`~@qYo~)@XSQ(kD>6{O~t>Q4dCy{N7*Y%=?a-hjq zYPMZ+u9364pJBbVhZ|mBpJ)*mwH}xk6Iv5uyW8GfLZaBsM%&?l(f0mzM%xo~76i8z z06;Nji!vVq6Vr%wFd_35`!-s~J;q*IGZA@)+APabgJSG)3YB-856)Y5CgeC1WRR$R zFGkm9_mC#vx~V0dvyw=<4f@ zHlVeUWaB`idVBf^eBDQI`T(HU_5l3d1~7?sR*l0CpG~AZWqBG1u&|aNG@>gm3dJ?@ z5IOQKm_>?su^61d)~QI^CW-bAUPxk5fldc62pKAEO~VT<$-O97svE2ssC5zUiQ-&) z4sKCCrSd{|n{Gq7uI)pj{wlW-{{XAtsNVcxQrA)LeGy~ zkYOkvFo50zI_W~Ik9Irh!ueeYgVXuWUgm@rIw;y*5b+)$!qgl4*SIGyR`3gtC-&B( zp5A%yup8d%l|SxDmoL&rUPuenYlPN4H+KCmJ;P%Ye(D+Qbr3A}*3YSzxay~#g35+B zsNICmPP=LML}Ptub&@KoJyAxrsUnRh(l!Ttp<{FSSev(!{k;8C&!^3avBIBuayxqp z{me6Zh|{kSd;ef9NRGXwy|Hio%yVUNm)itt>GnYIUbIl=Ri!rCpRo($o?I70>a)W$ zBB%K_vt#c#O=x6e|AC!5vkY^2?a$5ls#{GP_|^WT-#(MyE!Pj8?MHGd#*0A!(|Je0Sem&t{)Tvse`=g@FS`B{^_b&0n@BsKz_GtFL9Gd-IdqoZSdklis&9bgbFgO+$Y+tYGlfs z#XmCR_7XOUzWEbRup=|+Gy;9o5{j){LZ_>tNyWI~9h&6Kt5$9y39d>!uVWsU*?u(m}wd4Q}~KUxMMF^?B$<(dUu(e$weAuPw%J0TGwR8zxRUY z+|E}Ue&M;M_URXK);5*L8$UGa7xG=2+GsulOWpO&zk?B#QahPp-p}yEzcVJv#Zkm( zb1uHZ&|`=LOsh40rsOK}((?v@ziDiEa?u;^N|*z@~5gJah`#yLp4mQcg& zm&@&B03XxcJR9z?V-?xkwL4nbFbOt`txi0EGy7+&W{s{}xT9q@#A+Df9ZTKW%`5TF zBjgp6(!a{Nwi}nuFKGi&rWyX~eLVF&Y_zRnDedc@=lV}qU1a}gKhF7C5hQ^sl7%Bl z{YCgOswR0>zyOv-<7r0Fs{L0p{y#DE-#Ma|Cp?pl^|e1O=X^UOv-YQEd^}G|{_{9oA{-T)yz( zD$a&gBTU`)J&IEr*g5V4r07gGrPNwf&})sNYIs;%$D0N(Z$Z zz=2g@rUq5TK!(zekM^3~L#tZcX1w_)Mp^u`G@L#!c!KQTwcjg`w*X-sbG1{~_#L>^ zsMnkl3{ZV3*G}ff9{82#BJV~x^nGyX*xX-x#>R&J+T&y6|LacAaP#TduBSZNT^}%u zV&#u}Ml$rhWK!c`yVHypaTZ13%aEq;nehm8weHUHc+rQSd*P{IUc_5y-B|$|_#giE zEN@-w;v$BHd3r!G@7M8e9gz8lUH(Glt_czEQg61Vv>Me&0bF&ohg|ni@iAYt80W2b zN%7*Z0y)!GhM1J!^y7<-_09u3x1X9sCFif2w|Qpo#64ZKb3)`2@&c&Q(BB?Dj@t!i zIrMQ|#~kzS@|^pzBTjIp;L{`}ti3QZy0$L712=V5aLiMASDT~#1k?HLd*!{OoF};h zFLIS;t9I!YKeI^b^_TM&F&o|`mn?oCo+#}x@R+-P+kdxL6BOUSwyC@d%<_hhyxLxk zmF=`e_VEIe?j2sHD!=Y)Ox2Rbn=>g#q=kn796?CbvQ&QD!r%0Sr~Bw%dcrffbO8;i zfl+RMmDZl)GlLbWb=NvNYafIK32hgou1$*-@Agc(_#OJS2@=gXhOLVsa|}W z1I2!kj36ahCGIVsR^?qXX>pxll$|zLTHoI<_*%*Pk}{Tjb1|N@=$60W`p)`O*LO8x zrQRj)E^c&t7Zf51*sKEiyu}@R@7JEZ(H7k&4yt@njd2lUDXo+_D938GCvk6*HT6hvK%66=)-yC_xGbLD@}(Q~Scr@U28+ zdo?H4?m@W=FwHN26NH>^HsC#o3NlYG@Q@1qNP*s65~u9f^n|INI*w>(N+bd z)T*KN!)6N^(;37+@mrF)IMFl?Q1HWzim&x=@bkAP=#6ATrbob;e9>>u@|e>zIcaC* ztf|m%FAwj@^G42rAKIIiB5AL=bA#_rVB=0fuVYQ;x$)>(WC5b<-^;5*nmK}yWX61R_lx5LR$%J zOhk^R*7t?v`X&w~O_EyU@DZZsA-fCEGHbM+WKGqfd7_WoCv1hu^>yUg_Ut4LNT2pQ znf5wlFW~}-Yt;m1H0|+cvc5>=v(7>UP9uzLrr`h&j>6&~t5D0Q@-`$`-%KPb z|Mpe0CYza&OeCrx&t9zWAjE`HAc>Vn(4ae+~IMUbi>Xi!4-5#KtO|)9P5r;XTi9iz@jS8S8hxgzQ5@0+4cu z{R14PFp5YJ<$%1x4ha*rrBNoBRcAKB2;|nT;>6b2v8S=ueeCA`4k1lv-rTiE&$PKO zeAY8Gw+9K>+0(;DXT!)C0B&JYJBfQ|xpbC;mNvmm0Wh8qe>lO?X2!NX>lvJtTI9V$ zh=|RO{pMNErz{rFUb~Fc+HL*^6cyHEFrsCEI;@g<34E>AbsuX6yNm=`msTWTZFYMv zv!>eU_IE5%+Ut{8L*an-yY{&Dx=z!87(^2Dsoj79KJy$xEtHYi%sjU&!Jd{{tKMv0 zXK!kQ7xQO}=4064{M8nFBOc7E&Ys@PI@b>IMw|_=z5R|mqv;#t(U~cT*vxd4v)FQIU3!A!&|W%*a$N}g)p(JpZARYSR{$%>`T{3$L{k~e*~%jK1BSC z*f6gLYzV)R#0Kpf0!aEN5TqNyh{NDPf0%Dtg&1wWWOJ!DXwb6WCRh~MSj@@*jx*RD=pv!C(uduIAGQ?`YAbM3Qf&-CMW z?zQO;P2CpC;o=wPd>9-3J46cE&$rIW%s-6DBn-TjzZw-;4X6qjt;F>TPoq?Dt2$OiKj7F3oO&h7iUg#d=qrEWnU72c5x0^4aoes<%=8Mis|Gmf?ou2;tLvOT_NHrU1i7ZJo zv(E-rz&GQ5s1vXZ@CFPmGGfU*?RY#0g8W!O@5S7gZrGIdO_S8wpY^xyuv>rDUwwq# zI_%b;^_QR0Gk4gnKkF~BhM%azZvFM-75Z4D`Exq#=0ngiNgt1;f58sB^=HZ6fBLrg z>vhk6ih%J4EGlY;*9iQh!cuWfO*T0Cx=^JYIm`2Ma2K1=T`8i&z{94~~bg0>g6)0=Croq=OH# zQeeVoVAS%!JFBx_q=nUy+f{(c^{SbdJH92wyk#=iHH=x<=TeISFBIb*Nc`4MF6%em zI;apig?AX^e8!63cne>+$5*iPZC}CuxA8Bx&a;5ldITondUB*o(YJmr=j@b9c`v>P4rYrxxR}86ULNl*fJ9Uym)DFLy(&1#U$KJz_hCA zFT?bG7~ooF#O54C{IC>VM5(UgjMaHH)E4ESvv}q1)p^CpNfl_u1}AYP?jkR8s}aBK zD*VNB%$qQ_PB&rBc>d4eK1c;}GRAL+^Mp2C*Pv7H?~p)y<84 z<(OyS)jMrR;*h3HR`M__={OUG68bHzB)Oe>H??a!(Kn~=fI3E-;L{k$BP409chkby zw+?v%f9pPnym}UWT7T*|H7<=)<8{Wm5DXUb?EOukH649pD{}29VWX~I1L&$ znH)$WJO&*r&FrexO}>0|u2Gj$MXZJ0EqmIj86m69cdfBqYZ~N&aH`7mRq4F%MLbwU z6lp;&_rOmX+cbX7h4A#>F;6Ns!Ft=QSM1A4$VPeekJTqR`bHfe;+ZV~QB3Cq!H)V5 z%vGJhknE7($?-c6i@ z^wtknj*ZU2WML4hc~KS7=2JbVLYxOtaek=S*Z0Z1);@dkipX?YaQM2; zL?bFcyGe8eU2Vb%5J-6$&GU^mJkh~sEJ4i-*UM;a-zoaA6mcoxvhK;E_d#OGBk#K! z?mWJdXR#>lA?mjII;#INLa&vb?}dK-p65l67-{wKaHyoM4a7M)l86cxpE9iRcgCCX zsk5!(ij`kHb@_G6iW|@QUbt@45AG=s*PU9uX~R8p3E!C#u8UprlBcjAyQP1{%Ii;6 zxQCyT13$L#B~S4@w8P^oNpN5Y?~I2|qo#94MVnT6D>Pbmg#aN7g%~26pZikVp}ys9 z_HlQa=>7e|? zd^jJ7FbxDCd}~~=wzfp=1P=sCg2(vV7bqER8l_E|61IBm3xDtwVp&@D2hu~{geJ;> z`JyX3Gr%cyn~o8*39#=FP$WCUyX+-4YqfmXntO%DO<+D7R$PCofxx2k!8Wzgxa_hm z4X&C~_i}B7bIlbvg(%b3u%gC(cBpfGMc|YGM1{8EifCKE!i-wjox>>T8hJ~$O{n8S zkUc~)#SXZ(3n*05xG$I4(QE=-7_)FsfXxL6lg=EV1n7q#U1J(RdgfH6#YLcL1{$xg zp$jmoyrmk|PG^}PF$-$wbv2%v0d;n;htB>-*Shy*rADsK(A@9XLcNpXx?a({-fqve z6yD-o%koAQ%a;T+Ir=jJ^h7s+e%S*+ajsdXL6ioN0th)E%@(uHD*kDRS#LI_Vg!*f zu)A~ycpU(lw;0tP$e<&(ZQd+75#riY(4-R^)iA8n*3l_TW;Y#SX;w1=0lAr3^KKgw zT`pju%c8rrZh{#h*gl@?n8jVaq7OobM7N7D*4DZ$! z@@o0r-rlFU$Zc<(0nNQcnT&CK#`P)5MnS3VE2+J3fkN)&h~Ce) z8*b-ah11s>pBf(6W!Whwwbta`eOdy8$0^`@o@he^Krm~X`c9I*8tLee`f^T(>Y&B# z4dU#=tk|cx+3ws+=icB3Iu*dpy}YonfDN=d-HefTJ+mP|^qZPh6RcVQXomKx}~yK8+?d#eFx0$nb z{nKw51CAau2E6$Nvrp!8uNecL<-uq5Y4*)5%qh7*KosVTyyee~T`Bj;%$0-Z=21xlF#&-Y|j;tSO4457>6P|14@Z{Fzkvz2+ zzB`f^rlq&Rf-Te1_Rf(ZQNmw46w;5iUmjpC|+vLJ{MK1ks{Pp^O5S@zAEiiY2Onvi~%R%ZtuW8158weXl6%Sk(41| z6!Sfdgikx%8)Yy}%eSfE2)IgOnR8}pE|y#%3!2Q<6#Vy zjA0Dp>Or%lOEOD19n5lwh`T9b>t;1c7NhvWubbI@PO4VuaH81jFyLRoj^8iONJNL&3zY3$x3fRx&5 zOH@x^f~j_mXx%H*$I6qN{IGm$`Az9u2}!8GqNq|39TY# zX>k4(VEiZ$Ejw`~@j@t0mSZr19VoFCjgzotQ76H^1`2hG9j)D*bhG)xAY*V;YkT!V z1eoxc(-0NxrpU}D+Cfs=$arfQ?-K}0(^B?}Ygr)8!3uxuk8gYWWN5zbjAb471WZ?K z%yIJVo*2;eX|?#1^eG}csnd{n`Z7A0AL2P#d55GKIECdSX-fg%VJPWVti|2hvbq>0 zI}q0nydKgtn8qAVC?u60sIvYVk{h$FB7e2XHSCdu3)rQv=uA?vp6lFZNi%M8o28p_ zEpK8s8L|%Ik`LP*!Y%+hqiqm?^ShFNbv6co92O_Qy6-I1HHzsc@zyr_$k`_7r{Yg_ zrimQNGXmkvl9TC?+ijMV>7i^>S< zo6_loW5!a)D+!7^ivd}-F}hw^} z$XhU_mzMRLefYXi{K$=nC$R80VS@{a4_;UJOy1h!XY*b$5yc-~oA(NZ%q!UNV*f|T zvwf4&Ro^XsCU2WLDDzDu=*J6<`jynKP-LZ^(fzfOD{4oVyg4-#KRO=+AZ*o=On;Nv z$Nya6b9v7eKc7dDuIQT&ewy88t8ajzd1kqcaXGXuy&(_FZ@o*<#9lMAW4sb~5>R=8mSD_>A-K#R zpQtPlT-7NR!Oeu=Mr?wc864$y2yUiLa3e2tib;Don5PBFpw^ufj}mB{A7B8QhnZ`P zH)+IqYD`Z!b4Po%WG-1@59Uja z#kz#hY9fm^12jo}6N>=MyVR5K{rYe_=J{M1clsMMF|az)Y+BggD20ubZsQu2QA!pr50r${yVu-<`>%gxM(Axs8?tWvdo{b6wM8WWvX22hyb(kw%d(7P zQ<)B5KVzSmtm0I><;JlEbh>~}7trAXI=q61n;De^uqrf)MiS^V`F#DyRa+1yY@S$2 zoJv*Qk~_ak9i^#D`{sXTxv}rqhgZBX7D=<8D|F}djL@C?-F^1czSS0L zL)3kE&7Bdfp~F!G{=dugzwXM2)GRmZZ(u}k@bWm8 z?YO%rc$bl#S&f6|vrDt{b>hhzuAInE&4H124z+SIxb29(C#mqKN^C1q@2aT$2;R3y zinotQ>5E)_x9P?j+rR1e)Th}&BkNsebpJV_ZLaSw+jg*zvF$~_@v!mFmu=gBPC3^s zu9@46e=gg$96jwC5bh*E-n`78{}WesBZU`OAsp_jxD&c=G?ze<^>Zdl(95dH(~gg2k7+EQk?!sNtM&&TY^IyXH+5V36Ha}DFs<^8GY z&NH>#+mlM{^tz4sZPo>@?X}oISMg&p4>??-tKJU316pwf(cG}a+Sf2`v6f~3!`5T; z;u81qy8(vrrLUh1>$?`xO! zoBde^S(aMjqSO)>vBYO~oppZ)|buRpCam5yV=m}Z}Da4hI zXTN0SsBH3l;kmn%;?fado6=B6d%=@@&AWhd4;uFB5%GoKx7ae$T6CaGf+pySssN52QShYCxQz zpWT}Rs`dQFyt^_RW-Ty`i_Q$(7tRRXSp%n;P^SV?re#YZu*Z$S z0}30nGxwb+7Cp9tgPok~??N^&0u!_)-o=g~tkQ;G)kPynRxwD|{GB)oY)BpZUh2m{ z_PlD~Fh|*TnTPb1yU!GS0LIw~>1b$8G3zkV; z6|Dn%Y~zcz@GZ13ruE#&G-g61w7DBG(KYSslU&!n);`xWoJnj)g-j4J*`JMDTszC5 zYty<&)u+$pDTHA`vomEy5e;?b(lM^-cY5#AUlc5p-urr&59kIaF#DQqchAkp`TIZt zy}5{a0Fv0D?2Lhb7a*Q;09IDSg>1;M&i|er;y3EV zJhTL#Y3{w7eBdKxM)d@wc^y3c0e?Db@#-tuW6F;(cyAZd-$4qB&2^DGVXGoW+nh3E z;s?yAC@_=Rq_~aks>HIah?IH=pkc&*eAv@}#LzS<5M=u~vdgIs-VnR&EzCgdDoH6+ z738F%kEO(1HRBZeBb{J2TpIEWn_7#PxW}F zpX>2X_fxI(KxVIP3HSNd@Kv6{*J~!PLrMOC*?yN%OKkq&sBg>uzUORvwW{G#MNDjk z={BOL9pn=eMAKv@7!3q^lNVM_&u97lKJQ8{e~*;$58Sy_3mVwe&}-M^xi1&oWGrBIKgVeIUrDvgshl@nwe!+h{628y&PxkCgKx5rMA5w& zJMEXM^ehb=a8KJ-q33u<&*}L&*~YPheLu6!sGZlRpmyH$12>v8jF(5;#0i7b&1MdL z9XfBiapJz|#*U5CjUs?4D(q8Wt!&IPS+@h3S8i(qYH2g4-1)?zAZoY=B@}z|!O>}3 zn)GzP+NoPE~ayXDyDAEsGUm`4uCx^DToDfV`}^4!bpI$Z14pLio@&o3FE74bewk`4P)CH1V#> z8`+5BupdA}0HJ`3$%xq65ZVCR5RQDbi;d#QN3D}O_kgO@rsSh}9h`9g#0~+;7C|_u zfKpw9o6c7!tT)K?ke6_TKuRg-&W|ME*|`E~+;IG##0?$E;*)U0o_KK`+^`IKHqT=W z>WCOy?V-FZY06ouU=$N$l z&?uouIbO<JHQ>~VtQK(@5)Y(B;QucbE45HlyZna_ddAY@I7 z4EX*)2;ji5ywpLS=|H0LUeO64QOEDAheyZq+iBQocLmh>IQ&x@$V14m&i2=}rq8Cu z*f`R}To|jP!q1%zq}WV_fVLC?V^og71{xCM7871UP~LdM1ugO>R?(T5_w=dlv74EV zdk|kuc$w;N&Ewvi-17nC$m~$Do;&CsmlxbZkrro))8*O!OX0`2`E|S#AMka8U>-UlS>|7s|c6|gv(#~}jt+bh12OaMW>vnIe zbI%%>ARV>qi<_LAbarmHdqinFjgBblb}!O-@4iu;_lBecc>$ie6nV0#lLdLY1BT$x zMj2{49a=$prhB=yQSM}F z9Gw0*%55P_t@^fUtLsx@|EEtzt~GZo_O~(kHNIt5CkQ25Q210{Wcl)0RQg+R@9k!_ zLuDWc+x-ML*WlxL8hk85HpC8Z2RIj-4YPjdBjn*cBl;4b0!K5NoM|bnX<09Pm%=KX zWfiQ%rWQ(5@IrCQ26r|~>)7E$PMxI{DHYk&((XnVaxz@1|W-4>f_P8WtU_|*3JjY3m=CE-!=kdL|le9nOPLXyJ18|9VA?+<39am`j zs~q7nxT$JO4XkSuI;lEGjEJwAWp=PGu|Ua#9b#RE#ZCC2*p{SI$8n*8mO&EZCCRG6 z`*2cCOUW`wwWabE`ZCPwrKwR$E=;#viS>1cLin3R#l=${{Zk?HHgC0nFqme9ahPkm z@VQ^MPo}%O@R^Q(e^Tf4ZT&qvr|-_t_P_PWlLNPq1y+)glG6MCR@2@w>(<}1bNaUa z+9Q`QV@OJl)pkT~?bwdYwuL^QG`To?a%UR0OBYX1#ZKR5qO#5wlZ~L3Emri+;j`bv zruf)0Z~lHhPm=4@j0o|+lQD=9gK&^*G8^7>8MahAPsa)bsdIm4j%hs-INvz7bAD$? zvj~OuYuD$L#9ru;`u06(p@N`;ZDxV``2|<$Mx=^wB%?97)#jS0Zke(ww?|! zL!peC_M}-PpEL7}92FRH1S8$kZQthhO0yjG1c{Ma zuXLl0kN0JlNjI11_s30*6q&m@@SSM&q|Ky-xi2!4b`yIoQtZq-9VA&2va>23484JL z;zszoYSi8A8W<#1ExNvs5xuCTeIl08uaeH!Ml#MgZ^o*;lNg~Z+(!K7DtJA{OJz|u z6K2s;W>BKZ^5wVGB;Co%7$88PskzE%tIf!aR1m-8BOE<3n-GZ0j0v(IHWU*kL0s*D zX-4%eS5k7k3WOoD>jYtH4v-1#D-NKVXJ@N8URQYo9W}GbN}KYz%!FQa2t)dGi&qOH zyHB^S+fxlzYTC<;KwUbYYZ{X# zIAV(c*~2u8#MQcO1(cEb61$ngw`6ZfUDtEPW~|RO8H4hjs7@M>*QQCfAg>I4Lo9o! zY-sHfW%X;*dYOL-fVw8Hg|3xBP2|(jzG?xV!Q~t z6;fqij30|gzYnHjmM5-91>RKX?a({zcE$L|U9PPR+|NryzT81#gAG?UQxQ> zi9pG;_DL7Dp3iqu_@9>=`|9JjIEf-u-S_jFm{jhza0N31~2qTx!>3X~$ z=uP$a|GvHYIPG0K+?en|6|P!HS{uvYU~ZD6St;=#jiyaVvHy?aBHc-vP1xs$+T?o> zFb<;?lU0^vIv3GzJrhWA`Z6m;+l0s;N7wXXIv1&xX9nz39FZ_ud+>?D>`i9j8$|I5 z@kF+~53kP?!YPANNH;eP=_={CJN@c{brpkp#=83%-QSIT^@MaIg>)-Hx?#pw3s5n! zLeEr`v}U51??1rR|I~29vN6wZj-6Bq;;jMkd@00BfOwJJfs#rPF9G63UI>)i}gU6!DT2A!!cW}O`lGWGAd1bY@tF3~w;+VhRLrX3FQ4IGfoSK3b9 z{x7oEE!U8+%;3$lnUS!7r=$jifEt5d9PxR!?6T>nSaZr?XIv+uB{A|*Jis*^CgL(4 zRlvzAWj*5(N=gcOP4@5l;n6yB#&yJtg5A1bQ`_oL?bKb2UtMAlp$iA|KSvS?F&)|L z!6}3%+()d!0c;S5kau1sDt=9IGA?z_-`0}@1vwkLR8J-$+Y^js#WaoBgXd)ov2&ti z$Fb++`@^C`8H!^c`WS23U&2`Cvtz~n0^adIV@_^P#fl-V#@@)z=>LhLwEj}Ix|<0V zQ^*`f!;Hi`kl#;iHGC&MbnYyt;}zR#IH*hL+!|N59WOS`eabzl^{&{b$7JLVq&-f{ zX;aOQuXB8cgs{Vb*sp^b<7^E2I_$lf5Eq#|-9(fB{}^=kyXdcgL7zO>@c&1iPaLZH z7hAXg%gE3F6UZ}X43uXCyj+wA)d?R%lJYqEbZwgY;v8?4u1Y$Atm%5(MD#f6WeVPM z6q|G%P9{j*lLz^P+h=vSj9``Rod99W6pK$m(*evkT;AX-exu%r(}1%-?|p4p^bgeHZI#qpGkA8(CO%0*#taoN z2KZuq=kx{Cy117^WQzFU?tx%2nAcWl3dNRb`dFyoHPY#_L@Wl;PyXm zKfVMr)3U+&vbdgtgIy%kFJhIF54{#aou4^1Nmaunn0h%7LB6xtjJ8f${;eT^k}>rxq0Z*10+5ZpOn)`_E&Ru;~dS_R%TB| z!B&Dmi^+GZA**l-@g_2;48M$r+qkI*-(@4vqW9ab`eTI?^iq#}mP4a-h=OQ2=&AgQ0!_i_2F67FCy?8?ks z>odN(lYM;H-Mgxi#78Q;Us!a7QKBSAB*Xemn6wt~JX2a)M1z%tpcEDI{X+iA`J2h# zJpSs9(&FXhyAkuMif}5UP1NwQ58T$krUQh8s8q(PCsc1KS*GQ4X`wR;2UF^pv!0D~ zrU)R6d!ly*op_R@G9t9&W}S}`_5$qs&f>~@ljJK zm$4%Lwa3yd+c3BY;)q_z1N|e&7NXc{`2;C%~qK< zmC$K^8VaW)m!33Zd&i+a?A=RUcN%NCaz#9WY9wr_+!eX!Dh~0Lt$FQ-Q(lH1 z?!V0p-C4ZLh*FhhpG=QIyfCB8&?84dq-V|Edxcb)cvt#DRNi8fkH!^zjPySp$5@V9 zY;ZoaVf2fbSVHFU+oV!=X(3+%y^T`SOAU=~5B3{jM9qGwhjR@3*$c_M3=HM@!A5C0 zTXqpvjbpsm*VQ+24Q-L#9KqmP`cHg+i;^p2^-0;4_AI0HC{yV5k^O8A4XdhO;GD_q zf2K?cs4KdAz&qA2X$ngZnwLMhxiWUo_>8T+U2Xlend}N8Xdm zUTFTYcT00kXkptR_=z~RxbzdSd;u9QNFGB|3l6scgltwM19ya7Cc`oDy}DiX8{yUx zCj##5uuhUYA*zp1RLNkp$d1)MDt-&V)kI{j%%1pl1?J^4jZ58nEGyr%`2hKP5h7T6E#bxT!S+g(Z#zE_s3jAss!j0 z&{yo8wulM}lW;#ziJd@ zE&^UG!_|D5^O#7w~=+2S4=#E&_1R7y5TxHGGmfSF-rgFO`Mm26OhY(N=~ zCdmhT}bs!{slillI$m;S{)I8%dFs*sA02){Fl z03FM~wMX`{YAwiPj+|DOg+zmpA~``aXA5T37dZvD#TIJt_%62sB^8K1#Vlt9t5Lyf zRF)@G{Us*pK@sDy%U9LvE)F8mWQMzru7CH@X=Ki zwF+HS7{kW}sKS8}l9JnOz-+3MAXHK-HhzMNBrluBqZ*aI>zYiivdtdCgDA7>+L6Zk zj`v8=3S}DGZ==9yGtaGZ8}ad`5x1)Or{gZQzqG^c{RK-d~Y)$bl;uQld z*IcGmRWEnp`jB)~l(>q7n7l+$B6Eu*pc~jI9F`OP1~gC`sClZ<_KGVn;p)S>Ggxr5 z?MVV%O5ee1-9pU~-MoQg*V1k#?`=)qdxFF{=iYBo8ugyu8G(PsxlV)0cPNFXdn?Eq zKJ6Zk1>HMH_VAu_{;>m++HVs3?0)IodR`NY4(&!_#y8ucU0MW z)A||D%Y3eC4DH#WX#3P)lybg{V*BrNVWl6nXW>qF&5MrNuO&^^IE}AJD}*A;f-Sz% z!u(0;&Vw@Rl%sZjJ5%6BJsHHc_dpu$dt34(^QsbPByvpyqNBaij%(4&YE%Nrdnn&p zWNCcw@IB8oY>%s^Vd~qR`d0H9fNjvdbYNLe2UzKT?e_Xwd5KMLwO9Ayf_Q))(2cVJ z#1bp32*V>eOq&TM=24c1YkGO^Ic|y>t_Rq8`|y6NO%0O zbGe+b9S1>_=%R+xflvyDW@G-#U4hW`vjJk$f29E-I&v57uMADK>svsKJ7R}W;O%l0 z?|_}EJDPW((@vsmq7Uj&m2#3aBKBrk#-KSm2dHC|ogMtY(!PCe(q9LDoqTPyiRozp z58^d<_|NY<*@!DKC3bZ=y61hEg`E2@bly);k+|dfAJVSh*Asud%ZUFdeLc>CD#<>_ zxzHOj83ufV_tYF8ao&^vC*VUem`if4oQ6F(K9SB`NE7XS- zIzWgbB{iMcn_on&b27WsPWr$VR-ir)ktLnpr=6H}76TvIjY~S(m19Rw?YLO`7c+b| z5Yn=`10l`I9(Xqnsq1Go@H7tTO*71P2f{k$$w+3lA}DkS7vPXHBMP!n7L6E{W>VMn z`)q(XG0A9iNw7}|c!!Z%-^6(6$ZPUMIIGiJ$+c2FD^W(zri(MpnB)WK9?evYJA$HjD%O~{3JCTT8Z%X`y@IWZ+;oRk ze6=guzJY^mTt>f99DH8s%Zz-0Ru?h@FG5J;-qZ_#Z@*C7V%pC?g~`o%{!N~9-g$Yc zdp1({1huKiiw=>IXp1=33MU;!`p8cQ zea)|Ft)&njtBc2EaL}vo=p_{v>}NhPWH>hTTl;tjDj^>A`pvHI=XsaruSH#zNSI>&@&>9ZwJ?aiN#X=QCgdPR%Yp}19dm2XhukMdk zdOwQecg=p2l7{B~SfkCzMwCEVq<87lL#c6nVvLqidcV70Q#&fSn@xBCBlCUSD>V8? z3JoIy%_x0>-y?Wu1)pU+KZ5sC&tch4J!oJ}8-W$uei$pZ9u63pi88F%D2b(2Sg~c? z_xd=kgkeSCbE8?1lY#QK&t@3geGE<64}xz^$u z6!9_zd1mh30(U=OWFr=ZgG~CrF_DJ?vG*!6g6Dic`8_x-W5kH>+TW3)0wzubHXvs+2sKy$gv#yb(#hkk0|-qh37T5 zzkVa9MBDaSyC!vPXJv-Ro}f>q0mRDuZ2(FdVPcn5Wek~B1ON$UAH|3u~|qmfuFI1#aVf+ovIa?O${3v!THP?)c|peXh>P9W%of*Uu@Cp>xy5e}-wl z_)neo))}#TuFeQzKQ$)4qVvDlY_Nj(s{d|3Yn+t$@r#ETF0_uO;kBf zXVXr5seJ-yIK#%n%=d+demHk#cpGG`Cp;`B2~?Bw1oxi@Cu@#yWDUl-7;=cD<*xFz3A$xbM>2EJ?d} zkVKvId)B11n^R_Xy;+*NcONWG#w`hL#b3{tvFjljx_)P0AJX)KKG~-^?9<;)fQ3S7 zTNsr1HO^29jhTCEupcj)U{s%+8fue(A>m@bd!W_S3g30Aip_CnS8a6Vio^#SR9TFM z)QB1jP`IRs8QM6GDk}4nGL{5o+b1#`r8)qA21toLIxnOdc}oIc85Y#3V5thA3{-`5 zk1_EFV5|fIie4&hWw4TA9jx-ES@Kg^2H-|_pOeVO+1PP?LyQ3z<7ghZwAXBjHJg*# zTD*?lW!r6r$&@2=+2{gGcKl^pvzK#>iH{mdTO!5WlH$nnD14i=1&JRwZdFoYsO>Qx z+zLQWBQ`R*jkYcekDlu^UPR-A+0QTcHzxj{^r2HS(@_&Tm6_PB$2^&12;*+1%XAxx z=+-s7?vS0zj;fTgWuMK+9pCL0htyT_$``00+6)G08nnRgGNMzc3ijbGI#9Bb{S9sF z0H-bKw9225ZD&e5TUn*=x>ImnbGCAs8w$Q87Mw+q!M4ZnKUdMYY&(;C851i~-!*OX zIZE6ywMf@VxBsYGi*1sDi7Srk3mL{l$N!^2b$vEv$44w{cD!_I|Ja~TZTT;YVp_?` zvJ4^2>S#FcPa5;2VC-j3y-SDYqhqk4hBh6!pgpE2npIX#egW5nMY{gR1?`rNM)JVO zIU>IV4w9LTE?;63*1jVs6>p+Yyvc&T$lq!!D}P;kR{ksG-QkS0Ph@)BH0raAh5_3i zT|Eca(9BWP%O*}`=2}kkdC>G_N+Lc2jXTO-INIMB@Q~SeulkX|)W@*0B1XuF9^e?9 z3(bC2zH^KTE@a!0w}tL{e7SM#29$|c-M(M}3wG{OfBtJUc02ceWOyRyZS&{<8{hxa z%!s^V^s=kzzs~*tFg=l9Q7!s$!;{dvBiUr0orRHeb{0ikE?2}&1?tz3g_p0gw(Ycx zS0?W=8u{CK>Ay7?$DZ)4nA~uC*|ysoh}J-+f7RVT_!V}pI=+trOPeS~eT5M!{YU;N zUoi7CIY!Bs`D-*d;#HnEvv;_Xkro<0olcp#9D9wlpZzS$Ty%mNW0J+;q}E9}!Bmml z-J2i*5F+KyP1JHg@CGQ&u>~hb0VBX=8*gPPDmRiQ$u<0;rK5E^k2y3#bVe!ez|t*T z+sd^q_V=NYN}qAzR_@8&xfvo@#Qh-mgIps!qjbu7?bd`wH}$R0qZS?=yh;c1svN+_ z_@5kb=j`vMv{N^{Y+8pzNJthLk{E_yZD$Zmz7c(}%@9y;ljj|3KHkW)b;M%SHsM9@ zF&yuwsqt%CAmPLZ-r>D)MAX&Ro~!GU_{+dvk$NeT4*4JUL3^$vH0|Ei8S9pwbeFs@ zDv*@<#6ol;qvX0OzH9RzvL5dgo}Nmxm3-7F3q-}|Q!*(v%1jVbe8;9Fzw8;1pA~TMrTY$(!BS750=oygY{Vsq|0JYncjEw(jfGBg^0mR7|-}JMd0ZHB$ zAl65(&2F-390dF%OCv_*03rgd8JW7hXFyI__5)p}o>8Kd&mWz_Q1pw$q8HC}Zw#!ejhUwrE zO(*KlwWvSZN$Dxnm1%7Iqc+gJDVYA8blG=DP2n_>Y%9|;bHj&W5s3??#D5EH*TN8k z?wm}SN!E#=LQ?8Z@O3A^Bt^nhiG^=IaaUI9;e6JfdQ}b zd;j}?#HJ;>IGj2Tc|q$K!gfgzlTsw}Nem3-Wie$&Zj54p-#mt^Hk8j&gM>LKT3uc;fg zBe5WVc8!_$)kj^CysaG5x2{+6{@rzBc4YBA!e=XKv#suFrA_@xCUq>zdHKx?P!yPxS7Jq%&8OyjH7{bNnn;aT`=W11vO@d))R%#NgZL{qXz zL+p|-q|&jRRrqV5`$qziEL{=%$#s7xAc*ci)01 z*JdIER_^K-O>8ydie_t_u_C^}I5kO28ZnGXe(vjxdWDEPrR7Aps_EVeF|dX80`w)NwSoJ!iqWWq(14vg6(qJ7^O@ zG)1KsH|sNkuY*s;c-ZHlEA)Ib{%!0e=Xw9;hda3ra=z=f0!#0KL>>{A1+ zG{hzvS6sL!uYx}>!mv8I2)XtZPE>#L*Nyj-VTYA$tG$qynh@S;D&n-9@P`G_!)3;} zt4(9vbdDvR!SOl^F66)(qT4F50Wa(ySiEqi6<8eL%$0>ve(Vb@UQ{0_x#{6R$ybgA zN){3Rb`$YdU&$~_4q#EzY&I~HIvu*$=ZzFUQxI*XgCd><;g#PW*Iy5vrf=-9^c{=}6N<}}IbVmG29YVpe`>NcBUhNRI3k^G$M zHh6p{K0><#oV9P}FoC4%8oU15jC^G!sBVn-os*4_PTmBk*qqci!64I#U=S=)+tk-% zoV)u2)F8odA2100inuQH(`t2e-Gd7-w)mK*x3v>4=OCL}7QzV{A(nopBbF3Qg>_2# zET$K4;qUSu9bxnzjE6@v6QPJj^Djd2A#SgK@TlMBQ2;y4kvrARn=o;p^{E&`nL9tc zP}gK=@EX>{_gtqYS-nE_PjO&D^u6-QizBz1#x0eo0ky=8s(}Tl0b`bq9q#~qRLhFoP^v(0b!LdW-i5ZnGpOCcf#$%>9pjDlR(o0fdv0q; zP-{LKH>)781#+$b=A-QsAsPL>;EA{Jw|UK+a`aVgV{l1GHAMKM1G{w1VcnMwjs6i2 z-ca|cNgbXbV)3O?_)OM}we#|69~R1iql?g$T7?7^S)sPjK=$hwjkeKRG^fEQ^P{aa z*zwyO8hu^AX;2M~)U&BZy}Kqy0{o`*z+1*#UzD=4Z%ui=AUdDV`7akn&1EZQWyAiv z-=E_=aNwIOW@Yj~Gyaz5c>8wSEJdJZ144ES1X5G3jD%LqRmw)t6#oifq)=(9Av88m z5kd-qKsyJz|)Xyvg0^bBJGNZ(1%4)a^IRkp#_R6P=3 zn{D^B&7Px>iyX739F{g(Gp9w&ZvpfBB%o9fgsab%k?}W}3(IUX<(om)K$56J*dk z;cA%m4cd4y7y#LlM-p5|J1kAT^WL1?#=Kdncbkbh*88`TlQF@0-~=61I>0<1h#th# ztB0luAeS+*;hfMTQvmS5ZUEuBn`L|F5;?RV2~U%x^QAP6*}S~PiKKFvgo7AXS$LD!awr5r{uDq~A?-%wWD;)6zX$?KSZ z&Ntd(zx{H?HACmoZS6RAE=-eitn6HCRo%YfqEI{*`p1m1-VXr6I>c{y!Fv6(*uMs7as!0$m za}Q0#zHnnkQD--6Z_Fr|-2MIkkG*$~i|WYs#cTKO-SmS;^Au_91`(wJ5%57XF`)rX zR1g)(W1O4;)FePF5zRy6W20z-X*9Mm?wn)hfX@Jm!Kew$#0g*~V?s0*r7?a7F-^}OUKkgs{RjbxowQ3dN2H|TWY27h21W~nc zLRX8gxp(&%>?HzTX_~qjhWQJrl%6M;gI_|oP%|sF_h@Ei-rySloF{~gy1T|~URI>U z)c?QS*@So0ewrVFRJ{AYwvQ*7;4kk@%njR zh;~fTQZ9)QB+JvJbO80AM(_5O%(idgv>M9q#IfuKnY(C716Ld?V+k`MpW8W)=2Ix- z6jJh@f5n@5w|yLKYWsMc=@qQ=I?_07HcMvSr%(w!x59!{1MO}mr%CJJqaw>VwFWz< zmcks8RijpEuJE4Zgl=p5c&rJo+TJ+T&l`2b(Xx0sPU9;&jt>vu!x<>RdZ)rDlhsin zQdCIt2UQ9or>O1YC==~g!>-lHHuNhtX;|!tRN^>^7Ux~$;{JvXOT1$oo+;I(IAr5n zxJ*p*GAB;M=wl-)Ggzo>&SRsoA9N&+glHc}ju%+jhUwBBlh<@Nb7BOi)J)ePzz?UA zW)%qGZWin&voy-2l?B2?L8c7VH%Uhegas3Cj+s)`HjFm(DXruSL*B{l7%b=D?~sNt zurlDEMp+9C+eM(ZZ@tXDGo_gpA!_(SJW}?2q!C)y1)g`>I48vR3&~~?bSBrpA%-7< zHHvoUiUSD@EB9%trXi1EEK^%L!uwCR_#2ucePt0$!E0q<`cRyGu?uMm(o{Z7pM#X@ zmrRR83SDSOY#XTHD@FPRv8!yTB-Mg3)$3IZ@QW?1>fi_IHyV*lhn@vICpti-qa^ zwVjbkR~HN6BhSB^eE)^tCEw3+VR{ajP5E=^8kusWegRUZ4AVENrAdXtBzHpy|Ap(4 zmMq{yLX;OvGyNGMp2b(nSYiO9F6Sao>`TL8Gpu_15+P9fpil@@HiC~e5r=yGX<>pC z__Q#2NY-pG1XGE;(+M7O>32^H&kp%yg0yIf5W#&Yy|zTKC|gn9c`8p?BvcMO)fEYO z15a-(6--jjQenc7tW^WWhAa~nMGvXjD7PVO)UeCoJdtF+2ZL=vFpE3Yg*+p~%IR!4 zscX3qxP7_cH&8a-O&;2goq}X}MwmG8N#!%b78@}SwkzjEl7RO3jRaC`^hqnJSU8DHT|@M_>vX2iL{W5rk8@I?%8zM zL=EvG9JDZ5WZ|^&`WaXi$OcnL!86!eH8@Z;l(blf9bgjn=eXF^Ix;o{kNr= zi)8NBPH6Jw5O2!kSTDFzcX=-EZMZye-H&TAuHUfUGEU*x9*cu4pRzZAT~Z}*H=ESy zri))Z(_;r*5#D~kePr+ZH%9iBbL#yS0Hy=)7R_|u;epE1I8AdI=V5hJhQhIfrJE|H zO3FCivClV6z|IzMy!T~D&P%7B7aqi%=3ng~GW2Yy8|K(PnpLMP7t(*^Rl{;2#69x3 zp$_W|a|kU`$8z-LopMI45F+B+oCUQb?b(Gh9)V7%HuVu0te4fr^@$~%Et^-{{{{oQ z6)u_A4@zrRz{oNLoyl&tr4UAklL2<(54S>x05G&A8_+yBkV^!XHUD#>o`6 z_Zer|*|0X~9P_Z8Y!EjE^)aobt6@t}xy;M*O4BPr@5?+b2b(qrF`OMrdvvo=*c=p= zB;ze{O(jS<%Y>%2H~?5{scGDT)C(#8<2)@#8#f1)a~gXCT1a%X$w5c%&F)7_GY@d? z)=iDsb?+nG*^$O=IO+Joy7xsKGIF%>wIIx)-JzH}Jr0#-K2tEZZWB`L(h+kH;CdF% z9*0XaEtHRR5j}GnO%2GQM%5godAl@oaY0mF6z8r%Idfi6eG+6v9-+MxBH{~pXaCQ> ztd|ka;If9*tKTZkgce`@9-cGls8&)u+D4m=%hqwWf`e0y9U8b8#wm6AMJk<9^+nK% z)j>L?>hqwyeM%$b$9m(k5p#cqgR=6F=Iv7%BXFVcAG&^Gab<@Nk{-iJ-Y8 zg(`19c(%n0Z(CO!UiqZfxL~AoY9$=A8nL9)1H~W*1^@&RJ>we&0iS2xq9Ukg5l}IN z3bF6zclh2lQS|YOGv7V!Q}yjrzEwThepNRg^{=`H3%3)P7y+CQ;s=h)KlNo1I za5CHd{%bQoK2+jke`#%|`@D6T-@jfgX3o^D&&&vaG4m}}lDXxRwLY?t4L)%lB|as8 zEcPMe=~J@5EWh-Oe(oQ0Sp6T(xI%C-y7YB_WWl(Ca0S-o;@k09pL|O8-^-to{d)Ng zg!6v?0k(84h~ODn_VNiFn>ZnF;d1O3o%qa1^NJ&srikVh&(O_$^NP=*%#n=xY)Zq5 z=TPak2bk~kvW69ZlLcs&&u>_y)cKblVEtb%|oOr|wvo zR<~@amrfZX(_LEPty?+EZ|>0ojV=);r%s^dtm2H?E8cW)&C9{bi)EEWU#btvJo2b z5nk!7T&?y!0koE)FvmSmdje58ZaZ2*t)W&?>!_8~S|Re*8ny4AfOe{c{-Lfofo@r^ zWHy}lYb!THZv%&G(_k%?bvUxOxy9>PN^a0DB(p*uxeJNoQI-om=^bIitP(OMOCVTyILwu1ox-Xf&$K^?#E2YJ#x9@HjsVXykSO8)(0^#v7<~2O2$eK^8AvAW;0} zuRV3key!IHTc*{SxZ#?4_=#2lS)*S^Vl{5Y34ufx7y-W;D3*-fj zKhS051VW2uI__64lj*($+PC2{t@idct~U4@`uL)wvY<58s~hLlt?~9fx~4zR|JB## z{n-I{Kw6OK?Hec>e6#Uw0RB_rzsFvEecrk6`63mLO>UQ=F8Fcc#6Qi6t)=tc5uF7o z;rSWC`K8f^Uu=DCo}csQay%OWU@1OU!ZS1vKMsE9$cH5>0$5Wy|4F*d7e&}g=dH(L zdLYhb_Q!F|*_7EVt61uuvo*8q`}dc6G`x~Iv+w<-o@Q(2X1-$S zRfvtTer8h(?-5^wlUmjsN^ceY}i<5>AF=Xct58-mO*t5HGC=ZQL76&&f0+x>HxRipAQsa){P^yA?Y_)7Iye^BRmSQ19)L?V7h_lN{ z*CX@tV_+{Ha>PSM+s8pHPU5`mbCAx)GgPuOW079P0koKZ?43xHIBz@sca`%{)3ZV5 zX}^N>Qzc8N;XKuwke1*W!WkaSCucqL!XD>YGJ(yqaO&oK0plVX1(Ae`$TN*Q(8LF%&1m%{Hq0+#vz!oVnnUeOlBCX}M##ZakS2%?7PAnt5C&c+~z zK2oonCEIW1Iw@p>AW!gDu{rO_V6 zm1MTLvEHEelFVmhW-0ska(|CtR9+4n$8?w#c1w*f3BGZI>xGR32=}XYtxC`;Jgq`F zet}HzDm_ba_3~klQC1$dpKbSIKIc3k8RH(3K=t47`3(cBe-^S)CDdLDo7+ZG_1sQUM}OhlMzAXL`L9_ zZC=4kuj^R78Ng7(89J;Ljn{E(TL>&$^o<`k+j&~zm^On;zLo!i z=^VV?PNJ|~!>7NH4?w}-Y1Ohj6gDe=PM7vRCJ%RPW2UqPrs*{R?hf6D3ev2Xg@-kF zGB(Jiw_X-T3=F%^Uxoz$QNia*#d<}c6k>%5z%_`a$yTU)u2CR8V;wv~Dy+h6k35is zYgY`DZd-)~?zdB!O{v8G74RErQJG*0B=lYL()Zk6$yGVt?&&wDNOfi4C3h-oD-)(D zU30KhyPgjeX`zx<5O7Y7EqZxD9c0XE=%TiAC>U5R$nt13T1lU)&W|?16VMj3+)`H# zZO95K-Uy{68$34|cq(WzLOmycT|;EP!Vg{vEIym_g9kQ?@8E;u3)LE{7w3`o=}bjE zg<)EPXh>RFmUMiR5ULb8t^F#Z6G$DKV3@5z2sd#m>;6ag{qwe=dIAcF#5}FRm5wW$ zWA@9~A1890y%Qs9#2!^A+<-Ue9K!@>gz+G_xmc zX=Y|~$JGf()s#(Q&BE8j8p~Q{d&4NpS87a8dulMxYi|dK?p0lRlnt`&UKffYG2h#kv81r8h<~zhz@isz8 zq4`Y;-Xg^M(OdBOJ8ulIvPwBygmiZzjDtA3;VrNzscwrfS)9?DZ6ZZ5Di8bqU=S&Q zEg3!_-ZM~QJIuZ6JfkTB?~E|GC~;57U1Y)xO9F}$0Wl<#aPH03D7}emxPMge&Wu#F zbqd-x68H0w9`8Okd8#(7utXac^Ca4I+`D1&DT=tZ4-HFkzIX~R9>Q}CX!1$O0Xxy% z={ zJ2Bu$iw$|G$vpEse3>r5h+<}}W&z{6%`B-V1-da64%-&CRJ&J`sEQ88GJy)CPGvQ4 z8aqizE?RdOXQwN_D$NW+J4=yX(6K5V?(=v$MO(lr0&=qH;Jj%W)}Xj*!~Hl#3(NdB z-A2SugWVvHT){B*Y5DIxY4|q5AO-Idl!2w=vAq!{zfx#y#jv`sy#Seq#EVb139%{z zl!`_){yoWtKe!jAL)%C$8vKoz7lVzFko)ri$qZc0h!mp?Z4RO^lheow1|iMx1m;@Y zYp@9#+Y#W~HN5&$8QWG7*^|J&Vo&$-EV4z$*R;rFxHw#_CI_=2wGKXGv}%6umOw1f zZ4*ZP18o_9ueK;h{mx3ex* zs!m7y)A3DNvb)WS_XYSTZ*`@51~)vd0PnCc@`y%;?xAjKhXG6VsBwq--O|jc{DQh` zZU}w^H8lc$YWbi#ZW?%L^SQpD{?&MHI2t)&HR%TGWW zQ;(Q(_HiujtHDu}tChY+c%DIcqpcbBh}oEykNfGgPSdTjP0C+oDgXvrc^K(=|CH)m zka{Y-dJ+QN+0q;jh>NS_bAwUXH2k2%4*~e0pGE>LU~4~U`eCV25)2`^U=aQ&mzE!i z*zXqAx4-U0#$hS(b-@sv>il*Z#JhWZ8!I|C0}rD4pMx0KF3vjoA2d>i{znYTw8*g^ z2hHT7K?Ck;7j4W0LWn-F={U{N?Rd^xU8Tl&(&QIB2X?Mntb^R<-S)zy<>fqAWJRo# zVSw1sz!&X=oJBvqk;=U3-TsSxS>zx#Ee!E+Kr7Q=lY9p3cJMPH@XyGDgtP@c(PbQ= z!UDS?QUwQ2qDQGkDIX;j|GOa1sw^;?T*bTw##l0ZIis`654rZO+Dt_^(Z4j_j-?f^0xx(o5YVc>af z3fgwfV>i64nobpi$l&02=~Cw#!mI%esrWyH$AWL61rcC!)Rz%pav@-HLv*O*(%^n7 zZ;vz^H3(AH&%Ce{3TM=5PUh97VD(X8UZnuDv>>l85284MVSs3wF6Hh(wReV&V?nHA zhcJq(xyPW&o#s1G-G13mSEoXYUoOb6OM}RT`C*Q=z*tA1RD1PIQnvMj(#~t+BjEZ5 zwy+{1d79=~ss0VY;QtC^+st601m#VzS3qi+aW4eT`g;fxOR#i69Sf#A%#T?RXDv*a<|JaRF)5@xBACGp^pRCYzj- z8HPBxVO8b;H*|4A6;QCTAYT&yQ!p+pb<$>=C#w$wITLLT&Lc#?w*7;Ag17{8?N8C{ zQe8jIO4@xgzhI(6S|p`;H~{Gh8Es$gpK~QsxiC%1VTP2^ELyt@t9y0jSR5Ui6(x=VR zZz_Z_-XG%??ZzYjnQ6&v&I##@3Sqok20G(ZoJR86DHz4YAC9%sg54`zR$>h|WyPr# zPuF$vUTIpWah@_y^*PSNvJ;ZjjBqvwbC+XCe1s~fnqqEt;$QE=V37z|{Nvs8nX6Oy;XB5(_{+zCR|AOYre z>Gn<`;VzUef;b~JlnWu!wq4NR2IG55x=SD-G`dhqjUj==HOTDP7CB>Vb5I&EWdW16 z{MWL&bS?^v7l9a{6qI4`(La**O%TCg@;ZU$QyVS=1;o~*C0Au57Py(u^d0v-qr(z9 zcxLtaS6IDa6YFW+55F)(vAE9T+`3g<6?x?3?`Ae^p{aiMIJ32+vEG+Ar}ad5rT45# zh3~`DtoM1)(+g)2d+rjRp#eSy5Ci#88^Rn2;l5A96$dkBD?A@kz{^A6SSO9zgV`Q~ zuDTDa_)_{F#IeqO9jC@Y)54Kg-R%%Kq1V@wo-aZh3&A`4ZXRwD=C^4t&v$nBDti?d>3Q}Dq9I4<-kfgT5n8mJ&14xLmG`APk-ApLG^X{Caioo%ARs30n!-6DUy z_ng=UxDhaD+|t%1cmcr4aFDYMEiW)mqf66P@87ZPcJ5h=!WSEp0xii;VBbI78y3t$@Xjd5X5nh$NllmpqXZ_U z?H7XFF?RaLE%>EmdrOEKAmBawg^54)KJdU#zb`u=go_r$l|mmSqJK7>*qB-4?1!93 z;E({6EPjMdT=aO`q}Sd0@et)U6c07%zq|23g^PI;Bc`p!7)K0FM z%m-Rs9P>P{i=@t>{|!uMDMi00KaaRh0CE9iNq!NHCM#vOkyeVC0_vM1k3OLMYj`ez zgG2RlHp$?ow(JCEvN8Llk+CO1x?CfK4ef-+qe2+;;r9>c4 zppbZsUi$bWEZE#bD(aQ4A0Av)@DU*-%hi{c2hG{}DQqIS51t1{OM`r21vO2Fyg(sT z+94Teo%LXJ+`ArXQoub+PLe)6B8*FenCF_>$S03h1`6P^beWgMPg9);N>WX;R3cms-grka{%ED4_rjD*mfQV8Usj&v{jQ*U$n{x-Q?w#sAPk{+$$+B7 z3Ns8UwZ?zijg0a`DoymXow_@($kRq! zQHFfC$=mh;@=#W-a?T{%#@mmbRlz%B{7Uc-$5M?UVZGJ5+x873{V`1JH8s zBta{tAb(!a#S8%T%U@?j_h%6B>WDnLzadlbxPBe2q{{m+zF$QiQ8eu?xkJsM^lNgqt@sQ~ zco@sjt(I0mWoiR`s6)-hd|>A)u$6=8=BMUCSj=hKnNucjtmmQoYlVc50r zNKGt*A;wk?w|ON##F{>NURLK4dVsQLoxl_UkW#MuHzy`TlxW?VZ89*Gh3>_#uv(n$ ze7J~BsiO1#((wNKufY}R{RO1-(>0`2U^nG+p_W!hI?6)aGn)&yTy&&kEZAVHUdw#d za5B8-3NCEtM1fSW z$c?t7FqWAsYF zxy+b1=-bBc`zG{Za&mnC{jfeq<$a+nQHxV6t|l{EF7^Y*NE?p{<3(&}uz?R1t%Vhq z;!=fpa2c4qd<-6JDS1#>IcpGn2b%4I+S+kHxe2JNH{Z|BV9S?n%Wxd|vDTcvIgyW@^#W}ayr?zpk79l<>C^Gtkf zvl-zYB(RyU#4%fOBEl%C*~~3~o0izi;7@?UW`_E(nXUe8CJw%u$?4h5T-X$(vfo2t z#q2i?v_#Xsa%~FY@M5_OM2i*`S$$y#03k;h%|@dKzJs6nWg=z}F!cSbBz%(`3=1=q zQVr-ZA9M&p@0Nj4f{8|wsHEmJX)mkTq)3RV6h0{$n2sa|O?UwpfTR0A2sDx$U|gM2 zKOHmx);?jn6!*U18@(B7%O{+BS{a<|$KwBkcs|K_q(#H+?*Q_staRkP3`2sn_FEVL#R6Yi6wpNIibC_EQ9%@jDWNP16-E0ad;oZfk%$R(L=6F0bZ?%Hz|Ppu z*AFcq&1eL)7!|Wn;A|93&atyma0Xg11H^MLU_XKSK)_!931BO*GVlXn=Xe8J@CgUB z7D%J$(vbEA* z8(=wtG3+uN`YZuvQwIbv_%OvU8nNc^VqAsTffe2`B$*B*j0yEh>9$zC@SA#g6fD$7Mape z2~|cFMFW6z^p2xKAfJ4gXpX$B?USx!j%$G+cM112i+qc16j&mubuNw8rd0UT5=rfX zEde&pb6utpOn%7w>j7TZd62%#EF3YCB9P>EkpH+pUH>NSUpR*Q$}pBmn;XEELt$-J$FsNl*&9#x%? z;WD($CtJ&wcJjLT8g6q?HrD*X3Y(W;)OWqa>T3lLYv)7QSaxHLc=mv&m*zzyo0IIv zd^%Izs%E=0A8)2@j{a6WyO{G%>$p!-RmOQ+YmRH{5F9!Dm@8O-*$hlj~3$vE2qet1tu z6SH+-pZOw6H3)=5`6Yopi`FsQtW{pRRyft|x+wEH{h2Jrvsab4wMW-+8<_+90S zIu=lcNa0<3ZXsNA=CG`TpqIy1d+I2PU+sO%t8_9s`ufqH7G8-n8kyCb`kwz~j~@AA zEkCc06ScZP(O(CSqTT+&lgqX00BbaMyL3X-S%r_z;|I*qRvboVWirE;nzWvTTK>@< z1H56IaEuY{nE4(fGi^ps!a?MpTg$o;h>o2L$x zQyJZ#{|fRou6$19x=Rrs)lo53FlC^EX{P@CR;nO%pn{0|`}0*W(=?~_Bpg7C%Q>!_ z%7Doxt7Cz=w}zh!nqt<2d}dD|?_mvPp4L-5ccup4{Q=U$sS~udn_qFSC8N z_FVes$k>paRI_!?x&u4G><%2ytQ$MZOwOQ19>bVvFAVnI0+?DptLF-qe6<*Y=itvt zcBF&+!#zaZG%Vle-0cL+0szwqHHiS|L`a4XSmg<*P)5Vg+)Dt7HR!9;yg8kK_?&}W z)5y+zp3KrAdZd@F>K?0B|?XSj*~w?A;kfP`W!H+rpnqAD!Y|IH4&l=Ajgy!Veq5VuTcJq2IcZG5d-~ z#$0R|74uNjsF;^h#(4hG9G+1IqIyWab}~&59ohYW#sJ8g)x0hiKoW2#C%Wl8CI#tg zRx9Vau=xjk|0X9AIv@EVI!k_tP9BOO1-T+XJD@;@GWa(0b9y$Uo=ZPtRurBEpx>C? z3gZBHEjD-@b^_}Sz-I&CoRo0Skd#;lz~*A?od5s_#N)H;YD(tx)Wot0gyO-F3qW(I z`%vgT#xMsx?8VQtDd14aBjD}s);RRLLFVnCg<1gbj=aIN-~fJ@6Zq%*fqx=ZtPw}U z?K2M7Nsc?SbZ*mu@wlIeYwuc?esV24QwEByrF)Kuv>Zgr(y#Cy)uDv$OE|A$rMdTH zB!I`>AfgWfnot}FZTATf>@1=O0Qn;XD-MCOgi!4JLnxR1s_DR=^zUT+8JD-dHscxn z;S3+7&m!H2y)bX$8oQ2j0J|52JGP0PsijoL+s3Dqr%y^@>D>UD+*Dmaj}6C`6%E`< zV*vR9j}qhuAyd&bITg@{0QzpI(LY3S)(=p8fyO=rLI-_}=|^z~^!mjZ>k#0( zmzJ2*XY1e2n1kyb40Xcz=OSA41+JAmXFI~N^wYRb0oA#LUPzRkkS;qBsM!O)^WB6@fP<-tCK`v>4|;DRDarZ)(@4cu>`ooHnHvEOP6ldrakV9L#hT^I znhyNN@LtA$;z|M`zotKuG2Bp>u^njwo`Z0IA5x+tAH7(cK@`84lR0=Zp?@>=izAiW zUgyfw-@ttbJbyz65zk`iSB@?r+8NX()T+Jc4x*i{XjB($KR-hG{e&+%d36|C)nVxG zh69*1`kBkzo|E9wF)qp`q5&}x#ny*zuzdZX8yqZNya$_f@%ZrrJpSiSN?S20ede5$GF?30IVw6~#kiZrpA-kpOpfW* zy?=ToLUK&2#75DI10}!gAp?<-^Mbv0I6`&0+oKNA;)HK?lLrpbfi+8smeTX@@eC!Y z77G?zj8Kxu9f=kw=v`ll!ghP*RO}s{g6-a^RnlL^%eAwiscdm-GFwtU7-kEDQ__Nn zk+#o_VWHxOS=wQJdVeGn*b?pKE(+;iF?j<-Jq8!kles}R9D zcrUT}JuJu{fOECV;QoEH=Uh^6#n!ktk(+)kZo#&dbLcMBFMdc-r^(5iAsLR-7 z)WPc_uZp}j(j8_7I{P*Wd&y47xva~xU{~c}Ttf@40#%2g;T&S@=tm>WTcZGoCClA7?0(zrLZiCORHg-kf z@~bMXwS_Z?Um{Y$s}!~9dkmM~L-|^%z+y5gKalzec6q5RjelcVpP;aE6qdJ%?wy65 z;cc5xSj>t=%WG7g)(Xz>Wji#C>1AZ~FjRkwGB1PRMHmA1!<9~it9Te(-8@$7cW71z z@9@MFS;L7s9GIf9THx#8fea1q;b&xTic9*6$V)|@tft9>uUSj{ISNc3yKmC*FM_&Qi}Bw&{09p} z&3q9*^~rR0JJ=NL;8|fnFIChDUP}>U$^aN`-RXpVJi}r!At=Y83^+}p%ldcMj9}fz z(ZN*sCfL9nz`-1auCt$n?6wJ3ypu5HY=UjoD)jI(grUZ9){u$z#-aG4!ezK$UssXwA+9*we~Bv)@3crWaeX_fKI7J; z!x?+={t~Vo6ZU1SpKvJS^GS6XM<=|Q@#UnqGxkoX&3M%CZpK2xo{U?Oxt>x)ZpI${ z-i!^9%JxR&dTyX+Y_0zT{u`ZeI40vmWPXKx_WSVSB7SyDcst_~^4_Fp`Y<9izs8C!&4ZBHMlVLiy#KsusrP;nwX(Z(+m{~H``&Ld>We8T~G#SX!c%P}0GgDq;sGp+*=HmA z@B^#_&P3|SgLcr07Jn^wwgB#?SDeh{#M9K8{;ufa$5t0|Y*IJ61b}Uf9L@eUChNIQK84It)| z|FB~s!ns74$cf3=!DKM8_s>YM0@93ho|HDUtR3p?6}0RW_`MMkQm;N_?wyU6P}dZ} z3{PFNB_AyUaIUT?!BRs8CM{Txt)GJTdt=kwIE-r>o@pg-9NgkR6-1oar@#y5r5UF{ z1||Yd?R-|V#8a3Mygbc`S2$0N$a~mhJXsv@8g%Mf!VN#;x<3u#EYtbEK5fD524Tks{KpMUi1LorGoI=$y4MGN$E0{sIsHB=QPxtd0O- zy#>Mon!T@rF0__>lULr;rmF~m>4m++MiA6FPPxC~C6=|gajf+Kz9EMUPhMr6iF%Bn zp(^l$YRqn*;MqzmzC`u=IgKU?#A5}q%)~{{Sm^4G0@1Xh6_HM&fuuO0b4>qC)d^yy z;YLIE&XB{lU2M*F(9;#r(^b$D`CSpCY9EJ)lHTm-Z=8(G4#TmSidN2t*h3$HgGILT zvDGWl%8_s@0i*FwVZqJE^Ou;;=g&8#FkUmovc$Abo}xLQA8XRe%x@>L0DA?z*t{F# ztgR?xKDb^g`gRI&K%`HB1|GnywgKslu58oUYuToKu*WQu`D;Fu&(-*fcu7VW%-QxQ z5&HgXy!<0Hi@h+?e9aV^z48Y&Pk>SzL3GOic@@}l35aeTb~qEE*wT5igqfTrE(OYRcbxp73OmCOtN18&*@dIIn zu(MC5P}6j)xaF1*%4F(BEDz>l8eNODJpsbRjlLt@utd+CFk{B4*`ZY2r{I1H%MlCBEGK3@%Pq`hxiM_L!7CJ3@p{9oWS}q^=}7#n#WDuN z{1t-v%M3~{X2ti1$Q$m@H8byIq!&JFojekShN94gNEaY|!dYesn_sw&&5xmSQ*iA> zne%alqP*k?F*Ji=*c8i)@6W{qK}7NqBwBCke_3#IV}6&T;0yWPlc{jCrEBv4tb+dX zTk>lslW>uQ;n>A{SGOXdD$TIhM9g3`b6s*jhN6Y7^Y`%5j(}QvF$47t?>fEo&sxq1w)oNq$ddV6fDZ;pfM4z zj|ahegG+jXV0S@2(P2O9yYQZ{FkU?AXfr;imL{RDmp(Qb`L(U`a zNIww!L{JeswS+ih9K1h>wHEdEbIcf|#0zF(+I1-(n`G`9VnlnuHTQvQVtvjE%QQHq zyPddY@p>`D!7_=RR)B5p0^8&UvCR&CSR{FXEOT~`i)|9uG@@G?!8sM^77{8fIRl(C z@1dW^IlV;1tRbw^{Oh01Ivt$Tf@ya!=cMPsob#_(ZE{FFzZw88B5eRT(ZSc}vV;nJ zNW_Iz`+pj7xoFD^jrwUqoDfUQZX}YQl8^ z*N@Vc_;-j43+|3?DT80jKWogpx`n1~@kjdQPPhCE#{A%J5&sX2`N2b8{Kv*TtRC1f z7+9@Bs^yhd8(69w`&eb1ce4SE>k=3f1t2l-a)g%QsyXJ}{5|pvjJJow@v;l|NjNdD zmE=DIrrFW>aU>_RIyfIEx6|}%z`RWw?>T%(Y8Dv~E;7Ai8va94zb2~%7u>SaEg@FM zt7ju6nP4`i<*pap57w`!yPvUmrKL_j6D@|mOWK?ge{CY$`(rJ&cZEcVa#LkPsThM|7796$3GF1 z8NVcEN&J$+SL2If_QWqN+#CNyA*sWp_6}BwN%i%E8ceD&slBBBx>RIRjlY<5#Gx9K z`b+9@57gov6ZU3Yf;LO)F{#5xq5duup%c3q-gM~2MiZ#n+=9X`LM?s?@8$UR1ElLQ{eJ~{EuVT!muWLZ16 z1hHGOoJR&RFXmy5#bscgc9G^I1MlUStEkJ*aNcUlOJZI$M^)3@bZArm+*F9Poj3O$ zaK^6jDq*&6_+)A^gCh{4wM7tXFm9G!*)eHG|~9r{cwBrm=p6e7Kc)hsvH%y&17HDM69NC(V? zG((bcXfgBV@KKIDsYVM?+bmD68R>4WalOxxvl`MRU?Vtk5Y0K&7~SlJ0$ZSC!rjU0 z2_kCp82Fwht|SZtGtMq2&5FbYs z&A5IP5zhBN8xhX$U5Kc_P6rnv+G^brHp7+hA4Np0f;p7^D+2o$AmU$45ey1~3lRf` z0r96T13B2?`ZFy9Kg%$HGim&YFOk{HGtVtyy7;%gVZ?V@G0&ZbBG&~P*TM!Cns?Q~ z3i!M(ha$&dwEagEIhOa>VQ3!w__v*RnZhdd0&G-kEfIC~28kn{1we z)hIg-5bVJI0<24mK35URvkB{na+om4A8|B%SwA#;*ov{7aA}oN=g-`%Ept&JTmk)< z%DMus{qS4GmPqDzHm|^hV|*gBeG#+~qbeJxTeLuJC3S_vE{a?B`K*@p zKL0?iSN7zQ1rY_L`865bbRy<9H4Ij8`Sr84r~NeF9J5G0;+f?mM?|rd>{vziwV0{Z7%?x&+^izLWdKO@!bTH}hHDtEa}_-aufn1BIy@YfVI zh-FfthjGN)QSgDA&hruq%eiFdk zG{me7oUi@(UvUT`Ha3NT>ybyvNTey(z56{%j`-TvezP`nyrNGU`d)N?@E1Q@@{P5b zQ9t;=`99X)*7~=#nPETn{u#U%)@ADO-sO(+?Nh%)d~^=ZE;2a1@HpE*UUeJJb`)W; z3bA>Jo=#{sn|p9J4nmM2%xiF)@Yp~g*HvwU!@3@5!}%h)=ljD#Z*LbSXu!@-gT>bx z{ez^WcHx(I-bxkigTDReJ>iHM`(OagdPRsdtpm}eU2sX?-9+f5${|^8^ps%eKZjT{ zbBc(8&&@Y*>`z&zuy9b;Kc~>guL|oU?qFzQknLfRMgc9q z22tYQp}p7d{Pm9#u$fo<|1U%<{1XakQ78tD$Dhv}%}V^&3I_&?#4lB-6cj}wu)3V2 zoDdD7e8;L3IOywN^+AJ5G5JpE+cgS5sX-0SRGE z#lW}H1YgBuF#^&a&72?0e>ihGj%lD7wJF4^Y{dx#_%?}0dB}-e z#x2LL$Z|waG()lv9ES)uYq6~u@-H^-o@VWh_hZ*+eQ{IqWUBCfR7ik~#QR79QVl>R zVg1n+l_f9Ucu1EUyH$s?ns0)FZU93Xd;}6CWaBq;L`o`~rWxJcrmQA3lhcNe&tDrrs$dt{<)#m^KksId*d3h`{k1cO@GGlC5zK({om_&)0dEFLPdcsvngJ8^9w7`!7&XrQVht;!Yd*ClTgekF5|qIjU? zkhz2XD!uQ4+;p8HLJH9hf=oizV8KGCC>tnfLa<`Vz>@>Ve+gD7y)P>e;Ct*STQi`g z`U|8R!HO`yJHS`z?nEnggb0<)BNT(g3gB*#pz0|0yAhZs?)3D%KTt`XdPUU0S0M&P z&XA{x(lNu}54sGB223aZj;Rk_5Q1|_1Nx5-ZV6G~uPQ?oAroAh5v4c0 zM)X{tg_A5+%BpT-Eko(H(GkW~84(I4m5bzZPp@z&MO~qaKoJUf*2@o=w-%_?R!h*r z-YPxD+R2>60+rgD=FyP2pX-@qLFgQWOVLb+16E#RgjL0{#Od(PRlz%VI>s;s44MvS zEET+S>Hi3vYP(UjF|!ivAs_LPDYTRwHn~#e#>_l~XQup01h1(YX%-P>T&bxHq6bz_ z)VCkJhT`c>ha{VZ`~9OaC=o+;%iv9?#<>w)kJQk)f z54@|OFR9zM<2Xs_bQlKQo&ScuGmlbC8+f;6lw$JGQ(aH1`QSixMS9guo`*N542J~t zYpiIUeS5fK$^b2;hYudt6*@>sd%_i^+)=6MsX-ixMzyqjw8GtgA3{ujJKmhw3x@X` z)Z6F3X12$qe;=(#n-GEB7E10Hn&FLXPM-4+omALE^1uKo)ao>tB3(?7P8oNIX@O%L z7#Y@2tmZKaKW#k%#9}k>wq8_2M@mb1V-(Z0m20Tn zfy0wf#toD~NBzq> ztTp~dFa0e-5hs23B=7D)F_HaS`iV#;c}FS?(n6zR_CTM%XH=XXcs+PlDMaa#%3)X@R_a`*R%C z4uf!CBu*U}6{QIIh2pL+uHXxLTa2+)i~uWYnghq+0C@a;3GW&Zi!UChJ6Ql@Xp6-r%j1( zA`u#E2Hr>JN7S{s!CVRJB2~Bu?uAlpw4yTPPWPS+zcWwVUWutK4PioN&8U)kq7}iS zJ(aV;4;C?d$mVW{eA!29vtZ9c8MpfFO%&)evR?n*p}bIYpb=Pr-Eu%gw$za zf;T*X4e{WD+Usl1lD99#Y_;Vtq4vzl%a5&_#<3OCKVmB=qDh2IsnNn;vKs>tYdPL6 zp$!Po$HFa(F-q@%dL!I++Ce|s_|o}ukT7$E=#uKjDx%%{Fjzul(^kZNJZ**4HC8b@ zxPkLZi&Her3mJ{VzH=*zMz6$$dqr|MDN1@gMlmY3Ujk6u$=mLAluXatk-B&(rMFkU z4`Un9ss)$a6Qk(TUBSMsQ=B?&tQ;Q5;irNQa?@7Sd^Bx^h4Yl&8V5PImaK*dJyV4Lm4TjQ~{neErUml&S!ymued|2{CnmfW~DvlZ{#!`@qb^HB~w9MjoK82gT+ zZsnX_)o{dTqd5WsrCNnOE}9YXQO2kp&4}Ad+XLu%qEWM>I%B%IPNl-EgiVO5;ED_) zQZkc}{WPK~`2{=BpyABDk@yKTa;CsvZ8Zz#v0P%PJ|rpL=zPbohel=FH!ZB2?-dDf4b3C{BMi@4FMadSohw+QA&k_K-0<$q^ zON!_}2Bbas&5RQ`?ynk~J*_wfa1oCByN2O3GkBK+!ifm{Aw%t9fMQQ#gnmP!QNK_* zNPtgH^y?3V>z}~;2NR8={z2tv9DY7h{{%i-fRn`cnnvsQ;loON zxc9(l{rU*}7&QM_N<^4`Jqk<3cf}!L`VTM+cx|+Pk1^RpR3@QpiUvcOeFp18MN&!}r z7vEm_AP8Y<)z$m{xQJLHooydFqAG&`ZWr-!EAJagAJb2F|1iTz$r@0P5*Wc2tSp%} zMsE%b(bJk&3qMAG&CAe}H@vvsK$L}`U0$%EUAXw*F-kA`KjcUYKy4QEzYG|YEisxI;yXchg+N z)X3QsIWQZO+M&r*iHvY+`mx2)4 zDbc1iAImgnzjyIZL7eDG zi8QN79jcGVWxn%`sCRr6ClfU1$Ao&q24M^?`4$Xn+g0q_Bq81l(_%BWZC!Iq?ioA<#?DS2J8g+M@nLQ9Si;tB zT$NJe1ck5Y1DN(=xIQE|AM1*U*Z%=D&!PH57-;^eYAQ1yD|HJ@c(5U5tiL)$|DiI( z@$EMe6ZMBczGiIYAFV%>K}RudKv`4{l}YcqO!4{+DEn=y1JA8^-i9)s#q~Bi?$yZA zq8`gxUhO(nyiCcCd287*>}#s`b7!}G89U}9XUDXD>{z8rn=t!>l(D`c$Qy-kqA~r0 zjmjd}u>=&Rh-JszCa_}xxbIZ3+M{DrZ)0nCynise{V+JhnTSdHu80J^A4rgbCX5Hb zba?2kVDZfiFeh6ZKO+9Jn<4%HE6${ryoiFRCBu-O0Y<(tCFoy7%iqQGhj?zm^A@yf z8Ln%l@%kgCSiRQS5N{{o)F5h%7LD;k!+g<@HaBg;oD(Ty{Q$5p02Urci!xEjH$Y7s zQiA?nK<^Jo129;I`LWyYqAT3c>bXGmAyb@w0-)~!b*P8e4(y+O z1U&)gp!h!l^MROIsAtxLJaTd2$lGIT078{#qOeC$7!|GtU|D!K7kPV4qd-ETdc-KZ zt=4KBz&?t1kKx_J&hNwV9E#^ye52GVtxO1G$C$Hc7<{Z0_&|n_p?uW~-s~9XkN48f z1Vt48{nhWKPZJd3e%Enx4VwvXul&FvNj711KvJ3%W71CVQ?t{1aP7vm7grUoH*p=p z^?O{H4o<5tPVH@e{K4L`*eSh>OQ-f8%zLPJT>g~aF74Fb_!$rNHvMX9Z%Bpof=LnT zeR?z~PQ7?)FECpF0o8NBqk}88V+ib#~I{e>cg%a`JQp(y8yr8B=!BzZtc-||ZU z5!x7G`~ABk?o)(ueCw6(rPRrai@NYRII=1%IT0LeVg*jpB$Jqo6@RvqKDb}8T0i1x zw(a)HQw}r{klcFPXSY}W-XZd&=1G6OUlHndnuQd97XFo_ctA0dJ0}?*P$Y04OSumy zBKgy48>P(;D8l*EpKg@ic|eiuby^AJBGQ9Oq2G4mw=U`76vYBQ z3IO~rMG?o#fWWIMiX5NQCD5tqB*+vNXloRTKYLEfO$9OP@xd#pibUS)%J=U!|9@nC zd3=+_^Z)ZCWw!?u=t*1JCM{=5xk`a@CM}16fK))`C@Do$KotFmB1qG6$RU~sD+8#I z7UYNm0SgsS=%JvZ5>ZjSXbXslM-@eb()`}@r1it+`}?D>ZuXennVp@TotfPyN4%j% zdRZ0wv%t9fkEw>;zPUlWXC9yp!$o%3X??*ci+FeGwsUt;VLijC!tBQJR+fbp50bgyT z=SPb4*h_wY10UTPp;CCFYmGtfvYu)5`ABh(F%y_)+$I(o;{k8qZQ^$D?LW7{qIiIk zMv2MBStx&el*q>KBcsHK1RH*zTxs*2{M&!97H{+7iaAbKv6fimCyW+xeQ!s%eq-pz zE$~Utn~M+WyvbbjeP{9D>!FJ0haU35ANvJA$YlL_Xvl+1;#mi1&S)_deYi)92f`Zw z*lkmKYuW1TEsv0SjCe>LMA{f}(zp!Jr``@0UWCLlBvKzj!u7kqZ=+E3c2xy^^e2}? z2Pq|6L58&`KXtn>g*TMpE+9iTXZO-ZlJ9nLU(RQko#elazuu1+99KcG_6vY8`_?Br z&V(rUZD}Z)lZ7p@|DOPI09VIVf+yH6;IeZ#I_WV^nA$bW z%kQr}r{1@POY4jYh`o-o*neoG`^JexbrY=^2bLX+->;7owzxI`S&Q#u=v`xcHl@E# zfXAuTc#&Y73aDx0#n|YhXy9t~SHG(|p`zURRlT*lXx(_g>H!c($BRVcN!0mjyy!Ma zCsvg?OJf$~FBlX82^A)LUcYS`{p5mUok?B?W~xlh)XG4S?Rfe41+Y=h9ik&9?14MP z7>xGd9k7yIYp;~N3Y@Xy>NMI5Vs-$nN^SkLc~Dm`07L%T<#R}1YJul~2Ph@wsLx0h z;fY6kl2U>5p8|BdpDpMq&d0hW|b86dfXTI+{&=(W%kB z4YbOyxc5%cLk;3pMjI#UYxu}SF%Zk@`b4oHssUE$hG@)F=SMqgAw`3FP z%m&O~CSlTcQ1oPg*iFMHi)WJ>>QV-4r?Zq21$?*yBmgBrt5|oDW1zN_ew{4xn0B%5 zD$_u1AKh~o_EIZdxl7!IZ$jGc7OAPDFm0u0Y~Y$Gx9x9!6FJIVH3|U1`iTJe#^pwO z`fl-*T1PGJ5!-{z1GRYCbC1Xf$JXv_KFwnT`uQG_{eSa@Oc62h*an@=8x@O`QoKjP zZ@kzp()=l+ySj{Co+3u7f6}EXA~_VwgOkVb{WJ=nD#jRGLn@|D6%VM!%I^Z&i182- zzf2RO)QyxiUEGQG>!yochN{8TFHcNYuhI*7qDR|tx8d{J!B!u*KKJJ0s$E0rvpjK1 zeWapvhG?y--D$sFJR1B2rayYTa(Kfi8BZhf#pLK~3$UO4?JsAd)$v;hn2qDKKVKxo zUq%r>uvz(w{~$I>C$_yas?l-A@&J98FS^d z9iiA9qTNTKX4oSXUnRm|`F91C7Kl5uS7HQAyyg1;826OcsJ7DTn>P|V#7f1-4_`xg zo@wsy^aK_q^#9eP;=SYW(|RBMrP)q#J)hV(z`zc59K?$%&7VxWI{O zB$8)~NygWZcziZC@vTU_IvZQ+1|&{%VjU9KII;X`y)Q$+}A<=7}BZA=)!f#2PE>v75~kS#4j6#beySC4D&l*TWJ* zZ66eotxi3NpG~N|OT8Y1E>%nqJSdV?Gp&A5BuTJ;lzYcC+WVl$GtLLJ*7Lz7&(VYP zq1fc0H4|k8y)YkJ*d}W6kjRN%H6IfR6ChKTH9Y2li51fy5_o!NV#TOO1RkpKa-kW~ zqXjhmQD}0W(wRfGTq=E3EDUd8N0wp_#WPC=_Xg_tA8}1RSP}P_kg9ry%nQX)wFiB( zQ2ebX(YeP(TFCEX(P4d>W}{Y5h^gua^uQBXsC~)zgs5)sfw=K-Y}z$Qkyx;EyK95B ztW=>*F}9%37l|h#Ji0P=K>64Qk>nJbBCg z6}@fqb*4*8pcHJRj!%i>>N9ldDKReAyYb%tHa4K~tlO266*Fk`QW39qrF)lRu|G{%`=fiIiR>lG~n{rIgHT9_c$aUkFVv5(C1$;P_ldtRB|8XXuq8 zaXK2it)~DN&Swn?AeLWc)GpBKVgMUXRmGsxLv*fKbXHYTmx&o|#{zUSZ5X{cTChwk zgMasrWvFzR5|^XN63SdI=BlfxbUDffQO6aS&^PGd3X$B^FLUn!P%yoizD{SKIlBi;W9 zC9`~_)pu`!Qo^%Vt1Bh#ExoAi(;_9!>p~emF=4@n2`xKtVmhe+TV?3k>xk}p30gmw zF9tTnGbrzA(McUaE1m`g1ikgNh_&-qCY2ZK zs^9(ep`K1~mjcD(hUB?Zj4#B0+LZS!m97yx)m0Uv)`|kvaN6lT zhc%GCgtV)&zn=dc(v|i=`ZChBmHqU59cF%8JzaPO1twch{RcL5r!~Kao(7{i?a-!p zaQG6c(^1u3Ph*0euDZT@`e&poivnrzg0r?XP0w#YS}Dua(@=4pCTOn==QpIS^?md- zBW$wwDb#<|b3tu}p4PE+1kyT|wY~Lx9ZN?btz&5lq;)K7d+Bv_EbX23w2q}3$PXYH zKtM;bDqXL0RTKit{J;+#%c5?2fsSR7MNjKk)^*j>I+nITTF0`ui=MAzX$YisEXz9S z`8t-SKw3xA-cipFAlX5yECg9}EKT@ zj%8)Mp08u+2&8o^U2%GTU@F_`X&p(Nn1OKNSshD9tX`mFsRYtGmP%lC=vbO#^g017 zqxH0or8$t+u`G(x^K~psBlWaCm1-cZBUu`u=LZlW(mIy4t@L~yOM4)#W9bUh^K~R^L-n+dq$7~NT!=ZSH3fbsILIZNlm)9{ zOx7{DRW>+7H0y2l{<>^f6_5=9><8&Ub*ePU37uM1fqb2crop##9GIE_)dy>Z|1w== zpi+Pthv*G-lI91}$x(rU0k}uOJwI;86iKQ4{|6RWk^!NmcVr!^*AGx6kVZcqSj_{> z5m*j^kzvH1TDziA?f1d))cCv*hBwcVC=p49cfX=e{Qrq_G@?YL7#=!Db4tXJXv~I3 z-;r_5&bF&KWX4*O>8%pc!?FP~pEqqbSU};haLCkC=Nd^>tcQoT(QiZa$%mW0az4ep zAi5i#0q7UR5W}={wDJYers3Ih6-k6$f}1+2a-(RMvh#~TQ!|<_M_NJCWONR-txqYgT$mrC8yiKQ;ps0b zrfd@52E`YnseTFx!*`!paHQcw#8K8#gk20ovXsLbc251a=3` zJ54Wd7gIyZ^(v9>L!`cfGqRg{y&^I~p9ee>w4F!uX#OjrcQ{l3mUHXgSHzQXyr%nL zHovQd?}OzBhN+qjnwxApL|O(frkP!=K2~vrV$gnuCK8yIKxhSH&*k?<1?rqo477EJ zn4r$3Uw4RpZFrUHb`XSWpLU#zc8ZwTh9^RmhWJoNZYwOP z<1lH}!c;NyEbT?1<#?V_;y^s73)fO=LHqhO!+ka&Wm1No)ir3a^QUlK8!yw(J4L+V z^rsZMOLU6Zj&_y*_%mk%wjIw)0ax8i&%2K9^R5F zcZn`IE1*KBmOK`{eA{ke?^<(KUkk{O#)L!jY8nqMj@oq77KrJktimAUAfj)WMCd?v_s}lbo!x(WEjw(XDSOUrsHrmI| z_+sgmt)ba&XufkQcDr#pP+zA%UKOvZK~(yhSgh7k;vR9s*sx+1#qWiYtl|4rG(b|ISy>WQ{%X!BmNBCJ7|0&T2pRJZIC_d=<5?h|o|JC&$rgZ(wg3S0{J+9!|a zj|lZK?xYj@#P|+7^;KhmNa)kN%vp8^P&T^F)*$V1%JSe;HI^oM#4vRyZT5)7@CLT) z+EDsvkRx{@z2m`op)>vD5o^`=XwiQ0YS8Q8VCs1s!CBS=A_}L}Ne4t9457f3IKLqX zD=*s3`2R6A8=|jfmvx5{rM+?s`CwDdSYmyi=XvKVlypd#hc+w=k6e2nMz=hi9oed- z$P}Da)Y5Qx$1@{*vwz1o*)|UM-Tx0{bdx+~!ae|?594paE41{G$ck*Zj;)8MkNpH{ zq~px6`|15dI7edugHW&44r)9k?vV|Zh7mrSs7l!I)NxrezJ8+suf$J!Ch@_ zp`Bg&)bo9^l@b@O3B%5=A7bseNLO}-mcAh-NiPeNkm>a08`uOdpP~4}a4Ee)Lk^4d zR-XLa@mcwZL0-nrsV5HOOzh=-l~oFq?G7IUmq6RGQ4I*Xu)S15u&BIVcspz zhCEVXoJc(#*pRS_`rH`?3jy*T2Wr3P(Sai(C8W>C?Ei_h)Kl9Fk&)DJM6`){%L~&C z-~>D#F>Zzvbedw0ijIX|=uO(i?}qzUfCetmfW@`zhQFK-=qad(@BO*YeWY)}3mnj` zxKr-%G+5`jA?~UTK{1R2(~2bkm+j{IO7h$ZsGAY7HJ-mC$@EN~n*~wV4kk*WZO5Qo zH|fYxVUF}F{As;Xp>0H_=^uajmG9{1qY$cIvc4&zLJ_1@as#{Yk9m~$rm&2d+XVkn zzC6J(UQ*4M{kM|hKIcr^OhJ& z_q-)mw)WOtQx9Y#>~wlQY*0itoi4BYX?7>?#c`LL=Rg=y2A@WH~N!lg49aLI8RW2=pVmS%>HaUN88( zqkGIH+I(EBH>7?{-77_r^gbyf*9K!Rt`zAY!o^CFX)uIPLY2sbJe*J^`ZBL2xI0Xv zXRE}BR_p)77reuiEJu=Z=W|q7B?h#?m_oGkFk@F@8RmP*Py_XD??=?TMs(z^queL4*lL71 z7(b%jrPfe-x<=d{SOK%9(U&zMCA$Qi4x#FCe4BH)5<>Of;?^)}w$LRBD^NTwGeHfA zFfXe)c9hp)B+IQmo75c|^0w&IhGEzN!vz>cyn6ogwwPu3;6wWIZR~&Vd`Q>d7DE!! zF=o5P>SIXvPR{m~)?f-_t-fNrg~q=luEe;obeOxjJ8*(-(4BcdjXMFQ`22@7|Aa_y ztz**>lm8BcC{T2t5WQ0M%yrlu_hNUf)OW`y_iy042LOp_(GRwe6XGeRMWnk*39DFk zQrw}o_b^$lAm`9ija127dS|Qe4AgB~Ss4BDu2_`15e3_p@y9hI-MiC9?cN@H+wR?I za`z9|JMVwO7%`@_8?Aj$BpOzoBKLbDMQr`UPd|J}XWkPQ9&_V+B0g~*fb6)-dU(g5 z{ysbZ@zc&!tFK;>T6Rn8?zbrOeUa0t@=@=T05 zxh3E2RxAo)&%LNHQ`Z8c+^Qj*3O^7X?(!T=HE4$-@lZA9%v{`(?aa_TW87o7b+EDk z+Nq@y5mnrhyJO_?D_d$opunThKJL8fKe+XP(T5eBI}14N7-{pZ@X(D9#1zB14{7p; zVlY!Ap8e#TKSbt!u-k`XIA^wZSIwa8kHnLPwD;-QM`C&(j~Tm8c3m57wP% z&GFosFz*Y$&CA>K+wFr+{q_-t@L*8bi{0X{{Kj>wOWV-+(+HRLJQCFQ#cXREdi=EL z667%|ZD`wR@k*>aJGWYE|IlUV1h?;}tE#zC~GE z$I0KSbK252ujtkFJ-z+?&!?ynS}eS<-(mi$n*d~+0sspB8U1`49Y|{?a)5~)XAH${ zDfwg3ao~r@3{!spt+}AAw5|5+Q)6B%_$TlA(|C*T;>{_~{{fdIi~09&0gzqSmI^-> z=Gb>{_^AN*%L_Z;d2{R+Jb+=9t*PQ;(F@l9D<6yV>QZ{|jJTW*&Cql0&LFUlfTLf6 zb%J+)KZawXust0Z;rq|~w;jgu(^vYO;>)6MK0(U_dh1j1A2`-}eQ`?P5QMcEOQ zdRFubJBQ5!s?rEb zI48`8wI^xFIWZ|s2Vkr1tzAb9#2-NOU%e5E4{ppmb;Z2Be)2eWPOJ~#{C*>G9_!Kc zKIMHWo{f1FdAto5;j3~*P;_|?=f6*euSDM%dsA64{2M7ykZYlFOnslmeI+^>TD?mP zzY^I=|3N>0;AQ_J90+(NS+QF)JQFmQtoP~cSK^UmY%WforZHHu?834f#?sJlM4ZHGbLLxPX~s9gT!=|< zR>LB5u};-G{^LK$5W#EC7AdjXuYdddFl6wq4*3MOScZHBQ4Ktz5RB&Q0BbpOiefcb zcRXN8XEE}(1Kuf=y@TI4nt4v*|2Ejes)5->9N(BFZ!Uh5{1}Acx096ettg9uM(yOt z2abf`=m&gQ@Xizuefh2E9`nY@MuHr0sx9F=L(lxwOjJOXlkqG#Otc#yXc1*#2TiQGsz+ToL}S5 z0ft^|Ov&cveO8AT^Z$=&>PZ?`Ct|{Gp$k2PjKNLt$28$ud52Q&0?l;K9wvho z2o5^o-%Ih^K1|7cQeQFc-BZ?5b)D$ll40^k*dd6V8|p<=YfiiYWd8lxBbpcT57Nn&H{xFjgN!`Xw2hZFzVFZ@-$7FS=LBv3P7DZzg5XqudCn^O_B&`QZQh~K%OXDF!?zpB0qJ%>%9o%# znA-$BzI*eWWqRWy(D>9utI ziWnR4mVdgIM*jdO>MeqT7d!o)o%xKHI##8r`%s*l}nj@RzQ z*iG1E=0Pia?KA(uvFMt)_Knpv|ElONd6OBVhS0XFA|W1~cBcia3Xcg|GtsC=xpZdZhbaAopJiCAhx;l~v(2NXNlY(14d#YP{8#=gLnUn6qcKhsdL08H*i2gHVLQ&lbrK^1 z(B>UxES@4m5Ol-ww{S%YtNmTD5i6-j0CTHRxq2Jy;x2rf2MZJ`2*<3occ-Cj8yvV0 z@|jzWM*90F5!w;_!R@BbUDChV08n@whJ8faGfykn1=n0A%gsf4#IPf3rBr;R^q^6W1>g;9s_zCi;eTSKsGjgkMQ-z(5)aF4j~YA(e9x&wD&jBx5p@4 zcw#u_y53qA#_$t3fK69Nfe%~P*)hRpm>uY^vNC}puZa%E1{~c6T*Ilg!31to5muXn zNa+*QYEbmp2E9@LO&YEKEj zBe?Pa4gVc+4%6tp-(k~yntuIVbdLkNd}bW+Z$GT}F8skyWcT6GjNAVZ`)eQXk?f3@fT>#|^O{!JF+eX=Y^=HsMJ3%3exIb9!ba_5NF= z_w!Z)wPoOh=4pzCLSBhss8C};5^q^DWO$`XE9(mzKhzEvem|W@8~zr9gS@2<6Mg=- zc)<`^P4oW|=`Fo%p)Ug!6|0$c{(~1(@P^|0+`4=-h20b#U{LCLQ$(vhX~a#~Df6pn z=LM4ocM+WG>lr70Jw(GPX!&B_zD-WY+ie#)mM!*J_!ut z!n!GJRD93?^oFxmRn)8U9o6K$P@JmGI)cbnC>)q-@9X$ufs=3Opv_b}(n+K28PxE0 znSuT`N>ewKVZ~N;(4Iv=Z5>#}OAiY= zSd2cVaU;+phjBlRUai0RGd-x&AH5o9rfR%EZ!SKpM;H3$(sw~JE6R)A*83*@ z4q`Cv3R1O~YC2Lz3)z9^6TzY8jx?i%9Bha^PFq^YbCF&SV`NhwO9!@v!bZME$c~9# z7nV&vcu)aVn~#?T_{~e3OsBAnYlZwewPYhy3}^!iwxz$`!mVBG{@-9=7^p`l;ml5S zUdoRQ-XPi+Ecd9JX?lnpW4QYmxkKc^FjT@fCo#19deWRw+1=3o7;O%fU8Tp4Mex}S zdOuX!(oiebZGmiUc1W=uoMVl#g|6p_A;?d?K~x^~4U-2_`hcT2=9n#MJmRO|If1aV zj6gje7HoN;EoGwgIM7Q5+>kBh2t(Urw6LY@-Dx85U~Xnk=E~cTHtHBIxH?l#Yq`Cr2O`w-4n$}n6b?J?f~sv+#E)!0%(rU$2;XjuX~!7HVeZd8 z-g-Etstd)ok;7Yo^*p>aRpocp-XyJ!ObElSrDxUIEc9F(nb?YFleG5y5P(@V3RuwLsB<0^_k`zTUz5*ai&k*jfws zs=m@DcxFduGDgZ#L;QzvR{`PR)+W;c#Fxi@z~(!Es|ZyPVa*H8g*x^Fsy<=dv8kxD z7JP)(M9KjpN{@g$Q6C$E&W%}bHc~LOA68NOBF)&bV9P-IG`vyJzB~4ef$E(7ea{(qX$ZD`%yxX4NQ@hdwXEe}Nx#Bl$}mBu`)ex8**5{Ma&Ye27fv0`jAD=qGg%ddvFJUJuJ!({>-JgH?Y*iYEGOx;V6x3C-=1Tgh9br z20j7W`iZ?P)u@@FUq!~rj-kVG9JiO*d*;_aUkbop1y)$aPWuLZ1wRrmyQeaQG_DQ+1CN-V3l`M_e% zsV14*l$)^wCPA^yobh}0jMn+E0`(BFy~CD zHC3)mt>75cn*>FB6VrbaoqmA2MWqIMyuCE{;EL6*ZW=d2fio5Vi*T38jmpdukh+;% z22-lHw8~5;+spq1dDR*-4Na5}r+P+X8GQ(#4%AUGXM|W?RNtHNs4-FlcA;I@^8tP7&$w3I&3p&C4d3ZbZopvuVH^fZP_O&m#Xl z^vSDjJ7y3|(^*uTNi&jURv}Mun7Nx?I0OUQ@~gj`2fq{fb+vu9F3m_C^k=enAsZb$ zhQU5F;Sew=&3bnk=V{D^~w9Cq4w*#5_m<2Y;cnY#T|@%`-KzFjcO)-N3H zgVN`$n>jqlXU*?J3CS`s9LH`aLvxvXXt=pKB3aHysQbZWIn>bWFkMfUopN~O-C8+v z(_3O!R+HzduoV|8y|is@pNY41QA)ajI@m$<0i0s3ALmLwoZ;ZXo%tO388pKr6I=6g z;S3&$NzJ6SCK=ZnlGBMNRCFz;uBsQkZjxR5ahJRVid>zw>2L;DCh97wo_DsUlfJp# z#ZKY`rCi4e0J7^kQKVVIDSS7kx8dU;y2~uP1bNNXW?E*JMX`TCUNNUQUi9mn0zUSd zE6tRUBJY()(4#Gz1c>*Ero%wZqNe))Fz*cRk)cl##a7cX>6DSVCWQa+uyy?&Ucb%8^r~6W+xp3<9 z&_zR(%$2ikzL6m4>@>x9J8-F2hWUzTtGaE+JZ_y>)`4_aXSuu|;#m|YLtm0@ z#nmzuFM}KKnQ)^!Yg=b+%CaDB@wOJ)k`W3{Edd`)Jv8o!3X13=H^=ZC;G=h1S*k&+ zDHGcAvLJ2rA*${oT23ti5(+q z!;mthVq2R0PBl1&(AsqQLKyQflOf-%P+E66#85nx=608N2RGDX54n1oZwo^tBjLp~A~*mmFv zGO6@>57{e{1)yFT`$xSiNHarX{@DYk(}pge`}?d$E|;3?G65>V9SRW;3UAjBos`T| zJ8XvwyDAG_LLDnSycn-W7Ep|q zs!GjbliIv|sWF@`3T@~q;}dd$R;>Z{#@7+Aix-X70T!QaTrfVI>WO3NpmGZBCF8@G zlbM7zgOPgll8HT-2t2apQ5Ba4X>Wn`TVYgtK0u%Y%Fm~SWpSfAyP(Brlv@6J;1IZM zPPQ)@-)Q33q%J`7ejdv}pP=e=I@(LV8{ELw5r-M`*IRZ?(KU~3gI0`8mQjBIj5U%q zCFm4bhKUF0Y;T#A5PhJLI9kV)rkiv10S|>QCcnTyturJ?;H78CG@aS?Aju+01sSqS z`-UP|G0F@9E5=bse^xk{rb#JJ)eISz!FcjR2|WB0z_-q2 z)G`5SCR#56Bs=sGYJ$iOl`={F`p9m<`kc8;88o+#%r{&sIp;HKS!G3_w43uMFmQ5NYyN+yFS&N$kw-xl)b<3u!4(a$T{j(VJwz?SY?b1-~V5+L| zs;;jK)zm2F`Dk|!vr^KW4)f5ngQR&v!zxs|P#dEK6@_X)Vl!rOvIc*tRiWB20J@Ak zVA${s{tA${9QEpv=i1B94s`gKWA2*o182ZMw_&i1#zSt@xNi?F9V#t`Pxq30 zs7#3r#`|?_0%BE~%}4pBFgia}zGH~<1S+m+s(1{K*ZogLM_7fl$&D&|9$*8#5T@b& zHw2d>mydaj9p@KSwZs86(*0ReSp~{E0xKRpVgc@x4EW;hI(T!npfT6|SioU~TylU9Ik8(%I$2b-*-hFi%eKbOj ziVQp;(sU!Dly5^!Bg;scX!IhIdh|%SFsc4Ec3Q>gj(!6i{J4Pub3;3KKI~Ory++@T zlp7*m!NeBM9n{~1<1{;7jMHf4ZL(7YAs?rGkAKd<{#H1A5CePcHf;NzH7GbgC$s-! zdGy0=a=u~7YcypPbP$h2;;p_*v~rZZC)I<~oK|)Dzfmnv0o)Gwm+|DFhi7slHs#TB zc&Z031FbEBRhvB~Y|`gD+THYuy5o4xXwYKCUfMBQP6*f(agu8sE#m^FzcH{SjggsQ z9vtqyR-6*xGR_+#dz-g>=_j+!i;?aZk$j8XYzFm)_=*#~t z>cDy5{%>9~@_6`m9MwwlDsGICkErS#dT^{9+PP*=Be4~b9V|RY1+T&Z18T=9@uvvG zLe%J)KT{&_YU+oXU%kpV`2hOZ}fjUTLQsAKWRJ ze>{4FH8*KD{ECgntWryJevFO2}SLH2+Z32!`78sG9Tq=99kd_*u?ZkS$CHW9Q5 zPs0IaO|H#1LruOq?^4CLcgvXuHM_z#RSp#D{)(saWmquogRg!-9+yy9ocU!@731f~ zO$G_A$+_1SQSr+>xmr~pt5`H&{$fyv(E|(Q>tWc8oXnp^wNVwFACVnZb#TSlN97?E zS0mma@tCYf#PF5JWR3be?OBL_rz#daE*Gl75K;UU-`_e{3*d6`e604w*E}w;E@(HOSj~$mom57Ja-V$d`!!_vsQB zm&Cy)8xXYU3dYr=Lpi>>V5OYf^Tw}Qp!%5ZWK<9{Co2_YD}PpCw-rb{6keu&xQm=|i~uRxDH04{1~}M%a-S6w97i zqh-ai5dTt^$<%0&)&a{zvn{n8T;PUNeVKgB6rSU&t&OE$ zmO)oer&i15&{ktSOjcYp!af;K_bitMcmx5!x5p2RPF7-{vnMkB(!3o|R;qW)$ zR3;$|DTHOM)C3}-C1ga1O2sRrMSX|%tdMIH)>ZgP#Uw(N>Qiva<}1MI9~zJIPv=m& zbEWK==nX-rMh1*Gb~qvJ=M6q3QYjz3FZ(ceNUoK#i&(O?k(T7qM=NF5Ft2|~3!F>i z+}Yoe;b}QI(#yeuTR@l-Fq7@Tb27Ngl>4-NV50Zp6zp*qT4@u2O|~IOE4^UU)&RRp z5ZH8XLwNq~8|-N}f+UDJAxk zHvKJ;kC85{QGJCcRi7Qic^rJPS}w}*vLUC|C=s*}r|l|Ge66=Ytw10)+e~VgDHDf5 zZJ3K;m7y#jVLx1dE9hVass*TH+(O^3hE{jSOBA{W%F(EosM8vmGT&qQXKAfyoNrZ?wOp?y2=OY${w?Z2fr(fvQ+oXIGTy1d zZ-+5%Esv)jYDxq0?l4ZzdIfEJzNBR4H%)~Zff@yCp|@Rqk+!Urk7Gf_JR@`PZ^|=r zXdKoRKL@-AJ)AZMV!k|p03JH*4X~;Tx4?Be8-DX!JZCxjADO3JW3+u=n*cg@a2()yg_q;V^c$VF={A1H9>iw+D zz#wNoD@V2VGU04RX02?SQ9Jb#9eY+<66OIQ2R$*u>r#}75KelJRi+d&J|}y2@s`?q zXbi0eHNOKXOHtDWTYM?}5v6Q_g*pRuG1}x49SbsRO#(qli?L=MEIHeqaNN7zW)FL`(nk%Gts7r zUd)$m5%1Kjn%d_oKKrAJkI7*gqLk0hqotb6YUwo_5ekPXvlk^%jV9*>dwH}DHJSRY z$EhagC0e>3XGzemz5B$nWZJe~cDH~n?C4-8YK~I_mr%I#Z(!qV2}b61&QBQC*5b+W z^)STk-AuX9%gi?3!>K{qfzCnN&>l)w+xoFY$Zb6n7IGFuMc6j8m0tAK^D?m?X265P zoQD@-^|CZ=7Q9?P*3Zeh_iyXr53-fam(a&b2r3@!9HcKpMp@NV>QN$-K%j9YGA$9q zbj`(-pvrKN-UXw!0DY_pIli}7(S{P4Jc+A36sR&1szxoUU`zK{lXHA5PSb#$9qNbc zp#XWUulURJQgeK8L6pza7e}c3CDd^khn{W4?NH`kO`$Ky0ioO#ca5&by&z{Be%eHb zUXU{*49JHHc+Sj~G+ygL*m-yqX~gnNT@8y0P*$%Jj76BQB6 zecx@Q10+WqUfe{DBr{_@b;dBa%hXb4|p3C@bWuK4xE zUI9z!oIIMj2}k0GH`1C-a&Q1(6+%%?Z<6=3&INO4RT2%|3?F8H4B`sb7mM7=u}b+E z>=;UrHEUi~l2(QRC%>sIxQh7V^yt-_pMgV!BQjXvtlS(Bsm#i}vUUItzteXb{c|3# z2o}9dn(DErV^RAO>eVAway#0j7?rTBYiPg-JdsDgZI)R9eC;k1WxOZ{_io$(^I8+Q zT3r5RcbzV^ANH3sNC9yB0Lp`|YvYwZ`OrLGl#|25L8n?sbe>{(Uc^fv$4R2@FUh1r zNLOb^Xk&v+vDzM`bJ8-Sby1E%S+ofIHye^+j(6@b$7)w$i-HwHXYv#{o-V?CT!*|I z^ou$kmZhad@!CxEpSvj_(DowzQ!i!WLnzNjx)|GKt(u_i#W-U7C?z2C9X?aB(&rIW z;5fbE#qG2-(3d^4!_YbS&xsZ4sjcmxubzAGglQLJK+U!v4Ip1z;4jCv=;?}lJA!r+ zUWQ|H1vrl72VX>RJjHi15yyZ^N)z`@zzAod!yTvtcV3?Y?gWgMZ*5Nxy)4rWcWt6A zFU#JR6E7f8=f0pUW)t>CvmJLg@(!S(^@;!9TDZ80ZoDj$M(#q#;Y!@v!ywBbe3+cu zZ9`|g;kuB=vZe-gc#0l=RXNOq+zm`0#sHXfJP5Tum1b;#B@zoJ+^y6n(eqods`BXA z7G02kxkV=9*NrW5PRA`Zerk)UVm6pC!r#XYmdHKnr)hJC`CPK)?&8+NcHd8{x61ZG zxv^S0?cOST#07y3+oO>Sjs5}lY(3$Q_tURi(Ze)q<&tTw@4t0O`5kGbOQxstINRd& z8J@ARHhU8GD$hRE3Zd0S`xzenx2>ItTymXZ|0e2GDmNRR+)z$hVme6W#@Y?m2P zyj4I3uQvv^J_kBofmagb{UG+7S9DEd?<=yqT20@)B6nsC#5n%O^A7bmrtlWII8n*u zt)M0+PW$H(t8ZGkQhsrv)yH(yr`4QB6+3X&c!*l;lrs!oqS-rT_xPBde!A3YOcwLv zy*T!~35C2C4{1J{hi46BZqnCam#Jg0x=_yB?Z9Z57eWx?hsPTrTM-R;6%Ml{TnH)`UFc4QufjgHs0pI^LKiyzs_c~r#?reet?#G{k%3JJ zu$LQWsn=w`Fs7SMvu&Md{A)5x?LwnA5m^NHCL9)+4=@*w)cW_GSVH2co#=2jzx#R9(GEn z76_iM#Q`{mk6d~LV~l$Z@*P;lQOM)NNFX0?QX=1l{K)^wk903Ze)9pP9$#KI;Hbq| z!~f6*!GOKA^L2h=(jBt)qQwVgdUxoVD2=!9;{w^{-Y~yMxi4Z=mteEJ4hDcN(Zcpi ze9gRJ-gG*9P>xO*2|@LHZC8!om;*Cm_u*KHXm>{4KpJ>RcI`ax7NEs-eYE$R09kPl zkt^~_D>Y=$+C$Qu8(7((gQJ(O@NG(mWe0J&fpK%dMK9eq^gQydzxp$I_)ND_M}}sA zdc6+$Fkk&k%Sa6mR>=6fT7njpu=)O98i`wI^bu$j4jMu6U>dm*?V;TV67hPA!n?_j z!j`kZV9i>9(1u)KdS`uCdZ93(_c%H=}kSU9FJq`!z7SRh1b!d2)a*?l)y( z67>AK+5i~_Bj1F4u3HCHvBp_3*>Z}1S+0iPu-8e9PqG4qmRf=xwD6E!E)dv#_*F=5w|$$UwJ#%29*7 zRy>lzONg0v1zsL$Ho361o?QUb(7{yv{fY8xV0t`5bmpbh{@UW2zO?L3`EaE7?2SU) zo8i|=W8B;NDZY?iB;JyJBhG_y7&5K{c^Nt)?#I0aPYZrT^M$%6-;%`<`%sBjYoJmT zR|-ESheSw>*@dw#3bkh8U}!NqDessZ&W&UFMOF7PISw`rT(Y8@$K*D(1C<_^*?5({ z>CK1~JPLdq!QFai=D!L*$>~XZD`mRG^CEb>`x4bx%DSiqe@*nqqk!FL{9X3+*SeYq z(C1aMXM*=Nu^)bk5 zxu-^<88z|_={+RJ_+B_rai~TH4$2d+;V^%GiL(2A zF#fkw4xjI@ESkKoV&+NNS2eVJhBm(|aYrUjQ7SIHD<`Rj%5@b3-j@*u!@zYF<35n1 z3_%U&DiwP1BWW`{zOLfikL2p0HVs!m>26T%LZOYvRV(!PC-UK7@6X1T?uT3k`sEY3 zE7+@GvAj_eg^m7>>ei^^nJW~lX$B!`We2(~h)Ghp6PVfCAtVXU> zm~j5*y^Bb9;Hiic`cn~?P>0VNY$n;cio(B;_Xc}+EW<_JHl1kk7jk;gPpCm(e<9n2 zgVmg_1cePfzOMMv{5hCY%w#zybAz}ma-5Tck#X#toMh6Slx)`=7G>Mb4fr)}*9Aq} zmV?(F06XJLY3{^!t!B@1Csgi$%E55+a8F!OQ4#QBq9?zU7QOdX9c;UG046%{C00tv zem`xU67FL-{44~Vm^V;2h}%<_uVk|HUIY(x^x*ovOfXopY3^5Y_|W;Q8i}hv(0feQ zZP>FX!@9mZT*+(+HFFAx`Miqjzlia_8)+bLg?#A1 z?J)MYcLX2)971O-I^k`+)Yd|~o~mn07CSx?>lIdQf?gJjVEq=Fp{%!NbobVVu7=_Y zYiuPh94Z(%whb>MWh-l;^%IWVoG%bNIAxrV`#aAxGR9hd4^gD^6~EQD@&H-BfdxeG zvC1a2kI+WtotHjx)@{~(phx)8<~=!cUhM& zv{-c65?#IrR33*cJ&FHZcNn_=4BfNG`~>puT1nyG%7yCvwBlR&Q5(dxNzJCChbPBO zh_X447@CoozY)m%Ug@CkWL0(q*PNGwx_F;(;6;Hk|NH*qFw~w5(XgVqwxJz`)yiQl zy;DHrTnLY>nV~ebR(5Q87g${vx%Is@YGag9; zeg-XA`}-{Pe~cZ%&N~L7T=r29{7+N{HdC*mR%p+l&K7L2$A0%`@~6+Zz0KM~yNdRB z1MJr;*ZdO!+rytjW8PYb;n^{~0j5Z8k*kN+E+>@c*2&unz01Q{dPlogLWB)sHP8lt_~l+P*xq^n-PswhM| z)Rey*`Qw}N>(o%qqvsE{W-Ublbc#R+cB$dU4xQhkEa-~oTi!WfoWLC)zg=1IJ)+!h z1O1^TI78H~TAd@49;!z`=N-rdWCUX)Q*EcEeEHyC>j5OMc@#BLdltWYqNA;IGWy@y zl%Jmxsukm^+0!T+gfeCW#K>BzTv97W-bLhb=X}LsDSmIm@A>Gb9(zGmeu}mTd2sFY zi5-IhV8Wd9)Bq3Ju*nzSv+%D4sPG9I-Gg$h8Rr08@nV2BL%WKc3v#+@NLo&17oopI zEvNS{%I*UlE1F*biFQxIa7v3YM0`?&pHK_Dc=qM~-sGM=WNFC&6w;Yy15o^78O z05rQMjAnc<6Ahi0(bDf_r;Hbt<6A5kTDHEp@JSUs>N*o2kGKm_Jexr2btvbvANa|` zF#$!6Q2Lw!yu6IA18kuODjZ~G3yZm^73_Gz^8Kd}9>y7GAMzL{_{ZX<8OXTaI2d5) zo{?av!1F-C?h9W$^w&42%Zn=2)KWYD5-vnUZe3p zp{5n>yeiFVY{h$5p(Y!y7E}07(%rfGbw52|kXi~JIzNYW5iUt3E9%v`|M({|%KEX? z7G81wCm9kXxtleqhKgT)mFY%94S4Ynxj(X@`KvU{;eWwEYw%G0A2K_%2G#TN2v71d z>V91&#WLM|cv^f8bf|0i4^u+!Bv&jIT$kpw5C@);gY7C{u8c-}S&Tavv}GS+C4$SD zuUOK*SQ$(Et|JunS`qzxUCs`JOkt~q+m35ZGyas;1TWv^;hXZ!%6g5iVz+nSw~CJZ zDdPuVW$7(Ub+KB{L>zQrc3?a3TbPTFQCBerUL?rIlv?5M;5GC$@{86|_+K)9I13!^ z(F%!|fcCtl@=Fx_`ovDaz@5j4N^I6=i}-94YxxvyD;~=BZN$ot25i3}`f3sF4{a4o zo^OJKso{cXMVtPTLkn5J);jPcbb}sOtv?ln9l)86B@Xs>I&AIqs{v&&jo0M2)3Oow z%kepwwGgUbwb zmru6s`wuGen-;r({w};M_#S}sml!N?_uP8DlQ;XbxB}||kVgw?%m1V9-5;W?w*T?x zd4|h=K)K&Rm>CpxP*fBZRG0y8X=x&Asp$-O*EG$vv}Ay?iE zf3rO>K@J41sZ`72DCKwDEqHL>I^${b?}1q5Dd1F!jc=2a{8CEh?kIaI%m`n04Js2Xfu zCDz13Dqp#($)wdon+d06r31J6+O}>KD2u*1_W{e62f(fj8-usvkmjrnU##;3;vj9ZJ?*hRc4qj+V+IEdd7`CN$EOVvrh|3c6|CPJz$EJXGzYy|Ty%WMp)l zPoxX7xTPO+nW8xTXsEBY0D1u%rofN+K)jKQ8QNZE!`*$>fr zMHC0~OmUYEC}mw$MDNLrzMNnxOV%mPJ!m@W5APsGOHQ}JMxH6qL8Kdnvyg)xAIBOx zKv3Q)8rhyF1zu`}mK-k*mzQf&XqiF8E8jjyPZ&ggAjAokHIj)wG>G1TydWm4kqmxf zchsHu0baS%V(6_cHuTa!d*Joi4|R`O>Oc1r(K5n8T=5r^`+idAvkdq$LRxP7*<0iT z8k`nZ=JI>c=L9Et34k$y>5e54L*(_eJ3wp-#@U^&1`4a6$I;xQeuxlX%du5kVC8`~hA~&YgPg$MUYKgRrWXwi5)HDQ zehd;z`+M}3OZsTgOQ*H-q=st9$3UMgFXDA}t9g9(>z{fD<)R{&Yf8_i-sdfHEVVVHqr1`*tbZNtvLM)~!`7cZ3>9-zx^DJTFa}f$ zPau$*4FVgX^uR07*+{W5$Rn3$YKu=m=ZRh&i&!#ul9znw66u;sT9imB{SyR3~^>$_gH zc9n`gM|+J>np+2VIZdFEMo@lcXjn38MqOL=K<$<_czgi|4!sHL7Y(#`K0xE5MRGzf zWY{6zW3eh1;E7?m*@_3KJX)m1yn&7u!q)c$I$?DtBSJyLiRh7Nk)YhVmd>I~Pz&<- zl|Kr%{ut3W%9Dx}`VeY+OoWa>b+4v*AdQa^xlj;%B1Q~OFh2lUn(llq*3}=jSP~>f zI0@X)Q$8Cb5<(D#4GqS^<|fiLWfm#1=;R#Ic$7_u01_+41u;PU8{U}L#|l#-tjRL9 z=UI0S&>zGG#k5p1RQJrL=2$Tyav+eY_`F54;7DS?Y_M}njT2T@fPgM`*&tdRCu%bC z7&h39RpVI+wqvmy?#J&7-h<5D{sNd1k@gmvZrsIcij)&CGGkVw42w70fO9;7_hM`- z?x*s2krUDz-I{AG+GfigaU->aQN^)lV@-6{DZuQUOUPM?Zq$VJ&7_f-RJF^kLu zuv?XXiEgo+5?%~zpyuoNs{XuL#K;j`nZ0JS!+k!0(&6i&yC@H8MmqoYIWvu+m%5AV z5j?{jiJldO8F|WP(V-rKRgf?C5K}|AtsQWheH7}zkdBT^6X}X!D6LKt3xnS7Xb;-$ z-=~Qm13e7M9beJ8o+3jzx{5-2iQB?G+~eQv)5)3;o)okP{5UV{%Dd{H?j=5!19czm zkIbxJY7wJlrDg>kN*Ay8^K?p7|L(M>)15IJj@6)@&NAki^;`OgP&uIyc6x8XED(6! zSr!ZCHaT9yWw;Yk(k+|#^bpDxBvz3C}`7f%Mi&*&?-8TA#UL(rDzU@7Sc}) z=%@eq1@Y}a0q@*~ox&85d$@3)RQ2f@so^sqApc$oKIYtgw6ve-k*-(zyHg}Ca0(Sb zIxUUA`Cbryf#CGSeRQOs7#0#1sWIfmW~qISJCXwX3$qI76+r*p63Xl^K92MZUIGc1 z6dha^#3v#o@BJxZ0EU0hN*Xsnn2erdfY5=x%@F3pE1rY{hvT)yp!Hp7b;AH*On0w` ztCKaQu#-t0u06PdY321HIM?0Gb1-pkHuz?3#1c9)Kn#e~Gk7}BcT8uWC6tgU;7n|@ z4oI{Glr=w7n3diuXK&I#iJXs1F1B}ZQuxVoG*#!MOUin7? zV5dH%2x-2O@&}4S<)f9fWuO>mXD^#>axTge(oj9k(MPM4D>iNtnFCq^1-4< zs7C_N>CA)#7(UuJF04N^SY*rK-aSJ^e|a;RhKd+NOC5Aihl*5rR{gA@!X%3pe$=!( zQ|Zxck)?#Lpd;BLM)_(Woyis>Vq4;?yJ&H5LnEO%O^baOa?<=>S`B=+<%rDKVfWyC zgsUy^W0kTLb&}<#QrU32H%Ighnw+Ue9I)($LRXIHmf~?h(+7-BWi0~FRo4vH-oFS= z)&Q9_e(%M`&k-ZWwZy$Ok`C%fOKqKTR1fa)VoZTUd5E_R+TCVogHpGO!!i zmUhU~tgs1U5i3MmuCvQ1bA(8T6lm56F{%p`D}A>U#bKsbMhJ7fX#_ZW4$%>Bc>{(j zLBNW0d=M_B??;H=yO=Zfr* z^8m#O2^#Roa(F2n$ra}00HpExTXReS{}<)T2Z#?s1Xij@4V&(vo4LY*;A6e>#Mo$C z9smjgKybdZA3BB;p>uiFv{;FQTru@muh z%c$@T$d3azW$uj)%G9QZXss1|)s%Z^i&e~1ep*U5@!Qa{q>K`5LU-98?egrbUu6?# z>SpAFw5hoj3#--4zk)k+Z#}Z}`d?B7|Driqoe+fwjqhpnCru?oq7<)$-q{FTU_1 zU<@G&3fJso9seUNo>OjpfPtHv3^5M|w;s`s+N_cE(`d0d=Eud*?-1APc@Jk{QKBC< zyjFELZ5<^2gTs3?xmxXH=p^5(=a)868CAWw! z(Mc%BjmkhUzCtqp^ek<>MLe3!%T>I-;I#@l_@s=;Q?1B)71enVmqED4iKB{f7+oDF z=0;)Ul{yD3#cFsFEqn>(sCtWt3IzXAImZ}IkB%1(<)cOP{dnP0b}ynWw~DmLOl01p zPgu0;ioX0TX6vjpmyrgFZ_@Jgl(<$clI;otLyLiz#h_fDv4$w6=K>6;2Sf z%7{gDZGxBqbFjjRVsOtd&<7vPJk!tMn8Z=p5Y^E(kB?`>0kPIA6Ga;8oS7)f&Agn^ zI#F^KI`>Kq_bPE(Eo{`8qFV15)xL5ut+`#y>pHyyZgx2+QQ1%tO}Uf9gQ&|S5vP2; zgwiI7Ol8Runm$RG3-^O}XH@{c0WqoJTTlsPObP}o;Zc^o)6IsF`VQ<)?i?48q5upY z)K8zrCQQKj+5|27FqRPrjyLu9Ckaa+&gaTq{lm#SNo36!j31wx<20@eZ1>H7YrJ;# zbzC^GwoHfK06FDKyyj(Kw`=VQT6IT0I|0i}l9n_6#6f)Z?VsKvX67xnaN1NTlEOR? zhxov;AsnwMo(>m^;bERmAZ__bHOEunWYIekr+4L9bjBUo3I=P<74cLsS-hFar9mB` zXo9E~<#F0YgP#TOZ`zp88AIb;-LYfX9L1zl);O0D7*!=^3fs@9mw0LM2@G=i@-qP)G3PD~XAID0~-iK&QdGk2OOQ0`bnu4y7aG8z3Q>J!dx z^5V4O3Nv}9iQy~`fsEgnNCkI@0R=Va)VC#KTrsH90ML0`eEO7cs7?A%<6N^Fy!1eb z)WAdIM}wq}rpqc4ss0XOihUA$YxsD%q0dBH!yy!iMuD2*aQf*E5hq%9cC}{P;O!{% zPT`F5gdr~if2YclG@l#hII6o-EN6NWGhJAcx1ljU8BO{L6YVY|gU_>FjjTH_4+SHwb^mX>x-s8?kgrF0;d^ zjchYg>I~7nRIh7OlC*uV`Suh0j0!~!29!&;)pXO8=5A2$3AF6)DDxG{gm>hdpx;;5 zk$w*8!AS4Yk;jfN%WWyz^BwtTklz(~AszWOHF4dvX2d!);Lv`$qY%3Tx-gH<%@8n{ zXCGZ<@CM_ZAsliXIcADues#DZk#k9Cl$q};4qW6qIVa`=oVx89i{hhPix<+YyTo*P zBQ@M566LG(@m=DTWKf_=raspUey(FDQa5x`Ar2scxb(HNM20+uKA0sUBk^iUvJNaa z2*pl&D*ZM~WSL8_0x7>3uBc#&{5uNNRQJ#h!knuWcmk?4VYV2eqzrQ*@U`hU*N5}2p{eOWWsa=@5csz>rfhz&l z2ii>CDb^uu%BS;ax&ybXISXiw0|JA07SI-lxT`~S*a`?8EO^t>eDa}kJonn*(rQSt z=$1Na?oGmG(?M#2Zg7UQy$X^t2#e?oW95&6Dbq^u0oenXXMfRuxc{p|01VYQiuL9^6Z zI0@-MhO={otw^6ITWdcoUA${3DtQiiiA}6|FR_%z1bsVhEDM$RH958;y)8dePw$6x zKDwB|aQT|%0kmwch@P(jSg=143^)VIif77`UOgJ3gfq|xy*gP+j<73XgPAgNWk<;% zEf$yg7&Q7O8s#)ldrz4%NQXQO=|_>yITxKxuTnV52^D+hEF2h2GvG}_*aZ% z2MUjwbCb3~!TifuX?ZKe^?xB`O%~0cC;E4w6&yBgpC?8sug<57^TaK_R9itF4Vf?O z9c3zVY5ROJRk7#NZ}YKOtwSk&f#?>JG`}NY6@<(2^J(e=oCo9PQ~3gsraU{3Tnhxd zt1TZ)mlgo=TeB&2p}2zueURhBmDI9@Oq9z3W1D#>ZCWTsC$#42V+h3<*vlR!NH6WE z8%{qh6iFS>RZA4PNWk>?=`q0Nd;`s1BsL}v+31DST5s&bsn%>p`A2$o$WfgN1uhoG zFwc`6DdmyYY?D)_A&bSsejdf>Uw?G5xJL=}G~yZf06dH?6^o2(igjo7S^Kf!pMh;< zEO^?jxKdxkMe2EcQsYu#lfNNlnJ5nV4wG#Uf%y$c-l7e(Vwo7M{8B=$Wg?p|@zKz` z9o_DMq7uKXRii~K3VvBaH8XhDsqV@F&eNs6q~%i=(B*qX zJnr9EdE72TmW!P%c!_i&?$YbaMK(kR==scSy0Khjg?jiN_Zt+jShijE73HoFebGZt zXz4#jD^}n(rNa|5i_WhQ0}P&DW>U<(K2c7j>y6no?_OaV@9AU<4<3^=xLvZaM*%C4 zi`|&;MXLhrU|mndL%<}l5#W#DRebqAau3Y6kQZ(e;I8CeU`&r<3Ro#DY46*8B3B+< zr^vMmli4YqGh&jf7SYs|sMBQ*J+V?`_*Ip_%Ydh)OH@!9N;21+1u6eZVe-uaq;txB zqKBU+wbGx`?-LE_^n@4BO>#JsuQ}VS4dqRNS`8ZJs;5rFrx4P45Y=sg6uL^-eKX>J z7p+I|-d`om@?CUgl^CzgE}`7j;z&Y2Kygfo-f*8JZ72$qvL42LzZ!ll9{Gx5 z?iXuff{@RCEFMF8V~C`EjI#rZkh|{38(0gk7F^7nxnJmJnRqjE45c9th>=BlmO~OC zL{Y9QFp35Ki z*dczbf#;7Z#H?5&&M0GJ>D(I8JE}#XY7~mLbzV~8LNIZyxRrM%G?^O(En6$PC+WY+ zjH?arlY!8sGECjls4g^B*pJQZg2Ipxjq(u*j5s1l#L}z2Lp4b=06b}iL zUrSSKFztCr+%gWpSMr9EA*tqSUD2#DOd16C3IKz!KyiuF1Cic}bZ?M!r8-n90_&yc z+o14NjC}81l)FyE`?V|y52P9E#Mmx+HY2zhDmkyL6T{g@H0uyWxoSVm-8#kitpL&FySrDgxZ6gTogyP+3BGTHbmuC% z;xLMgniZgR3{II7ak%ip$MBk3yJ+&Cbo2Ru7_yg%bk@3npJ8KH?eZVKmtWr|h;%)J zIGAN3JIupA9-|Sys{`5Sr!vu7!Bb*FIf%vZRGLuE#|@nD(57-Q-U~L+x@wUT@d!4P zZ!#d*um)+n1O-%xEPpo#jw5S@7&5S>;GS6Rk;*8IJp-5|gh99P%R-#%7$lrH;alDu zEVUmrhiJ#QN)4Z6NbRT1gR0yXs$GkFzDv&2y3o z!|cbz>EwemIS{k6P=bX3%UG=8(t)NU`Ry`3_adC}W1@Gc`wMfV=A342e+|lE4R?{{ zagoKQqX_P5ilF(AgDkkYKaQiZ1+x6d#qvP+MhL_A%Cz@!kw(Lx5MTPan>Z5K1~Ig! zn>lT+zRqaX%8X&!vDKs6@4w-rQkYmYo#3jSN$WNU-R9Nb<#2@3$ql0W1ijZXTevo* zqj=*d-mJs8TzsD6-+-eb7StJK{Gpi`qA@({UcxmN$2T}FJ-w|qOi#Zb>90`D{aq62 zjwi*7Au&d&YCXEPPqnsxG?PL$iUEF}GGinaY!p3|oe{KXBRC^BJ;opVY1c;4x4Roy z@1BGE=dS7)4cp3H5252@5Of}bsPY|r#uWt8ZyUwk%H|m`c^4_Dxc({eBhMXdK8j;# z?IvOLbGMz3qV1bRH)WfVj%)(Dxow6h^5UEFbvWf#isV3`i@T;cf=ViJ?(&trtTvLU z60ZQD6iKVAu)bHP)3z${ zR7WfR2rU{*LpF;6%Jn;G(Pl9&KImWfWFpS?_% z+*n|U21<&T!wFKA-%*%?_G8NG=UR<2)BaDHe3bDWO);*q_>N6md9V?pyXQrZWS~u@ za+n)~SMt_)2tg8D9u51oY2RWNWhn^Q}lw(Ph`45pZ8-kEZ zMmhFBf>*IB#4^bG0qgbT3aQ~gz;!z~YvwCtM^`NxuljZfGe1E(Z_a$YCGm03v6mH` z7<_6l=gNa;^^SsjGU((#MBl-1Rs`j8pLZEk;}ESCXUGMdA50>@#`(c=t&0%dMx*0) zoFQj$o-9wIjDL!lK<+%rmO$hGDSlPFiS_y0@WLMm4x{pXSrDDvF5-hBsnW+_gGa=l zwu@0cfv0)`7(UGnAI$8q50s>`+>xL&h&U!Ii=jk2qZ)5-H|U{i(JujXv+^s{(no>2;>lDh_iCysS6nF~Ag97Bs zKF_I`0_M7`O!LkGF3upmn<;3z|8Vw(b^vh379GA4L{;O0f0xifw_~Fu3lu!!+=XUFw^TR9X=V3~YJV5XOgcFa zlMY-)E6;&v)TwGy3jMxMH2SsJ8{_Eceh6puJV(BfzQixaXPDt4_VIo(!ia!haoS2W z#h2bqK%tv|Zz?r~W*iVnr5?CO@>r!5tvh^Rbo%3BNk6-hyY#mj4hJip#^BjE*2R{5 zRWJpI3|SA{gtN`VW$ln*bI8cOU@IE2G~DxIv@-|!4BEXA^8NkFob3&Rue!fwJ_mO~ z2gQ{r&+lmM3;Y#Vbki!p7Cs`SQt%I?a?)48 z5{<4G19<-?xlAV5&~fUH7{r|yS*a~tRxUAV8*89&0A4p2V#qImg&Y9Nnc7|JH;Hbd zU|35rwo4~XvgMno;5E@p=+$j?M!NT}Uriu^b+18Kr{|f>sr314Vvb*nt)-84CRB3*0{*?h|f>~)dU^L4Rc&|k%v@;O>f z+QkVsX~#q`ZV+;?irDwxj_6CHb9RB}6@nV?}a4vSkklC~e*3&QU) z+Nqg9hYo`h=0#EQzl6glSjdMbyp#VDGXq<;z}qmCLo)s?=7zR__dhM|PS6(Oo@RNR zYX2=JL6PK_e+y&O8c-(|_(BnI&@q5;ABs?~BO+y3%R$s?g-1y?(pjO4OW={w`_WsCVno_c>%3GRGIDny z!2Jkz6sr{JWE2FF-yyxWIY5u^EtQg`NlcJW(*sQ+HL?|LbV}1%=Sz}C&?`-%dt^&Z zg{Nnx4d?4ykXZ?_gKB*(^l_A#&i zBF-pika}qgkoK95(h%bu>!Vd7zY(#bop286#OEAf9HI=K?mPsZgOkX4aBT6eNcETd zY7ad|^WGKd0}3*<<)|sarQ>gUYw#aXoT1GCeAR&dHLNJnHV+Ql&_cXzpf-~` zgxW)B$*A^fkiBIHShjXH-F#Ohj!-f*8Og(rcoF;!7nxmhJM;HHp$AV}Z;fMFKA2h1 ze&1mH!G;LjQYH7$hB4a^V)i|e+6~}$21MO{NN&e@RO!fpSGT4%G{n-xKwr7{z7xyAxgCTraN5|c%H3F;4l&r3cU z^>3ieIb3UJz;ff`3(497^)js~ zfu*fOwb^*tF-LCRnvI#koq5n`%(flHTCty>9P3kj_=#b{s$4~%4kc4Nw}quQNtR(K z`$h*G9Hr*F^c+H)9)QvT-PE zgtWT{3Ui0QujP(l{qrD&d?=;{6=PLXA?zB}pO$_IiSTD*sP;qgREBRe$GO^INw^BY z;jV>_pg;hcu>!wKVPAujtg>}pJ`0RyeI%NLR(1S73-!~Fp(W1Siy3bjF^|k!=&6rI za@vDj228^?I5Izmv)vA^101W%2#2?3XrK74(O)V8w~gLmUt|~r z1dVhZ0C9X{Gn4kj@VHWN-H_%$HB9QKvwmyQYV}R;AUhuG?}ded6W6@%I9d@qd8ifc z19qcjJo#Cm(V2A!gpe&hu3?dRe1(9WwP1YaZIQ0yC~E~WK*p^@AlLdJ;K%Nd0L3;y zvHcT~tCnZ!%6m_4rZtJ-30poD{gtv&l=-QcEW;7}r;u$vJDPTV3hrv#C_48kHpVj} z>BgsGYQkqcP$6A;9CtDY-qC7wp^@zRa5OFYOr(X}hv#9QYN@Mq;P`0T_L&$Gk1bIT ztDJw_t-tAPw_g+Y!$6@%1#} z3lWpN2)bN+LP;axCKb|EUSgKKvMJA!N2vS@(X+HIUE7;8K072+%3|`?27s0pI-b`*Xc8;xHIEyi)?Ma!GLB z6z3`h{pPD&ARhVyhe}yz;Fs<{A~B+3sK#&VW=silIyP+jSMdBo9!q2pWlRYOptt`c zx+HwjQC))I6h|6XBGy#{IyN1I?LWetu?qFLdE@VhT7~w8V5+(y?J@|>C-3+-FpU6N zK5a(&;whASP9&x+#Od1?UNZnOrmYeis&bRLyT%vK@Y-x`RZM2NC=GPgBsBVyZb5e43G6B;gR}bMFW=l;aG^8ox3riw_YEF2;gd zU;*ylmQmO_HH-|vzFlC+--Z}Q0zwalyoLA6JD}8WV;nC47`29d39veh3brak+r3t5 zU%H;Qo)?(|v!QD9CbNkv?-b`t}G%1y(xrKr4jH5LT}`@;}tVJ0X99qd85m+;5HI1u8fT<))p0J?CX zq4)d|GmP6=%k97#tu0F%jJ#0f^=oHalo;0;=IIi_Irt1u$)Q=T4DDdSy~Yv-!qY@0nt zy8-_Mf8Z|_h2KI$CqQ)g1nV@w9)Yy89gW*chG|=Yn{g=nBanwfs=b7r!^p&^We-r8 zo+$qq{JHmf!+T&CSb7tF??nANV;?OV-{0tq9~^$(3DNh&*L)HtsmXirUA^N3*E6_j z+CfZt`!0Hze*Q{Sgd^7Cz&HJ~^OeMtJAqf9X|(=p(9%ENp}k*=*shJkG;F8SY_)$} zqtjoD)Y7sMTCE&%G60aW51FfgmZ!pT+SahS2=DWFzg>D-Zh&@hLyFn3y!8if(H4-} zYp1*in04z6cXWhj$s}pJp?19<&@=l621K9gCi`&h4s=$3{*XHd5`=P{KGI_m4bo=&zBx-C6@*53uI}s~? zMc2L)mV|6%H$oG}XN?l$DqS>qs2#Sd1M?~8dy!!2gZw%?12MQe(%H_LLm?%&zF+Qh z=r^_lWc9B4b>EBCFmF?|M-Cy{Nrn0WlTDBi&t+?X7F-rUp+5*q0G^-JV+P9mL1;?5 zjZXgn<+8?m=-LmsgPn&e%a6j`7036pz&Hs47wG(r`%%nL34QvQ*9lfIZwCp@g<^K4T*{p5kFY!^2LT@fZj zi}78`xFXC!pP?AX*?w(4O}`?#C3^TUcfjQlqy9hOlerp$IDr{<&8MfYh}`tEuV7~t zNLQf$UStKp{7hMba)R%fp$G?yL2_u=Ohu*NuZZk`YV_coPdPsWs49G4IiD8s_s8&k z0f6Q2590ew0Q<9;nzJ4qZ13ox44vaVY~O`XJ|1dItnFW6uhh-Awts_JYHaqy)eMG` z2fQ?WHch{ZyWfswwEimacEnk7UB$6Ko8G@FaLf+pNLm4i@+0s5vp_;*AH(i%dj{S; z1!FjhMZ7whO*Q;>zX)~vU&L+0JjKuiNjeq)4iGvX`o;ospdXfv+v5?p?t+4iDY>Sj z0ba3&V+I^uQq}m`wB;AkH(ke5#;TZFqkce7KxM{0meN(@Cd`Mf>AXSv;WN7Y3pBT9 zQ_!z48S|9nSR3X*_}5q$hz{ai7XiS412pbez0AB{#S}x!URbFADjq8F%tb-=crp)_ zoKSXSsM+Tlqzvt!po1UaI)~gZAWSxUYmtS$6`zb!j!T%Gh9WFaa!vvZR8i z3rHex;KU(rdXVN~VURlmW%#XfTV2D{CN_tVYaL|!;t=P*;T0^njVx<<{W z3D-r>u2@i>Q(n}P{Zx*m9_1>Mn4yk^kxIO4O2>@d4RU0}&R{QCyN1#G*D?KwUT|H! z0u`98?V=za%0}6#!P@kKV2!cg2`;=9v`osSYwcoi#6La-H-XFMXkBk3*7f0IlzRh= zYwHMFbpuRdIr8mbba9sl0>vW8S+Mrdr{uaJ%n>V*XGLCqN8Oo^(YYHUHM%BPo7a&w zqa$nG28#I|Sxv#(9h?OhsgpahRz5)!eg{*2EELy-G;unqJR3wKZu%NDRWEptFD zXEqvW)9<3&^yZENR-HydMu@2yf_8Dq&2j*n`J^3)->jQD3akxp4Q{;JZ+k+JPp*CX z)y__CdJn>voSSI~j_`m#Adze{;H8N&@HGogn!j26B-FNdG>;=s~1)ATAvqDM) zN?r9Hz+FP0AKBbR3;2}Q|ADLItMvLGVzNIF8p@v$e?p3g>(XbRU_!9~DTz`;0amRV zhstO8d?beoQ6%J((Y`>ZFvxP)yHLfScmVI7L%aS2=k6X($N$vT-Xm^``6^^?SD|CK z=~#XFO?1~2`gL)*_r3s+g>OMijIR|%0GWC9XTXN7#3|v#DM7ct8W=+%eZvF#8w_zn zO8mnH^8{}LO}&mQz`7Wzp&s9DFpQm#Dhisp2ESO`)aG95kgyg9N^r?fP^!$@b@MW{ zdw7dn)^ z-UR1f4U)69!*rY73-c@$ND9q2sC~w}gD?Wt*4+%($w#ljgFBpnY{7gnhSa0vS&Xvn ze6rRIg2i_LF3UafXz|kQ#zEU+2Wt&PJ7-Yiv0twn)PeZu#^Bb=l4GNo;CC)9Uf+FZ--~dUyoSZpa0DZMkdi!0mxV)!5q7D*v)jZ zcYw*Xhrw*DE@)o>*V+80Z~W7HAVIH~;F?+te?RKz(h@X)3#$eu*3Dic3i#dMH?uBK zlmk3m-uaKPm}@WV1gZEL>NZlzm-)REXAPX(!iCaP+z@T9{_NWx@YgNADft z^CkE$@~g4q%H#;$m*72ktLdVe2QQl7<8pkdFAE0roa|cw%YQG}59e?+8#%Zr#kTnn$ zx9o)UMM?xOkl=dnMOZJuZ8Se6Fk-PN%@2z`7jm$p0Z@ZM8eYE(Kf)jN4^hMNW+I25 z4{(EZA8Um-d3*=k=1yyl)Wfs#+8u|OJozR(z_ZN>N3OJuE-JK^EWV5jn16PTg3lw&GZL6@C% z{VGwAJ2%Mj+D3eT6W{Uju8jf}HQqA+f2JGfiF!x^Zbw|TH0ITpJBE`cemx|~^ggtuRo=D5W)wtPi`B;+1jhZ?d_y{njh%U=p zRjDYYOPA#}z+s+fZlg<0oW>n6rYylEzXXafa*b3qbh%W;9@cp>eN-V1o@BdeP3!4m zxSAd6uG7y!Kx z!{|KCaKG{bBt6LE;641-$V<+U-P-2E^SMEh8z7~weAgMPeG}rpp%senY(mFNUIQQ+ z5l%&c(e@XEm^MO03>wWertth(|AvQAkQ?U)`!vOA_4v(*%)g(6HrIaqPROF05o&TW zE>M-D@W)1rd}!7zgX1@xK{WwV_~`wV6RBnmcmE6fxx6t2BY>U^5VEJuyXh@r$oSYawXtec5^e+W zu3SuA%`)~0kqE-zOB*p)zmx+z_z`2Y9?{eZ&h)nZlpLjID8~oUgeWy84yR@%TXT=a zsm3Q8d$KUQN4Hbs6KWJyMyXx0e*Cvw#qlkwVeiH?iZ_{`)u`=q8Z`-r3O~7T=r|PL z#b*_$Mk{>~rABtWjH=AC=bn_RKBOy1iXZ;5kMzoLIK^B0hhwbY8|fNO-J;dR=pP<| zdpI=cV>{p`2+r45(rwXdY|mL}WC=J8Rv_<+I{?@zH)yc?4`4=h@Nmm-J84$DnyA1$d~Lj%70`q#+wP)6@oJ`F48CvwXGko~ zdMNuw^W<7=UOm6T!4Jfu6ToQG-*{x8v|IZNXKddNnqgxEw86I9juEJuPUI| zdU}&&)*fr2bqU}p_tWbM>OjSem}LoSyz=Bu3QAN{dl>al@UFWb_R`z1`SLL-i53Mq z!aT!^OT5&3KNTjbnacG{TA!%0V}KKh>I``lr6uX->bxYiM4k>;Xli==C;%*7Kg8G! zUaZnlk*eFf=08j!-PC&3+(V~S5f9V*-PGLVoPjq9PuwnS48V(xVan0-A!Kj(y@D*s zYD%vQXaU2$g69j~-CQj5Pr0fQ%MA{$@^>KY;l)z>r?fm-O)cGUUaqoxy@T@tr2+PX zQV}lQ`u(4f{`6OJmHvKqKswOnP58s=FDbthHTcylwN%zdEq zg){le8NXQC?{l}#`=`bppdAM|T<$w`pCYN38b6bYRtGqP3!Ss20~S1^;PEjzMNO7# zX+()IhyAR7Hp#aWc}JKkx@)5Gm zHD<*LP$MDbmjLd0uh(O{CrWeP4;p~qyhls%eFpMz%2(oauRPV1tjWziXnc2IzNwt% zbyrPLVT8=eF{uk}>aN~pVQl4zchvROCw?@#_zb3PJi%ZPD~I6I0i}gs%P6J?ZZ2TQ zDow=$w0hXLq@(N+l;y?YHcS_K>uvNv`fEtHqb^VVc|(}x>2*FwY|wcx>M>ES;%B-& zSX}04xgQ+{XkYQ-N2C6WsE-?qo?cd*uBV5VdsC&Rl$5C&yceC zwq&X372KfqVqzdn9 zpQoi*8Ubn>ha)A{Rf77Xah5dVy7TqFd;z9_l$BNI6kEv5BR3v(imf;aM36sAaq#ZQ8F z^ikJ17_G2;E7lc-Ze)y;Vc>4h+r#uGBkZ)VmzrkT0}wdf;mFm?OC9B3LV9^q?qA*C zg!NW$)ogKhl$RBDoE7W((dlddRivBoP}vFYCCC`knJzYYo@i_+&N<0_SZTLOXk_>F}-mL2tF7^cPUZ$D5@p78$ePEwT!$giq#x z(vM43dqMU3Vd8ki=WWCERXK)j`UXz+d1#T#9m5uGL4FFHCO>(>Tf~z-1oG;ekXfC^ z%JIv_3E*!HUM2JyLq433(a(yNp0TJgAY(2Ih-WOlV^NL0%KWraM0eE8L)|B(Uf~mEAXmJLlXs76r49wzN zw39!M(wqEIPha!LE9Bn~Q=8q<7GJ5jEgmnomG6-CPD`3(8s86{_US;?_2gx z*v5BE$X~EwipTfIIDsbpF{Fv~2!D*Bo&1qUZ}!Ik-}yg{{58O~{|+#C0D5caD99w6 z;m+*n&3xWhu%JAQ#&f~l9R-<~aly{r(%kARcmdutHlX0t=Q;}VLBRzlbhKF8(e*Jo z55XH^UAJEM(rz$l+%wOXNeKe=Npdwp7g~zN>!L|Iz}~u=E@Wz!{&aJI8q=-I)3Q!y zjELpVoTt4XwCZq%GYwfr12R>J)Gx`nVkEh4elJ&*M#$}D2+?^2gs{29Op7zsk?dp% z?2@^UelngxXA4o{FA`Xy>I`KI(yKr!9terrU<9f79IfR=%I*6kXJKZ#(l8TsPK}qV z_M>G!k&ABgoyZPznob+|G(L(p3Q>;PKK9gI9S+tpoH7QgF}b{#OF)+7ra?alV*B=1mUDFT_HUWfn1_-MiujBt+fKYAKI?5fS zW)#*R?!5HGx*h_5*9bb+9pu!E@t1`awDfVrt@kTwmfe+u$u0Orex zTgrJZX8cuX)+4%d&j@@!Qw&bf^RWKb2=(c1J-;329kMOg)srx z(Uc#gKTdxosphh`=;-1w3F=An zwm}S4X+j_#3w-itLH077v@A7N9S63m71`g@t66G7sE#OQwf%f7)H*twr6v!E0U|(n za5@T~jDhnrZqgR?$=kXUR$G1-ZQnz_lP!pP4_5n4-F-r?;^VXq^qe`j8aO}TVKFoI zEsDkgT!xHyRa>jjo<$mi-#XIEZf6RiH>=O*P7Jxmnxzdz*-a18-oa{&dG$NszatCU zVZnFsF_2lMDN*CO-;J`SrYx=OA-XtN-4ZjpFXYG_K^|+ssqxMG>~@5H+oI`#8CZ zMM8|r-EaNxRROF>i=$?!wh8cbSP25HO*@{!vn z`)Pww?>Oo;pdEda*X3ygkcQ|W`gmSOdW|XDp!InOo?_J@BbpPnY=jkd;?AHnCTaum zoyP(kYiWY&Z4BxLW3GZ>gZJcw;OCvHt^H$&qGVX={P{NR9jeBb>YAO3r4U8GzV3}> z6#Q#t%7V39kv1Ay}+GwQbpy^xxHWeRWi}P|Z2xzCpR+Fs_N4ZmImxu2t z25-X8V11wwix`pXfw?p?TkT!y7^0nf(02pn%IK`6tY)yrSFuzya0m_Xo#ian4t#~D z6E9>$w&8g?g}RF{Z#XuAhCqL3h;{;LbCI?WZ7~hADIKVZ_G%d*q!(11G}fh#d>Rv2 zfXQsYk4m0Q*u#3WRdavbPk#f!NYx)o;$8EgruG*2Vt&yX(%U=eL6m2t?1u$n{7$7w zIcl7Ikrw5s$q|XnIbuG1P9YLqi5avtN6k}?CDZ3Qs?B`d0(5|!;a-E({sKU6s}9#* z9Jg}lSZG)qL2ed5NV&t*fkDOy?JkVQ5B1g#Q}60}5IiM^ zgJc=5)lV4{Lx}tMofj5eg$-E7 zYG@7528KfE#RaTvsf7-beyzpx#W6fz7$2l9BXDT$r$ZyuVQO2X_6r0*fe+FR{PZt~ z(q39iIk{@jDR9fcZC0;^6L_EqqYkf1nJH3x9%(y}mV|!z0Ux{0hv^VapiYE>e*S|p zEDEpbsArO*wT)}(P_8

xF1-9kTZzJJCWna@BkNAy8lO4_c9@rgniwo2--cNLLiq zO~`O`;=KHU58d0`#1zF%LiQ)1t1%%V6znX9EaB;o&~C$fk}{7Fg(z4VQRN z^Yl^e4r?qhHqsTimTuV8iQT4S7x7dDirrfkDVrs^r*|_gjCSFEGcR8?E2rR}DPNtX z%uc88^YJM58m4ahA;{aIdya=MaQ~1{l_*T03U5oN%mVcZrLY$rDNrW_z2DpSf@qme zF(cK{%8}kQYowZ>yfmBEjKs)(bkWw4>V(n10~6tO_)=#`mZmtV=pp^K5$D>)pNNDp zS%0`ov`A1O3fJeAl4E$Aq&fgxScN$FK~EAzw_}aL0Q7rFRq*DzZhwJh})IT35yv; zg2(CsII^CjjM12@KF?9%XmtR)>xM}DLcDhV0eWgQsN992n09CwZRNSeT@iD|TImK5 z@KJ!l`mHyMDPLz^zAndip3X&{{TpvqHQ{j#bG-I2>RB?G1l2!P9MId*&{vv!cBtdz=l56t7YDF>3#u2he+GuM7eAmWUqkXm^2=6>bjZyw^(XKIS!Q7fy?Fpz;w;}+@H4q?f<_=8GH>k>!bJg%{ zf(_NLf-vRj%_Lg*1Y5}D1}~%gE3EC4=li!ucjOJ}b(8pHfnz!BcPNXS;xxq3m@rly zm$0E{XOy-m*C1Is$c}XE;BNlioA!-WC;CeP8t^;d7Dy^D(&$@MaAbkn%Wk@Si)yjF zfDT!e^Zdn8?M^5>js)d&f^yn}q;@BE3S$E+Hx95+{y1Eb@1mvSfRty`=&5n)CI~{4 z$E(|vRom#ucs1YevoyFhv)>4fp@duUzHkhXwFWR_8|g|yM-rl{c85S(!h11%j7_~& zE$xbV5-gWYXvdXFa%hy*mz2oSkQHKJfK zjl7EaVNG0q2``6#t=k}^h05M-YQ2)0NEH**d8|P+0hAGeL?-GV7T?D>-^Zef>U>2` zq7Nsk&xJ%_`^bQiSFQI^cp+93l5xCL&VhpJymaumU7e@rgYp`InhS;?==cKKce`4s z{LqU6CaLrMvQU=pnFOT<7+y@$dpqL$IOqGgISG@cml|29er-Z@l}^>0YAD1RjnVNMWtN{vy{fj)n$v~eLFDpL2O^r9(h zhOe`KOi@ipI5I`e)f2W%Rd1i3gGyg2DVIJ1cF#nk&na8B642~hSe3m7Riwv+ zQZHjQ2ctb6e*MU4>PA_vq0@J$FJQ9P+zE(bL_J;Y$?+2ylRNbxcFdxA(;;)8Ma|RI zf^MA4O4M~)HW0OfcWlGk<^OLFPOtn_IkW43M zs^$UEAz6c&Vhd<1W-lDgv$-07--#vZ+R+`$c&g3awBcJR`7Sk9F{IFtyVT?uyHVSL z=Gpn;3_P$cfaq{@qmdThg&pNIQSdBvOSl}UmF|H73*4>+L#DnYn)c07bChc)x;#rw zHJvwVjrW52;F?uUH2BXr&9B5b#AGL`8x|<-8vQPp&()52S_kL?hDQ&?R!u())i(e%{NRp z=|M!r{v*xWJ{$xC$Bmnh6F$Lft^Dkh;ClLo?+7ve>dpEM9mbyX9!y0axW)cewz@Blq|l^y z1%zA*NS8+gBPftUJw-x|L6HfU*@bgJ@rtHOBo7|twHVe$?UansEy`U_l9>Fw3i zm*|J7N_!7WoVsEjMNGqIL3{P}OEg^jY^R3JqZQMXHZ7098Uj1AO1LtSbsTsD*%4gZZ!>@!YqC z*g$F0Dqh0i^W!fg>F^AQKL3lPYcrIGJ<=v5x#8u9nM!id0P|nue<2y~A4<+6xcbL6 zHIJqhGqGyG8~IF}b?=Cz^D~v8`0pe2tCAKNHSp|;cJs%BZ~^e}5aMvQ(gZ$-6`UuVZkhwLF>uDQUXJM8u>~dqA|0;SDucd7iTGL z3@=5}iCIwbme7q^O0r>c1VztA^u~=ebT(wulN)KuY$d);G-SqF5FE?|kM;yB=JlZg zaXk@^(3CR)j>?I2e6|wPwHxeBAu4(RgI{414gWS}zrsqD`Eoy;nKG?nil9#+`dPZD zRdYzpL7(l2qE2&gWGvw|wmC|OFh^jjH&hMT3V8gQ)m zXIMX_>S*E=ViVsfXLvoHZBn`7syq{gz}vL8;ITX?0Ye?Lk&~ z-G=Ah9A{8&D&o1^DU{(3z#e-OH{M#=SwlQ^PJ{99Uc1_rTFz5CiRI{la_FgMM9|QA zN@)LbAi_NXl1WGhP_~+5poQ21ZgU~S6QRP|Mcs!Abwvu!v&{BO@FG$)PkBx5O2g+X zPiFDh?!uk340~5K8xOu0Kj%G?Sv+)kNzgf#9K}>i0?*v`LIbUYq&vkB13d96c#W4@ z832tw^fB%@;ODIfbVmulB6PDpRpI{u2HdeW6J63LZ3!8mrYqdlo3&L%>#xt0Zk3nC5;8+aexwH^*O{ z>8Ax)riWALLZx+!YIb|VZsU2i%Z01=g-W;h1DH2<*t9c)fL&?){VojzIRG#D- zOdwV=me_cjvJRX#gFYLn+cV0Owg>Qy&GNn-hCOLu^l6ZQ2cp%{D8r{)?_^oZ(uU($ z&du%NU0G6Df24&WtrYPFs30avrWq0*LG;uVM?nre8+GFuWpKY~gPoJW%j_&xV$Cmy zH;E;n7apuWF(%kaggJtCV||3On7u`WX~i*+=&7=B%6Jx*CIe~5vuLqn1HJRC@~GUM znlDkt7_LOnlqFzk&upNzOO(guHFR@{(%Iuyf-23TpruN5P~k2N;`eMQ8|-))qJdnM zsP3If!)#c1ZWn_W~k24XeC9=yV` zwN~$lV!^@OCLCaieutz(}#8QJQWed%IP8sK6 z?Wx*k()s6WXvZxg4MN9_rk4)PK1WsmOSA1=jde&e4?RO8X$(FgJ6<;Ifci zKd4{_(Xce!yIk2|h&@j|Rwy~1J5gU+D!sD;kP3UMAIzW!E0oBN=3eT;84a{B!I2!7MLM8+l|+gCbzYN#=ZYroQ!re}jb1`VgR_|Ga0#_Ek#nX7***PsTW zzfTk!)QTF$mM<8GIf|dh)thw&T)M*5o)@4>Li-~Fq(4W5*?R4 zotI=hgmBop*$3y*3b_*$^aj0 zUp2*ODN9919os~`bCocUqTcGk>GWhShTcuDb@z12$yH+f%t`7iK!7`)SHSOs>3A++ zz*!v6KVHC2oh3t_Qsq(5U)^w)KFm`#v?y8OU`7ue8{Slza+ap7RE{VxD@ca$-196& zuYx^!MJ9YRzqr71Ew0CEz}2yTMLR!uEom&&nsQn zix@D&{dnFI9R84ctX8Hrvv*JlK+;g~OS+h+_*0k3iaV9BR+d;{jl^!I=K+X0IauwA z6_NRzgxdh~Q3(sBRy33)CI&qjaM;lWq>D{F+M}PMrE8S=$zwoO<<5qq-mZ8BH+&j3 z27DUW>3%*-AH!?7i78k0L~R?qG(FblzMRz5`& z)+!;r;KIDW=Gg@+HoTt*)q%!yhL`cb;o8Wg4QSs+q*b6}zDC>&Xj3gZ=HOaoo?-SG zie86JR)4Ha?pT@d0!e|k=?HQ(A5K%&LGXNVh8*jZL7^2UUHIUgDd63$h>~z=+ESJ~ zjl_DTr-v-7anoqfdS!@Lb#27}H4V>DBTs=puUU@rfGBnDa|X~wEWGc@ro8qJG*%YZrP|P9=I-7I+dDl z#PqN6P@(z2l=gS*o9bHl0O8ytG-e|#pA%@~MkUe%)<~b?U6zedmvyA%7qBID?kL^( zf-+F(NqQFyKh%q$)#PJ3>DXqv_wiPoo5-&u(irKmp6YdQ9X1zAc@nB7qmx_m8 znybnh_v&wIV(1lBX=QlLL?=|Jp4~C(7O0&El!7;Cs^=g_VT`VN-fAMli^_4sk8jY4 z7qK!&<57D4|NIRSFDYN+sg$2yLZ@HYPCfFmtM8U$Ci7>z9;g6hc)WLgGq6&QG(MFlwC%!r^Yka8POsHtv~>Bh@SPsNVY zVd!W3Po{{i%DAW$UHcYSQ29OjeH)5d z6?HM%bz%~AdPV8n8W+YAz#V!Z>a|JO;SVi??J z=1D0~zmy$`n*oJCHjKg~JS5>%p(jisQvf;x%MW{bEIOA6}TI7Ad`CRz+{(NsKuEyVF$L8GMv-zz_hs>K-+e}vNv}(o!_Cf z4UI^3e!6#%6MC7Fw_mZB)#8Apc&DWdx*2M*Q;7?*=QZtvV66|LC)4nqim7Wse>}<(oSWVsd{B{jJnK4eCe4X zYLT~T-Qm;JqdbS!132zg!eQgWT7gs2fWYeuZCyR(gG!kS1+6s zNCB!blin#%;@ayG24D5B3>?pcx^_zP?Q@k4qo$&PrF8cdqZMN9JU`u$A5`))?DCX2ir=Qgc^#jsL{?| zL$GlPcRczKy;G>PO1WF&u#`as<;N%dOeK8{zQ)6FCLM(~zm1I)-a$~4Kj^!zKPoYA zZAdWvJ>qB=I_*dXMHB&}>hC^^T~{=1x;Ev~3!AC!U09WGX-G6k;WS~;&}u!oZ=`ca^M3$^nUdj4lXgK%a zvgs*CH4$YvZz}SF`FpgpA>B9q4$ULq>sN1R<=tsZidz6TF3y|EjHk)iKBuV3*r$4EzS1C2ExwD>5CiU)?9@5Nd)HJyge)%mCwo@@oQV9&wM zUgKn^itldGR;LYmyc~RwGRwGZjN8NMbaS6F+^}sMb=$A>G2rRAIs0K({Ye_F-LJgj zk!Dg$(kR}6UE6pX>QH8&p5qQ|@W;~)2QYeyes|zB4o|$l2FX<3Mq6G}*2xno`gJ9` z%?B{lWN|MI;+Y+DtpJu`CJ-6!+k?9XIrjIIoc?$b;&mm%u*VL!(y$wkrl12#ZWO%! zmi;WN{dIP&T%9cZ~<1F@{ho#KOk%)SyPwaMGju&dF5SVGjv$h;Go+aTW_TYh!qu<$A*Cx0Cwd=J*82aF*Fe6|H(*WK z^u57%ovl2IK0c%jG<<*y5{H%emQUhPxE!#vaEg|W1FYa9^yFcsQ&3MIJe27TM;|x? z{QJH1I@)nq8DgwvA3Wv+eyX?hCuEil`-q~CDjmH_q6*rm&o!qpM-}UU>f$#CYHmSq z0*-9d;g~VYSUvs!dY_%^Yjji#9nH0)%4Ty3CV2@sP6@lSa6(@d2mntO$EdIVjFqZ; zEUi1H;8pDn*)gSGA7g^Os?(a$ zo-)W~b)~0c!lvN%z zZPa&+H2iJUmD!9OZ!7VJCz{bU{6`OK2K8`lL&8jq+j?AcKMJ<}MGkJcTw^PYp!k76 z;3RY~eVdgII;jYQVSlqy+bLz6Y`9^hAIg!kL{Q5LNWrI#G^PTp!e_?P^A$Kh?)U)q zIE6R?X4hcjQB6OcY~uAef5%W*Og7rB?4a~2C89-1;~QWSG@kii(Z(uem>0+e*SVjf zn^npX69O`HzE~NL#6{0WqNTIuJny}HW^;>I^5;kx<7)5`f45SBNAS~r>A zgyi{l+tNAjDgoNlIws32+mU_Go!GDaA zCcLi%J^7gNFB0z3#k13=_sS}R-3pWn%nGd72Hx@3Ed-b!STR^1c$09Pi583|9adZUx|81YADCuK|0Jpzz?h zj}VuJFx#e_0bI_@^@Z=IP9G@UJ65#S9y92;8xsbXytq0pb_B(kHVd%Z)dU$Vx$e7Z z;|EG~|1jjm;bwvz#tkfD-^3BM>}EI{hcjBQx*@%tdLg?V(T7U6=0)w`g0G#LQqvBeD)A=ehsp@UD_#_T7DW8IH?2Ag(ku2R z$5|XzKJHE8BPFBxcc|A6bv#!0_^%aO`jHad{CBj~tf>e?<9|i|kCbhO052MJ4wFFf zqWS#)mnZEwr>rpC^rVRM2*2+|L(gNq0-D>-3ym3>Eq&9I~7a5jE% z2p7203lVPJB!30MQ5=Tr2F_oLUn?%}3Kzo0GX!A?@04+RAueDAB5Y|)&$ReE{hCI= zfYb+wUr^cv<$A)i*Bpy;H!ePvD&xub>!qSy+2X&3)_?GTTd`6KQk(yMD__N;hU9~bu zRG?fR#IN%x?R^pUSE1j43X}@?e7(F5;V;4URxK>uc3JU|eeQ;PTgspkzPl7Z zdi{zLC9H9360EwP%;2p4ADO2t=@Yz)5`sK?jX*?es%o&L4*xw}E`Ryz25rMVoD z+(9+KZ9y@-1pJD}s@NL)8E|*T=O;s_(gk;vazh6#ctM8SXIIvhFw~rhY*0&;WMYZU zu_nSO*KX^S+?^)gRl0am;U&(Vm72|c{?R{ zQJcGb2{XQ~E>q564XD(QKXU>F|;~&lX5t>pn$#@vq7mw>|in^P95WZ3RAB zIF;6J3;(Jw?deo@yZNuJuZJ|M+jSXM@Rw`4Y=U{cU>4371$S_4Z>UZSsJzIzDBw~y+o8iOS# zu49!wfdy(1=%@(spBJFJe1&HVgVc?dMT&6u5=rWdyOJU_^mQ1#e3JHCx!c5R=I0Dy zSMJqA7?K??{#0LjAySyVeD4|{_U(ZdIVQl;Yo#@u8rlfFNga=K!@Jh-(v-F$)PS4l zG%-$0!GG!daU#QDu!K|l4q}6eeyG=vBK5;zo8fu;r8al#=|TrFLVlB?I*OR_4OgZ7 z3`nGwG^;bMM#|5`_b$i_X)~?P?7CFvkI%^YlMz=i*XoS>v7V;jyL`RX*#_TJ@m-T| zb;jU(8os4MtJ93{r}1qrv%q&oVMpO_3Pu#4<;bXhd3QOVzx@$+wxgKrcN+CC+{h0= z>WgqUvUU;)-Zc^Gu4t@Fw7iq(?6;dU&Hg8oKb>@Cs*ADPDmha)EzfJ_Md6)AvydHV zhaGKZm>-j?cf@d=5-NaA!j(Nv#V@kfL0WQseEmWF6AprjULDV|77_q>f$10JkX^(K%g3TvQ~6duOHO z9EqlLO;t#U{L}5;L)xP2@3={2T}5QbB;d_B=K^0VYBPib=ZMmZ8JCij*nB*uLn;>5B z`vHg^jI=n}hX?N}g2|a6`glzSh=MMys86DJR#c}g#3>-0DnQ>_7D?0S{8wBmg3;f-CrDWdjT1Z1H@wQN<2ps3P;tnW`M|* z2a%6Ow2!;%E$3&$)`ID@5U)%Q1fSvYN=HsZ3$z|qXQ_|cZPO^-B4!8uop!Ui-IfA~ zb;Ino!KGhXM5tSDEzydC8NeWu(M_=1mMOR(0c`jjWT*=`=P@t<M!G5<2`^f-J5?;z(`qp^ML?T^$j8%CrpgjU;8Gipj%SDH!X23v*&bZ1?nv1g>x`R*x%E!*po4X7!W}$o{>|kcN z;8ZsIH=Mi$cH2Da_m~K^@tM6Xt+!O>#v{H2BV5$Nug5yMj7g1KaTLc7>3|uHNysj6 zlGFIQDLhzXQ}ji9IX@M6LTr!EhCw9T8slE+W1@FfbxzYdfnVKZ@HtoeY{2VD?k%5x z@Jd0RNwZ*)!FizY8iG8SE4DiPk4E02h=1}HW5Dv3LV7`7?*0DAllNskyd%o+MQDhx zb0g0ZV{=&Xio3Fb(ru!GS?^Cg2XW~N1H9APkhIZDI_{hb!gJToIoJq>QrlUk1!G0l%dEaqcGIo0BX%bzi$ zMMj`ck?sv86#slxg_o8PI*05&&6`B|Q2l7pe(Yn2vSVAoxeAMAbu7YCWB4^$9nI<3 zhG^+WWOW3mH-_Jm)nS~DZ41*^(Z`l0oR1Af#!~he;oo``lFiMegg0@LUi3v{akV41#!K|Y;sx2>;N`)tye}f}>|6D8aI8q?oTtGw4CEXuVhtr`ihNQW z==uQ=X6-}a!?M~HeQ)-Z5+?vXMvMEh0xKC$Fn672UaFw_CqBfslp8!-?peY^#9UW=;coE(V#bfma^pc5oj~6q!Sl&Xt7zDlv zVs$vWIdz#HbHxCD4<4-FkqL49k18ezlg|mJ19%-}YQIchP7vJ#htH7naf*IB118vw zyRN6G<3!PpYdDQ1nwzwb(kF`W9z2kCyKN_+GuOTWuFar!gLv2}B7g6~H=9QAWMXQK z16MyX5#r$%`V>G%0YqIcJc0s*0q4ah0b)4%D8sevY6Hs+!9u&pRShc-1WTO)`hI;q7Bj@5;dk31AZ)U0ClE|h@g_2 z5PKTaGP#MXAk~x}N*A4FH>IwgZe@sFz4h8rGf!bRKu>+qZrdvBQ+P8*`te2#U3qSC zp3QdKCaTC3LI0GG4g(9|Uf6=g-&H;v<+&F$EL`QQkSCAqw&%!ilGrN~l}!>O-M+)T zX)zf~&0^{bM`bW|8#r0?k$ow9vKTDSq%)I2x3AEblf^iB0a>SDhFfXT6cHoOr>#@4 z+4&2dDg{Xiv#_;eQs)^^D7&eD(zz+Z6!!qhc05!X1>F%RSFW(UbPsVg8n4Bf9DK|d zWx|Ok`AiiP@d)g!sbYcO+)JRVmO5*kh41@xZ>k8hUc0E%1>dgMcADw3bMIv^5i0*WO*`e z$6ufcxtIuz@WpFK1DQ?tqI1(A0b=sFAGF*0kV-t54xgJTN?kYcV)bliTu6fJ9I}OhVTHRs`U1g@!!lTPDYJ zI`Fhe?TZqV-UM?)E+%#ps|euPiigd^jSEpm%GZE~u+Zb2u zIi`zA2~1Xd^*k3E*h@-)gPqDj{@-*HGCX6-@KR7RwNNklF5Q_f+G(uz5UeDr)eH#O zfRne+ZsYPLWJOE|u4}&@vlo!p11gB}Zw#Y>AroclYv2I1a)vPTk}&CYyKOTaV2Iq> zV!ix&x;R6``XYT7+Vcy}692?6i#%qE3qC(h)txSYMO^xUYG-1Hb%o?vVsPMNRC`4+QQB-V8vBsr zvqAK5TR2+`f_sjxb1)OO(}p=BtYb@DL@)2hq!H%$WmV3+eg-Vd}RCjZX`g5`GU0?m4N*;+&MAcg&h?@E0W+?yZJT zChnLw5ypg0oV-ex$O>U#RYYAELP3Ka&!!@bjYfl5p>r|*r>n8yrR58SDP$OGDA%Nr zaK|J-Nz;TW$Z2$7p$HrD1fuj?ZQ+i`@m-5qqTdS-a6G@O7iy=Esi(>K) zbFg(XUqy&RKeL;3#&Hf1`XinF0fsp~MZDhLFvmCeX3uauE=)I95SIL;1U($;xQQ?< zo)efD)|}COBf*#M(K1|GXR#7a>v{BUF!8xa z{5qXn4545vII=}!?;tp;T`VF;do-mhvvkxAXt665b{bpvi77 zU>Dp2tAQG$Tn7(F+{CS@T~j?mW%&h-enzy7IsgQuI=Eb8T5(Bp+^H!n&3%L=m9{?v zts;-gWxH)Hefo?pY}TE_G4!91Eg*MruW}>Tkk7LaOqsoZZnrI@uFpbEz;Hgs(^fPB zXfL=N@QYuTM?C0Rm@>h+?njp6Cehy&zk@Gq6yiZG>b(%mQW1DB&#)9(hqb+CX`U(;0dzIh=&}}gC z2RT+{Lgm@zlxOgkXdgV7mL=xLy+l%e9HJQ+JFa@XnF9Z;+D<>%u@Y68vBBo>Hae3f z+9qv8cAdZY0#O5m#71sr4+uj8%etxxU z6U4X|W6+E4rfeJc;M>UaGxBt6k|zg^OhKO5AU)3!Mqvt>9-YP*#=pf7w=mdTy^?6}Zz5-nP4-E<3 z=n#VP_jKlY5oW0Qn7(>m%=VeGS?d762y{F_>8qhxd~^#sS$ka|0P|2?jZNuf+P&Jf zhIh-hJw&yu^;LRTLbh!Hd8`q=z+d~Xffn~LEnXw~2R>0D<(E|IBA)@Af*VvvXV!?e zJ}HQ<(X@_1jxkif2AlG`)N!qdj2Z=8Smjp=$(@7aukM+iZE} z`7E+xMX={es*L?Jn~chcvmmYrqPX2n*5dypzje?o{rU`$a$}|z>Ufg6uEVzC2#r{W zV++u1oh92=NXyrWuzo)-)G@e&{{n!y&Hpez|5l3+bG!#9(>#DvAlWjkh4_COl*riE z&{Y8J1%P?|vTgQXQ6nbkIHVp#Dc)pTfB|!2Y+GAqKu)u}cqn&U4s~6R!JbA#)?=i= zQrrh++a}Yj^`c!DfZSyTQ*ePyV3619>A)anso@TTxBU_u_7t3Hp{k(oqm+KWxj%if zUif;vd|%41qC4xwzF3xY25Gvamb{lW0h$UU0TvqJA#lWt{iU)OOUpKh3vMzF(Nw4w zR?)XA&IZ3Mz4{`?+`D0;lz;79!!fGfAk5SuUwqhf{#PLrQuZniBTJ~r_-*F z>xuVrOdx57z;(Z&+^^_7eho6s5WbGB?0!aAg7>lemnoSNL7144M z0}M+)rgsQhp2PGziIIIPqE%R)*k%A<4Duzu*u#W7^NPOD}VGQLz&ay zo)c)z%NSvVcEMhJG#x-F5TQw4u;~CihQm)+6kWz04UsJOp{T8bAM%*8RX7Y^UZa-V zM7*KfHR``jbn=`7RCgVw`P;&hnRiZBR;ya|gB4Wo@A%xx6 zk)O3rj6a7G;P(G25rYzW=zE8jCm{Yb^62{@FU_8I5!%@eLY)~@H^v}2-$wdxmuS^1 zqCF5j{EFCS7;}w=zY2qky;o`at74F0^HnFAX=T;#>`@MK|yQACn!Ub;aeMxbY^(Ya4VanuVPx45aT1D2FGN(+ze^ zj9^DIy1oM{xpF3RynmXW!JHn)9ln+&wTQFh1{`POy*2im?)LDozw}9wK8W8)i7L6asieH=)DU>%#b-;GrB3^KTvXWV$@i4 z_H;lYKuLd6Z})!WH=|*d8aDqx9Z%VSI?VfOz2?P0my$yrCI*i#dOF$S#7G=%Y`{%n zZ#j(9(CC=|RGo2V5a2X%yNxkj2PWhra0p45$4Eo9-xs`xXh) zQLRHegAnveai{Q}lpmuZtkXs%`r-$akuaD^ z|0xs0Wz2Tlw<4ewOW+nMsoGg;S|COSJg<2Jo~r}8LO;70rxjNJyckO6bsX^0wnQ_)1p_otE?lR zz*QjoOHDAmsn}a?Mm%E(L0Q8v7qrnxC#h{T^*>{{nu{Y_kN;p;#U0WbJ5pd+@*fPB zp$ub~t{FyQpx0WQNz`hWFpZsyB#kF%k~WfZEY40`1+wd|CtL%J**Y2VSo{;){ikX- zu%kR2yQHD&4X7Fed1(f10Qg~}P=qNHyNG{vdlk0gf3U05hf797E~5 zMSDZ^McTMqvyz}n=e)D7NPzAPSZ9~NITsboEjK@gQ03VERE$; zk&f+)?T@=)Fmrc{0P3(u#Nwr#5qp5>FZA>t(I({ohT08oIk`laRmOnu|0i7JINO+m zzTYDr8T~UBiF5-Nau`CzNQQNpSg#8FEzU#Luq50K$+9`BfV)A z6=-%5mXOofeL+#NS3Eu>2Ys#|*!epQ*s(1~52l&*&3GZ?+EQi{k*;u+K|R9h2$#9> z!>fE$uP+;OsN+7!xKDHTR#L)SxsAzT8qdx|yczLW_AX7lh{G`EW4Cl20GlNUT8`qa z+4DUk}<@lEnZ(k*sjgh3IS3sjoSnJ988e~Q0 z5tlHvoy(om6O1D9RObe@HWmYfQsd=o?CR zg(eNK+iEBqAzyPWj)NpTGJ!);{C=nXZ{W=0?MZU}t<|!2T99Utj;4X5@F_tna=sxV z1E(MfWEJ1kvS=`MJcx6vvozwM;8z`&9E3ukGi^R79>z(0Eh0l8sq0+_hR&yHZaJ}< z4au_!}pY=$9&bO>M-@*6LNlzk5ocWl)$EA-#Oi4*`n>RaK;&7ztr;r ztt}CuArPxH$TDOkohiqvss47`2s#PKLDd10LB(QtlsRJ!EWXk~bx+W}64wuLgig)NC3K7Ux@>0{>jTaq|{-zTQODk;Y&;eMtC*K88lI9>?sb`RLLbwFu7v z+&E7^91`8+-V}8hEbMVgI*jgoj7A^EuIyJ*4+HZGaQ^a~$lneE^J5tjcx(&D3&8#@ zI(Zl)QA@Rl!RS6E`3U|lQq&RbYGoR61n~Z#r;ms}ArLdQZmWQHDgy&jY>!n>L!4IW z`X@-|ducT7s4&427;R)r;5M}8D0q1b?^1BvQ>Gp8%SBOt?cGwdfeSt1}%sCg#XLQPgp<(-8O(RUQ}pvl>aJ0)l@d z$<$#zJ@GxP30##o`gGGs2ll>fkR?evCePx1yR_yogl#2F&9RQ1GALk)cV9N^7ktkEX%)p0h5(e>Ujw<)!$4k#As2M>+mU8vQ1=rxBF>CKO{BoJmRA zba+#Q2bf!{%nCW%4ftM$hCKczSs(KbhFaxP^(b9uuE2EQCcek4YQ&9~l0e5zOutRQ zw*dd#{qIpynMiQQb%5__p6lxd?JpBuIPM}{FB9t%sw322aj}E76{m1g@Pw<5!&9XE z*%Ks9)epBtM+5O=YcV!-@TKi1piBIuGfvPkbFpVTTF@5Voete1j&Z-CizkF>$OK@* zC2CxrvSzP@;R8yuj){G$a2u-t!VYU_#(p7c<~VgCRyTnA5S(lwlxUvR^(_%O(+l8q zfzaRKj_*t8rX&>MDOwH(I&Ll#E-pN&x7-5n}34-O>V9x^LmIs!7K&4%~U;ffpZQ3_<64p!4{E zBMm*m-EcfcR`*fAx1oichgKJ$8WmxJD68fIE!;hWJNi9EjnMJ{gFWMhAa zH>qz6|9;~c1Ujw<=I)+vQJd?Y@#~x&J%f`dSX>1<+PGRa5iR46XRsZp_HEIj8CsS) z65BvHCF@NgCq=t{M+P}dQ)HEu*!RJSe{<(2X)Mm;nX(!Tp|Jt7Kw)Qt)1=iE=(yDS+eRfhrwqp+Rl->3-ROSueN%`&=FAx0E zfN6F?YbGP!?=q3j_79S@gZ$|N7(SXP3=2i zyrZf99jIH@(}+{NYR9U(rr>bGx1Y_wqIuQeG&f| z2k>+&>v482(4K8WN8>3bRA2{pv}59DfCQ~zhan@GjNw`v{~2_qT=a;(%R*B&7;y&9 zW|$Gz&4D@rU4;8c2|S4Ck_xO7Ka#aV_;);I!`ma8^KpO20^Fo5g0UXg@)6?MOoB_) zP6m0v>~tJuSBS9IGtdW|<+cA5EyfM!Y;D~QbX=ecuH+l4MJ2-sIm;jL70wVxKE7q# zNagQc_~z3;kZ4OxX4@l0a{hbKaK(IoP7hAEp;_L~%lUh?e$-x5gg9fZ#MxaxAiSL5C6LzG zd#s*KVQxAd4__K0THeQfy7Pd^mX}`NNOZYUgy0RQJC)$Q4hpFPA$XT2R*4e^_q&tq zarE=MqE}2cGji6D2T7Ks;V{%-0*N-q<016G_=2-iS$;ANe@`q4)v8U0Op^o3%FT&W zcjZIth72E+*1iX|qM;#${&-)s4%_}AHXRs>zoswg^$z~ipc+p03SB4vnL>R&5M2#x zKP;X7fmk4W+vC*O=j}F6`u2=?#2X-EU&Kp;)bB$v)$r#T+Vi0p9_0OgJ$r$46lLOs z&07Lz367@^NSqa`42AF0i)Td)m)w=3NeXAtRH)9+itf#qd@bd#Mo-wmTi$w);y)4* zZR+q?-5z)EZoHO8{h8uShH9fAMN-{7?U(YT&gvdKAs=yuW`88c1>4)G_rbKy4^8>k zGq@j7?MGPjS5eeC{7s92mQ5ty0$EbD#T|6hcckJbgdLL0crDpTM z`9^Jq4xO|4;R*uxHhgnA3y?m5x}JxjP!CrTBaq|dbx6)fauUuKFdN2@UYacs8o&49 z`zcqv2OJpgMiEvf;gJIri3@f?^hSmIkhB#^gI(EMAnu^6hJkebJWi)13c4U>o9f=J z=jYfRQlfNp0mhKmk_CUIl)iESxANpqO7B#Qp@z;7d*C@FJzl+u)Ge#T{b&Ua7y4|Mc?mpWY)@$Eai z(r>!bYw%y-3HclGY@dG4ou6F~a1_)AQ0`UHH8@x+5a>AT0(1udEKE|Dt0I=}UKP#c zx2XQA=%!zGD0J-@s&eDhNiV~?j|N^7i`}awdpw=G#w)PBB3@-}i2>81ZSfeYHH$-BwHH_SE8I5o@h3uhB~?zOdK#fX^kk;si6PwiN2| zcYu3Ap+PI@h4>nKd+pnsp;+6iRK46Qls0}WVhk1WbmU_Zot43=E|a4NMuFu4D@Kl4 zaW^#jCAf8yL5MuMoe-YiO@eC-2@aY39hFsj{u)S85m2$gub!hKx1&0G1vWom^WVbV z7>~F<%KnZ;uJ|~_n~+~ig9qGJTyVB4aR}y>UIQ`D4eGNG|O_bp##0~sTkS3AXr_Edyp8Kl82+(QH#$+P!L||-tR7r7|=?Z2Q#iw zCGHR;a!l0cGZ7J=V^TAbmi4DJk2~lf(!S0%sS@HM`%3eM;M{i~;sUcxxDzg--E+FA zPtyL+L~OL(r1HjyOWRNzLl|_kui6fTfi) zR5N_9jB2kvTkeDJ-L)OHXUn$H4jbu7YjX=B3%RlmsreQAbKV5 zzaPeDiPrrMxw1xb+|7HU+iR~!r+Z{c)rkcL^&M2&5(%RXUDUVmy$BT@0|mZ`?-lsI z8snz2ER%xoMQJTnzIfRj`QMM~q&Ws;B=@FwQhA*=;(KasCv_LTxgpONc2W!R&133S z*jZ)2EDFBcrgv6f5eV>T436qdE&eCqQKXXM{|7R%bfuC16UQP$v#>-%~|<@N#8_PWS6#8i^wx`;45`YuJ>5J6OPT__OJ)KqA4aiR4(w7uXmNQ&gx zI_PLI`EQ6va9a1`4H4h_1SV0z9$Z~EOKLlCkv;fkR#OfyEGHUt*|QLFW~6sQ`c6Em zP=kAmQxDUF8zQ=^eX4Q)J0qvSZof?O2R-~nj9y@})PI;~H4%v#RS4ZiWoA?qo zqsT%YbVRkdH&G3|Y=uzFVQsTzVq9V$)$SMH6y5zsjD}jxH((w_<53F%<{3)AiPOD# zwCH9dJC|Wk)mU=Z2sj;~!dsBoTeAOg`=xnw{ib-_FSrSuK7i9-htrG3-fDzX(FB8C zqu}3?;Y333P;pC4G?Z0Qbe$M(*j+{Q>qNJZeLRwzpabB$z+J3m+CN6Rh)&jl>DAAo z8+9T>eweIZijh%+pO6ENyu+6GLY4jUELd7^>TKt_a0}7lffa0CY_sGX?OTlRW zPG<~?kv?fE6g^1)0qIS#J07F)x1ooOr~S8a ztrq1{x7clK==yD3VKH)Kj9)FfJK5FUu@D5Nb7~Ad_dO13zNfUN8*=-MVN)*lZ z^%Yz0h%WL6)b$Qlx~nwg4*KNv(!x8!-(V;>NymQ_$Ni?iQ%_9itab$Vh+j&}?}~^0 zM*b%{lRmvG-paCflKJLWVxzi{M=|X)}rf#}kkCuzb1Xch+3$_HYMdv$@`L|;4*fhky( zH{pn@Q7kKwDkSauJ*@BLkQ;b>D)DWB(+~b;imfTo^PEAvxgwZ){wjL?12XkLAU8Du zS=|I=brX=Ant-eZNR>AEHV>rQU$GrpMp3^B|5hs>Km!FeWG$F+Mi8_RlHs<5;|C_Y zfiwbH;^sXj<)1PH+y=iMm4+;{5M~;wU4(y}s~&cOCNl6^3vKvKv>oxp+ZfT$EY2=? zS0?Q|NQT4LEKVE$|88+U#{WNAoRMFk_%@645rk8qfJi$GEhO|`#(|)i8y4pv&i9oC zg1?7TbPnnDHuRq(t^4oe(6N4*eh|q>$~4R=>^wJ5V{dJwt4^_=LwPgpwy*HQsW|2H z{cxS8qQK&MP~sm@axbQ_e~8C8ADeUL)1f~^=Z@Z3UV@O9RbAQ&7>W}yuoIp@qaTHq zB1m$6;0li*pFg1qAB^ZMWNSL_7^}XN{-;<6k9~Lk6b~z%M}p5ofit|+S`QBdzB1@- zp{B2EdFwMN{|a?o=Iu}G{}L;;c6evoPEbe#6i08-tOgO;?DwCg04dEw?f#1tKm|8^ zVe^A%oJF3)pYKghEpSuAkjk}ex!Nqy8~=qS$vJ&&x&Z#3jqe)GM91GT3on!#+sf&*Up7t*c@3k(mu((m z1rO$TLzymhd_YkKV`SI+2)^_kBmvab^t1;n&?e^0>991)!J5lcudZ{pt&ZjyjNM!1 zxuCLG&9w0ez+`RHca;TrvcVV@@;3zL?JfxJ-Lq{~48h-1dKtRjGHUK-%xPWwrps52 z4@8B>@Lm9rnR`OVGaJ&4oG1PEB^`4!uE?tXx}l*uYYLo!6a=VQ(y9BgLH&%W}pz(t22^i)eT-}&3UQ69r+1Q>Vj#m!Cu%bTbw^xv3JGy zc__Tnjze*PUDR#FrR896jPL0_(k6yuN%!_unJYK^L?_&h5%B%{sk?DO2!v~`vkI}q zu+|v9jnur)?6$Tv*~8dA>*Y281zV}Ko1Ur+sVpDi8Yf)Z32Pav4Y7^+r#OySZZX+i zf$xb=rF=Bk)D(OrtauoF>PMQz!6gsm;oUFx1%JaR!U>NX^6Wax=HUSb2dqXtL0uJ; z?r9t+Poa~Z#xOtZ7B;a3lU0({9I!~Jcsz{}q17ChZt1K>BW~G3Dc=r54~~10qP&b@ ztsqip71grVirWgpa8J#)z4i$UHuJoUCYtMIObo{h77SrDAf&l$#|qtKwJ1hbf2RsB zqkoU@ld&ko@WN?w6g_Myd+cGzlG1NIIlKekky5~nUm$Mte)k*XEkNGfH%WLKA2*`X z)FIinDX5fu!&>423vXjk$dB^@0qV}1V9cyXw3=nL5<6x%6!A7j%5CVPw=vb*)izvl zR*bP(E+&YcG}1>VPyHkQf(ee)csgEV@+^h|T3o1C~6V^z>h>e*_5>y`^x$+14NYARoA z>!ppIzhe`RG0uV*CU2O&CfV26J?T7(@F_^0tBPC@S0Pl&j9lJcSj7U3&d~kO*p-s> z8oUNPd&RAcLCm9BzQ&2P`_I4Sdn(}kLCsh=_8pEO3ciYq9> za#ecB&zNd3%pFkrtG{uG40XIU5QFpuO%60ZYWV&b9S<}PH&{x^Gsw8gQ2#J(3^K;Y zz56l9T{~tAbnNDDPycm>yUQh+NuB~Y#wsYX^%jw%-W0!E`jP=pjWqeN!g#gD8t-by* znoSG=^>(6k{#!sBLX2i#;c7E_{@y0$Xn!LtQE&8Z;N*eo$0x< zQ6cWNg&ErhJ_|W2p-G>lc}hn=q2*!54griiEIFW~w!MUbWtyK(C&SPQE$G`YV~ldY z15<>*V-&}ls6)8XJ27mkJ^{HstiSylYi}(ozX>R}0FkYEc_O3d;-|Tw4$#Zn!!h@f zB^K7wT{zNH6X3F0(dAA|X{}@~ zN>!jVBgK~43EasKaZfOxfvrv}W9PuHAVU=m{D(TYCkD~Gt@NIl1lv$XN_OG=35|$w zwHdpd))DBA(^vIQdY6;h!w<^x2xE9KDoMo@Xl(PfOL`_aO^YzLMmYW+Ge~LUJ(cE(C7>UI!mxe_eW3?u#M<3%98f!-FQz+XEk><6@ zx{`@I6sG|^;kAxtNIcS2j6|n@=Eo2~`@G3ea=v8bA-Q` z(=M!fBF~xs!`OSrS5-W5!{?kE()OH?-g`nx=q2=WQwY691x1lGdXXYFlr)M|xeypS zDHOT1NV_6}DS(OsA%MLAK}Gl}h*Ba%-tU}qL!!^~e%|+w``LSTXJ>b3XJ==3XJ^6a zEh0pW+=-rvK*x91Yxw`(@iOvrJsmpghFB4zO~_{$;tj{t(H8Y%YAO8|A^aRJ>7r_l zvv+XAy5wLi>%%Dy>hgIAvy!FG-VxRI)^ln(TE%qS+6j*X0|LV_7Pbs+R4>Yo6spg@ zK~nzYqqZ~<3uCP769*WH)Nx{g9qX$`{!~BV(38^`zOHY!0-kx(0$4t7Ye)-* zyM`L_P+WxckEkpdv&?JMC>p(TE0$~b|K2Nw$j!A(>ZRYTjuzdFZKepsGlg{;!i?=% zDvU;tg@SC~B>tOha}mc5i(#rB0?jlHIqN7l4~BDG@2>VXy4TZ4c|4Yqn}|r)NA{6i zi$|w|gfBga6z*}3UIqapQ8m7k#{^`=bp*_euP0z*JMy3DOcN2ZYPiK*TwSd?=bP zfEc_>TnO`z0-WJW^nFtigngG94t^w`W}wSo+w@7PlOoi8g;6B=iYxK>9SEI7CQvNwQ-^&YrHJS@=)Nyum@rlyIM7?7~JVtX) zj0hVt`&TTE!%ddG2-!YNYHxoiUPv_~_Sx5oid~OI+D|35g#CglWnNwt@ARalNHu9z z=}06W|AGfl zoUEq8+P4e-rw%aJcvM5d9%8Qf7M2=p_IDapVKcx_I9y<^ImIFN+fHzpfTb-$rnrnM zHUkd+U$^&gbYCq@-#&bD*ArG#)V+lmt$h0)t#2X5s9aG@H%w(XIB6-Ss|kuO(>W%U za#{+1Z^T4kCQHX$xHVkAa>kdhT4DeO)A^PnxC@X(+m)&W@C>U3sgRtz(S`q@3psN| zqGHL#Sj%i-6oz|i>aj76&M7Two-<-U@mO3fzjBhGXuUv{?9zY9+!Qt|*rE zhIIR`75elq`lFR-5izPOsMN{OOMboy-4I8RlD=K*W92l7;^Q5?o$V0r^jvH3>_D2` zS|rL3=tygqi4`hu8=@OXkJ#=N$6W93KW8nV1n})O(y<$#*BMZPvab4tmmv5N} z0oL$1)Bt8D**LRtMVvW8vUI0I?M1cn=WbfxK_tMj%=aC{{g|bwFK@=wZSiAn(F-oa za4W}}JA;{H1bn|yZAUROWNBwCUZBd#Fs+TiE2~A=WqnDvZ{dkyMw~dCRmm<8uK>+8 zm|n2oYpFD`CgQRJvO2+r&e6KvP4@l;q9h#K!v9~e$DCyE$9dBECV+LoaAVt=YCHZq zf1ZrHAhT}`?2T)FGPyZee>OS9{$g^lM!Ld$b67hspN{{(bJu5<$)~f3h3jl{XAyuS zyiuJ+udd&&Hg09|@cQOw=5jncq=&FjMYydmFV*p;MWVTeAI!S~a~`ht4LaXhcttV@ zXSrz4Ql*FR+lMQtzhM!(8~6IUh-6u%!CgeNkhL&>k+31~ezA+?Xhyx)0)EbK62K?zDtzbEjkzlgO;h3f%LwFgF1#7%m5&$JZPtG&f zCp$FP&t&68Q~)?yPp-?E0k9;<8VsWZF`ie$dU6>f#)2p>-ej5AEj#5B?MV<(+Gi7t zd9Q$tJL&rb@qCN>@75AKdo*LakKN(8Lw2(vAVxEGxVR78tatxVjx@PyqKrgw^0^xg ziikwr6H&wo=xftImGU=$JU1JpbK5eI9*v9M6OhigwJ-(NR}tyOXaQ@N5Y0(qBwRav zog_MkVCADjUBMDV!K$YkP?? znh&>MeZ)Yhd^LT5xfKmh7C}B~$i`Ad0e@isyCdKDaHX7N(X3GmBuVVNDuhBEyqsNw zt>K8l9hF!rNyf>_qh#UbRdT-t+v+;(yoZqsgREGbXh-%H=P;`7^cAg@^E)WAA7+yM zl-y6`DG?6zSwAdT;Q_0kcwWhIpuYV@h?2d7#`PDIl;Jz5s=pYZbhA?E0Fmtcza2dF z`NWd>BJNc$9UxrX!9_Xf&IHhk-4lOF+XjdhiU%?d5Q)y&w%D zB3vnTpp1cHG)&^l1`03jt+8mHgK?cFpRNpq*gd(OltCgAk83v>1cH45_rD^{VG1fi zD{g!GQ}!U?(I~aC<>~FTW{`MZm0c~-5Z-^8{9++P2Z@$wSL|Sn&;67>SR}ZN!U-)C z^cUJQSR`tNSMdp7^&GXFY6oLCqQ4#D3PlVNLGAw8hW0*q9JkCO zJV90k+r51OUWmBMa9vsm7XUqIDzf2Cl|@5Dhj>Te-;GpO%{a#ulWH|_nfM=ooO_VA zw>xh7=vR0(YnkGkd<@Tjzz8u5TguBuh&C|HI5t9z za=x8`K1oJLg^d))eevcZUkP)V5P#$()@kFAwi9W8juc&$4~nVvvm(J^;#LTP+xxM; zJNuNQBdvH=I4fhe()wq`C^>`fJ`0BTu=zYE2FXsP&Uh$Us-coAuHLpcM~T;DrR{dQ z_q-UVShvxOFNnnfzhTX7Qq4yi!QwBmqkHEj9i8<~gtx)bqNR%ovSmIzbX8F3Qg?qE zG8)^gqqfoJ(c)(%e4A~-i=wHle6iKGcZ{fVPzsAFH&a*@w<2miRs{H0zK#ZTGrL$e z;?gUazcLQr@$rJjj1_IODtX4eg8ew2k%}c(%e-8upJgC5psvBo#3|%x2vY%=tywrm z0?fBa|K>mGiKs0*%5_Bg1*CuSpL7!>WztL8DgTs8`JdI=+{QusQvNKmbsH}NWo35} zjhFz{VR;dqoxmp!K(-Q&!)V<^aXH*9EWzj*G@^v76c2&R)lOt6SY~`f>n1_eE3TGn z8`y^D7=Lkbmh6;I=*lFqrPa1A#(NV#-j-{|V^Y72cP9!EH-Z0yvBH+gHS7Vjw?(cg zgttiXGNVhnm!0wo#Y_>y{PCq1jSc2V6rcIfSR}nbmMNm6J5r-zaNyS{JH>{l#0S!) zDPo}<1kaEnF(Uc}uwfvxA-@^oYn_AdZ2k5&f3p*;vZ*33MKvNJ?#ipx zuDp50)%%Omrip>^Cy}!No^p8K{0D%W@3J+#zx7-EXIo6jltXFTjTSYL;%l~bkZP)s zX1Jb$n@0L=8WyRz-1U;^9lsvfB&c;P7%#ip0%m}_LrWqd*^?lVvmMO3om2&QAQN%? z{fOF4bM&I=GljbxLOCosX;EN%PUqn<59>PU(6dGR zf9I>fNKJYnJ0*x#&lU@ev^W$f2G5lUv&Kp_Q;mX!0l z*zIi}kXNvJE{9(4P^n+cc>_!S^ECerF*&00SukW%9(KGc3bZyu8_fC)%HILjz2q@R zWN{1Uh?XyaZVqRmC%z*cS$-5d_wSgG@Byo_-0`-~LFQC_4=^^5rNx{Mw|M-YmrC%>`X+X~#sWpb9b?vf6Cmb04B}&b9sl`lmFxO#aUbiu zH2O`9hvo3sCprZ5;aqTc#f81VxiAoUkUmFefV5pFBul>;qi!gY`5+P&9f#iB&STZz zN+Q0dFX9WJDe`wR1-yj?KnEK87N)^wwE8U&%$L4?ON2GK1337$(~AF@FxI;Gc`09&$!`#D$W}C|8eS?C3>)Y z&OC+DKyPJ<-ts0omL)oSyp7VhgaSM>R@f||>so4*jTT;~{@Lj3!Src1RP(QFa*k*% zH!i7}?66aRI}dtxAv}KNil!b=3$e@#u;!SZERm+{Do2`~i{qCND$EsrF+=k7>xZ#s z_}*vVuiU>Z6Yn9uXr%cF=j6DXbOqp!eu&<)pZ>`eof0r1>WJksCrdia2&#~_XaU|P zogaS$&fs*iM>J}LeH7Q&&ydDyC8Pd37YhOWf3%if$rF2{K3r?RdhyTWgY&U5bPd`K zymlOf=vV>ixB{|``p$#SGIky1&J$6JiJpFg*42{F^HPoP7{fq^{nSiC;=_5O zoziU`wVn_CB7FnRoi8E-F#WG!VN=E`0)7?Q!m_oo?x}OW=-%$n5s-8GngJ)8_z(T< zAOxwA1w*n3S&BIejt2Qk+I?!W0KFVX&maikYM#J-YrOy-z<|yG^w+d$ffyO+u)&y^ zUN&Zbx#HhjtA&`7FsvcC$<-TKu+%>Ih6Hu%X77Qr5k&k=n8$A#1_W-5Tg-Qf|ij-7e>|5GPtlPe>AaY$IrpcG-^(CSsmd$&Y;8gpwb@a^=@eV#GEfu|# zeQRvirDA{_awHaRQxtEZ%F@6s?W7t1)0aSA)-x9$lP`HJ7mpf8s21LVK6)5jiNz(k z`?v>Er+2X9u!Np@NBkJ`RE*)a=zzVwg=k{}=#vqtTB5OYG})fBL{~3t(^sH0_=I}P zA`+G1Yi;Egpb8CyB@J&5^TkvaArEIY+WEgksg@5>;t$yVSqUkNE*+3B%9VuGH(5mLt-#oU$q!fiOl5}a!1II{fkwGP9##NVF$EQqhQ2dC>E=k@Kq z*nXUj?>hJ-PKQ$xz}GN*F7SL#=T{5Zy4!wQEgr}!TISH(=qVUxk$9P7PINJ1#?i#J zB3ea{vf~Qw%~7;&Esnrip`ttM)OZkym5L~k_u3#_vZV8CML#86rJ!|Uy)%<;V0H=& z7uJcEDqv3FjOjiY%tUwBiRS$FIUfMsKOp7r0!y$79T#*3SR*kaOpJ91Zd4%se@IVW zMMKt$PQKBrj3XLYjTxp!?Xs&5fgV%dO&5+|;AO?czGvW$_L%L|a@U<@4Pb zp0mHEpLSpkeCC~6YJx%EsEc%D0u{cd!ldJC)di1Ki*)x?%~FVA$PaHtL*;|9(7SAx zp;@ls3!75!ia&9&|Bs#GZTW!h4XgM?Q8SR(S@#C**@UL<5%5ZlMm(LJ5<<)Hg_>;N zBNDxVBMq3j-{*BQz-6l4BgQDP7J6~77}FBj=3%q#++In4Qi-emK2+GNFkR&S<=iGN z47_oQe%*_88NT?W@)&9RMDrw+Fs~of&Be0*92CRzdpvu9FB5da>0)edY9uyEu#1k( zuNF8)FM{;PZc%J}DnAG1Z>@sw5LjQNX_gaUaU3u16Tv>*UpPga4?I_)W=}x9zFkIt z?-MBrk9}qRfdk&(<>3Gu1}YxM_b&EPd3$@jBzl-IGMhs6g2fT~$ zC#E@93oS1ZzR$h6qL!c&$8p_w8MoI@&hL!8_i+E2aWd{LcAS##Pr%oDA9+|puxpxP zyQ(i^Cb)_@C_{3yBw=G0Jys$T>eO;K3#S(${RBi*3wq`~@iDC8L-vadc_HQO7j~m| zndd@Gw#BlWB{Mub1y3sM7p)B}oK}us9@3cq4^q1WSWT|Nxi4ljC>~x`>i}a*X(x=m zd0r^QHqs(ahf6SsfD-OZ8H`Y8$qE1I(Qt_ssu zzp`EB1pH95t=u0DwCo_PDsBRl+NQXB(}xGa!;Js|s>f356h~M$9u$r3?MKCVvZ@A! zqjBg6|9*$WTw_s|W~U7|YHLdzQSX6O06b@6>cF8{xqdGO(n==)!xn+ICZ;hCC}4Gd zNOW#@3ypcAZ-4-)_=Z08gl=gK=?2RaT%SHHnzj40Kc-^P%?45%O9ek`6|$Q3tpRWA zO{B97DTTiR)&qZ`)rUn`z#C|@;((VmLAo)L!_89tTBRQ@P@Xv~0_}~mm&h!&6}Ba1 zyRkCBFyKZNLMf>P`|YS}6kv1Ft2%Mo>u<@~>Q<9n^K`IeG4Nz|z^idI)`p$-D@$ml zO~kfdv$WPvw>+Km(M~Xk{%H95CADORk!IMN($2a=NB&;2ly2BCljkj=*!RU|<@qJH z)9(vMMbVa1)dxtZT}GZqMJMIfG8%AH{NBV7Rz}Q9mmfYp1pQ_Ob6_4GO-zH>y^3~R zLr20L-iPA4b6I1{HLP8+);%Wr1(!FrY(>2Tc0nY`xV(h6M$B-AsNi=*-a973LI*Fa zC4OEe9B2;3yLIIYimA{w(*TydjD9~Rq8R5^boJl1fa7AftmHPPk3SL-%Bn@S8y^Wp z&iXnLlP-GipuKAGxC_M9%0uxQGUEc6Za|Q#mX$ zpQWA^n2N8{=n65=sQ|!Awma>s5L1=oZ&TA9 zre~cjTZVDE{(uHhjgc+AY3gZM2>nE>Por7>^eMiS^9$(CX{?G*P{e1#EA$xf)OqRu z5dT?%7vhkVCDCt-DCILT1ZPf#pNUuDXd&QpVRp{*uw0vtsg}|{hx)VOrrU9BvzgcgF_#`Grcq z9a4Td=zA74UkI89 zoI0RCIo~9hX>B)Dh9clzWbaSLn~pM~(5lQ-40L+^tZ2*mPhdy;BE5(FjN4&694ykM zvm&q2HpqwWH2R$I(}+olcldbn+f6y=gjb(;5Oo<(6S50~B0w4&w1K!QU{IR(ry#7W zHYOT#9>aYJ8+1ZC>ks^m_sY)U;>8b*4WlgV)*R$RG#s{6VsM|NI0RGOkjg9B`5^{W zDn#*O3{*2t4_De-SH_|XN=72nV=k;3QSc}X>}NrV`+CxjUcun6K#S+S zg4Kefq3UBvP$`1KgLFCIXB~;UUvXkxjlBo=t#LwC9^(GOn)h&eGHrviV^$q`86l5s zChykSe3Yg7P>NKdu_pWmReiaVwx6u$LU-D0MSD-Z=(t{~r+pJ#{70}SKN zg?yd&8Y+q@kYW4*i^XiRU*3O^W*|e->qd(h&<%jROR~8EoGyaE>n8xml>=v;7YU)a zng6)3a`1^xnQViSf1}XfXmC}XdA$yUjTA1+VGaa8KJHph)QqBL+ zmCMp3%O2RlpT#awDV{F4jI>Mm&v4i1`zjIGpjgZ;QRu+TtojZ-NRa}iY4S9J4zpsl) zu9&|yj0Rs4epvx1ir?#CY1ta>DbSrDds}hFt4q1Mu~*uwZtTJN7Cem|#vB+4m@-BB zjPrWoe<_9${}07~ZabQwZ&yxqLoZ^yGVl8#jrCSuBj9_K)ej2YB&Z)P?DhZ4Bw`1i zSB~%oIQK*L)cBfHATFyYho;IkcY%0v11{A2jweFq!hJkkd}5gn&?~*8YWSCs2 ztJTcW2QWErmGXB0M??Cq0&O|pp$(6TxtH_sxXxfXa8Q?PU({U~(eZ(6Sw_q|q#vvO zI}JmO*>CG%{bInE4fCZVUp4wI>3!V}18JS=>xg!km~Cy?OF|v_-I3)D`dlAv$m?(< zJ7ptTz7&(&y%~?ItNJK_Gr!9w%U}2|g%QW0CwjDxbrNVEt{ZlETXU$@S6EhXwro8L z)~Wc z1?p#>#2iMoUmLT@yc4>E&TqsDE_mxF@JdZbz7ajJRdMedv4iWEbk3+BuEu|hx!{dv zMvcm#s`2!ZMwhucSI|H1HT#Re50RoVm|c8>j5TLYd;x}j3MldYDzFR8k)zOkUrKo?bQv2xLu0LhU564^lC5k zY;&Wog&Djv9vEBOi`>2!fq?}`GdJUx=z@7vS+{)5P4~CPWL}f04hRs=gN^vVK6hb!_k$|M?L#Gkk7z!Y=~fJku7m=S!cy)=T&f50l~+ z+jp*VpyFKx(N3L3$SU)=2MR64Yd5__XJ9D4G|@{8HgOdhWZL5qfrnKc5WXJ z_PREn_zp8Q(ifr-Xg5#V$5bl@+==hmG}_nN7%+1Iv#bFOSGG9EBg?Y&Vs?rX0Ft=- zD(aR5zSg3i7&`j-j4}6d_Z>r=^d)at`B*RZfa|sYAT*)%^Zvx(;i!cz3C0WyHov~oTwU1?P($jcm#pA`fCa>?{7M=&eAKAtr zNcF%?atJIIHr1et0~%UMQ>%qv+%B*bdpI;9Di=M+7SY%6W89-(k@8Ktd^K5%c{3O2 zSjLQ@Bh^@c!Q!wQmR(7JQULV}G`{7E{?;VDAXzYCW zT0QBlpP{D4(x#s=>_h1M&tjnONMv}mZc^#>WKwDWi+Cgqr z3Rslmc{SSe3l_LYnfH(WfaEVCoG19`$Jr^_BwrW)UOf8o^%`=p<>I-lT3S=&=t~LL z#Z$cM-0F$*e9{UwK3=ucB=~d}aFNq|x9X3t@(3g1ic;SI~l$2tVuc9#SL*yYff#7~UQ6vmOH?Xc%!bP!NAdD4Jylh5Qdk z#yomfWT))Ula9PZeg20fS~rx$^X)eexWpi9+i@HQTl+&X;?}gEVhqsb(~TPKfg2#v zJ*zv5UA$Y%peZP?APCQ*qJc&Q1FRi5-Tox+08WRgSi=Ui;B@^tUO#IBrw2e7q3DOq zv8{QH5p3;-c-G$de^>lxiKL*as8*JBVwf(&Yr>l|aDcT901UM!z}os>z`oWO85Vb= zN_E2-KWjA7`JE~zPSn3(gRM_7ES9PeOu!pt?T1Q*J!(872E^rF>gF$Xp1FX&`AvAn zG)7*d*MqEX_^8Z|egZ{yVtJ zlcxSI{3bTWm`{c8+p&5N`WVlJXDb#L#24tAc!2eC_qxIZtUuzvzL%v-RUhkPaCWMG z2;yh`;t8Ce_0oUf`p|E`vmpWaeH)&B0#{&leM`)G?*2;#h4dG6gW)t8z0cjp6lVV8 zD$hst!}Se1Uu&1iMpu>kN(WzvH1ek6KT~*hg9>1FxCP~V7}eauQS2gMWlfPgI0@R~ z+a0CaG~{N!8$j)DV;=Fe)9f`20N%pEtXVP)OKBd@&UorK0y2pg;MFVvR$?iJHatT1 zd-%Pu8E)D!hd_@h8D!5>2cN+*q8Qc{fKLG&D^3}xN*byW4uy3p4kXZ6x^P=~G#PJv zSi1u#8^{=m3F3^W_2`90Ww0CihX~Coal+0BSB_zFQLzf1Ti(Gb0}5(`f^fLzHvt7n z{qc)7*9@@Z<^yEtBf21}t7IZi0n2cZhsqy8{xIa{=W3V`8vy$vCcTD)hz!lbWW<@a z;OVahl<+{t?e>h&I!iQcC^XDij*YTBP{d(fcFG=mK4x|k@~yS!gFaF+^gonm!@3I2 zw-$a2INu8(J7>JRNy=Z0jF<&W2KI`--`% z@-e+r&K<14pQP2zylfte-O4+{H>)JML0P#F^?5AtHo|i^%3=JcP|oux1G9KN9>DPo z9=#ewL;4Ts32tm%FS6>&jm%tyb0nnmW*oCrT{kyPTi}n?FIJ~1ax=Z>h4ZVd z#-`~B`s1Dm^7oU-b5g3^5iW zR~=#9xmebpoeZHr?hF5pT=Awkyd4S`Q&2}azChKz z#M<*1r$pQ7{9~~}{%Q48^?CX1p-0vN2jP8p@@=N=+Qp$e@xNZJegEiP8T$J5RljOP57k;8zbz zjHnVycTl@&o744ea!mH#)(y1NL9O;Ul+jQJ@V4HfO^sAPk4}g-rc{3NG057UPBv1* zeA*#;!@qL)Sihp0Mru$@sGh^vj>*LlZy>%OD_%EQWCcHk#4x!Q+ED zy#7H`m8OUKwK`^KR9*n#BoBm)hD8Td))jTdm80mWaukPgu^Ywhw-?9PcCZNi z7hFY!kHrC1v;yv3N^?@ZLiyUw9=-HnegCOQ_WJC{H}I4wvfq7`RywJXZW5}JnhaKd zGrnf^YgF!}4v}w?hqLOZ%z2Gsoz>Ppi7M9;E>&lI#aJV()0Q-iXG zAbPqTg{*k#DEc#s@%#|6fufI|HNaYA-#hMyZ$>!-l{=haK4L}BPs9H@8l{0@n3PPT zYiOV+8dnGy&XWna8FpF%&QAwqZe()+X8^L|H0Bk$p{ci=OOd~$zK!mtMysV>7IVKV zUD%f56Y^-R_QqRe!yBtn^mc-~n{9bx^|Ye2evL+Xs`r$?UZxZ;HB#9%n_lr!Cn=x5 zN>{zq*r<~)*Ai>hN8r~O7rYL=j;ds1zP$pO&7BsN;cIK-t-h?d|0_Bp)t3(Vs^6)4 zY!0R(Q<^Vr@KYD}O!L*fEWMU*Je5`08Rs7kl7|_474Oe7Y^5alzj_6)jvYqYVOctq z3Mp^K5##iiDcxTkp{#j@KJW(v@3-CH09+CnsK$EUNA^NU=Wv)o7s6d(hgmctP)$@& zmkojH>x$njn{SZ1KvpKsrp>|XKm}F08LYPEFepUb%z#Hj)Y(dx+0;H%9WR&I)`zOw zOzxH3;xx?Yk!W>ZlphU^R0BePpHWM%pjJG+b#IK-6ngM|><8=_Z>|YCKno((8O@&L zR4~(Kg!@^xVnCHz;3h=xUP#@MxW4c*g+{59JhubkvRuhykK8P@;4Sm2tJ7(Hl-jk+ z6C|u>Cr0{NG7&BU621oPEjJB~LHG)`JDyY%^sb2XBbZ+f9yJqKJ3VGYdSB~DkQov( z%tMCR4KnbeycmdC!leQ6ETm`J)ALYkZhN^mhA4i|A)U{SN~Y8PXf;mU=DiQzd&|Ma z+-Nn;tCCj_g_r#-xgZE^ZSoi39o;5sdnFz1L73o!8bOl9vO!7)N@4gk$=?zQDpvuX z^*<2P^E-quPUlS*c-X*G!TP2PR*`+ClUq}@tI;j&frJ?m#HEo<)poHzBS#&>RO5eI zr1=PYqt1d?gDaAMC*IQF^Xl(V|E6lJa(+7f&{Q36V3R>P1)W@hPVU`I&2d``3}4|& zD%bJSOLVpw#>gi#=}t4Xw*m@xXs-6+a8`5mxDxJX>ky-!l9hOW+rwD(4oqJBZMRyg ztxU?X=@i;l?bK`z(D4!uYEey5n7PImwmxH_3USXB+FMd=_NO^*)eyyX2CZ)k_FOX+ z-XPR9O516a-VSukm`ZEfsjb}gTxE6bN3IL))IPq-v|2xTnoi*-&OG4zxpjMWz4F5p z+v)adSJ}BF98+nY6hNY*8tkrraq;QcWG+T*=Zy(Qx(dGfFFTEY7erCrD5XPG!1=un=sofL>f3|c{V`Rm53Z3q% zUQiO+(3WoMU?)s%x25b(^k+A9Tj146FoZ;(>BlATGr$L(EVsX!O8dK`7gkNCFS>&| zA5S939%_p6##9>BLp`j_n*^@_h*y?Qri9+=H07%)v>%~q(BxWr+*=Kxw$D3y+J=}_ zPuY3O6eg5+EQOn$yy?w&HP{Q?v4W{nh&tyoJqiM7SG*dd9G#*!P35C|$qAc_**z`# zHB3?y)L~KUfQqFLZwKBqI9tafgRWQc%K)CN1U1@JIWC*FC#Y4P)`@sD1Kjv7!qh-> z&Gw13I1w#5KY@NoR0DlaPhd`#YA}YZpu|B*%B?y%f!vbR0j@KVhqZy}6K&~9Dy*v> zPM}W7$lP=SElvh`LMG7OWYt&sasr)7R%iNs0Ay3`O_R|q?zQ5=K-RXC3d=j1Q z4+$7EiKYzz@fJWfP51UfxjeMRXpmJ(9b6yI;hq1A?TsA4H`+2mji9Y@v_ zwNDVlh_6+?(w@amRS`CkSefKAwj1N|dbk>sb(;Zl%7SzN3jp{U-!9B&9G_MeqQ@^m zJl}l?2NG7$4oArr7m$r%BFchwm|RAVw7$s8oRY?z0xqwXf-Mf=I8mN&O!u4Y`3LA_ zguo{Fic$DXAYfz3AxJPoNM3+DoO4g9{^7TWA!ay4;uRESx*BXLKq_C!xQ61JL^dU- zr`6F>8#0Y|G%oTRJK&pYP{oX^KJj*R9i(7d__R7$c{rZFcpAL0J(K=^8iHy~CUtv8 zr@fg*Jp=mo8c!cQqxN*xYtaeW9zUb{H@lq(M14?;_|p0sWLyr`?*whb!&Obtz;~)1XRaq!el~f0C-J zLSezr-obiFkN12u;ewtvVP+Spz{r;bc+;cl7v>|+_6ZqXN=uFSp@?^Tl)CCR%JG;q ztxGs&YA&a*Lxfc6_~Ecs*O9?x;tM>keHDO7vcr@C<_2K6Eew+f`UhpG!&}I+s+r!Q;8S$^$Lz_Lk|B~8?;oD4C2em2TVp!C%TuDs8>&{Rm#>~YM1=Yxd zv{c~xCjmRC8UD#NVgJzC`!0c0`n&2tpG;RXecu{wXny;BC6A}|>DJr&+Gt9cq4pBZ zUu4SoTVHwjn0}n0hIGQX(~G-epM0v#c+RvnsDt8ozta~PBv2|78CVGLs@LO1`eBAT z(Yb`VF47cDLuabt4kZEM(KKtOI!qY#D{-}CyiaFms$V;UXFz|+iT2G>le|mDCPaT` zLpRO3^VS7tq#P=bv^l-3zU3g&F<7|c;!}IlJFlr_%FEAF%IoS##T-q$UdO!Q^#XnI zy4o$;;e}c{08RD)CbbT@Qq5Jn>xBsee#lvLK6)NJpFPAgf}VLpofYW&yumEkZa(-L z?%?=2UJ4&YgRK7a+BxDRd6jjVQkJ9QC|%Y81J?slKBm zMB6sJsh*aVtI;%mE@b=FXj|hfb&-ry=XKd?3wRhfnXOhSrjpE!v_4ObFqI_v+m7d{ z1593E@2TcU2jbC`pds?G2)!|bJ4o(0o74!r2tQt0ze^xIOkh4ScQ3S5TO z>L1i+nfgx1nUCfCwA|nasY>tz89mAlopN(u#03fk&p-aLObwDhB5gT>_bFyMaPOtz z%Yk$o&E{Yuty_*d72D1rFv;a4uLS5(3R#K7{S?0vi2z-RR;;JOm8iyYI?s_g)MypH zW>Xvo6KO00W%McfXNww0C9AN=9!8&XQWDj0(1l|10nzdlOP(Kbvb3Sj{NoeD6&g@6u5h~J$F?f^9TEur{G+xwYtr`rUJ;3FS8(WBvp!sWo z(3_5|1tw?u6@l{T1O=``Wp7jeb%?!2uXFGf?d0Hd`g$F5fc)$6b%1(uu!E*@uz@yl z@D82fAdhO-0}?E;0bi3Sje{4-!a)j^aga=ZYye1CYO)but>_sJP$v$2=+H)_p-%ku zh|&tsfR>xk0Mu&}Qb5E_NC6S~3q;(ccIQssj0b1lrHPx-yh5748C|}Xc5Vj968e5K zx;&d)wjkfj)O8CY$J12)dY(3MFqF=4kVv(h)`{8`;47BPZi5NPQh-PgI>}#+=q|pL z2Y4r_Q0*rFN@EMvL?%)p$~{jf3&H;3v_H7KvB|m z1Q?neY@*fMk%lq39T`#54n$6&=QtQeg*%Yemww}~IEs50Uy+oyH1;`H6b2pHoi+AJ8jn3}|GKJ(l_`=xW;5%Bk2gvZ0`X2RJJnJ007dmJW-i}sR z$#0R*K9qo_?1La0fJdIyDpC0^7UAKLSa0s9<0a~HWzk^UkoVM44vp>%uB8gfx$YHU zJ9S9?NKtZ{*cQI8`k0j2gJ|Jmk1YWwA5 z^@hTKE}T|zn{Z!WJZeD4Hag-Z=Cf*ZWpiKp`>YzOobE?~=hPsjtSNOq2TdB`c!U9E zO>rg;(yjRu2h%% zuIgjleN4r)Vl1hAtc&~6jY>7d`SxWrArBZDpU0|D|9Y~(Lu~i+SQUQNkJ8VpZzxCl z(GTaLTbA@ArAl4y9}T>`Pzi@B&)(u#YYpmGORK}3yuD03M*?@Dea6lJwsTeL9_78h zH1~qKR~ep6tuLxWl$}X5_oCWV*^)%tFRIDP;6C*GMJ#!%U-`j(Df*=s1MUu46IPA)dBhS3C3fkJr`rw9MWH#d!zocPgCV=0zpHs$CQ}Gu`+V zO8C9r^!qznB&81ZbfD=s)L4cpwD=G;_kmF@BL#{aOAn;TDozhQf0R=h3wHw-Tzv%T}X+DBH-ndysL zQ2k2HHqYDYUB$VC8=nURjsH}e8($d-&8hdFY8Q7sEe%tC5y+5;*oFT`Y(-*oI`^k~ zEmeorbwE}T%*`#)IP@4k`v1K7#xM?0;_T(Z0#lAnO3F@21}u0smQ~kA_H>42+qYtK zbDP&))j>9@6mO44G1Tmy8tqWB-Mu*ty{ASrYuN*93_G>V@O-1Ox(J@(EL@_#@&#$> zp4!s8gt>`hIh9qLJfwViPi+^dfapAc24TM)NBglnSW>Gb%cEWtc^{1bXD>>=uP$W5 zpS!Pqku1en{>0`KFaOU%{Vs)-fTAxPVL~1rWBHWhU=e_!u!7O1nPV&`I1c7?poJcn zgST04K2SSl6~tKHLz)D`Vn=&g+2t6^ZjOUhf|EV&N_ebg2japJ=WLIY(_$?}h`WsP zjfJb1HKH)qvI%hoh;y~W#b1fFtVJ9s^W>eU)lQN(k1Sh3jryF7o6LXz4dMF}B|lWd zl!TTv{vjrrakTfL>eu8>V$J4UsYZoiZQ6{Gr}!RR`!+J~n8yynF-(@LG-H_y-FT?B zj;n5K#GCE$&hwIM-kvMfMBquoA&5KoUY{CXiznd!Q?K={Sp~fRqxXJs^`g{AYK`LF zf}XEcce*-t$9@SG2YtGc+dmk+?RwIXf575Rd(s>H?c0++_y@ZOwLK{GvHFj4tjFq5 zt())uuE>@w*GM-XA1q9cuPIuYdt_&i)zh?Og?g+$tc_BVx{;@>by7NYqXDuOtF-7w zuW%UN%~m99U1d?y5B7C@Cto>0KPy_S6ZhCWsU`WDwBdM+ZlXzRp}f?M)|j+T(96!4 zv{{kd(K=&+c_UeVm|N;ED@=uN6=rgu12|{X+Glw;fGY=VUP4PtbP?{!un!i<2H8^8ch24Ir5Vo=%f@TnFvP92^iz*L)CW?3?~ z;a;H~5${SchcpCA1R@6%*3k~bz9*O~>tL<|Q3V>uC+jWjFvkJI99aj$+ao66nfES; zVTWOps@J-NVpFcd@qF!^qfcB7>%LQ>q?)I|4^+}f^MU?*s*#qUBy=ZNM{PVlXF6)F zz3M7@1;du9f{J2+rNw#Gk%AMrnIHu{bky1@9$l!llNRDt!h6;auz;w+;=#uObNGIG z(FqLkZ8zHPr0w%y+F9W9`&pw8reX)%S?jF;&kkoTlEcrOwI)hIXS(C8HG|3<=%Tez zOf6}ki`GY;PZk%ggHqjvPPu5)WG9Mq)n4#m679=Q`F>}Xw(drMtEfHTT4-8p4xiVwrWpRYn%22XW^&C? z$ca_BgWeC2r7FgH|>V)Tnj_x$p z(v`lQX@omip;KpC@2>U9y3HJx!^aZ_16ZQV!1BnSHdfHBVZQC@j=9gJNsZ0fDa;=gYKE=MGsJHY#c53&<4Bf1r>tn za+&Es$D1Bnw6h+Yhc7=*t-t3;P~rVzlkxOCaNGwod!m5>U1+bT_Ki{=M~l6*UP@JG zI_;$;hkwnJX{hB{Mq^+tyUu$x#P`mRK^s!cAy946B|$H-O=>SHUn} zz#7XAa{@4LG^l!=Lz9}xwAn{<48+*RRWK(j+rdA;AiS>+Mh7dLydL+_;uGtLW+}6` zCaDTe{+?#0@QHQ7q*GS`PUkVs6*y4|yJWy{YbW7w*jH<1^a%rTEsN0$S-#pcS&ci_ zQdv=7Tr`2eRpccmc!K1nN9a}lNT>EFjF(#6LFe8c+2H@v4gL>r@P9~y{{tKR@7Lge zALDszPxbA<6RNzwo-|SicAI|3N zI7_6`M);ql7f>SMp3{>Avs;7z9`*lI)%yQtuloP+I`ky(WrzCzrB3z#3ta2}o4xD* zd%!^lXAZ}4DMV0;e9)HeuT7Q%aMt()X}E8L|MYW!wpsb511$*DIzU!@5Qs72*opoQ z#Qc3Ljz$DQDEtsd>w~o3Nd6{B>#kt)z%LjQ6k+#ZOy>y42Wv6P`|W9Eu*SP8<-w5o zxpCwgqRr${JU2woeLTd-{V>GH)hyJ&GSD8r6siR%-P+UQP%R8ttf9~y+}qRDP_3!5 zz5}_2X*Nb4rVUi2R@69L^B-Bsa!Q|zq*mBRmt$wA7<|eH3E*Wty$pQJ@}~kYnPAx| zfMHePOTd)3(;1{h3OC+(1cTr|%?;NUD1F z&-S!ELZ{m|5!!O4ygf~d)Lv{F3!Jrc4(QCt1GEFWqt1C5%QyBul)2ybd!!a3hv_xs z4QU0ntS)b5nFpgHZ;YQehU35(?unzdxU45YEL)-~T3M3dK4u&M*k1xniR;rLB~3`r zgazk|NawR)xMJ7S^GaJ;xF8;}(J+i0fpk6#h8;qEepDh6`A;By2-4ZD?p>3|zX6KN zThXm(ZP>r7Re@}H1UscQvhnQsM?!1s`qI!=!wc zZ$H^f)nU-sVi4sT&i$F<-v9;_w>H({nm<9r-C`_Re_x2vh9I;>#cChO z?XpAbhUN}bSlLp$ujI9+C9SkjkDS&P2T*`pX$ zogfa+wxKsVX*24f5&&5NsE3`jXYE@F=&|QJYs*bp*-dnQ$aa)&OW_gq|IOj`|8Z=^ zJfp*;Hm(0}ZdU)lG^+l8YFPdMg6R7Hmkm6MYVH~-NnK42=GSc#x@#jH8<+4M2Iddu zlb>)qCmzgmE|xkaXdiygV7D>l4>!xNO0&>4&~0NI(JM*X8sC6eKGYt!xsaf1cSt&7 z!fnaumK51XyQh2+V+%~y4m&DcVySA7wnTFevaEs0(zp1H3ZzMcwV~R14-2FF7QY=m z=+s~>vT=G-*h8>p0Kp(hesq7ZmaCMuwapo#O>$An+uD8^sjYB!u8eupd}Ju%vr@G{ z7p1JNZNo%utE+R#dE~oQ*2dQNWo?wKl)F>$Y;CJ^r86F@j|KS9SG34Rin)z#)*Q`O zR#My8mb|IuG;%s^l2#1KX=C%sg_`Mf24B{~Hnui-nv1M_;7{G=X`>t>ROq2==V>Ex zK$}l@=4r7(@d35O66hqDt^k9LchU5Xm(q^ZdA>H>A)NCpov-=J_h{RE%(w0Vbag%y zVL5<87ijIAO19_s#e*mmdcLtQOqst-8IyI9*Iucp;Yv66NHbKLXILFx=i~!Iy=_FRt(rPv8J-_SK89Tc41Gx3tCvd zFq{!*FV}i{3`(jgJcK)qcv|;mfafc8cDXiFd*D;Qzj)W!U&P6Is`FakTH%SFg)IO=xH71b;3Mf1?ms(_ zzBB?*GmCae8SX7!UM`@dPwl{UogF26+eWU`RApeLl-fogs(L%aJJkQb z+_u60R`vhG8^jm1tB+5$?akMY$gm$Nph;`A&Ekq9y!)tgE<|1SBQMepD_8yKGty#w zZ+T+_Pwx=J4rDg=UvGGm>sqXJ0n>f0Hdxv0O^erp6Q1*>y=$?Ovv|=DYc*fjFtmyf zbu~ZwXRQ|Kn*dyEu;RU|J5~0z{({!d_NLbBv~;%#NW;!-Y$|qTBfM$zIxSF1@um;f zK|>wjMSri;rg{DDRZBIezs8eJZ`9g*_5Z&hZoCP4C;&Te!Yqn#qfSuRRT?CG8+0E*EJ&G^0rK3V4DTvxptB z?!V|eiYV5i0-m7fWCOkau+SMAU5viDU8MQf*9|4r)h(!4i>a?0C)n#YvKaeAbyy4S zIk?hWILF8KO6v*8QH_Lei?#mU>snKWwsRTW8g_R5GFpSxre~c`GM1LyY8?&;63YT< z%vLS#Nkdr0X9OtHa&0tr`HXhf6|5&41zR$a++T0!nr+(CYc^`moeS+$;^G}rvs0R* z`2V_~D@qEgG_BVqTFk#7S8d0n zdC}hLD=Z-aomU=6PCK-YrrWbr>a|0&DTuhg1M?NaIqz!L(DFdb);73Wi}|f{Tik2| z>z`J}Z~g$g3W*hgl(Sc=9rFqe?-C6{L%-XH(=cLSO*(qI&B=a7u z?vV8S9<5Jki90Lz$DSznd;}xm;ibD?Qq6O2bbOEYg;MQCYxbh1slimSSKFkNxUscm zAicQ{dJ{+P(@Jq@Ij=-pfqmG7SS?kY83)bHz`V&qH7q`MY2%zR}P_ho6!d-%#j}K@))Z2Oq z5Lbza>3dM?Qje<$a3;ouYgDi_N*N7Yn}KU*16&Lfg`5WtYDo^a^U%77z)@ezNUjfJ z6Ax)?ah`}4F--L#t-yfEL7iFoWSCWlwLLh=j<;zq8j11tW+KtH&!)AK<>vJL``FP8 zB%dSN^EiZ_aYXa;xz)*V5d@VHM~wkEYV@@>r%gw+U?n_+jvmnhyN5pgKx^TVkL;;gO^+4q_##DWpIq=;9x&{y(7HHR<^re!U$-i>w)HTq4n--U)aHcd-yjySiHIF}LhEP5 zrh#j8u_*!H3GKBfHKH~rwM=_XJ4`Wh7N69z?K!cUEdss_0zS2Pylex^GQb?P!^m6SKr< zgx`J)af9&j#}F$hap))78whQmeWI;)WFwYyI0AsR#yJobwm=-1$)yq;2h)a1Z6KTf zR3g%yKIK3nm-C4Hjh;D=ukUH~dF@rUov8wrLljqqd@xn1LKmzz%SO==1qq(~KzBm@x*NR~E=3Mp8KAfY{1Kp_Q05g~x0h+slcP*j2_a3PxC z`|Q0J0*}x4^ZR38GdpwU%$a`X%$YNy-q#5HQ*{0sf7i_~e(m^;Ra#wpvfxPwEy+LuB#CHMbXB|AYBn#>v6O(jYOr z%FV=!^r;4y1FoU^(oF8=V^wbD3MBkFKk35hcYktw6FaTg8*Z)I>adj%K9mw{46c1r zvxP{Tez#6rPsL}&xQp#K+`) z-E8XkJi}ofZR1F!m5XBqNA+!VIJyQNYZQk1>Kg%h4{AgPwrAVn62Jbo?lz1#fYXNh z>XP7(@7D;rpFXF4V742uxqI;J4!g5Ubs`38f7ZN&MF7hRdfg6t#VbH99K`P&TFPcVm#i0C_C5P zExWqDWKqyaKjBcCUKLzf>7bpcbk~~ZyNSz84GNCKy}&A1ErikI6+XCi0TUOO{;DA< zbdHqKL=!n&^)t8SYSVhQ0g84C#n7mdJj_$P)e{CNBen8ZixtH~-1b+GDzb-pPk@@^ zXzdP0fS2kc*Fy|6sx{Wo5`@x9mIfqaLe&8c6v;z;&|19|c;mMk-B5Dz-=ymw7(ogo z5YwDraJxoqZ=MKHzH*Z?%C0CEKUv1-?>#ICUivW{|L|ej_RvQv4;rkWOd)`q=EzY5NA87k^M?N zbSY&F62FARlWeOgWkA(gfD9($0$69nFF^eCI`Kq6T#1KnhqfK!pBL?xI^k5jvpUw( z9~9FCG5fU)Z~UL_tS+H^`*u-(Zu97u8bM|-T+o3@E%rYCX^%`Dx&kje+{Hi1C@HS` zml|_gS2aNK}Zj&9sVbD zSBCEF4CrfsKGgQe#Hi7 z0GdZ8^&LYp&=ka|M#E6l)yWujv5iAPd{V3$9`_sKCj-GEAfTH-lt~pbx!wbsT{1pr zlE()YRsrq@Tw-5XCnIXgG9cO$tNM-7Q&UJ9Qt#+)O?}#y`Ycj^@l0yU38^)QZWuIx zD?|K}I@l>b4)qrtr?v_{2n1Ar`{8EW0Et}65J2V`ajI-Ew7OX%W+$o@R@TZ$#i0qe z#6wI-QrkWWjYVh{LboTW&l^tMz+BWz9ibp#N-s6RFb-Ju^upW&yq9~a10Xr_5H0#( zk}B~q5A35R$cCz)Y6Rx1;f8fce7mn26ZjDbqaE^8EUL*69?<5Hgo%a}PtmuZ+C@qB z6tDCHQn>s30T;r*>4zQy*R{V2RVq)>qQ4qIZc=|ttk_mR>aXs^8_DksP>(>DH)WvO zF;Mc6H2Z>MIBTDeE&eTH6^PW2=s944^pGjA4BOD1B_n!tM;=UrA;$| zWo8{L6rY9oiAER$Lp+ICsWA3jDBghhc!*dhAbu?3r#%xNhWO*S8#@y5!w^5k(C!HW znxv{iKmZU71VBFkOs<1~;>$w3#H~TC8MBV6BPPgu?Rt!~pfiG%4OpWaH7=vD9)CoNKiR%#=iJKcuABF>{dG-f~1e<&p(D9}QEZo={Jr zaR}`>TTiZ) z*Rha~R3{mBSJjx;k5s>tsSD0{4vPX6>^XHg{dW4l`i@2yMfhx+yOCVPn@3|L z!2QPN-nY5FW31sF$EZUTWSKoiJ<6k!EZ^LfyjDQc9t;0E@!VK-s60vR9;+TRw5q~X zFb=ESq-$8K#;L;t2f~vKc^KJK4_+oewyEw6f@{aAM!Bg32-@ssSoJw06uc3>9(WW; zy-5sC>Tt2Sbgf4XH+)@*3?``08MYwR7ZcQkmMgE-_|m;i`<+cvi<3r~IwwmZ9g=Yg zVi^F_mrFaLCuR{DKe#j$qmtETzEcrQt4ZB^5oyNwf31LSN>Q#-kr&s*WIf!e})GjXHZ73xIar>SiXpCF!1 zR2v$~LrtRfM77n>>SHy*b3^+jT4KQwLmgyTaE&zgeYlQZjze>^ByBY+_GGtu5e_JR z7W!ZP)4?CD%x$R2Zt)f$REr6l$yWhmkW7cBbuw+}`AClptk>Gqe{KdHNPEtXz3`M!Q-Wpjf#$;DifjiV>Ll?uQ zNDB4Q=n!fy{2_{u{?_CR@SCoALzpZEOj5gph<5)?gbaQt#N?<+qb5DD6Lai=Ja@JJ zKtjEUk5DRmxQ?*YN4tlNbi(5NG`fSN6C?X+)pla?eYM{n6XUCqB4>uuo1lvSXZ31{mO|#|^mK8PT zq0?1o*>LA7aLrKL8Tz3fHqO9qA`e*~n*rj!gy)AD>NJOiKmkp;`aVLPsXB_OGu2Us z*RR%?%VuJ+RWcfj+F9yoa>vX@5#YWu8!LBT@#So_OMPsOprZPjQ0J(_tv|-k#Pm68 zYuAay3uBVaLW+VpYJz7P0*W!0rqEUZ^L`p49?emkyA5h4dr45`Avx$V(QdBV+E6Z= z%&Bu#AK7z;EtQev8^nXegp2GK)QPN|w0cz{%PF4XkQ3gP^NFD4+jZEdH2;!m&5HW9&TIe<>5z508 zE@Ij(GQBS%7OR2Y$CLCR8sij|g{b7$#puNg?tc-iHeAmo zR(IYKHFg{x0KWEJjew?aG&U_o%KLFRcvK4QGUj;jg_*fcv`c_dkV^>8gI)$)K8T?K zic(aURCLqM+2e6d^cBQY`fJC9$5Qn@%JRrkT%s>-qJ`DqNC{=TDN0_!6(D(;nk|no zuUn?Jm7PMGYO%RZwU#1gxf&%bFR3Oyr~)TI6f|G|3u&hPEtT*Faxn=cfneG##^S3=ZYI*x)h6|E-60b9 z_e8}d)k_qot4_+rOX5_zI=W3d%0>1IbFnfhPB>qMI~>z4>74cfDrzV~M@=1<(o77^ zP!||RAW`}cE{(*^4AoCreMu;ps@9-7g=7{GhL$1Q?V0MwP!~h$7=-2%!-LQnE7Xv- zdT3U1GmT=%v{O9P11?)?1s&JL+47{gQskS4R7X~*Gp)Fc=q{;9LAW|*sqxlO8KEl> zO0d~kDk%vfU*sUnS?V$${V(N7N}Umfm7*-QnV7p$^|1oPJVB!0{KTsWS!&P|RAnpG zW!CH}i8HnlG4N$I-kQDyp*AA4#?2s&e2EyK%L8G&H4| zHZc;4hYw(=5jEWpY$DZ@OamE+vj8`5jhaa5kF25nLo;!Ejk<#V=e??KA=fn<8v%rO z%?5t_e~_)lG;j#8PFI8dWG_+Vyrj~9QhRYR1J z<|25V>Z1T@$8``HBu9v{b?O48%SF-UHO$brFN(>psqLMl7PuP$%eEr#HPtH}8v7&^ zsls%99nACj3Taa=ULNg@ylB^Kj3H>>$ML5q{!wid#zgrF+!i62n3NV+4z1}+DIRZj z_oaB4A)xq_%qQ`ODc({WMYWEbCKh)B$jo~JuumkcS3@FFBeamawFimAdjpLW3-D+^ zlcl2sqFD6m6*3tjfSLn=SDS7S@*U0eWPl$5}s*8LZu4cq^@jTPO>j5QVL=eTK0k7 z0ppJe>M+>MQaM-R#3=yrbS=SNPj(zth(8WO zJrI8k@pUR$1B|%5S#2dR5qGxWPFBM$s;`gUawVW37P~wu=J5{LGK+QsbJqAR>IS;A zxJ8YyR+Rh%&fG#EQVD4(j=ip?k{kAhI)L1HZ>W16YA;wBjYjog?5x8D(Pyi=M=|13 z!dCSm0o{L7Jx}fzZ$TOcSG=vh47wU^Q~zvbf~p>*LO3cN^6?+mx;}Q^ItRJUv0iY` zTS%@?;i2=Q$9AVQv#3BDEIKy z;KL9t>QvEE?Afjk>wqcGzc5dqef$dFsJ5E2?ti~_SU0S-XaqgJq=M!nGF|P1`6vJ{ zop#Pu1LgB#c&-{3kZ+?Q1NR0{?M1I+Dkwn{ymijJFISC~aZ~fJJhc#dWGI-7aYAjL zW@;t&w7VaO1mbJ6tI_@h&==m4rIg zQ%jN2qTPG;$P`=2sqSXHhs6)>?f0-_f$RIe`eO4de)@4~goN8<60B_Hp0x_vGo0}z zgKnYBv#?`>;0G7Pq4(7cO4fBJ)>62$cdG3gg_J`WYvX_Op5&!DfMf6yF+0^j@$F94 zpWyHAR0l^m1<1PP^H$*YD7*H^j>OF1^laIA6-KWOe(;aKm{q7wRxX?s7Yo&uW z=F|Vs!zeZ2Upb7Xo{R9qkQyQW0=Wpke^_m#lzkz5j;Kose&Z2r1rdJs2rZwRQH?5OJE8Oji0AoyyM{~F_#&%DkYG2t_TLn}VU|_7w2iXYqv@ueC z5$TAN5Z4~r+y@iWns9*$p=qw9GLrW6m~`;GGT@5A#H6<&06YXt0F^QA9|Js30N`TU zQap_1P`sS_Bz_XbKd6mrNAc(y6mMMdBz_#l->;2|r1(&4d`#(+_~8_PuQnj62LUv( z0+bk{9uv@CTq;&WZG5HPiI?Vx4X5&^xQzSUE~#%Da?){BwBN^ z#r=xZ8Hj6Qiz|^jXa-x{OsqpMBCeS&POgmBYQ|XWY3;q*VJ{%ACE_wuI%@Z9;in(E z)ea*mKlRC&k`6+gu@tM&E778-}pHlM1y>Vy)9nGD!Z)zwcz zLlJ5KY}QHIhO`srlMwC#>Nebf zV-qlXJquGkASD9t5C?JWUt?l-PAnHeS8$lrrA&0W0y$hnnOJf~4fQbsC-up?vgU?m zV&4_DP-#~x#$Sb){#>c~>Q(ijv+`Q0`0gflrZ1I>pr2`{S}I=q8HKMbHvj&!>LM%K zip>vyQ3F&Z{iyJ<0CLt*f*c^;w_w9JL;O+P0#@F$WAw00L zhfTF7^9tGYpBk~SRMMY*q74F3zu+iz6!2tHJi3N3c`|?bfEew`&bm}I(^69R1_~6wJ;|+J9BZ` z0|q3|hQHjvkevs~rW4{w!fC`;kNh|&0IWsXEebobg#pDMSb6Sb2n|xOn@)kmns)2| z`A~G}#InOpcnKThPr}d|c-lG<57|ZSiI>@R*Q;>AF7Znz7O0rqME%aJl~bIJTv0>{ z+=Du^#jPt9sTxrDI*wS`w!2ogo0M806GO?~sVC*Ui_&*yzmu6w z>-;XcYAY7l;H940OMr*jxVrFaSN3Whc-Ydj!zcID2K_61g!r{9YvheujBg-kzsyaC zel$o?lU+Qsr${2G8_QB++{^{t7z|GgC=|bRXCn*`3Ts5|BIYed^;*8q zKlNZ~N`;%~+mpS9-|u>|ql(LJvDL)JD}4&ZLlf(wR27O2F>Hf!beA|4!?q~#J4I?N zOH_h(io#fQjB`81)mRqbHOf`W@e6B+wac%tbCk5n=qgo<263#L(@4aOz$XU9F;o0_ z_^3xxQx#{$SvF&Cyr@Vnc~EtzL=zGod%Tn$XIW>9&xdg58sbfa>8m)_l~+^KX4;Mo z3u4_wa6Ai`P~A-{F7KwfAX)KIg9WGJ)lN7?X>)^(xH4P1(D&z9fP8@?+V4M2`oCj=qJny zB&E3yEcDorG%CqrM4!EeJGxZ{$HLEDB(EEo_(LGS{l8!<43bxEmUJ#0uny>)5U>J= z760E$ao89KDuFwb-fIvtq|k;0FBjK*oXCWtN@|Ks<_<;&^CWyUqBZF z`hghG7tmJk*1l{qbOhyoEZOliT2x|`btAE|AM5^9!1aEtmE&3~THpSxiM!SRxGuON z)I=7hqy0)O>~G8AD^c1XIUE?$3NW$ zvV)EdsMt1|yaq8p@m4<;{#59E3a#nKytxV3Q7U_n^cKectfBiep)KVnboPQVQHE#R z6Immj?p|WZV3seu^na%1_7Xlr9>?qdsq{~odB!I`l^Iz^5vC;O@BU20F6l{rCgC{r zF+Q|}NemgvMk@*Liw}pgNT<{9(RA+{A&NrXTMDmXtOYOH6zi^Gk6EN-;912CcQJ4n z3mH~qSLw>c4uE2&Owh%uMZ+?=V%87b&OHGEZ=% z1ZgaG7iGg(ctA0BqJ&V!lijoy_nts2kyl~$dqNq`!g)~vY(xA8Nzvq~vpZdvxac^X z{mF|$Y%|+6Vjd+A(RBn1SKDJ*rVDZpF=OE5b=C;>nv3Bwc61PC!d`~sNVdkBG6e!S zI!#HFp=30Yh5E}-cx#_A1dmba2Tx>9pdNU&cgw|hBiSm4;|1U!Dmr1wTRe(2cZPZ# ziI$hYD+))kBxh7XC@#uPe^)#l#X33{yK4~Doge+K=<*!v+sf#ty}APjv))pao4!5p zD$FxRYcC_ritC21nF8J8P2o5wJB>^bd$#<;c70AJJsBU8 zxtW&QVUo1+{D6G%%Q)5p2L79mXH%5x`C`L(77AN+2gkFH?92Qb0kOWGe+rbU9*qb6 zF`lB$1ZGs6^2Lw|jIO`0n80Q!r}M-g6WF_ssYnBwwk5Mz&jGfwSEAWgP#vJGcazy( zPn-qll|m8M(5_ijc`2;794q8hHluz2I`O*r9EGN%rE4X%g3RF#tQ!x(Z57gQPi0dB ztCy80Sjf%>X(P($q7hgbKf%9Oo(N52=RF}F)^jeQoKYbLq^v)Y?bf9$dItqMiYP$) zoSev_Jge=S7J3wrdTQl9p-y7c1BU|@1dBQE1UhxzALgKqK?x7Sl>hf8PqA?l>)*O9 zdSJ%iFs|EL((-~b&XdOE{=6FDf`QgRY8ph(Q=rYxCznQKhZhKSGK*+G#73VCGN|Nn z=uVA?WemApT#MKFB(I@$;!9C;Y3NQfCbK4Jh7FTh9|!7gqGB=_BI<9GS##x4zGyOq zHF3o#&bbP9BLv!TBd4&JmA(1m>J%2FoX8jdOku&4Ab2V|W-7Gnrm}I$@_bP^m5oqV z<_l#STQoe?Qy(%foa)*s{Z!jdiD+oN@)Z$XpM(|Og{SaO%FahHaOpp#iKMN-Q-$3S zE+LHe=i8b}?kU!uiczL-9p1xF=Yvv#m$ zNk_Ct3KYyefrURG!TZoU34w+2hKxgG+nczA1n~({DzzVrtJB$l_MdFGGRa4D*RSvp z+z>SL1t>nczz;EFH8nrgJ4xsYK+=R6AO&vv4Ce1#iiV@&E)(w4nHN!Np26OwQ9NNL zi&kAh8qF^>R53F0XR;>B;qBtoOtz7mb6Lw?<@;^sH%Q9y z3hq)IERZ#_M?jO$BQVvpRDM(@Yi5I@(WttK{bLRCAbRP>GHpWADm+Et3#?g->Wk)yUvcEKa2 zA$}P3{)O+t4#qop$LToo$D&{UF5Y)~4{x{7J+7Znz-!pA<(7+x1uQ_xeoG`SV9gz> z=a+hkc?;N_7J3n5Y(=a>5lMBEPO==Rh_Go@AH~TH!w&szp)O>tSdlKy4ROx+5}UW{ETT=Qav>$FT5US!P! z3ckm^O(4m|c0CuyvpS=CiTsWz@r$fI!7qK0y+*F<5*F#03~sc-Tf{8^V{P-#UIKm} z12=cE$X^0(-0J;(3G2xl5~J+>m{EQ~^k2dnI$A@;gr&4kK)R`7!&2hnb??=sNH+)U zf3Dx-bRDeetf6AyGNeOnZdxzm|Zqpjk@>J~$_HD;rz_Z}O68m4wJg@#6(TWf&z-VQT+3oH!Fo=4$cYrd3M&0|OCFTd{6n>3 z7Va>uWaA;6$Xm(Gu=Mxb%WOb;If3hII>1SxfQa=1I2CQ)uhvVHm@gm0#R1MC#0uwP zgPR688flono+2R&usfj4KIjE=BM|qy#5$3Wv36S_%BQ@b}L(-!S2s0 zHka#|WKc&}O4F|SizBO8<2L0c6elJ(04?oX_y9PGULzn#hz%%hM=O*E;l!q11k>~i z>ue~>2o-%^VPSHpnDq*40cYzgEXhbs(OQ30cgSj_AntAUC~^ZMj)T(Agiuzq^h6+a zz^&30fRK*Js?aEn?wy_V^347jDqKI`t3CLm!MX5b#8IV`vo*v}=`T*M z#=>6ZFK(=6jeL^;gj1QPfZ|Zbz%>AZ+tucdS;GR{D||Ht1NF+58Zi=?EEQta8rGM( z<%0LEW0B0_<-(A`qVH?PP@GkgzrpL`k2Nezsqh!RuY$vZ8}}-kt6Uc1KlHzNtGM##wjYE zbhBddp;wEvwbo45uSF4nbPu@*KWlSuuVrs2O@w%L9VVG$Z-`IVSu?+lf6P4*udy+3 zR=vhLQtD%`VV9DN>(8&TQ2O^=58ei~*mXU2BNb@oUeGT2PpyD}&{y6fX02zj@*86B zdbTx8uT-7;2TMicZO15B3j!?NwV`G6`7P#IIm}ybP-KUyLJsRShSy}MR5D7GiY^s~ z{Eld>ZQG|Y(g2u>HU-Alk$YELGg2!3m=$FX+`x7`ovMI(5iZ4_Ian*wkg9_%m7Rhz zH2Uog%c;OvSB579s~ zCfY{Z(I;cbImFXR0;x}e0eOsrw5HN3WDKk=%;@8Vo&8-bbHv8bVNV78nfpYLV2QYa zGfA*f{%F7BvonTl0KVL_Cd=kcSiitkY=m7F!N@+F%j;|@^|e=CXQ|}gdfnQyecxam zs4otDgAJiRxN;s;TY!ZQ0_SWL``*B4LnD0i25YB$xJ9^ZWi0}za0@X5?ynW80K@TF z4izkm&}?Nr2!8!mR!Z*BH<1l0JN-@eJGrypV&N`n8?Dr(Y!utxVi6u&HdtAH6Gl0) zrW-bh@7@Bx@ycd#5An_>z|%(PfykQzqevOunShALGEYjmGAfP6(DFQNCc*Z>4J5_t z8&Tn*9wJTtVjy;H2$}gt^VI?t;G_g-;^7BufYK*N^x1_OsZbNsccGz7fnxnGlshI+ z9N7hS1^<0_v(8GICRXi6JiPOVF+Lu5Aj`cHr3jlMk^T3Hbnr-5H^Ji1@P9g@u zT?5;WM4!5WC=GxE_p*jChydU0y{vQaXe2>hgLyaLU8GX|`gC2qC-<_JOgCI+F*xWO zgT_T>Wgl~t!xbc@Zt1nCR@|(It=}SjpN_3xqNRn5o7uAKtvnI4#<7t&dV@KNLHijG zby)Yby8NF=h%p>NV;HY`Mr1+Sv!9g&>jg_e-Ns_bhsB|8BQu6PzuUUjZ`&tQ53p$d z6i^&m>AeH2mD2Pzaq$3FkeAnse-2={tXOLfILNXbs2R5(V&RJKTJh;2*1|hBP>YYw z7*cN+OQ|WlYK_>0$YK_QhuF~k z#Iz7gRR!cri&^8a$DuTzl_3jKiW^a=XF)H#c#L{gloqq+o+Kw7hqAap(V~R;hi0## z`q^t^nUtM$Py8N^|7dGQMu1CU;kSexY_DgN2K2P6s00zIs3!+Z!}krI5r6HpPQ?#^ zjHphWhr^dbwO`D!Vz4xUty&bD2|3x7DJ@NgUjL{)+hLB#U)gjG|I65N%)OA!6!h`luC4Kf`WF3N)Ym zj41}1H@^4+^9tNsUtqpK?FF93{DA+Sr`ZbEydbSHy6NEea36pN!i3Sy)6Cxqp~qW- zkrkC+vS88dOXj914MoQ<(G%yc663#QO#;%;Q14=QnW1=RzlWV>B~G&F{9xP~vF%F; z8}eY>;Y+rP+_Wr*dTyulOg|lod%pJ5XXA?UN{|*;M_n8iDm%L{5s;wQCJl_m2y$9r}2LtRpMf+5=yuN%8GHQP}gtR zs3<)%3Z>p{K#Rp=)Y5Kh#|{h~q;#&6Qs3L<1)0S+Yy?!(U~J@DwnWJf5;HEb#L(Oz zZHEa8EJ#RaAn2SqR1%}D6$+>oF0tWIn{ECbOQz)6-(lld5G3w?hrR?fzL#-O40pn1 z)?HpF-oDJ5(eKI2P;LNt-|xXQ!0mbk$q-&}h4r9ZS7Jaq7g)*lwB?#fHH3*M4RD65 zkfI~qysPL*$nMcqbY=Vp{=g>5_eJIpEQ8P)Dp)H|40xStN)OS(kT68VRj>unD?U`g zVhz=3{C_Ig=Je{cw-PNYH%MNk^>CvT{w`Z2uVVNm_^-Snd6mF#gn!2Cl2;l0X`dxo z7Te+BZ*7N%|C}8j{t0&Y#tD|0c6j(h0k7j(9dDVup@l7D{4_*FCAdI6bNoBKROcTF z9YptQtQIP%-K#LcHx?;y0(9vO&lvLgcB@SOH)vB(AIb!E)S3mz!ElQm zl$khmixuGMoN>Q`n=KRCuOKO19Qu_7EdUWB)q-nP@%NVjFYWXS;h z`Q_rf-`P*fw=ap(+t`SLPFBsD2QL8(mu%B!wWYC(A>7y*yD1z@|nmhE8=y4avpgJmwrCKon)x5hb*+~!0 z0_^3xY|s-JDs2@)yZ*^=xr@q0DT#;zgs%S+;^KA7#P5HCHPK^BY#H;S+RVqs56s{MpM207PKd(wnr;!jRE#Hz$8)m zqH7}^P88o~#!#S$N9(PjIAll`ntxTKa>|(Mgqpzc00;g{mWeJ8Ad#SYd;nD*xECH^ zYTP3_Ti8VU-ELtq?l<1Wo*Cx2ek6AUUbPf=EbNhov$exQ0`6TH3RcIGBK~=Z)654i zk$PRA=>G^K^jnenhy@3HkIGp+-gL-W_H$h`UOGhETuO5)MI5bVzT(^?)$PhJdcHmQ#mzRov9C#1!1xs-s`Mh+pSH5{s_&D;{B3&lfn%N7cs1_)ocNc3sI6O~Sj#fAoaiAMs`*WDS% zEHVeV@km*zSuBRAyo0iDk$6?*DRwT&nTsYI8#K%=Y3gEwtnO``Nosf~4&h5}HKivu>| ztVpx-@1-a7%~uJ)w|MdpW%WW4>d9NDA6P&Z3Xbh0nF`_mcs^J&94gs2dEJ1>uHLxr znYidWaS_kNwXPFaw%}=;O%XSFzMil334leYkU}`%ru6{(lR_-<6jNshLlg0XH~&)UJYRh1!@Kxg0H^yGv|j$iDcdngx@BxA4V{b&RZ7gqxKVkIwJ zj0{9S&S)%-1oCi~HZMw>a&hj}VWIdXkcTOfvw)~{mQo20yCM2L+#3yftMJp=xc7h) zkO!#Nj2CRDB2d!I!;v9XQ8X0!%0%ZzJXndGCq_5oaWV{4H{xyR5$&^$^kOMNe4b-T zxOTQOQY;PP*hjgD?Qk6{!Zqg-CQb(NCW_=PZU^xmxPzbtI7ov7v4cJs)5hF2m>-gr zyYt1p5WY424^%<`)`U5zl)?C(D-GAi6tvWe%+euPVHvXbf^_K61j%w_ie$l7#~1CB z6N+yc;>P2Xi^H{1A)eaDHu$4}&jb8NfbRzQ}%1EuBuV zSaoOTgmIH+6=0HaG@61{u@qe*Eu)Dj3*+4zfggArL0zE?*3VV~i1sPV#GP>NE20|n zK^=dr0~bnXtbn`jX@wi3)rv1rq8oK!2v-#{IntO9cfD?l$U;D1IG^^IoXk4ph;ZKB z(@qXW*vJt#!uj0C`BQ{F|Hcii`TvyjbpH0ll>hoB&*Xo*2_NQAL|2-VnsOsp?rBZ= zYS;M*mI0746L+|!Glm{-#@!Vp4{L@l1UIP}->jUNBd#{%UFkotIbWsZHWdZUd4~|3 zcGL3)G;5Tg!_Z+~9BD}7&V0c@$r3Cq&C%;)W{aQ*KC;_2sCi=;6GKDi-Zks27f#$@ zdIYxxv~6OBs)`}h@owG2dA(I?Pphv1fjLzjTPK;Hn-t3 z9jbqqBg{?PaxbMx`N_SF+-D(q>805ZiZO|`LGqgzdZ)?7v3Dl!cGnXrkvzz?x|I4T zZfO=uV!XezPyNpU(+m%ez8A@H&xc}-$l^jI-{Db>!KT+tNm@HtYEZNzVoiG<;ZaSc zq8c+6x6@!DN82S%wC7zKTf<;hJRewkOV&FxZqWBDv%#lSv=CuYJicx9r*_OCEwy}L z$a0Xh<(Qmk>0S4C?XdRud^?`B!Bpnr%4!sE8&%!Y*-$m2yUHMaA;B_%BGuPz?3_ai!f(9RR@)@PJMm3Q1}=tm;;$;9Frn5N z%T@E4VtHp?5SSUMIl!D9-2-}%U8_rP9?ifq4($VBioviS)CJA4U##lFn?`_q^n>ye zQ+qAmNpdH}@Id?{@%c_bU@nlgpVvs6mWIK8TNhfzB1O-xJfLk!6p9-VQHJ!#5&t~y zL;Qw&5va2Auk|W{K9C%(!_Y-O^xCexu}f^U_6T>=d=1XR+?6-SbIg@pc|$kcK%@Ha z`_Dh3$A00`jdzVjXNbpdGPL57>q!SFpU;4scn4Xw<{j^9rME7v%R!4X;JO-Nf36!( zbwawl-1b_ExYLb$c_%-i`Z++ZMMZC!E&{sqK5{!TsXJKgYv#?}`ApfRDpI?c8m%2v zoME^SGw6BIswd9~O^&v*pcpQDRzJB1sn|%1!Sr&rC$IJ_I#6YQK+LLmmav*sLC#Q-L@f=Dr6t9zn zSsO4L;yFFXb|#)LRI;av#01{lRo5f_la}UvVo8FI<7xtLtvol?tR`}2IjWqNR+*M8 z+RQG49-l@5d|GzxCl`dzdCZmqOxTE=%zPwTn zXg#IIm--h7syP-lF|r{<0DGHWpF73mrML~jBG9(&QHlt0{${DAIU$Im6y^) z>*x3Y-{uo*1S&j-8YL5z9SSi=8t(UPd=7grxObo9ot5qY9?kps{*v|tm~MF6f!B}b zBLHl^F`Dm_>6YM|WBDquo1x>d@P9f<6pq7^*c40!Ap|ds-CYuvh5QE}VNRJl1nPP2&U`d{f2~pS5qdm_WtY`TyQaQR!(NHj; znGNW^i)Y~qDMUMjBZRv9Q(M2ukxgCFwUAM1i&G?thrAz>4MSWPF%Rd2BzM#3M7@2*@kJes5rNgZn6!_WKo6GNH^JrX{t!d zY^a-T!@^z^QW>b5Y&)f-BZHVg{Q;0K5RqIGpph{Fa0o>i#sKXr_`ifdH^pB&2S4W0 zqT&)i?F{^9;jbuZpb-OF4!?BGSNjZpEDJ>;slM6?_|L;{y5^&m!hZq&WY~%$lNeXw zFV6DTK2FDvK7>NNwL|cu^hF`XUfO@)*GpgFsqKd!-Kr=VJbe-Tdg(Jo|tTt_c-&%S%Z9V*Y=~LV^ny>ZJr#8^mz^|8HX`rowUoZU%S1k*Ez4WQh8r?6} zOCRT?!7y*Swe%JBwIztqOP^d{TLiyedc2`GAAW1;9ksde>!nYwr_F+2FTGSxn*qOG z`eFxdD*SrsLmae8@LNl7&`60vFMWxkO@N#p^Hzt|B!QbsrP(20D90!0<#Ghvs2M0sh+A)@{iKF3K9&B9;$6i$jhHkeeB z(N`P;dCzQGffq)&O3v_m4IkmZC0*wI2W%YPByrK~WDlZ$vLT=T6(9J;+-$D1!M z#ZsbV8AbL>{ERG#(aU+)R#`YHfQsSwOLXC;#}OFE-UNj(GckR!p;|N;l1CtSD>$2e zV?^n4z8%F%P3MJ<-U-*NEb6Y?*ulV}KqiW4G8oENNilE((Et>;$F|T?$|_|2D2Mm%x@fp{ z<&vPQN*W^yE<`wvd|J#$(`bP$aSW{>)M+w|B3wxJ)Ey*$qSV^S@0*!J9 zkUkNlzuLiMDSTLa@MXZfdlRQ^AT>MEWSN059amcyZ7N94X>GE!MHo>N`9d@81r#Bx zhsokvWvM+Fgz|oUK^8MM@t|~+DcMHQG{jNe^xf;H%>Y5P3{X9-LtQ*?Ls|}POB|t= zpGDowwjs?z7_lB5%Vlj5>Ssl)$+8b=*MP_f)Nuj)vY%vuNWDBXr-7z4rf1V9TqGt) zIBn+fURi)lk&-O;uG9*8M*}ZNRg2`!yq6L*++4Vsml~8-!^EsNcu)Cz@!=ahFs^NV z?OP~Y(hKa#FcSjd>jC#+P>giJKgLxC{@v(bl`QGF)1QnspfD#2^FdeuOve_PFayl# z=I$VxZRHI-9u0lEW8NPs61VaJKH2DW#G~ye#ZCon2|QPaio&g6ha!dvmpA!nWzSGC z`Au-uTZW2LZ}I?-vqP*MKLlx{`WffH7$WYy3Eu9-p`yoIV4r6L{w+*N9mS=$_$Cx; z*4z9a<)z_b);8WkXBkI2~M>}77doi|qMJEF2n05m3#`!l){ zOjm&Ab1qtFyZYv=JnS+&tLyURw6_6ot`zX5m=YrjFbOyh76S^f`zRN43i#ND5)eqq zxMmKsugM(lz4(A z@H@Ihcu3chApyxIN;+r<4;fz}(>-X|@WL4VaxkRYxa6IRb&JAG6<*qB2rGtxA28%O0xY4QFaoLg!O^dsW`#bnp|MFyy z1iige=%jl!bjdHFub^CHF4)h!@*Q5!QK<|wXMcbRRjCLQ+jsG=eWnc3_g%Lt>u(RZ zgu>H4`pjVQ>TVt+zhvIIn|~|&RD@~qVbFn?RV(taV3^Q4#@xn2?BSn#f_{Ak$-`bG z7Bg8I5YH>(7G>HX^Q^u6iaew|tzUx0XT0Q<3KgqZ_)n)uUdixF@Xwwkd4b+?Bm94- zNnUC2r;SRqxY*(0F9tkKZ}v31#M}G%1i6>^dq1|A4MeL0yp7rx`H&KR%lf?7` z{10qG#~tKDdX%SNo05tFa~)kG4V_s!9j`ybP1_Z(cO)-jh6y>InJr9pf++$Az|jDzovUp4HXWG3Sy#tG?`d(S2Y z0i&M<1j1i+xPK>L`?ELz-}_k{AmGQ|L}*?%_`l$Rf8n$6z+aO7UlcvbVEVHOkio%!gXg$9ggf%fo`vs~V7d0c;Ah5L z!2Wop*Xiv=QiBA`#s8H686^Ho2HO9EM+RMw!onW~yDnI5E(~<9$UjI@7wtQFpS4!aiU+~Cx3E;7E6{UG4SXPYDSGuBD z_&ZI|SGpnz{>!QQN>^lr-)q{FB~6bELKTUOc@6N~=qEUmTq}%6v4vYH`XA*rvu}>_E>4)HX<;fc`yb=?6}J-!Q2z+EDmeI>84UR)qBG3Hxah@or7o~lcV43rrjcoXvjI)sq|L4gzvf&?z;@B4A zA_@Nu;%&tSNy+x~@cY=)!+*%09{wbx*Q*JAa+n?7p+$nl#hw5WyX^_!?^-uQ{8x*0 zpYo1vh;hsFg)9*7!zG*p^9JTN51Y+oY$UR<;Y`M6uF|IFn3mhbeD_nX$c`cPwUDU# zV#0c8#PiQMSBjHF=x01OeRi)JU%8W&J(oI}bT%Di=A_L@u$&sDS4&PT{262QYRQq{ z53^F4V}yS%coiK!KHhTF4iEo)z}u=zPm>%+qZKCCVfmgEC`k5}lT;(BK!lPJA)0>9 z`!{dV>uH9(DTuRQn;;GpOGS>cI?*yuy!|wP{eTv7+o5bi- zyrci71k1bSFgu660rBq@$cwn*t4X5p6!>wkBys)}AE}sHh!$UP|6nuXC9p1b9b3w7 zrCpQ^ptLV|lZME;zP*g_e}dkQ6)Z=BKUuu<1^)upQ|6xLQObE2@!n~^K*>xLL0|HP zL4my?;e_S&50;xY&a5Y$TdFk322by`w7zuCtGC$qCFJ+cy~WipxsPJ#E$)4ZN*U2x zbUDMfD7?2ge}*4(nj8JnhdRs3+4`zx;|iic-;k6_v% z$g-=}^=z$JW8Z1x?3s4jVKFVl$Z{SXZ>M}#jI9MRF_w<7wK)8XN83sVe;`^}uYCA- zqGkVHdUz+bx+pK_-tt88Q#m;1Zlc~f-lmNUGS7wjbPTp9kIvxA4^)4t1)%aJvTekq zfS48NsA(W3?HnJjjOZl}pTqI}!vxXgJWq7ii9=?0#G3Q`q|bqb8sGg1Pj`+z31adE z9^`x@-n#Ru5bcU!{XOpj?}Mw1K%QdLElW$rvEc>YzpdU+Gm* zU?l3LgrC}0 zZ_>eV|29-!&8^S9tq$*En=69PH4}%6=ME-oMp5f9)50zhkw5v9{w1>Kd!9Raf;=hdBIg2rUX@| zHBPkrFvQk8@NdR2)vFZ#P9mX#CpuOe;s1}&DzG`6FYZ+Eju@8BEBPWQS?5*a&&zzN z67mOEUH^?4E>cCpC*qFrlqm1sZ#kH&fp0DOTO&VCdXo=WdY_g~Hq`Aslzp+79CI4Pp_I_$l^VVNE-ebj!s<*kX@~FG$a2v{u zce{%bx3MC<)Ke_K4gROxy!SSDmF3golWHC)uM(H4(R_=A`yHOG7<-6qcX(?klz({# z>SPbQi!Og)t@ydSSpElaf7acs+~r+loOyQtlm8%h7mfbn1LYL){9imaqCD+*g5{#>TeVt2VST#*U9cVTY!g zE;T``K&upY?m?JV(oF>2=ba1^?&|L9>h9|5 z>gwupX}Ifo%vErT+LHdmUE6Nc=v_Mu;c4SFde=$_cYq^cBGpAbb`u)3rkJXN9-WH}YI-ycrN4;LU*W&t4=DUf_lAKHRm^ z3y*NR7ark5)C%^MPz*V<6hDle+NA0nb!|hAIvf8((5IhR2GEr2UB(*n2GOh6!HqJ> zw;k5ZohYrnON`$FfGx}&K;zoGq#1$-(If3$hRD9Ox4lbGLvepP*WRVf5H*DExzVK? z|9|WT2>TlCz0oB*)m!U_)9kLKh5_nYX`sp;OXi{0o%l8QLG6p;V;lo0;bxaK@xnkz zT|V%Cg1+b3xN#uea}#C=2M5#BH^Jx2>DbLKLk-Ts6y4FK+t{N1YH3echfT#CMimD; z@GaqMV3E#yHsfFc7dBo)96QnB_`49dA7MVZ&dtbo?SQK;rae32vHnC)cXSzI$Qejq zb#$o&4GP^|Qim1ySJ$LNB0vpe0m(Sk>@0B2M$WG^9AW8_2^AauzYdYR}k)f%$|HdgwdZ0B&^`Qdm!CyIynyEUEo1`xR) z{;%+4s{n4RAy%H8*KJ4=h=p)5^yYt zx$e^89`PW-Fx+EJsAwzBMK2V7CaM*{+te9*A zG4XCGIG|tW$E=Qk7ySjpoh)!ro)0B3O0rt|t87Av&8>2AinO5-9F~XHW1n`=W{r2j z1vreLwtU$^4R}cjyXkD6y=xo;Ri@f9Hf(AbsM(&K@P|Pszxi^UTn43kvVEXtxWJPe zj)k?9#+HGqW-sqq*S@6TMkO($+3FaomcW>4IBdU8!}jZHj08oq{CXWwFk_KnKR6i> zrRss=vP6q|6~<;S8kHXMCHlyybTu`z#nYcC%G5Aaoj@0jN(}WjDdvD?0>6F_rO<6A zC90=EQojYpV7qD%woncf=e_sB=AZ!>s4PYCW-pagld|8Zc{1#1X#8g1(2&s+Fp&*7 zJw%K-i5~D#qQf4`(Klx;;Q4Gj2Hsz9q1Szs5kZ)uSVAzl58_76EBivCDAZR;@U6Ah z=DBX89ACvYviVhH<91g7%Qff%wtKS{Nh-fbbMp>q!^slI;To85<#nmP#4-wW*oEJH z?DljGd}5(%-oP@`Yhy@Q7`B{MAEBugaDjaSd)h51_zWHORR;8IhR^M)7x3eE(0D8` zasLJk`*LN&HKxeaCP~dXDbYYby zet|Wvs>A`!EmTer@v4R)+y%=K7&$BshP&ROy8@Nu9z`aMSA#PV?i_ibT>;Te18}MY zc8`-LEd3yCwMotEPp<|lS#kpX9H?{yMn0XCWO*amIw=zk)kZ4sq=d_d=($cx0slST zNx7ZBy@HhZ?x^fz2um75=rZ&A)g+0+rNq~rb5v=C*eJe3xOC>e~wmJlUT zuA+}al#*%JhPx8Hl_Pu92(P?dlOn3D2>W`GeJS5%_QE6lnHL`6g{8W5*<0ka(+^`k7>)J3V$SEdp)tw2$_cD3ZFk7Ai=z+^aC1dA^$H52b} z6LWIrP0Va70sE|?oGsUSzyw7+6opz3Anb-FREvMUz?J8XN7#jUjW`Iu1cHE>R#_3Y zp|Lvr2v_zkcMz~VE1tI*Sw;+Tc@xmh< z1b99vU_=-(>xMj+B#m%AOB2k>7`cXCHY-{2ZELH8)y*Sk_Ah}++04fi*V|!ICP4(Y z;&+xVnw1Fb1Oh^pzNWU)=3p8cs@M^dLZ~uSxe{v2{Ko^TU<;G@IQ_{mrB|0WUWS;O zeD%4cTF@6^iY@xyEcHP+L32Fe<7&WbO8=#}pw8h+oZ)5$rH3migPTp*mi>x_&T0=* ztG7t10cMLv%(*qqS?V^phkk_z0k%LA)+1eY_PKU}N<*M3TzOvZLOmjste(0c0~`!G z9@?FWS0`!PHXGaY{1b=u5z5B!hJKzCb+Bq?8OV6JE{n1vm0kw4V@{-!)wLRLdP7e# z73KVeGFZU~n}as5f^j0BR`<@Prby*3c}rbflyXjHGR7!#xrk*k%3%3!dMidL<-ZZJ z%GC5~v-%^p8@#o7$tbB0Lckw|>C8?!d61`WkT$%DbZt_!_N7;1QN(QeIabLJw??Q~ zrK++pr1>&PPEx2E3G3wSIDo)9Jx=LvvWKdfR1>F+9O*D?i{&ZsDGS!5mw^4kXnW2g zXmVzHE<2R?+H-0e%__E=IkQ6SIkSa5XHK|1=MSS)zc}8Wa{;#q6zUVNWJFhos`o;@ z1{yY3WA*oVfw5J#gi?9DatA++{aw70VhHO;9q~$EgMUBjo1i>lsOdu=;w$#|)h!gN=nwnSREv^scr=5auqd-bo=3Xn62IMUc3#Y=>#!(iWm}sxDBtxohP{=wLkP!$ zWm^!I{*&i=+#8Q@I4MaA9y$YW)LsXRObSz9DhZ=$Ny>1%a#WL~j0=AQy|*bR zu}%X9*=zmCH(BWeZy6ZBH6HV_lht8VkgN>y*J3O2Z+)_o|GzNCny|X#$;x>7?zVQg z5aj(UFPQAUV-4<}@B$i!c?He|sl z5~cR=6llkFw;@Km>ybcd_bN|;NhOhL4Mf5dXlF9!$oCi#kj}KcHTEbqx(|)+ro>HY zZY+vYS7UhcYV!s91$XLf_8=((!ZCoOovn^2bu-craG!ONG9XZE@p6qG{~_XC$RkBa znf3@t-BT&6x&7$FZc4o2g}(GlH}rdBUkd4tC2?jXP3f+r#~10i?FVkBfLjG{`x*p+ zAYW?)%$Dv-a^I>l$Rvyt0`|-WnYvq{A!WZO-!yd)gjy}V$A2^>Ti8j6dpBEh4S}580tHB8HVoA?4|(BE zYI)x`x*Yuq9teery7M_`%}@*W5ju*+k!mZNwi>@=>?8V(a}zqI3T(tx3TD6~lXr>S z4c;#DcE_E7W&2>3&7q%qd`G$HmXgj5z2jbpJn0anaK8qxCVY-z(r=x_M{9$ehm02sbO{dOa6 zYoJUVci3b{w900l40D-YPge#7wP?NwHRDfce9{$5xjkC_{x)d?oA4xof+a;b105=b zCL%lx;qQiNe5qMN_yH{0;8)F7g#B@Hslg`~xWc^f2!G*)M|iOp9^o4}^5YE|fvFgmH6RzPwEN4-$w4nl|hZt0Ax5t49X6H1-v6n!7m2A>hNifT1 zX={ONlD86sp;Yaq^bM-z5g1t#uU_3BPYJ!1Oz~Yhzx*8Gv}mGZnDaaLNV z9|hYC&3_53$hV>!M%<2F5XgZQK})Z!jw8Q5O4oF-tN$x^l>n9v!@cu?%hEQl$TO{v z(!D1-0y_~;M_DCFTe-49a0fb5g25ZtvKl8Y6^;aYvyWoot7B$o4eY*$VelPo=%7bI zjjm9=@lfHk)`kSSjIs-wOKuEz&BU>Q)>#NgdWnzl2k0QJvk)Go5&uoi+KjIn=YV$1 z)S0Z?G7P0aNma#qglX6s@K$#!M6;{l77yYw zC5vXOk;cP{RR}NUC}ZU$I-8?p_=5p)bSR|^Q2NFAp`;3MLXIl`kDLCHt8UoNI33dSdU>AraOe#88{(DcuX4RFSM1q8}gSru+HOn|IrQU#^A2oWCIK_LcguzmQ_Q z4ZzJghB&tSm3$qC!x3ip2o7|N1u#W{QavjoaX3?6)nExxhrX?2S@evL>xXOZJ(xYW zFg2p`QfL6Vx%+?s7d{dC(zj3mw1FBKyolxjHXlpvb)(s~8?f5}!<<#dc7r)9+pSW4|^GF7uifDc}iJ#Eb3LfDXCs2;qjUzbtdFQ?M)*`h-ya<;l}B?7MOFw(H(4k zL-V1AI7WT)F>K$YS^3Hi(-iKl(BaA(@_A|;uGGl^v}%O1$*-0b5HPimFHnZbU)L2E zD9t{GmLAk^tTH4DLL+M%axwgHomQQRxw^Rk#@XHIiLuHvFtLrk9r}dU9<=0kW!ThK zytj+KK03lpf1+Wxd-k)%U=RkdnI@#?Lk>BJbeM2QjQ>YEce(Kd@}v7d;`~?++2B5= zD_>vwfZX=LFtUt;8Y~H37vAn5Y|b>azy@l0nzKQKwSnJSjk0aUE!^vnZx7I{aY}aJ zyZNld4s*WJm0lgE6io9U;kuBeG2W_S2yY#ramp$Q;Q}yZ@Ubc@!bb;bt7KJ43k(pv z@CZNeg-3Xx7arly08d>;bcvfKCn9#rsg8lMkr+;c#qYIT091`4g3WL2Zqms*p~d zCn+1?B!}7de{<10laz%)Z8FMWlo&2`vXVO@Ed`Sl9LA0bXX7vyNDg;H_@BHZDdm6p zOalH(yaU0{kwR}zR=S1+cEi>hHX}SP>$=ft#2IdOrI0(6U9e=P5AVSK?cHP=Jw^H2 zkZ7%oxl_4K_OA+%yTxZCdC6T$R&sS`^$cF1;I}kZUiHgnNpBmLX`VmSU{<#y?K!F# z9TXXb(X+WyQnx&dS!ExjZrviO+uo7Xj+DCVcPW<*hQ@Anf8MQpXfQN&qc>+LdkxF2 zb&HFXdt}38D}7b0qz!1+NOX%JX`06%cP{gRFsC8$2HmGIp-`vWdV`i}VZ0@bus#lG zTv!`?5ZQ7Yi|L$#8$)MH&=@P6{#VxYB8{uMjU18p&*#q&~*CNvwGqF0w(%G3x zUwtFkh=HVcOd6$@D0l0zGA5-bwvI}`8HzNdt(ceW;=x#f8`QWqH~~oWlJ!qX4dd#+ zuqZqUuq^J6&>CoVG6yaA2h0hScM|O|&r&9v($Pw?zvBlhw^>R-ITlsC$A;#tM0}B- zlmR7u702ZkbyAlhuEAF~jpw*xOOU!4aTdg_@vL$cP~6T#oCC_v;o9yF!j?TI}r$5jO{<;__OhxdwGAN5Uq5qz6#0NLME#t{S2xw^T#0CPp2PI0^mw#i@bDX_RAKpla&2Ds6=%>!3aldk4kY1eF}kKUzC6>0R_?Eg8DqJ%lh z;y{R_B}F;vHb)N89Hr5;)B;jD7Av82?_6bDmIK2G8;wDBeHaZzY5?TEYRq;k4$3;V z>pjJO`12vx@DQv7)yK?Jx-R6r@YR}vyl3^^(b9`~B}NaTchqE@fyE)6C1ud!R=Un+ z(m+t$eMdTPEI{a6>HCp?3-X`p?kEgK`XQR|aZngtnup!!@B|8(ucR6zyo@|wx!-`6 zzcU}|)fJcm(v93B!3lI>zS6hr-JqERGy|<|QAjhx2@R%-?T%aVVK#FjjaZ<(5`n>X zpr5|7J~os|5#f9yfyY#-Z&Wn?ti~Von}%Nvk7l$HBb0hAR0c2t3l=K49hOGVEL3`g z^ISCJ3P%k#Bg|WPbFv(hc%jnA)NJk2pNxx?4W?$v(jOP_6xb3p)3=Kin>?4~B}#v# zInVVF?!_9=4Vqe`jYcm~-iE=%%_Yh>gO8PNzZb3k%|ajFtIX@{dGA3N({UqZNSP8I zQ67)+3>Rx~CEm6tiJkSJ+u8zYK^dm;6K{U zu9u-TgDn)lREfdTJ7B3YKe1n&wm#mvi^2y^ygT5HEu0eBO5diBmnwWw-LOotB`O|p zJ}C0;nfH|kIyd^M z(Ei-YPmv!e^8%5%Co%_C45IZPK*0py9UmyG6A{mqbV6E>Mse{SWT(Wa#Zz2->(D&Z;4yvIh(MBsalR-Sy1kK9jkk)zLoy!NBg_ciw(-t z;rp}IPo~XzFDF3~PsT}NG=8}a5p_cw6_XrXi;YCHf2chNTDRJ|@%xphWZ%kIHNP^5 zPBtlBqbqx=Z%-e8WFvm};dcbTNAH~dUSQ>*x}*cjJOkPHEB;*qOj-d|ekcfdRn=|% zSXnFkHg!Wm{?zMJ6x5Wh79#T={5IgX48Ow01;a;Ru6xS@WiR`6@>WT5Ke(H)<`<~x$-F_*G*q2CHNS= zROa9_|4Zf3=ncM_de6xZw(CPS#`&!wbo~X5PmVteBuCAH6?=k%4;2vWtiP1 z0*x)XacU_{0erja{1HZ0hm|SiA{i@0Pe~*+7|I%NxF-$5{{~^N=i7=r=x!CkQXDij z`B>9iQ=p^#zv-xg(@ij8IEHk#M!;eJt^5YWH|52tr|><5biQ2wmoco|$xDZ(sq^5< zfG2_L0qm4M0bnE27yh4uDmmSPT@=#mkq)igt%`VQYT~xSB%%)Kyt`WVk901-WEhk{ ziMXMglAs%s%=!la7qA5_*$T6T*GN5rkrPa=Bg#OZ@zpSsqMUD(1URF=3m?-6j0(DU zz7iUxDKgN6O60U+bvc14c_0A0NP6oiyx#xk8|6;J#~;%5BTCQC24@Y9zS$xn5G8(0 z698f9jG*^vVqQ0zaa^H!2m$vp-KxghC9R$+nB;3P`VzRBp@vB&x^z^@GWhzC?OVkf zu2Cfyu$ojS#jB-2=`t06t4uSrn&`uCl{g(n_R52R$%kn6HC_Bxi3$7*b4uIqzFqfw zWKb^|%R_W@kj;Fb33tu0JX)~1tbwh4tq~7_LxLau0%e#njQs%%QZvo_LFpOmqaUb19NS&wi<_{Z1~>aJGTnt6Pn2SqtZPRF}x|MOLAikFrR~;xk=2^omBiIwy~#a;+6aV8!tM1?Usjc3vQ)r}3=W{`hZR9L)}q7(8b<2!SPvf> z(xQwWJYqwK)|nFS6Z0~J`@#{B#SU*r1w0Pmn|2RWW>q}fco(G&V))0%#~_|cAGIiB z3{T1=S|P3AZ2tCEh*4Pvn%}A_}9TJD~{L)~aOtoPG&5F4WqpnB&eN z$eI)$W!xILqF|(;je=8DQcfrlw+d_Y4lfjT0P_Jn?1Zw+@*0|vAek3zFi4#+r^Ymb z&+us;i<>{8DO5GBbEp;i`oe2yASRWDS*~YnZ9!osaHG#C;H1(G2k9L&R>KUhrHnd> zk+J@Nktjw!o<=3ecM1r-%1A`iy>U{RB!_Ubq42jAIg->D3*zOI%7|wlHZhKGgK4U z5%6naW*ckmP9Ew<-~FcK8lI3S`i#=oxYylIVUpHU(WMM-q^j1n&!DEzFFSPprlZDp4}>e~C_CvJOCs%IY}+sp0sP@c2**T8i6nzH88@0em$!U3I@fP_#7iyDE)UO zB9f!9kL9SVV4zuAS>d)rH2rtQVrWdF^52!PS*MZ2AaC`vyT)Ty;fd7?WmD8R9vIg!8JxYf1?TKl*sWY(*%~n zW$r===Wzn&<8G&W{!iUa+@Vm*G2B+bon$!7=hH?X=RSmYs2vdv_;s$UKc~25V+vwehqHw&b32g+dZlAuO42&x3s#d2;U`>1gYIYj=?dp3Y z)F&l6ftr-!$HAFE-5NM^b?k!E^17%$Axrojd`uGyXxwJsuz?cvA5xbH_4uQ(%G>3G zYs=t)FoV!kQRs>aj}{}ZCPmGU;ny5|Z1=?fw*YExQ%uGeZ?@BSZHi^E)_vYQNyuY@ zo5ia}Ut0n497P*W1mGCxjo~gx>u`!8Rn2(A$7QXJQ2icrN8nuqxKSH{}2Wz?+9C0(&>xJM?%Ai zO&v?@ebqH+&rh`Xl2XZ>|FV)E2V=f4XQQQ`y1uT1Dm3{^+uS&J;y*RK+bqXc}$iQsPzgYyj2wNx3VHQ_?eCf z31=B>#Il2)`dgV9*>=(x-*Oj!C7y$Fi#NE#75}tvwXNhToleaY%=x51w9c_7^tnK(bS2wC% zdDZ=ot>KRM6y09jTo{>clJoi&Ci#zz;4?LV{&!z~27>;A(=>`##VqDij z?=OL~cav0m-5^0!Hrwj<;cWMv5v~gCBi#o1Tq7Mi>6<`pHgh0-Y!Cw5@nZ(j*HfUJ zMP{R@3e<{k#6jya+G!Mpp483RqPIxj?3cz{O zB9n;L%do;^aR6*9MWN8jWFz}MK=D5-(ARXuB%Xydw9ZGwhc~~DC~lPukk1VP>zzv^ z*Ppc4M!8WyI$=EPqo8Q?H0Lf{5vO&s#lM--=V``0reHL6Oj*Al(HVTSj%U2 zCLmuPNL*Y!Kz)y1@D*J{G}Nq3S^PRn;SM_JD~9>kY82iaL=k=>rJ&?-jBAVnj=UTx z?M_5{bJ5my>-Eh>&4YNm>=cV%q0Z9BI%otc8Rjw6o`lM{;0ib=tMn7qfm+eI@&I)r zrTGhsp|v}W^B04yk02vs%)oa)(LpQ0NWt+m@ETOsk9PWt2qno==Rs`w8GI}q^%r)N z9H2&0RDek4@`eV8#U^CAL~n6SOLzJ%K-^~28#QczdIZI@%gsOja!-O|89rIi(&YU) z>gFku>kAqiD58C98!L0vCR!9IVom7D59p~tF;xDV4hD+IL9(B^)l*Cm++s2b2BRoU z)!N+R0qV=1w4N8-lYT`!4t1-TJdKi{`W#t139~WcYCC0j5*v*#Bk*-6F<5?>f`dei zd_VOF5*Gg=Sv`e?ZUs#U5}_IRSAnH(KX_Crr0T^Hx=Qc3r$2dOa=Iqrb56j_q8EZh zDVK8q!sKZ32^I?j^9<@LIM$q+WS|FwMUMO%?FkkI@=>}OEbjCNc7KE6U`mCE=nxPk z!kKFypdC-YLu*6CGmy^0I*TK?D0jBAI4;N2XI;en9vWY$frxVgyCowI98J&~!X39V4#S4B2}We>ABr=^BO}}s!Gl&rrxr-3 zGp@ALB@Dq=v+b^Rh=<57pW{<8P(wVzfcs3b@NgVKboYT? za0J&D0{y>>y@ngg*iZfNVR9A8mwpNp zy{sB&rNyK&IP3Y>Y}P>yVcMyB4z)yvgi&s|*c5)NSWQ2GJf$^wk&v#0i&PvxS|dbw z^eqrBsstch9Cm}Yy1EGw;z3#dgAPW5onVmt87UHjfZM6(86v=zPjOMA_ju$nJ?kjU z0N2b6)t^Yzl;M~;jAk*=+>8;FzX6R#dX+x2YI$aH+J2;Qy`>xVW+c4Yw zuvMhb)LJD&Enq;=C%M|E^sa~&Zi+(dnX_xG(L*;b`_vNLc0oD|2xh=c_P}sCjN%r+ z99XZH<4?hf;yF{T+-$6SEm6ED>*!d)X*csY1Ujd3!Hw&dCyUkcRIM&foXO=dQ6Luk zD_oZ@ug>z5Hq4B+yRa(O^8TYD(MRo#bO~VvxIhZJRmOhM;v{;(gq_A!n$Q(u!mTtf zDG$Kq((kmkt4PnfmB#0}c|dGyPw3#f=!R?K{!uRHJ;}IPpo62cUB&3~TY0tiBW){g z1l1!itIfQ)ukx2RH2mSt{O6?62!ZlS`{LOXz%z&Ojy7+a*5y!cZbLdBu|iz=pZc0C zexPD6Jcv?P-%SjXc`%h?Yj7Lg>@I5g->IQk5NJ;ik?h}MQcDazkg{5PV4#6ITl+xi zN&OS=O{T9t~W75_|w(L+>|Dk2%uld zv92*ybe84abf_m7>#uaSrx+(cPdRB~u7=YT>=)_vG_f!M^`4rB1LDpUpDw0oQ^hlQ z)=bwrBwb{1mIH;jd`^w&!ag2Z)=Y)gBg9P~fe4U@tF(dX9dumeo!H(YeJ|2MWG$UJ zQw3mn(jT}Bor3f|NFPNLdZ8iQRg=-Ix>db|QH}zO&~g_3vV`|n8R*X~9$iWUn*0~XfNf42(pj-?~juSzTms5_n|_Q>*T+SngV zHNLLCzwndgUeuT)UNdH$Yp+`{K>RGr78*53bTb(5qospHB7@^E{5x8c{_mqw2M1UZNr-bXiTnX zGzO!L&cnnFQ`;wPc$6a#w9lsVc_PLXx71C~?F$UWooj2p*c8-upa`B$@MO%0-huQ* zzWB^we2|_SF8V~beKI~!Z5>(Meu}M_c-xtFGLH~drZ!sz z{D_PY$>G{9j=U3r+F=S$FDoX(5o#SFe(`T(hMjaGkUl98PZ+8LY2rxH)zA<~4~`T$ z5nFz1=VN_WQJZ`BO!!1(rD9)D_luFjI%cCMvHHS)6O)n1+h!R$AU+xvvb4bh{Rh_Paf&~fAd5jPxdIG$~)+@QDRbg3lL4lO!e0nBlxq7*aB61Nj|QYUvo!nMtB&) z(KnzbM$t!CbwpgiPlNd@-!;t(gRlY^J7B&<`mbJ?@dYlZVD)kk_GcInr3vXj;a9E| z^mu`5lotqLcRTP$LGJ_Lh_|5c3tVN0FATzmxiX`p z@F}Ff>V;`2aGAX@2!95c7L>CF=`U+A|s2;l|*Nhs(+0BrCUG&0{Mdtnf+ z1B@LoOOd|b3)8c}b?vH$)Clhai~}(9kiOarQ0{CBa9Pr9sbii*H<3+@?rS1 z#+w1*Zr%(C@9}2nJ>0e5TLHo=z3>Rfc;OL#{T6(I>)l)M1+Im+;0s)xZ^0M1UcTv0 z)iGK#+~xFUKp3}M^!Wc2xVC!Z|3kyZ3a7lB&X0u`!qM z!1|*gaZCQv(i)s?!GvKF%oYlZJ*HUiKB}uJtTbGw*M&+~ z&kolM*Hjd$mSUGob%!RhnDRHZP7)vcH_z~wF23prqcB={TbB%+#s#zs{?j8w?1JsIS-$1uRAvdim>p8aCI)u>tFkHcK<&f@|)P* z)IU3|A)L&2iRYq`w*QNz{d@RGdx|7`P6_NK8>If(U6I~&mpH-cNuL(=FLxNrtRUBF ze`)ul@%H{}k-l%L7-DD)uX9fovtV!rsxTW zLk%;bV0@c?pD8H*6xPWb#xlOT-UDwNN+wAO#eq6Y!e?9B>6H>OI`d>Z^nVgWfmrOj zW1M%OWSlqISXuWBN@Xzt285xU##d5qM>?K0jxQCN$+Z^nAwFEwwsLm7#Ezw@OxF5e zup0XlRI&n)0gKn_qwP)FQ!0|u(g_U&Wq8aNd6H`IWfd*QZ9s^P@|h))0?vBC zexp9KFtiVI2{<=^b$H<=)T9gd5zZgVG323w;Qz2x2WV7pPtG!Y+fgX&w_zy}ZQDwF zXNef41<_J~lyL)5Twgt%oh1^YzJLKj^)(im@H8_<+KHJGE~c2BKaq7dr0RWy`*|^G zUqka@|C^!od(M0YvkQVoHH59>LaN^g^w@xh(_wmvEJ_WMt&n+IF6;8xx3m)l&PoLu zY&J9**Y5P=tSIM~kRZJ!$D&~km)*M=#Y~iXKj5E2!(*{-^9bmM-AEDQbFnXG3E`v^ zt-Y0TKyp)sMxbzKSL!iG%*h;sqFQ`)Jy9j90Htjf*cNipdyEEkC)fsuFW}1r-;d+s_Xps7M$674B;0w3l)1v(laY7eq?y6**BTPzyc^&5 zv!wcJWbLL6st9Kwu%W8C!U7XO0mGzd^*|;T9H31_^L^vVIai3VSCO#+_er?0@mgWw z&MZ1KS0q?p0VA_O>jgqUiv@dq4f`L!Slotxr}zs6aD!0n0eT? zpQ4-dAfXTf3qV2d z#;I%;6Yk_2P`S{+wcK=P@-B-<^B&-%&xugy+aBDiue$f}E{g~01=_n1Qvb`;x=@S+ z1F$U;wy-du5dgE_qE1rA7~>qcMTv3_rFo0Q3gaKg+v(&YFt2x!UwM7XL>^w|UCy5?R9}W3NTH);SYckIxTRv8A@gTiyi{~G z?)#;^j+Tl5JPr91ZC)luOvuEnk#K{Nr-MLM;1sr^P<_nK!$#!>{@bJYf2eaq1)~<~ zJc=)K6yBWh|3mn%kLOV5SCn&~7^*~~*rL#DS=T{8zD)TQt-B8+;a}8aIrhv=v}!pJ zze;Z{hr;|fy0~0WR6lIgc%rppqOlUH1S7U|EG8V)+%FzfLO~bHId|rFxW>$t&ZV>! zA~m?+!4C8ip6El)*J;)YRPqA(tQ6DaKq_7-)(8Lf02&y=4UEPNa;+3GnJI|E2-MnH zkGrU>#UAJ2wnaFr@YRnpBAibltaDD-iPET5Sk5<5%_=cQK11hMVN9$h@` z3R2bq9R9>ZJL4pd8)5|mABJuDNpxH33%cqV+J*-(CYtEx10pgE38sHz-`?IqunmY9 z@-K|@c3S)(7UoAO_d!iGnD-!hb2+W$e*v_UKi%o*gJOp7b)0(JFYDmLXu?CnY%o1Q zvmX*eVBE6pAu$Ik&)|o}v%!W{-lZqf>870ziv%98Uppf(uZz70sv3QW!R7XJ=Yl zE?$GtTABmM$J1no7#QbT*%6_52-WE6@g(&4sU47aX{Q6*9!~uMD3n?7c(xNpY zL3w)xMkk)IV(fSo*+nm}5fRgSt_0G4*RuJMMNZnM{nz>Vj|dleR@UzkuGSbcEA4d4 z-}jfJGjImaMCG{k=o~Os&wsNsjFhz^DRg|5wm@SvhB=uNFyANpFCmdsHCi#{yvsH6 zslBI^#V7?gnKUvohntW8@Gzfo)mKtjg`zir_wg^U72QHh(Jt-c4od$UC*B|4D!py3 z$S)7_P-HB=`WO#$jz-u^odSgUWl=^hA7SuWEu4$6&LP8`Ll9=}%`gKIF6u4q?hH1y zq$`s%-1!saFP=xsfl76VxBb!19{B&xqe6*GMxX@(ARZT}ufi&aTWy}^nw^hO>!Ttf zY_?Vg(=kSq)cLitND6)oi^o(X>C8MvW9B^dPazr8O66F~L1{EVGBX8Z%WqjzRo7z4f>- z$8BXO=zo}6Ye227|DYC{ih_E)jAa`lYla0)`3i;E{iRG?OcTKx{yf0hBq74Nf~@OA zx7Z)=7?dcTy;AUS+cs2kDfs^?B!T0Sv;aJF62k-`?l%w2Yk={mbzIEvXp!Th zF2=3pCS2!Hi&wJHjHkE?t?%{Pw>*PU-1gs5%-H17#dX5GXc9`VzUXS_?m+vL`_J9l)mHcXvhE-yzF4OiWn z>DmmAbdCpT(XX6Uvm!%rq0VG%2a0g0lL8p5!OkRn|3n;z?Wf$kx!Bi0EJoALL_F!O zI@OWhNse1L!EoM4ZnCnBb~j0LyHeLHxgzJj>9*AL&MLU&TZm@s!$kF z4SrHYWVRx!;|F)<2^@Rx@-)fv6E`WsIa_N|xYLcV<44ZU)Qon%L+hRt2|3F!zZ=fF zGvQM%g1eY0U_a*G-3hJ|80li!?)nA|t3Kn-JOCK)i2RCLpA@kfCm=sT8$SAK2h|~U zhM&~OV$_HEF5u7n`T{1|E=)4r*Ik73ck1&Lwk7Lm)KelhwiN~BItqKEfR|B#7l`{7 zyO5`ZIqhCxWckj$=U-aw`VeBtbH!3%b;wIE-MaF7YJ5ucnh*yui`#w=zB*Hha85&* zMGs6P&_y3n`U%UH`mDEtn-Mpy+vhD z;|$ahL(e`f`os<8fdiQoY|UoC?1JAf1>;$pEjy_7X<>%zq$^LuM4~c=VxECady`f@ zBVyt@aYmP3HZzDKFfd-uxEYY+p8>xe!k-vwdq%_t9|xu^aB*^)7Vpbg!H{7<6^_Lg z(B3L6?aB183UM%%_NovLH`HBGVMh?q8zY3fF}?24v(WxWtp_2Cu>Dxa-~H?WTYoYT zzPL6*0$TPB-M>)`Q10`9E%kuiON|>vk|E+Ko!%(ot&@02Lm9*+Rp2)s|68yR;u0(H zyNyzw6Vt4aQc!uQa{weL?hah`+PwncOn$vFHP3-d_eLfA7T}d-T*4Wqks;h!gLkJl z&yniir9%wz89;c1vS*kn7@>AhjBOFP^koF2-DzF^zdgJdot)#lYZi@6pd0 z-@#?dRvPuZNKy_VivRXQ(;1U*=;7zZvZ(2vW^clmmpliOYZC16wG{AzNHCp6v}VIg z_7|{Y8>~U|>b(l7atFQef=DtRKWxn|mOvuvc;7ej$c_CQeYD{ZbC26!(@n74nXv)A)*pf@mwWy=q z%ntCwoa>P8UFaY6!XmyBVP4QJ8nKu|hB{XuADbg`PcW&EEkPd!N}13I3NGs)^1S%6 z=o5Ao4NJH!w5+>!&;!S9pu{C=eOZ_XpXa3Hz_K&2HsbcYi=;Cgx52+`q$loM#GT|g zlV90(yu!az(&9OI<>e9Gp+(uk9?pg;VEuKtiB>r z2m7D{bg5Nezh;9dBaPS`V~n#~?K?0o8??b3<-D$SrrBAIG+rB~k?R#m_uVP2T4eW_ z4qgKMZMP#AW`{WM8O0nngOr5Vm6)s(>8Wb*OL%P&NKk{_!wD#6nvAjP)-*?9Dpk~o zuK$}>BH{K;x}z|b_ST4gsXu`qaj)C)#(T70rE?m-Y!6_hN`YNXenTw9Y!)dK z0z5#Y@eT59j|vd>Zk6&8)+P#u0=uQ_g)#5&(*@fNNQ(rX+%GD^{5?$SW?>F!10MXh z5AED6vcq0RD(INOEz~)-+1a05o6#57DQpW=8&#CM1*_3nx@!wqQ7|M>OQ~e{h@>D%*zkSs1fR?#zLj z)|;xgiQ2G1&Fz}FT;#{v!cg|OSh$#Gy(%h`6^squzFYzS;v|-Fa$pR^->;Dk2-|4< zW#33sJqo7Sn$EFN5zvD3C}{O)OHb}cPeW@CyOYm+PETzYy;5vQ zX47Au57jbDJ!a?rh0LbHocg*5c0jG$g*mDo(X8*>;476e7=u8qHYuEfUl$R>bASh{ z8I2w_qs+!3XiEuD&X0qtsI5aYvM_nlD-rL7IiT58huZqkyw}CZ+iOR-Zoo?c-;LzU z4edsg_8R<_Ub4#{wXlCHM&K{>CI-K4vL;%Xo%f?HSletE_!-fjTJoA=$^E(ri}pqJ ztT_qL$RBGfg>Ce^y>eY^VV>(00}NST(|jkG^kLfN6w!vao9T0>=sSJz9eCxd0A}^L z_``KBz<*vdz5nOnKhG0`=atwJEge>@kS-a12L2oH!Ub>j`2RF59rsVbF9USQjTdsl5+vx#y$I(*gmtA~gmWGp+zByn23_0< zhS5U7yYO!m_1PsRM$H0(EvRfCu3c4oEE^cHvGnpT*wa+RX;+V6O1}$x_B+7!fEmcG z`{tSnl0HjkcY(p}ChMEf>^}nTQgodm@Yp(vnM-344L#31d~y~d)q)AeuN=}@=rmV zB520^JX5U(ki+mh=>S!5*gpk`ECwP0|0g{OrJb@k3dbRRHqyaIY}~O)FpKt%rY1Dq zu5HxJ&US4B66#Du99zp6w2>M`z1|XG;lDB<_?81=5iYo97Gqi`Mbgx_MD+Y;8Nt); z47)aRc+HP?&O?(WY=XH5)+1e4`f(c1S)DrfvY?K946~XC0K_1s^&6Y49oq* z)bv?Szo0(YOS|3@F~OfAJ8xncY#~|ShAH<2L^)2lGqN<)V{qYb)Y~F8x0YpN2$Uuu zI1`BHy;R_0lPBMQP>ju>n?TVuFdI8@9&(#T4MsT1*`4;hjm52renn})J-IoW36I(N z0mZ!|B77Z;$`7>oP3U1)(S&!0J7Q>#4}hyR%UvkgP?QrZ)=*>UIjOV0f}F*F zujqIhVXrReB>no1NQkpwa8+Ypz?@|^!iIgkXCJkg*lgkQmjFH z6#u>JAj5JemLT8O!H&X6I=BZq;b5}9E6lb)$XDzPRwo`r=4WMf4^D_#FM0_gO_Wi} zVIoUU&^_;p@Zi&c*R``|=T)kB7p$s4n`pjK_ZgyHD~T3j!p zbNeB#8VWcb0ewA1)j(OtMaAJie|dOs?q^W9lo-@7VBZF6LyLr=5#>yw&+5e|!Ix31 zzMBenuA-OU7h{44f`wqz+W5NZcDnLDj=O8?5N>E=F?>RC3n*HU4VxI;PpHsi#@4eLI*_A;t(!giwm z9S{{eJYJJIc_zNQ=`1JhM3Mtih@Oiz77-ZhQ3pWxSCE7?^?#CTXu<)JkUktqyx8b6 zw%OUB)r)O2y5A}!fMiY%+9jQ!dTuFF|~}gzvw)?;tNVrP(n*BqkNw{&eA1C@Oi521E z*gihp_YWPdJImRxxivh2a*eR3$i>apUyB@t-M=qcIRfDX*=K%txqBA-Px$=%c`MHt z18t+_$SjOi73oxR1a=J{)B8uT8~=!YI3k86uKTDRs}7tfVek4Vhv8fadehxr?McN) zG~^o*FQ?P=Z$!7aHxIOHe9Yp;I*OZiGT-!T>8V=B_foG@%{P$kOHc|=u?tkZJj6`R z--z(UJ}MdTk{T2WarkmKddnaGQM>j68QJep!YJ;jFozr(>(*6Vuve@&Ktqm-n312f z^Mt!)OL0HYD1y-)tImrw_r-jS8|qvLxN=;sJ_&ye7O4JeO4tKCZuBuPB)SB2NB~BTuR{-2uG4XK(Q7^!+#V>wjHn!K(A-8x~IaU z=s16yn|9+rcXvXEu0(pHiT?GY7!``bjL)n)kC#)?Pou681Bi@UsZ*;jpQV&;Xo3uOtuSJ3Kzlw3AHXQ0ERHPz`2n z$6!xuqNjfrF=KJpmxWC}@7WB~$}_mFW=B>zHx;8O+BphY&3&N@$Mx~)2Alxg z?cXn4`5id_n?ClOdy(F&1s4fC`4|7VaOLf;glunGNsCVW^)33C{-i~(^PK0~xfRNi z%0``e6varp-v;St7~x6~g5p%ezyEy-Ga55oeE=}pljE4h7Qj`*3n0V%gmh-5uVVA4 zTTb~p{b_A0HhlZZ*$NI7K%cc@?lzPE3DK*(xn#9Xt%eqh@95^=t{t);zSi17UqIm7 z1qv-eOWKYtUMYM**t1flR8ja@)XUH+AI0$a zKZ&`p2G=1jW9(nS??u4f>)8rK;!uI-LIYUoztI5}z^_Hx#ebB+;$9MHns4Vad{G8Q z`xE4I3bNk+AhHD&CFjCTGPufvlzU2qhu=!)LYh#BX_B`4IVIxf-Ady|oJ3mkLvNbibtrdcw++hILH)eDs{JZRFk z84gFRlCPRdVZXvOE_|}a5N!YSMt9OvZVl)^48$lwoA?q%Uz+u+C{i%Tt2M`gEW||E z<}}i`zlw=r%)$_@TgT~1V;gD6X^06;^uTG+NAEH1);J0*y&Jd2Texzwjc+X4O;Ve@ zI}cB!;0YN?5}E_P0I4|<2uN^Vmgq>!k)S@v16(QK=Ha&%u&=I65V$2;&+wc!$CGvj zX}+@5*PCWHl}l|&4)8NiCHayu@D)>+vX+QfqB%2H!W9fdA-RAlz%L1fl&%aDrzE`s zP8;q?dlhL1r0~ApG;RPJn6hBQR-SJKn|d&l>InfX%yU*KatTMi~LJ zz1}9r^bG{^)l&DY9f(_qxToZ}zKgWD-dVeL(}mx}%(%~{YlPDF)PLTC4GHiJ2Vt1! zengATh=k0n8Jd<*I|69buH2iQI{_+rR(RGBbVe}_O{bvi=&;>6BPLEam+IRyoO$h@ zfH0T(FMN6PQLSlb%+9CrpXCh;{yXrf9!wZ_KM(GI5Jl>8bEMPYL18D@v;%1sK;tHr zofTseenWPMEPMcH7qM%KQen&Sj&J1Z>my`=mOy?ZmI{4T~Qr6>}zWQGGp$&iQ| zsN#2QBgWB3zl-efOr%==a%b}OD6Wk60Ddb;oD&1&r)casKrScs95loWY415<3Eqxp zNxsG16Xw>6F+H^sr$E0z|pmQp|++=Ub-+c(f-$#SP=*9(X6US5ZpV;_~ zuPgjhq{~6~BC#6xGS|CdV%cR`mvCCV(ASr?w}}ix@m~6+P23~L(BO+O%Ns#!FN&;A z&8NU&f5q?2c>4Gv%!_NO?IN&=r{GH>Ve<5=aQjeXP@lt>pX6ZtS=eF?g9XaRkGJZ= zRRe}9)2#&p%He4k`8KJZ|4#k)Yay6fUg2bFOg5yH) zA~MH;+?ad2bK&j+P25CRE{UNA<6g?TEP903a<_69Gvh3=_f*%wU(_yIepx(<75S$; z*QJA=v4`;XL+~hoaaghyPltQs5#H>L-(KK4?TttHC2#zo0#}PS9^vN@&lAv&vLwK* zevf?}zkiD=niKOF>iCbpuiT$1{({!#GkWWz$sdOkK6I8UwzSg0G0Y zfG4$RDCHR{hVHu}BCQW2jvYf6 z!>JrkdVF^duh7FO9A2h}6FIzI4<{hZctSZFzsb@c{RhOESR-(X#d@I=aHI0-RjK~l zy11*NlWe=$1OD66rHlbg2kZ^_FoWU#!(+ITWiLJMy$`AI8Z7f)qxx%5nry23`I;DG zFyOTpTf3MN3g{JJP0T-~@7;U&9kC&_u^o1@we(B7SPIj~2{%N^;O*NmpEN^3Hf7Lk z5u7hzq&9%L^5MR2(iLT!4egf&TCW-i6>Rcdjc+Agydk>fq(Ldinyq>`!r)}y(L8Y% zNB~}L@cd`2mrTJ@0R3tW*+JGwC;X<}6bZT4fu;kxoTfXyN|j@*m$Ar`laXLB zzbSO0Lv-yEk9eNovHS(2jK;SbC3gosKxS7p+MdE;%;svSJrXI$E!IPq`H@@n46wip zDz5K7^#i3F%!xkC8D?&@niIwz{C~{7eOQ#$-mrbmfQp8StwBCS9S{`}6%`E&br4J} zEHW!9Nl@v>hno+5!sLdF*$gEJYkgUj1u&7X}tgO(eXm9u4s8kdb15(LOz20-p z3~l!P-1l?5?{hqVym`>M=2~CB^;_Q`*SbivTD|?$$)L)QVH^onv*NPhT6H}W`)>%= zj2@#%pmS1*y_!rNcKdzb?f2bnPl<7XKXRjiY9|Z~`qUtITriitGXK5R757{f;$np7 zwW?XloJOL49Nlbf(X*a;kjSC`JwS;isD4wy>G@lKjpnuH~Y|=^nz*&?^^vh*5L%XaVY-i?gca ztBObi#8A}CGnEQ8N4=kvsY4B)F`P(uKU0ge!{knaFx)BMCBR94;3}0gUFkk|^N@3> zG_tand9tdyzr(VtSeBF*J;Y>=08jE1qn6x_fa>s^YbQ;e-5ObW0IjMM?g3od<4h*W zR@0CSm0UI~RE}{v?&Lk+;*J%@_na}9D(kqaMm#g3#Q8Izax3(wSZtKD28eN-bH86BsCxkAwZQKkK?n{+qKN{s5>-Xlp>S>1`mIFS0!e*^3LGF zTV5PMsw(89fnwak1*EFJSFhge)Ryan*+ivPr)~l&zaUWB!*Cn+$1&?h?Ve+3x4-*Q z(mqgJW!TMyHe#}MHmC9f}O?>2KJ z4EL&W*n^+vF}Dyes!kReeIDy@!N1w4)qezUM-Y% za$nb% zP3c73bDf;uO}uQl6W6~FMnJqO=CoUEemDm$Uo*%_rTUl4SwqBp&VR2T zLai5a?+_8>g*@>zWh`M05u>aF_Fi({3G=BtvS1%xw^ij@C3Q0I)_-$JcBwo-=q6Tve3=LfQy~)LQ-r9tu9QS42vtd=q#B2MGSxbv4Dc4W zT(g{_t%e?|aJ_lZb>o(5aa3cWme)0OX7k{%ja#ryye_Ef-qEuNHq*9rInk*6O|Ow} zdyB~tgzj|0D6YZPyq#Qv6SZETPTbf~x2u;P8GcBP7%IkcDg5-IwC8`kdWpL~RQ2{hrz)2ApE*=CaHRMZ@9vLG^bb8MfYm3;`p zWT2LU>8eziSoIk?O!yC0<%ASy-^i)M#2DkngYvpzVw@KVE1%)KbYz%_vZCTlwx|B_ zH7ka0Z5~GzDp;k_E!c-%Xl^d<>5r2sN zUD$uoPt8i~p=XI8o*N?G!@+Vnef2;giys^2C6^5sH+ZWw(Wt5{rVI=hkwaAGvjt|y z^&3TAz5xyH@U~zPi_B_?q&3)?`#$0pW=Z$@h?&-sS1w7lDyv5SyGGG-(0cbN&_J2# zQ(!B*Ww#KtnzyLj>>s*vmyX2ha*OM5qfzsO?v@un# zA0ck!^`DPNh${?lO2g$MFx}Zo97YLBOb_(x8S7dTyY$s1sgk3l_>d5l8>b{FEuKYR zwFdMnZd7tUawkW*QEEA>G)_2bVYov+bUE$FPWkTTv{>6D6VPeK!3X3RAtu~nt#mCA z(Ci&h5h>j{OArCAqsnLUraCJmT38nlfcS`u9`0O{cc!)R~Q6<_}(_rbw2zArUVqrUbz9>eTvgxSg(Y%pBFUj~2kSUMG!$nZU zt{L_QT7ciaU>}=CoR0>XnAp(x`#RrKkkQ;`eV5vW@vYn>H-?K*;blB3L(dkp)b_@| zHT0b_yESwM^KEa*_rk@^;bxLL%$?NFxl6GxsjJ*co#sxeBTdemEJm4-NZkqk783O> z#yuccO%^c;*o2yC*sxJ2ktVt`v@M92`3ZOi&%XSOGX@db<;&kT+`EaZ!@uWus%kD+ zmFUyNPqK@6*ohk&A^b~4%_H*O#0KEY!yMMT^JQX1Z`;^VFt69exG^p;wyH5TZAtHEvGh~XGG2#I8OxMfUqH-VR zi!y79h#RmSW4nB9iWoKh`N2xVuEhd%;`J=^qIY-}=ge2X$}~!j8cUz0I)qv+&s51? zyiEuZ+~=Z>V5@>6Y$wY+jP}*%RQ={n9~(nz%zODb!BlZIQ{+ukMW_iuV-Ylj)-iL6 zZRx=bPy65HA#CPiqlPW&$%)Th3lcOkRc6|VJ|9Pw8%7uBJO+g;cOT*ID0&+6x(u8q zCYtz0f@?d@b~27Fx!u!@y`$t!)5KL**N${;zpBQp1nReBiDUlmY zTt|j@%FQSuRNaGG4{v%+oh^9x&vl%0&h10yi+sCkH*5H%GA&Y!v&JoOdF{V`PfO|4 zhCv-HA)_;hPK{5OJELI(gy4C1Nv-8JeowHmWL_)ZpHiO|*Yd9BL!~A%aS)j}u+qop zf9v*||8P8Uug)L|yZNFSQLrmp{terE&w2_7B&X1kZfSD@yI`35r3}3ll zem_GjowSis=$u|*_ZO#~IVmmu!y#XXv1r9quQp{#)ZA=M7kHcm=J^9620J53RpPv>b-@H}x3@5E1;Pa$|fE}1W4 zR4D3(bmpn^#qEP%yiP@^z9RYSe3o;@$N&q&^0D#;3xo7&a*svKx2C$??1Zk9!*m#! zS+Jz$`&K@WS-nKjLMs2xB7|xeT_^cRRla^T+T#n*%3T}oc2ZmD&WdfQOzo8(MVxqU zsNfve$>>jbp^8GGs{Rv%bJ%J2y|Z#O9_#qQ2;b>Z1>zjx<2jQl+Ic)o!n3+xjq&!M zZq#geH*Q*)r3GWJF1bJOr+}^{-$&))SZ3(I$Zumwe|62pSW#dwyjrt4P7L%gPOXqn zTrFn!On9bmE-otnQNez*hk|&U9k3^By7U+Q@K6hwJyFgx%yUc&>%RpLnjygN^5Emr0sO zTxOCf2_oY1k3PL5{Wzgi<2+jG7hd^_+@2r;Cp<+$E$;J+Di>6>eS&9YtZQq7T;2I? z74okMVp>YeYvDFdmaxi&+=Vly5Gk?6Dc6e%&fZUnB0KTs?9P53i7Wu3>>{=M~N-;iUZT8ZpiK z+sBOm8O*EHs?*NXRNR<9c;yfIGV!W-4imSE_h{J_c2D9y^wA~fRq=g(W?~oY_E&?y z!%Pg67LOQhho+(mHCBt@3!Z!aOL)7>t{CF{xFpj`RU@yZ=|MU*lH4KRy_QBwMTo+l zk*BW}lZ{WkB8Mf4z@Z<$>^l2mqb2%L&Po*Xjq6^K_a)L(RLT8`;@W`JXnXub-a$oB zjj(CTiw|5M+q8SpOfpCh?zs*L9~DEnrgp)9G@JP2bQ3& zH{@4K#JE{Ir|ELJht_WN(w2oXSyLyqZL~43^IW~HsG7ky_x>RV#H&+meA|vPvQP4#_%G+L#f%eLy zUiN*OR`s|iZ&>njODQ)LE1gxMv(s#~}TX5RDI zgk34&M>zeC3b*0+5Psus5ThqV<5~4%^fbXeV{(afBm*t~32(x*D{YPw4 z-6QrFoqJaQ?rz4uEI+(KTsbI^vv;@c_K|~@is_5(c;E)dc6HAD2zPXq;rS(=nJ7c5 z!tA2LtCc@8e;Ka{+m(GmKR;VIKc${o<))>=Z$dc9P(3lu=_&&&ALL-c%{W(EN%eT& z$mBYBk9=<_C7`JM5Bc2Pv!hkiDu{5|wN%7MQCrQt^r0eCdKk!h>~s76XP7F%$tys3=#WOa+>xEqCa;J0%b zXYP@+mx^3!?YGHEzwJu}_DU{1Y@}Zl=WY3=Ex}S9Xi_h3DDe@X5kKH7E{LBPM zV=!X5w{~wKhm^}mxIw#8cHSgrn+UFegsBEiZ*X<>U&=Rc7Jf46W-(O7mdPks=}9?p zxSce(oD|(G1_$9pt=%{Db9UP8?0|AM*6^A`VilHQn^OJMthns zpSn#<^nC=YO1G7njIa^+D*5qk;vVCOd^seA4^k%IE+QtpvHK6_vFN^&Dyo84?xy@8 zU*G8P<=wLKc5$cSlpLJGNX$##k-~6zh}@aN@a$*#ZHlO2Kxe;0Z1!tZxp$iEF{;vQ zxys(k5+aAv!tZ3f@wR;APO)bEBt%m~G{55g>`I)8zCP7$jVS(o<77>8v8*D*friY)vs9PM^F z`qPaw*$DNB(+z_m-1I*@Gn1os>q3n7JZ_0rYF@WXvwy&$W~B2B!|Q z+qxI_UNu>!r;6DDBd7As9!h2zB~7DIOjWdLcB_0dRg9W_E`^IhDbvb{2j|~1HpKV7 zy`|@hF*}lUeCv5nJD{rPG>hk{_f~_qNIJaBKW*ryQ0c!i~nA^2!V` zCSdcgl+cRH)bi!BdP=B`j!PB)A@be~fq0YU6B%MH!~KgHVv%ofxN73K+6P}Wp;4+4 z8!T_lq;rpuk7tV8ulb&nBdVidhF*0$e>Lb|eSW-`KmRSW_>_E@{r3g)xFSKlu1SMN z@$bNoFHNCZJ9h4t6T{w}a%z_F^WVwps(PUx-KnPj(14c$mA7N^jx37#2)Q#$Bn03{ zZJuj%!cS1BT0DkSUc(40Z>Kb_5Lbkz&9mE>W*TT$&QRie>v`dyq%KB03*iRu47G>K zJ64E^bN@D5mjiBh^+QUNf9H4C4A&N~g4U9XdK?qWKYI?wq{#45S!E;WCf z=lpIU1IxQaP`vs@seT@@)sc#Yx2axzWaZPyrOrebL5*f-BPE%xtV$(y3w~5`Rn1jj znkteP?-Eypth2eqUBGli^;8zyEc>qAn*HX7Rgk922g~Hm*&^JKDmP^d(@<@;J9uD(YE zE}nw>{%)_v?fb^S_S1Z^rpg%~JGw?!eEGzuuJYK$bA)TOXdHK}S9i0TD%Z;s_Xt1h zbuo-~+}_k z?7v_vKUw89L^^VW4{KY7RqP@(%h9WtZ+#?hT_q-XRXNv_lgQImVz!YRcHdtmLVRpS zd&IlCOe4*z3>}eOtAyFJ-e@<=!>bq)MXVNsjUJxziq&GO*8)$w5r;#ZR+qh@^n#z$ z!5;E2t3^oACQtkMI#*a{GgMY{@Pbw+&Zn&Vr2K5PFdH{{$j;TslICeoXA<=f*|l2u z38lmX{2kVe_WPI-9S9j97p)O9Jo&PURX(&v1Q`!|%IDXJ#A}>I`mm}*ETV5YJm0zZ zTJ)atZOoHV1J!uPxAFsa-KJ8pC=68w+kCq@;lBTPv8|qVBSlWn6{cv~Q`gdrYNP!s z+orkp>&fze$E3yts@hq&pMjXppm|^UP%i6DL*?FF+U9rV&$%KfNx9*x3X5=~N~vma zV=V(HQlfG#&-i?#pK2o+I4$*K_ruJ&pR$2kuR1BLo~I4sP6l#Ry((*FsCkd|9@17H_f>WZuMaKNv?Hb{!-(y~spWG|PhN7c* z_NRvhIEMx=zRQdc*9ZISfkErhBZS75 z`LEcobjs~tsocCER}#WJY*m}A7L-Hie!jz%%3Gy@!>I%8N+UkVp^h6qaSLAqB!qsA zqx@*C2=PMRa*iPILDjWl_5^1E3#Rhzn#d^vBzDLWeHs7I)4%5G=baQj^B&bs}XIgqGi zS9XW%2iRw0x5aJ8p}Z((qk!G%mI3x@Dojld$rGc35I>Y{Y8y$X*DY2_R=uujS6-E| zd31m(fpO}pkM()t#@pJ*yVm_R=Oq-ryql&Kv(V8vhtb3L*r^f5gX0F;(-~L0MiRc2 z=XkFA9F6uyo%H;fwxgb_x@?RHY|iojsLFjW$dL6SWazdDw9^bHRK56A-mqR=yRd@g z4b`0mU(~PASp9m9-x|}?CaR4Z-IlS~%^|guYQMFfs8s){nxcCNs@}O*>Bqv_>Gh1b zK9arbMUX!wr<_YCJV~^Hm3QShn9sT&lc(<&<7Co(VnhN?GC82sRp&aq&@bDaw|E$t zB^7Ya=SS?nqgbGNX9bL<7^(i!*?Y0`dRp$iPh4TmLM$b!>)0%xW<_I4Ylrwt#qK4v z_Vs3i{lU0__Bm*87h^ux@~dyXGc zdCs&gy;}Ni6k+C6ipkSs&#UTo#{*o-jNoegV=)If8=-&6J2ndc@db-|OZGX(<5deV zUsL5Ak5_4!e}2n39gpI6xnQvXI^4K?`-HcYNL*=~4 z5hH_hX^vE%uj-}}JjeMvpppW^Lbr*_(564Y8eTJU*_`)yj;!1w?|nc-XW9nZgGo<1 zjYa_t``_QWB*!yHp2**3W{bhFfRyY`Wz~-?s#i72Jjec>ZI0bYX=&=;h`7UY4hCti zJ|Qf%=<>N7(KNzej(?EG`Y&?jgJRK${3)*Eye+)Qs@fwyfbt+?+PT~)E6k&xcb=Yz zTE~foJmQXWzc-*J1diwB<@xOC4VSU`B6?o^Am{g_?;$27@fjp;#fKU5_eiT!VnA9Y zy^>r>UF?)9pzZ>GjaVqZ@N{_}FJ>qkPQk#&X`tNGY>VIPJ)DVw#9Z>TOKHAV`oYFtu{mN~sU zs;gm(F-y`;oS~!<$`P6ej}VlG`3Gs=EJEg0spngQNibA?KSzd9=lIxZw)UD4=Wuf*)r=8rt zg{job(oi5)&vwePlWM6}D>DeI^)lPiyK$!`Ipy@ns;aAW1mj|5oY0H&gV7i(w5v=EQ6d?~kCWN#-CMLTa z7~BqaC#P~0~nitSBRm|crjM=R{|wL&p=;ZJ5)ho#ZXUrDW*^0RB& z=;~YjDoYsMRR$~Rm^$IMe>1CU*cqDIU*w3#g`O0q}7oi*-y7ai1I{OvGRAXm@bMEh3`Pu|miBXNDIuP{rdY96la3^OR z3**1MsCRR8*qv8dajdVsaPo5994W$gz@2yz#=iu);X`);?r4f$!ts-)HGX3rN$z&Z&0s3 z1v-DLQlHH4!)~e7?`8ZZ%wfGZk{e&CnFwP^zUlRpFd_8Fr^M9Tj*n%m)L%&!lRcP{ zpp@B)qGq5Z71U3-DMSosIm}tqyX7@5uu=Jox%d@#{$jrRRd@d8$QPdyGq~LO#8X0y zK14K11MM80P+9D%6@ir|7MoT`!_z_-Z;^83(_%sFmBgY(Z)$s>o93+_7br_#4kKKC^1Xt8`EhF0vvLG}rdQw#7*N^lT+HEyM;EY4&J%foH2D&j6m z)9cvN+ZL<538w$EP}#oanG$awqJ52DW`@p^*cWabai_IXi(hg&46HnfBd1ow_|8(F zRx#I9y0wb=w%6UY26G#=sqg*dU>0~R%R8a$YXkD*OUiO8L`?YMDK7QjShJz`RvV9QwwOsP?R8-*ry2KO^7VD#VFGA&Hmpek$FYiA< z4-@(5Wu^gSTX=)q^o$t0xREMAfecqU$gJhhu$9N7Dr`#0c08)nwyN}~xVP|J1%3oK zp(uAN_8-a<)A)Aog=fTQgOq_KV!^C^I9K{lQ%(tHOKgDic>l{swK?y9q|M2}8~e7- zN#;&Npnca-%`T>7U2sh*IHyLo6DgV3n(y&a0Efj3!j4Z%7Yx4sKuM zxyGxPcK7q(&4H9r+sRU%Gmnhg>V6)(3juh(_1T&SN*QxRkiJ%S!UL5+tZyffk&md6 ziaP2a_Dw8?w*wkwu=Xy!QA5<5ikArEy_&4V0Kat zRFkTLDadhtY;?OAJDl|q$3S8{<1rvS!x1h0o)=q#$gt3C+602wgcKH4lZ}_f{=^%2s*u1#u;B6c2q-EWiBC zahGH)yZ7np93uVKlx_0i7sZ4jKWtUaZBXTRTjlF7axBE+FaP$U2=F~hu&Ju6F{{3c zC1R3yl^pyM>mnqqfg2*~k3v)C2&3*ro&h^pTWx7n6nK~(BibyZTG?JtSj zOdBwcC_K@|H0-zi7ym}=mH+sgY)dC%{}lF*_wye@RT~!@Fw&lRi*4yx9H{$F`f}hY zd3dLoeZ`-V?IPW~39Mi_g&4Q1ar>A4fl*e^D*IGkNZK!_?&6h&33ACUF)g^u{)b$K z^S+EpW3(JX+C0b@^@?Dtd;!46+T&dv0Rq>lZ(TTB~1nFksjtkP#Zn;QSj^jYF@ z2E(*0pK0$EdMWgx}1vkH`lKWIc1NyVqx&ru05r`*`^vr7ZR-5 zs2$jXIH{_&K@?|tTE^NlF^@-FRVRnzR}CcoCim_Ui`t%H{IjmpMK8ru_TM!Y|Yk zfz>XYvbE`*Wd8|MTVC3URyV4GYN(OXk1;d7y$N`4}!67I|K{Rp;M1 zIlGq@(MP_pmooxS%CGi{n8DbEGG83Pn=+N02mYr_s}yk_@35&d?G2yNL(|-YP^HnI z<%voW7K)E@GiMmzP?r(9`rE!a>Tf(#E<5F$kwb)xe3c2(E)`;cT>UC zS^hKyXh2pS8WJc+?h{uj5zFaT*4Ny+kLe?~m%R6yXg3tqRK6}AFZ(JPu(RL4>+@%frbWag?hKdg^YxEfZ;r2m1Tu@Z=`hKz4FsLy*^n>j` z6xCdMODr^cHfm*Nx#%GK+E2^34~kiasv5^ZG1tJ)skQ8tKP|7T6}ySNyOx!Yr{&d$ zm~1~)^Y$UiDNnzCTf`a9nrlYABQB}mf$!qyshTU_755trMRNc9;x=R2lQqNY@r>x{ zhXqs7s^HWRIqE2he^SmnD!vP=l1%W=abJhJjrlz1;?FVg+``)cb5thp3b9w8<;Kd* zAvM=F@ESg!m{|R>uo|9_zkDp1?2MC-eL|Q2xV-d<=r(2-%I;4&^7pvvU$o+1y*Nn_ z8m|^^50o8QGsn#8)EocO;-Zh4(%! zkJW7cQrzb;h`zWu*gQ_^Uz6@fWym+YulT5Z;2XNKN9A9?5qB9a<78Yj8S#k9h#4}{ zbA*?4G>e^vM{BlzD{dL+QNW?NmX9wp9c&T1J-AY%{H(|v`MHf#u5p~};g)c&>1O!s zTluk#4=;)%#^g;kXIjNNW87v=#BFB3Q1iJWb%AB$*r3sCTM&*CSN!`fPrF*kcbbjC zcJ(#2-x*i@9x~g0XpyBifN)V_V@>G~;wHm&d ziAA~Y*z||o$WpE<*&1&d9lcZeLCkuN&LXyeZh$zM90{sMm%Pftg)&i{hl9OLE< zZd%;zv-g)D|12gR{6(xb4obf(BP}C4t7er$q!0I)nvo$t^fXNyur4p{t}MC6V47R= zrom)1OqiCLmX|h7OHW(3GGqC=ytOM=-=$r*@cJ8X%EcmU?Ucx=Gqknoa)qZU&6t+1 z0Lu1Z_E zdYw6A&Fa-z8F^Wm=DaoLG;{8n`?J=X*WoZDYpS+({c0p8J?qS1ZJsA?CO6zx-kz;nZqZ^XD>5_8^>qLr9(^> z`T7vkkFx$U)15;~iHORfMMui1-lja`?V7CeHYLh>ZcBl;fn(WnjN_URzLYvAXrY5rQcw$|wSw*XTlA42Q<9jaZ9dA9TS z6!p+si_z#pG~+-c|EHFC)EMH7o3-aWE>U5o8Sgf1H>}bg^w=fsKLq;8+;r33HAX*^ z#ZVLPZ}Rq#DW0ReW%4LfZP1W!#>JH9J~SWJImYFEOkg&+_?x%>K41C-nU+o9!4=e< zcxOcFe}-YhgBX(c{WE&_j2JUkz8qwFz~5=@a+rG4O<&D_Kzs7Szk++;m*&wXo7_Fx z^tAkSjA^}j{pxiq?^;dkl#!jb)*QYrFFh}B`J$}6ML8RDvu}*QTK;XcDPa7HoHc2A z5$2Vv`~LSI-XhFSd)`Yn1$wAfWaU`Xt^PQsQB%RW!&`CviWTd!@>GaptidZ+uUIo> zUdD;{oCFt#w2Z}dEQ)eqgj+twYay5c|!C2R?SiUYR>z;n$n#0{82ZyaO&oie_ndb~EKi|BD z2qGu_4dZ(q9{> zTl-%$P0nSf(cB0V&hiDf26Ii%q&W}{>H`RZEWU!X{$4`oY7d_nss)i^mdC?wxZPBw3Tab z%*u;%X5L+@#7)nj<6WmRRB?Jgn;HLMGs9)$($RmFBTn_$ebK0FSx6yNij4kK+yA{s zXQ7W%F}pMKKRneO9&0jsP;mRo^@6l}vaVjUI&Z%N`+R(C07hdMorQZr8mFHSIX8eHwx6?RpE0+{SbK$G{?( z1S?<}Y=n)_>rtLdGz`m1+w~MHhK}djbsKEk&euF(&+|m2_yQ?W5x$7(U@}aGg)j;M z>dM;n9GJQbO~8b5vQRyTE$}?N07G9U%O2OXR+t1kU?w!Z(ym)=7{V}=z+_kj%U~mH zgB>uYf|NZ$L@*2{?QPc+6xkEXfj+O2h0q48V8UyZ0c8){py~B?-G^K2v#SssR=_0a z|7N>Y&%|)*O;ing-XZ|#RZU7@3~YfG*aPFCR}lfjAeaIpVJ3`+IWQUK!5o+mZLkXN zfDs4CGFT3qVdz0?yMA6hIM}ZHKZS#uc0C&A!)34u=0eXy?Ro+9hovwV?t^Wx9#*}B zfbdiuf>9Qt-$O&N8Ro#_@1tQ@`~eC0i>9@}P-wA!h~yZOU^28FN0qP`maFHVwd=>A z&*x+X%!S^?6ebt}%f3KR*aCB5QX~Fh?g<2gJ}2=9ZP43}{g)&VI$$!iYE4Lp!3Wx) z8J56ESOG1t4kp1ym9jqN%42e01LOdy;LW~3kXn(U>DI0 ztm5OU1<+?mhh7IAuzm;e4eiiPCDi{^428-g+yQN{3Yv#?=uI#cI-t*RJZ$4R41+B& z5f=M&=((^A7Qp%u9eO!*T;8D{hd!nby$711*RyB@206Cv zU@feN$6+IEfi18HI-r*%CH@2m%`g&1!gy$b$uJk@K^rWD#c&5KgVrhx^%xpp3v7ly z0Ude=G(!!QMM4v7gr}f3szdjFjsSu>bTdpEO@y!*rmE*K4>rPL*aFL;1J*)q3<-jk zF&$RD4TFsbp4*9dECE6@jDnFc0a{=ROoF*E6&Ao^SO&{rHLQZiU_CqqHFJl49$KL3 zdECKBSOw!@z1fP2Ff{TY2Wlax1}4E;SOuG43v7c9cmZnTI&>cjQ9X=+NuiVlm@{KPM{EA$eluQ|mBJW!3TDIHTRZh4Saf@*?tpDDXeWI~N~dmtjypQ_0%*IlQ?G`J%RBWR=$+cB zC+wp0fo0G?4f|cx{{jpxJjhG$)T4GIKt`vY1GUUf-3HAoI`szVfITqpu1-CoobEas z!QuIPc@BNnb?VW3=p*j$)T?05hEDxFEP_EVqd6D}t6@B>g~=~lNg0NG9@K5@)azjK z1D*N>81WzhzCw2kQ(GwcI`wi`P|~TNg3Zup zAN@KEg$@`EFTh0TwGDsJ2j)S4SO|+@Ev%BAy4CYF^6C}x7Uu6IPoZTWzhBq19k2{u zfX#5(Yee`4IrAnFLTx`0!aSG=linf%7*^e>ABX!6lIK-~TT7O}(nCClMQ@X^H_3{3 zI<0ythWa`pf}!tr>c?OS?13FHbUy*VM_$1)SPaWyIjn%SunHcBwXg-&!yecGz24Ha zV=xFd!bsQz<6-lARszP*!h;;x3T?0hmcSlZ0WZKh82^5!-U<`od3Xv&RZ|FI0`#o! z)Kg#)EQHZVI`uZ#3jGg|rAN^eY=t%$W^Et>42keKjQOBb_dJMXFdjC2M1-*97^S|3 zEclqbgd1QX+yQsM9@qpEKS8y%xPxZc22)|qrz8mG!3tOho1iuGI35lW&}W@`67>0; z+5r7wF^q=gFcTh!9nkY_%FGwE3-CfC0>H!*R8#1ElG+13n<&)pP}pEOEP=I9`-(CK zJ)vhE_1_DFe;poS1hm0aSOD{2AuNPNa0m4Mn%V*Lpx3*&`v$?`F}ML9hefci8Fw)B zZ=HJBduSFWLJLfV32?)E)c-0B8wa~J`eXtbP!YbGT z8(_j|QU+6@cRiig8CpcR0cOJ%SOQIFDN8UKHd-;*FtkF?Ry-a?WzYi4zauN4_5*^! zh#yfcJO!hUpn8}9vwtGRFyUtk8?^j_J7{ur>dTH2Q5Ok;dCIluS09vCkRAWeh ztuO_Kb(2!q{5u|D#Chud2dEUrz-7JI!>E6ea`pRCj7IDclEr{2Y2cG{Yvi3|@dq{ti9y6Eqay(2HPZAnsrTY=ViStPb7hQ!IiUdNOQ< zg)n6_62dm99jDZfap;k-&g{_hVCFc7ejHv1b?BzgC@bR~dNj<2nJ{kxDOC(Z5ZE%w zp(lJ!g2ElT4K_}8=shsXI@O_Pe?cjq=Fm^UsH>5<5tZNK&@13E*anl6(a;G>H%x^w zw>k7Gn0LEF?|@|~4n5)|?Zq9~!@4^idM)gMEwE)d0)9#1OhKfCad3Nlns~wtDyHThu#X8?IwYLL!i&m2&`%(%TLiDoghn2S!vTxq7oiNe@UK0 z?{CQKzf%@qJT!mn(DR`UR=^@y2ebd`&>gS>n*Tx8okDP!0860b?>zq}DgK8;Uk0;b zHY|k2@Hi~DVkrNoLvMx+umi@oAYls;_Yfg0g{NTiuMR!vG^+oN6vO1-5e!~{Ww7`> z34qP84f^*|{mvi&jD!_11(sew6R_-}L$?N<#e<tQW4jp@?cU^ct}o1xG59VGy@}_KqD~h$u7MKRzT0+DLX}E_3u_nC58<= z(4Hay*z|N4JMc6V#YB9b=UaIW>)Un__?L=d+ z4(7rQySwxTc&w7&7bzRBqDgoGHpAL#3gaaT^#LM;Nw64RfYv$;o(G8l=D-Uu7y9U= zyoQKiEzE~4uvoE{yo08<$pX!wMZeRf=fH$_2?w^l*QJ{b1}*=63LmUHjDRrV7+GR8 zXelrUY9CYoOEF}Aj05QN395(w(9^@9*isEi)cdiFz;_@2>Sn>`rm^g^PjX-0}Waev_Vq~c@7ItqY>zR zrb{;uGH6NPk+(1(R=}X|DXcL0HzM#NVi*KX=Meyg!XlUrt6>>D1s%|f*TO2Sy;KVf zRfcZ83Lf|D)}x0Qw6Fo)dJ0S!)UDUTa@Yn4RA z%ixA7-Fho5hv(IE=u!zNe@@a|1HG?!AyVAys98AHS{6~^!C)=$AYXc}wK&hI7y*jP>( zf?j*N^?h)|UQ%qPp1(>0VD!Fjy#zMG3Yh#_w^eV#aQ?M!-6xoU_oF)40IOioTc{4^ z!}GA{01<^C;6Vx*Y=ccOp@zaXjx0GumcfX3a1Sf$y7lBx{J%?rp!X5t8BZ;NNigcD zmAu7J@+GQ+34i7H1gg(JNjdaCjYcLKnA1@UU^(0XTVXkjI7@AS%b-^ng26~w4C7&W z7b%4oU=y@;<8BhqVFWyH#gL4lq=&)+YhgW%|Fv6pz|7wXFq}No(FpX?&gsWs0XzjO zpaUiu&gqepsRhP!dOpmB#qbm?hdJZV={^yt9>&0w3Fq`|X!Q>}r&nNzhjp+#{G6^$ z!6P)mgotx`BFurQ@EF_xn`fWX+o1Wnb9&fRGy!8^6ikANFcU6=8(<17hNc@42x`mD z>9td-{~Z__d60S2IlUEDC7;vJE8d30(G zeNHceJ}b#07y}z&0&Ine@H|Y0-ce{0nqe-Cg8483+F%MSfVr>`S_?1~VJL;ga33sz z^{^B+!5y#-mca|K9Qw>c)%TDkFlserW;Ow?p{zjjz2r4)TuUK^t(1#xS5WF< z60FZVXVr@^v|7*UJy5fq)4if8Brpi}z+`x8(>c8i)@?x$7*lvokC=l7iYW`QVk-he zpJz}#EZt57R~j_W7tZO`&|HbYR}s!W1caXZsYS48zls<`-a%9pLrQDT>4k9FJER;Q zZy=z#c=&)a0&_k(r#HhA*a442|9J@f33&^Pj*~U89QMEp=rteBeM!Wywu#aYH++RX zv{^BDSx_Aef}vj{2sHhjLIM-uao7ZXVkz}76gK>WLI@qO5GMVTl)~e%6~?z9*aGa& zoYV7Q%vrJ)9)lO4xs}2kNBvL2kc=VnyL0*u7z3-|K6nb6z9-^%Jit(x{{tz7rZysk z39v;yhu#Y*T+j>~VH9kJ39tpGK-*6w4DM^k-$Lqt(9h@e=&MoHFSK0H)`bdT3)B{= zrjv#Un!9OeU|tVd0+0O*chK_>R0;Dh@;rfv;RfjN?9tD|^U!-SWotl>ZiYTE3I@T1 z#a5~ph7=w|!(5mI3!vw~9=#MsdiCh7Fae&2%|m*0%QX~QxD0l{Y}fgD&gQ z%V9LEg$b|`Zh);&^X}1otk>cILnthQNw5Xx!wy&s&%<(9F|!AO2l=2ZhdNM4y9L>QdcpQcb1icX~{b3J`fH@`-1VeoZ4@ST;*x+mJ(VH+>Mk3)2 zs2)Z@A3p?wp)eCh!woPI7Qs|l2D4!`%!S8b0Xzjup#$!No=eFh=ns#<2-pZMu-S@X z8HNs+4SQfd^ztX~VFWCPNw5}{LkFyao;Q+3Fbp=q78Gzu>8p?rZ|RpZl?Y>V2HjMmB2)J3Z}y7u@oX$0vll&Y=uqmJoMsAvq85|-Cz>* z3`PLx4L3l4SOi018H|9{FbW=nG4Rwa)c@iTQk0CvI3k9}UWp|Bc8z+*59o`NyZ0qbE<3JHSNNDPe_;$bsP zhAl7$wm}>8nnK}&7T5x-py>`qG%yU-!5G*8lb~rTDT6_<5Qf4XFb~$leAomFrc(dg zFck6N0<43fcM=echL%WD3gh7hm;j65GFS#vVKvNw$KVEd3i?c^tzS-y36o(p%z?+C z4K~6O*gV}z-eG9rK^<&^jnDyG;dyu-mPgT9q>>dd1y;jcSO*JW11yEd;Xc>|>!IhY z9=#2g%|?(kvLKr0Fab8fL@S0i4B7Ak?15qFq-YK*g>_dVF-)C{M;JN}k1*asFP4G3 zSOkOq3lI!?#UU8Xg9R`jmcjzK4;I0CSOS}%wH!km2CsNjmWiY=5mvxdSOxQ7Ei8of za0fgFt6(E+fX%QOw!jY92DL0S2~F@k41@kx6CUh=`?9G2@rx)_JSa_|J6u7bSxkyx zGc1Hj*OI5O5t{BYXy!!hVd)YCf&SN#5||CWvJv!p$_}(7p$T{aR>9n*RL7MF1Y@A( zM(kHw$;)M=fCo`Gkp-~%W&*gIyt#!!2OD4!Y=mX78CJuvWKs+xVF!$c+C8|35wICr zpy#c$6VMyx!&+DclT#4LnnT{+LE(V;FbB5Yi31p!jzF*)My(>C46+28U>-EXLKp#e zz!+Es<6#3Vg$}q6dafp7=nuU!5e#NRYaWIi423Wc?tuBQ3KqZySOlA43G9G7ptgou z0Znip41?7$2G+qO*Z?!318#spS!fbw!)jQaMg4EVupyg5mrEY4X21X&atYvGQo0U- zU{W3t!@~7wYAuEGKAyv#`zbrHc_R(jItm#~hW-zrNm%?K)f+ZHj0W<^QX3k8UYp1w zShkt^pNXMx3)KR)!X}tdK&^m1Fl;>$K0@_^MUPTwV9sL{N*Gp1p}P-Fz!-QQCPC8^ zXcX=!q5Xgxo+In-r*D9Hun-o)M(azo#T!sz84k_9kw7g+#X%4r!l;$aU0 z!>CuVhgGkWmk*HAHyAI#uqxcca@Y(#_Y?kus2nE2<8R>(CRfv9LTmH^hR6Bj5sZiV zH8dD7v=&Xk%tNH`Ap(Rk(EDvt0R3ShjDClf6BfZXSOG7!dJj0ky9`Y}x}O!$NVlmqBvLlZCtwtPx8g68A2-7pbWz;f6Kvp>Th zY=Y67$hyzbB-Fk@P?+6FnSnlEQfN2RkbRB)W+FO{p@0V^-=I2J&`dzE75Z!;ul|8U zSPlzdEi8o{|D<}s3(&Iw&9qRsU<{0a@z4TOVJ6Inh49pA{K49@*jpc=Ftwsm==nW) z3gcljOoAOS7y3L(05B95z-V|JWNsuW7tD~SkXoqfUQ5G3Hbl8 zbwBWG)%D}Yk$dlC6DK;h!`;}#iHZ~Ls$^uiP|;9vl9H0qM5VkbD%#ahQ7}nSQBl!@ zN_w?hl9HjKk=^W;RH(PQ8WkBS78Px`T{7;*Hs<-g&b^zP`~L3ZF`u9FKL0+S_vgB<}37kOfNwbpbe!2qX-&K)CCyt^I6>Ddu6sAs| z<)>!JNI_aR`h>?3!&)(T81@jq1rnuX&&M{G~yUq(eg!($JCc*rBST=$TUWK6e<+FU!Ilf z=)*SpvHxLSwbsu{9vr@i4B-S$p~62ab4CS;>VROriEGv z=4ioDbUw=b&r$FZC}0Rn7{>|BUQ~4W?G^i zhrc!}c`=MZEMGCp{HLG~&Pq*;q3&^7dL@Gp$FHL1IC3=?Mq6lBGCx6Iq6Z^5jQVRB zROrPb4r2uqIE^{fjFL&TVhvsBxR&{!qR_pT!H2Eu=z=G?z&Dsa*na~xe~O0;Ixu-7 zH^K}Sv4l0Oq2fE7k6N_dMBidQLYJZLW-@{yG>p+jw@`76-@^P)Qz#J_$1=*l!MceZ zG_&9MT^=^*L=XCK3=^n`aUSNsNd>;gjc+4Em_jdBF@_CHqax0QILjbYby+T8f4TXd#BNiB;6+ z8MHWrEp(v%K{AwQ{+lQS30N_PWlZB_nw1Sb577c_;S?Gk=E69HUG$^=2h1LH;sp9} zOe8}%nV|uge1utsnMXP9IU0(iX6&H-Ne=uW6+j;w^^azy2nI`xevG`rv*RTes&S?*T7Js;=*4J` z!q}^%7+n*j7>kokqnBAYe#Z$o{%2Z_!*%xK)O!rpACdC+xe#XlMn&Z9CJiXj*Z&}+ z7}!7tf6Q2#p$o8$s#mDc2Xr|q{>S_uqfqTIeSX4V+Dr>Dy@d;7aw`|c{5C2yPK&lv zA)Lk(ntQX-7>?l-T0i9cpK=}sv5KQu$09bdf+mUShm%s2)V#_<9(Z@3G848ZT*`i!vrZ_uvrS?B<4`P?`ElvF4X*-3Zesh zQ3^2%b`=L=3>&Ch$PIr%AE65~7(=6)3Sk(V7{@LaQT-ZSg$6961s(fumcp38F)U&Q zJJ`XfY4K)BRi>plgv02-5PGqQ5o}`)T^deA52}92LWFt@;1CAUfg|X}CZ^DI;AW{L z@5d$@4%#f~e#QJxQ}FzX`MhMal*VzaVnWLSzh)^#GiK0^qv*jL4x?k~W`3xYuEQ!$ zVh@YU$Uub~3Umc#FoRXhqe4g5RifOOLW{r{YF_7If(}$Kr{<{F6MusitlTX5aBS6P zsfNDQRP0T<0^OLv0A?_ZqnN}zj$#RmIDr+M#CnuMl|mcq*gwhWMjiIhjAMsxmi#z* z7%jyr7O;+GR2@!*Fof#gP$4v63@w;IC#KMcSqxzgqj3s~Bd8gwu!0(_qYm3RY+~^J zmQjx-96oZhG>ubhHcQ6eF?NokuQ81g^nQX0;V5dRs5n}&i+(f?ZI%+~Ja%(bs!-5c zsPS98$$XN&!jVsLBlMog;Ch=A(TUTap%1Za;|4f>5*hkEH~1{m7OQqDj_FgVSd}hx zFh($R8hwrttY8A0m_9AKSyKFgni9}s9<5kH50){6Q<%g$=CFlj>|hNQr;`y>qvDTb z4z*}R6AqybZRkcP2GA3w5T@YABnEL5!&t;PRxpKi%wijJ*#9R+IqGl%%{Ym6tf2?H zIE<#xaeZ`Q0n=E=sK!Z6Yt#s>=s_3y(T_n4V+4~ph6Su+4OM5*;y=@cXEAF~eKviI z)9aXy*u@t1pTlwQFl*3?84SF`{C9nx3lcDRn7256J{S56E%P!4Q1wMtMD(Gm&KSWV z?7xsfhhB_f0Mi)497b>)6F7xwY~eH-{>toHPuKpH`R}-hX+=O2Af@lpr(au|C1Ej1V%CTQw9qru!$+`Vg}VMT7m{FpamP~L+7iE zdW_&WmVQRYu!+Whlc@@XmCYG>` zlW6!ADMt$$HgOydWBb<(I`meU|LA$0Su#U~&@>aJMiguWCNO|KOrrY@rW<;(ig{GE z=}WYs@lB=|HZd!2Pm(E&WB-3i^>1hp#&86+za_I+!Ir!|MOQ~ZAjK4d*uV@1-l9d= zLdE~s|279=8v{7i){$K_3ROjicy)m*cVU9?$zNWDsqrYw!#~GmfAI6F7ne zj5L`4WeVd2rm>8QE;oLkzCjJzP={_bU;s@RMk^+<`gghro&Vsxtz7S)+z{3OB2%cv zJnC@*4Om0xzoOi58z~}S!VtOkR+z`E6i0>fv=)=({g%E{Cmo*;^+c*LJJ-PyOJ4h|M6gig&CX%eGF3SA0yG$@pckpnpp z>j!O-(%9k`(&bRGbc-~O&Se}gZ|gX2A0_{D`4%aL{)4%(?9p4KfKsU_Shh$lOs(A_ z1^bkWEXJ^gIn;i3i!{}z+;Ky3TIOR)UVqjl`w(r1^g<1mzx{zt5k$Bh#efo+<9B1 z9-6<%2`YXUF1FF^+afs@Di!W8b0gGTvPJ4&#D!6Z;{mz`J2;9{mr>#Ul!_jjFfhD@ zAK@k=BV;T}!F0nG$*xxNT`u|-8#i$xhNDyfNBGUR_Wg;+w@4MV-o8arFIFlXXu$HF z+z_jn#gV(VNL4wGiUX(sYO#(c9KV|iU=O2d3f|-vX#ykI#29ulhiVO}Lj%^(f(>+{ z>Ygo<4>cGLm_=Hg9a;@MALn=6em)Q-h-$) zy0D9W)Zf2F8bK>2(1TeFV*%4x#sb!`iqkmsz!rYCT&b|(5XK%L#a;?=0zu4T3MX(3 zryiun*iO^OT5A3Soi`0?#hj8<%;3k}bb0W@O*eOSO@EMo?z zv5uOR4DLLG6{{FS_YY_}4&&rX=6{SrgFqZRm_XGkT7Y^?;Si?LiS6gMND=H}3j2S^ zSV1q=&{kl&9Zc7u30-JI54zF$Jm=vQPDbS&FOV7oHAWlyUt~IA3-cH(QbFvX{t!m_ zOI!#QFEd+YODwe*NBwG2`(yeVZLhG@;xLY52&XWNO`QG-^WS_ZEummX>#L*)9hgQp z=Fo@Zn7{_6u!9*?8JYhRR2&t*;C#$u9z$ii66*tl$`q{f;q#1ymf# z^-znI-!cD96tq*M6hoN6FlModRqSCG``==gtYMu%8y0@gjnG)7!f5^jvja0|I*Q}} z$byCAn8!qoE;6(IXSx`Z(RWBOg)&ZI6`N@O3oSmH6VQdKI`bBDSV7lcN&PX59n@nQ z-B`!Cy!|fML&bY6T%Vw8(Tw8_DuRx`F{_4{|5JZw5K++llN%mOO3;VZ4P*ePv4H&> znO>;J8d`7~U8p#Yry6Q8f+kF(4fE*6G6rxO!x)*S;m0xm;}pgTBykEe*u+unVh+{E zlWH_zc7_UK4ntVPIC|QQ3Dp0WL5HRe)73)PZDugz@D`>U+PY-!lVoNq`#%|FbW<21 z(8fIadh{VSQGWslen=nUH0IGRQ9*edwVxtW{NwF@Oz+c`MlpjWtY8ECm0f+Y^(KZS~(Pm6H$OJwL&THx~yY&Lzw>>6+r*xv=}W{(8X9n^XHiVRSIqjZ5+Y=D;d3L!zMOE+{j7Se4VaA z3ue)W1*~8lts{)`Gw6HNV+x0`j$SlfM@Df3b2x!hXE6V#DKrV_uJ7{W^;`fAXVMaM zqUjsl7)P;!iZCreKkCk+uhEPpv}6AbbP2jKg%KRX9G0+y4Yc1#gftyGb zhB1RuKlM%p~e;^#4MF^RdyxDm#mAafqZ$|w!M z%2RZu?02ZZ7npwErJ|_+UYDQ!CezqL_tSLo`7|iU{P$28%h3{?!YuZ%fX?r8BTS>> z0tO9gaT-l%eTFW;IEJx+Nvz{2nx3U$ID%~)N4=K{;t*D!CDjfJ4FX=A#t^3RQ~>QS zFu1^=p{hg+aSC-868|xo!N^azF~-Kp7`A^(pMQypm&pK*{E`Zx=}qE3rZws@ zAEn@?5Se6wz%mw4|66YGWm1oJjNk~SrF+gb%0c% z6`L49y<)4BLJy8(5?feC?N^v3`)rk*IEE3_Dz{1njAIis*!@bBno%%*mFdvO31~nc znlOZ({;g6GZ40(a{g;uMMO!5gdJott1?1<{HobfE?PXvYzBVIoSw zOCgH^EMN%B7{MAQa2nI7_!=uAYO#POoIpF8my!`I>u4b+R&JFnms5d5wn}L<9J*EN zV8*yra$muxVbfMA+MwW~&>tiWgDTX#oqx~on zucpQ5NB@air3?nJfK{wx9oyK#{ty}X%vQ;aF0|tadNBW)D1AUdZ=+?XJBgNEL(R~F zb#!7EeW+MV1yPT2%wYkiv4$%9R>^QJ`_Y0{bfWrXDvEX-$0~NQ6Q!X4IxRninxPp3 z=)?rNFpI-DfpKi&D5^#n-KfX@Q|VLGI2e>TiCt8kM$4~b5ThS`pQB4Kc?RcS&-|Z0 ziVKiZLm>XgC z3ND1DAQg;|@+)Z&My}c_m2l{4GKTgLnYx*=ghS{<$IZ zv|$CESVs@G(U1M#qzh1oDYRi0-I&7w7BP$yn8ZmO#Tpi|hc#5)#Da#}o0$KK+ZYT4 zv}i;Vn$d<9bfXOe=)f=rFpEJf;0RW*gmu(Jwn~~f4Y-+6k0nfE4=2!i3tfUEw=n-r z-=ePxc(IEKG!ZYN7aN#B_3cc@7=4FbjAQy%1{qG^B(|`DZS3ICH@W^DWbihwi;XxL zz~JpX8xrz$?_dXoWP(wQu{+7con+u{Rw%UKFuE~`UK~X~7I7FW7{WS+v5hfQ-Ng;= zW5L4O1DuCloW%5l+~;oQf1QGpLL|-L!U|SU`w)XGN$MY_#hAhfj$;a^v51-sYdXfz zat{qbCuY!xc?@9z1N%>>k09{#T0qVZZLWJX}yN^+hX0(km z7O?dcsmIK7v?Rrfh$d|QkZFwRmzhPfKc;K%XRu-r^*?3yU=UmPGtEXQ^aw;y^8iaM z8Zn7hOrs04=*KY}!6GJb9J5%)0#0HXt60N2PGb`l4|2Vq(GVO%dz3lKX_|l9Cw4eo@XhR=5F@$c6qZc#i$2?}Sfn(Ug8tNaS3xCc0k5On-NMokL z(+R8C#v1lN%%FOmOkfgS=y`({V+AXyev{+TjQt{gj5>6o89iu6A9^r=!x(;(`5&P$ zK_G|aNxC4zsQwKt!xrYSgX5_9Ewco5*hD9Gap*1j_z_x+ah$>u)^HLV*ucQsWb#o4 zGY;Xz+stbRh4Sy|OYC9+{Z&$h5mY@!s?dhMKagsyU>41Pq(YcNRhH3?W_10DF@kB# zVG|pu_%r*z&HditerS#Ug_g;MI)f0kea2!>CCuL8PYBb;&I zbT>&ghHw&d*uXk=u>T)q<|!J2di3KErqS^f^M9Ozm%tPTv57J4Vj9)|q(W%GakStR zI|zMj-ytJtzzkY2k4~IGA67AhEsTFBN)7+TbRnR_JeqL=?N~(*ws07G7)Q+* zH$Wri(TWvxVIBS0#Sv7u=xa1#7HwESFP5Vef)r|)z-i2);=4SxP>Yjj!WP=Fhi=sU zo0SmF7{(apF^dye!YWp=g>CGidIJsk9vQ``k%Ena72W8c!oYCpv4lJu#7gGLO0eifGrGT z2a~9nr2?qIA||ngCDcC4@n}ciW*%-B!xYxAB=3(>n559g26nNF{aYB#c`l3w)T0GW z=tK+p(2gN=V*-mU!3j5;)- z88th&5vn9^fI94<5j8)g3(<%+w4xJT*i&qi;;7zdo0P!_PW@2+{7*q$U_nrBz5KTe?P1v0enHpz-p7(usco0P`} zwqIcW`xkDL3@_3b=tk3`ZPG9XF^gd=U>wVs!Ww3A8gr;9l6utQ1e$OXZCFP)wlIJl z45MPdZBjByK}}&4by!3rR&WUGXu~!-vHv9&B-EiF%@{;GCe&mM)0o9kEMOkXSi%~X zaT=#Es(6_iQqW=xP1r>n8uq8g7{UaGF^e%Qpk*-^!U*br#EOVRIEGFvpby6}gcXdV z>HyA1?E%~P`5y{p0{tbPTAFQ=19RxbItI~k;5KOt^H|3=_Wzg)97G1tj&^jR2fa9q z0gPc7(^$a@nwD|iE5w&Yw@H2q6#@xaVVl%K;~<&%38_aLb})v%l7LUDkst>zo4aP z#|C-ieLe!aU2z|aXxCXiY9EJ4X4qKT?}CVTBaYG>|E!yC@T{MO_@=7 zGATqYTG4?)_eOPiZ2+@5S=V2K8f6d@Nod#kUqd^Mh z&oS80hgA$<3nx)uVPQIh!HKyuS+lX^;)bsiKbs0;^Bm5@z~|}nH&`#wff4j#0)v>w zn7n=7HmQqQ5A)ytCWG#av=|FM#sX%)%nCQj4bhB6wBrPNa1w{Hh7oLH3fnk_JuIPX z{WhtIUhHB3)xRNA7m;zy_?iC^3S)jQfCU`GaV%j4r!ajnefL{NJ(@6&HjG@#{604R4{>c%wiJ@XupC%gjF=W#h?sw zB8D)81_S-B#@A962W^AGlGmkU>QxtShus~n}b?-6C(Tt`iX$clEi}t5z zDcZh6*EG2Czqm0PH<3Y%w`nm>br`hR>@o=7XIi2S6h-8#59f^xLvBC`k?KS>R;?fJ=$;x1L(jkda)Lz5Tl@7vR%qy6>F$kN{w3#qUGE9 zP3H_UOraLXP=_Vd;}n*$iOm(;CBwhT3|dgF-!3^(k3KYE2rU@LsAeS>qL9Ki+E-EI z4b0zzxAQ+9Fi0?ldj7Hc5}I%lE!aRicF={YjqE>!8=?h$=*18QR&SSz*u^%+4&5$U zraVisPs`jFw^Yi0zX4KU4$_IAr32SU-|3!4_6AwTAthsKC**9QB`| zBIrgRWQ1FgaN;y7`d@C~q^r=0 z;}||`yJY-;zIW4AXu6OaVGI@jqk>=FE=ADbXUufS7+NuofhdL0CG;(}E~RGZ9OlBa zRP1YPqZ-wl$q*WF`bsi|UCf~3YPtkl*U<7U9Dgl?3$+-;aV(+!>)WLkX3)@OT^ZRf zMZFZV-=J@B3@cd2X-tK;OZKhoM-S$37z-G|BBpQx$8Zu$Sj9=KVFR1k!8WS4QE}8` zFT6d_evtFP9N6>;XbYcR1 zn7o1cAEJ;U5XUjhU>@^WzzH13Dps(CQ`o~QYI?kEq7kRjiXC)e7ya0O<92BTHJCsh zW>FudP@rJKGFq^PHk?K~Dt0ivP>WtPp&xA+KsSakfDsI19Fv&9QA}eIN3nu=tYfr9 zp-rKT{U6dY)L|XX*g`vY(1VJb7z3!r2&rKoJ4DXpF)2x2Vy5h-(l?m_G9rOGBnVq$UQ>E(D@jn zdjS=Fiot~Hr#XLLZtx6)7qidOwU~N=>!`S4kuinlac057KK`|=?NT&HA@&*6ef;B- z%qsL%ng2Zs!&RoyVp97@PCy+daq3UZ3anxc^Y2i>1N!(CN?Z^vP0rKMr~lwQOt+{A z`u@!zK9Kl-8LZg-A8~ZeGDfhlnT8xhM&v;dqF~!WjWCSU=-Q_z>6XwnID|>`VFyDP zQ1+xEPGB1ieLYF9rN!vRk^Y`Eia9J}4O8eFNDT1EplAhF{P($4^T83sc zE$vA$v|$<(n8O^7V+*I`__Cg)5V(-glPowf$a!d8&T;6#DRg5C3oE$3j=o1bMg#hu zG(sVU8F>emv5jriuIx$LL2iIfOyUTZaTHanI39Qooh16sDY*LA44;4V` z7r4P{E{rKGU)Yn>hcX?%LwD5P>Mx?AMy55IaRj4w3KJBDQSIkKXvHxM zUCW-~UIU zOQ3`OU+qb%BRB!|sK+5JU&fd~&oDPaAC_?#8(2cEsgGY+PNq)C%4W9b`= zA1DCXki0QF*0y8^Y)u85ZJ&1PGbeTx6#sLn3nM# zzjmKl@GV-3lbFF8=CO$r*t(q?VjI<;U4ZQC(x24mB%r! z(TwqX=@P7B3F|nCO>E#ac2RL3Ej*qsL<3sUiVk$48~y0R5gf+E@lmD$g)D(lEMOkX zSiu@D#9{Pf97iyP32fpx2Ja_x7{dNfvi$(l9d!>fJ);yt4>Q_N zpif0Eh+`Qlgto_MA&#TrQ}o&6v>d%pQXwmuc#2eF4}+-vE@K48zSonCpJs4A&BF?( zFpG68U<=FG!Dx*FpR@V3`BdclRNzDoz%XW>Wo1M|o(q14jGz}I&v8MFVFBY<#?%jK zp^cWkK!s5KB3*`~*hPJjE;)%ojd5%jng1CIikBF*7{?aYP`#FU`!e$%J?Oy*hB1Xn z%;6|%eneNHqeP}Y%Z1U0Jq)4h$J`LLm_Y*;aN@^IyE+BmE1YO&ko|<3V*_J2jcM#+ z4*SRHQ`Eo8@h3A~(SjCqq8)wc!VnH)218iDX>4HbXRMH?Fh-&i+>nCn7mR*PzeWmA zr9x#cjNuBILI3Nd5NmI7yn`0M&4tm3<2Zr+r_s{ilVbE>2uCr8xhk2(9vV((`;TN0 zqm@6AIttnv7x*0W6m3|;VT}EmzQ#$cU=KT}dWVI|Nej`16%1qIFEj*eSi|mnjDGC= zo#W3Sb4><2`f%tB=D+J7Jt;uI|4%M}SXVu3`kUD9n(~?LsFkZSM0NcAJ35DZAsRMUNdJm}w7FPUBd%X3944+29IOY4MV`-XqTebxy__6=7yh(B2;tQ3r|Z;<-stMFyy55G)6p?!UW zIKx#26mM+ccU%7aLSe~58=rvnY?j35y@DXR&Jk1tg*P`ye(}Jwg(dq&*xh+^gZTAx z1mnR+o-%(${R;KL3fImHYbG~H6N~w$2ser^pChbYBG-C^Ke2bX=t0EyeOtWxLgBFe zbp%;y6pH_Bka}}B-`B@x<3Afj=^SC@!WbKt_6B~rCb`s#pLPpNjwle*Yc@)1PE$A* zYaXWpW{MVCQ~rP(pz3aJaH(*}0Rc8#oeh$HKZ4QuyB;gwb%?Wa2W*^AtW&*G^SJWc za!ZW-k*_eyJ~w66|M+_Y@#OObVc`h-D};x{i_a%ZDK@7*+#p%RV=rbi&*lVsW8!}= z6;`Tsb62Vn)E+3V^$M#N8MvBafPbOxAn`f24@i;5z>H_L{Y{Qf|$Db9)b2l;CvL(v6ZrDIW8AVf9=?O2lf*{{Ib;Q#-}JxrTg)zcHC_ zNRLyxgoniEsrgFX0{+>(9lM8yf!mvj1&MjZi~WKy*MZ|)Y?RRWLMrj8x8^!@e=Tk>8lWjwjv{pLGj^pVHIv4#BbSp_>x@r13kjhr5c62Gsn(}!Hp8XeMX@=>n$<5UKkV`pBMTU4)4pU zD>m}$S?MILimfVJwz)n!KuyCtY?|fMPMtq(sgdhhzHZ(IZxPkd6-ym_3oz2cTE!WuND`3 zgw>0RlzZ&=FdWYnmd$rSjiC9kjr=U6Jh+y3*mScQ;#~R5z#r8j{(BVsh5xFZs9@G2LFV9x=6P2hs9|YQ>~WwxK#asXM=+}AmWtJOHaSmJa+%{|;`?7LH#Kt);JQra+;S@b+Ff%gb zN%Q8UICH*m*uo447LR5oi6?u775kewZh}zhn2nN84h_mH*`njUB&_v`jnXLlRToXp zuL66_26;q9I3_T(QR>LYd}&hLet|H!$hto_KX#*}QHu9^gyjcTM}uC-D0!D=C1CS z*QH^S+9oD1gsLBjS6wI^euSJM3y-yyjfzp0zYP2-a%_{>IAzs)Z;C&=P*}RAMlg2L z&fxFf{69^X>yhGO`nBSR7t;3y%D%O7FJ5!DARH+7PL|C{`I=EqpI89(uH49K_)l`L zn2}gwub7ose6N^`SZuGDpIBtC*a)%kDI237yK#cx$X*9#iG}ux6^I3i?dp6s6=nW2 zyjQG7EU-t+z;RxB!%r+lS@olRUZ3mv10qBxcSWC=4<0y5(0c05L+^N9&bIs#;XROl z8k=xLGtKSxUPdbH8#zrrQ+{&It@15GRYIe4p@ZZ; zAEAdlr*D)J^3(Qb;w|fiRf|W7m7GkirNmwnpII-gSs3Ic&Awiq%YR)j9K0~iX801O zsCesoUI^zNwDNmgGc1o+`Ss@jJL$1r%1eMe(oTI{9%;hPhjox$>aXykBj5B>ug^cM z+vf@W$C{Tg47tXh>$siRB(YunVW8R`VijVeb3=6Q{)dH$Ic{KyW&cOXplIMvntj9U z%gM*DSXpAT!{(lsoFvvJR+_)0eOTzJ%cRzj>qho?kfR6B&8`ExWHtVib8|8e#^@ z@|Qe4C*+fE*(iSEVqxilPPs2QKz@}~edpIZ=cy>yc%h0ui$~=r#5L#9F>+E@n29xF zyOSzk&`zu#+bI5!3r2lxwD&kbu0@F0^j@(zu@)%ok0KGxl>ofq6S1mxQG<}Wy3Tir4`k1OpuK)#Zh*xoI$6O&u8XDvL$sELv3Vd6Df_2Mt*9~8b_gG;>SQsJP*Y5AC8CL7OUo<@&fDy&)H z7Z~@~h`+s5SiWzJGL08!E)|YkQII#NP*%PnUk3h^iG^>Q8`?Wxlv_ml<2*^`-Wpc) zlXw%GyILmqgO2|g^E9N6ML~K{u*yQ)8(Pv!fy@0TE-y|FE zog2{{8zUSY=cwJuQO)&0nSHH2t|Z^FMyyGUXV=`99GfQAAhxUOa!fJE_}eR{C05%b z#%U`4jW`D8&NiOrU_-v+o>%e`lkd1^EJ#eg+gWAbF#G1}&2HHiu>i4McaUQ}Vt!(~Y9bGw2)*bdW|S9)i(ZqL-Ia@I zn8LoC9kdHWM!t!em?j~Agpi++ zhdbG{$eZl?Xr+HpHTR)Ez&_JebMJ}rC*u7L9Fmq}96zypX2BUUFCx^w3v zV8vl_8`O90PJxL_$(^bq=8)5S)6aLl{OqrpTcz!sV7{B_F)S=y=woB(?v0Xb{y`pQ zGr*>2Zgw4;W;4g8Ts`?q&PI+{k=U-3%NZCaRv>1S-=TFpzvmj+Bw9*tlp6CN`{&;5 zV&r%DKCUR&?Cy!Vj^AItgkvS|B`Ide+%rg=`WlakATj&>az=PetXP<0v;Kfw*L^M* zRvcMmQ{g9H;b@#C2B)Ym~u~c;gkEUoVM|Um;vFkbY$o zFB$L0bxTBDP|zyNuZYJ4*{}JDcy3TQWgsxViEpIc`hc)R%m)RXvOF&SDk!WSaQ}3Z z+`nJd38LXj!8$O`c4K~fl)zrE>WPpK*&JNAyXcE)xM7z1_e5%az+Ud}a?c<(jBT4ncb z@wc*`-;0Z{6;4!6|6cB^!6VNA*9mrI{BLrFb>jN#gw+Ghzir|@Z!W`+UMDP5dj2lHaGh|> zfcYPr_+<0b+vv64b%H_Z`-iyddg0uG$$!en->RZV?z)~HGPO2I1@W3FBWCh?jvH-> zo30m*i%t+%Qv>-+Zb^lW(q6GTvBF-lHnH4Zv3@=ijS}0H1^Ie9V(C3%W@2Vy31VS| zLOe9dr>5dJ7$Z|H@r`c?XZDS4*dz*J;o?5cwoT$qVc}bS@$H+$z8i$=`lfaexk313 zUx&hrazX#$CUGN$wYCp8Nt&HQV6Gj!zFU$WG=#fY!fr|iR*6^ zP8^u%o1wSfkCCIoje=R}=@;L8)L-gidQ%d5i4i-(l< zMT-?D@29Y_8DeEBtHgJ2VibiJimM{@gKN&*KN@Zpv;z}t2gLs-n91&&1>HcKZ8s|db&K6B7@{im%tuS4+%_jK z>0OT5H4EgJk64S?p8XLbR^KZYCpNWLEJLik*Y)zmiu183m!D7S1i`VrPOcJ@8?(t`ZHyLocgZ@vD+P^>8zp}t7 zR`%{1M)FXXUqa2q(&Dj44Dxp&w+TjN>>%;l+l1qmP3>{4oGce_3+02vS8gL&4ff^s zxV0+I%y%ylSH*d%Ike2p`JG|nM~Vg}0cm)yHf`Rz(OBmV9Q(mC`; zUH^g*k(5?^H%=-W9G#YD&B3DeTinUER9yEhVZGA3OnmNJ%);0*QaOJ|%`0T0D<7m1 z#KpG@*A66gGg4A~{tnV)|C2Bve*1Po7;F;UHLT@)$}c!oVtjXLE}ypxhPA4}-N(rF zmS1VQdz>f7xx+WEx85NftPBi_%M-%s1Loy3l0&?*e{h8uO9-lEPPTWo$<8%~R?*?h#m5u$ zNt1oUA3ebqiOM^L6Z$&(88P~*#9YL7)yz#SPRzDa{NPTW*N%h5)9(`2ouWNt_uQ24 zZ!_@1x<`!A-1R)f6~yHsDSych8~BiVi1^35gf*+&>|<0b6sIoMd|UbWJ}2+La_$?w z1&(nYBCfid3EVnFJoj$KjcT==mAM{I-7RSQ9IKi09ugu~+q{Q~r`;BgFi~ zoO6-+p_?F zksl}Se+lY`)eQdW{rS)6y@I>XeKZs5U&3MM7ife3=-quOH>FI>vsbJ}%t>rWz87Ee zanr;Cd&JmOC=O!=A1z*WA5G34Ek1moaN$7vxEVeVJbBKbUhX~lOYWH>M{19s;VpMA z%lSVG>O~IX4dUVB#dRshafSVj`DbJyB^U>WEhI<0|A#D;(<%84_LJh__p?6QP7u$% zUpPToJVCtce&GRS>r`>o1FQl=pA&C+Kscr^@VWWk6DJ?wNgVo|JniS6#O()o@>bY( ziMQT1s1@%yYj8i&{Ggy(&?4wpitG1TzEZs4LE+ee&KdHe{p2bZ!?|_8@E~id=gb*t zQoQ(j-QnWQgTj#mlWdp8YaXJ4Lup}1>2!&gq=nwPJi8;;||CuJm?z6?k4+-m(y|cyj5Ajk`T_-;NkZ{~!_8e-z z^E&dB3m?TaCYG2>=EDyQh5?J4*&sf7;PNG6=={M2;@XE9pbxzANk}1~c5OM^G(4YzM{L`*a8Hr|?mI`!TGYUh%mM zeHyw@T>OY|rZV*<@xn)V0(g8ge1G<0$KVpNeY$Qy{J|r_5d-NjY@lCGzJtGXZIAK7Xud;! zU|solon9O~o}uB-3Yvic!H{^!^|UXU6)ehlLi|ORsT{jg{4h%=1n&~pew)=fc=wFd z5}!=S$9-F{DSLN|Z+x4zMV*|Hrsw18$BB<7#WNqLWfS*`&pb|kY$@@B$H|xXe(}sF zgyWW{?*I52Y5XK}j95=8zPf0TN5K=M!IYNYA>L2%E&a-DepsPGx3#V!7Jlw~RG7L`vjpu(cK=1H>a%!t=NDXbf4Wagf)U*J{c zZ%^{M*7k__A#vs8BjUQJgkzM`kBYZEMVoVviLX8-ygV@W^BKNU6fYeUjy|eMFuQa7%5%edBJYf4 zmXVz?c>!?|%a^(0gStaRdsEjhHpYa0Wxg!_lj|yrWpV9yg~Jz2aoE&cdCkBymnez< z_3%!f{4Rqn{L4K@;F5t9+hy_n{YdIxzbgm>hF`Ow&yQry_gHVV74gjP3Agl(elR1x z`90wa1DVc@)SUm=zxHWi`G8|~M*a|X>ENMa>}kO?Fvd22c_4p`pLm+bNO1Fv_@}3Z zuMJkW@=0W8V=UM@i5Kc^Gkh2Atv8tuSLTF+`?A|-#QSo>k;2sW-48%{0rs!uLCenH zKH~DlgR4dF_XX={*vqAwDVAxnFs63c|h0%yHsV1!jlhc=3&baLgK`wf)ghl!xc&={yOE zg(%BkHvSZeO<2X%&+}cI(ur-x_}s%dnHp5j{k5^-b9_4aOq=C)?zjjfAsW{2an}U zUh*ywpDL2NTHf7lklzt{oLDE;q`d1({=S0t zEZ()h*yhb_?lXMmC7#|5w(awu&Zb`CGkx_!@xzz+T;BdtTN&^t*ae3e_6}P=CEL))ca+|+p7a#o{YyJOY>wMsD%==Wpb-dxKAYd=q_LOdG>= zOh<=Qj7xp*Kyqw@q_h#;sB3&jCuBjmcGqom8qN8#t&O5|Un>XNP{>AsEPsJ~jW3Xm zde1A6M_!ZMO8;U+ z(~G*8R46-Nbln#2-sqEmbsF<@h1QB<#P>+dMryw7$v5K}?^;6{4>TWYs2G#hIcAe~KxLMY}?7H5We2Y&h%q9jpar-7PP6 zpv#8umie#JJJ;SP8((!@?<#zVN}-A5()Lk$71gfRCto|wxiV{q>tttrt°|5C#a z#$1z_r&ghgchGv=4{O0&t>BRdU2~*m2Wlw$VR>-}1Cjnm#PN5sHLFfG{herK|3;H{ z=P_i{p1-?Jb@cs44*Z?CE@W?@yMIo$cWH~=Ci}anY{h?_R!AG) zMESR2Rz0GZx=Fo;g z(|lieY(Kv{u%F7G{GG1kxYRb^^h7!b`P6*+`!;!MC*6~;O^)oOIuE=c%ilr=v3ari zEjBfZ+qJTN@6W1I-*P2|cfahD6NWI6ThWr)O%If~T{d*PZgu!xk@vb?51K=-%}iv> z4=G+)qa2)rl6w4Y*Ky(bulwZeRmOaI6O*&<^%+@Eiv#10nOV>Ti-!5LV74Z=7nJ#i zCU?H%@1kF8!M@JlJyh&+#p}>+>n_q#(IxwKxt6-dx`OG~I@eaf^30nv(zBcN6uc=L zc2kHEJLTTpsA2D0vUfL%wr*Ewp~pG~cFDRP*Y%E$cV&AIO)LI=iQL1)Bl-hNcj~He z*&h7M`amAs!yKUiUg94M?%BgQy>hS2d56)?;9gn!j_YQ#^&{W(K95E(tB}(pum*q6 z*z*oeB6Xj<{twa{^ABADIuLZAL!}NJLKWb@bR z$)fP~uYK~wf6WCF(@TpT_*&-nl3TexS>H>tCJxJvUf12>)kl1C*}JX<;hp@r@m<%| z&Z$_Dj*V?51;|^N8f+WD|gc3JVm7)($ zx1kDny2a$#KG$82YzCbl(C&JSgCUC$v5r(zc6{KvJFX%A;B<@0#;xy0awT3i>}7Bf zKkp!#!PZAeSTAjH^~H>*U~UCmUjABOE%RjlhqRmmw_Nuj)ulf{p8t^i zt3Ffa_A>ykNtAW{EM&BuC0qJwX>G~!ML+pme6}q52*qFGk()nq-5i;}l<>o3^9!gs z$38Nld#R-CW5uL7^`O=ptxq-kbZ(BhMqb_S(&KDAwSb~4p)Wp9KHbL{dEh)*{xPkw zDo6hMG3L}O<)i_IC7vq}>O^f`0)krhlKfBAgyvrOK-hqO&JIam6^&uaY^Rx|Yt%gGZ@XQZ6|hj4pa& zgY5W>zA`aiQU)p6_-keJASG6Go$MTB#UX!_EdQLLK-(tS^f}|;^c&@=&s}%L<(C9& zjxKd{-%dAPBFnyDK_LGYdGrg{x_Jq=9-P+28hy>-`Z96|-s&&xgnzOc)rPr1PQ0JR z@VtMb<9wKl<(!Yrc=_c&84M)<>>y{~t%aG^f3irBSSq{z=}L-AD-Gt2=1apJgi$JU zh8TC&V%I4PDhyNB4KZ}-|M@}mrd7du*q?BCZAE1{k^j3U#|1x>hB|9WcAWWX5C4(sFoN1MI_6r59%mK$MWC&i)t}YEenSkFLl+( z-NUYBX7mFGk80i5%fnycU4#i^D7=bZ=E6+lxJSN1t(83>v%jJpcpj4Lzhb~M@X!ny z=|{*JU8_)=lsFHNt7(`g{2Q@L51`t69+ukw}xa^mL^&y|^8mgj&z9j2L>Ep+`$VxeprXqVrNxl2cgN$yh z*d86_QJ~^C56Tlyp*ni*VeR_fRETr%sXeH67glq2EW8VZ*r!kJ$!r#$@M^#k>E{%0OJoD&5xo^Vt6UR`L9GP$} zFZZ1`GOa;1y9N*%f<;ZaR5k|dhZ!L(>etAI$Z5dwu-*`+;_5yX-U)AuP~vBqu)>6q z@}t9k7N#EL0ljC8OtXM+2|RYu$n?U2dRhf5h4Db1b*cM$Sj$->JOhMb<(vu)Pi0%- zb&G=ub;G(~e0ugv`TjfTt?VN-?V`o9{)lVgPYMv7imDZ@gc?*&2*b7IZ93cw56!D= zSSrk`LR=br0W3d6E)`Y^Q$O?kbDW|Z%xJ4WX@Qq6mihm2Eh1ehLOOqxLvSNxyde4548WqA4H2|0|S-zQMkxtDun6s9sImywq zM3VlC&g)zqvve4k3=9n<>|q+Djm5&EZ7dNsnL5*LI&9d+ zvSIx*7`1PE37*8;e~u!sr|f%HyaN+lhZ~R@mp${ zerS%Q%`y@ksTZ>8W~_8pEgNAe{ef!NsnRjaNRAu+*2uKZ)@oEMq~lxSa2QOX(HIGtUSIajM#&r&FzFgE2_Fb>Xe|k61hY zkIXhA;+pOc))_AeXnq16d%w(`O`5Z6Wy5S^oiqC35j}~h`)&ir%yr71*~Ym^WxyyL z=w)Se1I;XiX>2-R1rJNgaTHwd!?ON3V}rAxeuPo`ig?2{+lxr?lgv}*f4tW4SZ;aT=*S`80a~HPK{1{^Rm!H04zbM|a)M_TR_R#wpGL%%$?( zYo^9};yxbXgsqZvys_R{(m+S!-xTUzU_>9EMIhNv(+R<=bzAr}893fZc62t#oH@qQ z@S%ngx#$JgJjtJ9Fvdn|K>lKf}T6r)5)&vD(?ws9Aqg3}+eN zk1hxNh&RZQ71tlK6R_AKRLlZ%CQz>Ki4MbjQ80y}}N z7GYGzJsnoiZq?PlGaz|A)=1%`Zg9|*flNIzncHRdDaNYunvR(fn!v6K7Fv+ef1ogI z%nd8Hu~b+A%smw!O9cRRv zLzq>O>ZLMW$V9)Y8vfAhntH62dg>Ojy>d^4Bg+S;&-v9WGggpCcrCjLIt?HFv>#-du#3^o=I z>xGdI!4Z-N*kcpSfOXnfF09SQieSyKKwia=z6w~qjn%@cVX4^b6{G72O+a<*wvfNI zw8J!zK-02H6V|~2`BRM)M^vY5;vQEMk}G%>mhmTghfaC^RD(lk9AP+>ZY=G!5tcQ6 zKIvb)(@=VlYJN?Y#~TaF+prA`U}CU~dY+JNEdGBm&;MWepiH1KLYX1jo`X8))iiHN!1FN+KJP50r!EU4$0n7ZcnGQJm&wdu_p&M3glS`dq zfqqAGFcVgRT!3j|=fP@VIsU2sz&yk4(p-tQLi9JTCS)34W88L&F|WKELp=ha5g3^A zB$SQ8Dv{HG^|Fev)gOUSxp-KKP0j<;1O?>WxX*wUOhrO^<{J@9@{q_?uesFsG90W+3Pmeuc+t>_PZKbKX#R{&`9}UWg#pTxro0} z4zN6bm)Eg?rT2yfi~#FqKzCAmh(isa3Wu#Q^+Yc>fAz55E}6ZM5zSziq%1_AHoh4w zP<0p8M!#fZ@vv%GXkJeD)V@ z&kMBe5T;FS5ElFPh;_bJiWA6E_uJH5|HSaY1Y?nzwky~uDeSQP7l|pXL_RTz$yW)+ z$z~O1_f$wK(}Yaz44D(k`(eGX*eN;9X5ar{5ikA!a>oB)$x}@I(M#`MSPx+Y+NQD` zSm&;h*lCytECjagV*XafPL}TsBg0X#TYJ{iRI{q9F$5ZS&-5v(ol0S2@vv$e^S~-> zECW_zW4W+G8#|{6m}i3(uGN#ma{84$lr9P;dW&9$j&p3Mb6wFopT*rW1cDT ziAL1&TFjx{eK$T;!a@sd09G2p+ypYFvFMR)iR?sIBpMM(bs++p#N_RiLkLqxURZ_Y zXyNka5IdDG#je4|s$m+zKxDLiG{CBQWX@T%gqjdLErNdRH1ZtL`WJ09|12Z6ym!yc z1jfHY?XxittQ8ijNHSo}HkJ!(w6P*seF*asj|x~Vtd7C)=vl_MokMB}S<%Z+GNQ^e z-75y9*sCZW8;gad+gKvZV`J&C1RKkS86ixIy8spq^N^J%pT%_1 zx0vyHY_A+yY;1CP-<6HY#`Vif-kX_~r8}sdu+W-a4a-LUV@3d0!JpM}mPELGC`*X;)Kj{OF zDTcQ^>LUgLvsA>d!G;lv-$$1Ek)_r6hId#i%ooC9VKpC*Oz*#FnJ2=AV4-E64(qqE zY*>$8Y-5eE0UK+B^@gxa{Og8w!Q6U+ zEmpqgG0t_?6KKCIc#m^qPkUI-@qQv}QjH{uIoF6dw(@n#{1Y7m?f1PWbn}Ijg7$yY%HpW z>IqA>Le+5TU*du4H~=-wsd2SBaf%%(~(RJmyO@1Zbe7PHtX(`k#8HHX(5rac{!8Xfn(&w<;MD??%AV9OG5gqc4U&HNBwX4z)dQD zJ+R(rS$>gmeq`#LQ4VO!_FvQC)m~(zFX;eiZ>X0BT>35z;DpiX*PEups$sdXW;y3# z<6QB0nc#F{o;sYK?KR@#vSLP$_Nymcnmw`a@pq!!aOKJJ=n4i7_48!*O7_BH7LLxS3PvAYP6(^P zzhv0N0(o?$@t~vmOi8)eSZ-z}jvn<+g{8@g{eam7Y;sEJUu-Oj^PDw0{Q#t9OCd4^ zXUTgP8yg~97mw2C%lulD%eo9>zN3IW7(+;myEM!YfTvV zh#XIsHJQfwaW(0q)5^+&UGhHadb&KC$?{#vw`EtRk+h`#+mr-$dTHfoK&BBEXo%V` zw8H9O>GIKTwv<+0%GO4%SGHbCE$#No-b;*bRs~t3997X{|FR^@IMq>`C9AWH^Ha*c8_XI+ zt)wS^ih6(-PBpd?xEI#BMz&=cw>rkMWzlzy^=4*H(5+Uo#Ltj}v8mfZC)Dy?Hi)}& za=gesP6PBe=?hIPh{nf%40i>1#`>3Ak*`M z8Ki;L!1D6tn`~p@lH3qGja(OY*|0!;)AH|!Wxz7!red}ZKX{5Rtmu12)QWsy0s?xe z=3+CpxULOA1V2L-#q8xI*4Z99`pxih`ZqA`$q;8b0 zIehEFyK&TiR?&-tiv8s3MmdmUtTZb(21`Q|*@s;jEJq%Al!==@&v=~mlvK>WXy!kW z%~zt|nr@a|SF-b7b*rSTL-#b_CU>nvr}f+}udhRW^p(kxbsG8|vgj)0+I}T>U&V}U z;-1l?eg51Ux{Cei%KIcP*VyRnsU77R#Dh;6r%FSv5$`B{ShnY~qo4Sj(crU@k-Y~< z=Wk@?)%cwMm~6Tl%^TAwFJ4X85cWGsT2CWS_#G|EuS^Qp8?oWJzZ;dW+g%H!VLg3T zCAQ7}p>5}S+M(}vvVT2#yXp6G+xN+g&OZd(PzIS%aFCTCShfG0^ziqIb40Vu%`=jc zyv@N<(2^NOHVYQPZ@si+!bWJL&9W(v;dmi-CE+sn7GwTwFIM^3b^lRz<&iHqqI#}zJGbL`3FX-bF5AK)KByQpZFFU zT+9X%n)ZTv_~bVn!dSY21=_|JWZeei=D3?m{(-q2C80Rhs?i*tZnR& z)z?sn!yU5u8akBH9jc%I^sE^t|G36D!!fi&j$C6bS~3RLNa>{+&~=DDWwo$^ z5T@~Jg5|(SqV*P>$0N5oFFt2)$*>SBgKYXam(p&Q$xsE&ydvm&KxvyihI2Ci0`pu;sO8;T1CyWOGth8Qdoa*#q z&h;P6Xu^#n|4rF`oso29Rft=Sf6WA~&c+&H#WvOkD+pnkxb24J!ls@e%>AK}?9AG! z z#;LmP!`!x0HWZ)}^4^j;KVq=iaTAX>cNDNMllzvuUO=TRcuV%{J>Qa8Sf2OR%oz0@ z(Me=bJ!wV_!?Iz4j8_)+A9T2l#lq5TED@G$W9cxrp9QBN*}zz!`C$1r7V%%&9ZbX4 zOLNMAAs08DeO_R)AJSi06}9F6jO4ZbI1EitB{JPMRtIZ`1+q>9Xoj`I()g{H-aBA@ zZ%Im_u`DjCJ6N1v>|(xQ%Fr#F3(>yOyR?y7&lr4C$dZ8vbAdeY8l(JEZa`t>?~DMRahD z@5-(sI_-h?B;_Y`sl)H7PP2wMB|kCJ;|AXkCQGB28$K(n|9##WXv~i+<9FZt{svEk zqUJRMdTO%aU2#oE6n$SY$~SgWB1Yt`Q!USG4V~`E4zxx)W&}8+yavq z|C5nDxQqHomfu8Y>iLKl{4uS}`e=;mrF4J?CGF{N|?=M#874d;feqvxHtO<}=w)!smeo zJ{y%Ee`YMOCiD5TiP&H;m0HpzuqYVonmWgtbqlR40duMUOk&zC^hyPTqw>-&o;E1D zg)w|-h!0w4;*XmZRt&Ss1G6#@tPW*5Z> z1ZszR)P!9jOn>X;;jbN5V0rZ9i;P$ccsMT~Uga3TYx%&2( z(`5KoDpxh;JRLrqCdSX$#cIJEW%=xncrRZBX@rHwVF*?aQw5=y#$^)LZj*~SepXm3 zED%?{C%`m}YIVq^EDe_UPr{uQcFi=*0>%%G9<8#7Uoan51FH>TC9s$;gIZKQtb(P& z0s*^W^)SzuGP{)CJN-*ZDK(PL$wEfQ0)b2ABj(Hs%Y_e4!5r=eEO9?2sxK=%S?Ws- zuVZ4r>?`GDQ58$jKW9{*IV|gcj_N5L)*+X*mhsrnISgI@m2CgHvDEbVf*o--e%75p ze3bbQFfY1|wHM#Ppp2EdF|_7`vgtM!!3su*tCJ_f*(>P0jqy_Y;ZfaS)t3fE-)^|$ ziZLfoMOv#@FOI7Y%gWnn(!Gae)9s9l6DBB0zh3OR9X|#!=jp)Ql#|MgMW;^wJ6JO6 zRSAECCsLh{jLH>d#x2h1urXSK^*r}L8OQV`oQxh5Q9cbkm%aVt~ z;n})`7B8>fL38TD-0pw0^xz%F>CTK$(xzt6wH#fo6#dYjLPeQ0`HA<%AYnH zXF5xOD3?3f4*t((<3wi_=3t-+);h@`A0TLikNM|k#pTRT^1@|HIb*xVaCxVk@+x%7 z{0dZaOXL{k$_qW?q`U&{+H{OOQeiAiX*y$ZdTYp)Y#Fcso}p@vjX^>9Vz@y3cM~(7Tswqk8Ci7|idFD>~;F>e!(>smL&eFs& zo@KOlLdxzk3};Nz7|VKhp1`{%dV1NndFd|nU00Iqy^Hn0v}D=z3#PG&OJw^mj7J@@ z=g9g><1R<)dAyNN*H+JyxxeIqdsLci{w4b~Icf6OUvkX4`$EkIYl|l7ZmMU+w=~dC z-r{(5)+D3sin}>J5|uv2vvgKWTJB~}(f;i*|27pbce9R0+z8t4ph+=+g8Z@dzc2cuaLFeo$i%m z^w|2|4Q<&fopBnSGL#o*=#zgt?_p1^3Uix0Fv8NoH}{Z5lbCrWsJ^Z={a$j%eX-Vg zYht?bUgQfgH%>n>&HD@QWf`gcVtMCYf}FrI(|YULi3FF)U#FW$XOO|OWY^C)>bd4V zV%qT?*?b?x7QadkV2-Rd}ZNxXC|=c%voW1HZ};$ zwy_CVMhMfwk4_{bV7$Fe-)i%l2N`lSd{?$Ti0bL!EqM>J`P9W*@*cumx<*#%ePWGl ze#l5#Jh5hM#{41sEHdlzvFXlB3$_53cKMjR@*ofQ_#UDPcrTYD50O>XNT!N4(9s8o zC976PF&4BQY1&lF!c|H3n10J=-=*{towY`uGh!_j+5e7=We=kvI@ijkhmG4Doma^I zhgl8e$@b-saJtuh6%GksFTF=4Q;BRW9%jHoE4&954GV278L$W&%Y{v@o9VU)=7Zrj zc>16MIAjy7h4tH56RZao8tHaecL>u0>w$H_n&gwu8Mtl`<0O4Z|7J0ktw_9jW`uH< zkZ2n#gvG#AiRz_(mci6*q0Aa$6cSNq80C33cb&*&+gKkg!^VbTX*L#?Ld$}MW@;=f zA%tms5@8zOT#oKMbQ5ZOTb&WN+#W&^QuYukra}l5Wi`Il!rWJj<2S|@-g2d?-&*8t z`Hf*X-0NlMZ>T;cyzS~YRO!a=%lVID4$G5`kD^mz@?^`S^tz?jSe+XSoR2(4Gq1Wv zRzGGejO^zlS=H9>MUEQlK3{4cqyE++pWv^a&p$@fDb1I?kI`8UUnfiJ8LXri$Y#B_ z{z!J#)61t8O3LGOqD_U`yIU%u_;Dl6k#&PS`#4W%4c?#~y0xV4*h)83wNaLDWw4W7 zL`ln?*RZzr^j3CyeMNEr?kLO#ixJV>UJb8}_r{0@@gG&?Xpl0S(T^;$giu=7DwFSO%=q#&Tip zGZ^6)0b6H41~sr|8>@vi+E^2;-p1NtwKmoRtG2O0SmjwZH~}n!xoHS`x%rDuqvNJx zJVgbsy-~JucWMB^&8(9hEjP-6r)UskH_D=?jfLx?Y(?Y44_5A{n{q7vMqD^6Y$7Cl zkfn3u;aWTamF9+fU_*qB-%hnllNB53*ZQ6|VjPn<%KoQmG-1VZQX`eO>n2&J_p+bL zqm9Pub7F3p8E*A5X80jY!_^MD5k6Uh8u5?)VwyN=?)@zf8^zx;rmyW?AVruQ$+yU@ zzojkK-YPrv9{+Qh^9*gP;r20>)Slal+-=V=QXeamozD<0_Z@m)7}=aoOSnVk{!ZKX z6q|%K-XR-dKk2z67)?!j+PBfzHkJkJu(5ntTL{yvErGR!Fp&S?9lQ}9OrqP-d50`* zGS)aN@0>2u-!y4=ey40}V#74z?lG1St#mE>JzZt-uVl;bNkfBmUl>_@5k1haWS_FI zDz#e}*#YxZNy@XZ{3#aWW%6Dno0WA;v3!`XN_Hu8-=l8lmuuQv;Mw=g%#Ti3rj7N% zyf!urOS7@C6~xEJVqu9kmbhY8d6?S<(-AamEE^UR!ZgzhU{N7VGhGu?2A`~Aj-h}{ zSq-cK*=&b}EY=9?zmG{_We98oW^EapJ_M>$pKkSVi!5uV)}_`knDW1ew7!|fkWnMs znvHwQhcmvMu_!&TlGHvrHiM193|MIY8g(%Vv$1$s6fEbYU}Qb8%w`6tI?drqqFQ=XPrWX?8Yeq6(=W78*2b*R^itBF@-X-)ehOX zjk6d7Z^-N07@L=N$p~h1^6jzdWq1u~EQ1_?W%=hmG5R(?58VA7MgqHJ%O6=xiQXL? z)u>$|c452aJ?z4pcQd;<+dM-&EzC9ArcB3G4l7M_Sm*&gmJGKPK`X^ByECdV&$tdNT+s31J}Xl`50) zf*#rUCpz@bJ=R)54+}M~|H(*kX8eN;@vj`kJmTb|uc`>Uluqbf+4N^dIBf_|4fkL8Gg_&QmHt1o^V`Z{>Q<%$ZSPU1{p-A0 ztxVQy-e-0yC$`c#l(rf%;dSqm^M7{nuGQ7V@O{~aBS-uD@}Ay1*aB!ZR>h_F1sj2z z7!4zv+9#X;!uCMSWi%Y?_d-W}pUioIGH(A1rw^lX6i9{^V-bQ;us~LUtgNquPY|on zR#pe|*;q4d$i_Ng12)zR>wAB!e1?ZZz#g06B&^HEVzTH!V1bD1JptAZ3q)L58mz^} zvS5wVZZGqvE+5!n6D)z%+E^8=YTB{CH>!tK!ZQ37*ZnucZEE=iBBC2&LsK%m$^KI2 z7{w}6A0p$?$bMIgRtE*vwD5*&m=^Z@jUv)Wgr>A&N-z+B+SS4|5}~XKR%&zG4lA+A z^}q^kY!H^`cN-jBP5^Ulg3)Veem3TYdHs%wnm>nAVd*xxOqj>U@?Z(DKs`(5b8}(E zKwf&duMGw4ue}Q$(S5S?1-gzRDr>C&<4}*hKvPTmK&NunRzP(POM|`_&}4%N>+zyjH)4SE3P-8-gRBnzbYMKo-V-!#us(w=N`ZLe&75hYy} z;#7;W6uUCZjzjP-G1{u%D{EewdJK91%SOx0nlcVMtQYAJfi?N+~vta^elF$fmZlqB4LvSC&k$f^kzj3)2z(x>otg%b0(w<^s&E z{>8U<+EF%rn6vy3$nl2MIpThqWthH?)DtV)^hFlZaVux{W3HglV^QMYYH4^`S1|U; zzL#0+E5@$I`n}XKVBM1>eLDi4k7d<%3aavBzhHU}Q;m=1+3n0Qvj>!&?F2PgKXLO4 zZhQl>>J?t)(KQ%|x>jl}p@J)^BcG4y%K}J{)(Xww8YnMQ-EJ(l-U`r(u^%B;z#pP{ zWpyxw=ws`s!&o?L!V;6_4xZl1{9@+NA#WXnELfn}HPB*MatPC^PziH?AtN2+UMzMV z|IWy{uNvpYjfKc+)MBne0e&HyU!@E)|EUXQR)1!7?q2mD`|5wnzE{~As2iHu`Ma?n zz`kurd*OviE!eA4)=T4N!CVbv3g;8;gfE!PFnUGWheri0szC({LyDYsIo&cNW=6 zW*Ng)Mbj@O<#rm$;oh(Oqm5PR>t}@(eHBc#dYBE%4`J5G6_x{w(9otX&7m^5_bb`o zsi*Pq)OtU;=QXNb_E)m(HG0teujIPdh*He~T?_ov)A}Z<*XV}FFi)M=fBbbGCW(2S z=4X7Z`#jdR>UpozmwUgK)vpu(LU>U4WM?&IUS6UnlJ+1M*M>Qu)$)i|bsmNJwH$e! z9simUS^oyJt&DMb_6^1bgX6OQ4P(<4QAft6kNa5pxPdhUm?ldvWwEeC7`sK*r7RJa z^PeD#ho!?RCdcFtUB*0D!#7NmrW|;&EXJ~zMVODfj1`e-jzdQW!{y%ZmpVo#X8py8l{??$JuH)$`$LBJ-fO5PQHQ2?IW>AYu)oQ6|qGb?b@AI9?)*D&kWB4|cOSRWVQY zcN_OQ#**aLx7mv7I7g0fkBk2n{^N&Unx2FLmUMW<{w^klS^Q44elH47|JEVvjXsa; zW{#Z^G(;TJiB#4UkZi0SIp31?yJ@Ed_#J4&dIlx&M|7;;61-UMEJ!~@|7E@Tab&kK ze@V@^56#d4ZOAG!G-6y{{<>kcuxS5SdVLT1n0JwE=I+eB=n$I~FL$u9x1)!X^L1YN zw1=vecCjqogUU_3TNjhr(*SOy>N%O1W7GfGN&jpWF- zD-Ip)h>*<(TxZGdUgJA)5xK!EFCtm(8<`(nB}wlZo8~63KQw*B2rKK*cE*p%;PvwS zyT*p_uDnCjU-^o1cIR1{IQ4C-<0S7r5;2)4H^0Y8m-a&58EjlXZ=mSVv~p4}Gx(b< zLJ7i~^rKchd3GL;``r7!u_!X_#zRNz!e!GomYx6czHyfUP-f_r!!GQI|p66z!Rd>kNew0e?9kRFI*i>Gz`Ou7~ zHGIfa*;vF+i6$&TgXhwGG++%jxnx+Ajd@`$Hn%yj4!_(5(;gNAyKIijU_Bv@laa20 z4Q!TgJ~C2V(dEIKrjhH#E~5Mp-P`%w2|qbMWFv?JX44FT^px z@@Gt?tQugiAp4i{>;US&|CjO}cW2by+DQFFEB!W~HP-ih!tvTtYyz>>JRZ1}j>yKw zV7WFH^)nU?LYT%R9+q~u-1`YJ$^Dh=`h*6WStXI5lA5wA)iKs_gS=0T#OoXGnOO&t zODRWKXuI*k>TN6sRs#!-b0MrEglQ*H1}nZt_J7LwfUiU)ea1bJZ#jHsB!%bRcSz3u z*gQ)*KBE^Z!F1X+9Awp6U-@&K-6!)0QDQCpF0pk`kPpD? z9+Wlz(m`Pe&%P5q|B!4~UinZ^z60Kac^K}l_48c(_uR!arB=2MGaib0M8ipm?11Gz zqB6^z&5s8iEig{iyi0h62aLq!Esq9eG`zG*^plNc!5TuC8@YT~-J`PW0OvT>E;N31 z*wuzG&F5xV6|B_%mAllh*>UcEOxApj4lR9L9{d_DKJmD0|C&K)(GxPqXPobBctWec z^=-8xKKEfgF&T3=TbWPDX0hT$gj*133;$w%p?MV&i)ps~vaqB@NE_~ui zG@riG6g?PmOwO+;afp6z|^>nSOh3mLv0N*)qaluJ!3d9HO$m zay~r5dEDqm^p_m`QYVB9jF^zOnxf|udQO3&gjq=w~W7YDO zXJ+PqBQi}k)&^?`VXCLPVRg^QvN0AP+Ogw<7<%qC`Zib0+~j-d#$kc@Sc6Ge?=!qB zoxUpSciKzOpIZ-`43X2Gx&`KYM&=))htB<-tT{yb6MwJu$~vd@>>&<`6=CL?{jYhX z^}|Cvft32JmeWvz`cumE$LPE;M?ZBu${=Q@80X#!~Sm z6C4pM!`$F6_?=1S9O?Q$)%z1nUHY(T^e16tg1J`uAA{MWp>%9vto=tx`8U3*UGVhY zaZ>$nT@?7EJo0beUe%6ekvzAZ`TH!st{gu0M>-TfZ8p0MUwVGc7^y{;AK~qyQGb%{ zN0>oIJTI&NLpsxW$Nqned!4>ktxVPlJntk2NeliWni+Tuk4okFr^B+r$hZViR zd$*00@^0(`wNkZBK6V{8Rsw5<1-c29tAaJ#_eD3N`xi0%Ol^QqN}m%^4FdH-_Uf8mu1dTHply3k@b4d-=Wn%#hL~b zKTHI6$iAbvOa8kKK=dmN4=*(rIa@I1>6AM5;hW5podX#CAJTic-gG zuEQT~%Co&hqvH|s=XFV$g;m`fq(Pp17|mTZ%S?5ob;WEne~)9beM^!4r2}s1PH@g$H=Q=hWqC9nguUt0Sq9RE^nX7 z(=9RKW|U*>O_>{RZi*Y|4wj;3mghIp+L_tIa+LolYlqWJb`12$0jIevE@4kFW^UZ}JjS4s zM}#6xwDKOgE|OH#?2)aJ=J_l8kPXyB9ru*g)62v3ci__cSqtxm=S)HEZJS`x??~J+ zCZB-XD=AUt`EwHd_#l`=dz2 z;6f56k{2DqjAu)->x(Fb4?d$lDL_Z`HA8TzL~VgCVPB z5l=Au`ctVYM(V4!x9lVVyR)99U}zb0b$c&~!u$S1%{k8e z-s04whmLmRRxgcB)RR;a*rY{B1^0MZZ`ioJ@&wP5HXLV0gm+Gv7Up2p8aD1P>#3K! z=(oJJ9E-7Q4CBq=WWU!T^P^3AMu)74rcDk;juW3B^ztyxpQ6o+97V^W;kjMiJN2cS+jYB#UtpPm93d$raKbn%dR>2n=xO$nL`os zWznT4m}|=W-QzR#W#VtCe=tp=UV2Z5b;GhO;%C{ghy~-*dRXNOUw`_WWkZa)(hOS|jA$Nq zna|)a%%^qMB|R}_hO-efeX^bhPCn6$b#`EG^*>LLd!m`>Og(+tT&LzH%)Ng5J~gK& zjO)9l^gDy*N#^N}$^=<{lDROvEMeUL9)+@#P(39`@x|^>SmSFr30E0sj5Eu%9xxg> z$&7VmpCRKXnb+$#wKkk=E?ZKYG_xqYzh}}8Q-!CO-g97$up+ttzi4$u6`;W+IdHO> zv^a6`_>A#>2X@{NmVkUOEO+s^Jh2QNnICILg_nhxB92LTmYy&`TGYNXV5(SXMx0%O z{ZNRXT6k5ku;gIa8csdTNDhX>Vl^Z^K(bFEi}G<(>L0!opF$SZ1=Zibej9Tnn5)4QK@A(4>3Sk=fAgp-FRN%$93a<^AtVE zCl59ha7kuG98(F2PMPvK#zi7LDbtDYxQKLNimZ1L>4p@4q#F=g+=oyy9_pomWj}|C z4PhEs0W9k5DX)FF3QrE0$gPNDTd~hRdpa<3%zduVG_}E#RY- zm<&jNfbl- z2256BO0ajIGaVSko#1SR<;sd!^K@rFKlwOSEKlEPfh9$>kRHTCgEe4nAxwi!X22Xv zH9CjuxK8|@EL~u7 zVC#ERQZ)-Gso1qMv&{Q9CXyjcvn&Uev39DY25=Q#7%*9Fr4jq;5I0)o+F*?#O#SJG zwFg{U)oTng5Fq#!wK(F6nep+o(Pe}%^(Oo+Ypwic^0#53jiYj8hDy~%l5kA9CI&7CFlCwQ=>|4cK>FVa4W>J=? zZTu$sZQaH@Sv<9DPCS!nt}1W2IT*BNW9@btoQ*ZXYG9!qd^@bpCf5V2f(80=&F(>1 zSqKAJ&+$*fi*6owFj28S9#VN0mAUO^dFCuL#W{w927jv^Im?{y$o;9Dlw>Y6OMX6n z)HAiUtbJhrD@69T@xT*a`AKx@t(f!lv$j0koMgJ3{h0Z{pS~%&BZ(1w@$GUTiDKy} zlZA_!V^rTUK7Dpn^WJ!s-fFYDvGTluZ$voQ&UkS#ZW7Doz+y&{x#e@a$c~XFU4cf&}l$nSZvKGXIFL#}zlhem_ApF(*xzy5g%yS){CnRpExhB&6^!U;K2-)7j%Ny=qO7xn3 zrx~zN`j?tfX6x^Qq3A@ix{Jjx7>}jg#{!Fau6b(tAm&hI(T_~Ojrm}`HWu+Fjnu{r zSf`C8!`f}k3)8p}Zg4X)2iR;AEQB@MSQ)I|#%f@-Hr5EMwy`!?CCtil&0^gj=>}GW zK)Chxp+R`*?__PNxyDiZ2YD(L&DOU~#?_qlXIXU~6Oih^j`Oh0iJ$BHQqN-?ozSMa z`|1%&KIwesh~5|Ey7SE~;hF7I%H? zc9ePEyo9&OmzRSDsaisg1!kP1WV^g~fw^*V$M*5*BO#j34rEhb2{H|! z7uNKOKY)~&U5r&aX6m{GSPLvrN45E#&}5Gxo|H%$hrTX?VkX$R${4FBJ9;bqE%k zpjcQ{h@56bBCG}${4i#0xUYL$7XO#CD+B4oGx}|O*0V9EO4PT_#H0bt0ez>T_u+%G zKA9Q=WWY@P@2kPA=vzOCr^z4!py?0sn`BJZV-9T!gEd5La3V9k{AM;37s3 z&DimU(OY%&a1m<+`Mc%Ci->Ob?r~P-I1L;t3%us3j^5p}+)I@o-YqxlyI~Iu0SPJaoT)^d23wV2f+f@4y*coYS;&IWQBSDk}>RNWEpm$EE)OXDaQ8=_2rkv zD@`LVXK%3fWh3M1(-X6@btU0;f2jA>l72D0R@O(d>S7k>B+? zwfZs%w+nOd)OozPFEt}p^a4W*xEl}bY{14m1T;3qn*GmOmtJbdCuNPzjCA_P%tk_( zy32;8kID8+&80~LA$FR`I_&yFm^Qj*7|)T+UCl%<UbE)zl7-OOCH*1lMqwmyt5D>^h7#(l^|&v~!txvSaA5JarijENudv z@7He!E;ARFw_^@1jJ8i01=v_Otl7o}V2w652CKKRs87*&HWm-7_Oswf!vn0e31+~` zY%CX6Vq-5f%*#?PuCxVK&wc z8>6O#$_>DVY-|kH?`Qrl)k^9h)i*>?qZ<$FJUlMt1Fm_iycjw{1hnqvz*<8X$m%VN z;EnJM1zaBfDqy_m=D-@&dWU7<<#YtYq@X}n=yAq-E~j26{9CqOPQ6b3w{{SGK!;CZ zU(PfteTJEjF=f+fW&qQsg`(sK+2(Q1EMS)ZfxF6VGd8^N-_|VQ4C%;bf>1PNI;Qdq zmg@Y51=gl~3!voRGXHz1qp&06flc}1@3BHugt^|odEW9p(^%1qS-TUxH0z50$w&*P zeZ5}FDq&&&36_QCKpkuhIj{eynDroxXDumFL63YQ%o4NLnwjA}{~4FZ)|%f95Bu-9 z{A;cGgYe{U#^tgr%#+Z8TpkSVAp#oV3|Nbe<-!_mtO!LK5T;e57FH3$K-PPjoA=KO z591Z)bFX9-I>sq?UCET&6LnbMXrs$3-B+41j)W-Lccr&)25=wlD_4G!7*Gv><4SFz~p1LWvJ z#woJtDsw(ZGY(Ieshg;#ensn@eOQhwrSogQieNoROda(tUdQR#<&U^dl+mk9(-D1~ z%*i#+zcS;v!!z3QFn*-lSl9uy2P~lZHS1%iSYYs_ttJtcfE>@eT*+%zp3kMMi!o>D z!TVS_lxv>qtibG%J1?M>EV*_>yt3(sDB z*qXPOR|Cry2L&~E8eqjX)(R`Iu`XDyjrGH_Y|IDq+E~OWrLy>N`E--ffDK?Gg8Ex8 zy(hyGY>vG!!^U!8(Kc2H3$w8@*jQ2^!ES#bHNc^1=$}kA!upfsqzz`$lKkYEks8D< zFNCQcntREhG5t7(1I+_L_^zeaM9N zBg4oH+E~~jMnSO95l1Yn$0nBu>$I_SSX&755RYtFGmIIh{3G8y>(oj>Ylx8cR&}tZ zvk%Kf8#%F(59qLjBqiUxF0Nqd;pr)i3a5=T8dxgN+gK4j9)l?~UjF41zXY`d16nmAYXUQ15JrlPx$(MzjH)8ScR zZkS;aKWm32z(RAh2WHsVAS~L(CSYMU7Ck|=@yGE5D;OzH0NV{X)!RGu!GKQt2@5$DOKADXMLOgnF8@#X)UgCsUq0!xI2Ca4OQ4ATtME04c= zSSD;pp49L8Zb+lvEh|8~_gtWQ%72WtfZ=^FX7rTqgfCi8#90&OmC0uk~Op&{%_VDy*IGA}Cnk(nHxdf{Q~*xd0dknRB@~|BtmdfRAg+-~VqWNln|dCT*I|Ow)GSMn$FFK@b%+ zwcT!1m#82p8@5Z(wLzC4IziazhMf{l5EWDnvK6*VP&RD8#3~y$Y!EgGo27`|>~?Ci z`hU(n&q-!JYk$A*@AdlMSJP+i^Ld|h?mhS1bI;s+=iaqPsN>J&shEDu$KCmZGY7z~ zH7nMPcR73V7ptx3qJJ!Rb%Dw{FOZd9w-}upo^$U$b+mf~C%hJ`CFkMb*1b6O;MRT~ zjxqx<%S@Kt=LJHUBbd)qU(NL|R6qZTf64^?m96{VXt77CB~>`LTXdAVvkFD(*DF-v z`)1J+HTisW?>$T0Mf)0;veurDI`-J(WaJ2g3e02Upsd4w4=@8=ik<_M>;dq?9BoBKr?pg3SIq+~4)6Z*bxj4@mkEUR%cHQ&Q{wn zAB|x?q!VI70Zz5Y9F`5WICFaYm-`k~u%TTEP|4OXec*>IGNs zdeO0dRIhOr%tis$(o4=T2CqqQo9QKU9q?KNx09aB9m}fjhq+mR!}O9f^p5j5ZAn}h z>GNDqZKw_$9NmdnGQS3~9^uu%>l0ohyaD00!rLXhZSaQSCGU}4^ib~cSRB)K`e2R- zaEM;=0%q)k{$bfzhPsdO)5DJy^fQHVXvm7{ty2a+l*DRp4ZY+%Yv2_Ku903c*9tET zF4@}#uQ(~KUY@RfJmXwbE|BB(IOR#OUZ5O$$(a_wTb;z|+AE=FIauyaR}Q}tZ1Q-u z3SLF3x7?|PS(a)#F?glI+YB!PPcNLFO7YhLuLK@m&T}n(@xAO)+`ig@`BHV$pYZjz z@zQ{AK@aAWH}kUbXiD%xIulHd_^W`|zf8S&DK6ZGkKK)*li)lozO1ebEQxMkk-8G) z6Fkl~;Z?zF6J9O6&BBYpYk_CiLF;CC&4TNI7c<`2k!2^$1_AcNs}tTZyc*$oC*l|_ zygYbS!VANzOz~#pYz52;n0Bedy2jv@!>d)jBvT8r>&?7JG>#`?SMBZyk2y!k`x{`KcU3m*d(_KGwo!9zudvB*?=rqH6+kGed|qn%fbNtqIIN za9t9s3-V3IQ3_rLKI=&rm=ACDal75u=S+yeD1*^(oO-S%aLkgdm1BkJ4C07o2yZ*Q zk)(p$(J;K>`0PnUa8(UkQSL?pmOz`Z=Xm1<5Ea7#*%Me~4ypa>e z(iS1@5WL|N)LB;s4hvMDI98U9mH4pY@T&Qq-zzaR+>H4e^ZtkP&+$)n@3U_Q*MFj# zbrmksEnB5dzbdfc>A?r@e z*O@1zEULvA+$q<~<&MqujeV2CNLMrk-8B44J`%hZXAahstLLr`EE(5^SbMp;`Rc%e zaeesgoNWBiRFAXrWbH5Vw7A|enS&?mvhV=(d6No}?G7Ntr|iZZH|}lRE7k{cgE7oU z5VMmmJ}bxLbey8DT#rL;7vjmAtQ@gU;Z?bODpw1yU2rjYap7%-*DAaYc+JL3>gQnU zg-u?Ves~S=^mfvd)?s+{g7e~)5VgX~gSSq2VR&m(Je0o-=9&}}{T#g2!dnZkTzGZx zRtm2P-ZJ6E;gtw)JG`PoVRpkz_LgCd2jJy{!@E(R$1UU+*9G>ECPcbOE;>2kmBSkp zUKPB4;nl+H6WKkflr z3D34BSZ?dt1;0GWcNfu*jVQbvc*~MJ-L)3LD}fi$neol4;{MJl)s%0yth*sP)(3nq{-A zizey{t%KiHvD@6?Q1&LC8t$vdp?3h5{_%aZ8*%5fu^Q0JH2^Px{B5mhF9B~T$v3O3?0TGyDPFyMuVYT5E!q{xRxe#2ILOnxT77+eU`g)qnPca~BFMjg23Fuq zb^HyunQZM@`mB+Rm%5_9nI30{@bckp7hW;E zZAsp0l)DmM8(!}BbNp%}cD@QWV1yXHAT@ty7RK$u%YhdXUI9G6@JitMgjWX7E4(%E z9OI4koHZ~L=cg`ABfKHuwZa<|-Zpss!s~+9E4)5<-6;Icsb#bax(_p@Q03A`@#SO-qcuHS%L zYr>bP`!?v)ftTouEZ4k%cZqv`fdN+JQhl{&=>s??9r;DTmsx>%pZfRpx|jV$;OJcM zy0N@<4^%M+)xS=?_=~{earHWedvY7_jbmmb?rbmn*=}5Db)Ud~dSf6rv;MN(c=-J5 z`o}4aje&xtS(lGxrgyy6b1@JSUNyWCq_aC{DY$xg!|-;g>^pFRFEYuWsV3bN_|B@P znlVskH~_FwcnNs*!poY6qh*q(M|dH4>uS`^Hw8|Q?zl2F-xy-sg|`{rHsN)^YZKm1 zc$fNL$4t`{FvF8ye8qr;57%to}h)H|p@DlI}UB`G;@O)Q~jYPwU)xs;eT74P|9K5P3DW>z- zfmjnfyA0avh1V>+UGQ4q>A0TsvO4=~PF=JS2h6ALt;O`4`_dVYhaW<_EywlbElq(Xc=U`O zv13OLs`T3eN3AOSd1_M~T!68j@J8U}3D0*RzHKFWx?9YLm-TaX%WZ+nG8-Cjl-4f| zo2o*$2g0868`Y}Y@$IebX0`Qp96Y;XxT+}!Vugh_0B^1E67bdt zFKZzN&%z7AD;Hi7yp_fq+viJRE=vOSz-u+U5_q^0pzreUSAm=bl}U`=`Ym88lDr7K zc6enQ)vRW$aMLZi>vu1Z)ieikPRY47b%l!-q4I=R3NItc%hAgMZv=VS{sop3!QVRg zL$|08QPzT*q%?Zjb|O}tfzZvMC&ec zdO7r@>)1I6{ox(zqPuYMyZFwrA)e+Vh-uHOIZVa)D~DGI&wZNVOtm86pP+W#g=6SS zn0$ih%oglgZFk}Y4*01`_no`d3C9KIjL$h3{R5zgzOQJyYH7jEC|P%@tu5FuYwp^O zA3y2mCg^hYavE-&cWkwTXmv}7Q7t-U!dz+)H`?UTYCWIm?MerCH&rb!6tMXYd5KLHU$=~ zYT7im%6f5%i|}n!cq`%63a=7gb&?lC+I8^OY*HU?!l*;%;h2HKtb5R*l-#3M-Gj{> zc|e~e`|Aw+en=1SD-T6+52)Af!AXTigmAV~zlz+~ii_u=En_WE*HSlF{}#2RRo}vb zSciK36`aYuwiREI@VeytS}|UY#mCa<)oC~k`3tWFUY+pT;nfIl2fS+G^}?$X-Y$5R z#v9wkox`!KCV_g?mIJR0-q;VXm7o3W0C+tl(0 zup`8`>Hhhk{V}*~dH`2+%YLJtdjMzfLQkYFVf;uOSmEXA%rNPt-VVsj4pxM#y^;(?q%0`s$hskLs*aE->M}K>7Dtv>Y|7AnYK>7=WeHi;@)eGuF#61PSQ?nik9FyBMF0nUbA0)=K z41eCG_-ZprUG@lm57@o0dhQVnBKoGPZypIOj&7Tt7+p8LUHZYc!PB4hq;(ix9A5JF z^B#k*MoDS)VJ8os=4@Tr^hNMn;M-PPfj}v|#_0)V{thj$ag+kr@54jxM0~yXXzzt6@^QdKX*2zj=8e=9aiPAGvlk)M4o`uf60vHQg^A2Us0^`p3b zbU2hyC!Fa&U{=xha0s547=7>LN@P?DuMb`sZ!GM7G*Fb;m#@one{heNr{|B$+b^+q z$fI7H>7O;%t=#4KQoH|HW$BD^;Pt|5cGRX)EXv*O`2AU^K)ul(SR5!kU<}qJviTP&r{N$itUH@2MwkL0a+VU7yZ}Wmt{~wP9=B*mRysl6^>4oY1 zJ_Zc%lDBXVyo>`ADR&DD!t=w^EmKeV_#1&&a-h24aqLcIh?S^|e~AlT?T=%}U4!{f zb98Cd|Ui6w`P=1_~X*|)uY?cJ(V4ze!oqh zJv&5seuI7^uShNW4SpD!aVVBrC&W~Qzx?CSm%^)88-IzR#zVge%wDw`^T`WQ4W?Xp z_3%~-uNmI5B(DVdx4|pHODdlTELqr_6mwU6CC;zF(_39n5&Y%A>(`v_dNELX0>^>) zVd}*v&>uO6E6_u$XlEhxz}A0bE2~^b~Gv-M&Ii zcsdZg{b>x{y4=t6GrL#l8gXCex#DU3V6g2tbs> zwZGz#z#Mh^Gw8gESE)~*K?k_DT%ENYH`dmiGPd>CpxDY)7$~2jUfYg)rdOV(4to}9 zhR;+Rp2a@3@;vp)vuHUr=cy^r;g{lTE>Jf=7r4daU90B)7W*cCOOY}_t@|79{Hp#f ze#hlst1kO3dXL_pByh;YFD&sU!b|bf>=%BE1IFM*YC>n=1yB7Y>b1_m;sqI(CPv5D zx_a7A!ASX%F>f`z9q@Ktq7HsOa8_{5a<;{ zmcM|ju5DM2<)t^5uL47vE7kfJ@MEfxE7k8`z`?ZeD)sdX7}``{g>K9|aZo>gUX}k2 zBde9Q=xEKYhd2B#uq4pGek{WfGF*Ea4i@l=)mH}wW{i(vb`Z1M%pF{z9f5GPG&;7- zdL0vBBEri$9Sswn7jZplE(EU-UUJt}1TRmdErpjOyw&isOnzhMW~yO2BEx!kLs;PC zJ-!*9UWsI{4PNrP>jmtDr`J7s0ej%>NJ)$G2VrhcG11Y(+XgRrjeTdJZxb2j!)q34 zi{ZtDw-R21$gdJ!ZB%5q4(3{sxB=c8;kCe9Ei!C}S0?h?0WTub_QETs=hnZju3a$0 zB13024!a`59C$e*!vc6&!YhH7A@VDOm$*7*lSG|0Fb82KZ_gTd{laU6*9$LsleEIy znVO-q4c>NyEv)`|Se z;jOW0b^Yt=uY$SSn)GVnm5U5x@JdC7o8c9Uv>oum!rKY2K;#$ghnXib9EO)A5_`|W z_7q+oyb*Lk$!i>jHv}(vw_66UA71h%u7KBDn@D|U&{~+?0<44ACA=nhox+R5>k!^{ zcYlc@Lyf%1c!s~=rD!d+e5qQz$Z88Y6Sb!t&!ou@aq9F+{A6^Kau1!5@Eryo| zFM0UAlHM|xat?FBN|^ds7BQylt%IklOOMp_REWO@c&+f(m>Vi4zk)A2J(%Cl8_!&&BIOLk)H-ii5A_Z8Wbks=>| z8Ry`8&iaIT4M9vZ`uI|>zhv!y%xVOS&~qfOYc;$uyyW_ca7}6*`F?~J1uu(3vz2$ zKl`Y-QBC+mU`ep?MttD|YbU)t!$`N|Ms>~~^kXX;)#HD_Pj`E7QWLr{cBzV~Q@R5; zczSMC?{{O^7P<|ur@$}`k5SqBdf-ma&U@5~H}rSk`_*%A;A+6;`<3U9fvujwht%VL zMEcc_sBiv=VP4hvC5;r0GTJ>3(yEWP5X#OUR9uV>v;>hw1;*sFgkf#1TpuWfgK zFxU2`K8*r%o%u?-^G%GD1~A{De-nYKdK2FkE1yxb-om1HJ)YxL_@@{jzoa(39XKpEZ;% zy7tc)Uhn);J^p8$+VA^Py`^;!FY);^nqJ|sI;9`GXv46&xgU>yT>Edm_q(U~cg^(s zW^BIlu%3SHiC}PfVKnQQ&~w+Vnl62Y6kV17NDt z)vAwBmxJkhMxT`AP4CB?`wGi$JU1zQmzkU6{$#1?3XJ^Hm1h7CZ%iQY=redmR@ngV zI?BjkqPhVj@|ii4XxWuGd}OG{ktnky!(FN20(d5BO<5k!wNuI8QR(MVDy3NI@ z{7-NaHZ)Gxse6K}>JzlON_XC^d@c(uaY z4sV_Cy5X%g-eMGKTF(H?H3Ce)TMbVyn4Xs5FY9Uy9pK@H$8KB?z5OqN1?koM>@kPC z{=eYs{knbBr+-18UF%cl4&tlzz!dfMAo}uw9CiF(1Ls6Drl+oQMHIVOZmPEy-mviM z;O!D#6TAW8#o_e{Z#%pm_1A-n{?T zE-8&}KBe#)lRTZzYIvJ%N<0EGV_ZF)t|QgozQj>w%~5K_5RMe}uFf4-cmrtseouQl zTyK`@A3}Q@I7)pwgdMtaiCXX#f^|!D!nxzJevVyqiMmpIoyOZ|HN5^MTy(v#r`5yB zI6AfUHNzWOlIpd=8x~$Cyj@A2-amTa4Zw?={o|~^;gr#`$R3<0cQ0p5-ZVYC#O?mg=ftBdS0FL=rOyB?{4>^Bd*j{FIaKwSFwz;sXP zQg!;@1B;i|FWr+edM>#U9R@sGoZcv9@M@AgUCbJIYvFA(qq<#x$9eu;$Lzs4X^wtp zMcyzvwc+pXv3KdL8OG(9hGk=Al_HPu28=?NsZGOy6$=`d@7cR9=|o`+v0dNaGkW;b zWp0Mo_kA_xANo}1v3jN4gVb67z>uh5h1&2B3@X}JsCWK>vsoF(?ZNd^x9?f>PwZc@ zmFoC^qIb#ofx7RXI2~Jk{GQQ~tX{{4MpPTT41Cs;{!-8aPjl63PF5gS&D$N=&(nIm zTCqE@-ZQvL{eCxEjB}FKS;~hOm3jOpsbB)b&Q9FTod_H}v*6^h#-TISE4}t+9CNfk z`hv5fKp*DwG=QlBe>=epz*}c7!L8a8IA-a{DSJkr{Gk`Pu%uofx{qQ`JRZ zWB6E6F}9!~gjOO}R-xYiIxuTo_2}oh9(pSDFC41NDsW`gPnU`O3qPB{+~~J0U5`UZ zR$igb`WJeo-U{{bzc5fA0^`0iink|>{0l>0?`dNR!$`PoBhEd*t1{2ZI$|U+V|oPh zdf1|;5dKEMz*Dn-9GDpl-GXno03rzJNe`Hc;H^7N-8X{qPzz$+`s!t_`fLObA1^$8 zk9zm+z?=#C>}@x|%G1@7f1?u}Izw&xcVIy@XLV}LSKo^JK9fAXB=zt{&KTohx!pkv z{9W+v((0|$PR}+W9oqqK7@YNN`o3E|Q73^w@@QfR@R0B_nsC-kcz$^O!YhQ=E4&E2 zZg{$;Y{BKD`RzYuRxv}nlzRKr5;R|z)%d-EsZm`M$(ii{qia#Gy`Hr8!t*70x)yf9 z%YtWD*0LG5;Z!huTdq#;ho`rKW%aTY8cyA{7q=*fR;$(hg$dzP)m3m1Z?r`P;skJ|TqlvJJ(EX?#?v?uAND&HxQ zJJE~4vn#DDq8whn@T%bD39lAjPLijWAOPRhW2QTO-ESW#fYW%&Lp^0R}hR<)~}M1rJ=% zd&yYMyGz=FaX^w+f+eVehlkF-H4gPue<@zG5Ionj`DbeVKEV~4D=*U{G50Zb{rdz9 zGFvgv`%m({!F*5OWom^txMD&1<*7}pWD~lpB(E6dl)+nhxq8kUT5lqqHi=^ zKPk8>vp%Z77rHO_+chaz;Ay~X3?~N{jSF3aZU#>r$CXP}IXSr6v!h-;H#xY%Q+d6b zuy61Z&zhUm`hA1=c61XO%v1iE<0>D(A>$_X+P=Z%ncHr1bM*%ElzZwa;=>|z!5n)w zQ%+{z*gT%gl%?7=Gz8OYuA08#3(n8%xLF???X#J3Cskq1cWgoZz{hQpx8WP?s%$J) zPE2irW)8-5A?|sQtSM;0-i>?Im*)o-x^F7ze-ImSqdI;HIx3gn=sr?dzx(g@slkkZbIaH!j$kp`;`r{4RF&qcA?`H}d2(*Ss}zuXDcDXkCfSq4 zZmh0;iX@)9rqg6>8f$|(O&ikS6=z_BQQfO`W4O5IntFdeUBko^8+C%X$QT zvPc_(=S}iL;ELdlV7c_(Zf~Q&FPqe_rvavz_uXW{nf!6yjy)S4c%Y< zCbb|JO{e=lby;q3xu~$GRCf>I^-mHp~d#zNFys)UDq27;eyj7eOg{(reoX zuL_-^xIx8=@ICB^={2;9!2c^gIg7Z9Uf30TC31@13@*>jdvfeJq!**> z*SKToNp;vPEJot#J-FS=J)eBjEaX-BjNXCF6P;(F|G|0WPiLXOUi++CG&{H=J@x`l zzUaHZZ+Nv*e)1G&Z~ce&G~}*{cMazhF?(M%nlwlz3g{mjP6bQz?A-ur*Lq^ zB4d2U6F3Hfa_?=$k6uE-oIu`=v5lu&S1Fh*c=_t{jX2ZX9SZt989UU6q2LkGA2+7A zr8m!X+Q)m_W;)&D{Y^8S%@e(eJg0qP#$cYaZKAg~&*_=yZ_9HMSzbh&Ce?d@w(dJT zt_5?sIU{+vORm|2nXW(xk-A{B2RSz9WySNH&3P?m-`u-5?KxbG#Y|h8H!;r{Nb|PL zbE3P_Hp7agd+YXdTGF!y^PPBlGn~$hrnJWWoSsbY@H}VRxSWA`PS?1i#(bx3AMeh2 zPRBl3+vYht_Q8{pou=`=9dn(L@xJ!C&aMf*mbp&v#FE~*PEVGvd9Kqp$=fj3iB0wn z&T)23&gh=w?DToT_xP|m8>87?q-x5>=bhPJB<;zrMyEW*+ZA$#r+7PNJ1tYaJ3>zH zR9{EPiA~da?U?2rMs%9DFXRm6dbfp~L~b3HBQf2(Ipoy&OVLXF{)RcYwa?o=+lkGn z!FSs{Z!13Lt;9CW^LNj7hV%42IfDyl>17$3rI#WxOD{m(Y@K7nY@JtZw$7k=wocnR zyLp^?bsqZP=hO6g+=zesG+l`!Q=DCC*vd^F-{xsfW4ga-nzK1QXE?{{N%!{TI1L#Y z15=$?rne=>Y0j(#IL_NM#c3J04dr+5)05VXY$oI&nwa2io$9nr%ov#B#In5IQ=H~3 zG`j6szHL*T&69F==HRZ&oR0DwXV)ZeYmU=8IiqW;)9lM>%5mC!-jS(Jzb~VHs?#_n zv~!BnHbpPmwkf*Y?NfA-s8!^-b4s^+EI@n6aG0bcJQ zIB!;Ww$n1+TL*5ux7FtikM|~gPJDuIm(LkOi}vBMf!+?E)0>si;B)%2bhB)jJj2^G z#c7(HHInVb_w^>Q#QS>VSmJ$$(jE1{yx=1BV1Dpx_1J#FQ`FJ(gVTS!8hdRN;n$x|_6VqDL(KH6r^R`cPVj141iD}Il z?YOPAYofPjV%oq&@5scoUHbJY%~{@fR$6Noz7b%#)F0*tXFd7${9u0C{Gq8?%?q5i z9B;<~&W;>ktib8X$sa1fc~Ec9e4HW8M?abCSMv&j-|Sn40kU^9&Qhg$`|xN>6+R$X z7Tuoa-#*3Zad*0eC#PkK)0tiZXE-z5JjLl7w;G?Dyg9wP5_N5Kdb47vf$`p+Y^P^D zvQLcn>*|@1)0geUCVElN!;|&48JUb=>%RV-+0N!{-wveD)@in9>)?*;CaegyxY~O_ zFg!7wKJ_g?a9Rpg1M7a^*K4!=D*h5oJv)8c+fw-yADGKOe5;z!-KQaBI@ki z8PhdXHP!!#JqWvm<6r1i8*_8cRCUEc-;CD3r$)U$^14{~B$qn*_9KG6XzVKk6<|lv zQlgAGqsf(HyU-?X>?G#sNK|l>JT+S_5Q;wu%B8$ zEvA-IE2x#!YHE$ExFw>FMvU4_EoRNcIp0C;qIOf`tmbxV2ep&hMeU~cQv0>)TVe)j z3{ewQJZ-?OdN0*S^;;$9qk3&RYKUB!GtJGXf?7$fhU)U2IvNesW~!SC|Fv>HPHm@l zP&=tz)NZOxKg6-(*hNCKKwf8>TRz4*#_&@^)B_5+5E8Teel z1^izY`2Sqq2ljhR$Z;}JUh#BOA^kqHTm{pOHcw7nPX9DBKd`USmE`+44|O*{nDchE zKCPn|$+_zKr=t{@<1_&-uSB;DvGlFEZu3&0`rp5Bg1o z6wNmaG<1N`@H&Z>?6)6_J%``&a>~OXW z3?k@HFxfaZ-b;TRee8km6f%C{C>Ua(p9##un+`>X!t59sYB1epNoSI^jzK$BBHdEtbzMbVP538pe^?hj;c;^>J<9WvS(zog#XMDS2EuX8ej|t8?C-z?o`v0+< zE593@AFVsZtWb;^51IK^&bL!Lsom5;YJzIh+4aDWm)wsY+k0_7J#~JO6M5b@;$^V7(2p^9rZoLY7o0s$6|~fr3+LGmk0B+=$z-$cY~hPKwIab5Fewv#4eJoBt!A)*SpD#z@ z&U#ZN_qf)~@52hw+NaY=&roT>96SqmS7U zy*wE5(VaT#ZiJgfH%GflS7CNLt$Cxl-m7!%rky`(pMC6D`u*MXZl!voX1xkrD=mPP z@Ewbl2+==qG=r~}Bi{(^!clw9_k*)1Rnq>Bn~Pgvb+p2+r7JAEmDZt5oM9@allEbw zc6KSwgMN&kWSohUTA{Oo-tm>SW--&$#=tcE&i|}n#`r3Fo+PjOTfEZmn(q|JTn)L5 zq_lP4;?-Pb%1!1P$l+^^U6x5PdV4XMWt`NUWSOET)iF0s(P~YiOd;drw33&%{ad^a zddbVy`JdjT;=Qapv_&pk*OkUH`;16aFz26eo8^Dc^!~c=_)7&P1`=;ECeYESKXVUw?s8K*-qRrP!!rdeG(W~Q2 zc67pYf3lOOQ^v0wYY~`rIytYd$<6Vr>Jx(AX!8vQDSsKKLoju`WHj&hMq9d!R=#L- z^Zytfp}L9i-*{a^n0lFC>Fb8`|Iz5c8%DeSV6=Cqt5GN4d~iBmF@ZQWg9EF6W|-A$ z;)%D6uHk&ypUiyTn?^f&jCN7YVxf1|6@n@9bF;$L?`aMPqQ*XE;2OAa@V1%nrxsG{ zsctU#FWxXs{kkl8=)}_N^qsn>-D@Z5F}3oZ7z{~sK`6`T(@@(T2G*bTRClA9AHKLRKZf}!;P1Y!ki3)yU{PK-z z!K&b*(X^54%@WtF`p+dkC*<|&R*Sn1{%@J4#(n?$H4UEhp9`}fk`)T+a$8htzP((T zU3VLQU5mOUIemM*S(*Nmf}#Io_01^%&+1c^LsX4bF-V{MWe2kBjHn^|bR%|I6hm^F>nDv*ZPnZ(oP2-*t9wGe-VXsRhavsqail zn3PVfs6Yi3{?~YFzF}WDWr6zsYdWPXXw|ON1x_kAHQ$KHci{Q|y1WZc3(g8Q{nvcm z4Ib_J?SD&e{B^9iB427lD*CVGrY^5+fQ_l?vXWO+&HmAh18(h4%ZU1NCc7bcpPDmsvU*nsR?=8TEka=8Y6M!CMH96iSskeZt7()|mmzSW z4s55fjk+0uyL2FnMmx(`gEC%0U~UEjaR$n%5v*z@{t{c%gfoM$c?P#U`OcZaMQI-I zgKEMLgHKH8-D2wDm^AglnZc0i|6y?MlUbF)HEFovMtz+zV^*~IHwHmA?o{)HnU7Ih zsqNHGYBzO|>O5)E`KiU!QfdXYh8i=9>lrk_v#&mH_=AaE%&081uR3x~aAwqAim7|X)KSJFld|ey zqp^iXTMjT!~)QI#xjzGpL#G zR+S3h0CYzz7jjnTpGv{qTJT?3Fqf+PdOWfQRPHkD7 z8t@BQ=&zkL0a*|2Vbga?-RYn^)pU3&q6OCU>zhSwVucOvb z*DiOLp(2eVVT7Xfx+qsk#O06UO0p4QFe% zgYizP?)~)>pAHjTKjVW`y>axHfTIM*@7Pf%`~X`n!S4yso=u2sFr5BUr!)M4;D%VB zRlO4WAz}g3a*)PtNJS@HbT_7PJpch<5WEo(p%wr!F3#CPGWSB(+6bD zH3+Wrkm+!77X&%oo;3FhmowK%bsX;{HZ|K%)gu=T-YhaqFz)=r@Y&=x3eL}Xh&qK_ zQ!=N^w>w*L*km{ro*t2?WKeU=$f_P1>#cg1;3DL#>Rk1vyI*i+;N11sAM~UvRD*2- ztYX}%u29YWMsRiHtoq44C%9H}P*eZ{F2v>GJWEx2xSR`t~ZT{CYBu9uwE zJiY$9;12{iNN|Wc6O7(-KNVbpap#|=24|7`QgB|zOW6y|CO2FvKp#OrHAHZa;6jXt zsdLa9PCp{Txiacpq}Ds+HzIW<*ic9Rc)L+!+*9t?buKE0OYGHJzJDC$oLR-0l8ekd3T#7^ivPi zWuINZxngP|QtS1ZAyStzUPfKWQsxP+g7GTqB3(+fhI3ZG!%_-F>N;{(!{Bs-3=1ws z&gwzrju2eja8bNX)2#f#1dkD52jf<8A5SLiN{s*`1k0$nJm(Gpt`S@{<8@U1!)V<=8U)wM zcsmuxVwa17)BVNh)J33|TB1(8Ht6?pEI!D~q2Q_*uc01C?lZx~7;mMnBsUCBmp?jn5a^=*01>^7|1B~cWIRDVp4_IB~>wAM_mP1kGX<^Yh}Eh zdJ?&rg6m>D+RqQ=1VaLJM$G#8s3((~C%7=<5$Y-A<_oTp@fxF1=Tw3R2(X!8oLWJy zP;i}$_fk(I_Z`6{82A0#tkCH$hxT-^0K)`|sb>JxE#y$aMHnxou2vhD&G6goE9jo- zZf5IN(LGCDvucKaHRo!mKSU{dJiFvQvxxZUPIZjOsFiRvcZ}d#8INnd_2LOrady+2 z-A=cYdXDZBFYM-AFZD;rPdBLL@1>SK$oLR-4Y^|lmtfrLkIAik&;5peXw>_S$v8yC zZ5(caCy0z9jF(ZX!0FCBof8rjZx@h-OFER%?&LyZn)$G|`UZ=NO&7#g1MK$w46sKMcPJd~? zL~xaiS5q%h&tDewU%*nr)Ju_4*Z378wLMQ4A*avb=~C7Uu8i?Y>d%av;Z}49=Q^oZn(F6VH}xug{^;mvFK7FySEDHX zg`im!m0;ZGeh0+5gVDRq{elZKZdD(H^eS!j?f%fSm-psrBSu5!@i-3F`Ia{wO$anprSE^#*Vg zboIO|zzBgd>d!TZzmEl1!+3*La$gEA&UicZMsj<=>GDUXZUVj34T$K1)89|+8WW5= z9eIH^CSny~garxWxOKF54RFLMu2sUH&dI) ztrT1b<6YF-$ekj%LB_2{ZwILN_euc{5wxnvT_`v&?-a7yOztwl`N&zl!*EgO8UgwV zTD_AQHVUqQoYlL?DZv$!v)TeqH`e=HE~)*O60~|Z!AC@f738eq&Pcb-Y!h4+Iji@O zdoG#N<<}6j+Dfo18H86y&g#AJ^qRaOxCU}o?<4oF;9}t1_17QtbU*%d*E%4;R>s?@ zo5}4GTo>cL)Cb573ogO9H#1is8gOt>Y1#NnkZBg9fchXJdi_R3@(AN))Hu1!Kc{w6 zRgBkAA0jtda52WCt^DvX!RZ3*V7!a^2sqtagakLp_z<;?`7ID!_!_gq)Tr|-fVzV` zM1bCL2DG}B++l+Ale79LIDJe#LU18+R@+?;Z6PAS0)i3hV*qsv`M%&P8Mpd4xf29e zMXrYWYjUS*ZW(6m)Igw_x(xwc@DD|XamL%JztLlzXb0!Is81lJzT|M8NZreLKlMp4 zy8f#Kmtfr4$83iVF#33Mq2RnGj{6!2J_SfO@oE8v7`OT~7`=Lz39f*g)n~}97hITJ zv8&jS+X3o*=LP{r2wHs>jBdie6kHiOtIv_ULvWSkto~MWx>LDdfYk)8b~3|X39gQu z)#u4QDYzIpt1pmy9-J>KqHGV~8*iO#s4lw$__@>~x$XWd#a{XhRDZihf z)fWkVHU`4MJs0GxzC`Yyg7bMz3-;V1y@JT>YLd{2PYj9Yz=+@RoMPO6Qf#Ax>SsfsEsNkx}S^bz?Br3odL93q-JWg=!{RI~yXZ2s?4j$#${v!mfju1R* z6oi4PlAP6l!_x~`D!2x6R=**4lHlS|f^q6zf@cY^n{lgpjIIklUvLR>&c3FG(!lA_ z@;bqJ8IRfz9)SA$Ppts`1g)l%yH0Q+a#l0QZ4g`mIcn6&B)Cz4VS-l2k!u!QF*&RH z=S+GFAJ`YoYl$XUQgoO@|y`--Iw6oNuXZ9c5+sIQr)j1n2nJFHrT9=5)=ZeU#cE`5E{7IR2kTaJ&Eu z2wKf0mo2zba#p943ka@?oK=66;2Z(g5wsd0cYxqp$yp7OJ4kTt8naWK>a7{T{)MW1zc$9ptPoCwGV7y2x4mKDm1Z z*Pp}Ve?JqH5`0L23C67+OYSkj`KEExQCEL)Tm?C+ zKOpzI;Ht@4jp|1u>23G602>HeJ%QW@f@>vbwT#?f1=m5&>WPMnI$sH}o1oQI%y5t3 z`pH>6iCo&psXg2fIjiO5#=Bfn`}gLWZD;jlg4rTNKRK(XkP8SdOwQ`5WzdtDk_?9}+lCWHdz1Y9+a|1?QX2-Hm!Sx$^}VHgWvGh~PN{FBV`K<5qt}?h3(G zk+Zsn+%?)pN;h6kIDgtLKrsLvS7BtX64GH@15P*hSFl`ONSk z!S#}}dI7n|1UE#^@taL^A-Si(CGBiDn@u1@T}$wJkzoPj5$aFC>BIHQf~(?wUP106 za&L@rru-@b)zqI7e0L1gI|H5#Y}TOJ^5g~t*THxv^klZA^1-LCK&ey z%mQ3WZm-}%jEAY~$az0W?Ey;}FOBlU&j@A{EIq=3$T+w7qyld z77MPM@m}iH;Pln+#e(Z+e2BUpoL=FhTrRo&2hFziQuTQN4K5WK`WY{v){*<3;EEZK zP_H3(Y%-_IFC|bxy_Vn)l0k4)j8{{yBX^?UY8ba#Pwr&F)q!)@KgI;t1Jv92Gy%3U z-cG#%oZjEh5?m+aUDTh0(-*7H6I_Iix;L1+2x0v6gy6*jOkB^_O1)8C^I&j#w4eDq zGt3s-faH49UnP=<7`OThaC(cb7hITJF|`q#UcYMvS7ze)VFYunQ^PXBzKqK;^d5Co5cX?HNIbf?F7518_8`E+#uslo~glG$UP)DKjQ_|TQxTe z1-A(>X-lcA9>g!-OPQjAdK*&ew)Ln;SjD*2+rjBGtlI=vL(Zxq_l)404Hw1Z^UbR1 zAN{+hYy}u+-0B_R^tOCia2@2V-bwCt!F7={ifwck!M6q2OVDZyxeo+4NY3irQ~&xQ++RUT3uxoUXyNzoZ_-{LCjry%(I`ZM@*zeg&W1 zshB{VzYe{RV7ADxlw1|L`^g0bS7ABoW^(h!I8%NNfd=XW1PjMNcLAFjk5jjhJ5+ET zjCWBVB)3Fxy)!wk7_=D^{JsDajC*I9P4f`BGQs&7?_kY5Ozt$n6_Bfm5`2WGM=Eell!^g{IgBX zg{hAjF6!JYz?%7{^;&%#ApSYG39ghGS^YI2y&|^@u8f@3ZKh!74wp-6{}lwS{sy4# zXj(;vmE^2G0Z#8ualzG)v-%{t$C5c+evF{i4uVf7gSr56R-YpGJHd63v-&hReR$s~ zxGr$+`s)vRdWPUz0vu%A>UMJdf=iII`YgFm1?LU1gA4H@)^h}h1?VGa^|$1{5nPCz z)lPEW!PK6xfSlFm)3E-!YNiOVn4r}cm|>paO37LM9l7~}s~~4}2f1)mfYk)8{tv;$ zf~zBE^+j^a1lLT?>PzH~CpX&u+X-6jB3L0Z>?CLPWpd{Tu78TD`d;$CC$~10i#q)T ztiD3E;USjI=NTYZDvcEOc0L#uxz_oCp+$XV?H7uBu5TYyyrt-i?& z-w|95Ije7x8xULrIjesn_r;*NiKUsK)n0-LkzqSIt8bI@{55rd?;>aQ9dcQt9NT{{ zL96c)%pC>Yw&x6zv)V^4BsgcTX@pkaBey_sz9>N-^?iax0`xO(_0Qy%2rf*{YCpMB z!9~bL?S~Htt`cAwL8~87$x)+twUgL4?07F;hmtA8bTpWuebS^bn;o95X5+}7ot$DWJ&8Nnw+ zh9SnS?jqMIxG*`ZpOgE266cm*O3>;T1bdP|y@VCytbR%EeZf_cvpPg>P;hngc>Ko) zw+6l<_%{JIGj8>7?LURALN39>nCURpXBld zmmp_#w?28LN3Dwl=*u??7NRD=>96Gn2`S8<5|+X-5ozzi=F zTqilJ6UkjExNdS*v&gLnm)uo4{RFK}B6zLHFhS1hWO6qM&O6_<1*`j#+c3tN@SsjGWaeCO7F;(utA27@1vf~}YBWIbaREB}n{8(`NbU*2`N>(GLGEe6 zg~?gXGhEbpPJpEZtswYL(gZaW1e1eRu_>QC%7SUR=-1TLR5g>1K4F!!vrS_F2uOigUC%0 zTroMT2b0SsXX+m{P)5+|Aq0aW!zyxCi^$CqTpc;9hmxC{%HdK4L92%moSzCh?c}T; zPHutVI>}irCbvj%y)K9KHy?1n9l?VIIK&LCE+%)F;JgdC>8MANTP(N`QZv61lLZ^>M`U_ z`AnRu=ptzKy97@c8TOO2x{Taef*T@d^?T&b8Rgjiy$5pJQI``ucN9c5Ve&I>_50*5 z5L}p?)lza739d9su#|c%!Ak^K$+*=O+D+VI{%!0*n*1`U7&; z3a*o!)#J(CAh=#~)Tna;!3_c&B51XY+|7dX7IM>3Pb7DX;6jXBUFCAv{Z#-&7F;Jes}Pd%O76M_pfZuJauPYbSeA&>v~;MTxug3k%Cf^n;7l6ygL zRpe@@XOVkRa52VX3pxJ(A;I4Zu$7?IN^-9Wu7jM_v&p?7xNdS*&xsOzOMrs}t^SDI zJA!i-nVPe@hTQvt^OLjsV{*|C1z14P>bV3z5nP0v)$_=GD!58=R;$Q;VYspOUqjI9 z`2_zaGK`V4dI7nA3NB90>V@RKPT^2~7eT9Q34W6TVw^y3kopsHo?WS9LhpCjAyF?P zH%@RN9oOq0Ciqi=69ibwxYcTK`n1(#!Bvv8dNH}Ff~zK{)vfJ!sK+x)?Q|Iotlb30SQKsE1}JSP-A}G)T_s)#OeR zoO2NS1?qZorwT3_B4E{aNM{HzOwMW@GyI|8BIK-IL+(d{t1w*D;RokhfVwT5C%`IZ zSVO%IoW6r#t>79Mw^|QQ-$AfWaINIxt^!hZcwJz2JMB*D4f-vD)1%#-9isjm32+Y8 zxmx7vJJ{5B0kr{~z6!WraHWiwQEw#IAh;S6pWrkQ+~6)xb~9(=)L$68gR@=KMq~GK zc943Lu@jv29%2^yW@Gy~TR{D#v5PrdN{t!2g0ofBjmECwYyfd)PQBH&qaB>> zq&A^C^oi_SM0IpCZuK^Dw+XJFoYmXG=@aeEf*Ukk)JZUb0;pTnJp%L>nJNlXo5?*W zxCrAF)H}#MD!3}fYh1oJbs52X34SRu z93)pk?mlt}!F7;}kh`B;+UKLkYg2v)tJvyhfO;RFFb28{*iFvr1K{+gn<%(`a#pv1 z!#`)T;0B90`W$3}2brNyfJ2O1jf2yTb*kWehngC+`VctX7G?;}PtG6ZhldH~3oyjE z)knxJ6kGv0t8HAs!vt4M&T8~m1eXY~l%UnEb&g$dj&J|oUIjg@Wcah5_wf{IltJ?@(CNk_GXZ1Ja)(ftSoYg1D-H^=b z@_PwdeUjkK$so8va#lOY-7dHUIjc{R+ax&eVH|zx4|;l<;1&V;8MpcjxvhdLAZK+u zxhDiyOb%-5|5<|139yu))#u2)D7Xr8R)0(GHNjPpv)ZZ8KIhX!UtysJV9q z*Fetd3*`C**G$gp@5p@|6=0m8)g1&s6rVREDGzn7rZmk90= z84i-O+C}ag!6nF9eVJVP7o&Z@ZgTjw|KXYoT6D>57; zXSJ8y@q$Z`v-&of>u8uca`8;$yxo7T%F)L$Wf!t zM+C1IU^hXl1LQUcZjhYSkIDT~aLy5C6I=bn<*@ym1n4Jd^)Jlu4#9=VSsf&|NpPj) ztp1hU{hDL@a~oGB!D{NK0QDJ&xX7@9@n-60;PfcCO>pgucTsnddo+o2JL5qD3F_zi ztD)bw*i@L+FU%K4KkYE}OXRAbJN9@|u6lJ!8Ly-ck$YBfHH^ooUy? z0n}sgKMJsy@geHp$-OH$?~!KxLeyb$9|^9Q@iJGj!Tv$;GXYi+tfT&u+}{P)%y>I> zH@SZau8Z-0Y66_2uFuVxnw_BKD>3V^M}6?x|JUBPfVowbYwu~MkeRfQw4F|z-Dy+k zU{r*Zf(}9CFLTiT=sB10SXNu5^R+q_4%XXaa4Yd zzx5|_GfMr>cu-FcRvDp|^L^`kzqu@D?2pIu^m+d0>}QfU-}>J5t#4iT+H0@9hyLdk zq&V;mx$;jz%mUx^zV(YSatWb3gj|JK2mZxdPnL6#oTZZ9PPpv*w+Ux+Ck%ZI_!f8p ziK;+5vkiRY5grGb9pu>bG2lFLG$2X=sWki{!PUjlZ5_W_Gn5j}MR5Cb3{ zWfAMpH-R(2JKo~8pm&axa+wLxbBMuUJ81} z9`L?n@v`xpG?pwPxFG(}A{L-moCn@dEnW#c#a{4Uuy_^lDmna^58^8pu?D^30`Ok7 zcy;g;BjEkP;x)lj%q;}*O^et9QE?yQaij6ICXSQNGATjDeZiYy@q*wfE+QU{MLDO- zB1S+|>?0yi?Olr(15a^3@FEs34qgWMPD$A5GrV!_zX(DV7zOb?mcb_UE#SMrTWs;1 zqoicQz;}c9{_#9cKL$b^_#P0Kjwcc?1$`R0KX^x5ye#ws!1sc8oW(1UekR#<_y->c zc%kidhJ;iG9*F2CThVLKH-ItlPPce1=>11aDvQB8$Kpkx&-LTSK_ITSh)L)bmk^JK zl?yH20ClV&1qe;gmpBJRHP_EQ59M6qkbcn8kCBL5_h( zfVX)Z&!is%LGefspB_i#CYuCLF%I6hE#3flip#+JzQrpYgM~c$!SNdN;(F_Ut7dDh>9Ns@3$5&1D@is;Qhhk6~I$WU|Fa|sWyww)3{FJnfG;Hw$ zFpvg-DT>W=i;r5di_n*VXAzJ7oKIT3D)bHD+3@Dm7Ow?;PJf&OgP*gA&hcoPz*XSo zEnXOU#SejZjm3+C2h2JD1H>;_#C{MJKMdYFi1l}VSFTDb182Z8XosWU|m_^K}W56}w zRV-c>dc}*u+hpbr}$a$ zej>cF_MZe%aR9`vmccZ5ikE@+oW;w6r+7Jd&rje{`UMabuK@9-2}H*!fv30@yr#t~ zgQxg8;_;frD;BTHycwjZA;Oj3;@9bn0I31w7Q$zQ-&@g#p&tR}!F%1}`A+Xe36KJb0KXJ3(yyVHxrNB)cF=~5c;z6 z!MoVvRiPg;NTl^rJ`IEq1HUA}BM|*3OYzYzHEQTVNHO58LQX(T18?(wGLBqC= zhFG`ux5?rqz*GDu@U~dI6nKgy=JDwLU5l6jQSm+) z{E@{Q08jCL@Sd}H1@IIf0Ix~Bv9kv`G6vzLBEcm%|G7BLOI;-ld0 zWAO^$DSjEesKu**SIObWV?^Zf02r53Lrdc{*JARcWI zGaxEH0p4*IZxB4iugVxyMzG>08Evww#m%+AXMhD@33w~;Mc|i#b)a*u*l7UgoF{S> z`eER9;0)pAoFXEmfi2+vFc5~k2Dk&*5B(y@13*8*mjh!6zZQ5JaGSwC$BBS=Hxy;y zW?=2yx!&Gq_jKL9v&X-0=0%sJ%^#8Go((m<}Z}o&n1BVB=B&@*1WrlfM+8raN5LR--J!;V|iQ%Sq z(R6n~&t;OJ6o=!yg`?JVIjx=;^jgrog2PAQm)_-V?);uC^tSna(H}OIKJyAHSj49}C_w(CKF}jH>Cc2^VW4|`> z-RKm0zvy#8OF!>aDXwQ$3ZgWe=vgAS&OkWywqL1VOR;KkL^p`c<-kXEVtTi{)Yjp< zbXAD^jF)bA{XYNsV}+GV{9lPpL$o=Xh#i6Ktd-o`UX9tnoyZjNYDf>> zdwWiILkr_mkkkJH=S)p5Oie)xf;P=t*h$?AEI49zz0V`zgpZ8NcIGz|vz>oXWd6_N zd<<@%e2{7&DSixwj}j8gi0IU(a546;VxMmy(y{*O4lg~;_4o9DZt~)7{>FQwo%%p{ z3jGM|VIa#e|81b~U^aNf1z3}!h<`)*GFyDmv4zF#x z+wE461x;OtxWsEFCkufG1#fZ;aeH0n_ z{NzT0+of?$p&t38w9Wb#CXZf*K78He`oy0k{?HWq%}4f;lIHfB|3uSOk`U6<`fm2R4Djz!9K721kHVU_UTn@RqG@v&_lN zOYh}Ie3gT{y=(Sz5AkJ|bbC+pk0AY^sqnjK`ZmKC9TVEkP#8)qkyNxA_n=YooxU>h z?%LZuB;-GMqIwRi-INuoy(IRAsr#8D2aSuh{t12+-3(uqY+ey0nQ_na zOVN*gL-b>iew;%;+=At!Cg+#re8UHIdp{&%C}LS=Z{F#PQJEYzi_{rQJh zq~CLVLzLEvz1+Up>CMvBwb=cKbW?Pp|3 zk_diHlAzKu>jOzi;yqhoYMX`53zFpa7X@3-&zfjReMwLXw{*FEr>4%FZNg$_2r6M7 z!qp`ml2dPBd{g4rMJ_{594)7b(x+yR&SCd;{xUIA`bm*>e$u#{FD<%!i7RG%SIl*L zC7J(0x!I)X{h_AaG*DYZ z7IFcoldVC>6`)q+5afp7DzjmZ6CZ}cIaM6cmJ@^=0qSHc3b`LRI@yApI+eyvzuT7! zq6jijXpSNX&mvrN)W4^kVADx)L~}F%UIC~%ieNTaM7Yi#OClfal%dcZRUp@Znxi4e zP4T=pkoL>^#VS9aUV3w>)5N0;P;>HMH4)aFU>~xe+Isa280#?ca|!6HX9$n$j7v=?LtOMM>*R;^ zoa-9+T=(2Abkf9pBagGknFwQU!oT@b7k$oQ16=PqtK#4M(a8-PWY-$w5@cB?J$ut{ zp3yg31K*+ZW=3~&xv*6ATT$U}Dm zdUk;26lAu~-9)F6tY?{8*IceX`Pnyut-^O{NqDQwzjE1?8nbZ%YQ-kI30DU`3&&JG z267mVX}HQ;XG;8GgVdbn?Ii&b;38lQcsS5@bUDJ+(Gwu6qo+a6s|Ud0??{P7xk+$y zE`pc^p@p`g#2I^wgVzG{&?_phJqR99(|vhd3E5SA0NYaHqad;wZmwF_(sZfue#g6W zUw3{^!|gVx4k;>csx}y0FKsG~5>Y?$&qxW);D==BSOr8)Yt@jB%IQZBOrT`M9c$AyrqqfI&WE{V^@yZCDpoE;>F>p^Kp?QKx35qP225KRM`oh z(F<_ykZ`FjLpNX3@0>imhWN=#;4rWVR12kXGM_-4`|p%7H2Xa%nhFRtU>(>5zTJ|T zs?9jOHE!%!F~sylIh+G_VD9Fuvt69=_cwk03s> zu*Pxkp1jJZBRmBM5y7cJj_E)P%uY1ybt7UjjCP5#C)%M;=&I`R~kd z3Gw0o8t0BFGJKt87!D$WQ-j>(-JEp9c(*1UMW7Mrt7ggH)C@n18iu|JEb(qmI$~D} z+MQZ!I1ar%p4+2X61+Un80VSLf_o;f;SPkS;2K~W>TzwN$4>lz zNr^eUVU>;=u$UKF9Zg;}QU3fr(!`30U*~OEdPusoJ)YvEWcFbR(4OmSXj}3A&toYk&q9bAYMhE zV)Jh%$W(Jsdb}3lgWa5MHwhk_&(kOVBPr+_3e5isU(V9?;jaYq4M7K3{-wyZ7X-5} z3bufeml6Jw!Ff&z0g+#bq7Fe?0uSyI!yB#^&28*zbRPTEU11ALG~jZ zE(AL01qk!@GQT3`o37^}$02WnoQK?koccB#ovLJhEc)%w3YM>y+Ld~s4J$^bnapUw zPlZS&W0FGGcK$I5O_2^y4J0yxuX+fpln947SVab^o~6 zKeE1os<2-VS;Fw7Etb(DNiRhsnw>V1{`9!frTAc0{R(Dzh+Qq+#WSK3Y* zj%9&IL9ZFeBfJ2-WK^FM1A|bMfhAPF8mJ;1@yuh3{97CE5cGB6ve5*@{xHHvfc%C} zJ{mdX(0&Cdzk8GqEkgU^E+E(^7Ti!^8*gHYioXDoo+{Go5YEtCw??A8>YbYextcE(VIt7U_2(R1kBlS<09Xwnh@^A;zUl41)7Zq zf&H(R+6-Q8Hk%(ka3!WmpA+<7A(;8B;D%2M&iI7jwm12vlH8zUEL{}jjY)lhI5s^? zRrLl&_7QhdkGtM4!gIR3?1@x&AW>7~g6zygPCf2jw9MUaTI4>n-yl$!!0Yl_feCSq zLE3@y*S)}Wjn)KLx;)c0{MZd$H@l;|JZ?6DAOii5!AY*5nUS$j+R^&NY_p>^6hmkf zyS;DoR)^j0K)6rpsC2){QXsuk@~!=nJ(`)YEgF~XsKfBPb)WR!sWVgggd|$sB#Dld zBl2OQ7LaP>aj|Dg5n=gFuD52H+Z)IrK>Z(Q%CtGQ6dD96xJf!nySF;zE|^_?Ktyf` z=D1?6F&b=OUu6OWeqUTT5XTnm-~;0I5aiL`O-Tjn2$Za$p6tQS^rINIBx{XwKMM6D zu!WRwkXjly*m1)P1VJlpc)LYCsnbcAqf#~I$9chpc>5{Td_ie^RVW$Ai3i1l)`!M8 zS|Hp?LgVV%l<|79*gZM~X)`mu%W8V2k!f_bY1+Nr8K^u*9V|R04w+%eE@K{+I$LnP z^?>(A!kvH62xO`<asUfxl(%f08UHo-V-Of z;ZE!?2dgs!na0k}G>Fi=9oY}&szr^XZh73IUDF!{6S+^IslB&*grOY>+9j_8^;Y? zp(LnU0H(=zmayl$@UVCJ8Sa80L~V69nZk7Y5v*l=7Eb0PW#jA8K;u^Nb=A%0(UIHl z>+^f{z1(1^j+jZ*j!88%ma61^oyS$#nE-kCE8e?Lraq7wl|e%h=~P0_p0p|h9`%9C zDc;eUDdOoSCfOB77e5y7LfD@wTLIo1z?b2*hmr4Xp5!}IH2L;QNjDrCfmtoB>rL)L zeryh-k=mqF@IthOJ%~{~^N5C;R$WK1Hm?GW_HKBw9cmSbZn|oLmwdvz{uC-m2fOKM zRF|X?PYXoj1;Hyl;yustbQk`p7l@~;tr{4rN%ZdObi&5eqZnTAj5vou}MzlUHJ*Z{`&l<+bz=ofi# zMC@c?$9Y}ke4FTpfz@du=Zc;3qlV{a!XVWCO(K@tMLz;w9CGr{qOWy`J_Q{7lZ40r zDA>R=4plf3g`KE8hcU}Z!jm|j-?)j#o=^o(J2cReZZgd-Ff7&vC1|O0RkUX898B2)vm_YICqTRZQ zwS9po9+()Nznbwfi9~q%WKIh4%jwKHmNG?^Yq=nz=O2ZWCf|byRUc(AaVu8vdR*mK z#koTQFFq;GEw8e3yF`pc5lm15PA$xvS)@-wko z`I)hLOlaI}&QRM;k8;C!L}U#nM^PAbgrhCi^i^f!Dr@W_646@FOGR&D#17~mXr0DMNGX$ z(pIOn!2LN?#eQ{dE$hv5V@rk*9DYg~(R$;T?B3&_x-ifHPcK%CH%M1n)+CDse3jD= zQn@PCXFQH0&_SSS5;_KIhE0=5fJvn?u2Ck(LV1+vEI`H#F+jWcO+K2M=xS>7$bt57 zGs*=)>^H>TKmwcg)dv|05vVnzgAQFwn})?CSBD%5G)bRL-`uD3GIKm6kZj3n)5vdU zv(H{}HH~bsM=&7G`=e;L?=;%L8O8|RC$|YN?vUu|bH_#ZQFJoe7dR8qYEQv#x=j|( z=pi1HDlI981H*WxU|0*)<0*QYJTn zn5}TZ_4x|HIc)j8vzt!~;YtvOw;;(yvn0t@P~4AvgmOKVc65R}x-FgR+E`4$u3VD# z1xmBUtTS622pqQyf|tL55}q>pid{udUii17pSY{&k<8zS&dwSfU_r=QTq z^9ZE5g`CE8-WU0%l+G9FB+N}U^-Yxe;d7*TwslFV*FQ?hPo)j;e^B5^1HYZ3*v=HSU78tG%bzxCe$>GiAmH_nnmYXVQkEDo|azS_f|5RiXnZEklMW%In6Qpa@ z!%O#5iah8I9JL~_-k2KQrKUhsa|9FYe`rgE~sTv->Y27GGrT23m+%#ft=#7mZ6%)*g^~wXWRdu?DWZ z)_QSl@H=8}|FUdDEIgHyfQ-H|3JFG$!vVbat(lU`@D^66;?`4iv|_Jm8T7-^A-n;i zU_EJ~cV(pfDN4LUih9TEvOA`7n-sZj(QTlvQ`qWTL8Gi<>5MM>O~SPBW^f)};FW$w zs;CBs3+GGG(?yKo9kvw#o2Ltr?*14>5nD{IMbV#st5vt=hIj9I6_gO&4Knfc_Oadv zD*jBu>AsWEhYONU8R_XNPVHQAOmE6HzAyX%pIMs7={JtL z>nRehs}~JC?@-VhLJbcgUw6Zg;uj^}cEsQOq+B-nBW4((hwHExx`4-`!lH087fFVi zE2RdF7xeY)S<=S*sIk~d;wUYn7>e#m2p=KgjTdCc(DIbn>u(BA>`^~ig@o$xJPA4f zzon_{NJCl3?Y-;$S~;(WTO)Drm!{n%FDv0f%vawniB?dF0^NbiSV&lEZHhs|s0rNA91ZkGOQmt@&i?{(JcN={2gBQBpLaTU zp(GqXOd`@f7{eLDx>N>d*(SPIvQ6}AXaMJ^7`l1pFVfglU%~iC3u-241RLMh!l7IN z{WyuUb>=`hSys>+bO|VlBCme}w{fRQ5oa+#>LwFfS2PLft>_Hw#$S@g>VHG305?u^ z&f%{}QEcv#B_+DiV+=%)v&1(q`pl=#0{TSgvyeXf&}U!zEP67K@B3NrtmThO<(oA&vQ)p_%Y zeANnXQ0vPL!4qE95?>_k@H3L7G)S8u*^SnPYk&w`h?_{<&89}+&j9T&v1 z6@k|V`J>0??@9ty@P;ft-@qQvcm7%U4e(kPe-Glfjh@p^pE)Vu@H(ygK6Tb#~AETWYh~y?GDy%?SPA zR3Rw7;T`%=-+>)NsGK41l85@<-x0-aj;QwpiK8pFx^hbkxfE%Zy+BY2c`F{6JKsxf z>GXt{ofz*F(skxBa_7J2 zee&VH_jT$8T>4G#t0a%Ea<}k8E5G;Whx=lkn1(sQdESyoDB3caPSqFh=Y8stz9Tvo ai@dIlD`>7)f241re~E;>i*Z->$7HNf6iIsHD~7c{;u`e4{NRY zt#i%~$@57edE)9q%h@uG*0bcJn*C~7wHtT4e9tc(aNHi-W}sg!Th$BVWdrf__f>WO zko;@(zL#bVC+*D(tF~;MzFqcJ<0JFe_8SWC-nsX^tuyD>{V&Ye+P{5w;qaYJ$LM+T zEG(!#xM zHu3sW@v0xc6K^&WUmq==JBsIP#q$%w{#!iXEZ*zKcf=bjh8RGRT;`veW zd{I32MqlyPxTEq@il6e0S@p`Oy?jzps zES_%{&s2Q9LcGeyE_i*Lc)ebH{VnnQjVy@A-^KGh;j6^+Nb&qP@%4|z^9|yuAKCri zQxxUn9PxURdTV_huP;aKP2%e<#B&>bEz75g_YaEK^~LKp;`J)=+*3T|V*_D3pzW>V z>)(s#=HlzO!uA!fFSjuM_lx2`3wSk(u6X^ku+zoU6Hod0oBT!i7UKDO@%B{ldXRXP zv-xx4wI*Km<3zl_UBE}g`|K*k`#+(9T#Z%nyuoV!YQ<*ZZlcL+#g}Wu>-OUHYVnkh z?ZwxRiq|K^^JMXUg?PP0Joggs<>LYMVx1|zev5eiL419(cy2A;m&Nn#;{8M7X^Z!V zi|5_qy?ivq`&Wq9Uy5f(p505uo4v$SKE~qtaq-+(G7R^s_z;{BV%>mK6yL-GFo;`J}$bts?{zEM06Q8D$R)9!4$emg2Ug?-xB7GJsZ;b?f4 z3bFQG>bSLd@3tQ;ta{6PP?g2~#q(hCbzOcT9&cQ#$*+$RU#~CUh{qA){c82rI!nAB z*gjyRRU4fmv?jhfvVG!4I~88nzHp<}JHJ8LQNlJx>raW-_v5{M`DFW1(YDflcBAbI zetXl6w|nzWsCLEc{}H|Q<6rRR3cMbG+H02DT#nkq?K3xC6`mw2=L-p-?-XCZ2k&F? zda8K-E53dbudf$vju-DgAf7)F&k_ zi#NxK!ad^k+u|u7UlPx^iRZh;^Jn7u@8Wr{c%CiVeNDU`ES~!DF7f7h@vMm2hZAJX*Y$kMD|S zQG9)!c&&=pH;dP=is#j>78picQ}Z%1`~}Zy9oe$WMGdndIG+({g!&%QY`2)PdqD z&r2=@`5`1fVC6cL-=5@$j(q4-lkeq1kdGt9t6U)B`=|W)(ck~tk8HYiDDR(~1@a;9 zi~PKh_fdWbE3RLxXN*p5BV9SA99+>j~DqNDIaoq%b6qRz`5c%K4#m`eskw5 zF8{`wFJJw!6GmVD-&@YU^8=e5P$*dKJ6`74t?g7d{CZ>i2zym~`ZA|*O8e1Os|we( zceYm-{?Xoi^HqhD+Lv#!N({z@_Nu}q?MF9X)$Z9&;g?yDv3R#@R=+uGyNRq9>g@x> zuLopp8=E^Tez1}F{vrpnaA5leQTc=HTi7pa`$GHCZC72fg;RKKyRhS`!h5sQ>Fp!R zs|tZ^-1fF}3L9sK_)r#@ZsDzPw$y>&%GzI$wf{l;h%HwaZfak?hts}Lyj#(}W6M>A z>$4Wa>|hO<)3#U2qshzMtbM@B)rB{;&s@2x;AO|SDQmY!d-EMu75>zIRQS)bUk}dw z)ABfNcPppxe0%3@R*6qod261|Zq1eL%ePup_*5plWpax+pH+oFwx8YVGllnO@{{Ze zdRse%HQ8D1-F|B8)rB*&K8ML)+tpR|!bREF*Jek2y*$q=oO)re48_HXMlGjR__#cQ z6`$TjeEZMt?4Io-wpm@crG23|t&hoD+3s!Q6z?RJgty8!s zJDJ9|-U@GiJAWxhLyYnRuUu8AwhP;>E}Wd5#%HqA6=Ns{q$LLAliAmQ&u+pSJBEbIG1*6X9~19n(l z*t316_;rw7_iO03ZqMEy(0*XY4~uUq za=v{yJKL{hd1?E?oemLGL(b{r+E4AYTHN%_OREc4%JdcGm3n&pIBR`OHnd`$^_?BDcI2eEt9`=`Vj7D4@3bG-`4BN)QeWTRd6z>9 zVf(^eRu!(u^3IdLu6VWBEU0mOL$(b5l1()G-t63?`7=^MY5fx-63jXE{XZ$@8lGIBJb*oC$`sTzCrtdR~)ip2eGG6 zS7K*Zvc5cSd-w{sutRnSHqOrXw^_D0Q*nPP?Gs;lg18%U&Kf$i99_`+(h7i^V2Cb+*nD z@5zoi$?k?&?4tVetmW<5uUBOw_Wi8oKWBIEsLXfF{6IMh?Q{=k#ZKbrn_p8{f2);Q z+#~X$+UZtKyRxTKI3t^Ak7cJ4?dcXi*uG=W)rE7iP)knE@clcA31)3#t^cUV5s&Ba zG5r6;mPdN`Zsl?hB_F={au?|{?C$#ojp@PK6NA|cc>#)-DU!%S+MDQUFaNIrWg!BQ9b>sn7TEX6`eHrZ!6yMV2 ziB|rxUM3I1Zxh>9=})dNk1KxPpw7#(o)m9n;UJulKESVW;5ENh2exp<2a7Y7?eBV- zx_}N2@Ke!Do{*0d66cpau0c-x8cDy^_Z9o3P@buW1M6G23S)oeBdWu5I6wnl#+}#; zevvqmyc6edqwa*Ij&H3%d;4*fBY(ppA9v$~_PS?FdHrIym;Gv4pBL@qWU1iFUJE}~ ztT%b0Wy}dNce2NWI6&=bb%0&r+u%<41$9DI_^)+RR6hMe2Q70R3su2St^#8GYz)iSVZo2i1{lf`=W z((3p=4!kQ||K?}SR_XwcW9;=%K8c)$qw+Vwjm`CIo=aRqYSKlcOWGn{D+ zS2nyOe}@i0kcU}aMf)|lbJJ{@iOnwjYP3IDP3mwy_V2=^I3HvAAkOqCF}dWNIBP@k zMm%1Hpo&;E@|JpkQnPJ>_V;b0yi9lKjqpQr%R3Z*8ib%Vxq|qkC^6~e0UpLJ)sxi4 ziFPLH4$0r9$jAL+S<3eP3)HPvrz?K@Qj&9PmBn{%Pw_#wODH;=zg@n=k+?VT6TQvZ{jmjp6P>|=I_MqIH60wuWq&c zV-@-MJA8ZG2|YANixZML_DszQS2ec|Eve75tzDekyD=_xQ(VW;F2VV2^ zmUq74wQnrmdBGb#wB-gTo^;YFXPlUdYea zoO|c-M}MpkhT=Trqagm-Y+HFwmQ@nZlQvx;etn6xTwjH{D4@RHydK~Wm0yD8--^`r zHpuUVx0HvL?qDCUCXeljqlkz0$vc#n$a{Bfn6+z>H%?LQJLH|;s`lNSi@_fJNEPh2 zBbf}V-;U0Mf?vq#HHF6JL7cP%K zztuhp0d=Us8{~C(lRSV&m4t_+E8F6LJSWB`?Egus zle`0u$h+`Zx}5)d2zn^As6!u~kf-nt`2gM}AHsV}o~^$T3jL*mTz_MDN7gbEXM=#Wq0UGf>cM{eQ5`s77;nz@*NdimKX45)(xACf2MsXH_xKgd^GwlVqn z$0?sIyPW?o9y!6LQII z9H2t3?`V}=-%(F^HvjeV)3>xn9rP`&lj~a=kn20zAlG-axp1}qbfL8{4!i)c=d`#ZDRr!Rx^fl#E@)+%B2Dih*^ONPt zTU3xs-oq7F$n_Oh$@LX`rz@@w$<{$F2lojT|%4#@QtH^}uBHx1s(duZt^?&S+s z5#I|2l49V|B`|%O9 z|91{h9h@WccS8I;QWjJp_ij-qR3-P}9(f(^YuEe#0EL<^=-(H>>*Tt9KpvregFJ>e z$-@MNhzcEeOx}aH$ouewymq&`Lml#G&dcs-XmzPj{F1uWJ@R{RRo*9`UZy-HzwuP% z1M)h2n7Nq$dim{trRp%E4%eZ>*x(cL+distX5{WE%AKQ@=9XN4b=;!TazQw5kyR$w zcgQ8zcc?YTqYspnW>`?D{P$LSZm3WXs)Z!H47>_=vm@ACnK@6Y^$=Go4YvK1lt=YjMre zWD)12-7$FC;1z?1RVqw>uWns~dmcR}kM;;SqTR?~x~P@v~*wI`B$Yv4;>oh zLwJXL3Llaer)p@dTK>Q#xGOxH|N2ZTDAcKg4{wnN@RU4)Psuy*(mUrTq}E@Gg1;za zw{QfH$fxigx&5rV;xV}kw~w74ILr5+#h?FIsn9@&26+qKAur-DsZw$mt7c4Ifm`9b z@@G^|ow`FE_|w^93t{N8~ZQL*9a?;pzZo^5ih( zF8TVt@(TGB?W>uK`LCDXy@#p}9(Aa}eewVvklTM%ldHjgw90QTyIg;Jtx<(&xgh*r zcuf8{uB=5K9ieg(@`usBL%yqMpRNBM6`C)oE0~Z^UQh>^lGowo6Z2!Q+q>kty?-L@ z{}0_<{Ctpj)Tu+MpgbVIa)t5+xx1nA4*5ZwDeulbyMFQS=-~jpc_BLw@vpV04t?^K ze^+;6Os=nZ!v0s)zWAQ}9cqS~r~^1uI20#TA|I@$+Ly_nD=M#%>l3Pzk6%EvH#asFryB7P83hd-#R@fY;rv(9CAG;yqt^i*H`T4 z3gU0Saf=${`@c-x>WI9FA&bc`-Ac7@k*{1ST+Y9g3i^Zwq%{s z>q+eh&*s1W1k|&-N*(kGdF+_g5j#E)Vs^Ao7p~TyKEPm6$kyNdicc|IG5P$8$>� zzVh#(S_Wk*=rOL4>oKm9>oNAovoRKz(j?ax9EDWSSKKG>I%*Q7JMEef;r8}zjy}XCkaR}pFRL}<)lIsJE$n^on;1nzfTs)C|LX$;Y zBER(Y*#(5wmQwMzjk9;3>1(r{) z4^Si5`SoR&^IsnzS}q9xAjUW**9T~k>jNa@I=@4{QcUV>{q?EvIL1CD*9RVu>jMwT z^?|44dtqp1r_ugjAHaHFek}C?isbqL74qICYIRh}e{r#LZ|>^z$2urh1%F3TMkv{{s-oJc@ z#Q6ULg<`HC{!0SzGWq^EQI~ulc!hjdc#ZtUtHg!L`B$gHbFv^F0r@ZBG5K*gK#P10 zJRv^_-WQ(DfBgw~8xD|C2OmBlUmrdpzY#tq_u#XItM&Js9)f>f9vkuZ`Hq^UBl14H z_aW>aR4Beu9k@g8m6dnN>+l|V1KuZ(;Au#O777FM4tz-7 zhmXjI@G*O9hkS^!HUVb$c8q^_xH_4muh&+bJ zM1`oW{^KWO@+Uu| zd_q2iPsv-CtM)T;r={FFoA&T%&Z)gdK66h0*1|8uJSnEWDj0L%SgekcQ+XeDzo|Mc>k;#SwFgZ|fM>g4{b z)T|E3Z~T%vp$2*J7Uj)lm-F96hiJJVeE%C%hnRf(FDh@5@84CPkh{p~ke~mB&D8h* z9u-a&1^MWc&k&T7J6~4q2jo+9ij_2KM<7W;qy zYpR2-3iD<8;GN2=r>(0hg48XJ{c$M%H->#y-R*RE}*h-wfmgc0*7=K15K1d<2ik zUyYm=d6L};G5-=Oba0Eh$gQ*!H6b*qQuRpgAN%lWTwwSx{5>QIKy$lrpX z;(7UHSw(xB+=G{vJX?Q9BFJ4T$n_VXL&e}8`BBKJkvEW2CvTp*m0JG|DjbcVh&;Ya z-O`vH2S~_k$mx=|z9jyu9OBVCkM{owf>P@6E(8t9yJ$Zm@4+YJ$0KK^UGM(~=wN*$ zKbAwdO@1PRO5_u?FOyH<74q<81bI}@-xYoKFQ|22Cx0(;8sx?Isv&Ex+e0g+!s!S~ z$ZZ654BjI@8#yU?2|0tz#r)IDPZvhi;d}&5$SVk%8r(WRKa~H19DCX2{Pz*$EEkr% zOnw=HD&!61R1NNvUn6p|^;f4tjG(~aP4W&-C}u}a%ix{!Y5#vSf_l`Ui=e*22jq7k zXGGpd&Uo(X^T$e2n9d9G<3aovX%S?7G(VODv@enm;STxz$SISLLUeGc;NaV9mHa^j z`Q&5d)W|3BfczokgiR_;(IFzY0=14i9#lyfouO%&W*LHu{Eai&%B2<<)c7#@(f;0^Lbx}1M4Ds<2xA@9Qb z&Le*s2di zMNUHA&2q&2>#VaNHizV|LQqPc;)DhUACbQfITPt}{_Ev8LeP{tXtyrRkL8;XWRp*k z;~2cW2&j{*}`}%jy!?%DN=|KACM+<8IVfAOfJLxsEn_sAbaPK`W9`#O0NqR^nie<3I$ z@1uQ8K7c3WPavmDK1TbnM};X0Df#~(Xh?4Vvl_Ayc?muvcj4B*WJ9*J|3|@Ah553a z;J_vF3fh;+eRzfZx5)8wF2=us4t}m6{+)1mo&0wQYLF*r-z4wBWAdrYk@GL1!Vn!g z1Uy);z2WamsT&=$* z3gty1TYfJhs6yUC`zm=C?vwv7a_Z!RGqC>;s4zxQlYG6y)h&(5tq&+~kr&||@)gMG zg;cQ7p-=9>N8}~=n7jcga0?m3*_q)t&IkeYCITJ+$g5 z1o?us1%jI74YZHQoA3^K1n-i!G8gl2K!pxE49UCjG5OYqt1F(8_tAbvp2CZ<7#cbM z_43;WL5?ge`2ZbC26xG~M@~RKLQZ4Jv-LMcAzCWP6W9qsEpoe|t~ent!Mo(UAg536 zHn9Is*DlE8TSM|!B4|ur#epXVpONo@oZ`i_|Mw7NUz{HT?IrS8A;=}KA*Vtfz&-7H z|L-EGrVH5rH_@R^9>XK@1Rj%j;a&2uk3x?M1Ne}91RoiELcSj^Y(^fa-xrAa_o@7? zZsIo#Hu-@FDv`TrUnZ}@J@P3oz|UM9UoSrk|Dk|7b$AO7+#uIK?bal>krR_2hMZ*C z<@zh3Lua`l+=chZk4Dghyo&ZyavyG8lE2f(ikxiy+f)e9!69$J%j9*OP=&mS_Equ- zUcZF)|1k;yb!fq3@&w)@@4!doUHEwJ+4YM*>p@{UFUXG{@i(BjGV9X(ts9_yk$eny z$j?SjncND`QXi!*7vNR$a}eZ{7ty|E@PPb$P=^}4OMX9s`s7WtPstDa>=I%s*qbBR72pA z{|Y%Z@)FwDLn^o^G{}F0porW<`cb9R^DUx&E||$Xx_Y$W!D@ z4Q{paL-__D`+u7XBLq1HFOwgP6RMDpkyACe-=h8h5eTYNhY5lLgEz^KLrzRSLrzP( z-v8@DM;EaFe=mZ1$htf~mSyA=4epR%q;f*5 zOoa-9T!UB1FT)A>s=pTHaBGk8S)Fb>?Bdv^WeZ#qA$KHHOdL4N*;-!oM zpfMHd=rAE~z-Q#YMozJvAF>$jZSn*jmZ&gAkW1c2hYEQL_sCyBPL169le*J&<%|8l zE;OjaOO8+-BJvRq92-0#-vBw?oQv_FAgGrsEIcLO2th;gDRM>zpOD)!N6x<)6=n#s zuFQ|6-BfqNCSQdUDv`TrUp9C}csBp_C*V#9@~A@vK|Z+$uamzLISuj}+BX-j)?a`^ zyeMSLZ#9Av@+R7M$Rl`49>WLZNfZ135f%2ufhXi$1Wn0%aO&cBtIBIG5HKRErWOR9$JSXsFyE@|4+M` z?S1khd_aB-az^Af+K<=iV*X93Z~}s?tMg-7LQv7*4*6-wDU-X%aiz=oua}=LRH?(+ z2=d9R2&x%8ApaO7fuMkVfc6c8 zN95l@PK!JoBPgMQ_AdFO2 zU?_~pPe;&%yoI2t!L85chw>cc*vc3C|1N?Y>Y%+$ej$P?gK|SiAJte;YK|}HsIU|El zwCnx<#R!_|0`~tS1X+o#-`&4)aL3Q#Wf&zm#$^U|!n0$(y*5_&euL~XO zu-+Q=$<-sbBjtUA56Cw~&S>u0^@|_1LeO|#$UcAOJ|%Y$WObItQgo>yr)Y48{N*8n z%2a3~$TfJC{ME?u$veoY89WTAupfe&q4J89EzX; z`2;~jgOACNLe4bjV*IBFn&k=$FW!(J<6{xzkk61)GPp~AqRf%=uSx~$LN%*BgV)Fd zoKQesL{7utk??H(>rcQBAgDzhYy>3+?~nsu9@*Y~cFv%CJI}kJ@PY`5%F+Y~tZSuR3QzGwX zIb!~m*I5uh7exL5f;{p*PRKWSo%|u>G^ESKyn-Od;AQe>ky9b}kyE`f z%pX`6eCqI51l7qK2nr0|BrhDT?nJCz@BbqNwR8ddf9)OejS$o$Zy~2|@Bw+aIf6!1 z=pblJ-h)rcw?U5erTiUD(Z0BD7yth+D(sA)GWifeuEDG1yCcUZA0wxhxtM=?`RPJH z9ri|0lYEMx$lxvV{gBgH_H6!tTuqAZazU;?c%S?L1P#a?v>zILO#T*;lO2Cb1s6dx zgBNegkMR*WA&1;UPRZczO|<`iCxWWfp@txjJb>58Pee{Y9-)0>?)dy^p%Bdr^8Q=a zX$WeOchEi|@4>s|XCkLho`&dZn>n;%N;Hu>GiDGAT!zy1VF5LBiP+AHJ_Ajl){ zBgZ#*ec@{TJ%pgfq99kFHAGO;;4%55$Vtd2$my)**#Gya@IwTp4HNYc12K`e2gI1;8pThA;(|xZ2ip;R9h;@<)=L$e;tCFyD4mAYL3|_o7KgRDwjziu+PD#7o|LcOQ3)ugk zh@dKYj3Ce8HS*Jt6Oe}qf*MrN9+97kpcZ)#If=o$x5ss778!P~G4S z@*9v7kyk}dw*KRF6y*9($Ztkam%N4(>KQyGzXLhL+i3saK+uRfXrGYZji4EMj2!Fs z{7`DQ=bl}^Wj%nP(!3zAU;JnWg31Q3kUxYRkGzK*pFKpOPK8Gi)F4mMzG?87{D;U% z$VbQtJBC7!{3!&b#v6(cTvcepY|&G?g;Y9Q{>bP9+2<-4($J% zR2U;DGI)!8Kb%m9+`3rJiLSx>Ar%fl(15&zprOIXQIHJ zed9`5!7+m#DFi$wvrE$Q`ur7`#XR6mrtc#r)UHFYwg=*XEn5zE7UO2joTMjOLzQzu4!a!+2hh zpMRFsg-^*hMv!&a(pZZ2J+v>9r*MaS(-1*rDh$!VB_F}7;0jr`R(p@6)F_6_m`9tqFpzy1W= z7eOuRVB?c9A@3rnOMU=y`s9PZs1LMs;cETq!gx`TtIz7;02A^dd`A8@9Ju)P{E$u2 z-d@YG|1VMDFa){e)~D4fsE`-o9{G{Tsgak^z8)G14f1y(C?a>YzO(KOI3s@+NXd2A||Tw9ZD*EMKr91X=%{AIk)8lb?f}5_uo(%jCn%#r&&K z;amiHFN)Iocb{00QY+dN94VDYS9Rv-@D+n5s{}wq@@-lK}eHACi|s1dXXML5B%>jIp1Q?~a_}H}XR{Lyk@E zAtx+R;WY?y$%`#D1Ql`z?vcL%IW_V!+SipY_Wu3xgb0x_YpKC@1p&Pd;p)2zeDE8`8T7&1Rbn<^J8gUu7nhe? zKjily$ht2-mLr@{(cljGgUBgMm-AmQzcGSb>Y%+!{s@A6@+op^1`n1zTYn=2HJ1u< z{ml>*8N5aQGvsv0i&v=C)Lq-v`tMWW83YZ;9Rv*xJ|=%2IaBg7a%T6@{$Cf0_vgph zI#ykQLtaHt$>1*e#>lB^*ZY4TL7pyP|F6A9z7jzJd4QaT!6Wi;M+CK~5Fscrc$d74 zoIZIAIqAARw1!l84T8qxy^GX$vk7?@2bhuXkDOwfAIcuu+nI~`rdS>CZ;&60pon~ooY>$A`N<+DTYp_DOcB&GcuIZ- zPH0GOweell;FFa1{|K5z|P`S~aQ+b{_7 z$Q_)JZ}2+#)yQd(mqG+Jxd4yJI|xe1D`?*_c#r%RrcQTg2vQA`;`0z1XyR^r&-edT1kI>}_Tq#2F|H!WA+I5)WNtH$X+VQ<)^(w{s{!Rd|IN!~;I zFrq?=LW{hNpbq&E?Yrb-c%OVvJ#t#)b>t+%v-z(- z0d=8E9o~qbK6wK{slkWj2O?*@aJBv-1Wgu&Z2f7Ukspkp;&+$FQv6N|Ikv$|cKWi7V^N&X20#pDy@ zv<%+SuJ`|+LQqc^u>ZHNRjZ?K@B#T{$QhA4$QhG|x-g}}6$rBaD?gSlf{F%r$gf6D zncP!3;^%+XU9hU;pGA;QUdIX53?7hQkDO-aV*cyp*FaE29kjQ|zkr|)d5oN{!TZZD z*WXPD8Y~xtcMvo*_?Y|_+nxK15X1O*0fl5c>Vn0$nsR^CHP7drWZwK0Nv3^^n6 z;&t+Z#rzwuvmk!{hkOeJSwF~+Who01|GOT8JLFp~j7$5ma9;EO~?cNCZXXE#$-oPsooEIobN_QlX2W zp21V{V{t-5@)S8EgHIl({r~X@no)-lf~^0}kEM2-{5{Aikx!9Rp1b<|v2>v_FUZe7 z%Q_W79(nP4wK{x**U8_9oCbL*L{O6p@RXAD#NId!mACO;$oRRQs{_9V`GJ?j`LHm^a z3ItjIFTX4+$SIP0aA)Ca{auZq@}iJkQ5_vzgICEviyWW4ft=b}9;#axP~mz6HOXTH zMFww?e*rli@(yykp`p+xzX?GD@;-uw1|O5(f}AOQzW*O0Xht2h7f1Oq{tAK|@(FTE z26yuwT3=4BjQb4>^5u4>_rH zIsf(Y(}f{*_!ff3etI1`PPte{WpTW!I8zQGdZht}l{0|k%q97kW`KAb}lULC`Ag{rjPZ-at-?yeVDIzbX|XbnwVq z@PNDnZ;+?(i2Ut1(U$OR{_9V`F*+pFVFvG#ABLblxpSkMTq$`8K3uq3e>DV+7lmy7 zdFU`9ufdBy%@08Ux5=Aumpr~PRA*YDLV^x8@-Dni-iJrz19(h6f_FnIOi<{N&)`Gy z;+NC~jL04MjJyoD{zu)p`ToCxLJ0*uCp>tWyaxBk1GrD#gg5dYS}_XEe8FnLWAgW4 zt|a6gwC@^|KFlQ6G0vF zPa&vBUUbx*=#x9}0r?fk8I8mIt#;92OdYE5Df#CRWIdJ7siA$5Jb*je_5S}x1eJ9G z`~UGOb!9I36ka929XURE@>P{nBM%(}1yuMtf|}%A1V!W}5oFH`^7C)uCGx)`$R(d4r($rAe1q@=tV=2szpT7& z@CNy2$ce}uk#CT2gvaaUMGK}%#ri2L4_uQng)-_55@^4a=D+>~JPbi8bx062F!+f4801XIyU3X?T&+J{uzr~z%i|GbllKwi7`#k=Dsn31 zgD;0_nN`;+DEG;&JUHtz)QE>7F>uLm*$;)W(8oWw=J#u{VN|qzn|2hle zr(ei#LQs?3!wE$OZ;{`MoQ`xk|Ml{#A*f3owD-w-2pW(F$Qc@ZyyV&X`x=6#O9lC1 z+C>;3-#L8&fa|F3;W{uqMB9<@~Q8XtZ2d@(KC#2%3?5$gzHtA4=^u`QJoNw*E>~s3E9q@CvzAS3~2G2gvaa zUjGg4|5qTWK^>Y1Y8pHy-xxUwd5oOS+|}ogr3<}zL4N*O*2@r-k|zin7<@#&5;+s{ zZit{M7vR=!^JBRUf^70W+B*g>lkbR}utJ3af~p4h$zP73I{64Wfx(-~7yJJ*f@110 zK~T%!9r9Npr$;_RPCw^j{B>cFD_GWR5Hun$-hv&G!KdW=BFB0F6X~qehCU5bqEnuBk!YqoqPa~$cONF z$+Pu0Mxnb@kjrlZ?~z-#sWDE;KZX+>k~?TWB6n}YpZ`y&@M#3i$UOvEzt0a%9d45+ z$SILG(Z2k9+W)sus8EM5BFH1}qPBB!BU@Bc^W(9{L&|EKVn{7wWVi4FsiBsG!4u+=q|Izm1#;d4Tp)@<_Rue}Bl2<@XR|lP3sr$b0Y#`2b!e zAH(aJi{tC%H$x$y4)#~nEse>`@D_O$-XpKU`^zrZUjv2FazS_uACq_B)--?T`tTz8 z5blsaChl~${>xODpo2?p{hPWIRq`KW$b51K?Q7&NJebn{|K|v5QU?zmBJu#*1K0^B;`4m1Te-=5;v-u&j!=AdOB`P>@m;5;d zwa80opOCxoF8K?{3Hwy2qC-mV!-wSSov1EgOkPL(33&rPQ@+^$Z;YVgAM>{;LI<0? z1uv0rfgG2-gZ7o2i}CNF;N=RIwJm~bbx0A^HF%%=G2{%$hsYUf*ZY5680!M||4$-lNtG9l0S{0D!Fy1`X=NVyhc7%IiVF$!A4MnyaJEN|BMrAk=M~aA&=qR%*FiI%kOUp z>QjdvI;7+&d`Mn+4|YW4L$sePyIg-06lTi>;Ts~T_?P@xT6d`f*yJ|6M7}9)rcP{ zK{0jk5Y#ewhx`M`>5(^((_gq+f4VSO6td-a4uVGH9R!UHJ|+Jsa;z8fLpl69_W#AT z3hLH5=3i-@1@W&^l79_B zRdTzp#@;h{jr?BZ1k&aF*UPVhpayl&9+7_=K`rtcauS1gmpog4-$hV=sUX*1grL;m zL-I$FGbZmMXR@}d^*^J+2tmac^J6(gkZtf1`TrotCAaQYLsof__W!!zQHNh4s7CH0 zsBZ8E`R|YuY1jLI4?(dmVE?Z@A%6}*UGh3|dInF)!@nVDNQEYXMh2gduXmEVr8Dvt za;(4Shq9|Yv}`JDgrE}n5J6?~F}y;)IdVMm8QS}qi}|OQU-2Gw1$FAM4T2ivWwdXS z`|y~2XXGTyF6V!Q4xQzK@GiVZzB__a@-f;E$gOXv3mcK|EpoE;H=#mvPt{>c?jp$k zM}90TaEIK3m&y0T1yue)`~NyRRH;J)?vo#gpgMVs_5pbp-kiJo{ITAQpm<)8pMT=t z4MT^P!8_z{M^2A?h@3uqh{AvhK7vN%6SN;2d`f;4a;*Q&57`VkVbM@<$d5r#nY?(f znk%lstK{!Qj<0;N|1Tq`Mjf;VKeRH{vPBE z$OGgI*X45ljj3=7f~Mp#f@TIUTH9rlR)3%c$Z^OMze**+H7KQ9ev`6G;BB(_^MowbzF8K#f!v4Qcg&BfUgAd6+j1wA@+uu~H zV`A`GNQLtdR4nAj(nXMM@Dlk)k>iqAkW+!r_y4-!QHKaYHS#Kg>IQF+e;hec-b2er zP@FH!Jt6-Dg1Y226hTdc$K(le67tbE@#p`YwF}w$ z?~#8FK`HqZCp0kli2QowOx6qYV^h2jJ0I$x-FivB{S64R$xFy_3|`i*_y0E{sGph`fmt z8XJ5{ekXFQ_2p2C`LCB>jG$sxSa=IwCQsllc^6(KzYhoYmtC&EK04Hv3&IERfc!rZ z)FdCFePr+!`B3Dj^-qNrtVOpp<+c z1P#dpv>%Z-;S=(ILe5NhHvi|JfaqXtm>uJghFFc$kyKk z-XymkP-B^pJMa#<3s1?t2SODzph6uTCge@{lstx8#r&N+7`NIcPte{8snA8COnx|m zD&&2%uNvGZKL$B<_`|3^?SU$7KlAOekO88 zXBVkDv~@hn%j#`{Z9f8T10?8hlLN!wF5v1LVvM zUfh`W|92zE**HJ;O$3z;?vj5CIaTr)Ii7aC|JQ|@E@1!vJp={h34$8rU3f(PIC5I# zVILh5DroPL{{%sO@-cE!gAd7nrE)@ROoigN)iRqHd`A8ZPN?|O{E)fGu?=3zT+DyH z{Qig_mparCR57?mK0{88JVH)=+2#7vg~oD0_&*R7k#`Xk8$2Q3@Dz1NyW}I0ldb>W zItp_Ar{tR=Xh>dsP#s`o@Co^r$eF#A_WuEuBpixm$wGgKsPf!mA z^>9W-O$XGpAVxq)fHMEJ-@SIS^8Fu9pC?V$XI=Jf?fvd|CzCMG0l$cO9{7{Y3&3w> zUIdR>Z*JY36a@4dx@juVkJCKEgcJ;d=hv!HRT8VNbs_ z^CIw()AZPuflsnr1@4~ILr@3)_N|FM?SfqMx|1b%x|V&wYroThg1|>Uq3xr<^K3r? z+_PPmn@fPA!GQ|En=F@ryROw0ssgW_t}9dn9%H$|&+Yxc3FO+dyC+Ody}--Y>VpLz z@CtK3@GA2_H>cnKVnwi9Vbz$2fY+Iafj5{(fH#>(fm_$922lRRK;g0#^k;d%-ONXT zdzdGId(Y>i7vRaAddSL(tNb_9&vmI*G(W<@a(53+i30_In*xHsJ+J8sjR`(%3?5n_=VO_xnaPMonVXpbz4XB3s`tJjU#STH>xifWuDDWWLj{py`eGa&> zFV2Vk|HxUofHF9w7ieAuUf_Zoz(3gLRvlf<~*$=$J z1&4rJ+<+Kx*Xw!+lE4#ru2CKo`#z^@S_a1u@{kvvuGU@FrI%58T7{Wt&s}n;O;Fp$ZN^{<-dnN#GYTuLG}CwS5D4 z`UTCKlB@Zbe_kuxz1>|D-5v=Y$`4{8QR44BW@|u{O8YKl%(P zJEYnQd-_^ocE|&N{bk*yW#A*9)&*CAr&+E6k0mbAEog$G&J}Vk>TYqIE93#5H$4G7 zcn26r9K@Cv( z=LJRME!{F7@Fw#BaO-Vt9|Z1Z9tQ4Z9wBb$zv*f}D`MafWF7||VV(pYXPyF{WS;AA zJ^#|I$afU>{3|do0xvT!0iR@E0bXZb1#bO|&;M(n@cc`6X&tzaxo7Y0u`HdhpIpF1Q3d$Z`dEiR09mxA*@wZh^I=yJZn}@BnXc z!2#e&?x8U7$gqwZ@8$_B$_}Y+g_UH70`TZNdT7ePt88Bb?q~ZZ@c2clLX>}=eY#s* zd{-CX2kx~U=vQ%o$Jjmw+;xeLn*yG1>iBuZRsNglSGrg`l)<6S4wJwmTtE|euB8ib z@7vw5kxRAg7u=qIRdxsog-Xw4OgqGY2j0^KB!TCaBfLGqtw_r)b z&Hlg44k@GH{eOjd8hB%q4wM64WBWYtI`abXM3WUoP`Dn|T~q?@VO|FAV_pFsU|t0t z(wy%9K@nkx8t^FdI`BC22Jj^FCh#y z9|r#P2HoHYaXbIb3Rq-^BsiEBq=9=>3+P`7`LA>VW#Enf(!AQ?dj7rqf>zW!3OjI& zr%e;M`#{~rE`Bx*@O)qI8@#}yuj%+f;O?suI#3uC@q;vv0x!JIN2tJEZ|MSZz-!!q z0`M@$FC{=>3aA42Ua2co10G|!0o=V+4~>fpGCh>!iu#zh_y7JYbO8ZyXma2Xa8uDJ za8p3?BY3`>)9-(B%gWsf%M?%pUila23h*183+g-n?4dk0`FnHw8C&%+lcCXNMy25w@=YuV14Jr~?mi zgAt{k1&rIZub8% zRz!`0_y0-eao{=TBftyHQ@~5i)4&r|R^&lZV_pE>U|s^=WL^gD`VZZsRp1`YY5xxj zA3InFcaLSQtOL1#2iV>NyutQf;6b+c+nn;RJ@%i|7molq_$PG1A>bhn6b2q)9tCcW z^ZNoN_`b}WzxH-ri0d5X5Q^3m!4wMFkImyfe4{_HOfJc~@fSZ%gGH{De-4az$n3K;*;O6Ah zb!hikrf$@-4|t9%6a?NF(e_czJNtkCf9hlz0f*q{v_lTKhwbygQxzSj2;3a)l)E^M zzd4hsb}8sPp*Tx z+vkA?nHPbFnU|Tj_x}-ARKX$2hfp=(e12y&fJZrwxGWP?Y;j)J~VFf|)YaX)@a39N&kKj?@FVD~wiUDshkK3H`&veE9 zyJ?3JaPTot0zZU#3V48d8u$s!bCRq4H)EEU3gTwW3cyd}KtKNPyqPuvviyw z@Oznu+gz_d))hJ%t!P_eC%$7#iVc=%^MY=eRznOl~E=6bh#eiFLbOCYTX8Mf)kFb3bxV>Vk{7ZqN z$__c;f8n9Y1NZT?D3Nx<(-~BROKpl85^9JxkF4y)=;2W+`T;(4Z zWU|zZjSILL8aHq=G#=n)XuQD9?C>eB$~Og@>EQ>5E3eco2mlZASO$UL!1f{Fo0vxg zx98urJT_6GQ1dUzavZpSKEDeF+{ay<0)89Yr-75bp8t7JR9P+nfASjL6Gh-f<|W|2 zWnKY3$$au?*#GadK)0*`4#{J5k~V?A%z-S{o1uJ_xeNH~%-x2Y{r}sn@E8T}|4lM_ zftzIX0XNC$2X2xv06bx`F$fBij3MA=od^Rr>qG>&S*oMJcaPgcN$>xG;$|L#5#a6Q z0)7$Or-8><&I7NqT(F-h|IC=Vb&aedIP@|v0S_>*0AIs=68N~uEy-2>Cj*>ZQb9b( zfh^XWiiViGfSA1`4xK)Pb9^YydZ7*#vHe(i+goZIagvrAzb9{@-jU z+~8o{px1maaC33;0XO>tKX9`@2y}58f3radb}1}NZxHBvK!KaC4g)t`9RY5-IttwG zX_bF5P?)Zc12yE+dJRhA3D>ug^H{yOs#aQBUR zC@USV=U*=?COZmy`mN&m+5nzBmRC&R9*$$N-Zae1+y#8YjR{>NHz-o<-~sM3Hy*&< z%zePk*!zK-Sr$lu!i;?oxEcEpa5MH{;AZS2z}qV(^Y;GV%Pok5!zQz20&lOFz;9#w zH1HV9`EH)DstgL<3TuC^P!YI~c?tMw%qzgd%qM}D?21zUH9(PE&B+CP0|&BLZ<6ag z<}Tnl=5FA>W$sa2<-ZB!yO~!ya0oE>0dFT4@OE+mZ|9ca_WWxnmr$tr*G?|r?c@U9 zPA=dB)vxEabx;ASXmz|}fo&%Zh-%vd&no3U&H zH|vD8R%f^AQ8Sb-;ASY@YhnN2$5RoFs4$?=w=suS~Ea2a0={7l4QM(koyIcyCc37?gpp zVO{|qVxFjiBDg^pFbUlA?o7K!YQU}evus`mUYn_T6Zp%!bR6qAJ6AgU|6Efm+*;9| zmM_1rxd(WP?ft;xT+uM_=#Xw$q>Iz|o0dhp6x1kgSq!*o*$8mcvK(+z(IRlWqALHY zpfEL`1a5|^2HbO&{%wak@Z6B*4dCgJ=1t;u{+s#gW`(t`dmfk0)DAA-)l)Th15ci& zxd*uQ3C+D7uIHcsbgl4p6n0W2*})II$o2u?{xfu(An+RV5b$U?p&g>2Xx^!lB?jE& zN*uV!l@Z`3S8BlB5gost0EH=_0o)YO1a1n52D^vMeHS+XxQQQU-roP40!F~W6i@^1 z;sWZxO#uzyCVsP<)A#@JLJ?ix-GbuX+ydaHfH-hdzzA>?zXrTy$EWG3IQZG220X~T0o){S6L^H}tx#94(Dk1c?rw$Ux`yuwkzb{`AGq7CH=jY^ zlWZRWUbf>?{-r>XFX;_J8hC|y4!E^N+vkB7f5;mR-~qNTDz5V1Ouvif>lT#2;XLML z;3xEI`wH*~_e2%=Pnk~&ZqL8{xqzBbsQLFupDv&dJiJKr2JkrZCh+0{ZEt;1`hMWDr^<%Bb83phEPh*EX@blQd0Q_m@CE!O+>G);fiA|go6;Qlw zk_fn;b7B(s+gv~mxJl|da8Bxk)c}Rb>LzfL)z&H9No2Cx1>7XH8@NeokIgCn&Ga)_ z?F9#u)jr@RtNp+!tL=+d0C;kT9)gJEYW|t5j!Fe_lhrZcCadGXO;(QpH%XlYu9DiG z|0z(ItWE~6Uk~V>xB(+ZM&IyyGF5oV& zuBf}s?e<%i$x=^SVGp5YmR>J#lcYZ2CQ1FkO_BzH@1NkMHwX%or6J%ZNyETRl16}= zB#i<$Nt%d(!YsWh;3i4az)h0ofSV-E12;)p(7dz%H(6Q)2eb5+fSV*O12;)p18$PB z-orSH7)qDp7ytu!%3j?2gO5a>YfE)WL@H>)}j4J@fY+na%3UHm?Jv8C#_1L?axA*@6&T2n6H1E|8 z0pP|y0=&T$iUKzkN_KM^|KIBZQr!y6I23?;*uDtdWP263kL@RcYkMlc2?{fvtTVd1 zuFgH=1#Y_32i){f2)OCdu;MEJ+tY>%h=W5TrRVnua8p1Ic$$ClEDzk+mj$=ypFgLE zpdu7%{uzflaQB$5Py@KJcZa)s&cpT|;AC%?Zv{Z%WrrYeQ$Q5>FI##&hygD$PXhP6 zqwP~+*#GC>)`~PZ6yDT42i)}!&GW!d*r|B|_>+ItylA-D|9|6py#khvg7^QyDeX`P z?lwO>0Nl(P_nF;8P}!u1%mX|T>(hn-Q24okAaJwhM}ddgJ_g*xPXqVQx64gfMNmXI zPzksxcoKMw?Q6h|y*1R`6J~n5Y)<)Srk`0reBe;#0{qC`I&c{HB-=-T*EVST5y@5l z*VrK`6~sOJX@@-U2HO{a8~X}y%lxnb@W2AT{x?8Te^9RnP2fdxQ2#t<>1We({a)qq3?VjrF|0@f1*SWQ#JuRyo$Pc{0-(VB~9^p6<;BNkHiD(z6 z@%OSrvP(hd|Ll+gZkE^r@I2cWft#GD0=E|;m4B0?9+~S{Lus+#6{mjDR1@2;d zA8@Nz`-h0z`ERn+?AycOVD{~C;5BaX2=F2okOOXJS-!*d{4-rz?kMc}XQo*Nxarb5 za5H2L;3mHNQ{6r1eS^>cJ)khtCIH-YX%M*S(kSpK4?zrgykM69n!!fdufLv z@F3flfSVRi0yjNcW8U8Xn=Z8?-CfkaTmm;q>H}`B1%BYhKHSX{mZ?#sThU&6M}V8l zYZADb1$p2_?x6zk+zQoD%D)OI%rvV4Hw83+m$`r@aFY|BPj~ldh3&nHtNb_9&kR8j z946Tz1l-uifVZ!fz|GR07TlhHX)Yiq6l(s}Iq6Ek%{(q6=N(ZExEbO)aB6^_|E_bo zyQs+(asw}Nh5W!R{;`<=aAO|Q>1Tc*$YU!yys}8QI0!t* z1%!Z`wLK0z%=ROatNf2I)&=CGg7^qK>#O?X#{fw@F=?QOB z|GJeA_^U0=!@$i?F-3qExZn}sQLbq6GqC?R_iTA^aI-@Jc#R9F0Qa(e6}ZW*Mw{#P z$BOf>+%($?>VNu|+gtaH=lt#-3bVZzxLJ~ez+G$~LZ0C16hQ?SoC7|xyZ+&zJn#=@ zYF-7N=Yl7JM>&3?2@2B_)@Qq0YE#J@r_o zfV*6pmw;Ee0cGH3sjdN^WcxaCJOA7Bp6`TQ7j(BQ&9_=^;3J&8e&Bg?YX;n`jFAr4 z^RLJb(T>8Ne#RjQyv+6~;L&Be;sxMUwl4y&ZAfT`Dk|7v5_pkY+yvfWduzD6=S%~< zz}@_#RK5f#+LvSCUUmorH`jtV@Hkg!1h~nG9P{@6Kh6c@!NC+zM$Wh872swGuLBQq z{6;sY_y4`R%iI@scU_nrJiv{;7kK@8?e7C#yis#MaL-MOQ~m`&k+c=`^&7zJ%tOG# zH|qkzz)Q>{z`Y~dKB~CNe>43GF|CM!Ly}t-2kyR9+m8TGU#oc%c$0ZbaC`n$uG0=_ zp-}TL|9Q=Gz^lBG$OHFr0R`YyUO|h%OE>WKzXS@`ExO<`@bC?qSAa(^)4U42`Z>)f zfybEFF68;&9)e4>LmeE#7i-=CUcX55Ch!Umjm3HsKfpceGTiL{1H4ANje__8Q63r( z@GxJt1HhB->VwH3@H#JCQQ(OjJH$X?98$o`Y@Y^h7M3FL3fq@}^R}J7{~r`pcBlb2 z`}_uQ?>>46{5(Xat9zI0t7QOqV5#O2n^XQ9hX@DCgM zm9#0jntxt)usHclh0L|U3%tzsKH#Q@Lck~4J`6lf4Yuch92BvZZovp}Q$P-QlI`=r zjeQY#g?qYw3GDxG{h0331~|OR+{4q#^pLf$9{VWpD-YLk(!lFn(OjF`?WdKlPX{Ws z6>9yXJs>-jfgAfO@BmlH#Y?%VXlRwLkQ?|Ri6gWk1d0g%WMUY&NuoILINOf^H}*N; z<|iBzc~Hc;1x4T{87G04Pty&k0S|vdb006w?VjKdtN1nV?Eg)&gu$WCzwHvEklre)SHJ!{;+P0#s(m%hQ@{~rK_ z*+NBtn_s(&0yp+a;O27xDd6T^^a61^|4j=TH|iD?Kf<93yzpcFt@o3_qX+1oX#x-O z+xpfO?Vi)~&(z4*QP|TjeULT`0XK)zVc_N?8gbyJCq{q=_UG$=4ix4S5qaRIqGjNw z=PJOBeI2;ziADkx#=(7MyNm3e@SBfN05|pl;O4_?LE!BVqcLyq|IMe@Vjtm<0&ZH6 z25u@;1a5|))Xfv^51CAMD=aevHQ=TI>#FV^GDF}3ZtQ))b%iMZ{Gc!nVc@1h5#Yvt z1h}bC61cH1D6aC~OurcaK35SO%z{$|9^Aqk4d7)e`=j{1s9K1rIvM$IK z@&PwTFCpOVX$ibNErF-D^6!6*fWlNL2Rz3=FqQ}ITcKN223|0~kOtf|pnf&%|Kr@^ z1~`}{)_qN<>r@Y!7JGo376*X4IDXJ@v;Qyobl|8_@c!S;4l(3xp90?Ao&z^MS_Gc( zZ~-Myn53Ho?q&NLaAR-9yL%|Y_AcPOF-cfHP?%q-^8;^ii^ISxJjM~=X6G{kyvFuP zn^XRq=@;Sx^5EckPG98;z)hD{fP2}#3f%NiLvl6$%&xR46~xV_VLW_WZ7OOurC#91 z-VZ#@Z(ziLyJHJ^{|}1NMf!KXa=?Rp6IliR@|FC%V8EZgNpp*DVod`~oWOOk|2Khx z;PA)|I#3L_36uwJ;#7fGd7W_aiAv85d;OzZu+QlN+--%L-E?2TJOsSNKOh(eZqAJ3 zz&(5mHUd1H;6vsVD9j2~2JXH^SF{2=#k>aGwNg*V25=KU;o~C}Gd89GKX6k(2zZkV zhyYLWv0f5*D5V=v)V#C*Zyc;^S_X&aA(}UVzj~JrWbyf)X+V(+@Bue*qFtQE-vo+v zDd^8~IZz(B`DL>LaI@f)fSWVm8t~{n)Bt<_gQ9%5Zkd-498Jqipb&675G89ExQUYj zZsHV)+xc$_Fo8BKl*;3iI_!}a_#fs!4CJ^f6DQov21GH?^84&20P z059L2&|U50Gg;FD6DSPa1d0GR6>{;xqKOmYAE|Q#H@V_ZfFjHe0pR9%Edtz}^GAXE z57o0K4m`%Zz`VWx|3GCU{VRgQH}2DX61WNE<`YfRViU&$+{6iXbNc>2UIAm>3Tw@U z`nEg{+?Cc9DgZZes=!Sg_bs|dOhvUlrRTN^54|xNdAFgw^9iH+uBlF_5e4ZZt(&yPwE1Ez|9wx_yxD;->nODR|kYb zl~}xvzfKEyE}$zI0&c$dCjvZl1AogFaQfhbp8qjWn0Ke+!0S&PVE054xH$t(0na_I zze^?!+CQQ&^gi5Tz_CvRMGmH*+hb&E%&g1GrMyCiV))=V1t0^Q;q@Dgvu^1vHZ zA$$H6Kv6kJ2Py&g74`Hh1CJc+vd6drT)n}d{#B7L)V!90{eN+`Ufb*7P&h(6G=P`; z^!#oD*PrdAlJC-fW{5|6wd`thz5ZAs^Com#VOQJ=a1wcdr{?KEUf{)_bCLqL_Sg1) z;Niq7tq6j`{%{D@Aq?EZLlXf$$w#hH;JIUT{5Wv)nXp6>6t$#I#uV^JuHipE1)iLx zTbx7A-vOBiZa!05(7dz%kFC`;ErLV%cY3~-fT#Gly$syk##exw_XVn5oW}phRb9Yj zmxB8KT+M61t2|_N;J%l&eFM1Jm^6XkpzQ7ZyIZ&1Wa)-4=)d`L0XH9~a|6%M*Zv;h zckqJa1-}38dY1W#+vS^r&FB2X;85mlj{r9xzl#Dle}WMMZa#h&?{Gc;%-3s;bQF62 zE!Hhd0xwPL9!dcZanGfJo1>Z>@aXRodd%{mFdw5W0Iv^lk^)a%udjX;;O0J}3cMWb zw;MQ_0L9aP=A;8&{hnTW>%h%tx*Nccd|tUpG%!e*Wa5zguB#;uZvepSDhav2YN$E3F$40&c!rHViy>w6drC zi-5wzfug`&{HK^P;Q62PkI0fJ%XYn7O3U1H8SAV4yC81D(Lt$M&1^5TswS5(MmB)S(c!TY0z{4l-`F|Z0 zk5qK_Hh@Q0=n6G~n~!8#_iDZAQSy~-I!Mxe*1?~#z0)4=L z`z`(b0e;|hz8nV)H~W9{wtL7Zc>iCwvy}D$z`cBf5dofCqbn2xUgn$BIPgU2V*QQf zBcL!}LY)L2{iGh66!0+LsHA~UzNGDQz+ZjM-c{4*|3Q)D>v{or(XU%p1YWvHFTEw; zO}Dl$121!uR%}lBZ;~az_vKY^sEz3PJqg@=Ic*KNWp1^A*KX7mZAh->-+8=oXi5cf z4_|Do`*cf8Me}=T*#$g&vM#_4JpMD?01t4_LvDTj_k!Zepk88qz|%Z5e&F@hxeds>e|JQkc9tMXv-prP2Vf#ftxod3&7t_{7!GHi=e25Ije!2Q|vNui~lsE0=$<$ zUsMHd-Z@E3g2H^6d<}St@A2xu&0o(pfSa#wZvqdTsE5qD-+u1w|IHtby0oG_Ezjd= z=>|UI`}*?g0p9+SdEhxtQePLR@sIKJ3v?+gt8}jZuI3c#+rk8gO$OUI!jM znZN(P0g6Me)>p+Q@H`*8Szp#!YFnI3`^@GA2(@R6HU4^jT*K;fUK1LcA5%R^8Ae&h;01V!M@ zziD0qZvFpnX9Rea z?UTT3n$!Lt6z8qcEh_-8bD$#dCi5!r5XYGWZt=%@Yc{9+Gs)#0UqUolfXmg@aKQh zpzxfl3&;Vla-b6MpR#=!c#Z9Az>R&qcz~Y&ri&Wv;QCH?wi^dGaO)@BrNE7S0Jxj& zBWzrk!KY|DN z5E|{9{7wn-G~X#9Pn7r_4pfBs-~oB;Be?lFUbHtq<&K$U zB1$s;N{&MTI0Uegt>%=K~zHVc}o)v#T2xT%U#N zR*VQvXC>VKqzm(VxGK;=qQxn}4;8#9xL@!|!H*K$98RkScQ}TJ!E1y=NbutX zH#eCokmNC8zh2mn2!5jAKK0g&YQHM@5}`0Bl&S#91N>f&vcFW=2L-=e@Q~nF2woCA zkrWE^-i<0)^0IKaUD(I@7+zKA%Yv5$e@O5EA8;!BqUL)1qeAh0;Sl4)Bjxat;Az4C zB)Fe%*OmR>1s@T-A$ab7KL1w^{}KxGSq;?_lDql6A;m|8z2`Q4&*-E$`s6?>y@Hdf z{m*B(+W*T1!EY4A^&zbG2?(w~Y@vBjaDDuwc}Q@5^QC!MaP=ck?fDlG3Vj=@9ioEE zc^ng5pBicVxZwJ|6wOBjH`f!p{G?FmoxgTS39h%Jnx_Tt)yV!oC-`21=LOfhMXfB@ zoZ7F(Y_V`C3I~tiCBgR=yezmrbkWL+;5s`ruL{0zyZ=cyDHQvO0&0TmPXcOXUGP3( z-w@m@cvJ9Y%ys!Z3sg_&_ocPgCHQg?$SwH(f_nr%Kya_%2MX>>@cF+gSg!eg;ouVv z0l`-Y9u$0~;32^e7TkR8uTy>g{}7>w2#3Q2j|%=V!DE8Ui%?wf!-f5b;HwljJTLe$f+q?>5fF-^-~)n}1V2{rvf!%)uLv%$u2szw_VimT z943W>yu8)~UnlJAf(Hd}2tFuyQ}E;4{jUs?oi+Rf;ouVdB*EQ+pDegX@Q~nM!9Q-e z8h@WqoMII8>=*o0!2^PyCU{WrPY50o{B*&?#O?f3)9(zShzN(U;8DTP6g(#Qkl=B_ z&k}s3!xPp9p-6TV*4cum1plPqX~91wcuw$$;CaD6ZF8P~1)(@cI1~jxSMZYH=LudG z{4;`A1V3N!YCFgY+$;E%o%N4qflyo}9Q=Y`EqFliYXlDp9v3_$__b|L;~y4^>)HzXT#(?` z3mz5x2Ek*3-za!o@S6l5QC#Jp8iJdJA}Ji?CNm}Y=Y)M)@XrgL6Z{sz^MWUC6^epT zd_nM{;I|205}YTJtt|_l6!sOtZ`WMARfS?yI7|w@QSh4JcL-h={ELD&1pkuY&D+Jr z;7*~iMmw`0CAdrQy99R&ez)Kr!S4~=Yq;9~-zyY8qac2t;C{jH7d#+%TJWIY8Now> ze}#B^*up~bfN+QizDe+?;QuCgOz;Nh<6O~0=SML{@xP4J@NdBID9KPq@x@G-$Ff`7f;|71`Vif;&qNx{D!99XMCAfE^*#Cb^D15@<+k*QA zFA5$I{5ygN1^=$#p*E-Xe@`gFZG~k$EqFxm9|#^5{29Sxf|mr33%*5hGyWq&@k8N| z6#Pemrv(48;Az3P3Z4`ES-}%|p?FRx3WApfFADw>!ApWq2woO^o8T4A_5S~-LQxeC z{~`FK;6D?*Cis5}UKhL~cth}?xBH(AnnLjl;b7g-nFaqPxJ&RC1a}MmE5SX2R}EL= z?-hy{je?$ig8y1@zu>L4`Qt&?uo)Ww!cv|r7g69OEvbo)U`Utg9ydoS5g1;(wQSiSA zUK0GTf|mvVo8Xm%P}GH@D)>&pCk1~^@S5PS3tkue4Z$1C?fw5hgrX@N{wcWi#m+2v zQ*f8yZwc-e{9l551b?Tq{?RNDig$&BPw=MTe!*LU2Lyjl@Sx!Dw>gb}NGLvNE9kyJ z@LhsO1piR*sNmCr#{{<=9YtJmm49mbsRL#6Z$vma1y2gzBX~;i8G@$;-%aqG;E9<+ zkr#?tf)@mL30@R@w%{ef=LlXFe6Hqt{#Arxci~VKd=J4V1)nE)P4GPhuM6%Lyzxb` z|DP`uP2sRWaEt$zTMgMl!Civ)3howsFTp*AtNs5Xq3{|7@x_As1osH;7kqEQ1A;FR zJSg}+#C88u=7oe}U*QlId_Tb>f-e<3DtMpZF~PkZp0MIVv8FC2V=7X)7+cv0|`f|mq8Sn#soha`leA{2)TUKRW>!5giDLRh&QP=Z%iR6AEpF;AWkWVLhSja;pj~bbNe{TLK35*#)@;M|=2>E=Hr-VFAvU7E(0+*27 zFXYQf9u)G`Bo7PuI+90OPN?y_iNKgJ_&muILcWdUDIt%N>|E2Sz?Vqw7xLXC4+{By zl81%-6_Q7_oUq66K>}mK;31MHg#1;Kr-VF4vU6>x0*{g0FXVBO2Zj7Cl81%-U6My_ zIq{NRfgcbU69zvdc|yp~k~}5k36h=1bt>>PlKX}HbCL&z`~u0tLjE<$qe@Qn=?c6= zU`!bNp5zH3|B2)&Ay1L)T-T|E+c&UXf>0#>I2GfD0j@*I)}g*=bsVIeOddDO}z)S_Vz!6E` z6GC1}@|2MKNp?Cq6*!ROej%?Uc~HoQkvuHqRV0r(5}g1?6BrW)$C5lDhbb zgnLwg2gzVe$PbY`A>^-;JSF5YlAXJCD)1P|{X!lmc~HpTB6(QI-wh^c3uggimAb7rRkKO?zc$Ui4}P{=QkJS^m2CkTuR@Dj;mLjFC;6GHwI$x}j} zBH1~sQ-Qyd+%M#vBo7Mt4U&h2oOqMKr~vPfJSOD#NS+Y#ha^u4*}0x7;ObOhCdvIm zosOW7Z4cjfcc9^9ux8sk|%_`l;kNP_mk|L-KoHVB=-w>CCP(AK8)ny zwoKRmRRl)cfc66j;brgPTYm6Y}Rt zo)GeFBu@!>lw{}boeF%3gpi*lc}mC=Bs=GID)2Ls z`-S{-k_UzS0?ETlHrM}O6Brc+FOfVZ==iJSF5QlAU{YD)3j5`-Qxd4#|T;o=5VqTU`Ga z5EvB(i%1?5@)D9KguImGDIxch?3~}Jz=0(93wb5UgF-%x zb}sBx;1ZJig?u^5gF?QVGidPYHR9WanO;3Oq(~zmUgC9u)Go2I=}g zEWmfkU{uIIAbCv4KO}iV$j_2ICFBW`or^jZ_!-IlLjF0)gF=2GL10*bUz0p4GobM}>Se$zwu3mgET`A4l?(kOxV2F6mU@B$E4ud-$G7+Nj(^bS*hI(0PydZ{N}lo_mbr1cV^ef^<-klUIW*U@ zdbittdyOxP9+vso^6Z~(b6$Sj7wJU7Y6e@6MNew|rxk3~taUHl*dNS1N;}7&(7T$i zxvXk*{gO=SY{#bjdsb@}#YvG*l2UW_ec3N1oa4QJC7ZYAl6`VXX4fs-3adZn=*{{+ zHh-_|r<2a*J#$-DHj#85+B4m>vfri`iM`*S&gQMa(e#Jn)pCzjbtd=D^fzXO&FMV(C8NIb0D?_JOz0=#Q7kAy_+)Rb0U0*z@br(IaxbfuH-Sm9Q){|P6q)NNIoE295+8i~t|#} z=Ua`z;4Ct<#%n#U@gv@!UOaug^ToGTTT~g>=3PC`%v(LyN^4ozc_QnwR>mgQK0%kj?F6I&W|}a&!&&6&!NW)FM2bsWy{F+fXpdp9-IC1?asdW zyJuGXq&L$SvRd~#`Z7;tyxBcRorgPbx-L67>Rh$Y71S#=%Q})Ovoi0p8e{aZDyuVt zzdbhlvp{+Oq71wHa#h%JU^(K-|B^<`Lr2Mb?%Jer=I#t#VVmh2~ag&)DeP zd!Ak5jMe0|aQyB)p1EnGv)^%eKaD{CtG5qP+g9B}ub0gYZV8f{qSr~A_pSUQy^iwh z(d_egIKOw!*@ToC4dlupVS0uzJ&j)9U|C0de|-DUGJ0)#=b`sLqB|pNGf#Yw{nMS! zMUMZ<{{4&2dmKBnpZk*Y@xzlUE$z~*RXgalspMbjwXURR-v z@LkSBSvWTPDf48M>Us3`p$F+%ji2iHDSFVfSoQtZG<~KfxuBOG3+Q!i&&8{@(_@Mr2dZ8R zCWoA)Q@y^E{H;1Ba+{vDf;f*rK@iF`kL%N?sKkpl(UE5 z@7%|+CHsl{ovZh{+pd1!N>%I>Jzk;5iP`^mzw?MsZ=$lySf8oP{haHaDx{l85 zce2ja^M9i(xeEu&8;53PZ_GGvIp~)ZPt~vDavyycnIv89sa>V1UA3q7(`&Pfzv4XL zpe<~ia=VYdiHw8p|HZiXxa@_>_%SxFFLWP$AsOcv{x8O_9+&<0SDc3)lwo7FV4SXM z+UcfFHC|qu?RmiYiTM#_AhO}!>;(@vFFb0s!qoF-6t1C|p>r2M?3g{cqSmu?)fqGt z)^)cJ{ntCwSsK(L4Q3{o{mv%mK?emz@w-Uw2s$H&bMK&$n0E zsGc{|m{Pt<^M;q-_APM&Oclkh+(}ryDRHl=ltV4+0*ZL9(&9@r53|GC}O|z zua6kBTPeSC&b23ghn&^e-$RD6)011ynPp`@+v9reipQrnsGxh8sBE8H>-IX>F=FlUpu3Ho4{UV}q?HTvmGc@H4W{jXBpkPn!A6hhxq~ zPG@-#gU%ySdI*ES7XnJYe=-r!XsRt8&3)ic#^U-e9tSfZZ$gDp??@W-4B z=PZ0{da>HkoOF5i^v9eBI&Zu@d(&gi51mKR^W)B;y?##S+n3WNc2j2PKk0RC)_$x0 znf>GA&Vv>_ewDT9UD^t$t8lGn(fA&hXBQQmD;=fm`hs)uz$w(83+4s4cng`KC;mwp zP0xNqJLtV6$_bo+T_ zw`L7C2j0}}d~468&0V)RHt#y#%EWfJ8ZJk03vHmr`*yPqf7G%zTtIA@Wo63L-V>+_ zmyw*UZ+4!Y=-K1Nz8TiFhdQkdN6ZMeXcv)QmS1P@BCe*U)*RN6#EQ%ARr`^JX^8WM7Yj&JW z?{27P%6I$uZ*QfDT6$P-RaA~qvAbi*LM6`{13Ix;spZ~Lx#UH^@P26nIU z!F{bw7gAbXG-_oo9<(x-3|Sewdfs(ZysnW42R+x%a?2jB4wj~jiaSDscPe@Hl;4wjlM<(uhZl2 z^mv0FJI{5r$f>d8dPj@;F7~9&- z!Pa2v_?GLk6Fc@LvQLo1@0G*5))osLJ~+AM+Cw;;=CBKRLD|1g1)S47rv8iI7TUd} zy=QM*yW^F?0oSrU&aD5BV@v(go{UAqIDLd;%jVOpqpony$h@}BYSEom@rv&pYbR24 zKiBCAwJz1>Cf7zUK4YtT9dkM}PbzkewKaN~W|z|&Id>g(#@5;u#IDlJwVRc>dax%` zyOh{k&FXYx5+YuEhS;^5wPpn~myJ3zwa1CA*X$~K=jk7m(Y0?|iLKEaHT*GkAze(W zwNuG(fCDbKS``)Wd&ExEY=DO2oo%x+wF`-TT(iZrAAID(8JXJGhGb8hR3f82hDC(pnqZaC^vbJlF% z@egQf(Vg`7wY<-GljP)w(@)oWJmddPug|0vMZJEIUKe`KEbaIos-R=`75D6BZP@vT z^;5{g%rebLJ{}4#_*Hb6$;$(_QnGB-g3tJE-ES zB~Q?rypt+!TDFp8Gc43|8w#}ksvYguRc_fmyJ*#5a<9yVBR!e@-aLZy6W?6^UduG${9<+37PY3xd$@YE6xnJVdD`-wrpz>D+ zpZdu}WzEF>$3InGVA1Q1YbNG7p4v_szew54qJqfIIl1io<@BggAQkM(*J%I$j$515 zotBd-7>p)|E}+LRsM4xI^VOA#e7Dd2^a_g_vyB!t?y1DJF`u>J9?HlozOyEC7ky2} z<(I_*D`wBR$Lr{ONnP5g3yai+#c$A~M&rD!z9=(z(c;X7Pw$<%V{-3IZl1Mim4lLx z3aEWAxOF#Lq?+n=AKj(UV~QTH(BmlT4V9q3x?ERyy(>91@8*OS>}x2ka=mJWQ_jx> zx4v}~)$)}S26jA7@-Kp06{inlT~}YNd%@wj>!I!6Ca$`acCVEYvZqy%?XLBFGquEy zOUv_z6w6fbk1DRQJIY~Q>mozf7aR*MNB`387Y4W5P9ytfR8TinNR4x}hq{y=!}NIP z((D`GbuLZ3LEY#{I2O8oHS5f|WaC3GwaMbs{Dt8Tc^$lZdLxl{l>}ffTaiV5SJI6 zNNMq3lolsF<$b{Uv8R@8OReeua?ew0!AWtqo=$o2`dRC@s!HdVCWjuS#~3}fU7G#j z_nb=?{fH|4D)rbMm+em#I&A43kpq_gC zQ)SC5f4X+rwry+npS%94<+I9bRd4=e;=VOMoip>P^1R)idYBus{c99tb#SX{^yq$1 z+70;Y)w+>g4OnPV{Wq@Z-;;8j3S34D=1JU!-KhL(w0O_0~?cw`s*;M{;Nx9sNx#roxZcY+??v;*!i(V%yhI z2T?3FO4jcCW}fp{n^bJIDySogW$}G8vxvEBiQwkh?qG9?Mdw@B@7CPhGr!q)tF^h$ zMVE?=Ck@c{{Fv$Edp@W3c=bQnIXa;D^#53`6rBLoh`s;DbawhTR?Bz&iR6D~bLa7= z47|5-=D<3N7rV}CUgoq~%|BSJ=P35&%IB>0tvATWo=6FpNuN-A5}HYWQ~O~W1~roo zKj}HsN%>a)Sg^H@CY8f+_e0w^o_46p zdD`pPaqU<%c@le@U^FY6H|p85W7~-XJGXJL`7?B|gFC@$j|aD^*{K5lQU;{T?Iz;A zYT{9k?WCTvD`(;@x8o)3+Svh5)d5Q!@avbTp6DGvk`_9(_^qTatIhhv=JRL~yp&#h zUGyy}kKI3%Cw*OQlAfJDQeA&&$eyn46Kvf^cJ`ij(wTYq@5<(+0lE?#qlV8ngPxbu z@Xk1nUQlZb3Q$JY)ibS26y#{CRO^eXP^!dg^-Mu`vsc}|mD7~f(>;68cDpgdlRfPj zIx78Juyrk2+2KE!WoO1!N~U7!?~_b}bD5G=X-eJ}Y+bBmDmA9$XM(K@luV`j-k){M z@2961Q}xqkiME34GJ|DD=E4{))1OWb&7_)4)5eu;(h0SW+eTNe%UtNSGLP<^9NMM( zKm|#6>3glrdeZ;vqx5k)315;N`uj)eEl1`8(*LESPjnY>ha>Y7GWa7I*s12(D>H{$ z_i?)Xsw4KZdx9->llIvjtMz>~V6>f@XZP)1<6g2;OY2g4UQD*iPE85bVyBQ7k$z8- z_n^lD`kZiYohF_#4mtEBn@0xf%>y;^il-dbG0Ip~KnLv||2L|j(ido=s~b1Pm24*f z4e2hGIU6ZsoSZT0Sq-6jRtck?Rl;1v8S_taP#N>MdZvuImI_dJj{_&o*rZmA9V*~* z%86Y%C;p;j6;R3B=sK=sl@m&)ocN=XRZi@hbwXX|Uc7)EPDQ^>xAWdhGDCCd^}p2H3iNswy;lD3knEb@qgKSs_F2{{ z8U%IPIZiiLt@Ej~m5pouY@uJI^afSz;$A7qZ^2NbkzW-pD@tU(RElvl`jcUvMt6CljTjJr}H7*U(<)*v#O*YqAHu z;5@+j=09wsel?qn(bsOA|Czqpu|#f|EXrrvP}IjKFL!+qS+8Xf68uXOaho%HX~>*#~DgQC|C z*TGBGPU^?Tmu%ituV2x&hh36=@I~jb^ak3@r3v?oDvy5kCvty?cKtuKp8jCtoJ@X} z{YKC+>QsSxeS8zmEw!&!uVbI5+gy_Wn`~lBXajG#uDF{v^f%G%X_Z*v_?{P4?tPo` zuHp>Z7u7#IE&HMxyIWsWW6l!>5?`W=Dt+Gl=qSPSXjl`YR;$pnp_x3syw(b(hH8%d zb(J|*tL#j!jZlHAu;-kvD_;9R9sKo(A=RBqGfS@=25D|og|lMTSpao z&ZaB%Sxwg$W8zSH z>K>^`uW2S0Q#7P2{$pmw`pmYq%QEFP{f_clyO)0CX!TuW4J409u63l7Yv}EbwW^XQ zQ6+Dr`|J@wFr=n zy(*F20;<=aXIh6(f7{WTeu5s4J6h3atPOO6k-q66+5ylJ)%3%}zfO;@Ia(eEU3_T? z-JM3DFKB&d@CVigI_MkkJJ0&(7~M3!w{7=K{qucieYz+3-TJoO2R=2^`u(t`VJNFu3Chbe_}vgu%;iF`MCvjVJiIj`pugcp4I#T`8_v%#O4(Fs#CM) zdKNa7ZRNvRN7ui-UTvobl&sPsMOVe6YXm>9x|DJxb^QtCw7#{Iy6Bzddkm-w)XDI! z2j(>2Rk=g~>F=nIu6=!d>nc?l3iK}d*O$}zo+J2Onzh%dCC}l=K4cv-D{}%3ovMso ziH$TIWTz&Y>ZRY%$w+NCf|o7HF8MKCwq{sQPv1jj+)0m(bV5gS=odTfIiyqT;#nE% zDoU;GdJfTwFbjM$KXKhOof%GFK@U1VtoO_v*zupv zEq5<;mZq1_9jH;=xA)A=(C-FrI-VZWbT&DCGd-x2Ty(z>qP?QaMQgiNUaQV6lM9n; z>piFHNqWWlmWMiU$9?zzdd2HcygB>OUuK`!>YS4}i~P@}$EVb}$eaQCiQwk+<8yRb zw9E#moP$(ZTqjjOyDZvfw96u0k`DI*logBU-1^Uh)^{fU&DyY->hkCFt$z;FS;>x# zb2Am1&;c5>`o_5f?>MdRFCqJcaTwjyad6UFy@MLscA$=Uu*dp-A30R$ba?N--})6b z(LPI~<)ewHjaEj9VCK{Q(D~=ARj&L<+9le#du_8ud{B#+F zT34giyhFV&gIsKaY&>P){f#p-_Of^G`qnm1mlY26k%(YxCyi*G-o7}6Msxaj>eW-} zak3i8IRlqJFt2pk!g60Dxo>TNt z(oxnosbG6IM4!c&eP*ypbD?z#ofgnRY-@ToJ&vJc=Z&)mF1v8|W^Cc^&FLS_<{_P( z`6-q6JyoWvT!Lz+YN`s2EfIy1GD>S^edEVb^Ox903x{~L7&9-_PN)Sh&@ zPvf@Z(r#XvN1TRY$EVh}TFado)ne(VTCXbf4(%I5d#M;?dvbS-2Yam}W4+edPtzqc zz2YkRbTnNiSN!UWLoQlKpZ||)BA0ne$8sBi`w`OvGV+6 zcE-A3+gjiD^-XnQQ&+~H+!lO*&ih+^Icp%gC%tD-b2QZjt*#EKkDp~9RzJO)Dr@oh zKB_;rojkCkXMLhI=?s2XEs?5I9X)qFWSvKEG^omu!OrPm>mBNxcd2t`bI1SU!}Y)E zryF#&v|dij>SwJvuWb*~>1PkMjZ#m=d7X0iUYf~PkG8wranD1sb=EP1bcRd^kH47R z6C7Ac8MV%lm~(|=owdP3?-03mv%a%zhLu@1J-vZG^04xKx~N=AGkW@9>g0pyv0P2M zeOAR}Pdw_%Sl3cd{4>~GMgvqM+vvg6`u~r$HxG}hN*=%O5|ZvDgoLaF$Ob|dKnP3H z2+~OqLqNa~Kye{}I)Nw}aRCuK5Oo4UCoSkza3p}vkVYI7P~+$Tq9YD2xZy4dpa$Xs zvZWR5_fxmKNfU6s^Lw86kK29kx#v{XsZ*z_PMzf*QCd~}7yJdYF+5aA^shuc@%CEm z;=|~pZHGg$pt`rOMI7^J46mj4s^#m24`fR(LoJi@QoT)st-ZBPAq5zFIV@_Ls%_`^v^3(qxvnn@k9WV9mN?qf*qP_La2&}J4%ioC2S>v@ijpQxu zfxW5o*_$$NeYXqYRRO|Rh46Kys`2LtpUo$Hsb+Sc@R98yPzw8{8KmQRJhAnj4T_s4 z%4uGZhvnElym>Q|d{xVaF`zp~>HgXrpmZlvg=^?&Q_j_wQS=Rzt^=)GWZU(5$dKK? zpQCkMhXR41eq?s+B&sM-=_+0zxuPx#zYH1jDKJiF{a1FbPc%(NqH8yZ{k~iCwAlJaYWXW>BG7N!54Xf`6V)Q> z$DICL#T*es^5$~5!$d^$I^oXJVcp@*Db$k?wf1_5;{92o96N*BsM;Ciql)o=JEHz} z4pGtdOeUR2)N27mxgx~OBxNsoZdvitKF{9nadfV4o*87zm}s4s8Et*p;|Q{eUT`$Q zmi-WMKxVBN^T(nfnrDu*RR>d(og;0#SfPqTQWiU z5mAjyG|9aT6R+jD(4kHw?sL0EUA40862)r~-etQ=dyC+RtoPI~1lD2oa?8sp%l|yg zGbPAWKwp?}gG_7SRX!taE!u_&M)K!ctat2G66Li7ClRYl%GDk-B zvcCbQSPt*9w-^U?j%SLniz|f}N{q7QH{VN1->-M&U7~9=?;N_)Qp)-ciFu8NQ0W_& z^Y3wl)_bn;nyXXa2bilhVdt2uM)GW5yl9x;M2X32)Kg3Rp(J7tP&yd8a0!k@D`I- zx==LMOVQSL6s;19$gry)6qVcEA@IuNQ9mW;PI#2oP1!OBY8tyLgrD+UQ($Vg zYtU>un(a$PCZLAjM{Qbhu#yYVY(tciCf+AcQ;w!Fv3v+0*s>sb#>AnfJ0EOo?Wk<6 zFsq;FdI2JY4V(CvYG({*-xFP_n&I}_Z$41$@mT6T<0X=$+1~D~&TCv=J$;t;|DyAk`jmhA06cTidBw%3|@d;&4v?%qX(Jf4tx&m~^bwDT;i*6^U3!|ZPB zfxK2F#J*Abi@Fdms=(_-S@EEhAZ6qJWZYbIQ{zt6d6NGzy5Q;JdI2~Rc|C;g*{j)m zzEDYJ#QWKy;YC%4JC_O}WN0~n=Z~TL;qp8q>r19t7ezA5O{pKoc-^HRaRoNQsqI?L z%4q;tqb^%%>7?Ym-plJQy^Tinx=W$uYa*1Ay)3i}^p^V2be00|xQDnXBHqQNLLF0C zZW;fWv*I%o>l#mJ)VSm&rZd?S1cGrm0m(S?-mR8mtisr z6YDjj7uJh+XRVhW+-AJ=VA~W-ssyXWc=@eq<9C79G@-r`n8Xy?LLjZM$Ztv?drOOR z#MOJY(e&#&*fL}+^i~I(u)e7(n4oU3^T4_erkxs369lULL+dU>R=d_W3y)GGQEj-*9}PWjLPhbgtrA zD&4vu&#Mv#;=+T00TpWs+U5z4k|t_$JpXrvDT76L7jY?t9i6G`J34Oxff9`T!6L>9 zL|{UkMaZZKxa7-c{FT~20_RDY;BuKdH_r7m|8%V*mIopv{Nf%>5b7|&E00I5_rznW zXAm1iTI zJHPc94@0hp2Jv|GdQVp`V+WAO&)AHu9nT5Y5OsDpGE8b8sM!S`Q>X4!M9KSf>Q2bo zP~g?6`R$mUE|ig>OnjsscJ~Uf3e(JI7+1@)h{;@8IEe{gChyS(7Gh%6eg3%V|ku?zL~)n!dZ~#zLV!;MxHTdu%7A= zkIrHx-lLA#EB7J1lqjB1R!5Y2rW7V%);s}V1kLXM)e|q#JQ0(^A477=;U_%avlu>C z39n^FPwC*CxvPV7QC4NKPR(VxNge{;NNlr~N$*DDI1kIe9_DZ^GZR9cOU;B(XSMv} za*D(KfZXGH%Kc(9U$C>%%opsukN@vsfyDKt@!ytShdig#mE!`^cS<^@znWo*Eg=0h zN$=svw-w@#4)nbc0L{`ybclJRp^5?Ch zY^XA1n*W*hW~osQCnTLE`bmcrL@;&{cH__~?@S%kHp^@uj!L+%uxvZ>*0hUDX8+{= z?95(|Hapgem`jhH%zug>F@&wxfrl|aLb@nx);^gqX#W`30+U4rHVdq4@)r`Kx>Bfz z-7N!7Kbvopyff`)UMzu`-dsh^6UmGJGLp3Sed%I+Map+|QF8ogX4x*}rGL^KjOdC*)}3ve`7dYFOm+oKkGxhGe7=!G7FSLK7lWIq{-?WsMwBX`;4`% z7sawJ&zHniV z3*lSvV~m6U(fVXokrJr%_elvF&4hr`|B`1h4!wsPKQ(J<(PMc&Ycywdaw>Q3GiH4?;E+Kt=u=2s7fh^!=+I4NVu~J6O2k4D5q4@OyoDr7H%4oWk{BEl4pYoQ8 zzWU3J+dtHLId+pz@}&Ik*~%UYbK3it%XN%poJ+KO3TvnC0oP*~U71aiX*K39oO_>& za%%DR+&V43rir`*sM)Dd*4}IC(LAE1+ceeYxKF8fFx9NEs_Y5y;D*)K1?O#C8)4rV zv~cI}(oiMYtpuqXwQyx)vZC6gZEj#*`gSr4i*7q$4EadQcFg2i7NG_%I=SA=6YVOJ zwyO&M;PkCA^}qfpw!U>*T>Z%@@%6{YC(xE%*wPT}6o#B&pXmCT+6S@&_g7sf{Gg%Q zRM#jBJKn^e{7q5LI^G}9yD=S>?22XCrf;^$G5j}OcdpmFw3g!bCZA??2y1!QS55Z1 zEmc!mzl0cZOO)eLPC?Ry-mC&JEx0FjUbqQ(Khw3l!_NX8{&>C$%(&K4rlI^WB`(qo z*B{d~=lY%62m4GXl*nwoJ}Gy@hC5An@3Di-YO^DQHcD`vWNcMP38v$HPSoVqEl?9k z-6ozr9tQU_6?YlqHj&b@P!>;U45`Y!L+3=;dv~zi3<{5cD@XU~ zc^wG?gk4;w+NVw3Q}XLim*>^D=GYsg$5u7*+YiAyVvCF-Ku{(hv8LyK@=7nk13heH; zk_9TUtsiv*VnT#IgZydZ61s)X?!>KmnI zrb_Vk$pre>zS#qFO|=YgQM(arU=NHF%mq*(CSG(_9y4;)-uoeoG4~xnp2xqWReM5m z7W3ZZ%F~^lmr>F6Rbi8JH|SGZmy%(bk@2OL>`%QLzNd;`t7$qkJs)XBJ$IExZbwI0f4{85=pt z`0b0Jjt;-PwbFds9J%!j9^G{q-)-2rN;Yy(?8sf2ZaV_#ya6R7gCEj#aKqA!5c)sG2d)?|T zuDc~8on{vq2Lz;7NIG&W0A$Q3`GsRN$B;%imP%SrE)gBm+oiiVGOG4_*#grXl+qF7 z%<>KZ05Cn6j6`I+_<#y~1&Iv7{BF0{*()JHY^=zkjEMfeLfEl|)v6(dzcN}%F8X&^CGI>TF ztnvYsXK8bTXVI_+Y(Xmmw{Ct)%2nS@<}|W6L?O4g(b4?c)OPN)EX`&AvLLTrECFvCW6 zW#)g3%Srv3J9Ry6>^Y{zXz>ZgeJ!}N#?_*H<6Q%;W$9(2cj^CaY^;%cvum=t{w|)y z6_qrF&3z?2m$BuRA%>Zj%0@o_@_)&vu-VVMJ}%jn$qtOOuvq#(GZ5DB@s8K>+5=-} zpT)Oa-vq|)Kk=9GCtUFWn-r>S5rEfSudKL>f7waa#I>JGb_LBeD-`ECa}9`-@?M+X zEAO=#X?d^B%*=aD%2{fAB`IuoO6AJ`%sBj`7JB`vQZJFar~6>G-yh+F`MtmdhRGQA zTwVV@lIH2$c?6wUBaZNEWTaooq1FhBHmT#52Q-yqQYwdacQ#gAIz z^`m|8=EH^d6bfg5yGlf*jY2;czGnA`p9_1qKg)%F?YWRr%z-_$<6&QkkFQf!+;IV3 zd|_gWaTNscV!rU=Jj(5ElNZ5}Chf*IKWTA61gK+-#-CWu8ve6pu{^ksrLXh}qj6GD zcjJLpt!u>9?71!EvK<@gw%lnv*QyN(y#m!gnzW23jGtPyp@~n^ZDd1mW7Px08msQ- zsv0(x1A(Ug!^n4Q+3G;!PPcY(W`{=1EyVm0IA$?S&S)C${LdLrWEPwA zimYKZW@EB@)XpY7?l-0Ok95ieig|xkq*FpU<~_q}33{6M36bVLbo0J2(kTH?^S)=K zQ%0ZWJ(JgN(ASMp-1c8RTV8T0T^siP+Gz-KU=9xwsXi|T)s3>d2R0cIr?p<8VunT1 zHs%;j&j=UH&d$d$v2V)}i0lMi_E0!}xy$i*U!VQuf?(R{^_*ysIcDy12U0)6p~+ zgK~maJdE#U>{+bGb~rlHow3nyMdl)$}M zjX-Oc6lEoZ)rYod0*3LJnYfNX?Hgo-*~jR z%nHg%bG$YrXhl3#Zf~Q6hL~aS`skxcdXm<=@zG25M90ft!^sB;?BiRN4&h`AEZ=6* z{Jb&w@}OdlZq6*o$9m?~p9m>vEo$_{o6B&avXc+HW#ozl{Pb}u;<`iy>>w8XY zQtXQJ2;~C!d9leZd2tvZfhIfq8$?I(iiSn8)F?DiQ=<{A>PfvmZ%rGZMXH|G@2!Bm$H%|Ez7u%^2%wpmJcBhNg7n0ds-BtjJVXY>KQj2DCSUfP%67~cfx#oG1X7}*{4U$pwKj9$UC z>!PoXQNj8n+VQWAFM{j9M%}e9L^vSAb{nGebxc;#A?H9(7j`~xhU}vppPLT!6{YvYJug+zm|Gh}QKhF0$4uMVc)LPp5?x>e3 z>&F?`cV7Uf^xGSd!$926esOMdnq`j~Nu7}YB4Arn@@z#LN4YJk%28_6Fovt`T*Qm}}5y`DfBSKnzc#AHGSUTc8 z0f+-Dc?XC^t@H}0q!2L2SQM#8hnl<+QKo*8dg4ujC!KmNnc=OY)UP^IJzKx40?-83 zuee?Pw08CLb%|QD+Z;8X0+-24!8I!YSD6o&R4F$AS74R0eN{Tx4rd?QEl?KBx+!_K z4BATgnn7KdO>vjeR;8Kj7fuO4;8$FMf{@ToaQ_d0?(hJ3BAkBV4h|qxjD!ZEmOd}N z7^Q!xaWKu282wc6rJs3>jb9iK#_AuYm2mI%j$?^5E3VrR@@-R2? zektQ#8MbUAP;ZX-Yn8G{BkO0aOPTF+Z?6%XfL&jKa`E<@l*`=tyGEHk=MD0B?PRp; z%}>2Ta-#paqb1?md%QDyzyKs34wh+hx?o;r|i`U~iE6_Ua z8b7V^uF}tpzs2jB+C!fkAI9tX+5;XVE&=`Yz-LBrf<7u~COq?llVR6*(ESV2e#0od zdCGV(0mYL0g)yp&KBRvl@5%zqe=%hrAg`?V5KqoVl(jMO{e2>MOjgjcSYYXs3oUKco zE9O(9=oc+Js1S2$Z2DQ-qs{r;SbRhqqS^PFwNIN$i4;AKxd1Pe$vg*g4*iyq5JdYV3-YUO;iKbPuFITN<2T z+AZD{N=6Z_y?!6@=4TRFZprXT0r;RGpHCrB8o z$HKitNRUxxj4PD18G39>9es#kk=w4v)TnA~O%Um;{cTM84RGX?HY$4gX^~5B-zt?Q z7QVja*bR-+JpR6w${|o`axm1$k?#DLy;f;51pE8e6o`~M{kiY?eXEpr>6Eo>^;*lo zz9pT(Q>A@yig4k{DIs`Loanj0>R>9zJl4}?QgvHz=jGI3JFz!Gm;iCCjN5W26mLD; z+j)v8cHCISxt2h*H|7}YGU!Fji47K_K866_I6U(MN!MF*raxUxU|Vsj;hS!kK=$`k zW;^N4UG27H)e%2i)R3h^x6aLq0Ex@Y^0k^9V0EWGTjMxwM}R*=`dykr;IlR7%!1L> zppf|6<@KkCNKrGV)KDrxknzY&Ve$H&&ip5PJ7=!H$eGHPn7@Mfy!YcJgOcuCLxx8$ zltJEq*4sIq(fdOedf)RR=gcQBayG%42Y7GTyX%GOJ;svmdb0W-qrSU7SDj>ZPtxPV zt$(g8UJw1%9JXfIlk}b`=TWl@VAZ{x(;4ay5@5AS`XKc|>=F1<+S_GNsV@v#Bg1kpiqf|>$sZWu@u~ui;S2Yc@HX=VmY9!m4 zIfIM*(XMZ)T`cdUX3HVYtFRJXUwz2f6{5TxNpwYmShn9!q!MPD13+Pt2(S}mE+lhx zoU-LZ5KF-(y-Vh;0$4_AAi0CQ%j1;6b-iT1L~$iBd9XO6qWeUMa~!8dwsvgzy0ROMo4 ze$2(rI&|{^JvwtAbRAouWZ%*38FEgZH~e{GGWU|_IC+NR@d%v)2i3Vp*`DsqADiKv zc_h=h17&m&x-a-XH_PEn4XG^t>W?x!ndQv0Ru+q4_yYjWCf>jENAH^{&q9Yc{^)%- zM;~V@^S7`5QHI(+&PBZ6@?YNPb*wCY_K)75?&Dm;`=|ftz2mmN&P5TG#ZUfG1_)@1 zPRd@v`(>PnRl~KEi{9*t!QYX8v2LO!L}jFB5rLpC6eIB+yZG(@FY-k7^a$SIu4sE2A`iqM}2_$9Ce<5W{04bv{K+3&7QgmU*k=}Z@ zVee5Q*`m1dtoB&koRJu*oXLTw}9`fUvJtSA! zq`8xr`t8FqAo?&}gEg`4($LD`{?=VOPFnXeT&|ILp9RL0B)y}NlBEZweAL?Jr7r-Y zbgYNKEWP{l47fNUOYfHN+0!OXg3q$!GIz$B0<*uLq=Zyaa4D6HjaftR_QPtc(D^iH zQT{bAFT_R&+O zz7_!4r2P{j+6zayg|GgeAhcU(qC?Oekg)w?9eU`uEinZhF{9fnd*+J_rRxP|yry!Cb^;1$(F|UhG}0 z;~DHrp5rvNXSMnkG-jq1*M&A2@sJ`S=w8hfy+rwiN`afv#dxkSa=xdp{Y)^i8L^lC>eov*pE{mo0(Im$1XZ3-P<}gt9{n!_eR-B3ht+x8xfGcMt@9D|{{Ko)}~5wyl@&(7gcsrB3@tFt$~Z46 z=TR~~fRcmnd#t9`<1FQPqj7-V)A9d;)_DQ68GnE_GXU*2?xmRoYr9#eTfFl-irsx2 zPu;@5g<*kglc{DzC(~Xs#1!u-gZ~uLSpa0NNGj$1A};@=la$puP=?7TyOO-upDqJ3 zNt14GRA%c54q5&hh^g!kFbM^IY(mBK0BmV&<`Js=*xFMmFj1!GQIB;sY6j{9u4{C3 zsBdD3)~vJU+PerWlOvaG`)^emRuI9JG&X&$XkN#vAla`3|F#jLI@X(Ed8o2=IwAvs zwxvYl4qa?_hxyKgn9X?*BaAMC^d1f*?Dj%Jf%>djxsFPuqJVW=W!;o$i^@6Fj3M%u z>CU>%$_GvCPd}*ZnU~PK65uo6)wR7FOuFRr+xSVSgk(;F+Rsr75?zp!p!OrlV(6<` zC^y(^=pD8apQW!x+~dp@a%`D+&)io2f`luYKk{1oH30WooEX=KAlpXZ6C&uvL!2^` zSw(0^7Rg=j#!Iju9-NvZ1N&y#T^6{E7@jr5r#FOeRmRZ4dUllXEpX@6W@F)Cy=$*< zM3RHlY=v@E9u9?tXJKvh8PC>Zh^e3*dD8gTU_DMfV|+4L&v|UO78zax^#U=cx7fQO zdY{q}J@txK0(31bu#^4FlgPo${H8+UTNz7o&)w-Zk+2N=bpv<0HBnY*79V7m&|To$ zW;D_6{x`6U?L+j0p3UXpkeJ@Y!X>g>#;}z0qHF z&OxypQD078rr3-pbM@NGuCO5N5V8&kLI?(alOSz|hz$HzA*cvfPn@ClPJ|F3jzpPJ zVbi-h&IJpqwidK7>I6e#~TNcu%dqBXqudo!5yGMEh_NTQnu+ z?TwrS!Frx04{f|%MuC0?LzvAPt-S1+qS-QkBRT=0`$f2YLNUacK2+~L=xt6+lOjuQ zdG2->!(}NZx?9$hOYzW&$~^y&&~l489IQ279ZGbvvvCvv{g;e;*aT3|k!$S>3vPem z=Gnf&g_ltHXJg?ddhgEddr|LqjTbM`d);s$j$aGM&ru`3)|gCs9rymlzjt94MUAB0 zq?Cv@5H&JGj+3GnuMb#nYuJbBH#pvUhYrhxiMgnDig!`%8lXv#Tc!Z^0e#=>!Ct)) z$+?d}IbbfIN_LeqHRRVD%>}f5+u~+7ftO9GgUG*Ab>?$4aMsDTyk_6@3T|irYG@kY z+gbl@3?8oc=$wSC$STW1*%Vj67d75BW)IhwI_5&JbUw2~OdsY{I?C~6JBFoov~N7y z85$Q2GxvbJtk{w`GR5SkC|)1O{zKpNa?HDB{xEekIX0<{W2WMT_Ol$@soEx~iZS<6 zJ<2iu9HxcT%YOPmru`|9Y3~d*nc!Ep$1co>^Y|cVh6F0D7X>E_X?`ul&`0Qh4c^U| z;p7P8rz`a|_Cdx4XyZ6n5}8GZrDuAlCzf;SiK(HUS1NY&r8m+`A13V+RB|&ac|IKF z+a^&7m>Amvo3kKU>FlT`FFWF8WxC{l2rU|@7oWpwF#gG&8dT{h7Rt&P6i8D|133#} z28~BONWnWmq@x~19XOhmid0TSX-16X9Rs|~a$KE8dS?@a><8Jcta0Y>XSYP>SyQ%E zAx!q~-Q-DTTL90kxTBC0Uys{#_8oE*=9eGe;5^IW6CiE4QX*7KmwO${ zUA7>3;%V7~!|?nX|1OgP#TjoJ?Rb}yT1n?SO_}DOeMZ~teBJ1LU0wAcT3vogu2{_j zd>%`Twd}1Ja*hnCPDk@VdSAe1B7bLkl2t%~%irCC5c6y{73TQ_&(elwPx~b#XF2j9 zi~nT_^Awsvj0J0=oz3*tLp?65_uyS!(}RUO>-746vH`CQ!mMYe89QIqqSDG>Ev7m^ z5WBkW0l}}hQLm7>u!r%lS2+No(9D+@kT217GxivNJj zd_m6;VK&VR0^JCw#mp?i4?87sW%65ELUOM5<$sU-l9#<^nY?q@(hrB^uwg&mlyaW~ z7a#|1ZS9kTCFr6H$w3wArXKOh!8)2t^vL2q|4j@gcn^^%3y=e=G|PXHgH)d!pvYJ(`PmfT(#6jn2wwhjV(k9dG^=VkM z_rRSi$SgK)u90z>J|?QYx!Y_!a2Xq+{tUWsj*l??r!cRtu$Z*lAyFFqI7g)no^`$LQU;}?!72^=N7i*Z z6#A@dZGMo=Yh8UE{m0`078AAD-opC(_(Y9<8lZkR3C;r4@yU>2bJN1JM(X8ySMe#% zYoq(Aj9;PbEMuCw%nx&7)|1lm!qxE?*#!??Px)kY`sQZjbMS5@b6JueK*&|t$jTVr|fONI%jn9ji zzkku-EX|AQujjrUW!T2(T|-yO)*O0uOR91G7`>PkD(7bFNxk>6%WlmXPSBz;PSAfH zq)D0GsX>&Db;+_MhY2zz8Ouaw}>jK7c7C#7uOMUUIR zW7yhY`^IEkIvE=);^J{~Q5iPlrEXW~-PFr&Ae$U=q;WP~{C35b{Dxv<3CBiFqP}F4 zV%1g|)3I54hGP4Q{4JOSc~{6Mh01!_>%)zxv3j&oI}Xpd7%rwq5sOA4Fbd6cGS4IZY3L!j33792_x?z7x3MM96D94DK(VWLwtm_ z`g+B-BwOX!Jf<6<*H63g&Uih=I3A+M7&lDNBh@v=ofGt&$Ra@R1GJD`M_}D}b%K6F z&-P+)WMD zQGKP}N9|#3y;2{j4ew|izEba%+TOpdeGBPd$2LB;*5Q0RZ#M=M>jT4&kG~9TBkNBw zjcD9ftoKKPV*}(n)^)S-e6c?5yyOW+>O?&{W&>cQ7N?R$NaMUhI$@&TE%KOelafEa zW!yVaPYIXl2{WZH_|}tR*}GUdx^=PQH1 zOU=!3@{um*ezpmZKGJ41jF(IF39;Fd5{PfE4!-V_z}G7f-`s-ML$J+@Z`LF|D=k)- ztow#wS$21nJkRtwkDNfz@h#)UNqT3^S_uhp>>$D8*}^=3 ztzyAj_BBvfSZ_9vdn#IV3Tp~=5p9}QDqj|SKfY)^N4JPN&rDJ0cy z>qz|7PwNtPmX3k$Y0zD+K4h%BO26`=*Pyo9=VzR#QtHtNGB@Q+)e~5}=N-v^Y;?I= z?~#!aKtL15=KP^U3_&x3ea4Mfv&f<=Y(KML3>~?Mt~HuHpM~}AONe8!RZ~L0Vstx` zr&-5&mm^weo(Or~N$->(Afts)c}8%mIZ{lvfo_E_BFxe~3b>S4hdc8}Uh16r!w6^I zxXR+^5HuEiIX4{fgqSy%{AhHZs%Lk(B#C|r0%;sUkS@Ui5PWZ3H&ss#-$$~Lo<%mJ zcB-CI?B1z3uLXnXeo-!bzwVJ==_U-)vWGA)`eaQu0V5o_-soKPzcAZHA1g8iBeZ1= zLyMniXswc%hPUtteMyc4|jiHBwg+WRD8w0M<J&n7r(UTmH&zhZ^{Ha=z$GQLhAKxeTHGP6B z34NW8C`f)j0%BuTVu=VV0w~LlW;>Mx)!7TdsGdP9hH)}t54&yE4CU;R8_jYW5ZdTA zIJ^vg_$#=dg|n7z%9Y8nY6Td}@&k1-%1F_nxzkg*SG#<|*{d%9pHx&i* z`ho35+>c?fPgT=F_DR`LrJ{1br=$x48qoM=+u#3_$G9F$e&LhTYQ|A!N?ThyTqEI& ze7~x(>WyI@Pf)$*V*C<_C`BDM_h3VG3g7DiI0KDZb1*U28!kS8mb|;N0 z1B%yE+6^d>$g=~A9*TtA%%efp=NtE2s)st#AziggfvG zV5JDsJ5*BCwZb$JP12;VJD7LjJP*f8t;}8hrZk|9yE7jC$D`x zDS$?6+VTbwR-T@mIjnG1?#w1 z^QK9Ape)wQ0a_@CB=ecUCkJSWc{DvB89fJ7z>N~|%7RY(mAR%aZyE1R*W)4&!Tht0 zj~X*alULpchtD?o6un-!x+b8>AA=Xtl*u!FWxEkI zQ}3N9UlkL&P8{aH2YVIepXZ~8jpCVlruvMraHc*&ebjhuCU)#0fQTLYyeoF>$V|ON zD?e6PNHofk{kWPDPHd;S#HP71tClH=XA(b}4Lq zWsq~~G2OYKN09T$upnoGM|Ylz3vw>;j$Urx)p-e%qVscSr6^a9n59${;yW$HB5asF zOLoyZYV2zAUfJ0yBukhv35_WsBFAlNMH8l0oF)JJ)X#Kh9Pcla_xCCl%|wl*iG_W# zqdmV*kh2wOljlT40GsBL2(rMoP)-gj^TTQ)DyjeA@EFDEJCpMWHYd|s~UneQHIYepMqlt@#` zQRSn3O*ulhwp1PSl;kn+lQKKVe`dj`dgG0o^sCZM{`f}xvIat)Wed_3uM_1^Qa*0P zJu>I?OaDXwYe=2Aq%pfKYTWJ-s-bXy7Spnq|LGDkK>x_HB)og$=RfJGQEAKU^#{$SwIDWDSD2AnhO2Kc z(__knVdCATJ{iOSNQMN_u9-0G(J$GWe80_?cghgEQR(i%$Tj) zwYNfy*JtZ{jk;H#fC$vk0y6I2yyCd6M<` zmhCvHaBUCT;)qzW6*qNrZiRz!RcLQ~=Qd8pn&)?W{kUk?VWxT7-tiGh;3~$Er4N21>RO&}~+vG5iqm8~+FPSfD- zFVf3gvDLC>JW_o@eo1mr*kDpG|1V6-T*ATq4L;9ELb1zwc!7 zyIfQ2rTiqyi^t%SkzyPbN+y#WzYt3%$HT#`Ws5JVci^IyE`DlQ>Egd~JvnUd;^bDN z&#iiH=k`I6tG63>-KuBX+NT$SMuhZuLePr#5~&XIvWbtjJD)Iqyj33q*mJ{vy|)`h zx9N#-m4GRG-RpdorrF*1@_a{}ap_#WtMTYXlqDeO7)*w_NZ4|mJvj)c8YR&l z_!;BqZTg7w4*U%i{O`7T;s@+Jck8OOY#+>Npr#wP-4idJV<`U;L6CdVIo^NoGw$3T z%M&7HNvISRwPSImAMy;3?@OVC3m}PZhopxONvao#SEW|oP9Uw0pJA31yNwvgrXq=f zROC8~uFDlYUeN-+!l)%HXT;X9)zFJqKO_=vw+Vf)D&B~kt6w$j=WT7ZlI7AZ)LwF2 zhwaS z1I^+HaU=2$y<3C`jVxhZ6u)w1<~C#K9r~qO;x^-+JM^h9HQu2=sdjBII`o!JenlwC z>^#AF{$IwWv-LzZ)TpS`qa7WnNxPo9=|VmAB)dlg+x67HIDs7H7g$!>|7(tq=1rIn$(DI)Ett3S_<${Z#|{$&6I#QrSmYB63|lL z9Cbz(!fD$}lk6$elj^WB4|1t6758ON{uUhJ!*=x-HrZ{&(py|GlE`}Zzw<+~; zzwkx7HhwP^D5yV%b1s2Yp+yO@pYi`I%Dg1*9eX8VJ+)eX0WLh;jtfuuxbWnKx!_F4 zSSl9z+&8QGqPTxLrIY2e>DP+S#^iAlKe0z5G)@6i*2N~w^s=^njj-w$6qtFAYpt~Xg&_LR}ryN6x2y9TQ3 z3`1R@M_YE`%1VgO=(a!~>G%f#EWYLQcP`fI%Q}lKk>&H=klI@i=V9m}5^iBF)f46t zd08HxUoXJRIIuu=D7H?^t9OT7)++5Y?c27+@*z}8D%0g(Ud4N3+&L?p9ZnN4R9h?U z=4_5>q|pCnIyEt$nE{=J8zqMfg#ai})PF`@1a^o2H+bVv`EWoe{F<5u0{-zePrS)e z2osiy)#F)~R^*ssnP7JxB+mh^M&{%t&1k$=PZ&JMjD0D${{@dVO?_zPYP{DU)rVJ3 zQ#!VY%iJ;C?(WAmjr2NVT=IU0(RZQV+u}bc&$xCWyE1ycX56!owJ(8tM8rlOLW05` zvgc-UMS!di*A*ZWfSdX3gg>aZ0;CSy&KcP&R;IB$AsnQAxg6xH1hM2_6T4((2Ut+Y z4qeIH+;(5F8_Db&M4n1*nu1{71ZE`XK`2Q1{e|XVYEj~2AnARd${ey}~CB*gKPKN?Ao*ub;{qOgFgk)`%rPPVb`)$4C=yZyUJNL6SgpX*Rvka;4*w0X%C4Y zn`!}1EtRhenTHUlX-4b7!jhyeg51ICB!URI|J9qR^j76UXSI7~I;{O4d z32O?lM0Jb`a8zWVIT?NnQ9{UBN1aWnrv4C5eKgbLS4g95s$xfZj^VD-dk;9s+U+JB zk!B{IM&KT&TUhr&;HnzdSZD`2%9d)Ln|Q8--wzpA-mg~~jrZ&64r#Y!Rc&EMtT{8X zpJ-_%ZF?G4K8Azyibep7GE0E}AHMy!kMI7C!Qq*RLnP-u%;&63ht{QKUiK3!i6U=# z2_vxzZ7c8O8#9e@kDA{KoF4z=%A$X=6OH&@rP7+y8CyOAho)sM4uG3^3j^X>L7J{h z04Am-g;3w8oT}Z7O=+d(76fUR$Fnt_f=q{R5hQ|42r31*AZ!AeAngw#dkBX|g>a$( zk++i&&nf};$1ve0$_t)m@+E{B!4K-4$5}h(=enpUlS^)yPa5k}iOZQ!%Hnh3P| zu>+Z#k^R`pwa^vDgy6H_mv^N;mAEMO(UlSZG;VrO&$e%6g~dM9AroLFFVO%(M_doK zpFxMjUrf57L+BdFvoLXgtEc27X}cb_w?1~W9@jC(mC!M-)e1{Ss4>QG59$N{By%5r zn&vY1A?0Sk{KYWe1wBHS@WKu)Lfdp`d;b+qU4Zd*Fka?}cF;Fqe#=@;50_~Eddhm~ zfhW*I|1nnoSx>b{;_GBKw*OhrP+u_)|5;D6tOrY-_yLjC`emtrrpe5YtUiVtP;I&a zZ68?u=WE7Y)%v)^u^h}MD{iHWI%tLvnn=3!#AxH2YQ0x_1`hXedW7HMzRPsD7p;`$ zm*(+T+vu}I?-nXkyml&9@`_QsL?7DE|5hq|H%t-bu%Ct!+qD!yk#xb9N136o7_ThR zvyCH5a7#sO2$M(MC< z*lNP7clNW_JJi^IEeb$OJMJ5n(sA{$ZCY51gX#W7G|L^6Idu=QI1bek0GgGi)Xz3j zYxGMPBAmOuAn6rjP7SAQ-Svv`aE%_vavt&Bqg_838*B8gT}nCA{1}Hf9QRGr%X%w` z@H84tHFQ8x5=@7lw`*h<=|p?WCGuuPi7evT+!Mp#GzC9*JKr%8xs`WjI{%XXNALtz z3vtRy;F!TC^5ZW%%+T0{2oOMl1njr~0WuofP=+3DwX&-0bJW##xvdNyjI)h z+o>e^r*rxJ4JrG_JC%%IAJQ|EyHHtK9T19oPey}e@jn^$K7#wZ)g?y3!+PofS@&*_ zU$Ig$Opjl_G7SR#I^6=%((@qP3{(!{`A*}}hgrthnQV3)jm$AE|7%^UpA)jNGB~oi~{T4FH+=aDIi*MO~TB2jgnH{|X((4=%73R_L&tsm$ zxZ*GDVY0#pah4U1m>FSHE5fA*K>LU{l?sBKC02siqdO?nuClZE?jwe)6%z9u@qt<~ zJ;eK7?(2~D5#JKM4<^k@;Clz_aCuLd)s_q_v2cDE0&_$M=1n!lW@dgn0D<}PN`MO? z0*L!X05<^%a->fH8TJT0=32=yE2xb;v&2J`kQh9uM?Aq~I;DZykYU|Eb;Kfj1ua-I zBF|o-N;>CcnCYroeg$PLZ>QFPsX-yHi6LC@ma!Q5EY1Wo1q0)+4)bpnjrwXce>VqE z-CCs5kY!J+nH5FZSi7yLzY>++econfnFk$W4ux+9XZE%Csd6ltzW&Qv>KB|}5&)&D@ebw%;d7k$I zd>??G*SrAV2cSpT0>JkH=mEHrsFW-N;A#MF^Z^tlEI@x0X-ZHUZuV868se)pWso5I z31k=B`_&wQ_~f--Tt~o_{FvZ!C?!Wgmi(X>*%6Q>KLWD&He~PlkO3?+yqnT6$A@H> z56Mp;`57er?HAWX;i!yw%8Mi_nEMyJ6^aVw{yQ&@s0i*?sulJarQ|&aHQGmwe)b^& zSY`xEd~fw3Y4#!c86-zQGQi%yCJiLh>bywOKqB|j3~3;lw!(`f4J6acvzPA~GmD#DM(r_C%9MayFBrm&;faEAh((D6j3g~DKACiI~?zec66j-?5<3&;s z&V8d=v7L_*M4~;D`Ao+E9}-|?My4wb6~2n3`*0iu$9{11K;CXpX#dsEdTVk6NLE9= z)Z_+`tls5Casx+Y#Vt0o$M;tn3PFU55=5DqQA(5``v<}&IDYD$FmRlF-=QPlcc2&j!$CnoA}{u3 zaIQ22>_gYA;eP{4pq!3fu3E#w0L+GlqeZDo)FS4ZvH+64y-$txZ4kf9iXzHe2C-<< zoJz9zV#D5;aJ^4y^uYJn#eGL$$~ul_?j7MgjOD=+YHx_(eg^mH+;`%B9`}V7dqX7m z4|89}eH8akbH6^76-O80mS@;)8~Z}UU&}r!?0(zkGHP#8JG#Tc-i6bF(Q?SE%f= z?BaOjCjdXIM$|ZAWhJbPjJ3}X>teTscemS8k`e~;;hgfHc0QcgDRlePeriP6&kG|b zzBfRLy4Z+v>aoN7)$qmoM+Rt$*?k7kZRi$PUfC^S;0R4EkJ_|4(KB4Ry`L5lwg^o% z{`b|z7b|tQ|EyZa{G>)0Go5;B>djI$8wcsy9FK&lVKwDYa|`WPPWx@3dJf|mr=Hd6 zp@n%LJ=>vU*s}S_6FaHl#y+RsH7aaO5s#J~nKgK{T;WF8Bl?Zki)%{su$I+iwMyj> zXMT7Nhnp$R9o3b^`(DN@|H1n;&dTCX|LFa}9B1A`mBsJBY`ph~K2X<#J}~Z$3hH*P zB}TpnqPfoO)QQ=v&ZfuA#>k8rV9%IM z)7NmxHy~uvSUyPT(9ID^rcoLnl)%v*qi^x(L1v(L_M4QVt;W(;SHPulaOq~av=lx( z$Nz5r1ri%sOYr2w1k#cTtvQw*88vtmHiiwhjO!96W(-%NGt|&bvB2eG@-mpKTIg8* zEUsi2yu7VxTJG$l({ejTEp-(CMeSIV!r9TGXqz9^%7$?)p*h+~$&OS)!y-mSbbarZ zZk=COJBIbMuP&aZM3nEQ%GI`6?pv}fpb5eOzlE@wB26h7J+3uJ zs(T#eaRcuj&MR|QK;+F3iSO9(vD$G%T~TkPqz{O%1Zg=^J793ss++BfbGI5*BRW@9 zVugfRjMPWq7_BW{8?29^Kf!^tUWhb>2`Zc z%%Z8CMk<}cM4xtAoIKB=Mzus{D$X^ug&^t+qIY4XP`wd~BS5qX;1kryoK0$aPA&IN zL1d_pF~jH-xLViS`^Pz_cG5b9y$9|8SR-H~S~k*L0`@yV2{d2qbihowZ!{#bsVQ)?tuiz}^OIKeE4dl>8m=xNMov@VS-GiSs&sq^3sz za#9b@DQn3;0b`wY>&j$#$M+R@7zY&&hT&PAzYO!IF_o>k$ z|B{Yoj@n7hgWl{{Q%bYk0(WkMU5JC<>h(`@A z7a%o1c}k=UKai;m`X1S+MmA<48$}4$`{c(@$o|iS%vF|!>ckAL@AOWY<5Cs*>g9Y! z5%b4V^D)%8ko}gf%slXa;7D+UlJ>nYFV9B%W9?CM)p^1tLoBvRfyd-FT*lqbeP?i*9mJGZMUVO zBwOLs==kk6OLuy*nwHee5}Q>1L*dlucs%t^_W9PaWGqB4i>9Z8TMv zU2^)yd1^w=<68fmmxFRy=+HY!>ArqkW0nmejeVK1f z4pJ(1cVU(Cg1n7q=H_qQSao%)n@uI#!!Au~3LBBMIBZzby0GC%Dd{Om)6*SkNk7T{ zyX~n-sa(l1EaT#NF;3ZUlzT>Mk0f`n|8kfKa9PM?Rjs>U4+$Dq#Wj+v zLr~DT@A&^a*KJ$_cy?W>a6W|9HFk%+b>fbF!&dazIlOqsH^WZ!+By8LtewLRhx(_d zT7$KSlC+p{lhR_xO-_p&SDe;m+_B)`h*QC#5ivOtbM71xG3O*#@!ujlE$1r!B6Zvr z{y*WG%l+i9vgfSee=FDBUk#jd)mMY&?A@Eg{opwtbAN*W56N?kck!R*j9amH@VMf= z1IIo3an3kL%-%ucmVZ2CT<5*nEZ{p(~I~3n)Kex z!J(^U0ZtKXoFzt>zhm0H1x?fL9jV$EUe>|BF#qYuPBXdg=X!=KpYOuVk*lWFL{g~%`|x@c@oHPZ}>@%!L{ka_ib5zRcu)`>Gg%_u(zWtf&!dzmU#>SFMn}y zPLk*yGQB+^!&HR3uxFV#2)(gO<4G5VYPqu0D#kdrzCHyRjuH(+KXx*@KgG_+8_sy* z$C4F;PuB2NV*;`!cVGnLn-7>uzVqDQH*!t)xal9PM&Eh?_t^J-(TkA6d+~V1)5Wfr zSn+gm=^Pasd1zZc;~gSd7?Fe}R5paBc-`K&iI>d6?ajjNorT&Fw^wxTESy?q&uq-i z+WO+u_VYQlO9Gr)oYgFW|1|NM*=lGQvuEXY?loeJp*yS@HDf4P)X{G2+n~o5gyQaw zVT@G77^xh0w;Ux-DL$~IGz6I?c+W7Wh+$6P`=z|^zmzk~ zy4q@VSp&mm8(S0FOBMi}3K`k@H%4KBjFBP0G@NTMU%UYPfc$*1`uOr6_+kzRGVB>L zG%fP+rM$hVqS_z^!^{9szQ*`6Ud3~DzsiPc!hK7EjirCr zhlU8@R(rIu`|tWiB^RPB1J<;s%pWH9A6oTCRGy?=jkC@NmNNNtUl4 zA0Na7a|iTD5XTMa=I77$59E9YtnEQe`?oqqEla)SP!H{vGYdL!N;#iN?6z)PQMa|@ zGP!fa+7W^%>9*x z<31ry>s~)j$A6L4TzGq~gD9tOu?2w;PqF0aP>;M@O1p0um)G4jt|jZ=H$N`WBA?d> zS-SY3855q@yQRpgms8BV`LU(|Uj_c59&g@!kCdr>UhnIuvVM?~l9rT7Rr20RO`3*7 zaUkB3ageQ`jm*n>#t=g-lLN4VUDe&59yg1skD==Fg*eH33NcxP+!3xq?Gmy=4x8_B zJR;%C!(1DR6z2~F%5RxIEqBgkdAZx@kr}Z|68G_66uUIhvCOI*O=a>aS&eVGMzx07 z5f!n7hcwG>%cRg%7SwR)Gxl8R$_wIGC1zlBWU^}2Ol6P-W3zQ<`EZwv*mhu*es~$SbZJEJP_|mqaaJbIG#{4pe`!G8m*h*p=p=gXya~K~=EG4?l z_wHC}pLv>#k0`prEh$OIlNI-f5T&9CA`eSbjIlRhTpHxiY24JP43MX(maq&HxwX8A zDS;*VW$t_oT&`-_(0H9vl1S9N2_ZO+-a4r}_--=~!scBJ0h0-!m7-MHeOpn91x%*a zJFto?nMG{|nMLjP|1tOG@lnDNf+n4vgTkVc_{c3<70 zBwyVxY4BGx_-PDCG-xX=^3@4X0?6RAYvd@0XYgfyEMA@eEy8#)24@+{+xQyeE}uG| zV_###+Wq#x%0BGBr?2PK%at6RSL}A;roT>&&vyoLgj>z@9%Mn!VQ_vO&=!tWplmcf zjoq`Yt9wMl7gspZ281)t75pQ`t+2s4g5V z_M3ISM@9Rd{F^I+%Mw$9Cx1OX=+=Gh7K^W4_Nq|blH2l|U9d^TEN*3j)++Z8LB)h6 zSPaS3c=v=g$<)1UrqkyG@JZ*XD4Pc&^}26%G;0QeKwh4+#PGr)dYsuxwWE1&PkpoQ zC4njn%wP%6vvt*es%G7Rq4#vHKstS%Iz=h+$4*y|C~l6y1hPL(n0TiJv0}`)_hpTW4{@+!vOsrV|id5D1qd20E2Yc#AY|+@L&v9CJo)yk2PFpA3XAkQv;*WjZgc)UQ z?wZT2v!Bj1fn8d#o5rw$$?$W^MG6-z z1^$JEWqIG{_`@Es8iEG$*kor9q01)%`KrKD_u!*Zf5|LwHwZqDidvo$XNvkZNyv|y z&}+Q&;7b+??&kh|_?+}H3wt(Mj^jSd^yfKi05C~)Vq;`A!tmp}Q8m`rZn#`d*BrGn zFjlo~z}bRBz9XZspspYo+rqm6si*_s(mWpL$?KK5mU$$t=}d~Qs|$WS?HqKVhfTh|G0oW6ZT+WiB9A`<| zM5m7Wd@}&NCU2s1VtRI^vy>ig29c~O@;WUct-xwi?MFBm)RJe;L*fsV_ivt z$LV6EmNBY*?+iJd{WHBXN;%EFBg5Bz@_JwUZz~8b1Q?;1`eg38G3@38hFW#24jK8?QDRF*h7Va2CDfE@_mL5 z?r=?X<_`X@;`gu6iANAJMc}N2qwX9D!|UlKMTg!0um=PP?7CQP_c&ks<3-ud)m){E z0Pu}@*-mT9T##Ch^K@;&O;BZ#fab30Gg<{gm2*)`P%6!(3oNPfdo zZbtw;mL6Vx!0N>bP@Ic1J~Tsa-nrcUa_%p&W;<7aIPYdjI_7wtD$V0;;5!*4>f*Q0 zJ=K}W?_35~<(}ev9W-;fx(-hG(UQ{>er#PbdtNxH9Y32Z=7p!Wb0Xj6Ufu|)-92I7 zk_qNJW5Zk9trIW%;$W>yM$8Mp(2jnam0Haz4a`-K;Y90yAA#779^x(r(#^A5wW7;b zBOsCkFL|DF0!GCQ_)-v(=iNMCNnJZ!InK3!;h(5e2_$fp_#o`RWcfOZ+$i+yUIB~8 z$3L+|5GIaGPzSsB4tUMo+$*QSeE5_}EcsnrxvbinqDjs_73DievAR=O^)-1joC}Rf z&JnEqo3(czSYu2^`H|p$aY8B9iK1k=ce-=kb?QJd1XXaFyyL;ob8_6`_Rn>= zoGN>=^Kc4v(#aA!FoN&RMUw%)Nhn-qI^*e_L1#D9(LdJ)st;_YcaNi4$p&~gf~y2J zMO9OR+U6ASDX=L(uIQu!u3a^G2j+kq1;fAchk<8>SBjD>wXPhP5}xWzzOO(y4Ph&- z3@Q(VuKBAEoMJC{9h}?&ic!FSaR7jK(`z>!aMNf$J1x*}UFU!5yBS+1+cO?WniT~u*nt*PkB>M3orf|2fezO$!y444wq>(e9{tHbF&`O-l(rwxSt$Q z(dRD?JvZiu)@+8Ci*Km7=Hs4o?y+VxR9t!S`NjGTEwtutOQ_-H`iiOh2LiDMF1{cg z(Dl%&^Ys;zE?0p(e@qXZe7nBF`Ek!*)k6(^99G5isMu*a-dh>p!m&n?Q;3*7`Bp?r zeQjTU(T9%1Le8{=-a#(K_<&B!imprZirl#f;Y)-ykvl~`zvjJg$wBKifs-80Lu7c{ zbBD&aD&#w_|t-|P6fvknWu&QZJ*WmxNR-;_*87j}|17>}^ zgUcBA@|?Q7H+WC}+jvKm4KYKP_$dHx;emtJ>qd*F&okY~JgV#%NdX<$;_%IftfhfG z7EkF60- zF~PPDBFQ~-UPT`5MK(RPNn(29yo2*QmI?mo{Pu-Y|HVo=hhJKa6>a2j6g`J5%I=rc z@yAcA7k_ZD3q?&M)Y=WvJut!9~5j)Jmu6I6+!r-w}k+f=}pS?EJD%YH5am+5#O= zON?$|b|w0oh-8#GTdw-MbL?v`-0Q$UFoCF}B(zJ(^dN;E=p<4b5rBh@$4(rF=2=I* zX7x&XN6B{c`dg@dN2;0C501{Xz~P=ig)O`p8i%&2KO$QQTuBh8r(RS|Z)GCbvmf5N zx4vyJGN9xG=)ujvu#O7a(7D>tx%ODcdH;Y&He3y6PY?gs^Vax)WFzSYX_ujwMX(uF ziY^cav|OxJDjojtjJkppsD*~ECrS3V9;Q+ZQ?l)&?fTjzJMD%Q3$lx_C-SJz= z6?kYy(B6a!?qM>S-B;h{xZk-#JY&UA#*W?&!$x3vmNNX34yO94Eg3~esvnRFc0J0e zXIQo#e@i?5nw9Lc3_whXU+x7VpoZ_-){?mPCMHX&h& z5A{qGXR-hO!<{6!Oz@WWpYEyh%>A-A$=sXY4!D!ttvizhk%`OeAOiD>&fp9uTZsz5 zqS?#y<|ZWNFe`g37KZ`J%F=W{=N+|u@9A%4eAjAq2%q=NPq$|TEQa5X?D9?Cd(NW! zIofWX9VuRD`3X9@C7@>-4(xxOGlOm%WljVbZ47m3EdOhaG!3tw?_J@DnzSq~WV)u*P33AB<}6su&gEg;z@lpJ}qTy&z9q*vLNc$GK{*uXj0!-=Y-Zg zd3DHrO+$qh0Nkv6?TrYk1E!nhWTyr%Q?2rvT?sCy7U%1Ke48)vwY#)r1<+)x$6c3N^dxP6m!XYb_%`f4KCRXVRDsMg_^ z7CMMHR>^M^Q!6z?_w;Y*+#~O>{QF_P_QPE5H<$nAt3zwj=7qG1hKhTs@v_gW=7rom zzl-NWfAM2jca~mu=U734I!G`s{KKcLV`}!|NZAFl6IXU|Q8?QK32~^E_~s6tD!3-jPSHS5N~l| zNka4CY+qYba&fCDbsHC`Ifo~iRipwDlWWg$Fi(lT}v3A>6?iK;1`2`uatWe+rJ_^lmH%_d(>>nA}4kLKtFS zF1gt|1dV|~NJP_qGRxOq@``(^iNb*Ju6$ox_J3wim5uFt)n(onv?i#m_*M5*^>QBD zDKANVo9)!NGf9EL1dB;$B=dk^ufv~5(|N>~c!e z$KSX*dF|^nQr3ozN3E`aL42Qh+zAl$TjQBU0`V3h<6}zw@{QlD_}O>9QvuO4*I&dF zaU1D!Xf5J8(#LGydgHU74}Yia^EQD2z_)9*YCCh2-f|L^yFnlG>WpSzb@c)1uc+%U zfsO3{A#im4khpSy;zWM^ytB~6Ja}NEZQV57 zHTk+018Hk67xvO;1WJVp3^0ekMUf*xdOUB_v`iCXfBIJ-mh#=!fIZ^6&UaxCkkbqJ z?mA>Se)fls77ZvuDv#{G&vN{6cD4yXaoUAFn@0Ege(k&P#G{tul0c99Q_tR}`Y_t` zo0~LpZOxB?J{ub~A1=TH7hquIw8I6|zyXNSGYj-tld6_4da5bI2pp+-K=#mc)-kQm zEg0L{wH-%eIC0^y_Z+&hb%*uF11H%golx=ER*@~@VvDGkJ?3_htsoF9+n{@IdCQ)$ zzP`ut_3XKgFi+9hay_|eW$%d`9DC@PpPAUoC9@c4aM_#pOuE){ie;!3!IVo0RpBaO zE!VKt!afL*jS+3>@N0~I0}++2AeIkq8_{xMHp_x`dkx<2U6nYS(qIc6d4`VI=|I;S zU*CN+DxEU;Pj--XUm#APjgj}}quau~9u(jz)6&XiZ?sv`%9|${&9~#5w}WMgD(ccA zU)&3m(aTT@*WOZE4igx=Y*&xF0%OZj}8@9A29O%bD? zGsUJ-_i^uGTfp~p1V@E3%~4*8-O7%$SgqevgoqwOT<G5%xF+%eS4s7<$ix#xwf!LA0xNE-3O z3*SxFsRXy0H3c|`HGnyU?UPWRK;?JWc#Fzd7M{aqCiu6~z;9u~iTCtx;LLBw8v`rf zBG;~HXFj;?dH~YbCwR3LN+*E1UTAhJtrIrs>T1=&n zlI>5Rbf~Ap0Q1u-jn?_|W#Rm+^QrfxL0}!MH{e}73_}0DihoAMt3On+0M{s@ z+=h2J!D=4@)Q_(>Fl=f8vRH3rYP(T-%-1qa=#^b@5qdNIXWxq6aZqo$iDSkF_foG&jzpLGQ3-||0X$hR2en<`@op0D*W71oK4+p# zQ0I1E+o_z6d8a|uc{pK}0l4C<<41N9_aZN@XoAm=$i zANCF+{noqERlAfGUMp}YuZJxe+IwhVrOn$W1MHqi*J znQIH3yrrR{hOPLK=MUIIYqr@#J6APStm3&iZiwB*rh^RFhmplFX;YV}khj3+!T+l* z?E9nD7nqKfb)S~vD6pxvES2iNLF_$99R{nLr6u&d0K4KqDV(KQ%qUm!qLW=M|7+1k ztveF9|b&nfbCUOE94q-c&JDUB)QD4%Uhe}#y*1SBIneAdmyHVJd<{Fve zHPeEE(vC-sNUOXPG;W3x7zjDx{ijGxT18jp;H+7yskYhHw7omfaYT*#7B5cZeUFe+ z^AtSfi5$_qj*a}4|0nq^+T2rcOmYB~=4neHU{}9Bk0%D=? zmqP93Cg&kD;YTS@d_CA;A=u!$mcAT<(icQk-lUs49ypzhXoL>%G_!k#S?b?_0^<mFR|wq-zi7lw3>b$wAW}2@ zJK<2+g{jNvb)Y|MT^_tx0n}`diPtp0o#%Z2+6zXbB6dbAfkCF-D2EsmPJ_ z;lu5Yd+J86c%jpp`bQc#i54P3B?KSF1@|vBa?f=MGvs~)_qXC%`#Sg57R1j0mH3Of zC!IORy}Rkmb~>YRuY_dx9=M-1hFYFZr>>wQf3Zm3>mUwzMqM&1eX^uQ6(&^l>UEVgcZw+M+hy-J5X zPfV+phz>4n|?>+t=M;yo0CU#eRF~yg2D>m zYlsG2L^Nm(A(K-GcKq1@2}|(!j)*TXhsj&-FalJ!mH5nWF4j?spzqBWxfhSD7V6kb z9r=`1njcE7lhArW671{kt@_yr?8ET3b+>c|~FNpCr-6;ODI$MM4#D>WwYt zSz#oq$@2dGrz*6;u0|d%nP~sz%2SJ1UrY*@q;FjOCCw-~MXC{|&=6ev1 z;I}vv4#YJr9q$hEO{0V_oT(nGXHbGu<+*UZTY!Kd5b*FI1e5^*wLm~*!UHu=muU%+ z2o|AS^y1ORFIJXCWz33M*=uGp+YdK3PM&j+#Th~iF4vi4o>%n^%tYDX{T89bt|(ka z{n%X!EN{XLR%F)yo9D!xR~(`L9v^7^!Pj~H%@28@k2dsWb7Kk)7xv{-=;}^me?Eg2 z{59(cwB00}MsFml<(Seq_WsKE#0-fGyXgtO$fuc};DKFG+oS&%eAM4d9^d=+Qg#Kq zKrP!+@$O9;Y+RJ){orxaY#Z^BFT2X3g)F68Dr6^3`vC_1`uO5~8rkmb|)!^=*y}|p|Z;E^N6<=@%S^p_*tLl1l-X#;tTGnvgcQ2tNyC1 zRDX@sF$q8Ac=b$FF*GLf_7el)(=*@*;0m}`cnbcpP*hc4{H)y*n5z1kW&m+`1>isK zskI}ZL7T4rIP+M5$aX{MGV*b*n8Z)+QHouqu)fK9( z3B_G?VYvs3hTrH6^33k9*=6@Mc5cb2{;XSM$czGebAnBgmZyGRBb|alO~n$@M#_V2JHEqgunaw%B(WuVONAqE z&tHujJk3ohTPhM@R2?*o=KZMvY?;2mX8Nq3FvJ+0ExSz5A7D{w1Kv}mvK^x|o`%|}lpvS|w~Uu@B9 zwkUM~49^UUq-Zh5`)pk84UdPv zoS7Ge~e*$B@_)YHSu67})n&&kI&`PeTX zFUrT8iTcbyZ{-1+vmj|{5jc+*Wrw(34w!vQWcc?*j5q=AjbU^P;a8M_CTn-$zi1u}0EFn8KC zZeBd#N^tloqzy?)Z3B->Be(GW@YK}`952sh1;f+MTSmK#iAy{Z?c0m73Ns+_ttv8~ zEr9b))Z8~SS$CEEC-uk<7Sy12)K{d_QN?cyzhyT{Cm)ZlOW{Zv>=NLc-EN3u)Azv& z72$6s>(0+qv$jnP_LMb)$w`llTVKHr{tqoPpk=XmE3yBhSo6kw z0K8~x#AGfy5OJ?8MR}sIZ@9Tm#HSXB{zLwscto{JEknxFxbYc*`zsCQrktO3y z06#GZ;2UKUc)5Oe_~$A5R6@7ffgVBPmX|oQ}hk_+Q#`}CE*ij}CAB9yr3jC68T^5sE4afU8;CXS#8aj8i>hH-n zaI&&tl(eH;afH8?swW0^97;QIa)WB$kBBq$3TavpkM%6A1*-B6(2U1U!f~D)p>@^b3I4Mv{6+g=S?`nu+bA8oOf? zewp1%6}m8m^Pif1nCt~z7URlO$cchwV{tw*b9iY*rgKh=JQIt(h*B<8S9bA7|F{Bp z*qa4hcu>nMon7i{t06c=8utMMn4D(kX=zvP+~R9@qbIX$n`y$xc;KLP@V@YAhsoVw z#AS}mY9L|;ds+ib;?A%8+9l<6b>NbRJ6U^qD4TVseR+W!LDWKz#f#zM|0zxp4y93d zTD}>(P^m`uyn~HUma?8mXrnT1#Ud_ZfksK>cp0;`wnQVEcAVFvrF-8I??vol0TIt% zM{lwAlsvSRD=Ku1hO&V7Uq^~gO5R+NoZMKE$od^!Vs9SD?$sE*c-m(Ic<~ny*O>-djPKIu8bLd$VoDwvsr3UVOj3s zj9WCD-OwKRiBUW^c%insXznOA>on7SW;SMG)>4uV;#=!&W=YgYe7>>dadvLx@t5$D zIW2BCzV>kaXnl05M7rIX0uVK7M&WAYZZ-NH(S}t&7}t`|Y*&+{ zaL*w3bLwlwEvHde%DZP6AgR{c&do0K^jux;`3+=w+gAdQrkHpcwEz=iXJS%F%^CVi z-J{h^V2#Db;O#;6*Se<@YNod)*0@^p`3_9w$I@3OwkAu60l^dq2qBHivwH(CoteMb zbAG`Mo?p>G3A%@p3&k(x5PIT!v+ilVCZ{!-veWsV#`krvxLXx?I3j~`w~ZiF0oW1PlbuUERY-u}-7~OKC}3W~b*&yU83~Ts zBFp<3c5V3evHD$R5}PZ!Nn+EJU%K|()tK=Ili3VxvL5fw8L?Kp&^XDXKzxQ@pApA< z@!@Zb(-6=Y}Ci zQTyiIWHfJKV#a7EWu4H2JZ`QdI|JX9UsL_ zGHSt1CkAoTeM8SUN=_aMZjy&4BLQv_SL_&WIx+Nr3fL6_Nuvr^e>)BUXUkRlw+1n~ z7Xtn*F!~=YqkB-$t*iz|H4Vd4hL!<-O7jkC4a>bZ*_-PF=^hg&r48a9h@y8r2u)xB zn{6=7krA?iZyap?#dygl@_m-5O~E?`X0%7aJBz?O?_b0_Cfd1m2<^-Wj`CL*t%w8d zOcs2cTODSKOXWw0u76Sa@7X=;ebW3glcI6lY8VfTqT6ZveBUgoWb(u zS;`Cz?>|pznUQEXjP%knPl3Tbo5LvP-UKyryQTtd1*LhxmWRt)gESUcuGWd4+&A|( zX1os@*@yZ@9Fk2|lGIB-yGD%?ZHciI;}9rd>=;|{DCnS4OE>eL9?kHruXJDK-$|!z zJo8NOt)K6n?eCbaRvsaN*?j5{H>pc!Cfsc9gBBz+(JqP)Td54Zifrz5RoA9%1 zYj9F9Jzr`GwiV0GlqNXLz{8T7F)=7{NU}Yf1|2;JKU*Ha=YP>t!Hlu^dC0Cf1^k=_ ze$I>nj;wMjqjWseD@0S=VC4X)69jy5;C=fk;zha^;Ne2BsCZdRt_xu!6y`Szwmb0$ z5s%M+c=wfXIdD}M9<>zD&TPJ8FUs>`E*sCiJQJge@xiqO`eB85Z-BhhS&_`$BSXTE z*K9b@Duh>v?rC;`22YOF!n+oIdOgIF%mHm8v{dJ-S;hyOC9olYtAx>$&zg{2e4HeF zikV8qYEyM3=VKCU=YY9x{2=g>EQvS}jqc13&Vs={&5WF3M&Q=GD5AV)$4RaT{Cuv6 z_xyS)Iv@|4xydU%M+y92jHOe=k+Z;t0)GC2TY1m?fUoVeW1;6P&gjCG%L5x}39<-f zlTuZFuzD2rPHIRa-gIg<6XAlBb@r{g9AIvyzK-oMWfuL32#t98FTUAF8(B zXQ=hRbE@^P+@m~AFjcS5SmY5&L1tJ5K*dekXu?I*dK)OYOdDVB=Q>iT*0h zfAmUnGF?RiD7$L=^(3|a$W$)SIK*xFmfZyo(Ig$=*@=X)% znHuRN1XhI0kubH_fSKc*w|h9detqD`r26%>C@w^yA!0ujzddB(M zm>o0fcnkF+J2}qH$A$}OUoIXBQu*Cfa(8Y*X4K4Q@5wqcrKnu2Z8-P|z~!gmAVk>C zK(s?`dr8TO2jYvXQWv+&_Yp>PlmR`!fL4!L+%7Y5f}JItyZFkPF&LBW%{~k^m?caMG>ucHc`ez zBip?aar{)x=ZfCY()_qI>C^M6BuHT?xFud4_w&LzAoO*JgP_yBOkuPzj;0+hI0d+y z?OJlrN#^Uh8gJ3Dq1qjh{WbR%ou?NAMCzujPG6B?Nh(iy(8zqDc$?$Jx)Ce(*IZHb zhBY-Jk-K7-d5(1wADMkxTJR)CPRYpruZ)ULu9Ss~jf{mJ8d+>qlC+H^Nri9J-c$6( zs`M3aXo=--)ESxkiofCbF`a#*c50EtJa5;M%)t)SMh6=$=ZHwT7peD;4EECUx5p~@ zi#26vwD|m*qkYd39qr-lj`c?-b*!(lU$<7n2ilDnsJeS+Qk7TrANKNWYR7uTeHZtA zckD>2nySzLIbT)8dyy*YF8)cAe(6qM3<1|6$W2W(xqtUiv{X2-@gyc zBA@Lz<72Rb(8x}nSL$lIi>b_;Qr{*UcMk~LL#CNL%?Je1;>Xfmt>`942-bz6|MP+W zVhm(A|@lEpU@pKL9*c%#WrY#&K}vVAc5$r0YIgw>VgC*n}h z4Ng277m%H6Gqax<+^olXnJm~|LoO@$aM~^L>a$?g6zUN55yuMz^d%I;mFF`3#j9N% z>ud5l*4Iw#SihUPWId{9`qpRjT{ER)eKBiLTSUFWqk|W-1KhB=d~@QdWFk)7ul;$% zy@E~@7E@8P;J}_#viS+36N+$fN0LRsD^Bmy=pqt!uPK^{S3S@4gwIM2usisl%Wp~7 z)PZqTI8ZUe4u5Aev3v54JimE!QLZ!2Z%{r zcYoD1U!4ZAHfMmu5kg?a5BB3`B77lNA3r*#ClPr;bk~v$B|K%4KG!_cArGcMFNNUc zc_42zqM}jV0)yXutF74ub8n|TVfrO)iXueH!9ar$1$ic^SHwNs&b=+ysP&}D>@#xf zO=ljJ<`rF(nRC?vSCcTv(Zo0uIN^XdIGAJz#P8+hauL-XG%kaxAF0}lV3$RlI*i6- zk0oVxqt&=lwvA8}H(aZTP*Fn=mM*ODF>Q%~wnW@9L_s<{c1f~;OD2}HBNkrhum;3t zc=^g^Q<(vNZW@Vu1symBOWb&sZ@r)8K8i%*Y9e?Z(2x!blGo6tNT+QCl6_NG&$?*5 zcG!C&y&OeCDMPbTiDtzVPy&!A*TW=DfCDMJ0L%=6CQ;{rMSItxudu$mY zG$n;uT3V0dxy6d^vdq^urDka-YxGrCID-wX{O<^vYl4 zFTyAo3g>zB@pINN;Ue5rqaxkIg1~`4vx)^-?Zsa#zNA1@ws#grQ4q5(UK&h8A&p!6Bji?_)TXH|zlC$@!Lbqp%)5;~96A}L#YV!|ls-1Emzb5~Hw`R%#J4zE#9dtnZ zALojx5JY_tQyo|Uk$Pe>2UQ4xr$xW8v3BZ#db6UbgB9fu=^%8R>*KI1!LWpeR}|Ah z#L7oI^3n32RIZ^mFm-SQ|J{Ng-{DVc@FN2apfQPQTLczAsc-|cB%_>IGxdUfSh-Is z6KgPcSQ#{kZ~h?l`hHoSz^4_K1}6nMc< z4s!k*4Sr~Z;q?W2R``1bdRodmlP!fcmdxOnEaQWTFrnd&0)2C!3V)te`0#82?8^Z8 zSW+ROB@njHzRsMK0rqCt9bme3NLiQ}yaAA}r8Z066k;XN)6`5kV67hH(nM%$hM3 z*|GMNuCEUC+Tj__a=49jFbLVk0kQcUze{TT2ZYdgw1j3m_Z=`--kRE0;ay6gmW$vQ z98gliCa$y&4q^?2OoxiDAqz|agw8woOkAS23?q&Wu%cE5_|`yRVBBz$DxNFyK=?{a z;_?C=iYaLs78s;zV3wqTHIV4BL(ivN_PI`ns$j%64Zg36a-5L!b}O^DntR36A?&Bm zGdO)xxrn?vjen>hjr+`k;eRgF$0o$yI|F46zgeh%CH%P=dY+sr?waIEM@uo$=P?yd zc;eo)zbQjJ(Pp8L^1~!^7PkNFxbUB5=-UEgP&texMS}_EKhKJI1xdxP~#%$-zQ$#GS0t` z)_m4+BeY8mTai#O8y*(IJztKq+eZ7Hs$C*nV<2I(fD zqE_c=?jlFgf$!m$Z~`Zedd$;Zqyfs(GDv}9cv0}Lv@r{klh~^n&E+R6A6UGzvK5`k z@hmO9ryO^3TqW>~7B4~+bP(jTG=>adJ}*NkFK?hsab>F~T^%ncYwF^iS*_<7==-$O z#kX9s)@2}@j_%scs>n*RrOahaB4u4?@4_v!S9bbK&FX0KUt>i)Tcc$aE z0_xn&<-TLr5_QM!B_hA8J9dVDFi176kl1$tf;ZxmEdb$Emk40rsK)up``Zg}1@YJ3$QI{3MHG3T4M3eJY|3XF=) zBK)}`y)odk5&zD>MK^;O**9i6k*>`2EGEW|N3SfuM7xeb*^_-pY8j=8~$C&QWM@IPOrXXGIbKPIy-=6EMtN_3r~gopRu zFLirb=7nr?IQW~Rz(xlK7Q`KIbf`CtlUIh6c9%6cY=Cby3ilKe^*LN z-vSkS_ok68vrZFBSee>FCJuZP$;5$^s+ch^+?x#dKML-DG!FQ29Imb7*JzEL%u)UC z+^hOdp!5{&L_M5+-XT}eIEiLejHLq$$dC1B+?#W>IVWf&hGua2fKMOoeP?$5_7i$~yk^5ARdp&eYLHEi2wasz!2V?Qdau;t9b@apX2xL# zl(0?xL3{HL>*AV!S~s>?4Db)Bq~H%MBZ7a{Mg)I{wOD2avp__=rr*c4?gM;3E};La z`bJ=1aWJs&dz;kxRl)iDe1UJw-?w3t3f;=(X7A0nB=yLPJ3vvRC~PXm_`Q9jT6YK_ z|MFK7o10Ze@PZ{H_zT#z129+t>v;2Is$X#b_k;I;&UYmUIGYdzLE^txttikF!$C?=Yvq}v93s*ondeZnW8ah-Qp%RsXQ06GF z)Dn8!{I;T5pG79$u9r~ZAH%kU=9KsV3F0X4+GHHl`l}wT{I)=#WP4c&Y^*>+tiU?6 z94pN-0$`Q~S^z*Z;$^@ZciiZ32j9IZl@~|i3V1PF>j~EX#BN6m7zfx8he#`a4?3_B z=e=-m5|t%WDLFVc0DOmZwndy|bLktHq1wL4KE4!Q4nyKvfQ?7-kr)D)TbS-g2La~T zAi%6O0cMmp*~jvj0P|sZSyiWHGGaP&5nlcbyv))@IL1KQCIK(cQb!!{@=RTP^Rsnh znlZjdegM3TP@{uy2ei?_p8_z^tz<(ffw*$li0d_0EmD=@PiczKWCF?d-6jJOBkMPNtZ zrGLW;mbU^pSk96y3;*Uyyzgc0hp%G{24p>z0x59_9!P1MiIg~aplgK1480~Z-@EG~@-d>wCyIM!VBRwX`J7gBq5u{>YMQh*0N5z+ zdjMXSU-g}uJOoHD#t_d%K>A1ED6rv?e;APd5jYAABA$N)kp2-kn)yEgq;SWTR@dTz zLsk=OoXAORIgtaF$oVLS=--gk(vQ)20JHf3rco#k;Ur61C>zB*n+S;~sYUpEmJD#K!6Q`0CUv&P7q){ z2=Ko)sSp%2N-$M&&);~TooffevwQ&) z=g9iKy+&(!kLmsSB=s1GF5-$ZJ<)Z9=@Ap7O!rxq%h2$6=6VU&c42rpwP0lmJoF7* za*SZ|0u`FhlFCv>`JI&Jm*IC*T`K&Jz)p;Q5fYio+Wm<&e5x+Bc@~UMJR|$FmKscj zpiO5D^#>g=J{*QaWy1Kp0{wcQCHP>F;duv!=Wo_b4&)ncF5k{Afqm0AMwf5L*Q3k# z?8fNwZHM2H_hR&`G9X+R>nD0|VR+U-z`jY+hHL1=80#3;(HVTs5?#M%xqqA~m;0$a zpO4e1ET5dz_wPLWEccFUsmFeXugt5^FAj}5|2t^cfw33)oedx2cZ{CEt%D4YtXq`f zF<7^Y3{R0TJcCm|H0?xroW-|p1xw&yU4?-bQyM(#i=ISBXu0fdo|o}lmZyviERPbZ zG7GC?wJDN6_-OpMOke3h#DyR6a{|R2>gi{?kEE#mN4dn~P)=n+!9B8vEr%(2o9m$) z+KZcRXs@;yjv8_W?Axkp?Kj1KY$b5*l#-!WMVb&oIbpWH`N@+Mt z8|6O=HmuIZ>E~GWT;!?;rCi7F^A1R`v^e){;A9_}!R_Rt5pTz5i6n5dY-0Uy$f5EP z^hW+X$nQa^6coxL$X&QA=|i23HX4m<7J+U#taAre48*e+FA>k8oY1BQ z=iIJM(b4oVnxfN+v|}QRr4bmdA}7P`)q18wI42VlTjquTutYBy+dJ6l96BA96vsyV z;jnY5KIx86Xl$r0ndPC`W45KUBB4gx9v6`rjIF@%K_Qi!vl!m9RG)cUZ0i2f|0z?q zNk4v}Ql=`ofwz`8Hc!wZ(_^NdsTh1!ma zgd3OXu2jNgA*rIq8XI|+2{;>WTc%$fV1bSgEeQR-6oRDxd&8f)5JPh#J$!~9MdxC) z=@cg8etQslIw1Rd4w|xWh`82pV7Z|vYWQI75M6X1_Y{Ck$xoLGkN=+F>GMPidbIJpwE(ErxO z%@96Tp-&iZt_nklt%RhDed{tqU^$9b3=ILFhN>0%wc(Uy`si67;q-@X*0+cCDaz#& z5VL^9tl{ydXD7_kA=N=VtM)g3ziY#6F2Ivw3z>3UPpFN z+l=4eXw_$(rrN@3pV1c^ds8-6*d_k-?$78G1B3f{zo*R;YUfBt+l_g%jYKsv%T0=b z�B}F!j$RX{{fC!&|alAwl%wd+`^m5&9iNy|9T5^9V z_Gy^QRJCp~M8TeWB*T8QnpMlG@{*%r7kIrqPKA?i*4^G}EAg%toZdkEo-t~>5TW{721F`$^{uJIX=l$)x@8|s|si%zhYcTLGs!+2~jke5(Rgwk^ zAj5QwG*3RxGmPda@wlJQK)soouQ|Ni@4Q%t)J^uuk@qkeiG1ILTgFj>r8(Pa!khRx zMf?OqH{!F{8mFheFeW!7jqjoHu)#BwS-Y3{z~ijxG%U?Iyi&;qb+=*I8B&!oEDV0QCpw1hqFSi%@2d%pkz~D%#jX zT{YB|1#cpCd5K%FFOa$>hOfC*Pr9aNaH3>32ofCW8JvaK{adL>{I7>9O21gqmiZSe z3d9PS6{Sl>BUa#KyZqJyPG1;oM0yxi_GUyf9~%hYVoi52CI0fi5=BhPqF(rulfbE9 za-zn(k2N5eW863aQE$M-N(>&~;9eGaEW1W*&mjNGtnW#Vw6B*1<{TzqSN5|JvWL2l zsh_CV)KWK>EjOjb)`U~$p}3zY&ALx%7A}oT?bG5$aK&@Q?Nf33KHI~p&#WWW9@=pR zPfOnEq)yAkXppd*L@f8xf%;j|PRX-V#EH679QIHR4_rxV))V1*x9j69Ju_v0c*FI# z>qcPsx*54gGsGD;b}yfG4rX&O7gI0(Mx5C6IeBRy`l z+=Dl2tZY-EnpH_Qu`U?unrzuzMvus>Q`lU0v$^t3nKdC0ksT%mhs8W#cb-3npWj*X zxiqluT_Z~8^jS;ibSIb2IqN7TxQTPt=c@`Yh^bN|=K@hvtEk)~nj{)%E<157JW6u`Wjk#u!u{%Kz_|&?C?IqK$qQ6VB$e9 zitk1QUkr*S1DxkpGasOw3_Lx6Y!D5}85{W#%R~xLZ`K9tIxNyF=eT-j%V@-#g7lBu~P8ZM5IRK=v_^jKP6ym4Ud_GnWqHH1@suR(+j|ta2qDEL)gJ z-^`2CkC&~=4c)rFy491bA1Ac)d>(thn`fTolS8;+waWglmHp4u3-T0X>vw+?**e5c z!hJYnF?$;Kz4Ap`zWpjK!*TcEZac}YkwM?ZfOin*f!Oe-QS1pBuT-_#kOaM{>Uiay z(e|ZpWySfSMeA!?Bed_QeR0N<_U{H>Ib?p;-BUF02yQNd z%^Y*K(<9>_BQ{)N;EYap`Vh`>ukW4Y|R^~uxykXDKu@XWw`P(r^bi*0DFW6a<*vk7}aE*ht-D?-v$_~`Jk7nfO zs#KQG8-VzNYf_~gVq}|~AHdR#l(xjnJyxF`T4M~-q1e5n#|LIsg45Km$p8gzD*lm3 zfLY!tv`ZN6Hu-JTq=Y1i&k)Dc=Lv9j^spQMJ|!e3{GkF*T@jLw4;2`c8pWe-=-#|s zNC(H+feNH9__RXPgOo;%|1~9K8?4U=O%V>=tlOX+tND8jFHxyfAb2H@N(K&14sZXt zWkQvr1`C&!OFfwqDw*jGt?BTFI@=p6S^%z(Jl|RnT668x(5mAN6+18Yd}TfvdZ%!F zK|{rNcpi4$p-;^H+O~^)X5+zGCZBoAIZd!nIhP?K4%ZevQs*yIRS1FFA!eW!h zw0sM{J-Kl!%8i|$CnlzR3jdqHSP6A|o458?y(GyR8{I z%K`B~Ep_9gu58h!p)qRWRh8jXC<{6@5~Wwp9*Qs)vlJalYgh&};>4R;uIb#Hinu4)L* zeRmWL_HE&x*6OP>gaMbWU^?saoFgbA^3JC9;X=QDRodCR)nmtYEp9o6TAeVFXAXlf znTEn}yg&Wj`S1(-~b!b_mr0F2A;Pgz2{;FfAY+l#_&ev-W(1iCr}x?c6`b5n)8 zxd}KCmI^j4R2~l9jdWN4fUfK2Tg&d&rf^PKZ|f6#;30&c|_vl%(VxttTR|n~OMST)8 zS4c(xd|yI~ta7B5(UT3yh>pGU9)0qsPYE3;{hxOJ|HX8s{r{;m35miueJr31jsFvu zc-eiQI>Q3hI6Z|*!`l7Bq58ys#7zsYykAe7E2^=>7Hi1;6(O1^kI@-)V4SF2&yLJf zGY@0gGEjP$3RTQCHu6)KT76i-jPmfF`}MpL@~_vL5&qr%`n*fFgb~{~;f^oh+jeok z030*JtzXcm4ZA0U{^SB%zo?I2Ryr6b`i3?hi!fs-CGmiXRUf+Y2smg z=4}3BB+ZpUbPcNYdoCSB?-xq zlc-CI%m0rre&+-F)w!3eIkx$Q>otcE{?!9|W!mLly^Ya_w|x=4Ju_|Eu7=N12^GxG zQR_6mg`35H(3|&{fmvDB@tGosg^83%xY(J1S^OMp?iU-NMI-7o8tGR*hC9erO!ALgv^Cl3?< zIx2kC2HhEuC{vjd?`5VWW&=4qsKpisu8*6bj{pc0Rx}9XS?m|W$5uXwC~i(aa4|Uj zwu|$BW&=s~a*$)>l`TY)UAjWj9mRbiPL4qkmt$>Zi+)_U1Q@0HynJz%g?O=xVp}k( z3$dF?U_}+eb_tj|kx#1(`&?Tm9j(ijea>0@sHKF23(3 z!DSFff!#{k(!A5iU`r>(21^R>7(AMzCF7rrHeqnI(->`_K&?AGF&e;n7T%@IeJmr` z&`^QiwpMXpIcLTJrZ{CkHd#sS&Vd6!wmzXzS38vzOs&=AChf_~=w1soy{^CmQN z6(edy;hVKeR9mK!aKGpKV?#K>rsQ*6M48P&_GMM*)3Scsi1JvHdJ6ZRmlG{h%}gNx z?e}QoE?XuqU|sR=vn=XaiG>iVCPJg=KlX?-G2RVA-9(vE{{Fx?A=Y2uSYKf(y2gc_ z8};m)TiN>Eq#WR+&}UErw>`ah;MpSH{WRaLkN9o9FNWfaep{y1ury{hlpzesz=J0K z_j2$Jgar^8Iw}K;f8bctau_|S2Ipkt;dilShA(W?i}XKm_FwqbWgJ+!Y?H2MyuCEe z)Ges;&E%w%jIHswl4+qoG=}flq>o*4Cv>*{tG<03Egkb9^o3PlRr~6{TC#7`BgOl$ z0?o7Flwb8#%f2;_kec%Ajq{E);?I7SGSf;jRr}3capZ=px<>UMYz+U~CKPOKyieM<64J+SDcJ_)A!-nFoe*@{^7Kkd9R4M3fx47#o{MnX}B44Dtz}vi$|I35n z+K2RvfMM)vL;1YFWY(d1P288D2fU1%WzlilU#g0m=c?lG&b4%YcW(CdL-XXmD*oPF zt+RQqd(NSGi&Xu;*-|?Gs*1nHdtc>xh-)*~Ca#TK4P5nH+qwRk>-${a;rccThWP=^ zKK1iliN+GC*wXp!xt50S&&_^Tl2_7!hV65;hWfc~N$n{OcZTP>=0!VUDYjh5CYH~9 zuhVkD-L|m*Y^Loe-ItHTX9mKn!l_@=Hv}GQgaM~H zxhyGU5>rwvi(Gu#aX~QeIK=HE8vNUTNH|~o1PB2kd6QQF*f6r&){$i8w6y~dUR0&+ z3;SD~ct+B#D$YI1Nz%bOIqH+xrmO0q;r}p+BuhWZh^+30g`VydIX$6lFX4nk$oce93sz*8*I%o z7_IZBUQ6-Ky>hUm9R22_t?H6pZF%IAN{e zcy*PI$56^;AFpg9eS=3Ah0ir1OgXq+#ho7Ja}BRn^M4VSm#dij*<3o8VoqgVOSm?1 z$uvoF_}F?%Q&!3wl#};k?`-1GW_jmLtFJwk_y0=hnvv~trrbK+xopX_fOGm))110} zqBG8(>x{Q^IB8T3Jv)NlH86hQ;WrOVnq`_1g+;28G-E2@^bkm@lv#wKUP`>vwGV|Ts#qHXyG|U>lNyD4-rqiI? z?0__`)A(0uTn?H4s6FIMGQR;99_l;p<0AGS9bAP;~G1tu3Wd$uLr~ILB!P@Fb%1?1%*H-EA6G4XSAJ)^# zp86{2jWd0B9;!SLfPhxTs{%J?2(Ged1^pX}TVlrwbR|1490rdY1bx4SbPyv{f;J4! zw%pwq{_DdK>Mn5iCC}Qv37AUPG>8uMx3Ah*4~n{2x6*wDlg9fBrd?ZHU`Z%0&_|aP zj5HB)Ylc$Cng@Q@+7*qEF~)_o$-!CGMhzB`F+}F5$B3)rt4GU(LPe5G|cz zr8${%iPf;cTt`nr|#aQih^Sg@6ZB%h+{AytR4(G#z z`^fUEh5atqYG)k(A)l$+T!4V-w3-4bq=9hjH+0u6LV4sQNbyW{QH^+|vhM9JW_O}d zQXu!G$u(S?xfIQ=HtryG3eCmdPl-<4hw2GW--hZ(`3kaAF4kg}rj|`yCB~W$*TO*< zv7-=581w?e*M2SQR>BgjVF_fyHZn;TroV)BT)?DU%Q6jL!g`j+#q$`5&(u6o6lEz` z+%7poB!x%pp~gLPAMnobXJJ0}yT z1MP02;Z+u+VD;D$1#AA!Mpss$Mn|5}kzdS_AZ}z8PiPg9K<~`BpdPxi!1D0y0`*W4-*YZM5XyXHAf4Zt zYyJMZfBLqf{J$9E zTZnuR)!kmc#kvh%jAf0#+RO?hf`J#yeriuL;Xus%H?P7ALQMRbO&oMIzBO(Wt}&>?~V z9?)HDP+H>DAYRV63m};&^XT4za)hcU5?U-z5M%m(h+6F{>Ng#?=ucVh;gVSYhsq zqy3?hVur>;hf1fmam8_d;`E`6sjXax+PTMdx}EP_hfedI>-1^9a~;C)*v57GDrIUb zS35>F3#P0ll{h4onl!4RWIL9oAG3`ZP4I!An4E^4>w{1J#FQ01IAY>V@bphiDZ@m( zmgD*gYECUak1F)AqX|A2jum$>^QYL|6WL@hvZ`O7n(4R;`8jc4&Gf|iYE$BTrDmYE0LbW>lKf6D2q27fsZE=WP;-vg~2&(;~n0j zOh-mB#{rYfo`~TQ9@T90sH(|hq=H18&c;aj6~{}`Sb=36v`*ydF^>1sy-kl6jdP5n zQ6Z>Hp`+4}P!&^>2@+%QL{_hx9!EnF1N`uKZ2CD-K?Uog$S&0estc>CLci+HRmoj% zSk<=%0~2cJ4#eJabl+JTQhqKv(HS;RM!eGdpEU@V2%SuRNCokQtc zw{HLRYJ=ht5oXgEgJe)Ptd{OJxA%s#mbY39|%?ik*>sxg^@+y7vhUw`M zk->{b=tO=wpQc|FuF_fzIj~LLexVAE=M;XBH`CSH8JuoPDr8$rrFb76IK|2ua zHVE=nR5V77=_3fF&!8$T*{fAu?2>`J#F9UzYSy|N5maA{HwRwIGY3Y}=+#_r-Q;UI zwA9zK8$SAbu4j-1|HReHmG)eg<9*v|N1XlpjyG@dwY*;LYx%<}U&|YnzLrx{Z+HBD zwXfwsr8)3&z#Mq-33EWnTH|=B-5fZ9kb96$-$v+_d$;iY{$SoOObOaB=6M#Ntj+lE zxjlSJ4aW4iTOIc^&U@2ucQmOnb+6f1JDTR31Mdv`)!g9)%N)BI=H3xex7K~Sb<8{V zyByk@r7?Ad%N*x6|7~6dL!4&U95--fL_~eFe}9%EmH*G$G)L+cs~wB4xXbY;``wN| z^WM)ZmTEC6yf~HX&$bzk%OCoA=`Z;#<+Fv)w;tMCx`pd$u6wwbXS>3&fa^}K>vN|$ zex5tSF`Nl}ntLUB%w)#`_e95??n#a}-ACI6ksWLJ-Mw z%ztc#V+$R;FN)OV6CDrH;d+FeOr9HsB6Y{*WJE+5S&wj%d63F@Sx&N3WjkiNM>u?F z+ijUyjt)!-qSMx(lYX*THU{)>IrPuLekdrq+_9Xiz;Y#f;z~p})E62M)Y}KTiQK5X zl^KKEM@OqdP%A7E3u-A?`b5?UX4ab$bLCEc4u*SnhLyW6ry+o$e~}>I%Uro6)SBh< z1U79O6D+Ma4Ndg(0yS6b+;{_Q#ROv@O#~mTN8aBpe_o?et-nS&)D907Z*W*a?Z-FL z7O8qdho5~7Jfqv2!Wl-whC9oMd9Gx{qLAT^+%2lXo==Fe)GrgG-W&#(p;FT8a^fo< ztxcO^uC=${d++8G>nY_DkB#wiC3xpnQ{L4T994diys~1}9Yc}LSDB4yZ{gi^0CauX zX%4*NGY1YXH3v@Kk`mZ@L)qR_NDc9%e99j}yt+MjY%Av9xR39BBabVSoa8>PhgaOb zcl(OUy*Km!#oE)>7320+aeo^ZB%|dNKnOoWZmYyN;#uRVbM#NNsW~ogG>-EQ;YLOC zu7U<_U6Hppp3^4bhPN`vZ45GtK@@VyU=4`J*%mA#Aj~=ui5cuV?r-Ok!Nw(#NR(%s zJaeI4jfRK*|7-Y^9WD8D4d?Ae7fn2cq-0U!>~eOqf|IGFuB2!Uxrtd;39?WUs3!C? z*0=Uv(mAUM_S$kuJtIv{D`0z8-9U7!pQ_*w7=4B5c?bWbBAFc;wL| zDMn9`Ue2djotR*NBN}1Brd8ta5g(7`9wMsk zD19|*;04ZF*TSZS6RUC8dLo7`YY`SM=Abx;Lgh5nU)wmxNLwCjHq!B1G3R8Cbc~=b zWbxF|julh2Tt}wW<+#S`=7CZAk25(de+@4$L!dc~?PmdN6Nl+E50mNgobe9Pv*XjU z9c6IGaRX15Ak)13~ z$F=+~Z>ck|I1DBKY^Ku@jpc7J4v6bV7VG#})$?2ZSnSnE9#u#C|1GetU2&DPDnm#8g6K-3jXp@(-^~>Rl$RgnvxeC ztm+S%M2@1fs^PolE*-vet^w2W_Tf#s&!BJ37k4UV=aW}F!$4F9WMJWqtIlOhc+yWL zA(GL0s6AHoq=Ev~h@4`4&O)flVMyZ1kY&%>mF38%Fs6V4H(g6LL^0~B*)3k`8rX2b z%Clk+Rk$}AwAn<4*;;JV&lAiqDS_m^yzAw;3RW=6H@ihFtGuT@8=*H{Nx4&qJl@t=G@ zXU`9AaP5tP`i=yHet3g>?=eWt`WtfhTA`@jgth+QhS7V?K=25T4D1Hu3GErb{`)z5 zU)qpOc0s#6NwwMg4apVPaiTqb9&0XnVC`U7)n8nDt7+&kH7whirC^-I&G&F@8C>DW z@n>uKp3BCt&C&Gk+yXGnM^*0^SL#fa5wEXGfcW`ORh7++xM43(s1$U0(BHNM0vSWd$(GROwr3Ul~@}5A94W70KjKPWq zQ*_*OdV@1by%gGk!3P_V8UzpG=Fe^k*UYFA{{=|Al}|zDRz7dxvyIP@e12vKbP*ng z456QZxwaoEo;C=4#{))BN2J*!!^4fN4{aGM@iow>2(%IvD={YvVSm>oM?7AbA<#GE zpVz*QzV)@o@*J&MNMK)^-EtQ%^t?P-r->7o`|@2=9M9OMLfXb5_T@QFK|7b=uZVMJ zI^KU7A6M38j=%H&saH*&QP9@ccy~!A_g*!7c0;g#r#~|ik#H2^qL$^j4FAff zZ6yZJxB1~A{9AD}{0y4tqxuUY9BuVR&yTqO8uavAm($?9NY6-Y@ek?mQtqqH=6R2I zoQHL&+~{B z;z$uNcd@f(z`BlF-~x6cbep>bBc||K$Y&{^ z6@31P&&@1LJj zxRxUT6dE+oX{3O*pxN`@{s_-|kyaYCc}~|y(P*@%OH-PM=p!uxZ3il44-9k^12xj& z2nK29x{Ut|;Hlw39+p8Sm^?>ikm+{MVFq~(gN!>rNcNub>t8*}!x;w8sRRbO+3Y!5 zAK^JFgG{%1PSr)xXlRgKq@EU%5FTW3_np+Qu~_Eo#UfjQtMaEA0d=Ssi?tfKwwj}h zc;~6$q95dyd~<)`nLlz#euJm4yfV;hA3pwUOG0>0^X}zF|=;!1HL`& zP)5Dol~)F)OM3(w3C+)CkJj=G>ED9?*<^}NmV|&7b(mi8H}3QvKreHe=Nc#rF!~5-(3TRFhb&`lab@`)j6mM5;}PBdcc23%>Z6DP6lmRknzo zpq3(gZBx80s?Vp_iZN80Is2gmgfmGV+qNlimur-kazMDkO%#Dd5@aoF83Cw90@Cb# zxUsNqRq%TmgB7ssL`qsQYgu#o)ytY!@|@gT3d@BdG)mm4owUObQTU=!$~`>bQv;`r z_5-J@zp%`6U>H*rasZXbbS z8u4w7aF?wJ2`5;~m3h&1o3<%|`_$4s_y3@9PX#7CsWC3k%u-|QnrgS`jo4xOD}uv! zn@9j#VoaQ#2om*j(nSDUOJa0U!$xOw!VgJB0G%(hL+g4ABV%s8fR7Pnd>Aqs z8@m97$gu|4i?)kQ3 zS<8W>Sbru7c~p~fXl0V>UmoxE{9vfpa|>?oA5Ogt5<)l%LanEa> z_or&vj^Cjq;QT#3BmN20w=7`NFG@!hm_ zh$LZ6`{TV$hvTbv9f|ceJs%xvqKRGgtROD>h?JW_O9sEaee2)c9`gg-agY9K+`W&s z;$UKx)|-{S`vByxk6JXCCn4;yW2#w#r~;PY0DINN7q$eGM{ zaDILAH6HyLm~zeKp=XXW*otZ;pg+s~ch%^Mnk$u-14Q2X)2f=W%mgyXeo^v)BrgnU z6(292Nrs=ohF;F2_3sxU%2tYl!FUK6>b2nd6i$q&H_dL54QtI@*3ym(p|8-WQ$wk% zkpdRi(zIYIyJyixuulHp$N!S1Lc-2RfQ|Awkxy%{_E4z!OoqE8UJXdP-`mu0?76+V zbWbIeX^HuoJxyw?{UAzwlNxW&v&CzCQS4xoeXJqY9;d|FPjVnV?)w=FEvO79#r|Pa z;!p0YPm6o5J}vz6CaZFqTmta|OBL?|hM(>OYP5X`h;y9n<90>W&B{{(v*~ya3ny(! ziKGgifsDmBF@Yv)w0)QQ4Q`sb=*R^CrJ-5voQwl$bbjZNgX?y^iXoPi-m*Spe9}#+ zL$=*}&*uNs@CKz&x*GxkRq0KF7E~$9)A;-o<=M96;FZr1ejz7!fEMRi&~=bq754V% z=xh3wL@vP*ukFAW+$+WjW>$a#k`d)A9FjtFb?21^n!J znb2>(m0ahw6K89zYA&AV-E(JBl-~_qn*-y>XO%vM)E=-X+Mwt4=^pazAU!VH|A8^Ok;H$E znBN-PtgSQJ&CgGVyPY0K#7ACP)!aB+eUuM|v`dZhR{)Wf3(W;R;7VX+q|)~+C*M~_ zsy&iDx`HG8y8vND-^@1zoPOLheg=9U=VN4G6ijbigYhyKaFzi<#1pp)6y<(!Ni&Lw zoY-7~KJTL_U>0>-cCCWw!}a4l-r21Y zWV_^G@D>R|VZHjGXGalL448K$LhuMR`i>%l6<(LEt7}f^sT0PM1-Elra2P?*ItJu0 ziLYzt`Hm@?w5 zS}GKLLn_os@cq?lK-k-BkljO&T`1{k5#DSFgoG8?XOU^AiEEL{R?r3{zaXIKXm59JMHw)1;tGRE@HCWBA#%dg6cOyv@Py1f`{at#0GlEzv>>&p|VhrIH&Zvz3KfiS0KkEg4V=DU-xj za7(GAq5C$ZE#RPZ=Kz=5$qbG|BVBef+DnSfMvO}?bz_>FGLgc%5PIW(%F<)oFs4-tXtavARXVPPl9%X2!?!9eVd`}UPieGYc^JTU#8?;BI|IRUpH4)a?$ z%sPuT{RpSv>Xq0PaS;Z4)(~xDnmpiBI2y<2_9$z52M;uvjrLL=YC;-!4%w*x=H!_; z1JXGQ1S>o(EbkyvdNp)XVBZA4tb(_z{Y{Ig3z}^yJZ`H83 zH(8F%nVdW4ISFhK7MBQ%`!OsooeW$_JU^+B(0!5cf$V_-Wl?(qwK$B#w~~oO>sXAh zdz#Z>!2Z`3$^VqD=*U-Ekbid@s4me6HR;Gz#K5>a3)vUm_?jq8$hs|FLK>|^$Bcnb zej*%!na9E(J5mT;gOK-(qQ33~rLT*U>ePhj?Pkq8;fo@i7mrQH>r|yRk9K;e!B%?n zq3nrh5tEofce>Jhe5}$u+o?<};=y6&s%AOkbe3@Pk5O7{lZW{&PzZ5&pyg5zDC zcX+2s1@klLr5R?&9fW`^65R5!7c^~M5^ z48lpH(zuTSbi1+~>o8%r+by1M3Pqb4DwlgZs&65xE*a25EEV2C;u0+ z9MiH{UaLnqVKo-+HQ(*}%ES){i4257X=YJ{6TR>ya zQyT3^A@_2|I#kRa&&4PnX4;ZDJJVsG>T$H!%FaJLj?UIJz+siPfB5W2Pk{&P{% z|9WO6GwWs-v;(FifUDhZ^;Cl-`W&04(m} zcY%@}C`IFF2|+5?u@y*F38W?fscb{wB_J}Jfwmjxd&1Cq6-Wp^31kGH1Ud&9q_)ps z@VrO|+W?cCs*Z4}>?=LHI_ zSs+^pGvmGIc)uN}wqC|P+8hg>i33DmIv~;-5utfrCEVmKgBswpb36yMD}rp7_I474 zjYT8iWb+OPhOBMRC~x!GSTaj+m}v)uM7Ev~oEM0_mM!)t1|#&LEv8^^^=00cjbpre z#W|rL7D#aPRJUU^uBolKrK+u=Dt7HD8hagma2TnH#QP*FM>tPo6JXuMm0=e#6P*`& z?M3X|6Rk{Y$L^m_huxFCIxUdF$zWD6t6j|4iwEjLC!szrZhw}vznDKVE9s<)D&Nvc z8&;P+iJ?wppSMRMGeNUS-69eu-HqdOX+kw_aEi{uYgQ&_HXeI zjKr4Ez#=>jjQkNUJUm44Y)>|LYlhN zrYZO@!z@66&LjlFHrC*YiB@lS;CI|C;4cL90{&%mx()D)%T|15M_DhS z0Qttmisv8#vWG;J2`@ocy6m;20~R!|k6>HHqtfegP*FsPlj3Tnq^>L3hk`=pd`X`? z2OrgJd{ia)sAeH#n)QGXC2@YQ_6PDw@c9IvA1`h}5ap=ez=0eU+nt5qlD=Ej41QPo zk#UmqyuJ8F(W0dM&YeBN)fMESlT3LlNjL7q5TucuI~M^rK`$YhFr0L?1vKmbnt2o|kX+d@6kI_{;Zt ztOFBSiFkPNL?$v3Dd`#Xz9ixL@~2AvY?VK)@~4eID=#jtDJx*b&@Nh=%u(hx3H5RC z{A5Kg%rCSew+x!!;OU8uv;%8)w zG+OKKN-ziRo?s4i8@zo{MlWYj4J4~l8^v)d!?MDK`)VQr>kw?kZ&9@-81u3zS*sd> zs>O0F`D^Z&>c5U2BXX+*N;_|v-Qu4^IoFwT#!@l-XjX-i-x2UWZggjZco*`*z%bQbs~Q6uIwD(+#*lj^OWZn@}~wy6+o3%D%TbR{Ix@+WvWZSB=u! zZj5Z|m{K*PoP&~WXAvnPefVQ2nwGb$xy!Di!h2iJ`)kfBEn0h|+EPxft|f>GqK3cN zxN$)l&X|VA#yeIl;PYNrU2dQDhKsCfWK**vQpA%p(q4vET)rTyxh=s5Bnp7U0Aw~B zfs`3YU4YCoAS1ICCm4+y%45wU@| z&z5iTdAhK`v!2guxQ>nTxm1u#0ny^Ed5$>iILCMpH36yKiDg8=4^Th|;-g&RH2odd zweAUyyd2^g{jX2*KMgx_a!JI{4|2wFU?R`4Vx;Q2WvJpgF`>}42(N3Qo9JbC7KigD zI!@&f7AubRH4U3$%v|7~mj6-(}Fe(@{Tyz5So2w61v z&TFRBoUZIeu&#xxj&GJIq6nRBoj;NTVbqCYA=%mf^s1>ic+(+MzD1Dj;RNMS@R38N zdvXLAf>vc5*yS|fo({XWIpVKuI=IW=b3VaqUpM893=_b<8e;%2)}b7TUo!MU;wr2G zpEz#wyun|*j^k2nGqUAv(7u$sh`^s>h7T!blUZo^Fe4(hAtsMRoNAKg4qk#r*-1)- z9)5dRHY2HB#Ez}+WKb(-q3mSEUE<1dM4{(LBhwF!j|imU?0;5R8B#83zTM|||6>x> zO!>NMnUakCxhmb;Qf>D(hyY_nvXTF#V=p#UF{FimSCFK(y3j=UO_a(60=C*>Q3k+q zDfjgA?Nk_qxVm^oJOVqGU0$bFf3s)sWWp1^|Id^g> zD+^xXgiko(5l(CyqMcb;`Al}kCfbaKH>mI`_=&cF)QojoVG_9m%%lKDVbmE#wnGY# z3U#^<+Fvm;s!oiQ%cv#mgJDF$Fz$mFsLX#UrCWXQj7{*2@OR-EqIyK}?uzo!d&Pr z^IzR#mcp~qq_qcyVXG{{U}ha=)UE6;G1!V}+r~mjN%;*Fi1#vlOW6(>I%ksyF>5IZ z>jK$Hzgf2tSY`@cEqCwDWDRVrL3@qZ6A0nv8U6kS&DXM#g^)_5he_)b{=vn9*l0jb zR3GQE!o)YQfC=TUJ-_}Vh@Eg1oa5@I!xP{fG}^Y=05dQ(9nPqlA%pJNPmZHMVV-ly zF65L5d|9M=N%JD2t<*&mtJztN8|_49Nu-;MOlpKn)Z7WK54fy||Ht@5vFVkp2>l80 z$qb%9;B7uf`nMO%6I zc@vyV%t$d*ayD*JMvbA;%j$D~{5>2XYTJqWY9k{XO87nub7DjJ^fs)4P_i*lxp~|d z!09lk@r5iZI0H^&I@yRNMIDh=UA>!fI|rsNMP`NUdFVfTZ#p!=OBl7 zaqs+KCu43RJ)QUz!uPr=(7SQ>b>fh*K>{-gR&`<>=*)80x#NHSGmVM5)ViN#S+%j8 z^)Y&EBb5e&Q)xMdX`+kKOK@Mm!B%0#e7ORpUAKYKxhxuVcDyX0ETjy2Asx$XWRL{i%7ZW;{5Smanwvm1UA&g9P7!$()yhs!9%X*#2@V3NYM3EV-z?ArjaaiM6 zzDu@#`TrcgE6JGb1eD=UZWz>wKrGuj)*+2cCu!0FMu+fvhx?KCWw~XtEU(rWUUOOR z6UOKy z$e?6dWf=_&ULsH-S*VoPqXk}vN;zgR4*IWC81idWnOuYyWg$Fh0X%3v%I>wR`q4{7 zZItRS-8-XJ1vB3^CB_LwJ-%G&J9n1^*_Z;s>2I4xYabayC3!eZh&uII{iYyVc}i1~ zySGwrE3D5zAHS45ituqUd9=>^Lh`7Q4uK-sgXp6d`Z<_B`Y<4fXy=8Gh3I3LJSI1W z?+IxXk|yNQCd_hxG29OutmrxI#+gm+HEL6B@aQ|H3D=>xIo`#B zQ1wG~uOF%){&At81$Xra_rs)Q5w;NsB*H%TKVJ*yE;j9UEFL>&uR6Y5#Kurvrr;?N zQQA-q

XHwu*B$l)k$#4p@K~Qh*o|X5trVn6K4_F*9kg$oON)gzkQ z{>JtQOUH9C6N~sO=7Az4WDz@Tz)!?55#v%AmcX%J_~C%$EJNxua%@{fzj$R)3`6n) z-(|oTx78_SK-3c{!vgF>zHDsbOiRhhL9(5SIuD>l^a$(zRGrrMsl<7?f!ARPH3yvu zt;Rl~G^Qe#5A{U^W~aIxpCX^ffw5)Keq{9Kt?W&)Eo@+cW-YeWS<4#scn8*|y^uJ) zfwd8I4A~VBMZ~bsLCp2}n=FioC$a#cd+xnCEJ6;k3u0Rk_=$bN1xIhM@p%p}4=V;q zjeZ*5g#05}%Eav?E{x-ktDat-DQ2Lpq#_c*u4u8P?gY-iM>UwkWPXf5J4iz_NQZQK z5aeGS{@C0cK40SVs2vY4F<(2O+ifWvp)v|rQ`}v2Vgjq$Ftv&pGeuRVJfm2qoK@l` zJ5hR74gnB2ktqK=QE0d2;P$`I>v3(v#+x&SgDPVjtFn;v1*9mu58Z!nM02=Qu}MF2nr#)M7t2}~wRaVA#Z=#f(h z_blBDqR(%duN;!;t>=Cc&uMB>g#;JgX|R{n(j$iPie#RNMp7TJ4Y=!A>@)06Z9IAN z&Rk%35}&b!-#$cW;Owjq-U$UdVISc+)h zw`QMiXul;^Su``T&{M@RFiTwUdq#6s_sO?fl>ZM^9#F1Dm_KVb0H91f)+8kJZE;3NvUA5qMcOoC~TkpY$Gw(8Guz=v%tgU`_i zP9`j%;U)7<&OP^TR?EuvKFnl=wTd7t1Fle%2z`c)!J{T~wpPfq3dGRICGQxZMdFc> zcOT(hGpt5f&^lPN81&?SF-0h4IeWuUzvMV~MFjSBRV}!UabEKGmm>o0T~${t`1Th) zaC>B6>4~ZZrC;=WQDndeAQtm`ux-6@*i4Jp>9<3XWi zTI0RbEJ@yJRK7&(F=9Pc8gt04Y9X%X@>C_>(wgHBj*B#pxY-)%U7cX}uC`cPZ%A1i zw=jp#bUxuC6E%EfqH$`uY-K+C33YBqE#cs^dq*U;i)`;S<0$VmYp!>iZLEZWB)N_B z(rNTHxEYB-wfRTA#F+O)nn&mM7Zg=ggFBXtP;XjcQ3Y|!i)dwaxvljE7rn|T@_j|Y zSc^Gtc6Tggr*5R_QYORpT%ub1dkmHm(Ho_Ca&5b%i%(vZeA}rN)!>7;#xs z-Z-?I=)k}Y6O{PiCJV{%+id2<3QHWPHV}faROuCVZKJ)eXcLMXww-V~QA$MvHyls| zcuOpAD!!u+IDa;j&j%RF?s!T^^Z#ioUJ?A{&Y|0^NilT=rq8b4W^2h@ga!;&$%|HZd>q#-JGK3t5Mx2A-LWAR2r$|EdewQ z$zp%9R!HF1)(Dcv;;+!@s&V-E9JMyBODa9Ab=B=iR+=vtcFU$k)eTjZ)foR)C-Zm%bomu_XA#fJF+J`FqNdsF=5gJp zwyxe}ZC%~X=YvFCWf<%g1ja6!ZMOLCFvCDG;)o=q4su)a-Xg!56$ zE9Rg*mrskX8*BBhb`eb`a>iV~ze>+92AiVI8JPeMsV>Gp&gos97wv66NKK1zNy_TH zrOKX$A)IeH9&OH<9dBq|9cOD@-NsPj4Dk#_sfeGh4B5n?z+5`hz=#T{q1XzJF`Oo* z9Ruj1Cb{c~CR@EJ-n+VAjjDK=-hwyBm~-McOtRJGCV5wTmU{Q(G8|9v7cu7SOhz6c zqT0WT;oQn_HZh!44Chvcvr~rC7GoZv<_68N=226Hz?1R@8yIQ^vHb1uF-f!|1b@$M zat6#J5xpzNDqCFJXE(UE+Z!^;gHxKK zRAQv*9sCStlje0Cv9LT@yP%8qCV)9wsA2pwP@l7htqq?nR(iFADrWT&z5RBse6B0F zZsV%ps^_X3(R(c&w(U|UmMyz_T1KC-ax3hti)@nR%Oa+Y#&+p0R07Aglc)QADzOs# z)>C0?I6F_lE0EE6#bHBWs?ivjv|mXIT)tfij6SRcroX`pbxQA+Ws?KJQ!7oW&Y^6u zMky4*(W=hv-d-(H0+ql&UxG5Uj;YJ&e0 zZ%)?sVTdl}83PR$gJm+HSp+$jPEsqeWiAqX9FaTCwXv6;^M}k`G6l6lzNz%wXeImn zF&zL2IsmTZ{qT}X1;+I0gpcO>dc{ESVTMoZ?ax(v7xVJc7;p2LKNdISD=8ID-4SVN zoWaXyGJL(Yzba{vR7M>_dKlyeiqZgZeVv`e`|lnYWEok$FSRh?LBdS+K}xln&?;%6 zQA$U(l0w`nagNmb-MT1Tyi>JD^YW`~e7QL69e@S=-lt(AcRdP%w>vy}q}vb>sJ z4Z^0!{LAvL;L5kEmC8qyHl9n_!k~ZPoY-lBGbqBVw@>ATK%M| z?G>{*$QnF(+ME<@yUc6}K9Xck{Y;IqiNT&EbLOnJ_XtiKt_+cV5j8>Cvb8Eiwxm@d zUDC1>uKgL*hi45&{Zo2x!DY$jG3w-CAlaO9p{L!+=Fvk3qilx)7n^_ics zN_T=R$pe)m1UtoIrhf*vrJ7R=XEK8KrkJx5i@u|NZi57+dfF-mH$R`O$7R1!n>#C2 zeefHI;|HlKD)`>@&D4c9#0{64?4Cv15@E#qK2jE8q-_+*rOck<-`G{VKunNjzwtF= z%nfX4ENMuBU-E2s2MCJ(7^r3MPYupbHD_Fy@ZG8AVpShuTJW7zbK-?x^ulfe$BnkC z=2BtDNIqEKWydzIg!k90sTFNBEjTaTR1nE80rz4*mR&8w-1;qbQFz5|6m830wYM%q zRV$&7R`%L67T+%+AIT+IY~#) z(J3-Qz|VYg*il`Cyk9}5LWXjnQQn|u2BPS}%(WL7|F*;7l#>>;?Z*D{=Pw`>{9T4RDM&sNu2qcmIohvyL^I$?K~X9xbjQ|YZ`IrRIb zoZI0&d8hMjo)6vE{8%xYyZsQ_5~a7(k4z}IQmUU^a7)>nGUm{Uyi@i|wfS$vTgKlno@7?nkRkD*4L{R9Ha3xwW_)7F@OkUigT@Xw&I!v zlTcQKsh9D5IUR=v^>*3@zOP^bLF)PCbY5??RU9u-7HvVCPMHz6Fl~mCU_d77EI}cX z_H*b!W?-QcsW@~P@JdG(m$eR$O5p5dgsWm@(xl+h;pT*e#Y`rhHmtNo@uQNi1or%X zrTJ^LIT%plD=YsGU-RI5tpZH$Wz4{afq{L1$Db#gnHP}JJI*}K2)+h0w?(9yVS^K2 z3Fdjs2^XG_?X4CCeOcy|;I$*nQJRagqZW$XuKh$PFHb+XwwN*;QWTh=<@gl?p!g^wcz=d@vgKi86=*D+&aiOus;S_$QM ziHfl0tleSzXfqp(qvsYTSOFj`Yo^>SM&FFR#!AoI{fmBHNSsWguLRt(RGc`1ipknv zyw(z80t9yp}`f_`|Y`Jx2 z!vk{IX|?B}y40L?DgD^CJDc@C#1*F!@~^ zbFiSPTbzGM>on%LWuxDKg(UQTn)@CWzU;qz#9(B&KcR+4m>Ap`>NifG_&<&KdoF?a zh8<^uk2%a)Uy1{=<~kV=B!&G74es1eU3Z|8ysZwmOo-Qu%{@G1)>U8Dcz_*jFbJ>EiK3mGf@Ch%dP?~{Q_tYM6=R8Y&0Tjl{0nQYz8GBUV6P8G z_i=_7KK|+{U%c?OgjHD9oV^=adxaDBFRPl1fplO>cA1h)|1Xen0;1=aHC8v*8!X-O zjEDir{4U!;Fnv`AbmVp42szPES@ycxJQ{Qma;D2}H~kAFtsuB`)Wsyt(D|r7&7v>E zZ&7ru@xzDY`;3+Q=3vPj#C5}pZx`HFRy=shZ62m|Pk=?dO?__N+-#{R+0N+IqPt+qR+w<-t;6c9<>h>bu2;Z}YoD%NaJg#H{FdJgaADzDytt8u1?eWj$1H0LH+T9uGR6Qj zIyr#jkE3FZ@7ytbp&;pC9#YA75zxyxi#>}=qyQJJ%MLHIMih*iB;sP{hU z;_!|g`Rp62-ET)WTO^;Lh(ys`$N$nv32F|}H*Qj7HE*OnJFB}1Gs}*zS<;KvTGEAo zN3+T+T+wyi*}l@|0;CgJ#lx&%nbVqHWVF~tjH*VAx(3~<^)=WHHX0cmn>)Uglij&Q zEb6{8AXI_BQD)c;B*Tzke+0CBuI>Xp!M}|)XB!47bzdr-Ja8!@U3>B$Tler*CLrv~ zxAL`l=Ha8Wea*6tIGN&0*|o=5yWDP$3A4_!%R@WdR?*Em=LYk}m{X$%R{X$FVj8l8 zUms(>Obf51nU$1<+_4gYn}tk6E)@Y9t8wK{FUPO!bNOY@FTv&`(z+bRIf}zARfh;Hz>r!Y(2-b^ zP@aIaiUU{{bPOV_O2?q!p|R$1{|M3qw~V{UKrk+NWSn_K(k01$aCn}1SjvD}^*I7B zSh4gHSW)r*XR$&sLPMwRMt|`i4KX-&HKa|Mgq%Qf5t86NLfk*xCA=TRCb2Y2S1k|b znbQ(p$m*XMHpwm1?_aQbm~!N;9ew>1rGBa?v+_NM?-whyy4fJOa=h6R;cEa7LKcSL zJ89;q3j+S`@#cxzpL_aKboo`1x_89}-ZF(mjWYQ@G%oNu-#~weU9C5L4ye0B;k@b~zg(5#DwjzzZ(w6cVF1e6R7p z;cZ>u<_hpW7u=KqjlMo9-2%>Uf`~2q?P!0LstxnktA_3dgwSYaGg~nPqSa{sv-o!m z+-tbOn(pG^^544rV%ZQ=;R+gv!Us}s>=)xBp|97-)Q+JYzVO zr9B39kmcKf8Am+prK+Xdei|8Wu~+LARU$#%kfz~IRGJIFZ%L}Bh%<67Vn!2sm-Pvj z2GIKXOvaof2FJ5+-`sm0^33(4YO5? z9p}^hP1cvvX4how37#r2J2mI@Kyl6R9+9f$43Q`o!urGlTh0h1j7EMJ(eoR8%3-n_ z_RE2?Y^03kBq!1OZ`%_=#nZi6Mo*rZydZG%i{uX8wYLA=Ged=`5wHz(4459y@gPv z@8V8`O&u4f(rs))HtQKgt}k-Fuw$mr+^uAFIhEd@D01UY329~UA^3%iN+^$ISEmsRMI6oYdj*mVB!=HA08 zzTS=mU+*IfQ^M(w61pKC20`+%tg0*oq575L$S%X&ckH&{$1}~Bc{2xodjZqVvBygq zTx*llWv3sbW%NA4!j6ryufFJ z(fE`MC`VPA(^7$oK#_s@mtA^bOBjS8S9nk|&=2MNpaID*+%~|?-u8r zFJ5jj=|TSSfmynjqbJLESw^`hX14tu zTi&sy3{iVht#oFRIf+0L2_g|UVLM_~8|&S97rNjNe7JVp%2SgfVZ%W+0I(}}eEr8a zT7<9^V^M_-FE$yoVRN^h&6C_8(W`UU|ov;hZGK){&1sOHDs2WP=X|5pSaeLAhNHl zym;g^B>8SaVY*1q?nZ@hnUVC7n@Kv>Tuwr=9Lz$>T3dS8ex-Tra>5`+s!y>H%_3Zi zlPL;|$H^3L@1h)KV!gps8I?mQ-F`g3NLe2lNgyqeMhD0Wiftf6;lzeocAyWB$^_#y!u;rl`CI=fv@#{>@ly+1`GoaFqy z>th2F>?ZGO7VChu`3rOv8PFdu8qgb;7|_A57?4ER{VnlxK}OoNPIhECj7pF58cIl1 zeJGl)19DLUxqvK$!ll{?bp9o}3yUZEPVFx*CKsUy!muPz#Zlw1sy#T`Nt~AtGvFPO zn)0BG%wl#1o@R7Hw`753A;XJYM(0`qxe1}jIbd98qy>b?7}6Pu_eHtPvBRQF`U4G~ z2XAz2paBDdV4}2>gF#f<5E3Nqw4onq>y*l^w5Msy$jFDGUmEU$_k4o--2?!l$0-=OqNEZLuSS-QSk=`BLmPoGFsf&3YxJIG99z$rqG#1?8bER0%3pce6HfR$A~6>7gm&akGk-IxT*U7w3zplA#wK_7JAm*mlntW zF@_lXZlZ{ug*QcW??KfuK5E^jwB2hB3!lYOa2o>%-OtePpQ7Vu(S0}lcvD)2L8*)# z@<7^Yqc(i}2|7JRC;fC9yY7LsC+N6|j-{j1bkI)+WA*!v@u7Q$h5d98x|cD2+&yvn zv;8#Q^yB;V#^Z)mr)_=D5WCcrKUR`)#@}mMnDM{H%1y(S`OaaPF-y3{t$Q%-v_{1E zaX`9@AC|qR#%8YH8gnpyuKhS5KFvUmGZ1xHR*Yi0a_qrZlp&*;Vf4MGg&CYrQn-K6 zIoIA){b1Sy%wAo;E#{z)cdIw0Jw5=1j-yJfGjaOZ6V>IxlOM4cezR0I*TCMo${Bbi0Ui&l_%ef9zHIKbLC0)!n&$kzvgmbe2C~U_ z-18Ni{H_a|T-cFLOppoo^1kfn!JIfzr{1VQU#;h*pK~?3eMr~mXUpChqTEthLafe4lFe?K<@Vo)Og5KL zg%xUjnq7(Uufhy=pV>QY6K7ifjKxrkQz}=Pm1zWCOsf{+oS?)fmra}6%UO%=HJsJJ z8dkwX>fyeGGB0`-Ft%fY3r#hXVTPyL_$5>Q1VJJ^-8PZl&_lws!r6SH&;Zk>CWqWnWpq)0-8R!_ofqj1K zLFu`b-@ES|KE4||eL%I@W|`*_m}IvjqS##4SvJZ4;$D*--FEVSc0K&W{32{U=A!2qg&?{)RBWe+x`(WmBgfTkdU6jm4FO zF4@lN2z*3t8@x(RStTgpMFb#j;{Unj>Sj-A1Q2&8;KnC{v0HR&hUI5V%dmT(ShAI6 zPYHr)XL^1sXP`Z^r$2 z6~pv=mPPsea_Xb1!u=u?Tv`wEp6`AD0G zjp;g3q3>x|h?eu|sFH?@!6+RsNA3NR3F&M5jj-YE0%C+_AT}Ubv*q{q@hi%zWVJRnW zl<=gX?v+H$iehk|^Odwsu7hd2p4gQ3u0yFTLR1sptDPY6$OpzK_XDn1D5;Wcf7Yo~ zexSzKYY@{U?ob|*-%m{NHlKzkom$KRKZy2iYP2mMf&Y~AwX~D2LuvQHKH{EyAnjQi zk0~2H6|AN>oIBoqFzuk4WPg{orL>E*ZJ=#_)7+f+>;Nc)zfHfnMZH*B*w23dZVwVom3O;{WL0748o1dZ$Clm5JfY( zY|PZrATy^EZO5m~bUh0sRyto!t6;L5p75uYW(4oJ&YWzKNgsf12Oqr7oOB~Jt{xh9 z92y7s+{XuK+$Lz8U8iwTZsH*Z(KvfW_Zy!TO@z^Qqw9&xU}fi&8AH-Z@Z5Fgp<0T! zH!PIM16@3bEkqYej-_~Y@jx(|Py*toOcf=2`WK1tB1RT5&d9Qazke9Z8X{|nN4Apz zzhG1*y{F+p!l)e3haw z#^^@neyz#5QEO7FNCvhszbW(n{H8cE2j_7~bjY)+z56uJd6~6D@_b;7acfA3CylXg zcG@DXnraM8s)GTXCJZ{j%H577wsLKJx>wQS{MBl_KSNQwmm%{#sK)u{EAjq(LtJ+U zz5%H!B`;3gc^!OQ^X)e@YRapod=>r zdf*FR;C>OSp7$B`yrJhfNGk+M2-I(QHy0~kE*3s*pz(4VM;qu}LEDn2OClY*F5UL^ z=lzR-MeiW2f`pY!A-^I)iiBw8|F8yz`CoT*i}n?^Zb_&43}PV+Bbd3;l=zh=VbAC% zVF%7whMY;Fat!XI{=7qn-{~OS$(;t9`=9A#;JEES-pO~aj9VzP`5Lp4HOm=TvmC(s zk2rC{Ho7(xye{L=VEznqgokAlXkFTilc0NXG$tJK;sn1}YIbYuh#U{&i=YcB>l3Rv z!t1^ZwMeEV4x?4g*(AzHTtPLxhYF7t0C#R2gf!bVOH*A_v(XsFf^zU3`(reVtH1qSjSR= zw=Ti`_%9CPE5{%cJvOR7O~xX5<>fnPPS3kKCjdBr8XS9tIYPZQ{9mL?(^2%=rePMsBEQ}C^CkIygrNl3OxAkiM z-8r9oc`^_XE0)MqviSuX@?B;qDx}O%uz>8rjY-U;j4MM;>YgZ@e)lqzec2r1o^%02 z>wp!+3)da&%03I>6}l#yBW%DHPih#3;^Mr}b4YoWp8GG+^A>|u&jRoqh;B10!Dp74 zqyMiCVhfZ)Krk5)3?4-J|20SiZ@Sr>t9=ukspTM=Zty>y9mt5eun=AD&*DNj7eSax zwc_=>un-C77vdV)4Ey%?clIxeWnseK3lH}%`X#>$ap0cz8E3zajNnF?ULSrh6v9;m zH5k0B1|#$Usnn0p3x|_7gj5PokniH`4pSi^k@7njraQZ}0!^)4il@Qy2jnYGO^cnX zQv&+lEpGUTjG>ojD}k&8P64oE+PMyMue36mXv*(Z9ry|CWV!Wj8%DU77SgU=vZI8W>%R}IS2)we(!_yG6JwOq+mNFq zIDpw{y#m9-OhqCEK76CN;RvTHq_}}(Tze{ogKZ3M1J|d(XE71uf8_s(z_9b)M11hx z%?|@ZqKcmq-@5qUcVao7MU=MpzBw($e0JY^?`GCvhy-l1`n$6Ob6PqL779YnZaIFN zwqrpm(XuK9h}T7%$Vr;&9$~UjHGnj*M2DV1Es=V7l0vtG6u3oq-TTlolWA_PDfOEl z8PmzFqcon|Zfj_NfYkF>RLwZEQ0YA~uWANI4Jvm+LoyPS$__r!G8?B09Rlkz)RYQ2 z;_x-TpV4UK(;LNNokY%)4!rB2^vVWDp{ccSnV`M82wpQk8@Sn+EoZ>;~JU z&r%jio)_K?-U$~AHVKVC<2~tMFCCmGo4Au-rK1bHhn%DXTu=M|*gN<5sH$u6pEHvQ zlbJk8$ZG;gcxWc!O@O3gGYLL`K!AXcYHtIkYLdZVL|ahd1cEj)sElH#*8Xn5M(L+nlZT4K*o9gNA@Uv=m!_AV`O%Mp2b@V9(cU9IpTL~UeOd5E&3 zo-|c?LkMQ^9jIU@A8KI6?Gn={9M8)@lu~ zRcTOMjG`kLir^H#V%i`JHN(_+ISd%UNDhu*3k=_P0;2Fr5a-@<-CINmA)47cN9Q9lYDzW$GkcnM51#`&NVGa8| zn<*0AnY?4rh-Q5>(tE}pL^Lmq@}B0mREo^iD_sLN2qTcZVBW`2KIQ)krt`Y_eTg(! zQD~aWvju*|-WlNgx7#qyeibe7AIcc6CAx?m4$lD# zBa!9T2WO7-VpWQhX?h!uOEEf$YL)=~$!wJJHA8&gS!#*@#-7C9=P=M*Nq}LzV@m1w zY;W(gf>hsIOEILb8Q$+5PwzW>M)iAE)BDWi?0uFL1Xsc6V5ADXwubME-YHbWBBQl0 z$5_yK5kF(!z3?-!j?41fSY?zlS;UepogZ<&d!hUmk`f(LxV@+}(s8TV_w3#5hp0!L z91Rj1AkY4jG?+Zo0@nEc3o}U!W+=}!@MEc`ZNjC=Tp90&JD|g9x^c{jFrr>ea<1s=dNR znZYEO)H`gd@53sKO>;*11I{wg%`(*L;@mL&!lTH8#$6bPAXJcik=P8HDtmE6U1Ibu z8oWgT_A4BZdbOU>leh+9c`|zD*6xM!TL6%4?T!WjVg0n|{?r4qgQOvuzzp(f zWnM_5-P{F;z3h`TfRM5;17bSqFupbrT0a_=a8?}%?gB&&nFo4+pzO+ zn;t%G5GWYY`dAN)xoXJIG?}Y9Kv)KX01~xGDilRgSC4c|T&!TrJBC$jIZAfw2)_Y8 zbvnv696MF@#eW|=<_z{S8bH<8`Z>5b6@zVD;-@tbwdi33uD*!MrXFPUYr4ti>5*O^ zOjH=VnA|VJ*tIJ4cijtTsY550jKbhKzL!(4}> zUoQJKK2;X}Q=lV=(LP4w3|h;vd|jOEh$eb~JR_|0L?ZUPG5?NB6WCwrJ7H2NHrf#VP-so=W!%rllBBKWd&3rp88Ah& zVlzx>=)}gwF7w9b8#uE8ckNNi4wsT?mBrbOH*wgYKT19`PSt)!%I7CiuT(k~E%rxK z8tbH^EUbc8jfQJMVjjg9Dl_UR_5g9e>N9d$U}-5ftl*ai(q2CgvX$skghK zM(>4pif$zh9YdiMDI?FM>~+zY&Hfc8=K=cdW5H9fG_cjHzuFw!u))0L`xJPM(XjX( zB`1h5aVeAkgB$GEp3k$=GW2#y#x6az1!R~+%(z$<8VwRT(?=37fOpkoU_%k`vB42|>5U=z5N z_*3gQm24q9vBMu`FI6h>bLuRAY=rfC5?2P^C6BjP;w3)4o>1oLO4qqb%#~&A*GRsI{Ok+SlY`b|VTXW2h3lFRXK_1e41C zgtuM(ls2%U7zr}{fN%!rfUw}CiFM}qiY7c6(h=!EhD6vtAb0;TyQDK|rHlS|?rWaWR7C8AM=_w{5oT8kK&=#;Vu ze-$9}R8v(tV;)Qcq8|pYVP)1iFR1ff+y|QI0qk@c6MYkB=jz;CX1OuL1skGk>5El{ zk$bMtKr6kF7&#gHELDNQ+I0rIFyP|TrzCu~jOQ5;WH4s81ZdE}Y!4u)?ma9=A5Q=g zlnU`lg~DJ(sT7BUptKc$xa&kHD3y1FAVq(YN`>GbF|lO@nj!|j5ytF(c?@&|R)v<% zK}&G}N5YhfYUpX!S0t#$+N_J|>81hbN$eR0J?-l!N3E)V<{5M(G$cUxrz4}x=(IlT zpd*8ZTG@n}QQk{OAFNVi&BS!J-0ITw?0OPqWYEzg!<4}b)to79rPt`BdeL>)g> z82Nk5E-Nl0p*49Yt~+mPy)u4ktCBI*sisY}c6Uz}an^Px-~BE%r@VXIlr}g2A5G11 zc3(NAb?LRa<$p`f*>|CPvWfSky(0-QJ{b}}`UwbQ=*~>1hj2=Q$O@sQDq&>df8<~> z!4yocmJM45zdB_5DyHQ~uF*Q2s2f)W z$)oS#I+N)s!SWx#BV-EWGH|yXyuN-qGD#GpS_Bz+-P+F(_%i($7)how^-+*Sp2;d! z)Z&_*_$*81aB^j*L{hS}-(bb(A!>&H|C^({__tq^Qx`&!M;8@JWzv{ba{B_@zzjj_ zb2!*(=okQwKrDoC;fJ1lAL_;tmh_zao;l-6e*j|@so8`h`y+NPHoV-x)Gp%^%g`iq zkMB~%mtoF;@%j~mWfz+>3^R)`by*lmP*AX$Mf%y>{Ke)Kqj}wbiG@N%#siA)Pmd7Y zpB6xpKYV4RcQSqXDnJ=FmR_Lx+F1GmbxE9r`H}L!h7%c*Wtf~gnWeCP-}c)qF}lX~ zRdDc+8kl8)P$r4y>NLlznf{QjuSy^1g2TFW`iQ>_eZ)5)BK3f>Ljl*iK_BZ(v6{M)t`tb;Z^cm7D4hHZB2JTlU}Alc;dZWXkqQKf#v5T z=pv$}`yPCPjjdwpGL~U2fo0f0&In_sHwBjV!BFVtE}$@$VRdk1fhZV)@3GcA#G&qi zzyg0_iK|CxUX`8bZGU1BihZbs*pTCF_-U^Z>q}zhEI_t${)3Y{rlHKXy^_x)Jk!l@ zC*|d^`B?TZPF0gK%T^`mTV*6fFlk=5FKzGNceI*gGe2Dw>*yqE?>y@V$ty&RayEx= zbjgmWjFs3}TdwMyDsfO&{ooi>?gR;iiX%x%n0u@2Zbzk(Bq@{eS&Q6|2(tlEiMy_u}7*Yj~*B)gqr>uwRO$xbC%#L5n+ zFf)g!vNjZpOfK)qb4flRi3hUe3<$6~)9klpNirV+LTF&1DL7DP*oM(#%aRU#ReRP< z5Lm(0Qjsn8tg7>a70sItCPl|@E5uYp=#Y~HzHO-KWo*+bdq~NdMTa({hqRYs5}^Dg zW?hBJRyYfLXvVcl&TgJb&el4NW0KZZWo6cmk)?J|Ae{=G#s(H=Z1)kBUd)npVxlr@ zfizD*CHsH!9#X4h576ove_tqR&Q0Nu6mx2I=DWW`LlJ?Se#`2~$jk>Lvmey0-%&;(zbGPEn#I=#7x_)+o@sx3ulPXUz z&E%ZJQ?x#h1?MR?ot;u6Jg4d6-TdB)Z&A`0pJpTYcz%Rt{@mMwGBS&6*?m>h;){AKTM5{4OhP z)8Dd`roRyb)0Q?BVtmdYD7Q|JfeCn4S+`v5Ssm8vS~Wu$89-mAHw1-3xxSzLn2^k8 z;ReBGOtCC3WXovWAZ7B8815eH4$X>TN37UiI|LGZ=*C1QXuk+Ztxur0u#x8s&rCl9 zUT~v2CxCP6!ZdS6e#ogoBVR;#x>WCInFh zTu+x3uA$6{`aJ7*eEVro*MiJfd1 z!*tEXs?OzfK)X_9Chb^Os`kX2HoGU&Y%lyRa^eJYq82t<3mcUkufj$(HL3jwNxG|q z<-+&z#5CFAW{=Iwh7p4^Z z1i%!K@Sj#&3eF|k@PJV^t>Qv}TtATP<;jXq@b^Z{K!u#w{LMnaFw8(7{Y=<23S zU9m75U68RUkj&{wjW)Kg2aBy~<`nxm{M{mZ>&&rkHyixL7a)Yv4qtCY+=-0WM934T z-ciQFROFZLGRETA#yb526Xzk8q9!rWGZ<)RV4y{wN_hkF5<5{LwzaB#*Y%Z`;#4}q zZlt5|`WecwiE@&j*pk{_oLS$FuJ=XG2 zX`~KUHX0wwCSb*)>~ND6PQqo%(4{7EE#w+b9mf0;HCcqQ;jIW`OhiKv46HuXy)ZRh z;)ZTxf}&Vj9qaOT*JOHqY0sHBu_tTak|uM>2lcQCso~9j>ZPy>L$!1X zpNCx-uF!K#k7TCFV7hk>5{u>D>7K<&u#gdTA>mI;mOb|8Y!JCR69~2v_#>#0ZyDEH zdvNg?)FPWXl2xTkx^&2t+%6vD0<^k)44TmHo7lUhAu&hG^8)tOT=Z;j;90ouoy`c0 z0=UFQ?~sQ_{~o>jqG!6Nfx0>M^`d8`f$s=&HlF<<0Fz!H+b=~SI{_ku@3t60XU3W; z7@O6C=>f1Qof8o(&Sj~z2FHLU*st!MUJvT+DbZ#+PFHE8pF8mIiS zjdLo`Kt1kP>u3)|LmR^)nXWF|IIL6}?-}p@!>t)hQpQ`7?-&&u z<1OiJ^oH5w8Qg0rzih)qOiROC0=lO$-obPx)(SnuLYR$gOivDklo>!=u7TSSJTjLh zAn&U*WYpQO9ZlzS{{szOq8+W5oBo4(bcu#~+cBXX8Qk$;co2Iu`3`I$neK2*Ajb0^ zj$Y%ZzuVB$jAwrg`t(`0c^c(C-#n=_{vIkjFNvu4Eht#rO@AAHaG^; zpRqsUQv7B*fdrQ&{Gf&w zVc-1$kY|?z;5kVp_!Y3=5)7e|1k{$^@o$BIY=Q;u!UUxr#FrUzX;A<|5r_tM1RF-BBK)Mn$Uueij+6<2 zEud5cBLC+a?~5KK?;E<59LJeDl$a7+`<XN zG4DB36DK_h5?WEHXP|i7_gQaIU+|60>i1Sz9Z!=@NdW04^A<PY;tLfj za+&i!kZ%P@ot|lQF~6mkQzT5$qikN-9BuhRkxVqJ(A2x+9bs4pY%|-^9=v8JZ17pHhIcM^AAsTC;Sp} zF+P@{>NjVzSzO|;!X7COvprH=%bDPhaD0~}J7@9jCb8wh6IdwMSsy9(@Xk7pH1svS ziYEtipF5KwiozawnssmoHpxva$R?0?YJw@+lg9eEiQmyII1kxFiw z&2N(wi>ft@vyx~@Y?7lv+u1AgyKZ1b8AfXo=4}J2`11N)v9x^16zi@)&OTy&6;k-rw{4y!_8VgK zKZYwxH~Py&hOJ7OnEIq#xRw?$_tkQiQ#mA9@({U}NBI8vXBNlkkIhvodqs_$`(mzH z=lI9BNHdEQrNv=-2S);_VI9hpRFluSx(4pxgsCV-ik7br7msMW%EEqPD=y>kpCW_J?7tvXB%Lt9&Qm1>-(YHbNf&9r>)G z#LHqJU+k-GrKZL;s&Cj;m$0#lQ^f%0t$-{W2pCH7oAGl8UcaJZy^lh z9eEajO%mVt1x^gjM&thgOk5HX3*cpW>L6?Tr+1nfhx-n!hJm$}m?S*5-NX)F5$OLD za2RdwC75ULPD^@5JsAN{$mt7UjG5Lr<1gI<5~wfw=P)EOzrr9+Cp*A&v@kTkgHTIO5UYfT*&|kO zCpZuh^V$sDUx4`v_a0^E5vP|#DhX09eEAUCiG%?g(1@>IBC|zYiEP_W$S-Q%qz2I( zBz<}dDog8LS7RPF!s+1Q$ISd8l0!B`nfwIZI14Z$TI*e>(n-iGb6-nV-fQ{?x;4``aHp@$($)g^$Kk5Cjc*u!1i*k$xD2Qv6x zoHF@mR4sD81@J}2Z(c`o#lWdSKl=r)N1D8m_s~~}>BnzQ9R?{$9V_K~|7_42_XRRT z4P*q^#L4hNTZZvL`XPh(9V#&9awbuyGUNk&pLU7wZ{hnXoGjT=GFam388x6M@J*M5 zda|X8VL?qW$NDsJF0gGXcnAz8F53r=NKJq#Lm>S$((X#R@X15E0JZB0h|hU^kNwgz zRBQZUm@>JT55#y9&)FMu1OE#Ggw|72r%PVS_U3fw}q1x}VYv*m|!l@W#a299f%HgfAsZq_+kSIv&IYl8-iSSHN zqYD+6$;RNExIj9G92=T@CU4TCsRuS3=t5V>1&fq$%BFY0B`JOeT-nWcK{k9Nn;Ky|#6A zt+w?I(zb4{&D&bNK5y&VYQ_5kS2~LIN9LH!rA+vbsq8Lt|gjW zyc)J6B{`CsG3-cc4y(Ids~Ydg2MqDwJe$>>eaK{TFUsm(c#MG&?*{WD^P^9@6AWF$ z9IYhv=nkT|T*TgU(xR9R4?qyNGu424eY6YvTD-Y5|gOkWYh zt+&crk$Yh37oY{p84x;?r+hMlZzzd|JuIj$txJ~SU$wIApvr;`C;u71rs#DMfiJz3 zv7!>)3iF?-OhlQ{OM{~Z_43l4)F96OD4QBonGEEA1+d(px(q{HFkquDg?=&32>nU+ z^gTXxk0mxa1(GmC?W`bIGy88Me`|4wulXzOtYg51`5V+@?5;b1RRL+zW9=GgFrS`Ja; za(ECn+@c zWQAiviJE-Ry7H`DJ57%zzr;a4j}G!bkL0dBRX%2y2awy8oT+WoXXds=Jl z0Z+1b)1W0=A6nAYSzqjLE%Dh8d^LhP&Zz@BF+Ia>NMFpaEvd@ z>6|KK;8B#RHlDZfEK>rqgkUSeY@S&}-4#Z-a!Cb}D<4WlQYM4aHr4mjH!Q=G+4$JA z9NpJPuKJ1^EXkS#EQ<~)x}$E{7n3lq>lV4!V6x>dzBN(nMES{siw197)m1u?4-km3 zd65;V6Nq_2MYN$r$@gv410_#%rteFh!DU66k~XHSbZJi>BE9>YZ`A!*!b3%45(*U4 zvviV=8ZtM?N_?|P+muK*92GN-S;Z0Sw_;xpH%9~hI&!FbCv7{4sgFwB{ z2K1aqAe9Ku7wIMeQeevax!IbTEJN}q-n~lclC$I_Z-gXL>*gCdQb`QoE#|mFjOvY| zr=ABx+f8xqx3EykGOQJ|oE84v^%Jykf%quB7qN=zq{~R{@Gn>t+NEO9&w5R^9U5Uw z22Ykm3L@EsGUPRZu|Ll^&lD0EjA?`+zAJ?sko(2)1uI~P%a9+%&(p%gQl-6 zgIa6+OKI7R>RU9&65<=5X9?*cBxy#7Nx(7I0zHHSfyhFnhiLdMpjgx2Pfo-nzjL?} zBPjBSK4CuY5uyhyf`vU1I1d5}h^aGu%WULs{|n%iepw8@{DI;U!b zTvcrnZ+sOiY);O|V({-*l@-o6zv0Q`xGY#)OrBY{66bEB&-#pcGnbi^=AFfJA-XcY z0iTRR9bPT3ebUfHO1=T&juS5l@7{A|=Cfm{fn4Cwdy zyl-J^T_&>-+7cT3+)c-zol44pM-RDiJ~hG{jp1k-+o5E|$56}8^c^iFzW;a&Q{SVk z0-(*V84AKmXS9O|6;pBNl_C^z19Vw~-TXO9APfG3yAjGvt)g#aDQ*qHjlzsf1$3HoVUJ zR+d|bVGcN&vhU?RQ9?Jaxx#zYR88o1T!W7~SQ}Ou-+T~Xm%J_TT?_Go@-6#Tvw5!R zm7byUdIOM*E4@c?xyefp2{0yQa&@TdXGiv`-U0xW@~ar2b5{vRP#X5(@RV58%~1Wm zVXhqczX{HFj`#GA{U}f$tLumOt{O{rPv>%DuJnqpuczQISNKl7ZOJ#qUF)0pj%AAW zFc1*sI^T*DF||wPgVIn=OQOUd!VFi({(#S-Sof2TuyqoW!t7}9Fh9GZl*SB>PWi&F zbhW1v>AuqS#LSh>XC#&IioX@sx5UDa*rL($s;OR_ilC4~(NY_hA62{${1sL?PU)Jp za#h5W*67M%VbSTsT3!mN_nmpiGA{*^h%1{&&MQcw%;w)!c-s{5f+TWK)w`DQR!+@k z2ehNX_oH_$Y1W=+O?{qq_IZ}J-!d}CPR(NGdEjsM`Z{*cEKcLtK zlhbmh=9yF47nYDb|H1v1jNW!$-fv0M`hPFTsbv?AIG7d><=8>aD>)pCojAYScOImQ z5IQ$P(cQ`tkol4=&i)t(>aHnjU#dph<^0iZ6lqZ;vm%v+k&(*Od1luW*e|>Q;DXtWgX5T8xsov(b)_mCi7;~z z2Qk`Rxt#25x2iVZZw^{U4Jss}()~!H@6&^p$rja`K5Vyd%zKv7$t{1HUf+79t4jiw z#LFuyHTLd%TCc_BmNmAU+VkydzP%EpYv0ScX02ShV@r^=lR0k zw>WwcI{JOf&{%<)3Gq!}{v4PEUf;Lhx8$TuH;))5m993881^hzI(fhgxFjFA@3r?W zqqAh>TFnsiPwn-L*kt)$zQ8y>Kb0*ZEvQv9C17+#qHoX#mdU2leBU=eunaRbyzcwX z2bL+Oho<{}_<`k{(_3E8&vj~Xj+xC)Ps1vQW6GPE;z`a{0>HhWhcjS%ey&CsvH&<6 zH)-oH@^jmMmEVKRgx_0c4$@nDI?;FM?=7Q-ANfW8)klAof3;a1G0beG1AjfdVSS@w50fE{K1lF-2=ne4X^PX{(~jk_me+Zru8YB7bQc% z7XD0K27Jrz%lo6{zCN#H`%eGSlA&(&C4FddTaO9@lKR$vXxY;HYucYIWxc=B{%pzd zee@?wcAugLd#io^&z2=of|fwb8=UvqeW`!34C(z~+FxLBqTR{iHokv3!VK+cTb?;~ za=OmznFL^WMSaVp1z7pxv_pK4$A=Fx!q&*S-W^M5jQ@BSqGt{k4?5tZo ztg}u{?yR$fcgm&)iEq$Yk+`Vq#30AS*{Z$SJtyLsh<~jucB>H{ZS^omr)CN5ggNUw zAPOxuyBi+-y22lYRQ;r)YM9CozL3qSwmK3nvup#!!}!WV=fcnb2&i6Y-{(h z4`JapU(qqvi+zwm^6!VxF#D8Ui11eTFUybgKG47HTan)H^)IW6^j1+O1AvfSDED>_ zu9d-%FnL0Ow25a}nxQpeyj3PjY><=xm#om9h~8aWe1hL6xlVCa5z--+=F|M2{@60- z@Fz6q1e4jDr$o8OH9ekOqC~srHEkfdScLnorbmlvXw2)y<_*rWAl9-a>u-=}$Kr}V$ zh3gI;j^fQDE4DvyPqg#nX})tGTgGZ_UvwvQq9iY3rAs!t1Kz7qc+Kn@2~F-?0$Tde z4I2ysc*N@gJ-%j<{t_@yQ=m7teL9EuJ^( z;o@ydP4SxFt{!YoduZ^;<28d{P)y#3e^Wj9i={D7)rAbv#JYB;>CekQxp&xt7Z)jw zFS@wWxD>gD?Rrs3;Y#L8+(pinxJiiPJ57ICey`~}%g>Vh^!0Bl_w0uL?lqMxzZZu` zc6r(IY`OE^Q^Q>=-X~AX#sb%hjohVd<8A!^MR&GnzV{V0X)C@*y?mP4V^*ObLbGHznGqnFrZ#(G*7;yM%`F|0+|G{eii03qB}{ zTX23=h~p<(sAFe^-LbJE+%aoqgyWODV;sxA6Ya=d7Uf7NiF7Q-)bOEcNa4R^nH+Cr znH?KV4*O1%7H|JVNwGr@_Dr+QevZmFnyfJ#zY%kj*&36`)uqJQe_$F^c&}-QeY+{P z@CG%(-o`f8-vd-U!FD;CE%uWKZLu3y*4`n;tF$fisTrE`5lJ&6vG_N zFn2J_E`~XuVSbiju3?x%80Jw7^TYXy_XiB~LFD>R6y{1N_Gim zAJ8Hk+B7W78%;@tE9lL?nv(73D|r44fYt2xP@t63cX#pWWZFU$Z?kFB zJ?sDe`aN^HU%%%u^QL=Fp@xl*bLA}Jx`vBGB`3xV3!fCNnC4e=g+gc9BoqUhqrU$=@;gzkX3QF$12qiC8x@fs1(*wc*Ux?*yuHD zlk+I+pzIK3^XSm{H4i7xrL!)OfcoDtkIu|un(k&XBKxT_6j$y{E`s!`tQM=CU@v=F zm=a@MXjcm8r-M+j{P^IKciL)z)0fVMkefhc4`m;99g+ z(V`ZID0AOrTx+B69Q#J}?PKp*6jEs(e0$}n!FN_}NO`{KHz_|Y@-DJe?pPFBIq!#?i+-N+ zLearR=F0n0o-2A{$=YX&)~-#7T1MGx z{GPz|0>3}u`uDXdbMN8zlU$=7PMJH1YXgTA-SKcr)ai`$qU-p*jo%0O|FzY1v-2^~ zxTmE=u0#KtrG$A#b47%Nd8{rqtoe~4uACw+Otu|POPJlsLU%0pO73op-R@@4L~nAh z3|a6F_m>##X8wO^l#vLYD7iojZb z?xrwS1orw1dre;7%_l4~A`nmet%N=~y>{<=zO5%Lx0-fm`)nsI!&BbG1h5Xp61kgQ zi~3uQ`nv|*ezoZKGftxL_WWAj=hv2#mK0}2cHdR>V!qPjdnTf$VmvauY(C$C)2!`! z)cELAmXW;`FG@y}u0DtT_3l%a@bDY(-t7EksyE*IaItUphnAtf7f$hUk5azxl%?7_ ze5$K4{TMLLJ8c=S*85hUwhXyyN{-3`dt<0NA1_7KXf`^?{cu8E@_lr(2McPrH!Aq| zqmxq%vY^iAeAA9q+It zM#$dfJWZ*Z$%1{eFXnHS*a^n?NLy*x4zSegN0y7_F$~zmnW}$+?DxuV-{wS1!p%~| zw*Q6GqLjgPQ7oSbJir#j+A%e=GgWC^E=K(q=B(rjH^mI!6-aus5UCZMCs4dqrIrh*`4f%^(8X$ed$0$H|v;@ zpyaHky_Qr$@LOw&)3G5Qg-uznRpy(qR{se@Wcy35daSVxvz#d&&$#$!mXw$0l&o+r zue)IGKr>wUD6ni*!#yvTe?RB32<4t8tk$oVFUomajk3Q!ii5EEJudy-@! z>`jADjoQB`d0yH9tX9$PbzrPAO%AY*vP%R`_v&$OF<7pTNEv+mpAsj*FYU8w5PmC8 zt`4EwL^ZAurLt-^`|IQ`bh`>f^w8~H;l3BoSZ=WQ6dbVo2A#DG?VU-Z&oYyu%R)m! zB>U?Re;69)TYlCOryEsdZu&OzLhm&E?b%=|?>uXn7f~KaTUG{jr}=I;XDJQ0TK!gq z3)89K-_Kcc;y#TU)_LIpwch%CVZCr4{Yl*UfbmRk=$iAEYkV8dTShKn-P4e{ykeIu z7b@s(R$vVju^V$r`RJUn%iX)gs8`4G#DgwP#vOYJQb7)BbMJAoD3v(G)XehGINWH; z#N*}^9Jg_~?ff6DMif@E8($*f_s$)KgFz$D8r-^NbM-PgB<4)M_X0jKI(v2OUjWP!Ng*LBHcJ4jwc zs*@vRFZ@Mrw@`GBMGLf)$t`b#gpUu6ET{4=gwx8f$CuK-ff0?PhowDDCAYE0vZ5{V8PQcD|;WFh4 z=UViU5|zJJnR|jT=7LAHt>1l0o4<7y8jqXnI+v;PPM5iI1JZRH*Beb~V?W`VSDiMt zifd2w$jW2UqbfrlUW|ZSTvV`jaZxGP+O?5UFK}J6HgfLmT)ugqSw<(`6(qgtkydPl zk8z5MvGFs@__$PTi6YlXh}Zk%51(0PhrdFa?N?zPSS-E1@t<3!rOA407Qt3oWo0?7 zc&KJ!GpJB)cHE&cv!urLpIcJ2A{MBkn7qYz(#_3k)78&+9Gdn*Ow+Uix;&k0IK4=B zsg)zR=SPnmTM#{J?04x^DZLs+4;}*g>$u;+UG$CH5z|}q$??PZE$Qr@{2l^ThN+o| z#Wr+4QRg2)|7$m!wanSzIszQC8gGy#*x}u-Ij32T%SqyCYxEPwJ0`55GDx>hwQ<6D zc*9}XgZREhx%BXV9b+#V)^tcedS%!%F-o-OC>_c(ncCL?L^O-sXv*Lm`oVN^nD~AU z8=tRgG0jK8+5}w7CQc2PM$jF+Tj8Cls-08A;i1s95SkbYYd@+j4mJ*o(awSV$A;msPwGN<-?^N|ghJMU02o(HEYz4jMY~YI^d8@97Jc z)U+cIu6W;SVg9wEF~Iz*Vg74i{;P%g&;Gk*d|2uQvwqy)7rvOkTT<0WeG~p}iM955 zN1HK@{Y&W4;*2R{Jzv&IfH|{#CeT%Iy(H-r(15Jz&B=MUqtcRh3!`fzg0E3>>WBqd zjz)dUM24WO&Z%8yB~$rGS=wYWZ*4M}xKu7>Yc-NZdQ7N|d!6*i-yzd~sYkg3^=RM7 z|5}gou2-sV8=)-3cSPrB7~ue-cr7xA%$vngL6Gu#_C=FQ}Fl#N!iY)in# zY~IBQqS@=Xhp;*;$RLq*b#Q z-cY_g2O68zC|I$sw8pyWz!5WcVF(Tf;Ksudol{f7m3yjj$ygr@S&&EtGpIm1Z>5qU zRFFrar;0%5KlR;U3QhIBoNBQqisMP9O<9l^PnVX*|4(S|wE5KcHeaON0aua_&@~4B zKr3teui;22N+`{9e$~PCP}=%(_pUZ`O5q&Jw?b*QF>fV1)s(`QD4(N_wh_~&&p$!U zEHymWR;E*&&F(C}FGr{c^($uI{gamq#bmL+{&25we2w+TerI_!?%&i*pX-m7k+Z_^ zYKTB@sc`00Ku=F#jqYD2lj7K)yBE4x6BKYw=hEH#-;VW`hR1n#@2@Vdoa!43cbsYc zq_)^vR<`ScS@pJHtV1OGTMZkcw;D$H9Xn{_tT4X>7-35&iO`YA=U{+{@di1BRT$uC z--VFSxxJcYnl<$1lusdp47i?*Mh09j4X)Q`4U%t7@z4J@ES2^FsI%n?#aYObq!uu1 zE6R4wK&Nd5ggk<_M+;~2sg}@K-@MS!oL&dXhEUojy-eJ`043~$bedSB?FsVdjQ^*W z!M$w{#5s+&rR(cx8?|$OAv%$#B4bx;sM1&w)j7r5;)ko;4LR$FxymBac2&MsX1SUDUIo(&+RY6)S>H?s%Mcn4CDr()qSg0J?Vr_ z+s3+_!U>(2$z<0gr(qV(9`oDeM^&c{{mo`w*Zhew1a_8Et4-=c`n5Ouk)ULLQF2#xD~ z%%b=j&Dl?%F^0enSC9q?i99_^BtA2A)*tVMuHy=wEDGJw_7XMIwuIR#*tqb(bSS3) zLr;GFBGqQ=Ecy2>q5&EdSq8NVW~6g%VCRdazr;AC`tFPjO)jY!e87R57)ow9nnyg} ztx99+gKB;1qe|yt!ZBL1BqYOuR_JJ0_gG>I>S?qPk5|Y?$adPkK#zN73 z71toHxk_VusnYm4$(z1tAEfURtRbz3P_75D-)cYuM3ShCa6h%t_lKy^w8ZJ8d9yR5 z5*7J6nC$^FIyy8i?HGAOE>lUP@0w`pcn)%rIwV^0qB=%SXXz((yd;*HJc0xP#uWg> zN;nz7H2QW(J;%ffO+6Bjb5T9XHLOi~>Ur_{dg(|S-?v`x8x|8fu@}8J$Ao66xA|7b zgeD}J$mEpCa$y~jiQhoOGqyhL@okFn}uknvoPd3Ef%S|@H>d&3-j-;vJxd&GvaOLa874b^@A?sfHFv|nF8 zXI*V^1kZe(v7yfFQdq(=WpZ1Vo|dp{)&t7Uwz;mx5)J`5Jd))v^RR?PeDy|7y52}O zBU7Tg)OSN%==eT!I%}aZQ-VQqe{a{wdLWlBKSjiQ2-1 zB{VqBfN;!A9NtT|+~W%$5}Kp|;Xb!A`AOW6EkH&Zk$ZOEO~5LUiFv`bjILdU)7PA6 zuOpb%&OT0J%^K?nhMk!J)buQMkPBN&+(c_lZL+9WR`rqO&j@s`lMQ*OJzH2ti!1jC z`zg*&B1CYfvSSfA6(EOvHVH2@q}&D|Z@HE1)Tx9}`5K3WI%bbTdrVB|oa$i$zZ6fR z1l3lk(yq*_G1zg-2`^fNVpxWqRANS72~^YYU1f6Wpzx~UcPI2tBZqE>hM{wXfh;ae0R8WB6)&qRA?I@^P*<3mSUblm%5qR|%rB|dc2 zS9)=L!ew6USdaJz0K`U9lQxlx%s``ay3mJjk{!ak@k zCLV>6^~Z$NHoMbaHqO$xRPZKVk^vN-#vi7J5`1Oo zVj293H-3qP$uRq+%bVZueJ3?^*pP#P>K;KC=&7!^9|M0o)%Uy9&~b&RYldhM|4EzK zG;v1QzT~{H8EzriGNOF8#QA5QY+M(VVOHvG2I38cTtz?NbuAtIVyjq5|IL!b4nc;gjEp$XL@r+91m(g?Iy!2qD^{YSI zk{;^pTW7jaXD~Jmy=(dd-3u#yLx+btt~XvY5H3P@1i5LQOmi`jU@qC*T6Meh*rJN?Vv9O8Ymf7!>0-hZd8HA*>Md*SAT z&iPZk>n_YYxc`;*ZQ&nr>)nf@RW6e_r5XbXqfR3~cay8oVBWh~6+ewGk zhE2bJ7WcFy*ZnSyKk=M{`n@QnF^*ZI+7St{uEw?TF6WFmC40+*Ar6Hc1Y%gI0Q%8{ z1B~H1f(j|2p?{)R>+?r=x2BKu9tN0m4yDV)jFh^{3CVw)G*5_%#zyXK=5feT8xi73 zcGFi!!gc?wZ6mzjCVds_{r&4OmAvB}>3yHyt>$TRJ`$l0L+r1c!rc2)D>V@D*Xu_d0)T|2nSxAsVuC89$FU^Xt`}S738+xT96xoUGrtoR7cRVl^2P%C68fLgCvtW49dy^ z0Br@BEh1|c6y)0YW)|Ow&l%-OKhdL-_fMF|WWK^dE9=$B<`ZGzo>K(&>5jhxB{@g% zX68Z6`AFfzN3@chJjMUxC|mF3|0B$Qd7*=QiJImXUw(-?+nAgGjx*1Y^d7GVGa`a`wcoFE)O<4+#^nNkLpQAW;Ulqs737-o9Fn|lD^*7@YvPL zf!(WJvmeh@4s4h}aH~@}kiI^xvN~NkusTUOuqH-1P!mSk&1scuiGX~F`X5drYLNg9 zR7>y135xfzT*dnoMn5lp)s7>o5}}4F5$QJW;oPH@i2OJuVsWApv3jTyu^zAVYDJl| zIYgPW+p5et60XcyJXo2tI-cK2ln>)KeG+o;jm%<20-N2(aEVZ~t}f8k1aTVDvno63 zwuM&0gia#hlF&*C^kF5}NfV|-SzYaBUAQj-2M|MDAwvy$?14qdERj`NdO{~^$`8}5l znkj5!aj2IwWWJQqms>HsSgCkWZrEzXJsyd0t@khS6Dc6K(%@Bw=-z= zhOv0g#{t23h-Ly1NtpgP0x8EM9>>z+1jM70LD~%=1nSrHejZ0jBo|`gOuAD@1wt`1 z`JfP)O7xyLpS7{5W5JDQl9|)VsOt^yrePW%&-WAfUT>IP%;TwJEC5WP9w(F$)Ue*} zXq7XKFWE4aOT!!@c#n&PR4ZbyEJYbClYYu>PWZl6b;=;eGRR>J@DSwjrd9Ed%~}2g zj^e(Ngf8i*-)AL16{5Bk3q%{SQ0{nF&T%-}35|{0^tPiCk+x*$s_l1iWtCUvj4of2 zGp78m9Q5|w*`RNZfeBD2nIzzD`&-aTB(wYv2~l2@rvb=tt`S_i z6Rb1ETiPbl42w?-_HB&PS z1pVJqcIcr463ce8f?b7uqa&2A!+R9(rkbSAMcfawA@ZJ0>m$%}ZCV z+WsS_GC$m^cq>hjo|;Hya0jd|+O#IQE>gKiQS2VLkN4zsrK?gSJ?1GK5aNXRE))8s zTj?5Ws!4veCayCoT#?B=5gc6WduScXI;w5YGlBy19dQUa5)i zJjw5E=D5z2SbH8*%*|C~P!k12!@~?VN4gRQH7`P zRJz8S*wj&{G&a$@&C`eMI>L*m$0=QR!%dDS006&_6e?XuczzsZFkFcwIWEq8olT`S zY&9o$KFSO@LKM@pADg1~{xu}(`A?LnkBO=HRakZLe+;fJKAoU69?w#`Mk`UC*UZ&g z@v)nfu4m2hozK@KbavdTbe&wlxL`GZwPr}?kxArby%G)fPEsDsRu)dcdpe;Z(fbkE zdB@(reEC{yBv`n)^9Z3jN3o^NC4ua3RKdizI**}ToxAA^nfznaSrcf!Dn8xPmf%0!E9T^-0Bjpl_V5eNKf2Go~59XpjFtMgB zEa-jElIAbJf^tuOZ$(>1`O9Zh-t6jqzZT6y8n}mYyHQRDtmFLUPf7iGz3P!%9FN6IWTIC zYj$+CYxV@D+dF)-;iB3IMlqQ`&ZYOEaT$|0(*>f{h5=LO10YNo|?xTz58pI{30 z93q-qj0msPEa?2L8qSbNSvdJ>y=N~`$r{ zogSbWoeo}}e#5R;%-W5e?_2@2?3fTJb)o>EhoDZBhf4r-F>wk&$FKB{`^x|$*c3n_ zAw+4ISK+0+hKK4EQ0sv9oBnk_{1hmjaXk^e&?LT@<-@ z(PZ9%Fs}u;Fd%tJ(H>NCfDF}98gaD{&0j)OG;PJkTCl+`9OXFovEe$1>M zka;_A*w2dI8}{>}`P|>n#MF z_oqyKN+Eh>O1%cu0}|x`XxI*Or%Uqc5vJp^b$(EJW6+9=Q~E{P-4{q&Ho(}Q|RPWqex3MUoJYRBQ@`rL8&k%WdKyl_@9Jg zkEaTh@OP$`!RuwNdv~)c%!k((xMq7n@1y`0vrT?NmEEEufP`R!XVxnm+bE1lpXOk* zGDPd;{U4+8!jb&^AGFH&PXOw}S6$5iFUL}Kj*7-?aMa7n08NBIkPLVN8Spz~Kyg2o zdXmLmFiVvlTtv9iqws(bgPD<@(|fy2SMx2Mv(PP_YJ_egD?y^#e=d=5u??ehoZY@p z@!MOarxaxKJ9u#+mL{?7$}``e_lKluK^nb3>@6kLiw595@=|qiMdkn+zdWx^^X6}< zF20TD-Frh0e6chFB|j1+KMEy3n#hqD6#c>Vv5KqfLQM$!DF%@Z%98m2202mgB_xiR zVDkT}iwO)?8Z@)nT}EWzPth8;Oi$QVjn=Sb`c1nyk=ea^pRzDP8{#;;D#h{5jBa03 zq|)X3sj}nWP-Wa&qHd|H5QEvMVUE!lQXj#F*+QKqYNFeT5zhDWG@?NS31TPGS6SN} z-cc6G!JFis!EAf*1-5G(3~|meV;wOMakpX-IW$74YI~90X{=3-qcnekLuA+9#9ik# zrSTm4>{--(>$3!oabR!jodm+{y?Ix=#>8PJe$V~D6D;TFx1#H|j>E!gwriPg)bn;U z<#wjE#G==;4k=&y;1dtxO>AW`)5@Bn%^co538lD=omG%AQX0K1yXpE8NSshDCZd zQCTY-tbDPo(Ni19Ud54s&@ijhmoT+xH3V7H88Lgy+CF?`;xqP@DbGBnY7S2XtHrVA zNDmw3+gT(mbmJDaQ#RTh?vYLN#)px7coKD}9jcgZwtK1{(zeb~?H)J!_iwq^NRh z%OW$2C6`l;@{EIG_H$KnDO{>4%8q5RaJUlXE?Btc7HxzQ?Jiwda|?y;^o6V0!L7Q- z@7X|l0oCo=KmGowJ&z}!QWg8-<(ZOqh76&l@QEKQPCT@=NuI1>>JtVQNZD`_n8AK4m{@oieO_waMZ+%m12^ z)V|Sd@^tWj9_2^%vbgq#&7qzn{NGL4M|xRk`$J~U;yK2T*C`bAo~8$Pn11oe# zx!k9wUBiCXYuSNw1@|kt-_2FU|36di9J}47+*!F%xnt~8${oJE;!uZn$Jm=E-ahvB ziMLliJ@LC^iznVa_U?&yS3WthYV1!Z-ckAd#P3#an^;wO=9im_-shU~t4&1-T+8^s znCp#Qn~FZ+TFdnU*96LMQ>zp zD_YBSfbtjSQE-}spp*fpW4SF_gD&l(Y&$#xpStKd?8`{iPiK3Ux| zS*I&id+>?MSjd=s*tGsn6A+VpVp>!vvOrr&+*{$Dpel>CAcYadlMA&2cX9F!8H zlk?f@IgbPu4y)hrUSM**!`$4;C7OU6mg}|3WaScm&(4#E-NgN}Ye1i{&1Fnjblr9) zEPK})W)vz58)ObJVdda$5~ehV^E<;F;aSJ;aCTJ9;eso4U`w`-W|_Gd&X66buaKZ2 zg8|ge0V@Uv5dJT-KZZ&&nDq^6WbFUVezr7t>{R{=*ElXFZU=$3Y&I^k zduT{lR5A?-&kUQ=%QM@Vs4({iCqop)ylg6@Gfi6w&Tln^v@VZF-Rss%+i;cg@dKPry`d--Qpj{7KX8G zrtTJkeWhm3#RcnGzk7_w1DeO0g}>RFGhwiT>Sj7hvf-|Eo=@W-3zHvV?5e^e*6^_mME6?Ye2d1wLB%dJ%l9e zf?AF83GmO;dU;5@ROIJ@mUd`IC(1pF$tFWI+@ef9rAFIMv8!;LNwvMo{S<6WFnH1w zVP8~!V%q9APfjavpO|KbRVmL~wQ(c)Cmr53N?BByrYst}S}CopQA)=uYg402xi+m$ zojZa{$w-e}#I|@Dzv}X>)3)X--fop40L}lGy*H1Js@VR;&*@H1C22BGWT4ZXKnMv5 zWCFsJ?u1D|W*qPe-3c+(*w~3nHWt+(FMV{7vGNmq!j28R?g^^KsyjI{rpDcRfSxH zU^qhLb&KLfDnQpF&_O=hd!%{rm>3#BdFO)TF);_E<3Gid=J2aZqp^VFhl8KW!1W`% zTEt1b+SJPR4qxFtT3EGe61eq0N+B7Y(<074;^ll5IG+Gh#qaLvy7XSC8zZpq0I4N^ zf%V9}ZB!2$_jgo}HY1>vCUoxzI8tzT1Z?VYX9Sd_j{F~vfSJC-?~DMo7igN{F3^;` zJ3v#h=u$>V7c9d6b=Q>qi@y0k(KRL1Hxa>)neqF_zWH~$<~@kw|7q8J2r88*vYMWQ zKwr1&xBp8V{J%$~lK*WE{&%Q!mw`)2j%zOdD-NCkG7)8_;eU5bEEh1F&BapA2g7rn z77VRTlqo?B)=x8jmI2+E~q*kyGP4zS`7 z1{9xDz|{u|qsgbPuQ=^=-vazEoPN4*Cbl_9*mi=j9fbdb+bE5{3y)-65gvK;YhiN6 zabYq~D3tn@{40&HRTFI04F8!%xFhH75vy}Hj@SSNkhDS43P~d*4Y934I5}bch)xL` z?kI#SQp_bIK7{7isu50x1~>p3;4#EC(p#^AH)D>okf9i&+ zcW_Qo=?1^0bNJl*!QVm9I+SsNUhs^Ipo^XRQ}k<0grI7xi1+ z<0k$4c-aql@Ol*g|1G?{V*kJ3)%clvT#tVruVyI0qzrGt|9=ZFuY%kLuM&k`HE z!ORJ4tqK|u9aO8ch!)0W+WV%Ev%v};cIN$(ol7Abv^0V!w zv1j3|dBDf}9pUTw_Va#+_;|kCdB5AKJ>MbTZ$FjiJ3=V&0Q3<(5$%xy+ZtyDAxxK_6@3a^YG8}JnnbKq3Phd|EVPMA9{RvJ4GSNMGe z1mRkCH$KYO6AwfUI8*nb0As&90tLc+JPE)Uwlq%xiVsqI;(@sX8~jQI@rVyldEz5b z0pd5H;tgoTdQjyvG@=A|=$FESbPhS=-mW4F zDcy>Acp#mP@N`iL^`Qm{N(j zhc(u70SWI z4Yb0-g-?y}b-aaJ`WIm>vj|=VKdVCkEI#$^c0y>;!Op#w0HF{4gwXwP1e$sorcI%OqXFpH z2DFd>405}BFrmGs5(0)Sp75K#NMn2NY4^C>aL&ZWhZU|)R=7HO4)hL>!Fm5Ux%Bta zF)c~T#>an6&xx0ff0T~7M(O$g9e@|(<;I((V}AQ*06s^$Z`qhLNaqa!z7g@bmesZy zr(ns{h)b1ibhW@W+&p{m6~hf~nIt`M_hzMrNs{MEbmc;a5R)|gZrWs%l%pZ>r-;7U zdcMviJ$NU1RZ*L~|A~+8ylZh=)Rz6-m+4VS$JC)?W%T-QqQ*PCaHXr<70pZRW(xShEqT|oaY)d{5g=R`jRh7oC&6EcH z&vNr0W=Vb;f0~ejaoFQWJ-;+dntQkGwApP@JUCmj-c3U%w&6V>Fzs$y_s80%{i~*} znj;Oki-3P3A2|o-U|I?NpJ2tigWx|7tuNp7gcNcITkd#58g=LEKT%s(er~=L;$Qj| zju15ob4$7Sl=Rr08u-&swH+m!o|4AhO#_SSc*m#PGReQ}hv`yZ9`cOzm%9-DO=bnh z_vH=G{-+?>pZiZivMj{8v;TF@>dKuZID1S5m4`;`7F@cpR^`1r+-bpi!2fVs$5N^9 zU6>(dZDcdYR|I#KN(0*wH#(=|t8+oL9viCN4VkTLzUi z1nYRDz!cad@Ps1Cm(N)$MdUSV zaCIhhTRdLlg8w)C5`=LdWeB;GN6QPtiH0UGib@H$dZW|~+{cs(Plsv$aFv&WD;$XE_S@Ds zR)hb64n%{G@Jj(4dP<2fD8@?6ANlCp+cv&>wiFs)2&+C-2Ak%8sf=Tm(5aGKeBn$f zF-?oro{p|%&bD6ls?-sE?WTJ>X1^B~E$x&g%iTJm(Z_Ss z3aQ=QsDmq{6#nLlwwNL6u9CyMzXgexvr>BEZW;SZY0jN5%+K9pCM_1{)`2rGN`mt+ zaGe>5#~gsiFpfupl1L%*G(k+_Yb&JmJB9hq*V<~u=(Rjv`kIveFEZTiQL0(d@ws!A zch;niz8l?(|6}x<+^cfp;!_*H^*Uy73^&{&gIj$5^176x)cfD0IsQdj$G=Ltl0Skw z+_*YYgd3V_vtNpSDZN)Cnw`)1;XzO86uJ)UcDW#%@opqJ!(DZ|`KCmiijT#aFLZhU zZkTwfzhTAn0RN>kVkf)0d|}F?_s-G+9eFk_UAA+h$4m)s<2a)^P+jFIJgu*2bFMo${)UnRA>m!A2}sa^)^|3lyP(%*zJs3J3>UXlY$6Xs_?=|Kj(5Z0@}@r&Yr~yyFZsTtp?sSY z={3fH)Wa=&%o|cz%C-AjQms zerwSU%4JH;Z%78eGDSN=7xh{Vm2?%}KvBAA+G-51f0Fj?YOJX4q~QYYcs}4w49Pif zf`6CckI(HwydSjwO=-Yg?rMIs?RW*NSBkYfjVI{e|-(E#h~K!&OG0_M$&aB9yZ~-o6$%EM3F%RHf08cN7J%G!dx!+o8hyvNRustB>X~q*|)7rL>7p?Vj zFG1$-u9ez%fCZ-F2H?<**W&@l2jbTs)6sNXecYbky9PdSetU5b8QjhiI^oV|7;Oms zmlsB&l3to|s02K6u@F`wx~Gv^I|Qc3wle}Xie`jLx+)1xXni-E%%POO^$oDL&0VYV znR^3Gy$H895@(9d6e7*u<&RFBS4x>tZ8=5Z5)7l;<@~2g>G8XL`aqTBy!(Y7*6E0A zh%;8RnYrqsd3g0L3$Pyi(<_D`K zUDyNO9MRq!#&7wb)lzIwZ^XmdEtg6S{gx-LlTu6Qw)#JCn2Bzzr!!^L0J^NTNgb8d z2qao>t0(q%7t#S_@jVFm_vVDT`EK0c9*AM6oVZitp*)arnAgQ(CJsq;#pRUP;STMJ z2ZG7B;~dTryP;OHPc1IMKcf`0_Hlp=Z8_0pyiBC0~rPU&|phP=IC7)ImJ&40iZ z8t5v_a;?-@L1Fz#0ji{F3-`6SUCv9cI3m@6*X_xU9HRd`HovcMdCoJskD%+MjT5gf{HhC{*f=)b{1M$p6oLzm(T35R zrt3c%f=52@IV3!jqVmI4$b8`jDN1(-;d|3%r_ymDS-W9`e6h%92fS&sc+Cc>Ydf84 z$TOLThdkp3v+`dyNTcF2CC3DZ7(7gu?1)Xc#pZT}coK1Kd1j~JRQ|w5sbj}{IPuX` zYKE5aIv`Vc75?8|uzRy#h+)TVG?l-*QEHA$_X%A3zBuHW-*EQ+y+cEu!7C5LW_CIn zJ5vniwQoy(AGNALRy8SD^!#Q{s$A?ymFsqujyV~MQ{a-&+=L%4IcrwZCuhjTbGpgK zy3#SU7%jcaya15#EIG`gc2Oi&OAJ-U1Xh=@PZ;VX#)Eq-&E>x@y;VNz*RwlB%84 zC0RSTOBduxLEaSYBK$VsrwK^WUcmn`fH5@%b)}?fKS)W{4hSeo(f*8tKxF8O-wOcv zHUJ()+$H>~@VYP!_Wd2Uj5yoj{Si$V6*ZW!H}0LdQ+a|AVxtl94x|r*ih6s&AdIwu zoBx2D(fOo8P_$t7ui3`gm--x-<=OIyu<1K&9)a5_AQ+Ih^$HBL#IzU-BuHni>2sYnffxcC5;MR%Gts}lLgo4mzf1V7%NxGyv+2Wk{p>q@ z7lyK}tB{cOEBNctxq>XAtGagyT&?PFm|mE0RQSkE90evcN2-=4MFcOMY{5bKA;$Cu zwDvN7dk}vLzD%Rud_FzAK(8H_+F3iVcc!)?AX)olKr-L`jucaJU;AwBi3uGM*+aVx zzj5R8(+3KMyfFdYwV45(wP$dGcr*&7BuowSb!;D11tR+pHleMH#@=#WKaa9>%EwK)Hd>1W*B0DTEE z>Dy$|Dw%fsXdlm1`DjeYB*4BeV2V8r0jo zmpU+7a|#-dG3<*vA^{r&+2zOD_Z;LXNTEB8YMX zc;uYALl)gea)Bjeg~bcE-xVx)yG@&w3k2!l*;ow!6X4bBAf75k*o9jFr1VzIrvPXs zey^d0R7pLkQJLCFd%0Jp_Drwt+IeVA1%8Bi$TfBFhrP13S9|4X!v+ZHDnDTtAs;?U zl^z1bQ&>pP(FZ+{^cSAjIM9`wj!j_IOxG&p~`TzP0?} z_oe6(cok%g2mPWU*uMo0??ZSII=L9XF(?wyraDcCMyalqEg*;dg><}YWs&q9Ev`cB~&>%PO zW0yKbFa)k(qxtp%&wZ>C3F`+EG=;kN<5&G@~I-v{`8iXVieJ>dL6 z*Adeo*Rq@euGz~5y0*+3?CLgqfU7xTpet*{VAq~W16{iH{ES`FhuV|DNC9&Px(12D zj?bu`_8&;EidMeq1F5I+PF2-j(C?lb=vofYj{@vSfbR~_D@DOogC9=*y8gf~8WsoA z`sxUpZmZNyWqpf}-YTU6>T_Eqoj8NPwN+XxmhyfdO8FtU7P|RCAfeZHmvU z(!Krehmxqi+Rn}2uaSO^OCBv$R3;hoAYXDTp+S?eMkQG4Ybe7u>3Oa8F`?r2f}@*A z9uThLBDwzdf=@S-T2VNQ58W>5nO)FX>N}m|k8hU}#RmS`cB!X$gnzMJN>$s3E$4r3 zmpZBKUoPi~wURN|?$chVDA}TRnHCOkRTS~ZYo#plDZT;!G`23Hg#bE}tm$YB> zBDC))TdJ9#_(-ye!+GfrDIxG@OdeGY-Q}M7xVnamOZ>yRV}}$G2<65}^_fkXau?pX zLn;=(=L0{M`UIXqN*zkL`~Q6jfbu?XmH@|I7esM=9G(S_kwQi!e>t2h7gkZQAQ zrqAZ0?OgS#RG=vX^h#WiF;3&=BR`co1>FD!;;CF&1~VF{aPaK3I!P~X=P%bu_o*L4`l&jp0N=@bq(SQ8_6MpMhClMBowvNedCEyz1`Jq7Wy>R=2m0atWBG zuTZfT2)u#xp8F(Skh25tUP(FCS)I~ha^Y%-L9i0|n+@$tJ z9ew4~xKwKcuC4gEk5I8ysXNS8g90V{r5JSwptX9xr0e0FRhKWnDo$Nv5|g!!>Nxl+ zMx@U3!+oi$8$I5{Gsi}T&28hlFr4H&7$TRq$ z)U~fdusXdnZm~8C8Y04cOrtfV1(4uF0J7T~!9|YpzH&9FvK}{HRDxRXACx+w z(~cjMhKX-*{UIrB?A3Uo;vLWd>Y<$w-2#Gk#Q&qS zP*H>Yl(!U@XqvS`1&)eG?~4%R6ZmfdqH7OH?Gx?Pl&Y#c`3#i+Qm0V^^>nGFw?c*n z{@o!dK|LJ>ZXS{hDINyHx%qu4kd|bSTU+(q!~Q$g+;;N}02ztg#fPP?z3s#}b)`Mz zXHe-)FKBa;ht1vr1R1#r$?KqMW3`AXeQhXm4x5L)?5s>ZVCzZcg+RQEv4SsbiQzHoc`EGOBIsfK^fLF=P~d zRt5;o+~*5rtR{aU^}$Fg`a+r;;k*FIk?5Ar^E%1?jcR#VshXcfih49)KXep*^foU& z3J^B_!BOcIt+TPrM|S236#}?%G1?1Kf?CnG(gu}W!XN%pni!yb*I87uo$vb+^QDoG zcS^WtpTFmnlEk6>m{ST5-g6INU?g<_j3d67(w)-tViTWxOj_?#s*>Y)OudvHR0_Ol z6-<)~CX@;FQbGT}j~nDF6bvqtkbmO#f;wf2yS-rN<}xbhorp;KR^gZ%ouW0Ka7RQt5s9x)ajF;xAnMM(P$iatIzw!#iEz^D%^tfg8V(j)?PW1HYAmMX?+2 z@SQZzuN>VSITB`&QB&H*@~z)V_eEZviy7&ryM_qah=X@!=n)6+@Vyildk#r-vybDF zd)rF^kS<6P)t36y*?i3RQbyP?q*wmx-nJZRRD6q>ulQct9|Q_Gi4xvPe#+mZL1y1r zp~B!R97ka3PtthxZUj#Kg!y|b0?{Wii*81s4+Sa_m_z}t za@UrhlycN+=W9j$<0k2*UxB2EgQDV4I-hX83XaZNt6vB5D_mj5Z~Tbe?A*wZ>taSw|<7A zRnCw9EF~l-A~%jr$`}^)j|M5jqrNoJSB?e!7Av%gux&K)*fY{Zbt$S`a0aYr<=>r= z68r}MD$(@?E}q3~_y(VQRw|5q=}|C;;OQJv3yH7B*B&}6;biUj+HDskoLII}&*{sU zJeeQ5DD{`DReL0PED!uenjhq(O&P(SBEzU+<6Qnlx*~3`UHq%WMDZ)W{5RZQS$q}J<}&~BsuUgSGX-?P-B!56HZ>6do!s{isZVHE z=$4bQX-IHOKQp>g_~<{NU;LHJe@MIWR@Ufi(ugekUmv+!ScSrm3`a*44{}uwHn=uI z>Np^EvLU}rfK(N(l2iGyYmh2W@R;k;$jHi2p@K9(A%{8u_+!F(ia&oH6W#=V=(?0G zuB^R%odm-+9_W(Nx^#~aDjvta#>W6@M0Hds4RQ3}j5btb23W^b@-=RDq4neWUtLl{ z=vR}4idn5q*=KYG@Ix-CcaW9T6l!@BtaHnG=%3P;kw>taC=NHcCinNW+^pBgr}-a$ z0@xs)eiNje!w24!I*Tek`=&H0bOb=R5|7#+%YVEnm5VNJz9n^z`51i-$&~8GrDzLK zQI$posSsy-o>$$HW{NNIz}v{&kIT2g0z0_AMM}W3#@Hgo1%3%c6p~c=%ZyK_s4u)x zRptQsHkVtVMq2sTEz+V+KLd+fsD}#Nl7!qEP=89XP(fWv^)2Zf0-mz!Uk!P1!(F3B~#__Z}GRSbRY5bFcd`HCzf zSg9!v83_}Ab8Ugh)`;m-T`l}u^e#!q7q7bc7fLwJR*fd^Rwc}wpnffu-oc}0y~+dC z>}~O-+HGo9EULb{!DD?{ldAGYZHq4}6ibXA^LQQTmKYKw8y+w{ZN_GWZj)}QfI9^a zB3>|t%CzW%-PbBqib@#EBdZA}2#UwtZM9SiN*IeEYo*Q;-jA{lN4^q&fciz}2`ez` z+AHxThmfGF!YTxS4kK)+>!E~+$xP7LD4q;B7QH8)I=Is4i9d?4qp_coN8trATM0W6 zFQ`26#}L**OC~t=2pbAKVQR3>(WgX7*h2}1K1$euu+Y$33GYSNWblMPL)g-gr^N4r zwo+;FgwaZ;!{7;{mCgo7hLQ)ZbPDEPN*IlF>Z)>;FdFGJ=sn>hQi8xzbRN~P}r^Dz8qm|Bvs_sfWTIm#;x+!6_5(@@T7_D>~R30SIN~g|}uH-=@ zod!o&C5%Qog@!cQQ3A4{l}?id9|)tBP77@P6joZP^MsXFTDmClo>rzPVWpLgot3cC zO3@QmT3MB>#G@;nCZi{;G_tOf5>JgRsWf^%lvXx&R1%a{8a-j9m1RjvywXaQC#R#FUB*o<=DZ zRZ2>JWe5xGZapUEA-`uhcra5ib}&A&9n%*ax!yusr?!<%L70@HQ|Xp%TC{J6kHFfd zpuDdjiD7Hcu{4dybHH0_?N4EOG{G35&Z%^k`X$%-)^;pWweUJW(T??xBtfIhSb$OB z@WYZfI#tKJ1hQ_a^RarMd7kVh&|6aJMDQ|HFA8{yD?~XHkYmQSwc~MK7RWMG9H0YP zf7Q(E{P#fiyU#Ny&(8(1_{2|9D#1s{G-8W031NSNfP+1ofvAXc7^(Akaxg1Wy>-3z zU_1Q1f*WUlGkd zR#~p`5$%~a?CEPQ(O1SA;Zd?@Q-Khf^~5#4usvHCcG(2QAI@Na=_EK<$pyu*{{Ej7 zc@_%0`1lx>CT``WF|2d$k7n5Yprv>q?Niotz}8ueAG`ysi?GrxFb!}OHxF_pn}rAi z6xGHfLd|?HDvlWgl!p~g0Udv!gSS9!Qx$Zg)wB?O zBaX$2C;7HGHaK985+800E#gu<`u#h;A)XEH@D+;D^6fbO)8aM?E&U315Q=kh{|@XS z|7}W^a9b^(-GOxz-{Eg{VA%ol08fW@%`4*HcVJmT)GuvT*|A#oYz)m6InZCu82n|D zqC_^a)L(vwzo%ts*);HqQVcHAg(Q=|{2R0uPlxSQI*gi6>5oKs^6WSHb4>ypEzaT( zC$OG@B;#mhRB8#3ALUgEY)FX-l5nD@B@Ta~rjlBMM{S-0a!=zI8(P zl-XBX_!BBxO$yJ@a)F@L!QF^pV4<2*iPIqs=#-{c2D*%BtPY*1sN-PtuK`zm@$WmA zPt&n>s-J%6^K~paYy+S;Zn<-(pk@;=`Od_*=vbn7iyzamY`;rL?x7Z3+|(yn$GhrT z3f3e@Ns5_{0;yQQ4#NW0L@tv+i-gbTT-LMlE=Pg2hZ7@#afI!Ata}?;+&RR#)Ngp6 zz^2z} zpevw&ggHPX6-=JmHYcP$Ao0B-52u>#O{XP2G=K0{WoKLmZHtH*gwyArL&ir(lXc+Mr5#r4%I@0T-Ao+s4g3i zZ_|KzyNbV@!Swm|@}TggU=91CAk|Xrgrt`0{PIfMsdj9%4suPoisv)l9O#;M3)6{r z3ZTB24xn@Jn_I;%WU#z&J3VquJx*IGVz{M#z%1UQ8%y&C0)3G$u$s^4#vWvLhiZ@u zV)<}4)=y)%;8?yWLLkrLVcpq$zs$=m{1ITnt=(DVKuGD17~ri^+5k?g#)(vjAXuK; z+a|z%dkXf8J(ca`6APbTnOguG1@0Qc`v=OJ+@ungzSqnzbZ6s>yE~o9Mn>9c&Zl8)bhMNA>x2p=X-F1Zmu=UZ0_E`L z7EY2GhVYsKP+x@orN^&|1W0uN(pU|QAc%vEvtKRZ+H98SUwEm76CXD5(KE5v+mOZl zv?N5TamC)}zqR1*LIGh6B*YQC=wEqRHtU2PJoqo2zQDI+Gi}5#zbNX!TniL0s)Q=w z4cRQNv;8AV5)x*PMs#-A+E{w-g-De!GY@jLy{*m?D1Z1HPt0MR!tH`OcBv=^$#0`# z-7R;``3rnP4jY|duY$Kt^*T|`pV=LyVr*2&c>x}W7)8Gn@xwVRHT79OaVWlMtXjaS621#s6&LK8Qh z3csf}>m6bh3?cGKSQ#LCt%4VuB3>Va}A z{e;g3y41h&{(V@g>gnJ3j6P5*cmBfPKt`%G!gj#K_xE9XKYT>msw|=WQXe)v6kp-C z$q+q@F<2@w8**J5Yw!02F4dohAD`8iCB#`Fe5|BpnaYCYMpU|}GRUiK@r`|1atLKL z{ZzQ45^~r~#eV3^CTmYzY{7$-Fj`~COOWL-I$>P+q}Jgi@Rt|)#C{k~eSYC<`mt!0 z!;jbYW9Or67zm{GP>nj2C98JPEWW)z)2e>G$WQcV>A^}1I-%G1LDZpHVfidGNr_yJ zId%)?7l$&(M%aD_gJJGPT7<2qnNP`Q&r|!uZFPpQ+Kc&Ylo+oN(E#Gzd%lHZKFX== zY;a+rW;Hg2@%xSJnF1RU)|HbRY`AT6+C7`sM-SP&IgMcl8gFzztqvO|YUHjU3XEa( z4y+W`M@yUE!7Y04jui7Yl?yxGIM2fhSfaG%4>!Mhk@qfOsd?uww(w6!8uRug2xB|l zaOcp-X)V7H^=-W0uw&zOch1IJux}@UbXeyUv@>kp$=@nqg~5kW9Lp&y;c7O9^GgLR z(zgzgZ*gNXi{`pQHp$cLg(lwere73)vyf@JDRl4$jo@VMGJr;>K_BR~cl!4q`u0R2 zdr4!ZnTBQ^Ol30$FnxseJJdW`h?4(?|9Ph(+zK;bBx@ZHx6OpnvKemP_*qa zwC8^t!a8X_MMS9O!0&s?+jGr5EHh!VQfS)BL}QE`jqPUaxkOicOBI;f^M~$X9U|>Y z1o#v@rP|Y8F1|HxrKHrrEAL_L!rw!>M!5RB!pq20-PoS*zK6vG+u9T?(8utz_b`3* zfj_Y+iJKEjItp`f@yivYF(KOrxt=&Y zWCs?kuBulBS1&$rII_j^PWM8&+0Ng%mz~kncxx*yi{VR0uuRSSh%kj2U5!<-wFgG9 zZK7s9Vm6G#YmkNxe90)5r~32^-!qDB*KF}-t!s?o<)fKi_14dP<7hTM%}M}_y590N zIC1=;Oc5Tp6jFD_0zXAzk5^VI$z#}xp!MfkIK|QAS9Ol>AH!aWdLD5!DV9QeErl*j zn#I%S_>8fvN7M{&S{XK65|v#lmF~+`o-h=7r~`&!M73(Y%aNa2<}hpdm*d!IRn{4vIG&~Jti}d^S&fCy zXV@<*#!}-PSetl3)#xvGH2d?%#*=Jz_{66F32QaeFS6PI+QhAwEVz$rZ1t6*rQj=r;Yw{r(5oAp(bMr-}>fwAkRm^{@z+A$~pJ9YNX#e4j!5 z+xWlEp_TWbb*Hi9BgFwbjC|^S=uzPefB8OE9c2WeE_7qFsRMuM={Fm1w~S4!;RW}z zjFSC7x9|Z-7u#9t1K~VDLVq!Qq*|9D3el$uH4$Be+}d)LOcl~NZnS9O>0zmNV=Djg zObf4!6mniv8}jg4_FNtAWu!b+kj4_=8(<8;@*K9Dc*T|@-i_;(_mLN%Sgu#JzY|C# zZZc?u8tR`<@Y{)Bs@Y%0rudiz;ad64VlD6d0MnwJ99c5YB#;Y|9pVO<+iDUvM={$zksZhL}Y~^AQW0rB!}Qd zKl7mvvK~RhfyPo5uFcp1PyOZml?PdL$v=Rb?ge)V;0OaZK;AP#7zZ#)3y310!<0i5 zY4%cNj_NK&9`v@_F$$}Ca&{(6-j zccpn)vZ^QnoEL#fFwRB?GKYCcI}@)RfsNyAH}Oq6k!T?&xd_|MQ~c3~S-o})@S@eZ zv1rg88C8fl!fEm{K5-(O5_Qk177q2>X1L-|0Y3uQ9G8K`GraB*|1!|#{`dV#&itWKQ{6CCYB!Oq<#N? z(wI+8EH%l2%BeBBCigZ|s=@Ufy80FXLr~$x#0ZkSs3z@JLf)BKrC{kh(BA*@{*M1o6LH7ESj%_^>h{#zju$jx818`jIe#QoS!IW z8I0zrVa5=ynamPN;*mgo5}5bK?*KXl$G)ORqYPP@vM^4JUdj;96ZydNMUz>2iE};@ zzoSHT{s|I`jVMTfGVtFssKRZJfCP7GA7}d(XN2JK<7P}-$pb$AcbWQK|=eT2){87I5+IA|zN9gu^wZVM_% zeiA@hCqud@Yy{GG@51&rB+WsvG-=JBo#MTxu-I4{rR%UWj;SYity+Ci3plzEVcciM z{Lv|_19J+Pv0uK(S4?3KGv|Bv8(e%Fzcz*S6iqy1D(f>4TG1$l%CR;-NWaTia}ev3 z)G`3p1juJ2*5AaZG^iV{y0?{JI1nqiet-Tengou+axs4X)$d?rqeoRmebNpMbQE|8m5gIoZN* zFW9x2oEB-VO+7>EUk-W+lZ>5LPGfqpi0_%kTpBy+B&40eIJtj1oBoiUw7^DFkh~2p z0|Ji2gYNbiFwd}sQ zaJ`XFoXKK*><%G`FPO(XkKRBCZ zL;>#zTOs9{tnX3*!!;P zB~(1CoTQAlyqWC;N`Q??GBHIn6ZnYmiktsb>Xbq6_2qOL^ub= z%wk0=1f(T8VXjPp6I|zLDs(WD50%}hszLym7mU*n7kG;y#ndd*j zUQ=~w;3uA7>Fv-3k+y1(SFoh;;3wH%{Ol@W#hAvb6h7}s)-l?y^AVT&-ZFkQ8PDf^ z0}ub*g3ralIeg2Lv}t*g|Mny^`YE)lGk4)V=d&)Vv}bwId^S{E!rz*sX!?> zd0FkyXW2ecXFatiRi6AYoRWbL_`~`kek8lh1!;1Tu`BQP9P8fI{#lb}J8X83VR`BB zw(JJ(Te~qO@73y*Ja9@hObIB3-88W)U-}%2_p`!tm`-O+qFN5aOAFkH zb(I&23>V`Ca={eRu!ae}C;6#2j)D#6;U1KVbd!C^60yK4XD$jqO4T-Qq z<*;H+W8DU*?boHsZ>rPz>gQQUGLFG(*W8sKc%JoB>3`(XLiSw;D_P;l&`9!v#A91| z!L2Pp5j>=Xv1n^0#+Mm9DS%?FtLEY&o>9WCC9SN0A_M(FfW=rs$LvnV!VS1WWA?PX zI-L);u%oK(Nj$ogy$8R$eWh%es^|wER>rnzkSP$Wf@s^+99~}r>t^x~Tvg7xpd&F7 zju-Q+a%LnOPqZ!dJb$(vQrqfXBz8*K|l*q+DU3-~B?5PFm-e*m)S zBJehOY=_=0pJU3#C3w+lK`q%PzG@MS(Q!ZUpBAyK0W(rw`8&RGF*CPUI$|>>UpR)<=N01UPPK6uoz#r9 z*+v?6B*LGwlwxqj6msOw zH*r(}%$1BxrZtE6p-!ms@@=P|PtF7_3#3s64-B{@Q5@iS@WoQ-T$P92Q z(}WsIU$M2oRgd&l-t@XXIkFp;GDC_`a~{jI#oqX;h8)?2c-pfuB?&bzwB|SDmdIDU z3AzD7&Ep%5J0^`0<~sDkxHaBPCr@H5-X9%v{h94mvGS4WyoRQ^52)T-h6Lh^bUWTJ9e9C1zKmtX?gA^md%xi})n_g;xXO?R zGtko7@A#)kA7MlKE2@X{j@~2WW`PG+tx>yHs5<1ifYU{+mx=JC_ErkL__UopEmGKDA{`N`O$Y zZ96}+oUMpkjtXccS5=oK@2%=9d)PSE)?n_*SH8l!7FtD^x=ulBUy58!5VI!uG@kD! zRG82e!g=?$W(Y1oY;IUFz}42Eo<^iclV>gGs#n>-Ue<}|*TZ0@7Ay-adkS2YKe%g> zDAO9F%M6Lr+Bfsph%RFIQsl9ia(T(CtV;=XdS6|Zyc&gR%>1PxQ+^#`8lbfB(F6ZN z;7{kh)_|K2p`uTbJ^=()(UqR)fGSwo$ur{lZ(2BMw^i7aTZfKzo$xSC<&W-dzoN_v zz#G_!__O?TFQnU9UGwwB@f zAB(Okbch~OfC#Kp^^o7q5crXmEVmnRYiL2XOlBfD1w@maqY3F8M1X(^=`vQDG-S6! z!E+S&@NN|>QgcT@S$gx46|8-U)djZAL2)=cSo?x7$p}-M9L1ew;eqF#Hn;HwMwdFD zb99tV08Nl~3R&{Q2p>Y(&VUn&veZu`?uww_)HU>#i$8^)6DP(%?yHuM)fPZm+Q?eC(pS3xE4H zHYdqC6eH#fz_uWdhz{g%i6$Ms8%SaymCek1uVNXKXfmQ%rLHbdz7JX(j$K!L5BzC& zs^cktxdJdC&8!mW@EXGKU9$d+u+@wAD&V~a;S-2IggR+ptw-M}qfpn6A6UimCQ#>U z%-Kp}e;~BxGGHwNcyLxqASp02Mq5WS0#Zk~iGp&QT-{IPfsI&kc8T zMKo_T!v4f3aHj3?GQlYt=rUCG!3&P6r9~LEpQJ<1Y!qFN{qAk^A-PtdQ5k4F!KyU( zka6I43uljtDZIn$EML{<8$R)MmRtzDom~ShW76AURu>ayiZG6s8G6aURDSjV#3t*{QUw_fPN%imy+ zur~n3Sl*vsdV{5FJXL`yPW9)VS0iF2h(=suuJ+-RRx^D9RZ0jN8}sF(*Kj(QECc9K zlJsW1z}K#3G12Y6f|V0p=(z391q&zz#KwI7B_NbccomAQzmWUF6r-y%2s#BGIKzQ> zlg|KG*%ZLF#)5+Nu&S6ysyJqy|U*qbcG$0~w2#zcWndW&^P zx^i5xOnpF>sfHi%SSo6(rvZccooam$%~|^vd=;n%>-P5NNAQt-r}qjlSD-%EO?Nc+ z_Gn|GD90o2D&na96^JjbR`H}YEHn78_&5dg9wq4as(JAmHeU71asKfd=nAX75X|KQ zzqy9#JJbAM1gmAEUXYW$&DNcB=im-@g(L@os0dM2xE9_(kZ;a9M}NL{EsJ3au`DXS zdo5ek(+O5=Cg9H%7;vyqv|WdT(GB>V<(}emOY)*>A9>u@Jhh6|<3P&oDmFvy%qrqDs+r5rX&QlD&AqvN z<~lZwIp0h)$X{aGTgSSoihOG|>)9DmFNW5sURb68~x=d%(}x z1OZ`b$miK_v-JLy?M+lk`=r&_oHy(J zHoBdwww|wfn?3HGkFXhL^5b!vSY|j$NhLE#*3_Vp^$@F*HZfg@J>?sB4&;oTQuX?N z{MAh?ez@I$U4L)W06fknKu`q10(bPdI~RRqHzRjLV-L9i-kM!ULMe>Fo*!V7#6km{ zqA^HLEe(=qRR!_uo0vZCFTlJ(1^eZPaC*k&LlB{MS_f4cd-CkftY7Cr$bbnj2gW)1 zGzLgXnV1Jd*O&*vp5R}F;f)0WoNs0wN=Q;dw^5J=_2sfgjl2sC9|#oR``n#_<~mO% zYVwHOjg^7&4=SOe2q-53*kt_2cBSI%W$7!(pC0q9M$2auz;jrAF%Y|Pr=Y)st6;=mO938oNeDo*MLp(vOKzsoZ7SD;F=;}E&1sG%T8R)MvKk3b=8T$I!c zJBSL4P?#u0*Jn@*_k&W64FSC5U8phyRau}m1@X1-vaWtgUssxX^RM1zX4PdU@9`c> zE+*M^+)H7-uATg+=%KI?u!#}+dtv{CJfavV|L#rCLps$78KE=?i`dj2-bRf?8j+FG z>&krj?)N;Zm4Z(tJg`o_$5M0(J_cQqT!g0mcrSQQBjnO#N3^gwf_djH*zgW<@}XPU z3|fsS#dV3neD@aCp&Qu7lT#fcCxUz51_TRM=To*CcAOj_&4rRVj)FPpw zXFKbqw!^u$$j-XxJl*67QWjTzfl1{xx6&5s0ZT&=f5*-`b>4r}!!p7dcg+NFZZ){@ zGc0Z1$1ow?kusZf!Th?N%}IBb`uHrB=#U1UEJy@18u5Goixyr?&LE&HVM_5f#Bsw1 zEP{7`ocZ$)K49xq$G+tEZH0f=JxBTctx#+h@SnG`r&PgCKJi0%*IoFM|NbG%3$~Nh zkG4x_3&pgZ_pV{XU@Lf`hIQ%gd;teX97BqGDH^W#L`yo}E~d$Mon9+{))*>pOA=|R z=WNo4@sl+yQWbNQU#nsIsZQdZQ#!5eQx_`#g7y*ZNKr@GusAc2*?4k}HZ-xZEww4W4J$Zx&?SMyL)91YR4we|s zj=L2j7Igqwy3D39KKLWHPnC4klks(L#$8|E$p|h%Mn_ofV>{UE;{Eu9Pkd6ijC%wi z94%vL^@xTk@ugw}*1h4j1<%+Cvs*40WG5?A-TH$6iFnP&pu$67%?VgMblwHuqKSuj(Jt0o75;hcnq4?5 zp<4e1|M*k(WDx3&wOzzWQFbeNsmec^&)LoV_+NIjq-@2#lKjbOFQ$slyCA24F_qM6 zfl-T^@uYS&h_Oj8P6$5G8b>?R5&rU~UBVc00B33ba4m0x?_Oe_JZl4tF1}t#k zTd;pG%ev>S@7-LlNZfGS8wi_E7>5##WVq>??znx-^Zm;-1mPUm&A>qvG5=* zlBh){EH*2OYKuN&kBj1TetaLx@BGD)7H-5;NE=Snm2(eaLn=V1i4kItKq0ildAI(0 zQ7rGXpLJ3d9pXj%VIaQm5MQyMeXn}z2*5y17j+nfNxT@qr926ic8E#a!lTMl6J_Td9O z>YyT#iVm_2pQZyO=ytM5-tR&H3pFP6%hp7P2b2*ep#ud)uV?Jl8QND<;dUEv`0W_$K`{?ni*mgVM zhP~o*_PEpzX{*e&0bhU+L3k{v`QnBqEF)LD=a6&{t`@)lw~>A@vZyF#HSNb z4@uGxM+?U@tud`N?|mS4jL@CLr^8rV9X|9p)N^X-2Gq~N*N*-#(nVj+^3UuTOtIwwC30~0*@ z9!W8{iW@|E&D!!bX|HOP@T?-!7Vd=iTh`)je@pJycpTMvq|L#xL9Rn}mCM&_emv6G9 zNRZY7vq-DVtwDF&-~e!wJ*l(O7Q|xkOsg|U$s3|;Dg;VtP@$_qm%#781(muhfASW~ z4;*SIvWDA^U`CALb+=ft%3Z^gZ?jI()(hSIX8+RDf3|C;@8;j~17?#SgaxR6#H{zhb2e zelE7=ycOE~>dxQ<`EqZ1xidIN?*xWj>I_bVtAg+a_YK>H!BcG|sfW z&1KlNTJ+UB*Ol(75x3~-cKsx74s}XUh8r>d4G2!B6Gi~NNGE#pYU#w95)WTS@zNX2 z9*pWUWl~4tE4Z}6nw+I3tyR+G(KwD5qK6vf*EwGCg0Rv9d6y%zUYn zJb>yb(mW_@b3*z88G0K|pF3ZI-a?oP51?%pWLQ{mfxjAj%P3>T?}u@48}z|j-#|NV zv|+$E_tl2SMEk!&7i3YGv>D~Yd1=x2M*I$AMGMMSy+TELkz{h9t~p#%4|L{Jg!RWs zy(o}78VIkXtj5Hx4-h5z*Bl^5B?8+yCh~LW;e9=33^HdAS^zpE1&S&8d$CqL8VP&> zBZ3`wONRdOu5=4F9j6BXO89AB)?0?FPmG`gfnq9K1thtRt?3jTB&?=+|EGp!TnXF> zrDIX3=|=A}chG_$0j(~7Jh6@T1c|`_@>GzxG2FwGWNm^?L#75q4Bi)>^uvOHFSd132Saul&2W#5o4D}3qljcQ@r@!1 zdN_@G2qCa)wx$f~7a|r3ZIT_-t z*^)`2p&}b?7KRFV6LDm!RzoJ0g^D}mS5DANp&~EB*^m~XzR)K?9W_uYh&0_nKBSfv z<2YxMQh~Fq7?NoQ^UhFdC-*gXtF>d^@CgNN;7Iz8hPflkV!K}Et=Zg?tImd+>-+Wv z1@~OHG`w3Z<>4;u+z3j8e`kcapVHx;58J>WI6JMR!@ZqW z^c005+#>gY7VCP7Ir8;-N(mFCQSC_o7JpOW2f5}q_JgEH!^HTIbIp7lB)MZ=qHn@P zKfoFlF5Gg}33@eLm~|QSUAP!1|6E5&5n{Z2sGjCTh`e}AbEw;8gZKf<{v3!WlY+e` z=!FPjin_b5lb*voNsx5$?SFGUeG?(Z^v8lFxht%FRo>Nqpn;(8d|JUsU@s#-SSTkW zzXR4lcSef5qVE83(a5nK>mSy2u<~r-z|ewTDEt6!aBj#+?$@v&$*nt=p>oa$4PFR7;URqux)`j^OtXgQUqzk#EQEO00gX z)ubLl$MHiDrW0v~N@>UnPcN_ zIUPXH1`r2O1{dWaW!$emFv)Fqq|qm_Vt{O~r=U2ITmI3DF#nkw06{5yG@y@Wd2T(@ zUO-LD{r~mVxP%tJhYEs`+pr=g-MB98!&|<^kMKn?&W?Cbr^G8 zNMqXc0m|@szU;8nz|bGM?u&?D2GDq(8AWxbe)LwH=+C4q%q^KR>3Wr$W!}MWP%u&7zT{)g-R||`UA7bau5d7LsJt#%BRzP z38G*44M3{D22kCfjwXl!X}2OVvU#973IA`l+ET{i|52T#V@&ZtJd7}R@9U0i@+FAv z^2_zKBT?*;A39cVP7*=7ej9=4-IJyrW5>V=@`PdHs(y!`1zKVts$~;RPZslachMWk zqAZjtIuj6!)RzYL5+h6UyBgwM#SKkEL%_EJ-n*$VG_HQ$HyNbe^G;f(%8K-xpch?& zixz{b(F>r;i@n4cxwVdd?}cr3rjAU##o!oT4$$&P^}qz2!49KnrKXlI5>C=;JA*!8|}E790VNedP{kHq_k8S)IU~WgM~@QzFGywx~pHEJ(p5b z#m%}Uv^Z7Fl0Q36r&7^eEd7}(63|DSK}<^d2DmhR0=6ky1SnkQE>fZ@T$|2#+9$vwj;A&=*bDGfJognbm#!#B|)kCoG=ALXtdQn$KPXxE00#EVUx!nrvqssKXe9XVu~x$^6A?&krz4@2^zd$GlzaD8q9rm6}uu^UDNPg7Gouv5976 zO{#hkJ|t|HF#vUV_CQriU`dy$euP^%Pq+aU7?BR51IgG&-3z@9r}qG%Y&H9i-`JIB zu=i03dCbl)ETvyFglW`W$m0R(N(QU%0ywT0gz@u$x`8uPn$*+ii-EJ?zRl~&4#!6- zaMR2bBhz?hc@&0PlloFu!A3aPFtlbA47C`jK2!V$k@j}=5&g=UKy){5X*Q`#y6Q01 z=7ID<9mQx+FG?6WcIcD8`r^m@t&XeJq}u;mCy$pJSF=e~=WzU>&LRwa2kJ0>u(}5* zte!;ryC6cFpfDTNSKI~veO!uJ-Z1y7j|$7^Kwt3~?6wQD#LUp!!4Ghjy=ExYW{KxQ zfzMikwI#oPx>kG44l^4iCd)(f^Z< zr=F4CefMb(vJ}WVDG#Fttg#U=Tr5z}w)qHC=dE)LqjLkqfbj8JZjzaUP!!t>C^cL3 z(t8%!sVG~FPws;m``I!`<#>P)so+Rr`-)iiV56RDvqe_UO@FIiX&j-x1Dt^n(QJWF zCl|z?@>UlYs^`!zxR9E zIu{^fpLt^{hp8)Ze_SqG3YNoOA{TRTd+{Kw8_HolVThEVb#D39cMKaEkol*txokLH zA1Hd2Ytdp@=fX42)h7IR*41N(gS!*cc@7}xVLfO-^L9*a45oRoL9Z@A9uI3;*MDwj zDt_Zg(&nHEwi2blvl7e=T)^_ib)~l%hHHAxkppOVjtG-KI8uKgM-0$~dRWA~KMi7r zI{I=D&ae+W6qGAcq4CMg6@{|dL#4SQH|0Bz-_7m@>=59dx!R<{@gvy%%sFYz+N1PB zuE@+>c0?0Gn_qg4@ys!aoe;Qe9ln9&dZ%QGr zJGev$z;IyMWyw;|4kB?*kvy}v(VQXT#t|M1Lc;JK;{CG$I-+i&7)#k%Mi1)XosPfX zkbf0eAA`w!s%(_HPG3Y9hlpj-o-^<%@UM29yLPD5q2$q$Jdq#u9WaPn#?{!vt()Ma zohLFP@evDe!vD%X$*?%mK+act22e!4m>kuBij1QEiZNVqRlX>Sip4lwfPYPhr2sck zbL0_vGhd8}LWA*$qWfQ;KpQnIF?A!u(>00@RB||8#Kp+mN6o7#6-_iI2(H7(JwZwjalfcUa;M>ci)GWJ>Miq)2 z2(p$HibOEeYpOeQ6gU_r?^SBiZKD+L`!h}1gp41C%<#JzNT12 z$?}-P^>w4gjdFnZQ%R71oUqCjhwI0V6Pp7fJl|nr`-8U&0k@tg3pzVNEECR4`X273 ztqR?FlXymWB;3(XGzC%c&0xGeopP_O`yD|v{AQ8f1NFnqT=&zGU|M*yQ00dYQ0L9K z6iX5foGA9n5juK*qIe?r16;#gkdCrn-wn9nv!NtovHu~Ek2K5uw@?NWA!j3`D&Iqz zbc>k4^}oGE+#T{R*H44g$W9Y)6-i-l;F~WkEP*+=jaJ<%?h%&{RKaC(Spc28RorcU z4<%Uf;)0pJyF{;E401$$AMS{%#tb%bYsnHzmO8RV(1P0_yUCzOZxfROxFb4$n;40N z%t@HZ%k;n`(OX8dPfilXOqQ5+tB^AxDNT>D9um;saFewq5=<#!C6i9=lY}{p(>A4B z4{nj5f1vze{4{rzK{lEcAnk;$`^*pA7Yc%3}fkW|N`+BgAJqh|A>bkTZ@PF^2 zh9c_N$3YfY^u@bfrW~+cj??4z(~`*|xo2%CKG~r;-o54^?Vc=(5iX4qIAZWG z9v-K)y@xt9$T6veAGVt|vExCA+RtJh_~82pV}II**w@hSH9@rVnxwnf1S<=UL-osa zI&grK7bQPjpw{2T|2s(T(GOTON{92xgQZFr3wEVq%$3*^KpP}=q_EHN-OUYqkA}~ zf$&cPAtzD}4*nK`6EKrlttBt}Fc^ zq=Wm=(%Y<&sz*zYv=ppI23R(K2QC=DOcTAs`{GsyUd*dlv(&c65%kG4VZ1#Di35=s zS&T$$s%rXd@wG?M40sZMclvO32flOA;=Toghk=XL((R>@Y9+kb9!A~>V+@v2mGb4QwBIokhtvH%1r>?rT9Qhw2zX18*l)Qx{ zUHQeS^@pd6yLEE^8Vb1^Y=^0aa_<(|!*|qnhey%aLxge%IEZ-q%k*MIkmJCduRk;D zj4%EnlxxSCJ*9g%&5`uv-NHKb47%#36YR>&akYTQ&hxlFcDpdY1f@?4w%XUY%S1yf zmkxRoJyX3L_SSdhFKjWa{=ZK`7uPC;i#3fsa}oHkjb=$2U`Pu^Zl8)u39S43CAb`<<%mgpTl2!np*Tp%W;7gUvKL5`qcn=tfnf|GI1tc+3vo1$p2O&H~o zPtz2eFv*VnwALoZ2_2TLW%?6h$|LLMt_Xu~NrWbuQUk+AHJuQd+jo%gU zj!FeFU-*Y_GLMK45^F_l{kS90?+yfKUjY8)D*odtKk1Iv6gs&?82csfMZ7x* zj$Al`{Ps$5?l?>xs{$M0F`bUeOopG7QYn6^7%A&qG-aun6FL|u%d$utoRi*KDlB~Z z1-difn$^uKw`d%0FZW!?XS;nq95BX^5dUWl;v}#GL>8LoRt&~eHK#YiB0vL|Ondlw$ z)jqyiXy>P=era*X`j;gw*>c?{EU;2bMO*f$xs8l==Se0rH1 zO%#5wn2Nxt^X~;R?x=t6UXdp2CeR0~#IFI~Iju_l$<-o27p_G|^V<%|th)d5ez7*5 z)fuaFS!zA(jW9o6I}~0u#td4zMhqw{2No?4g7+5?pZCUa47)Cu@moLtrgk9jBIvO8ckR$ zZk#r(tFW#%O}z%24lejPmL12KhoQsDdA~xS0EV#Hm;u|rSTnE6ulfKtvjgm&x1uJv z;1&GFYI}C0>|Xqy@FZPYD@sE#i5f6=YX(hUC$h?cq*{WpDT7%+^D=ZA^M`K;A7u=+ z72fllejMor;h4m)NWTfI1v_ZQTX&7_7$pT?Y=!+8)=ev~Ys*yKU1j<5Ys+MN(m)s; z2AY501GW(MX1WgFWcGT7lRfDl5QBmd-=BOIe^ttsV4~kfw?nRoqUfe$5Os(G|;%t<( z-1?JmvVW}LpRm-I-h;g*SW$LGV~UhUpRN}}bsH$MTs#ua%OJ~4(wLa^TiD zQXHZhxl3-|JZIH1w$h+?y7Hy1K7_~qiY*T zPgaTs-7LDJN-SaZ8d|O$Oed>^!T;4%mPc2s#0~zhiuPgkB@YQzr`ty#ZxE@;-yHT) zFQ9rE_7Ic!{Y5Ot1&@^$S|7eqoY3{~CSgK)Wg-NLoJ}7-EUbNIqRz{EN-58m>p{b}a({Gza-##90 z)s9g<~tUig%` zWT^nYW${n!#`ihjab|vh27Jj#JIH;*I~@_-YgCaNw*h5%3~ibeI@Y}s<8|z&3#up_ zr=VL?+aPrp>McPz1HvanOHu*1bs5@OJi=b^GcFhG!@FXaKZ*@Vp6BoOp+?+b7CtJz zkM~I61NbSp2mgiZ9-v@)vS@q#lE=h)MD(Q}c8cWi+jjj|@b?{B99Y;Ru}2c{fvs#> z5lN124G&KUa-q7EPSbXY(vV~LZ9{}6*y6ppOQ^#0u}M;Y%Ppc=yTyHRyo0{KKlS!^ zn*$o~xNKzO%;Jvs^XS5EQK_3ui%GmJ57|xT$Hi^JSqF5m*9@+&dK?U;dBx67ir_~J zwjf3kDDD*GPQ*kU0?#QT9FzWq7HxZ7`0}o|yop zb{Z;*)JFX*KHr_DTZ{g`XC~4xX*P$Xl@a(YwHdYFU>cmQE`Qxj{BAUi($aCrI9-kY z-{AZ_4vXY}oueASb;o;w;PKZzu=uLwGzgBmjm#woOR8b9Yd>E<{z(z1i{eTg8Ju54 zV4Bd+Mk}5Yl_51q=kF3*J>s~A>7p>z5O;$zpf=-F1tLW66>K#;aW700xSjoo`t=%S z0iD0FSM-z1;^^#NF+b#)uC`!(K53u$0TG-4#a-uVtV?9eZ||g4E^%|P)*DK^MUjMsGe5}J4uw{d-{!EP+tCNp9DP_NSejvu`e~Rz#K|#8sII}yMe?GdO>#OhF zFT!=Qq@(ZyB2I49QJ({%f3%l*DCW+YXJk`906*t|$j;w9A29^+)-}ZP<{R;7Ivmjk zRfE9uq-3s;c48Sk{JTl#h^n!GUkr0hN}Nyc91y0Ym4B=blRq{zw& z$~-7;NdYk#9xEQ_i1}0d&JN zA~9^)Ae9GJYJ!nYL@q6TMwk=~PR8KQ&!auhh>xQ^`HLU{lVU?FLiqHB?0pDT9unE* zYai{TiV#bKZHc90RJwF!J1$C!WGNW+ptRh8CqY38JuMiU9khVQRt#}WD<1IU2LR*H z@qvh3b>DjF(7yFL{K@#!<1Y|@L5Fq&ATTq|jR@YdW}UQC2M&FslPUDIp^;fmX7{dC(w7#E^Sn? z=F8ua+l@Q?;793{8+aPMoI2gWQx6XhYO_g)#mHn2kAD@`qaC8)(HNIQTQfY~xQyI~ z#U%N|Wz>0Cj5jwfLjeAXx(2_9xLFesV~cqV;P-gX>cYAM+|Y_=1%k};%0(j+0Y_eX zRy-}7zzp|W4n56%PPhV`6RPzTdPLk6;9T@P(vFA+f<2CGO9znY!V!@X?vdDTI~O8k zM77_(xIX15blA9~+~pBDNjvxYpb3J}4Jyo%VlVdf`6eF+Ftu<5@Q5^BY5kiX+-QV{ z??SdlGyV9y$V*DZbi2CZCb4>~JFxz_fmHN@7#Z(LL`eIDf5GOVIa7^)7m?zM`>NG= zl;s7H8-L>t9P0=+1|HI>lVVP?lvZle)8{XU0b?gYNy^*o5GIi)v^&xtmd-pGwq-M5 zq|WS~9o9?W=A1Qn3DMQ2S5JKdULF@q7ru{x4!tNwj`k#+uyn+~V(EB7>ZwXDE1<~$ z6k|J9Huq7xZK~mc*m2@F-*IM-6JX4@8ozB|Tp+si{?@M0`!9;Vex2?C*z3J0@~obU zratOx*nr&xmI-RK!J^vGd?8fQHVnFZaq|cM?d<}Tdoc`L*}ca^|K58Z@!uTUFxpn! zHcUW539DTCS%9m==y9wO-s1TM-0sLI6&*d;g2F>b^zlsNF%A z>P1@5CeG@iWzh~wIU(i;I}gA-a`rLWaYE!5+5s{vnsGc{{+3x~2ts&Yb4(ybH>Th_ z7>xQJkPi8T)Zt5z8hpc~HNN|$f?41;Pl!1wf1*AMOJ)V*()Op1Y55fe(L+LU0bJBX zl?~z!4&W5)zI>?u%LZ{q2lbnDIeJy_Z8tnaWb|>Co<$n-b{dCXo?qMkcqU15WX+n%O&|Uz)_j zDLly1jU^|lbfG78P04C2vYv-a0Ym=B7TVJ+UX$UtKD|ZU6UxKY7<>yPT`ialJrZUk z7Wt1Y!Y+Tai6*@c6V;bDQRnL-Gdc>H%e2XfbzcdTBCVB4cq!r6u{(uYUgP93l!^d!p z<0x;4{%_kDFv8iirl@;f#-vci^6>bOU-SXyBk1Pj5-R$as5D_E@eVRe(;Sl=N2G?8 z#i?oyob8z&TkaauQMsAg{{@@hd7Ekc+oD+haSQEu8w&STTd4VMVTyYUj4zuL@GVaB zF~d!+42ErQi$A=3WOq1+~>a|%)x=kKd>x;=Ds8H%H#0y z@6uEix30-RR;{AdU{tTZgi8?sWSa6icm}S-jaGoouW=bwS6BWSpjvLU|Btq(I%sl%70&gi&|bK|J>hPuz!TDT1Erl5BO*NAuv;sUT56!B zCq-6t3d(+_F=S9!RE<=dTMTsgq=BV`QQ`8{2}N zUyK^@OmJrdmEIMZY5u_^xOD;&G*}T0M){3(mJVR7mnH?O=L`nA_^ue#2P3&$HO<;k z2o(w!=Acb1%Q7Mp!e`4mu{jcuPBc01kA}=-y9h*RV{7FqPbo%f@MHZT-Z!> z*eeF59Yv@9tr6$`6;&DlI&Y6pcKChgo>Kr=`H^7)h%?5RMpc1WJQ+c;9bIQzMHxI<|pA zPmAU9i<@ZuX$b8P(wYfS20e%q7r>hW0IQr!w7PTk3t1@8>lDf<^>l2Y@T8ySsf7V}7!0mKX zlhXHOi3UKT>OK)eh#J_5zIs7=6sYgD^|ge6 zD~mBS$a+uLpVO(&qdxG#b6K{mxe{bq(`N5S<(~>`(KlElZtQXHKu*|-80wfP1OUPem>=r=^E?b~g4lV^JIr+UGst#5T&=oh5CwlO`bK!@?~Pe= zXw>H-qa+6OtrDI`z)*kRO#{`{+#pun2tdssX%ha2pz-Y{O9793$KM)iYZ^=kKNsl% zo>Ew>y#KlA&Di9n%b!CU4tDqpoN=Q!QsEaO6K~(yzYx)}mq0quWE41Em^Mmge$ZtW zZT><`(4C==zYxX!G)Q#Ch3aqU`A$H?&({4E=!ei+DZ@0@G3hp>1GS3(1JeMlg4Hk- z3!Ug5hDw)@`{*b@#-{YJ;0m$+w8rvKiG#P`kkQiHDhssqfk@|55p+sRua*n6PO^~B z29`V(5G$IUfE}A6ihncQY)6O9B!4Lqr)U-JwZqkT$mZfu@eNeu&N0WHisIo~gAqvQ zO9|xZTKS4|{!xY?y#eW-G8r@}-u$aRLJNhxl$L)fvU9Wnw!w&#XXFOSt?Z<| zdP~9CcnD;1HTetU+eXm)Uy2<6&Z@f@t4aVe2Z>5=guXD`@iM4RoOu zwgfc~QB<4Yz`@NU>Gn3MqiPZ$)X?RjiFI zjKeD9xx+{3vu{PdELT$0c~LOR%bWatC^;|d{7Oz2TC||x4;4)1p(#eo5BYqQk4rC; ztP5BI>?)573YfL?G&t_gyFgIyY{6DrQrfeTQCdR%?*3g;kTM8XCrx()f#FklypNjn-cTkEFGTSnsDULi6qE=33Etm$EvzV>qq8By9dU3AEFf zm#}{(#E>~%G08J_(8P2lmF|vE`pNSvXiJ207j^z9<|GvW))qN->wS{6b#gEQ0|62j zf_7{;PwOv>wQ(`X=dHyMHik*+$2bCE7#em3GFEM(;i*}4#qTQ%E8OZ)wC{=-Jz2}L zTf#vBW87EZKMr=t%xyE=fA>FUgCX7w=UNq&?RI$&S@4^+N^G3c1~MxdqE#bqmqULN z{X;!A2zEKr$xb|m@{>3tkBg?US4CEghpz`QDB9M2L2gs1>Z-VjPcayTOA++RRgpeg z`>L=-sEYuW1aZ_a=n7n#r^ykn?tvlPRmA4B0YmuN-$wncGZNa>10*&%W{$25wxFYa zhQsYJ2QBzn{94@kU?(Nuc;swuFMCojz%CD zi*?&-PH1}Fg+_peoxL1 zlk#rH^$plOX#i{IF;p;$o<+BXsSa2f*g5)US8Sqc83Ng7CHnkVk<&wKiMNsoCRg#l zi4pz(N~y6&sRf`K90qO2Pre}>c$SZAhE3ai2)0oEn;25=X*w5)Lnh9hig|S54FW!( z_`AXsr6wV*@ps=4;DwfEwM410NHZWUsXMJKN{v98qr*2Op({;S6{UtEtrbty@qBZ8 zc2|@dgft7%z&dJa#>PQWst$=RyjchK)!%Vzl==sz#dgt`$8m(fMk3u0b`9PiEV~BX zsnf2Dq(`nnCgI$7!;Qb{%bSvF>0sLf%)Jr|1EWjV#BB-AO&hHp=J!T- zr0PO0f|yU909JQ#1!BuZDg*l6gpchNqg18{{K6;We--F3OIRuzqtyWDbOE>1Xn?U+ zhZvpgC|1Jt(xCy+C#jA5X1&p_M{tmpwR;v6R^lEr2 z)%}j6(OKb&q2GQNd9e2!a9!kvJGn=0yTTEv9_T?!u8X`tCm5B>w5+c(s6dWY5$?lT z;>}YxT+UU4fSE@4Bs7{?1C-!yfz%kBi}Q_qspEKQtor62so|4sc(JEY)F0y4v^go# z&hyM^VVpMuDMar&YzO>sq4Jr&?l3-zokr zoP0)E+hXZlrx+HjecfTNH~Dblu^cYOox5Y#0_C*)+FB~oDM|8)wKPqqWQ9AwFh#45 zJ1re2VCmOjr$=>49{c;^QDb`|y{}XHhiZ-S`zgDjYmt@Zdgu1C`n9s6=mMNg%?b3d zUK!TM>A$7Nxz|I2TVab=TUL+hxc_%Qox>4_CX?JXHaP7oFy3REDSLGs4GvJWK=nZF ziUgV!p!70mc@?@im3v(OtdEX^Ljd!krMI=m(~|+pdttG7KyV{kwN0^fd}O0lfy$r& zZ-p(14hJe3258N8+E|2&`TTR;3;*+g%M++YmjjjF&`O5|DFf1-KxXG`+^`R{_Exc5 zob?c;Zi3Xdu0>Yg#{Yz>Fq##lES786Aa;S0ii($llpok98}2qWz15W<6bE49fNwMN zjY%m3&_nL+`6Sxb^>E`G^h^`rwrNeM=X_si8aiF8sZ z1AeyHmF|9*%Yt;c zHd09sB`cI=Y}|R1BY{@;P^^7e*ue|XWa_PcsNlUEO(@)bEcXjntYJG7rJZw8&^FD&#sO=?l@xk5 zP3akg!?+Soe22pUS9%XR9j+A1(LFS_1kq~>B9vR?oHfjlOp7W-ecWvR;PFLX%9H;q<4;0>@Sa$4RcDspAL>y2Hf5xVA5~P@Sgz^To!Q#oCE!5`u8>HKjZB; z5J1NQvpR4FoWXgpEP;oIM;ZaOp~cd{PMhCW$^{HeuL>i*7_0mucgEMd z-V~|kC{XBwdOL9H9Nd{+M;0a<)j{e|y{6HqzIBbV6O}p9zaza2 zreEEESn0C%se=t!|b)noKpL?aPMk+~G{*iVa2_5(=J(s4U+T|02WwpLUR&M}# zEzld(Y3CHu_fndIe?XyXV=p?{OUVlc;qf-v(}Jv2ob5c->zfS9gw8kM9d zd8zLp0Z8C2-_67=+Fia^YOq>U)$(?^ptQ+Il%k9o&jqw*;Md1n41f)`6~GuQn}0y;O`A;D4a!py-tV+NaMJ+LrfL%% zG%CZ=yx?0;zy7zVQnqPQhv6#@^w0}jRI+={y(F8I0X@B4G)uiHNQ$9WlM+L>nv~QY z-ZI<*86X|5QR_^KA;t@2)Kc3G8DLKRIY&)OLWH-{lA*rQ1x7V^sZUJGhyZW3D}&R`LN+M zW~8)(uUnd-bB{@x=M!P-rU z8QA|rh{3TK)ZT#_A@(vM_GKzY-2yW9QF6oonwSbhrg~rmmG)7Z1Lv>6SxQ-bm6CvN z?sI5APl+>5-OxBfH8#Sw3G{~fP2PXZZ(^T#nAc>!vpSki_f@`>M?}}ZkfjXJ1$Yci z8FbF9!0@pV3m4u`$w_y*bOyEJzA+u|!mx~qyCXt6hOOv%0<=b>vARA~)=z0HaoQw< z%2F01c)drvN?Tx(04&u?+bdas&sKwR&_n|sc+6h~pSx7M_d;QTcf9*6Bj}Uw*lgDDoRMTN^-yKAaH6ojkkB$3R zJN9aXI~t($8t36u8zlYP!E79Xh^G0~NffrKyq|v*_W0K=Fl3 z>BvB35MRc7xsCQL`j%5`qbMu~EVx!ySKF5+q$fYy~sS%!1?3`{=Wv%Q>hjWy^ z{<79{edzPQzM4Q8LkB52ky<;(QnPwXHTWawWp@WFCR#E`DG2abB{Ll!q}&waZ+1r) z1q3Cmz=b0;SILP6aIpHq2@Y0DbCFJ4OcQgJf-b1fCD9|f%Df?e6=UjXH)N?lFY2WI zx4@>&@9Hb;6l&>5Wu~8$eFLC4)+{Kt=3kf`XQ3R^`iH9_e|&kn^_MCX%r4kGYfsW z%A@5_PXq50RiwR)gKy%jC3Je2QjqR6z-ogPmxT$qY2&4E2UN@^`=_Ch+J&*L7<{<4sdf$3_v_P4t`+(XCl(c9FXf&Qq z({`sx9g-!0;tQ4ZXeYmLzdt_c(1Fz8Lo?ohX?Gb-ECh3PYzeI`R9fJbUNl@u(ygSa z!?umPKaVLTKcFqSc%~bl(oy>sO*Nsr# z)XASOr1eFLHO*;*Ipy1kn%iy0WRqc{1j|}GCan}Tvlml)k@7W+MB?x=o{dh8QsVmF z`XE?1ZN*~De#@#BO?(BS;q10FF+mPVJuFIJ8g{F4tDMtGTW(dxro3P2qZ?p6Y{5f( z(P%~!yn#aS;#a>ymu|(0v63=xQ|1O%^jAmz1HQpZAKf~7={BWbU|WB+&p+q_enQF- zH%S=<%ke3bz=Zy=jdo8`=EyORQ0FA2pW+&z9uIL$`uHgd>o4NyhTD}vJzUu!c6#@! zr+oB1U1^Srr>AaL?g*_Or0z$O4KUH=Bhh_>ahf@2=M12JlNIwFjf2(k;H1`JVEiuW z6We^61|A%}Q*Rll&O_R#_^t7P`XMSjKdBMkNDhR)1ezV2T{gA@Pe7jTrk+nA1m>JF za!*#$0i~Io+6xgHPd7wOZ6@+G19xa`4A!PxHR356J4G><&-l=O5rg8TuyZ(Z^sN*va$IB3f+`j^3^(q1ltePT$>_YRle%#YW5G@zrj>H z?J$bBR18rcZ^8>Pc%m&7)1QqlwS}!1s4AEmo<4RMw`IMR*{_`yrWNdDDW zgs!y=Wp^ew8#N?3zVPKCn$|In8}%`0RCP0}6??h8J80uw%Gg45e%Y!UroMv0hEIKY zCqty$%GacI|g48m`IvX&R^4agV|;x|qN=YIUI!EbFZ z;`dYdjT?}&7&el-xqLIU=Qy2C;deD4*A}&Pl-dhZ4C-?%83*W7cw~}Cn_6Zr0K4yD zJ6oeJJxiU}1>rB4H`hsDULl^b=7RR|RyYF1x_{hGd#5Rb%b_it1%rQ6^sYUHm=y_5 zTw}3JHWX{c>eB+hb;gejCuZkEz+o>&z#C}k*^ps4%I@!ijUNNL02K_x&BwVb@coyo z5sD@q?XtL;AGkQsRkjIb&!Vik@tVKzTgYg$3{w+%X&`gXKw<9i51dLo@C*m7ovus? zDTX*94HBp^L+G>VO0N9Xd~Y%V|97w$3SL zDb71Hl;)5rUEiO9Rk&N3685jIHgtGvDs2z_ez%g6IfKjK=-!JXrUgf-4QD_2RJTEv zj*sc8kLS#aW-3KtH_S))@~*UW8*P~h`o0v7(V+h`=%<-V;SGFnN{&2r_t*YcDIIX` zJdHHGp{`m@!_}HJoqBSfUnYjKlfTp;g6UYva3FHD`xuDn8&CL%T(yx2QP_eIzraWh z`%Z>Q)dOGSm3Bz@j?JT2XDLa!cLN^wjPm;%M!P>i%N8uKx2siMyT4V|hJS>X_dP)& zHf2N{Ll`TEF)vT+>u zWm4@tin4>Nd2TL^w_|(M%%M4UWs3Y20JAG`@|W}Ij9tkLTh#y!5&)EXO2H#!3Q>qMxPen+XGSCR6E<`2Tw zD}oguE2a|N&jNrljAh6kT2%&NL!_7XqMA~|4ab?EeH<^9D_cWaN2&)LMe2E15iOjp zrD$Ma&K-9u3?1!o0093I#Z5N1MrT^#W_l@ zZYrhB#ZF&LW9LG0{{C)SH5Vu!@gSX=i#;hGq)T(LCHifm%y~*~95XA;aQWt5+ggLv zQzrxeIh<(8JO%zZ3|<>d7v?Exx@mZgTrq`!ZHM4LSe-+3X&$zajVNfoGBm{^tNdc( z2>jiGJ-}y+z<>^c%kR@Ril)z3mdkq|r&IF*%V&6aegR-P-A-fiKkl7&5PSq=0WzpO z@?u!7Ro_Ev7buzK6CU^LRmdC8kB53UBS9^Y0GDDj=%2TmaRJE3VU_*`p^1d` z%*Vz9%{0Fa8vYF6J_ulxwjN;r*y=`cw>9Reht`4D!|aDZR5Kp>UY_-dxDBwU@YVGe zN?oWV&MDmOqi4~<<48Q&g&=mTq`rrA36?s~q5}^a2g~EtHRq~nH6zqzNUNL0bIe3}b!Ylt+N+o^ek^B^kI>D8sXX)pS^#rrH8VF>Mbda4rdwiW?8e)H)) z9I;1`SF?^Q;ZYUiNOdUk!jU(ygS~v>+-J~eQ%#UsGdMu4stHi{-a|o)lmUnkfngQm z@3waW8(3!G!d9ulH1QSk6^!h)-MWsJ?vc5Kx~H~p!3d0Q-+|zQ*Jg%luT;&(h@Jxg zuUH4Gd@S-lXXx3Z*lG$=_aBuS2BHox(G-ky6=tg$Wiq6@9k6_gaX-B(w7}}pslV%k z%zxl79fjEf@f~d+Cb%a+&|$;6jYQgKU5#67WpxkmGZAHf07CK8ch6#%FoH2r&49r` z_+lktsJGTOSdB$ZmIt%loI@I=-ujAPJ|s2yj=$Tr+aKdzU_s0Kav_Yk7b{hf#R2Nz zHv$Wa<>Zr31F=5aML#W8GBf{t&%a(4MDpR;soC1KUXosATRslI@YXIWS^^HgDL}2! zg`ErroNqJk09Kv|evxF?U9^6Ql9J18U-z3)uku{jgH`t~m>2_UX7j)fYZKb!(yMo& z>Dpa%3QhNP$y#r}gU_K|)VW0Y=Mb+A3;6eUBFeFVpQ7LHz)q~{0PE?^cfbu0>W<^G zk$zkXA@$rk3R|WOv^o^E7EXQpVU@A{W&iPK0l!>ykN>RRAJ1n&w7WLiKje+8{G0;# z3Sein+XTa%Wy(a^a1WhYro;zY5>(SRy0A0OFZmGg^B)2YC(xYaU`3+JW z+C$ax?w@AU#^uTj<~L^h(^&xbF`}|H;X6i1DsSkWFmPef9wScmc`982ws!Pv+Oa~3 z8(V~ObC7=!hAlQZ7-o_zz)NtS4Uh_kBCi&D8wP%VKlV1~lNrzP+@~FM<{P>OpxEm# ztWZ|#lB5uI<4eAHUzPF!GjGg%U2^nPLz{Zix_cFK5cEZgK9mmMtEh6oY%01BwmD7r zQt5q4nrsT8hw3MqPz!ApDAD5m1`woc+l z%}*@!EARHhVt{4jEU&9U^y*{yuEmaE3U5c~Cq}HNknX|&KE|B67gFaMrKsQMi271q zB3*%X{bWdrJ**@wLpgz4p9CNC=g|hgteaaLL37tC1wlvAv11_}SPNKd@%!F|bcTNu ze$T@g*5UV7{GNd^ti$p5@Qbu#osyX9ttqo~e1*BHoong%7Q9uX+yfV_SohHrKJa+- zCMwELucV*W0pp6kq__u^G%Hq&!v-@7ZI*x)=$D1ewnXXJ%jY;K z3gT31GRI_hLyI1#inMb=8OaaA?gc_yg!2OwaqTQXk8|IG%Is~$;w=~MzI+xMO`+-! z|DkCQD#^hARSzmzgS};imWJ7ohc%uHLkEfOZ%{WEb$PF!h~h&&0ZWDs)AZ^RbXZbG zryo@A(0h)2N9Og)gJs@(P@9!RbI_6l=4w0?=E0%k?Dzz|{s1d&ZjB*nlS9?*|H0KW zT*{k@xzhyM%>LrsOMn`n6y}gJln1!r;Lu3G1NV{Yf9ffuTrq|tA=zz{qSVu95bIG` zj&*pzPBY7uwDM(WbDV_slH4!r1J#G|{S9^le;=42byVS-cMpFbggA-Ib3XREw{{$O z;|U1Mj;-=E1kgqVMdT6R_W~Zc>iRuvR`-?3ACJ2h$Kd`JS*^vc`ws2wcECUhAy^#B zBzZ$UEpRBKBJmO;FT_efi;d|XQ${a2ls-MN$UM)y(6eC{f~1V*2qZC291j=~f>s2$3`GRM zN+mz)A79|~2NOM3Lz;N^hug@F^!$q$4P@JS<#-sg^}28JE1)-gSTVSKR9B&%4XSWH zy7^eHfYI0bFDR}`F-6^nJPY!0;r4LejBPZ&N=b`ti&E!yWlitOTK@=Da+WSyoyu8= zNql=(*1bFEr7AGe`gq(3k~NG!i!GyF`XF8aLG^-F@y-T8ogszN^(v)z<_BE`_*mp4 zkEd)H+I4}D+JX6;HslK`dI&6RV|QbnzT@N2C+|b3$i27@Vt+m+=`tnB?F^yhsDKMn+IKKv>N;c{qzuShsP;%gK~Qy@EO*d>oVj#&oOaWfYfBEp#&4^0yD}J`}hoc6-B~6AM1Y^7M|{QS2X>&K{1*J&%mp3a@@sM z1jxM$8#Nl+rV(CVR~M{Ae7Tfv*Vg_lBB5GCx*IMVpjC8J@i$vDd)FuaA=&>harZiBacb&1Dq+6)|T~ z!AUzeDMKSXb`;^FpP*QUBZfZTq@+iBbWPFfuUI}8;%#b$BQ`7jdU)quC39H~lNmD#y^1n-xP3ErqXJIztS-wON73K^t27aWg9y z?Zy~N-lFu^JDXKM;w7)zTeQ*8!aV%{7&U^BPJX137bI&o|8*l^GOyI#;W7z>EV(!ZlF!$7mQVWFJ# z_%`JRIe8|vZ(}36GmuztYqoG{NKqLjZHIEzNjGfARS_X!w=2W(?^*xXN86SD!#}*c zlb)I5KT1cVRn5*7kC(yPZztMu8((|0WCHy`$El6%S=n)rw^*1QCDaJ^K)x;jmW7+iw2 zu=(fK4H|KbN5^{^&n&+Bh!Qt2Xu6*(wP15_RBnh9Jm3sHxXWJF=D#dnJ@1HD%|^Yt zs5+kTvXwcnJx=`%+*(3fygIEUUcC-22s0SWg%)GLC$Q-pxZ*Me z%FL+U(_r2Kg5danbiI3ARYmtdzV|+W>^X9i`$ah1@hEr!L^SmrKut}}qiJdx7cY6q zGE2*P;(+F3n#MMCm6ZXSIIQ7A%d)p1Hw3>{v}b_@%hT?@NNiG^a; zsUdg$9;(%inEx-NV0EeX!WG`D2u#4gJ?dh#J*Q=j=dtYMM~31s8zNkX-h%r-qEy3_ zq4NNnpgb_%Ggi`yb!yz;dto4An>@CA)r}U!s>g3=OVvqAr2fn+6MjGLQ1hH;0xYvf zY2V>D^WKb-C_2ARjV^}phpDPMX-SNB7I*FRSRP)!{eevESBJ<5MBM&Up084WCe9{AT_?4OfcwNZ(T=YqXqH zpJGcK>yOqY=Nb&KJ#BhWkEf(B|<-R zfD%@{zcEUC5#?a*sNO8&xkCKrk^QM8QsbL%SQ@Lnaw0Wuhk{;EgQu6oYX5O(cs5wH z#qI(>%CXua{N{>Yv&U+W;5SqA>H1i0K7Ri;v5mO#A)utV+MY2FX*ZwPqC4X9=D9Bn z=)7@G$4EBprqwT~ad_Bn`wKW$oln2Kpr-eK2uzsarE4u^i|}eqDeROk$Osm6_R7H^ zO|WY$#u{_pYQmD~v?{e=NCzGnned`IX-ruK6xq2pi-x1;py?uTCn{3t@5 zGYQILlY)a6$@wk=L_M+M~ORuzZbBx9< zf@8|&g6MByTIVg6%KISz48LCinv@w+I}DCrxGuVa9P8EW;I!fhEmQ3{xcA$51<$A@M3%b8q--XX)L0A z9K9b%@K_+mjw`GvnL=My6Gu-0V6hTVy5E&0`85%(#x~^Ckc`M~jh}-vGE~^wcKLc5I z6?td{Xk#umY<$e)15LdKxWUR<_BSS1AnL#~yxMUkg|5G%4ln-J)lM%rT2^v_1-KB! zg+7!6&*KDUyamWZvX<31^B4rXvhjY`9w5T$ETQc%GV+Xl_kNzSVXiMffsY>YR=EjK z1W$Qf=W+A|t+zkN4;XZ^UfMOZwF@|Nu+rsxGb~;oZcqnWPJJn}GY{02FxUK#HPIkpstoB->ME%a%n8mZtm`q@e~ z)9drQamBNM;;Pg>CI^1EC;Elbyec()cvFhD9-(!cu%F?%!o!D4;M!WG4Fke9q%(_f zdZneC_8g}}uW{mF18at!UT^EBJ@X}J^kn%X^lI1rX@?B;0$#jLEL(W+mH&0S85UsG$;!XCOf3|vnAH>-o9hu_skIJzLUmR=`qqe`m6b&% zEe?74zFk&I-uBk3h%<*d8Hy(l;7|zTRso(h{Oc|CUh8|Pm3I&Yr!({c9EKXc!38sJ zVI%Ug@V@}g3)h~e(yi*yB$z5M#a8vxYH<0a2VnOCmIs;Zh>bUxAPFSeszy&v86%hT z;oCMa1FO?qpWYU{vzS>zQ2q^+-|0>-sp_Mr`y;&y>3NW!%&=$PY0qHM#KT~>shamP znz0QWxosRR+omS+q2khGKO=G0_)Z5q-UOQ8YJhdG#d%lOQ`^z8- zJJnR+Z#n9pk2ZPM!rMpL@E+a!wrWXmnzV&zq6B?lNm$xsf^6a^OTt_WbS{P!k1F3* z!-^#%yw(gibR(b(Z65lP#U+XWJrt`?9X35bzi&Lg#jG2L)uuV$1GR?hwN5~JLs1HM zDa{@@_FRhPFw`||vw=l7NXj_7&p%j#8lpg`8ESJGTeSl^CQTQLAdK@Pq&X}+_G>Y z)K*A8?7)8dg{Ac84&7QE@{SrUM^NTFs-?KztT}V zpOyK6_SP?cmCK6*<<@b3<8rbGn7|tW=?+Rfova-L(45~%djRDuop4-)d=2@~maT7q ztCU!)ogRrbRcI}{QTyrO_06mFE;d~Tsf`wuYU493~z-Leo0wvGkBbwA8 zX}k{NZ-A6i@15BAE~c^k?_rwH|7MfM{|ae4|C>xlcdGI6XAVo{uVE!%Y?+MAqRbvG z7H_Tn)5LzJ5^oCKrFM<~(hbP7g#mfSFUj}T=K%xeSiEWCE;Tl?(G7?_oDRsf6~=pO zr|sVK{4O;y@*Ot-b0XKI1H^i3xs4Y30yV^M`ad|`j_ch2!pZK1$alc0+zrTcl54`! zaikE4Gce=SSQk$d8E~l^keQqTQ}wIDVXjg%%YYm0K12W<_=p>jxt;-gyPHPmq1aV%5^8G~+dkION-yc>l5lmcq-uYr2=zdbaT|LvgpHK6uw?&^6b#MO69 z#+*u{`XX7Sni?S7!wvZV8I}t7u+)3g^%_t+(hbO5$~AJ=8&F#jh?)K_h}qcPDEKrQ~|Q14pw`Sbr%@0Hy~>Y4EVac#s-T4cp5=Dt^=_6WjEkfH{fV@m#W-NH@drY2fDNcUE-Fx z#n_wxNUJDUJv^?Z(A?IhSZODM=Ul3f@2_P#4BMm>X1tNjUfApd<+n!G<&-6ww?z@I z2gkMvDuANELg-<7Wse#YX*w@sTZHW;{ug(VTTAftDfEpa4I8`Bi9KpwU$8lpwZe3L zojrlpXBiMWR`nbGbxrmt(#s))9`_AeX@L;>fyTb42F4v5DVM*a%M|CaiKC1qy`V4^ z10Cw(<-D$xmc6H12SM&!DuO(d5u;)Us$w1VBAVH#cOLg1;Cyi1|H&gfK~O z;`o;z#l71>7vEDyM92LsL-xeX!K!L~03ly{<2)b|W)oHl2c4q{@2hcrx&Y=rlQhTK zQySk(Kl%uFO~hlo5%9{Gf(0`lN9X?|c!;*Blw9wtX^uVbb?l}>UCxi8m4m+$Acy0i zv6uMgwp!np%k%xEOjd!Qcpa&iZ__5ihfqP@J;3=Qo-XA)@bM9QeSfWUDOo>IV~dZ- zOYoo`0Qk7%ePl9WO5)vm6{n-%M6lBdD50!4D?IYxhWgR~Z7}j#@Gn9`k3sj@<1TOC zn5mCd7V-~pd32C1X-w3gbj9B5eC5UV@gL6dm*AmNryAyiMx|*fPMFaHnk9Xwyq|P+-SEfh~a_=;8y==>v0H3ngjSa_n;y zIo?m#hPR+_tc+lFCFJ-}T^DlK7+Ce)?`2j(wPWMJq^Z>QAsoP}M#$xC;9}i0`Huf> zOdvQA8g{V8jmM$ie~fA)<5aG*s|rX};M;i*yG2F14qgMTkOtN95-;A(cC(g+a{E!v z(1-aH$4l#jG(7a8caWt-Wr1YUQcGxaothP^#B14jZrRBlk>a&<{I;M@o$27H8(Knb zb!tShgifa-y;2^V&1No!L0v~G?d+hbSjVA_A8)jWvS97tDSLevZ4}ZcK2g;poRPXgUglTqYx?IlT!`IN*eX7l~DO`Kf zN$d8hH85w4{z&bf(io;~J|?qYBBG7SR#VH;V|9yXyc<1%_wg}v_>dpNJAOG;0(wHf z;d1#Gun4hB1$!XBk5Q|@t?_x_MyO^k-n>-7J4xRc<4~m$hbpna$v=L4_MN!Nvr7c8 zJnkF3vd-7ux^A9Se#%#F&90%i{ptWL@7fbvTHvY3T(ic2il(xE<;yzZh zeB!%m#mIgW*=cvsjE~g?o;X5SP(eR@tj2e~8%nA!=mTA$Dw`{5GE6eUb`3QRDnzv;J4SfHj|}2*jHYV>q13E`EZ&Vy`>M_W*8J|0^+EPmH2v z2h{!{PrquoWmn*EvFbi&Er!Rje>5FGppH-$-9d4m!aQ)KVe*jH0%tVjTcFFkm}Y#c zj_EoTvk9;joxHcKSEOt{F#2LEOGua#r_r%b;o|Y_D7yBkI#roHiY9!9^SMTl?$zD6 ztql(boWWtw0DBnBoRCtEyGPN6&(sx4!3eT`u8tPpk2LfF>r^WJTpg+$97&&kj(x?} zBKqlb^z7m`@;a!F9_ocUixug-K_;y7Vbb`g^gT+L>vjGQQ|LJT3^CFgh&s`xl`q_| z*kxQRD`K?)Ptp2=YGG1)A^bF9X>Mu%@3Cj~Fh)VHx4@n(A=q3C326Od1jQXv(?h1MSe ztx{j1y@%A^9P$!Tjp7m609Vm$5G$hrY=WqH39~&GcAdg_3F8p%+O&a*jSVM=$L{PV zi1ndB%Jy@6Ca=*Qc{%zKhV$59WL{9>A;wUy|26CQE71`)^A z-VN&gj2pN|FzS!oL936bAt571v=Ofbr4UN2Z&VhCjhdh;JJ@%)YklRaRO^SH6OA7oLB|)f%NJj($6?&R_?l6WAUU(n90kI^*AN zP*ERPlLZ!UmV&M6F~+}OkQgv_`*+W<+BG%Uuox}czEPtL?2!vWt(6xod*Ba z8Qr1R`rw)$1g-^qc7K+w^(oxg{RU1`*GJI9->5S@f&ok4eFJ9*T)+5MN5pFU8)5vL z{jHi~KvjRM{uqnLZaTbmDqvu;Sfri)sDi7bU*Kh1gl6^DTu|JwS2atM35%`1fj>(U|uSxMu$xS$|Lm83}WLQ18r%K&ewo%=s_D ztM{PR7nODE3C#2}Zm7KrH>Kr>@C3(XM`*LL?d2i*6U!0v1}ll>!>R2DoOTy)r;t++ zl`HG1@RZs=XfEKGvKKLgeNmpNQd50OT_xj9vO&%2>!8k0%|Nk`*0-q1{MZEZXNM=n zrb0T_0)u@arJYuDyK*i|bJ%;>hb7+%Td@>+E*7USjfJ%OG$41QBsw>CAc#@x>t=d2%&cJCFVL=}}qeck1n|8P$Q41(dr0375RZ4skW&Nne z6~n=1F{r@Ti*2Ax0IK2(YyA5)(A&pdbtODND+&{|fsg`h0kpx-5gV@R4o8iK+$5Nv zB3uQ38A1}?o|#vYAa?)*b*4JLB3avn{~WDxij=HhT3supX!P}u>MKfJ3N89cT^CS* z@M~}5_6mZcA=3P%x#1LjR_(8-c{KSfu6f3#X!VPra`6a4PM%Vv)(Ui2r+6D4yux*h zv+&8;Mf=aH!(t13w9kg>(bRVOp|VTi!&<{Jo;X1`FWqP#?>&^#epaX7afG!xD^3hM zT*BR@kV@<~$~QYtYVLuzREFKRLL zsJ`da(vayx5CE=GI(h-deF=)kNnkQQmkyl+8^#W$i1S!+)uFWbyt+O4h;$ofEF7In zN^P|vXlO8&ARnB#@`)dRU&V6RP)Lqn)t+zxU)4!wAc)Hq z`LWt7C+N>#)uc|P&~Ol5jgl{@30Y;lfLBUAwPhzDOYju@etgf^A^q#QjzWlQ?1jth zHpI8K^wgd>L8TYeA%RCw6{<%#6lCP!5P$j!`W6{6NEEI&fmFxgZE=5Q@IV)w5eRWW z2VGQ?JZ654yK}v&5X$7qi>hDD5suEe4n$2E(M~)ZymVK>@Xo$B*B>RiG@Nt0ia6ZEgt~pK*|EA93hy@6&W69Ls zfD3$6CyI{m6teD;IW(+|x)WWis8OC#Iv6X$akB-yiOSmZR?4=byN-Owh zQy*>XaoVH*?5RaPO6M-ANnLir_XAt8GM&=68SMKg#a&j5!zHVh=dG+2&&vn%2pV>*0@pe&2&iu0GU1!!AtNY~ZB z^IuWJ?`m?eGhM3&2sUjx#`VqVTGb=e_B$5IKkO9!2UME#cFOrf9qCyyJ=?UC*8HL7 zgpAH7u`S6YkbRTbDar5j$Ko&N%7DZo56sU=v@}%HZQRf#AX)0qxG2{Bpq=O(9Un%3VjlR9E4jZ*3TYF(aJJlnLYfs^p!6u~` zLH_ncYwT%ahe+bq_}-!&@D;do;}72hu9m%hAHoUw*Euxrh8i>cb^}2Tf*=+b)4AB= zw=|);nZn5g734Fzc68%&cl%4-b(b_{XzUnJl^doN;PP!e#^g^N?th7LGu_?%5M{WV z*hF8_yQpO8cn?|7ZvKZhUuDu$t!i4~aQlx)ci{HjPJ=O7%@SllJ_nPA*;ouuXg> zT-Q%4QQ+A5r1v;p6=3SihWW8*pYQ(Q!7?uVJerhM(jjTW!ZonSfPjlVU2s`s;|I<*Yb?s)U zR>K0?33NN9O7knOwU3{qw}aT2YI-${jlPI%0-yoQIZ^=byLgXw6&=@M7Srvfcz`TxS#|EAi% zeG9E2*al&f zH<4DfsnMRJx3tqK7(Y4(;)aoG?o`cy*vR{acM74O+tg_hUmNV^a$-SOF@G$qE5kf! zeSl`P!(AV19xHx4TiH;_J3`+zw4q&{-1j zjYwB0I)M05nH-cN(mlPKL7z_stvw_LzzIdjB3gMl788_HHaaGYIOQ>o zuE}B|?rV)!L{HE7+cbCwmMS7Hr0NZf+^@V%40FAJk&#UUwKpE3J&K5dUjMBkx_cJh zrk#3-gh@n(qu>c#5y{6;zl1S?HV7QUUAv(#n8e6{i$hyu;A3Qg6IPoyq8=}y^(K*y zhZzo;M2r&G4^v%)hty&u*~XLaDeaWPZP_uhl->3oMSF@R$_cLvXh|mXSs5 zL5>LlS$ZT6?`H*iiB(GCF{<(srCu(ymw!81JBjqM&4aW953+5+c#QOFpsn@h6GosL z=CVgIU1ReHYmWlvkwSBJKGq?qUDZ&vb+yZcaIK{hZ~KB>kK`w2UphkDI*D8!WNRwfRjI92ovNBsXGezw}p zg^0rk7xXUJ>~5bhG8T#rqOF?2mK6vD~o; zgDN7sHn4L*q_q|3Gy(HR0V=!A1fdSvEkxhwXYWL>KpZC8#$mWPWaC5o2>2yNS`p7& zn8grt*@_+V<8Pra+wdrrSqx4sF=@GGTWub?ySp5mJ{wQzq3#NFo!j^a%@$d!o=5x5 z817sHmCf_$qFKZT4X~OImw>it8)}`_y^rLY7ygy2CWDvuN~e^3+xzroKL6 zm0#IYE|$`;l;I(pnTHX=RJ^0Yp&$o`@%;|dYF{x~v5cd0zG8qUk^>Ht)lcBgRiUo* zA#@)UH_yW~*-zZ(S>dJqdWiP=p?jCO%I178?dwD2>n{?GgaVx0eSU}r`HN6rM4h|_ zELpba#ClPYzvvaAm#S>?(na(;hYW3hDCXJ>vipco+UGBZc-EzBFQC!@LG~sNWT3d_ zgRw28FUG zPH%U*imN^yb^yLY0X=T#&fDmzE+Rtl96;;4h{zeGeRV%<4|kDAfaI+)-Z)On(&OW@ zmtu)$HmtXJ=`mffww6`a1!(M`%Vl1`|5bong>4O%^0Io6ibY5iy=N+^m{I(V^lwxi@VK6(f{Ct7`rX6+>h`i$fHOCLfK%nwsX&=x`Cs`%Ju_ zgN=VKnh6)rcvSyv=}w&@L|0{ZHYG&}YqTGD!3G2J;2MYr-H06G;_EZK2i=rS^CHA< z<9$#PC`P23j~oXEl{lEFm_=R|F;4!4CR@aLzCZ3Ui$=tX zEVV8~TL?qy;90aHR!oT{2FckmJF@JO(A0fK}L#PyUp=;>0kOH<*?HZRn>o zAr6d$C95H}r_ z5`S$W`t=@OJ&hMV6LFg?0|V3-NpIbc?fYmYo8vm*YTBi@b0Nn)CGF@rx)?8}WSRoC z-WA~O{!)e=D6ZEDi>M%M9*7Ur>JJ#*sLPQu|3Gn;zfTv^QwhKUAt>=&hoi^+K2#%IA@vIujz&?0GUQs+GZFM8Hzn2}-VKppIp#R}Bt z7-JqnXzT}lG`Y21c zQ2%6+91)k-`pug|TVZsme*YzBZ8MHKHoj`B&4FS6iDc2Of64M&X%MEh zHqgQQq7hoxnefAbE6iH-#^ z-p3Y6DY0rfpWL=`FdDJEi063FNw9*^4N!CE3|e6ov4Pd+K2KO#b^mOAE*3NgYCS%o zy~yyZ{xdE?lM54|S46m^OuA?l3y03gG;ZUypd0r|A?MHi+CKh1DdzlE{Kqc3x&>-I z_qzm?yT*$)i1h-9Wl4v5!dp7R6YZ};a&;FGp*u3#^jq7{pqvX^hmCV=wQ=>qbh5kX zT0Hl^%tFS^gI6}U)A=~O^IGZITBlQ9%HEBN`r?%2ELYm!)_M+MR65M9wXpGlz0g&x z130wjGp5P$HZ2#(FsyBuXDf667|``J$}?^GWb8525z1PgGC27-7cRif>b@w%zQFl+n!R; zld2swB2@&i)DL%EGx=Hf7SfDVF)FC60If1F1>f02>sK*Yd)yLDAE%0Ylg5l>;zF&1 zY#QPI&6}@@xBR|+WX*^)5h6!?ywbQiYKfP2o(G=K05@x_O~d=ki+f^KyMH?E=_xiS zYtw0RFKqRmqlLY&<~>O3dx=Ev>h;fgwtD%8)5pDp6?s>BiS7ZFUA4C-!7~N-Bwj>q zVS>_nL$fzcr_sH|Xyv61w4t{cpx9&RWN#6!d^3%%^%gIARzz#tr_s7T*s~ST?ml7; z>WfPk$@m(P&YMh{kuC<~-{y4av&sfiGQ>)RI#`_{;*t))&6Cx}e5iR&aBl^C!Q#My zxW5nbhPbw5Nv+WtbUZ^8Dz7i4{+VJJ93M(E#gbSA>8<@;)&g;di^T>{Ll(v3KY~`K zN}2V!l+;&DQJg(!Nneqa4cDSRtB17a@EBsJ>m1EfBE(gMbCD;o`(@v%QtXneaGVIE z7I*^6!08xmLlL#~6j{7w&$-nA~@f^tC*+g`S$V8>#{1`RZyCsEkKQ>fSm|f z=1bk2U~eZ@TA3(5_>ZYs#`wkJz>zUn2>6jYe7NgH()4U$ob)1o0t=*4~_Jgcm-B?0p?#C0!9SD{F z1ed!DmsG`Soe(EBTV%@B^hmbojiZds*V&ZwV)b9q-uV<#{nc3^!NfxdxXd zgC7vCnL0qE$;y_OX!UI(wNqJaQ>wPI7d6}_?Dp!7?+?+VkGAjz-fYxk!K~s)|GBrA zJJ_kE&UD{#Ztwqwk`1GK28t&vWtjYB5JP2rh}sH^RWRzAeA=qLoZek~VnKJhK2YGT z@m2NKnsI}`-*N_Rvw`iJ(#UMbEZLt%Np?}>S(T=}kVdQRqS&)AOq<{aiC6 z2L_X1B@LE;=dt$TY5f-VWzQI>6g}zFTui?$J?UJo$WVQE!W<^-{g375N5gU4spmYADjbOc`5Wpn%3{{w3?HnM3DXnPM|9>pRSD-1I=X}=V*As zchDHjx!p8x40A(eGQ#Mrrm8U_sc%7Q8+m(3N4Lzrzu(|mxTtiJ#`Dadf^>oO&t}i= zSIp@!NN~CxcCEjy)HX(hB#r0}V+GFDR^i$Jdk@{f*)h*bKS+&BSXCsf1_6kAa;J#S z$#%nb#$`sXr=CwHtj6(w6Qqg+O9-c(L|Q(+*&XEo>Sb6C9ME+Ot-n*Gr^-F`#|hH5 zV1D2h88^qp8c>XRumYQ9U9rJ3?74;hyc5G2wS}U`0^JalvB7xD{**P{aE-0e^C;#3 z!X)qh=PqO}+#$w_5rGjvcOl4YE9#|j%-Q2{J*j4_(3G3qXoLg1?Q7j=h6DROY?B;f zqHjS@ZDdJLZB=DY?QnfhGK~{`d|P@VtX?lI*V0RKBEoI%I5Adnb)$9Tz?|<{>B>0Z zw!=yxLwqV!aaIjdt7x zrVi^yKk$E_ZX_m%rZSI)%IE52Mp)2v6DPNR&4o_J%657=ILYuZRsQ>7`}E zU3+q4wuWn3^M8StvV{sJcj;O)`(ClcQ)z|?wNNyhe@{k-@G9c#gKc#9NfBQ2N0IoC z%#v@xbWyKNPOj-YL#QV2>Wx@>d@K6UuvucC@l{%%Q4=^@d@Xm=Gi?=pG>+%85#a}R zKsnp7*jBrJ8QyzP0_OaJqwG0Yh$(2UNK{IC(}1}m!@D{KGv+yGZ(1~0IE^|FH{&g{ zx#Ce-8If4Ca31s-r9FYF9>mV*N&_x={)bRuimeR7V$h#xIFMarwc+9ByX&7V%7mKZ?UoAMzDi&Q$XYj+% zDGr#n3UHwwjG4;x$v?+891pWgo;Km-5t-V;a7vJT2@dXG~ko zt4|A?XXi4oM%kp&uG(EoqHE5t5X(LM%jO{o4hCH&*eu#tB~dj?o)fpJmLuDNR`-H_ znmJ5rg&Sz?-PjKd1!Gkq{bUme@q+O3n_$bW*1DVU1F^K9%7_SR(N^MQ^GT%75$cR7E=Au(&Wm>%%)S5o;St8p6bUad1}>u!-DEJ@m? zINUJwmC4U#?n>S@!av{*hMo66*bv+%Hek=hBS^6U8$lneHg}@sHKKEPCA#MXDY)_l zXoN}qGSU)gYmMmPjYiHS;ITAnt`X_sCAR{j6$XA1X&#jNt^w?krlmDNZV%;_6S)Gm{Moq3;Yr0}<^>^14M=#cj!KV2b==S+O5%m3(z|IMEc!vPo z@M?q9Iu0b@77qa+=5N#G+x6u-(DfrF?h!FV@_;|%z65yN(W(;VbWBTiIy(8veC@zt zyjEa5w#j{EScZ$kp%C}gBMq7cJ+nvTcCsNG%vkfq9uX^>cKAVUcuyokr|$Yb46J=< z>-#urNuZDL6>u5Yza3+1<#;E&CyAu#ABX{+hM!balI3L{p2yWs)XRm@K+}L*o;@(7aoye6hP+~n4hLdz}J-)uD%6gcm5AnZ9 zx=}CkOm~B>gBwIkW}Tlt({G|V92j8c`|IEOZ|Robb+`O>)=X%`=F(eE*7n`zbj+m# z`yhGobq2^yCHW(9(&T~uo%#ry5u)Jz*pMEh%>BaI*@TDZF*Z=$yIiFD{o)`S0g&&9e%vCX3rrp#l$q5)(Z}h)b*H1fqpmin7EG#kyiwsrLD&Rli0b9 z%wLE@osqn6zCpUz=*KUxkb{`h9)lApZU0hy*9(-`G|9;C*9oCB(4l+W9jXj7I=uuX zmQFQbdeR49i7>8XUk|4vnZEx@BevlUds11{-OB+^)$*8faiyx925bvhrSVQvL_w<761mpE62c;uDo=`>;%do~qHlZRAH#}+dy>4#Jg7oPfs=m@8su*qY`Im~CVz}{3(~o> zobJpw((93)kBE4fu6lZf)2Q=3q*uVz6dH-1UT5p32g%vR^#gvULWSRn9MfKWzy2Kr z@UL{>J25n*ng_UXV~Q4w!7jw~^BC`R+(l!*7lGlB=Xy40anRix-5VFYJejiQ_v z#}c$EMcW5)(Vw*MMZE7i=rw$_Dd*W*5jCmddr=tdUuCTSUGbmq!tkmSMcF@yc%Oh< zlKg4b52E`6%=&v%WM=r ztUbT}ZQyF}j<@g1Ir6y-CU$$zC8q}|?!B`VBTUQlD;8U4hos4|eNL>hQ&a|Qa2 z;XwQc@H89N!(7vlhE*Y>@(ac&%=HDnoft~|9t400mx8!MbCB4CAX5w=qoQ(r=i__N zX|9N^)e){7q}3sIc}=4cJH|zFlL#E)i*7NCRW7jA4vzAFxL)79N4R!#6}T?Nc+3W# z!`#Dd$8;~n@_ib^y|2LOc*et!Qipca)Fv??tTIJgIt3OvcQU(Laus*b_9hY31G&@g z!?NMdZP9aatqwSkLxZqP=zRcBTgT94;3t1fp3RsuM<}~l#MtA235x{gOU9%s!09k? zllk~|SNbk0WiitMlY?bt3BycuI{MLz%_1s;za}6`kGsTXHA_>?$mKY%KVOIqbH|SEK6>%2NZ}UtJ!aJRCLKI0 zqWbaxI>9)ookjHz5Y=4O8yI?i{*-^ej^FIH!83_@Hv^(P=4a@PFVc{oMapPYM%14G9Ke;oi0F{A7N|cRc}3jCWzcSFx}JkY z&=lm=Mq|#4O~pp*Xqoxigxd4gI2|v`#{6B2k)GIrp&RBj!>n~Wo_E7M3mDc&*w{bj z7TCB*$OERzI;a3{*b=}nRdlTM`f$ye$+DDi4U7Kst9V^rPl*@AIMY>3peHVf*x<(z zO^XBX_ss}UPxOnLSW=k^FQO`nW1}I)@)%DG4gk+r@8J#QlELIsh?MaFn&Lc`q?NKs zYsaA3@cQYzThi+hDx{Uh{w4y0|3G$=F12x2ff@9!O zM5$)IaaVfO1|$g{s0n zv2>5q0b}s7Xo>fuQLa?f!{t4fvZxDnJwV}CL|za|OnVpd5Kuf%z&b%&X#N$50_M;v zqYmh-?v$mQp#h^-Y*4ONlQSaZ4QhAjI%qKMIcahQqE$rKllbv>{oKJS{ zbmPi+7MctmU-|~Nn858F+WNZ)}x zRz1DZT$0oN7Dd>nr)aq8&6RZ-J>n5m84O1HJ*rLTZ&li9pV4qaIREFh_M zEH;8BGB9ZYCJBu&*wOZD;vwu`;;w_^5is()7>ckVuUyA8sG!#CA~H1?m*MLMGCxGR z&bQyxZ!}p(Gi!#s-Us8p^b%NgFsobPuJvTU0X%0@!3`Xgo}j01h}^)ZUy#c6i($jK zP=xDosjcSZ4bdzIFGY^6my}VP%Sr}6ArS6bK}Y`-fr+oZh;=TKTQ!nP@Qol~_zs7< z#=((7tS^)LmxzoQ%%I^?h7r*{$TcXAc?wRx?KJ2wFWB0ombOu7`Nnr8@1ovP{EGoe_1R0c_Py>C| zk-}Y%QNiCLH1XN>941G(yc~g~80GiyjY*q1eHjZ1bOABUUZYq37U{!#U>j0}Az?As zjFo%|*kRuhSV3;WRK|N*F#Y>Ffw%?uNr2vUx~3N8nu%)jy_l>}^CZxk#kzKl{)L2!L*AY;nPEQJR{Q`c;_m_6P;WUJ$gyVl6lV)ZyHzPOUH~T$R zF^}ljaTxnZ*UJ#LHeGUq&uCOTyrRR}XkNRB$UggrR2~Lm#vp#!1w=+-?pXyPz#UzA zz~G*v;>e{ebyk^cm3H<^R(K>Z2dI2~P) zvH&F#xQ|``r$91c_I(Mh4Een0{{yoy{gzr;bQb~ReV3e$&NN&xN3oFI_ag*4O7LLM zrbiWXLJ(lioH3a4>R(3AJ+xIZ>tg=QX%@=iu5)x0DSDrf(n6O}-`%M142IU#&5WX^yxAbRF8{8j>zb&YJl$%Cev%buNK1|t!^G?TK;6I3R)C&0?;b9(!fAc)d z*5DT&){;A8tP-x=;o~Xt~ z(>=}q^$F%_qwDD*t{&9tX|@!jPkEk3@wZVt2pDb$hEM#>vNhDT1@*AQN)rO87em?O z(v^C!iV#mxP)o$RpQu+I@|x0%J~6Fo}6A-Mk;Vx&A&bI zJDgST%47sr1lw=IYRJ9ohZS!bZTB)SXI4n?EpbeODe5Y6KBwWG%rSmn69N-<8m0q3 zQv}ohXy0%u>tue?a~;G~4+`)$hx#l>^%m@*No(SlIeV`uQdK(5%fyD0mJk533nN` z((w00c!y5~8crc)wBiQwNpEvN@r3(iuyr8bmH{&G_u=2O@mr@v7E>V7^&nuJSbx|b zN?PinHR8Jj-?uqEvOfhW!M;bB+?60VOCWt(`j_atxk(s`5g_?ffXf6N!>}$IP1D2`uexaMHsBiKE^X?9r1R%zkvAqny?f_f? z65B@M2nxKg7QeX%gXpL*$N833z@Z}@jLCernPjs$XX-zlXuyW72$i1+D{*{+y7)EO z-nSseRE-B!Jwi(yOwkVk^E+Vr+yYYy#Bu?X5MsdWrb@FpI{KeBnA-ZtMEno$*Xet+ z*=>-oL>r}mVFE0TF5v^H&gKX|M4)E3aDM6s4}KupLua#9&3%#OXQ*ojebCw5J>t>7 zc(RAMM!J*V4rC4uv*N0Z;$xoP>By5yx@qJ8qIo{%_3}1Sea(l%AAL#ZSZjwTaVi8R z*YO}-_BBV!1IWh@|K6o;_!q7OVU8f6`ukt7HHx1*FaliT^xw}+YS*FQcI@)6(M>;d zsQL@4c3y1H$fU0R=FsThx*+#Ldq!%JmsZ{Ap=}#z+u}P&+QNIz-&@JyZ=UBfYb|$( zHIrc16guc{j*oS$!y>Iej}YXVgX{|Tebj;$csMJawEHO_z?`A46n#n@BWYBCu~u%% zC~@S_`~Y)52wzu#nLR>U0?dPgr_@X3?=%=%ngW5ry**2rUChZoLy^qR7@RbTW_2<5 zlz*oeyO?8!Pvn*%gleFD>xv6{|2@*!$j9G*lp`N;-QPTAd%ReVm}A$ybr3`o>8zC2 zvzJb~)8R#OpgABk8LxoER zmN=GNM~j$^Q;@sEZ5Xft1D4JllW01$GUs1x2;!G|LLre~2{MN!&bh2__^nNFU&V5* zPnHr)q#Q_sMo1Npp(T#{>6;*PN-7%KWG`{t<8CMe4K>`jNn3}ql#OyJ-p*s}*I#kK zPkZ?2gH2K1PXig^$L*kMPTy9f0y zXNm{9emC>Qx`sFYymm8`?kVyO^L>QP@ossrd^fd4n@iK)ZoP@?;Cx#;+?B8JBYS}^ z1!?@QWWExG$Miy6Z6KC}h;H83Xj_aq&1c*5P|ab%t$?58YxGNud9dW@rJ(-S-?`-=>pqk>wl$qV$Pm|3^s^6?J`1>Nf+DrPk9_l0x)N{h4wRx3%LzRl_6rE`9AMwH(a66uc`2uSW7k><6@-?a`-%SrEng>A!Z%;J$ zVs!R_HDDG@G^fNOyuwm2K$wnBpp{>S;Lww-hcx4+=5JT2Pm(#_0<80Jn$-zlm~f6p zfIaZXP3rJHZKX$(pfHxufh35&lO!jb!)~uPsBruW_cYYCZIx8c)*`Mt7CadUM#t$v zMuFn2u_@-jQL6!8;UQ%vcgzrs zBQKt(>p&n_T%SQN`0a;1rjB!$2pu~o%Hhs*M&VQ&+JWDFsjR``onnrE;9<^!rkl}W zAaYl^q`|5sfS3=UN1Ga0?8{i7qqB2ttu7r4;ra#4sw<$nZXe;gM77<_@x2om3v|5S|EbXg zk}r*QI%0suaPGLn==fCfv0|C(!Y!bm1q(SD;Sb=QfioSec|dU+c!&E1`SmXx8&Tsl zoN>28qQ~FTuLj}lav5bLjA-`%DHG3SEKbL-C=+rEspG&kXHbSa$<4zo*X0Pl^Z#xy zhUtm*cjH0u+mQ$ccI5xio(Wy-UkK&$*rqrgU!n4L=xPOcU4_Rsh)II6-FORGGZw79tt^82pi&m6)Hj@_G^Nq>23~8n~O9X(%59kcy;jDMruZp2MV}mWIulknk_2SU8FOb(24aHmw-2#-F%Xl1nWQ0 z-4`BHez!=K{-Gd6Fz5*K-q%oGf$G8>C1yqS5 z#l5*^WE*iUj5*%`PQIUuA@(7xQvafh36f|jPF{+D{Nq!HL|BdXN{+OQ_Z3B7?)!a2iZ?O_e;BJ`efWsvxd#Ng9^d`Sd{=5WG%brI~S3#50{C z|EaBy)A20@^fX7%nA^-={%GKzijZ}P>^;pz5p9t91z29H;06^hDJzSxyj0*8e%%$? z+tVD~_1!Bs=~i6o(T^(NyAN9@m?(OhC-#0C1U63KpeX~m}811B=L!VN;q4GBV2zz3+!<)!@pbc zTNj#8ft*()tq*9*>Axc#mp(C7BVCv9JEpFqe5C8#KjkA`zua0Lt6H31KGJoX%X>++ zuKR41oNf*W{`PdtmM@ULwb4_nSQUbca#60Wz+)?J`W{AlC2(L|m`tBOiyafL=h$F= zV7QNvZya| zvUmyO!WrA?$8>X6=0+|n$(NT0O5-g^e#Kpuf4^*$HHt!PeTAZ&zK+IbU@dwM+1P2c z;$e#*D1-knvp#KjvS&FRPtr3P=4r+F%Igo+@HeUaM@$r0o&E*A1o>zB;i*96e~)~a zNdA?d%jIvwbLYrsRj)&|@Z2cGc7a99zCljMaO59Eez*TqJ~JKw9s^DQAfPV2$ z1EpAzPh+B;L4G#!IdrNGz09G?OzaZ|(5_7AYXI=D!4g0hGNH9FxE;;~(&pZ;x>7)9Ylf(VpM%7A4 z;1=-Yw553akpGv>ce+B>ff;W=hd=DG~Zp4 zqTK;w&3Mw|x0`yzC7ZsFf?FZ-hF-o&`7M%`54py3qGKb(`zcd}Lo;p_)1-%gg4>>XJkNjs;YukZ+ME%f3v1@AUWJHu#xwmHbd zYgnrXJ(F!7F#hIFmW_d~ZxG=ve}t{I|0SRUC8;0(hnCov{}G|fl(}^fpVlo3`9^cO$GS^Aru=b zfq){Sf`SB$yq`Je2BOdJd4BI7?;rO$=boLN-JPACot>SXt?S0mSj4I1C$yy⪻@N z?a+*8<7!9!j`f@M{ic4@skiDDkb)MoVaMXGhXB)C{0v%q<9C|UTkRtEqjkMi-{2|p zAmZGl;#XWzRX3^bDLf@JT((i=u~gPu?c;rK4YmxG(7Su|*0^d5kW@+TeIPuKP}@G} z;#wNf2U7C_&F9BiTGt1QTN52-kbmf0AGMEv69+-d;2MyOPAw>HXRm~+okMN=su5`> zM{*`UGYHeX7SEM8q@0^zZ|6qYInAl8ojnq6p39NW^XqxQG;0Ktk0LGumkFA{Qief# z(?;oBg$k|$(&ycf=y+e%0vBQUV6lsETe{sBb3z~L-cOBg4);L>G{R>WdZwQ`%Crhs zN0PO-t5=geU#adxs_BOrw+jXLSD%(|)4KlZHl@w4)Nz2?Kdpg{%CG`xV53^hu!nyE z7okcGN9_Ipi|R~-V|RS=OOlL=yf_|xjUM@QHJ$<1x(a@_!aXAV>;i|e4=|tNc-(h~ znGBCu_`t9AzF=p%K0u9;TT=(C+Rpni;Nr2|V4c1U_!OFNRRen!!|B;J6!&67TaiJf zu-x{TOntPu@Zaa>^LVC%CEr+v=SG}b0|)T;X;cQx@L0TIRl7Aum!$T>5cx%-->j-P zS!2{DBC)-lMJYqq(3lu37|x6{?7c3K=U4DP`Q?Us@zmt4UBVFEgu3S9$&^1v+hf#j zCLAaDjlRR1inki%Te?rGqoR-&0Tdmpw&3)$G$dAiHOPXH={P9D7K~4@k1*9y-u{_V z&LX-Q3!d~OmpIrQzkQ4uTPntytvI(esGI~FB=%pgQ@=RXcSsT{p_}O)k+v4Cgx>v$XNr+GV@maP{TO_ zKDY5|P+B7@uoz%UB%)N_uNV$WI6rAz$eW1vaw88!$oBW}-2$6}(MZ_e^hP3l5*nEc zI&q_>GmT(%TM1$?r!q&eip_N%3z++;C*zxJ)3snvO?^nUM+g%cA*dFOQMmJ(l!L&O zUW{NbX9ig~t_4%Ht)sEYpd?eBVIHFq1J(8d4UZp-xXCyz(~njTRNLT~?Vf>ZV3<>L z`0Ge@d5|nxZE;xigXaD*)`gx$*N`9N%2dS-H3lA6@(WQSs*gxS04H~3|wqddG z1ZGDVY!vheizb#{iKtZi#rBvFy|seG4)%7mZjkC12Ck2v3h1Au99F=8#xyWTA0EEi z=RiIThj<66U6die(7i!w0`Acn@wggjnlu(Nr0ArZ7ugyA}})mdW(F4cPr6EAD7zI+E_!e8_FFp1~f-DXx>eYN~0#;scX?)wbb8p6nh2<5WYy93V|)P0B=9bUx?i*%Og*m_}cTl+Lj2%rQ`JE0tJ4Kx}8*1wfv40&5K zTpSK&VbtYRHUxHnQwiL)#>lUo0k(jP>63J02sS7epzRE~hunvvVb#=OD75YCsHUz% z{E7Pqb;$xp6(A|S!>2&~HNv}$L#+J%4&Hfd5)A4ArcM}@FXwy~ju6kcpN{7A@o0+r zik$O~jz_;5GT}1n${wQ!B){mf$TQ(q>u4)#!dJ&aoTpVqF6Jd!J3F_VcXgNsSHZ+g zHw!AqE*N?6_TiBM-l?(zNxH3r-3+=g%}AOm)Q#Q_lr20aD z-mOW{d@{gyndP1Ag*mV@0N{AZh*7GatT@HftkG&q<=tOs{bcr{(Q0R9^Diae zj8>P(&ZV8~k?>S>q45doaA#nM+=$J0+L@rvQkwlj9%I#!K7rTjv5yU>j1=ssIZKd2 zeo;Gqrf0{hFDpgY=%2A_1m`Tw(3OO7m}g)-AE$P8ed$LjXB7xz11FvQiMEVWLt2?6 zDSL;>xeM!sVN!fuEVeCj<0QLNQ(JY`XtR9>uDWk~oxT~TPW3D8V80E?W*I#5Uv~93}B{79k`1EyqZ4$8iIu zryWpiZ;7S1CaAvidpRkcrr>vQoxGb%F0+Ki2c5?g*A5 z6)(Z)=DB8x5?|76k~&6~zb%h}>ihU$jyS=m@ z@GZ9~mZB>209)O>w38@~$4btRwBQLf#J@Z6^u`)6uiOm9BtV-wO3tw$0?OaC{R#C< z_!zx7Uu~45*gH6r&tQM*Pj79=kF<4~8r819BmIga{W6}p&}w_)J3FSIF!AN6URrKg z5dAhy?d;xK&)}_{bRha4b$${y?;|w(Nwte{q#@6-La31P zCaU41^P7WozFG`O%L+jZx`Rb@44SwJjterli@U5J{x9w#A&iEEa8I7vxhoEDvL=Y> z3%rQjrqUt;Q`4y5r8@0vZH(#y-$XA09xeT_*kv0VPKO~USo+?Ae7 zQX|u={P+=HeDzQeaw5Nb%b!_j8q4rg% zJ$KYF#0Z!%WOmP)=&&I=*V z4KLd&#xN+{WN!nuf$T48ZF|gK1LngN;g;lJz5&kCBDii>T>%4@Ap#J0@n><}?Wci9 z;C*FM7yTM|Gv2p{b=R+fXQF(XKySlDp{lYbPOdcZ5njf&x5{K0daG{Uf|TgYWynqdfPn!27wB=Jx$~kHh;j zx&C%Oi0KOW&y%|A@d~*@@8os2^W3fCeO6esy%6tQ=~rsH+w<_wJ>0A&+RoC^(*=K8 z=SAB&QY!b&<4Mu$rKD13xzFEJ!$w%)y3J`%pMOrZZn!TQ*GB|;G@)BM`|rB zweZuOsSd{$-#;_esNSCfD0c^z-H6cE4uWO}-dPHjBCN~d2Znx{hi?|7cSia)gq*pE zQ;f3?Q1UD_yj!bUnA(c1b#tGVy`)Ljy4n21fBlL7vmE~~EHu);!IR#+;_4TWI!uPc zDX#DZhQ`as{k1gG&o#t{<%A^R^e^D_2?H|Ym&+9LlUTS5vtEpimR_GtASwX6HM@vv38c`bsnJnlK5Sw`>Ag{5mL z)y!!S`Z64<8gdqnu_c@(^E@cs9vs))R=t#l%vC442R6dfA9!L6JbmcXxea*A8r7h1 z9HRI#o>1r(9pUBG{ov(%}(gGSfUrm-r((d`{ z*nvYQ$zCk=xM7)SP`ZFM9%^M)Dm?9LU_wPh8>0I_kJaHArkwXmm}_Uia83gks9n?A z162b^5;WWfklLrP`F8Q&s911vkqnoNRcHlJ@fzkgz;Q%X7QPMXT%7`>r_Qn^{D|~l zk>0qLoX)Aq!P2kJK!v^2^A+5NOYsadFgDa+r}!Nux*?}3Ajl~?$~xye%-OUIVLblHLIOVtSXG7vPjfuLJ#39nMj zGin&kS&9{>D}%IW)R9mV<{K$jIpsGpKVzh%ZUxtK%2fF{z4Z(_`zzZ249Kvz#Qd!4 zsVIAYpz!C_1MV+etS4q`wm3poL@lRl&#S}SlmGL1CJlT+{YcIvc^M2Efw*OhhdJ}; zcWxL(Fq$UkJ0YI6rzR!3*~9PR8#Wo1qn(McDt!Y7I<_+1n~49dtaX#%pO_eh4IoNd zruw85C1$`%1sla@aL$T_-GWcp^GdNC{}TgZ>h|&TXKP(E)G9GNrmhJ;qhjiu_~{W- zC-W0w3@Xt{iM?a$J{|LKD^}eP^vyE0qnu4HFRI(*X0-D~^^dSGHUldJ&PB)o7EV0< z4nP2ayaF7(`2fN2>F`V7m~7^{7$|4S9tPKC{iYv^U#_k&(vsj8kpYfPL64-~gi)S0 zFINW{Y3Ys93U6bTL^qeKd*z9gw?YkVKH+h!@<79zKhPH|(0@be<_dL!sVKKJgnmd< zz2j;yJzK1ObiE97P_`sH>+heLq^eS=2doX2 zUfNQ8`$X}&o`{RW67g*z{xfIPK7%LrM)%<=TeejPP@PR}J!aPT=-6+pb-2Zk5>H}H z%Ky(}oyyO9Fe35u7S6o>fb3hXbyM*_ju~hlV8BqW15vy0t##uW?kcPKi_+D{{2%`w zR?V?7I~#`r=K)}%gXyYGAHrBayHZSs`YQj+nupsd>0E~TiTSsY25W^u3ihJBOsp+m z7zOi!4{V4RZ{kLkiuviB0U$B(G9?C_Db3U*A^)MXrt}kQtmFNn z?pNcfEu) zOkL9xK4Ub#%IR-u*;+ND<)7aedPS}o^ZIC94S<%WIVzS8=^$rGcYmU=SJf5PBDj?m zrOlM;N`LQSPeUa0nyT*hv;|UKvpb+tG`_0@Xmt*8g@}~tZa9}Qt*dY zRqrmhW3c4Jvh_5KREY<$$j5rf~XDU~6qbEco*qTS63_UZ=K8d!rRF!GkFguBS58Cc^)VIL$k+dCb96=)m6^ zXUD$BWoDwYhzaqvl!NB^Hb!3#uNy`m|3BR)pxPNQUjgR#MmX}Z_2LAW!sG0`?WJfB zX!&~ZPbHmLuTFKIy#$UC2m($;DK1{aFCinlO~hE8?HQ1JtCwQr=;mE^$MDt^EFE9E zjZmH7xD?Fy44Y(&wub|D1;fHkgTHMCR_b)Msh|H9M^$Rr$i&nDubAS~6ZTNq26gm2 zZ0d2|NywY1v!tJv2Vc~D*r@BdW+2qFn5SU3NZ=*wZ?Ta65iF@-#T;fmICdBe@Y3BL z{67!xp_13!KcO%)>~+BA0(K+#2a+vnH;wtm)sHr3t37!b#t%tPn9Y^&q{IS`ru1tz zIQ!OO;Dbfepo6~_ljw}dsJKLzg6+`O+EPEe8t?3AFqB9;mST=3+(dOHc(1UvF)t2H zNRjPZ@Qs`G44S}~_Po8QRbUKdrak1mC%T=}qv~vbYI=ZKpTE zH|l-#trU;-L*$5FJezO~8EU^#Jz?%Su#P`qZqByOqo$kGt}Xr^q<4&r1RqG8?%AXUDy3i3kxgoaGZ-ujjE0@{9JPl}#aG5~D{bM}O^mfwkNk$t=cpOp zhhT+FoFdgps#KhQz*@JtT(R$?`J3ThUULsKDeI$e}la)XanGu;`ET1 zx)HQDSiE#I@G6%lajq)zU88K z*mQI7XzKO4+Oegcozry|XMz?WK>2x|iC`M*ZzvJ8u&lY)=wDD6Ln`=X01aDR26{VnU8)6#??2&ytQ|! z^ETDfrDhT26o%PV8nI1%towCd)geS9o9#COdRud;PMm=|GFbAeqcSzLi~4NJ*ejS7{)6pWk;twnF~xPymiuG-g`i-QmH6mri~AM>_gO2073 zv2F~7t_#s_qw#raryu}Enssp*)myI@_FVMldulBxFAwb5nNINIS*puZE!_ZbQu)l8 zr^YwWc_9xwD>u*~2Hh5mYH*bb0moKYl}6;Ner9~Bbd;o=rN#MhNmdro+xeJIoak`A z8srX$FrFZ>?-GeoPgxJh4u`xh9dg^ut!FdQ*( zsS=GSP%Uo2n1@+A8EjIE=O?th0ON`4hH`LLtw3$<{UWre9*u~T*i&PE#c?95r=5e zcAOVPdKuuDUhEIugWlS%4(8Uew1BtGc69wUXh7QsKI(dI-4N=$!)RS995lIjlcRRu z(xM%}{{`81pkbe%GunKVzxvYI9cXhEUE5)_E*|XO(7Lay4agz`60LKlzVE0m0+p!+ z9GCG0jd@4);xDF1Zj^TvP6fP!Mpe-3@1W3^>EJtRqzhNS6$VK)9oeOJA-{K3Z~j&b zA6a`f{fg$(_;=M7-V@O<&qfVn)un`9cvlVS2=^5n7y#j8ptY6bmjVQloeeHuq*v8T z%Y54CwL$dhyQsu$y74YlmOV2JD-Y9@eHp;lMGcrPp%MB}>-dQOhXdQUM!!9TWB%v9 z%X&<2cy%0LppHbb^%3${hs#7d*RIl0tKNV)2L7d;YFoJ%mF)yUdQ;6#)yJ?BFuV+S zu9vBs?meYJG@ZooW202V&^XfW(a_j{VUxSw7#cHh(`3WY_=*;3YQQ73=@^vy0O^jM zXUcn+#^1})loS+Q7>!L}I;~;2>>DoSEQo)^P*yOM2btefL&Eizm2ox)&ExwRU4P=V z!5)Q__Z}E2^*z-M>&s`}1CMn=jd}2F;H1#*6F`67+~juh<^|KAF*eZN1Ye8>rYmq@ zU8ZA=!O(eFfrc(91UU0v4nRNu5BV8wEh@;v>s6$GLLIhax_FTm?E>*{k$qQV;^zUH zD;3`#hmq;giO1i`i5%@5ZnT1C_pu`!|)+Y0T~hDkULX1C_Gi(Z-eR z>u8UsP6|btN&9xI;VusxV^exWyl59sgG}M5(RBxz7-a*QQez&G$-{y6T09-uq5AY| zpcBJ4(8&~QRKe;0gH8+=2{${Y6I|`~V6gm6`}e4!9X`=(=H>8@Gj6fMO2-%o$i?*1 z=`si*Xh`0R)o$b|DW?Fc-*nK1jjws|zR1NssS^#^s|E%)^ETSWp9~GgN3&qP%`@R8 zO5ck;%wj47Bxd#R_TtRk{`t&4-iT>XzgLay1Xc|L?{TwC@Eqa8!S*UX&*~G!+{6`05>HLk{+&Y-kE&WI}UOYJrupJqH**X(F|kJVHN| z7s>Y?jH{&gi{K)5iE4_}qsmLo>Am;isML#Yysw6KdHxz!wiYM*`*`Ypd|e*-@y$N% zSoSFnJrrqwR#X3dYJk7_46FrDVl`%#^q^)^qK7>>+{wO|7VU#g&*q{#oc%>_?Zfu% z06NW&SZeYC+|RCJubnMlGPaBR|B3x}Y-uLKUAGV36Ng&s+%LnBG16N1J$xqE_wH*{ zgMIP7hoAmqth^I`O7zYL z>NMr*8ERUrP8VEJOg21r5j><=T_`eKbfL~)aCo~|_4CD-FwA4gnDYuP`q8h1N#GZ< z6sum;X}>DuQ0li|4eAMGkq%{QAON^K6CphLR``Fwe~hFe)5V^FahVFgZ7u@m$T%?D zesyrqbQik`DjI)n>BtS+0dd@)n~vNWSi(i1I)#{t81A-{ISL0<4yYDW=P>(Lsws!7 zIAc0g@snbr%0j5Z|hwd+t6;m{)KW>s&E)3&?&KBt?IXwJ|H<`=`KL^E4$KQac1>Gi@@_8!@1G zEO%R9T?_TVX}m+QqPU!*Lxrl+Xs$2iBfkA{4#{?(Sy1`F!mVCcuV)C(@dxGYCUr7&+zfM}-Kht-L} z8+u@=10`36_e5B>t34kk)Wy1+3ePg%9ac}K6>-eM8lb6#%LK>EmMY`w!Ys`};bw3U zYpU&ZmAw#wNwdIy_x}f5+D!I(kSU#R30M;d#4a)%e2MWl#N=e$xlcV_2Y2JTD^9K^ z?W&V0>PIINE*FB!RQ5qn?{5FsxgTXVQTiup6r#uO`UKAM2k5g;)c(QWZ#E8BGFyFj zl?R89_O1SepBROes)5lr@R!XO9~QVc*6MKBb%1{906nKa5oizRLx0D*br+7{m8yf} z7Id%_Gr$`N1q&&>h3ZS;?{pW=D>fK*lAZXh5HCFa5R$TO8TK)jQ&O24(P1edEa0ZS z7-U={*5ALxw?v$dzW4WoVk0<{Cw9dHa1YV@Wx$1CMjY9|;AD|qh<8>>b0JyS zBO<@63}J}%=O#m>KSOmVpot;Q)=6we4W$_;QB)^7d{PbcPDNgpA_@*0Bu@>Ne~90Q4W0l%b zsXa#PtDpcLpnX+prjn#mkJDJ2BH+|%b!u3dYTp6t*pHHv-69V-&$mTjUQLjs^Z<_U zxak;GpH}B6smG{)H5`ow{*TsFtAm{HALBXGJBoHap<4XEcMzxoOqPz`js>aXN9mTG zGdM&QiOgrzIA<_fzG|rHMbwI_p7->lU(TxTO^Q0$Q;w2y zPMs=Z-0hK&<9|B&MnRmOQ`@8cTh3t|AE1-x)L55k*mUKiH9wR8dAN`jUcz6*t>;g6 zntdL2jNuN5T3W|{%|}6iyAQf&)BESK=P(qhdQdBbAI-xd{sHtgpy26p`@GsU#s%nh z;XJ(pF>0K67g|#;0tbqMkaIWE_VmGlAN|0sSu0aq*QQ{i&4rCtKNv)_zf=RGhR&99 zeg|W@$4X$RAgx+)U%MERHy+-OYp(uiyOFtr?KJ3rOgHme;>== zp>FXxFD1>osp5-z;*)M)AQ*rZqG=f3zyF-sBM1SEc7LT_PIIZ3yfBEWu325}?JytC z!%dPm0mj>BQ86v-Bl0BsyZFZL#2C_5!(v=@7)A>jRJG39LQlu(3*Tz|9~j%hz8ek} zoQJj5DtvRtw+l;{PA=dw>L`!3UzcaQR~k>W5{(G8+Fq zWWQjyM>u(KH7&IAd$^(Yrn>L3%IHIFe^945SEZmE2BB}({-7T5!Ih1?a4|g+MonwfDe_E8ssW>Wm893edqDUAO7hT zf+aZ|l}f#Dtd^!z{hw+#H>5_w$-ozO`Vw3#4o8mL@GcKQEJrmito0M%&j996zGB2j zTY>*J9Dq0eBh(djxT9v`xYYZ1Am#s}6L-{M{zn0n3%!p`>@{#9vfgGVcR%fW>im}) zXg-Hexq5skFYPQ%{tF9Q9KQNX9T4*tGD=YLxK+gr^&5{=-mZgFEz&HGh`GCwhN}+t zvudOllHS68DX)cnCzUncuqjJsu221wp0VN`Re9;oCQ6kMmylFcP6>%iQGa*Y;8e(?yK?E>{LkN-%vUvel|<|c+3K9vB0d5{S&0S zDMr#SFUIiB-huy>iIV*?(#!Eb4p=_9uSP~?M@X*r#KFn`THM8~lDy*Z>xy4@{CeQm zi_CwkkGo%<^}VC` z04rCn0XE;AU76hNsS|alpZbR)}lH z5GUuWz$lG>!j=$1@;~a!Mp`Dy;d~0xaXZf?+cg5T%2yb))cY7TzBW#+gApLq|w;v+=Yf zAx8fZdRrC&O3V>Dgr|RRz%JAo3`1;-T(=1C1GdU_kI@ZT?DBF9sv0be%c0Yos`Qho ziiiU<-&Dlhurrgueyw=u@ME{k8XLxsyoawm6CQJwYMUNn1kE2I-*v zBPl0;18z`4w;M|xFKq=f^HPc#bu$o4`jGP1Hd2yFc#dDkpAgB8lX+$ICH~v~c+gF& zi0#!JZWBHJFnF9d44(q3+*^zayPJTs-r{`T+Dmxn%Ta#P4}^Pb@6j=nh>-1wyC=H( z59VBmUBwle&bcuBcxXOBy_$$Xb1x)Ih-JkUNT8%9!q+?$P`P?2OFwN0t!yHOVYBvh z6Y-cFMRHTn$)5%`6`|(afJ2-)9kVMfYASr;>$Vyxv#%m0@sd%~`iX$LWYqK?-g9eM znef;C!aJW1v(!A;pM)N=;Bub7J~n!uTlL9na@|Y#egkmb@!dvpT{8a10WJdbFvDCW z_hzV8cZz8y2DB_fsTO^(_-mgd7xvQ7Qg5vi?}^xh;P*1x-c0mmF`N1sj3RUm84;_t zt+VLiPAG*-%*AD6d97o6y+Mnd(c0^@-&v$NkH*l#mR~ojx~clm9(UXwKFLLR;rzmU z7tv8}kzI$Y^Ykn9(5O5F>S``pxffzt!HrF~x!S{>Y}GDQ(_FNJbTO;Kx9ylr-PROk zMOb`ZUNZx*RIJ1I{E56^H$ha86?{&`Tm5+}AlLwzDLbK=AH}nL?Jx{MAA>cW<;ueFG_`Feitl7Rfc4RNM0@x1H_in;R zS$2@_xQU2v$XN+98Rs1Tp%Ij|9MYTjLzr{8X_0UGGcN!fi{N<98Ie`$M=&1uiqFfn+jtdsCav2>C z7J+G3M}f`4q;BbowHK4peGG;KqEV+e<jm3Y7|9kN58$Q|qPS?Y=>xR0hVVsWt z4e*b1IwFVwzK-EDfala`bdw&E-A8xD%}3x9cCfViNF@_P#4TB%F{S|q?Q!PKB9`)( z%AUrT*>uh#BHN&kIMf6aVOlZwJC5>zb7Ey&JM-QH;%jNRz)lnvCcK!KwZm}$lKO>- z!Ahbhy%Hw2Iy2FRVLOZ3hKu$BFqPPT`U{-Xl#;?l8_vahLm21b!q1&?jKtxE52T!5 z(DRe`)1hz??bBnw!MiY%>b$FTwpHU2m!=UALf`DC2@&FmqU|T2Nb$Dom{xoumtB^d zXnS$dOQg7?EIL4kT8aa(%`a*tvYcfvdn9-e?%%CMD0(TlwKxh+x!PJ(;GwkE9 zo%*;e8B|v{x5>`?OPXRY#%bqIeWdz>SXH#a2}uS1#m_=+1hiR|@KKy%?^WPc64yZ- z!znp3KPG-c{q8&_Mw-_ZNjZE#g=gstG^Udnrd)iV-tHvUy5)M=^DvH*Ayy)xu)#H` zGboF%wfG0aQD^Z74$x2QB36MluXYhXDgz6U*h3G%?9pbglw*e8cnB3rMy0vClYlM` zFs5;~1Pju+%X!ty-H-Tx9)E0qK)p)HBU;3Hp&SO!01dLDjbszejuz9E?jO(>csc`7 z7A$B8soz5&wlj(bM;zOOa4t|^`6$)LD7qY8iw#9*0){s^OX-CkqD?$X$QleY*c$m@ z1H^{~ioFOJQZYy`V>drTzmf?CayT}2Jd3FmN-)eoQ8BrEC6k|aj;{0&gL~z9*(<^I zcI4zHEkfD*QFeZ#X6t=C1eZ!U>h~02e%(tmdy0hFim$BS?7)^@=KPpui1gA-s`|XB zo;O7`EBMn}@;P3PT6A;jXKxC!ZgP#e%cT1QGoAMbMtrmBlK1tP2e@EQ;oTP>?UjA? z1l<@b8(uznLE8-LB|LlXaiEp-)Bir2g6zCa%YkPw6=pLrWXunjFcYO%z3uU^^2Vdu zw6LG253O(G+>}=J5)lpRxwoBx^8s85an_N_dWp~B_`bTgNRijjjoxB{zk!mcN6fzk zG2Zr6i!I^kZlJV&(#(fe{OH+?Ug#rS4U{qf%kj$uAP=Y#daI8Z7PAFA$`;)U?5XXB zlOdaycEYQh=Zid;lV0U?1oGP1&;(FFAG=2pjHaa#uS2wp+l;KGXt}?SoKwr>}G$0J;3}X zTouEul&2V6?5-=N+*!@=E}76NO|jgNBvj_mE8M54RNNJei-)#l~8M*!7hXF zk=U3-Si62=g|SRaau9}FRM_5@;13G&e8tKT$H8QeNoaFA9)`^am7SQ{*u;Qud4JKP z^DVTbK^e(I>r?PwYDBc8#zceL3Qj)v$E7fd;7P?^hDN6ch<3`KyXl_+AnEo!^}f1e>5HH2 z1Y7HuhS%<<{#N1Ryw#CL7rT0S(L$?;R5tFWEmrZiGG}*5bc|@KD1JrMKMoVUa}lkG z6Vb}Oy>uW>{Myn5K1s|t7w5LMDoe2equ4l*9gnxzG#v5cnFv zg`)~Q${99}D~Nq|IMEIfzWuiRC%J-a+zH;^K*O@_PoT(T7>B;hC{ob!LNE(1T^J&U z`Ezm@^j|K4#WyFjM-6WH8wzdPVv+PKFKrl5#Td7HLnSB}e8)@PP~q9{^CcLcP~{Du zVlVyXu@+0w#%5CYjlj%U8GAX}7>CML_5rzfvKrx~^`M(WMV}6H0iKWjr!at6C8-WR zSH5rmr&1M8Xm)Q%A;cpPqvWZya~QbyIvpD(hBdPRSSj_Tz~N%Pa$2J`!$oiZ^^U@2 zsLwn?D?m8Y2>piB;o?Q*Esds(z-nM^LmeGpDcpf$bjQ6BSP2bykIF}gE=rg8=*|ey zTk+jRT}Fylau!VIZaHzj*1zBL5c{{-(Wr}MC5$`a=8dvs*17>Qjb^EmMwf+4IN zC#=pDXwE|2VRjsJ7bev-TLO%p8-G@7oja0QY)UZA#>DUG}I zcm~`HI4eTjAA%Zrut2s4fj}FPei640a;$>wNH=V`0a_v6xmVb@1^%nv7U#Iz0dQa9 zz{^&ov#x=B9kti-=N%l@f42wgE4-)gr-jPRu9qRMOARWfJ3XReyzz$3nMs%`k5V2U zY3@kn74fQI11b@Y_Uj-7tk`jckf`E*D`P+TOt-7hPq8J5uT`NOgm{xezPNOCZ7yl4l>iB9?(8e;X(zyB@ zY^ymfnk-tSJ*)%^iwJZ};WNDF>Ie5TKdm#60+9zBp;tDlu;PZf3>7GRPWQ2?=1Q~z zELV~b$b+$Tyv$hKzzm4wtmjc#%$*Dq2v}YaXPV+3QGt=BAVd5MMynXm9e`|ofn5Ao zMJq63Dgnop1Mf`{u||}BF09<*ppMO;<~Z7|{IbN4)1EnByt@uhOh_zmJjX_-Y4xqgt`^dj$G0HSJL! zVre~9tnKs_sJ{5k2h^ABsHqKOwV1~zBs7oDpg3uPelrJ)&(3I}aS^GP)`?r&Xn=4t#Rm{0xg}uA6zMpB^TB&5Misw@;ho1R8l_u9=Yga+iiz>*hse$`Pl~`1T=zen z)Tm*nm4ovJVRHr4x6O~KJ7&h^x%j_-zFc=3DCRa|J-x?xLS@$5%VWelO2s#JfImb4`>#p@x{6joGt@X0maTL$72LZ3uI4erik zkXx4tq)h!VP&oBdOszCK*_e8=D)lg)$s(HzED>HW+k*d{+~)QsiJGIia7=iO501tIe6zNyezi&;XMd} zt=I$OL}5MM1)VHCq~bhRjw$P-5$#SDz8$88=@V1b-W7w-BsPZV60PI=> zTupG19i#JAym4URCbFd6>?h?UMoHaQJNh>r({_WbkG}=CG&G_)DtOzexi(myg?kB` zYrRo<3GPf!Zf8R$HeVc#2!%L)72}q_@zVWDe=tECqXl^>O|U=+h>`|?3GnR@#{WkV z3cWHzm;(v`Xl>2DRYCgvng2Oc$4`sjPJ3pE#UYuF|1DAAtfnk=VKeB9s1nM6^N6_L zf2Nqwp$3&`U>^nNqMczsvLX;iG=7mt;|V*r3!g6a(Y~Uxnb1I3WL?$IuHm0I58RV* z|IRl|oD%HCoeIfymI#plq_(p}nmN>YMh?Q>6dK@bC7->>2Eel zF9(iHl$><}%UinnlxRIL&OxR%4l+f7OdJacs_MVcrZA~%_1*pIVL)91)IP91O!)0V zaWKM>KpuRIa3oN;yVCC2A~fxf`{g)2N`#uc^K8tSzBAjhQ1n)3#$s z@#2q18c%QBGo|<@eaTiVZ|%#z2%z>K98Rcb)*tZf&%>$@WiVVgxEQ0j`_@LV`b}t{ zY2=SM9{|{ifQ6n>IN?JV#4%=B-}$c0p_3htd!%V3q~ic08RZRzn*yHCsWILSe3!Ia2{5lkJF-g*j=c^ z@OT$(zUbtvrL;tcK!&}7VZ=D!U2F{8!I^m1=x-hslP z7!>8Bg$<*R^QWLvS=Vg|odLt0`2*k}$RE;P$Ad}~UIT}NLq0(A)?#CGx&;SY~T33t?P)M*a&$B#ZK_e{hu}4O}QJJTpf=0C{QtLgDAZLm2;F zL=JXGyp&f@PoH)1rdU6`W<@d)6DBK(y}C36?)23>X!Rmv z`CaRo&Ze+MP(GNrxTXw87#E37gYhrb8@HsPq=P7l2PSt{4D`2TGwRPggj>|iNN1l2 zEb<`-;OyV&1pc+%16h)b zUggD_N1F+8#+;99o|X#V&dVU7 za@(=g^407BfgfrGty<{iUK^ z=YGJ;Q{Z=Z8GoSGbtXT9wBb-dxSHMP86(fW&?vtM;dexzwEiq1^;-jiwDBk}H&7}* zs9ylX+M~Y~&FT6bw*J}(PKPsBNgN+a;dEcEBd6Zi1rkGb?sv{XR(R zhwrR9@q1sqbL3M6RYkStX!AmKaa#xN1i=1U7XTOvg}>JMU%-f-&aem?U8=jq_-d_@ z&R2Ueaa#QgHb|Smuq_bUq9x-E)P_;#XGQC_9so0XE>LsFyB?F@&gpqtMM-!THo zxw;zcuU+obP&n?V#XB#ij2Qyi0GFt5QTS?KKZNtuzWNW`V4D0Ky8(b_x5H))2Ec;$ zIk9B&y{8RgupGV^gjmJsXznQ{rePuR(pI7RhLz1n>oeErl~Nz6czU>zHxchl%-0%K z0K)uv;Tt>_(<1h2y9G3rdhoHi-p!qRuq5ZH_Ek!MUU<5s0t>U+2zu*ztYN(!w0j<7 zjtwZ7zp_VTHOynv88_pGLB8+`nCG#=jqqJUTmDA&JNQk18xhbkA3(9l9`4A~0H4C+ zy}*{R3-IFs$C^wEw6`QUXjufp^cZIZ)3lRFScn97oMp2>w9IiF9_)kfHXvq%P7qT( zX+*waR4fJv8&(f&v-aMMNf}yWsxg0NH^Yj88^C!pPq=lhRSq7UhJ9qK7}%+ zA#~&g(X{UfN15-TOlTC@4SBiYaV+xJVZROyJc#_^$X|r~OsqEmyJea1p2{%W;1JM= zI9`C;;edl?m~F-)zcEqEVY$i#kxZ}Sk|;+$?y{!H_nIRg7M9tx5CuHNfUm*hq!HlV zx1=1_P%x=w5B(4Ic{VV;VVF~x`?$w`0X!G59Czi z5{JwP)svHWi(N`>)mP}Phg+r|d74X4PtnQYNuC$;Z@58{$n z9uF(UxVY!CBGWn4MKzNtANXFx;myC&ggYDuU2I~2cgtX7rEsY!{65#n`fZOEnr0Jz zELO8xrL#HIV+Ez-OE)G2>c@5BuS>L29Yx17#cOUL zRO&#(iGi1mI2@ZLJZ0?ZWrbFX~f$fm5SBa@ILcgpQn-sY{9a}42 ziMidyScl^(QTVE?s`l%OX$U@7&mi(sI@+?dVUq_66LU5XGj=6ow+b#2!2(|u;epvd zKh|tMyB7Y^!+AbVM{D`ptaW#BI5MJ`PQEI7oAZ)&!!+h~FYRseUMDX1`Y@&Obnm6z z0?5y79fkcr46_GctjOTK0B6jxyl@NDx>M)%A~dEOKEM4h6yDmmK=BJuT*OVG3~IP5 zdTUE?W+hBVW0*lQuxA@g_VvPdWC%V#P&}{C#y)$RV!GL@nPkuV){sULx6l^yk zj|RB+9B{n%!*&(crT9F}ZoMi&bbW(xY5wz@xWf|w&Rgl94Iy{nMr^oDrd}Jto8Qs2jaYqz)AEgCEP{EQ z-Y7b`q1k0%w|q$J_?G$sw@spr7aGZ5nJ}rX_`to0I!^AJL@3SMB%IrJO2Pz*iY#^z zrvWw&*xZj;>mpmjZ+uSIyCp`Rk2eXI29!MAq((BzCQcs^2vy)+g78M6ds^68h2(rVz|50|8a zW01Dcfmec609?>gRQW)P^`OT5hxZ2ZB{_JI z$ybYJd!xyDfZ;r|sPh)#<&G3~1W=K}YS!Y{Xu=lpo3n%r-E_-0iAW&@+O30Yda|>` zaavAbi_>(NM1%;nIGt(*e*rc%8)oDh$ae0-h=Smf4R4C2irc?Fr{o5c=QeRc=wH(@gE{2| z)BSB?O~1TgJ>b&wIY!WiJZu<-nC~<%=i}C)70$GTQ>r=R91B6StWTJOx*mgL;;`!os_=*59aEEwCu@Y_EA!fENaEmV4oIPc43r!2#dh(S=PG161u91MXev^R4_rOB!<`v zF~CagMhqstlqr9rRJUjgt$0t&@z@81>oO$w-E!-Y+~w9yw>Hwf_e8Ir50U6fYI2A@ z6%*WQAmNk1UUI9Dws<~^RrJGZg5DL$AvAZF7%^o9utq;%PkSHj6G#vV8TdwrXBuVT zWqAP*v*b$x;w4B=b);va*4*}TFN|3HCL?_=(n~jz$8OPGt#Y^%Yv~6lVK@9Yi+IhE zX9=}ufFRg<%Xt|m-FL%JVlmo-XKWa11i2Pf3oI!ph2fK|q4sc4xf<}SB7&G67w}xL zkSh-#H^*DOEsF8?n`w8{m3qRoRHd6n+VvK=J2IUlVas@hh+g_3GS_lkZ;pi#X@rs=~7GaE3 zulBkbFFWEWUf+;rB zYN5Fwiy$}s9~YktTX6xt(#N8uQnsFsd@K@LKea(O)K@pYRSn&yXDWkBrcQli>Ty`S zu3WIwKh?sAemX3UJMaR8@upZUB^5{DCZpixL8)jfE8*)Ys$85=GNS20xfsz*LIem& z@}{vBVtc@?SK;x9KGSzB5OILr&sdCK+&~_c=!I?TD7q5V`SMkoSt$~fj16?CQXEin zUM*StDZVSOt)u+U#RBExdh$3b7C22>S5MQA3V*Vhz1&K69mOdP=cVhJP+n16%+0*$ z!Z8u#IS^8viIayaXD~S~T1fpuv{fqB>n#(!(=IiG$*Qy;V%fH8;YIVl5ThgVfQf|< z+XJryB+h|H23arRmjXOLd?6y8ie{El)8nGrZd zVRQ4FHO$CT9fptwLKI6XcaQ`x#J>sKy;AR+7{xQ5qO;m1CsS1YixuyF z@d_SAhhEq^M?zanZ@7MXjRd z-->~O5Gn9#59`e$s5&2(CszMhHM_N%=6oyKrd2UOx*VYc*a5(2_};_Z#^00VmiqU# z_|9h^EI`7l8{bZK&54~ue6%n*QisW47>LIj6y+2iY0pI}AIYdi@hy`( z(5wq$TEu%V8y91og>Nu3(REP8iZgUE4s>0u5%l8)F+y=#L($)XB@VnyQ@(@H+VL`N z{Z8)!8y)%%^c}RC0=^ghob_5nBir=vg0>%hr7rMV5`$VW@Y>GDW)D%0`jOlp2zgpDprMAs)lgNTJ7DX_M+*Ftml1Xq5M z4#!% zZZ;;1pY|*wzz?`5f}=6$^s;Ikv(RN5E-vi|(x5Chn}#EU1Tv)}14{s2JO|sT|2;9= zIh$E7Jgyz>y(cWDZ2!b|bmpEIts0f<)YhKzF?GBzzIHAOXW}QiQj5PuyjS*&*vR80 z=%XdKmY;D(%6=uPWY*texk=4HZMfHBa!s3mGnXk@%W0o%o~YQ`k*b*6DxoVVS~2&I zbX!qRA3&r10FztSe~j1#98BDpUn|~qUcvl+-Xo0mE9NBut(F^%0;6^D^EklcYqDXB z(oegvoMN5K;Q_vm^it?FoSv~_#Tj0LG_lbNC$ldXPfq63%K4XQj>)`1$!J${-(>y* zvu}I)ys3Eyo+VE=Gq09$gs#rn+)nl{Y3X9FR-Cd^bLpOH4s*(m4=M=}=AllW5tuu; zbJHQ^SZ7SJv@dzFg?XofD<@lem|u}gXtxJY?4qwd%w6SeWcI{kBgJ@{N69P5?r9!? zmDy>2;3^$2^BZyx+U;d-jjgbAUgiinlIr*oNWtFb#}K+`gtxh!VmeC8yv0c@nh^Leg-W%nvKA#zX1$8J!F_`%o1_w4rN3K!x@N0|M>C zLvi|yRs@?n;~Ug!HZ_|_ZUXwNv~PVK{zuDTwZjHzqh3;79b2F z|1e;3qak=GrcY^E7%F?0cJkL>=xcslB$seJ&Qh;%Zr@cgI&%G=JZ7Zb(AHDd~-rn+9A+fi#N1O#u{; z5_(TTP*9Mnk0@!VD2h2!h9Z~{1PKa3gliNb1w=t5g7T=KBs39}B2t2Zyx%$Zrr`T~ zKkx64^VzdIv$K77c6N3)9L^9L9uAabdYOF*w1*w!iJd_5iU16Gir_pQq!%J=dE!u1 zAVRqUBjG~@MoPW7fg`0sFunCvB#O3;E<~cai>Pe}psb+Y9njoM>8TEg_ad$3z}fT- z`?BdiJ7XxSBb-4rsUu*0NMm0&s$?gUZg8L&Fuw>^wx)lu=#$ya3 zBBdAv&ZlyAvPg&pY$!b*3tw+q#Xd9DvExHgT@k^RCUpf2|ryhED@v+q+iRX*$KXN~M59T3IJF4o^Hl9y4; zn?(;&rIdEh&SLY3)@?cM4RfgQL)p`sktU54M2}gtx1VGc)hO%i{?dCw(4uGV)6P^& zJ>LQIH@YsvjD*?QA3GJ-()rI=yFDts;v~L36I%b$GBG8}I$)S|S>&I%5fbhne)bgJ zJ)>kVCm)I(BXw+3+U$2^$@=jb^uib^Kop{h#z@iZ9){~DMB{`U%%y(D;9dF+66f{p z&*>zOmHfqv)5$!RJ7F|U87n2YzxpIEoGlzy!IQLQthC&_WV-FrWCoTN+xE(<^z9im zaGVtATvLmZ6oA6)aZ-C#_cd?!5W0Sx6d~5mpsI1w3u5IA>N8#n6+f9lS>vVUed9rw zcP$~{=-F@_bFE=BI1iqs|9(2d2>z0jDz>lT*&rS>LHbZEe~NycAngz*JxR+aN<+l* zY4qzvDN@`yjT|RQ{l#(9X~-n0n^-uF@+V0P{iBg6@9~>%{W3omVzAVAoNjfWEbS1) zrPHldQzTIo=RIltB2yCEi1((_k!jLG@$^(mnJ)Da$4ZRVb+?t`1Z)S86YIno3va zO0&hh7@9IqG6kuiPz0OiT*bAh;`v}7GhMLqyIacdXVb=cQZF$#hEC0s?u$FJ>F4>< zM)8$wdSQWN78hk(w=BR&12OBhg;GC3{BIT|J}>nYzs$1EeO|gHIu~-`3qWA@BB`Uz zmz^I&?=F(Mt2!(bEB_``Ln=al`@ce~3t}kdMd^Hoj;phQ%qir?XyG_E89wR%zURg` z4q%?_=|VwLFsG$Kmle3^wr1vD+t}fZ%NlJZxiQvxFG&u9ElbJvU?fAYE|$U_3bzc4 zp`D8*Q-?<;W1C^GEz8};JrXmG=qDV7Q`GmssMxAk5hwCKPwoHX*DQ>9@6qnd-V~8xU56Fc*7RvZHlYOk4d z0!Q#2xSlZrq~8YfU@-hSE`~X8N;GhZ6rFG-))sEDhdVFrU%zy*q27cmg+mZ_Y)`*> z-i@c=f5eLe>Q{j7AN+8Z2URSQ>cwH*=(CrlZ7v>@AU?qkVbnyL^$G@Wk14d{74-1v zDfBb@gQk%Gt5TNOW(qBSReB&EnoNtANZ1>A!CI4yh=toQ)WfSHn|ODu+HqIDKSF)S}mJBWkrp*k&3Gj>=$ zS6btMPBw7THe*=X>G1IvY^FBT*#w+(xp6t#)c0_K!A^)p6F4Az2q_hW9FSPN9fu85 zTx^AN7KEx%I6jT)xkedKZ}MI1PZW-OPc!+U(W6z$QJ(K-xVt`%gIJl>KLJesP40bEQ} z1xMEMX)AF~ZK#xKeV&BD1q8_^lFR0i)xtI38g&uKkA~_aHJKebMG+YE7YiomN zAkr?B`ih|Aq+#^K?W|!%EE`AZ8ulEp=b(WzO^u`N8YbB{>4t{&_}X}id|R3&D75Nr zX`&lf(M}k@7{l%FWA?O?xB{FUXboBcnz?Z_n_c)<*j=kV{FL3_2-l0d5w139b}}EM z7VnIu#FgN#ppCy0JkwrUw-Ph_v9Wk61(^n6pH)&P|Dv(Bm8ckk=uH8zs022k0NPTC z6KVV^#-C;QhA#Z0jRH`yOWgAByi_No5$PhsY?+)CBA zv8~_6%6rx}AAC&1S4*DW?b7NW;n-NW(hw6J`uHpD(kSLTs3I1wmfAqeeD!MZNDdPy zpTM}I9Y`9$b(L0~o4y7HSXf?LyqCP!ph&03Q2H7S@)6@`?;3Q7lyP)#jnprvh6hI; zpIX?uffingj*rMZfOepUFn}Jy3FAIpg??|xdC%5gn{jxR;QktZ5dB`ygopVZ;H(?N z=M($3^@B)&&nLJa-8RzxwWzlRW9aHy>2XyjQjD&b&s`6-IcS{}?yQFv!1vrb=`r^t zTz2`S#Hg#4>guHE((6z_bWnM{^t1Tw7`nV3v)a$&$o!7fKjhMAPWKaih_KqJ-G;Yr zYA7DGsPG+qm~44R>Kbgz0BVD$of1@K_vsGC!kT#*p&T-%T z0XK>5NUW5D`Ky@_{Av+8) zYRu5;{~2B_|FF8)9A0aC-%rQMRa%AH-e$IiySIcJY;XPP;RZ*9=hzbnacDt;iK^xV za@|_~i`upP=X$jKSGczPhqP(=H?+!JtxHRIE?)3$Dwtc5q zUxrT$QigY{f9k&p%ble|-$icu$%uJ~M`XeNT@aw8a*C z!WLVsSGU-xY`43|wn%>Bz>#!$ixdnhE?dDtgp8z=t=P3}8AUU;N>(QRzBEX*#MA8e zCEqb+JWuH>k|iD@b-}zK-PTX}OaXmahgYH>^ZZi{oT=!tPXmV;2ELtqe1zUX3Jn>4 zP1S;b`t^P36>-E!nzl_cdDMJ-POwi*j-|!0)Hn?b!ZvA!*f^3LOZ9r|S&IGfwNqHD2`c40)B(80 ze+CX}+-0Yf(6N~iH;Yk7&>VpD1rWH#Th%B{-zohrew>aIZE3m(h=n7;nZVP4cYHWb z;w<}|+S8>nX%uz_)OVNEPkd`Qy|PQ%&i=TMuroI#SPMRqJ{7v+IbU`+h=v2;hQPM|A$q#(CSWEM5RCGsAsm&kvwlqyyv(3HK{SHsQO zE4>ZZ>S2|V1#$N<8vTisF8(}}N4H983T{T9IaCB$p3;N0BjxZvpb8v$pw`@=8j!Dmu}ZG+1>)z`Di z1Z(O(u#``18gifhY)t}5lz>EdSZ;bZkeCV*(93Ji0vDkG@TpMB`rGJe?gX3(z`^i& z2qzWUbm#)*QNTygu1n6r6nn_UfzF52@ zoEEGUU{(Wb!U1WlU9Ny;`|N-4`$J2A7wBN-JL94;$n%mOJucg)A5rc6m1=YY}0^1#zR&K<_$1X!C z{~PJHcy^HWg>R+3j-q8Sb^AeDCKdM3RzscX6u$96bmRwVs5CrQV{)hPZM9J3NhwsB z`zUlJcohZvWv~R%n3GbzXy|S|byAwqRusEi2h>W1&dz0>UbK`CMfjOZl7CxK=x+Vz zhP2tmx$ry8D%XT0>(&NoyZ}=1+J7m^P3|RZrKjBF!D7)PWOb9x?4EOzL)mq5xB27T<#7O0Cqeix7L-tv%7cwxM*grqKB*K`7!i0=aZ;weAE z=>&MmDeO-1l83On(@VY=USZZ)s{s;}(hNtmsv%0_cl()|2ME&mXjHHX)>!YQ)K zfpWP3U6NWl5+rYQt;CEXwp(-}EX0@Q1lL!%>-U>ElkOh#y{*_2G zLgX06Ssx-lF5)KL_y+1We>k*!dN=&gf+Hlbei%y%VB=aZZeNscKUJd(2kCj3{|z-=+){+bfAP;E<7<-Vqu2w-vdjOz61wOx%n@CYp#O+cUvL z!n0Vpm}{EK66Chr+_R(Q-X6`kEeXg)fh@8UF8%Ua9->x zcNXFG=qC5)EKTT!jt>&nZWyWXpR)Ut;xLiIzsT+$h{J>mzY>p;hq@mcFXPE!v=vN5 z&8NIL9KDpq%O*xS5iftlpsBOin3fJIN|5~+^jU)3FX)qQ%+0sh(#7~LHQ=eGTOP1D z9!o)q@=5VpEZt5-PK&}QEJ@zrurC%vsKL{=9Ew908B1*(KseR-k8%`eb%seUM z-0UNN$nUWBl_%SP$@XFbXjLq7lpw@X?_@a%jkq9Lo`9q1?~-L7uRDo?ZqWh^9}XIE zi4!w)EZt9*+lv|D6p$kO;a$jt6nQ8PkzY=cXA4zyD@BgOF?FX@xwG3lh@O#-bq#{g zymU)_IX#go$2hM;a1Mg0_H|c3lG0=++LtQ(`jjLIo)`#vSu*YNrEH{gB~|VReU`3i zvZr%KxV{HiN;gt59ZgM>I|dGD6|G4ug=o6*z&VT;W+U(33NN`8`G3;n$y}TX{cN-M zqJDCg2z9qJ{V=cjo{s@NiEJkY}(v;8A(3bD7={mI&+C zN97*`+@^kMpxjqDO`i{xgPhB(XetgI`Dolx?BSc zXBMYAH9|Y+!?w1)&F=x{P2gY_vz454!6ip7ZVtuF1Gm>O%s6nT48zQV6n74jUw~`v zJX~Jo$a*Ye_-)QPO5l(-a!%iaY zng|#)D%c0*lu2;f(i4*q*g$L9_lNbTN%FmRO3iyvZ0%^U;I+FpEQvTfLmq0{+rNHO z5?*f-EcH_i@|8STXSJOR9@cG>#)eV)OnI*BYRuFE&J0e9k#uaPY*7pKxd!(H&Z7FV zbA7GBPs=r;P(#;eVUqxh%(Lb7a5l}BqhfX3ItU!97&i}>M7h~Q3@fkN=B#;onU705MVnC<=)1A0r%-zp&VuGfuCSa{zxqFr4t&)UxBZ+QIqkYPJTyg zhZS-sWAH>@+l?Bdldn#2s%l)e`jU;{D8Oc~mc5Ka@$>3x6b*&mzFJOX_uOjmvdH#& z0$sR=NshPFU?WwC>MFZ|@5-}OR< zU<<88C@*E%Ao5wMJfxjy@grBO{8PXk#ij%b+rF6A1I(;H0&&psJU5&TTIEdVl`1zD zUTF(Sat@)TpU4eDob}~$d4OpCPZJNq)Ok)y_0t@1Vfz;Dt`$p$l`^^(%2j5_wch?r z9%yu(Z;wzQ`qQ8Ta-i|J4C_M&@TWx;HrJ_=d2fG;sg%177X5X}WHKVZgvd{{N`R}g1PM&VC9ocV z^E*p3TERI3se-?5fVL~(&rtE9b~qBRlqY&bAOlUhHEcZC1b<8wW+tS&y-NN)#uXW3 zn;0%^ivZhSC-`|w%pJNGk3JaTXSpQ94AOmTb+z1I;MlH*u=c>6c?k6}09ZvBD*f2S z-X;U8%Qw+9$?)Ud*}D~uHf7e{@ElD?3;iAIq8Lhj_s z8DWxb;J*8Xd_+Ve%sebdxqi{kHXIMaEjf$<0Klok@&@B^*ZZ{SOZoloHTpz@$%AVq z8#T+%GUJM@ZX9wDu1O9>4L;k%u-Ng8AT!}B`90&aAY(itn~W1sR~?RE9n$G>C)j#K zj!3Nsd>RNm2LgO4h!Z)7M9%kteis&y+O{l%4=B9`yfaW?Uf3!jZpvy9QjW^LWA)e^ zl8xA#d)s1vZI68lv5)>MHm8Kxn!_U)G{CC{{DoH38J>#z%Q=djc_j#N{T+b2%#O&} zWI$}d`$d)=8jI02zlTVt$e(`u9z@}K`~X@APx=8p1n$fq!0;e^*$>!2 z!`=D=Cf3XVns8Fy1_i)2|CK+3I&bBF<)i>-Z((IMl7XqW8VizP);0@ua1Q7mKVlyb zH}yx5hdcd8IXWlyy^ppIF zpB}1juMk>-SO?K$UWi2*p-!G2P4SvAI9}?{@-TlrUNP$ZEWXsN0Bs4_x*Kh-&+=N&GQOnG<<=3=$*WOY&z)kftSOXvrV@l+IVHFE)d)LX zc;;i#PQm{wDnBoez-z411^IxnM;lB57qGf5aKIXMK^_$_1wR>(fCay3*cSYvu&qgG z;e`xOxhR{24k|EspPOq_<1~wSM|?f#hz2mokan{QTuO+5+dSaPE*O!(Z}K?fCdBG| zN$%IB(1CSm_uCG@?5c2vv6dbghLFSz+<#aK#GJ*3ZBP!Yr(wQwd-~*(+|hSFf?1ih z^_7U(AVoD7oqet9@3JcRgagM463=~MsOMGKh=nq%wk;)Hmd832K3&}2y5h1t2{J)s z>gE->yIa}3e7^kcQQGEd+^Kej8qp(v$g#$+0H6Jb+}>CgnoG<7kfTP_9B2rh6FRJa zeG2&DOSm!=++djVK3qpn#}P#Z25l*%tA`(H!rI(C8>Ic&oS7hvRXB4UM;i3%6;G$>)w>i=C-g=2J_?tsHWF3* z|E%6s{p&yCo`D|wQ1yOA`>)C-rRHyFi!>efW$mS_S7jgGZCsN_g%@&16*EG#b6^?I zga5q%Hi!B5lt^C0y-VkyggMtRINZ=5-sPXR_&LBo0)Ec$PrV4<^BRV4MKE=^js>eW zm_}TeqkJ-eQH0{@ZIf-(1W1K8g@h1Y$Ef&00G;dd3yvT6ukTSELVa&Q5`~VMa|7(+ z?;yGJhP)7KS>#`GH)R%(S-y`}yl%+tP1FAZ%hX-GZ{7VDPE?En)4C~lHI76*+`Ngs z#5N=y{5LZ91AhAcEkEUu4;(7o?dVOj{+1o-%fIEZ#`g{PtzoyY)QT0IY04c43*dfs z2StGU+a0XiFd=(a?&-vXx-|J~nsrwmW%HQ6rXzRdXxB7mL^0JCAcnDC?&pz;fC|j0 zypImW%%2UwgnGG?G`6GQX@K$$&nAaStCypVWkRmCsvZYN9)s+$Of21C4kWJ&UAZSu zRmxb;$DrDDex~Bs?H|Z$@PhF_^19H=4;s+@TC@>Xpu5&X8L+9bv!P?qAkPE(g9dq; z_jVl}7sm0fTGNH`w;#|8_hoZSuCe~`%${wDBI|wmafi;04K`W0HT;3xUGV5{&uAX@ zu_9QBY9P*Tl!trtYXx8)ssw-&jdH0pzdzK5r<}y(TW0xS)$2-t*OvqI5FX+TDF7tn zomHPIcSOY5Ehs%8@cL6w!rAK~DwElrXLnDCO3EaQk9M`8fuP}=z#A6vgH)U`ilt5S zG`C4!ZIpHaI3f}W!O_plz}tkZ@bG*EW4{ubJij!-aYOV~z&ZZeFKMn(*~&= zj>4qNnx+H626Fdga@^3V#WA$oSy^DrLZqR-av(k0R`C_r{6kr76|G$jzfQzT-PK68 zv8}QX>S2hTjL=QY@F4W4ixLv6hZf-AiXoxs#A#3mI911HEVfUEMf zjg|?WB?~c_7P%^Ewon0~`3Pm)E3OJF1tMLfKtAo17rk{~W=l++37tb5T$PUWT|33w zhLGGsM8EVok#4vuK`o@hB;`e0a&^oV+cU9KQqpYkD-mkXgcjZr!uWs1kCB_=SEATW z@jsKB3Q>&Era~x6>q7KWnhKHElCl;a1p{1otxxfyPv=T1Ehi60x~nMtM3lR)s>~A6 zT02!Gh25K~vOlyqMw{9ViiUR^sRA`U*k02D4`UE60Nx2Vr9a0Ha96N*h@qkGNYVC#!M3f+uCvwZqw$rxFg4vF52H`Ru>jVA~X9 zn_DL`%Y$p*AwB7gr{dRkR(*rM<$jq2FQrQ?4lNms1qRo%eas{44EnRW7^5}$;8XG} z55ou3BrhdI%!s8NFU4B~QSwq=7mK=5n76V(9C(-3c`Ih|pS$#hw-V=U>4rNI-lg|R z@KHQ-psCLSk#m@=&x3*fxz@0<2=9n*lMizQ`Wba)3%rWq^^Ngd>$qW3@5Tsubu9>=(tAEih>*u5iTR{VAI7j=&U5uSoFKDa7>jQnx!p)N5uceyG?I>20C+NRdBR8ww&8UH9_!L$ z-e;WH^d^K7ATNQk&fmyPCm^vhJ!XLB1bMrWjrKj~r%b|i#bke_C+-g+(1aAuVtO#5 z{LB26z_zX^0vDxa>b5765LQTkzFobD0K}~eEj^ePvop z_2L`v9{SrNqbM^_3C2Cgyg;Q_&TiPB)i)k^kLpo-88{Jpy=ezsZHa^;5jM`%R8AcS z8(S{t5*$DI1J0Kdn(C>E#yP+bBBSnr9{{{nC2PQ;UO`HfkWa&d6%TqbNb#YeF-jY^ zO5`8~J3lVw!9;AINejjtwm(RDo3AkjD`p+fRcOJpE(-=w%!s34laj@5fk_#{?g^8! z%fa=wjqM18a?SDnx2QB!*(qk?YC@QDkCDcNE63UG9HAUx_fCZJGV=9Or1E!EZoC!_ z2@y_C)A#*ltLvkG+vX(cS=)8@;)U!&O#L@)?4Ts}`sZeYZhWSw9d>c{Uij(h}b zFB(CISBCKX(;oAWH|8gQ^Gme0qY@zeOnW*iss10?^N@?%1E}`GHJBPI(F7mdw7Pdv zQUqMy9A#EYp+bg&2^c5b=GnQ(Kxd_2z~BI3WeBd!b6Twts(~=Ov!dbYC83M5I=*nw zevAN6$ir&KyY+(ncvwNqO`mr6DG(>i!RDTAzzjyae27eKT5#ww1Y(b8M%3G+GIP+8oMJ zfCAo(R=VO+bwrF}wxQ;=s-7t^0QM%W8JKA=IoI9M7%YZxhsG+A>^>K({HN0eU;XS< zH*aQu@vX8O4f+d(xoz>Ff^MF%U=!DR2Ri9 zX=x7NAUvtKs}exnyD5H*Kcbs5+^qTwx&`wnaDSX!Dw5Mp`(VFpOU|=2;f>(Cj{fv* zH)Wc5<_0CkDIGZelsILfSd>8jjZ+@S{w5+`d0JGv(u#N`SvW>N#4FkElR=HAo2IL4 z<8RQw1msq`PKy(iQyhCjqVl1TMs1Un2@WSN8a!7gDD7!UlA`(_zTQ9?L6-VMa9b0p zyiPlk6x_YIMz42Q=8C(nSs!#)A_b4IrdfA@!Up$NO zWUxK(D=Eq*_U}$Xp@IKf3R-#>!c&z{hR3ms@G+@Mpm^+0T9~RVV*Hz_N>2`tNkbK% zO|))JQ#J_*uny|4z(AA7AGC0QlIon<14G)w{0&tOP<$iml3Fo4zUCFhN!t70Lw1IZ z3Z@UN#a^W!{y`50C}BC3wurkg+2)EU-0?G`+{}k`f}5P#{UK6urtaEukg5egW8+2G z!l;Lxuktm&3YY<~I3#liJWaHnC*fJH66Stv{Fkr!CE!(nr^$(71Uw1M2z7Za2n!ei zOie7qVK#^1!loAZGYr4m7~hrQ=o$<+RkgsMVECQJ_-+gjwZW6cUdurD>q0r-Bo35##u^N!SOXWN02ewyCl=9UZLrB}E*!wc(q$8b=~adgR!DMP7i& zxqmmtceY2)OzuMgk1Kv2ZuZC$tbFRJA%_DVSHg4jG>Y?jX>Rs1y@4+BD$0a0ro%Eb z9?@Lvus;wx7qCb>tkTk3GumNKV;TAnU>)r+!PHx8m|&}?H*PnMoC{bN!19XwXt(X* zU*D4&N3y^leX=GQW*zQ4-n6OVLzEQeX^Okkpdm`Ut)=qpp{WRcYl!ket59Yzi-0>+ zS=tgBiclkP&kf~WNq6!YrX-5M8Vc9HsJphgS8n?Aml}y*?ZpI9qfhmKzdH=vKis3k zz%{^)8IIu%_r!1vW4L$h{`KiLdMDDA%Lum~7@9|bWp8=%#V&qBfe4!AnLK#5a!c_O44b1u`YiI{{YT%y$z zl}2H&b@e1=iy$Ukq&`y=Z}$<1?-^pdFvr&+AjX+CMd7=O8>e9UH(sCWpDdHW1~mQUht+ z5+%TV;1pfFOO!~X===+bOO^hP z{=YQ%3_n9dmMWpnr$L+dM^x0q`FZR0rOF7SqThYx2T^Vs9ZH3dt?6$lSBz+{K84_2 z9SVO!ZuYHG!mW2Trm2`HGt_52Gcj!7a7+mW*= z`T(ZH6W`D)a7Q2hrojiM;>;|QGeKOmsg0p9&0^B1Qh7dF00-&- zONrdWO$Jd*nU#B-Pa>9-1!zZ)H9(sM0x^{AJ(O$)lz-|CJ3gvcr2T4p~VN4 z0x{3iYCNRC+Qj6qY2X*iXrse74XdW8Ui8Tq%p-czi7%A70`AfuRb&sd-FU66MFLL)^1 zhI63nQ1ZE+H#|ryddXN{u?t5qfW>mscfVGq1e6tp8Om=$JY0l>6q7;HL>Nq6Qs}N3 zzM;9_D3byTbKeNMYpQ@X2t35P3CcihFL85?yLR?#y8MljKm(2|?j92d)SJ*t&l;V; zb2*lN32Ot~B3#)1R*9l3$CUsF-Fue3gK8B2HnqAx`q;z% z7uY}L2PF4=YQ4$g)tub)=H&hbSZq%YxJ7?ZP>nL6js9z$QKR$~9MAVduDxjIcgpyt zf91F`(6J2R6<##uxDwg)zwEdY-KGL$Fs&a48QZVR38k;&d1S`mO+!xr+y1}k1h5U> zT2TY-I00H-kfwGo&R3x{ZK&K4@#6{p^fZwKY*L=sI8?f*>88$43ADA{;EIa*ssD2ls=9p@C-pq(p@N|B>mVpOj7i zA3PrrrG-B$=Kl>|74ZJ&!av&op~AD>lmBPo|AqSjgbDwv!l(7O75>!!rtoR>(J5uT z`1lc$Pb=M=zyFFC2_G}5+ugd*{L@NjwQyy=ug3dtF*o;kW`!^9JgtO`ENrsTn}=Nj zL#9vBC9#DgD{zz8Ng-LEJMaJ8@mMkM}(FlpM8v%8s@b$TS=zKV;{q|R7xr^&5?D`<@gkgL_0^VsVRb*N7)59~lFxa??4RPNrS-(tsk)K){kGAlJT7=Ov>_*)$BG2^E#R?! z<7el=iy+<=xZrjDFDT}KPWxF#>Q#FGuuTF3(K!}(&(dUzKTWxygu0>F2M0kd5cIj& z&+etSFDPUDa{aX`crPVjm*Z=gQ~3|?t^7-C4wHCM!Q<>bwNQXhGT6Z|C$GM7q`|P{ z_~e5$@S@U32%*<5D$~X52kEbiN+>McdHtp&DL)--Ae;o~>1RR*Yr=2Hf1W?R^_yZ6 zeGk${zd=R~72)5&`JS$(^h?SX$61JjJUzIiquDr|2W5PhnysXTOgIuT?uFIlPXg-ZPTiHl#JQq9p7C2hO;M`+(n1eO}#oLqOubs~Ir<;E&k4JY$ z_shKxJG{|&&LSxHIBQoPsBRz^PlH=KLx&)K0TT^&Jfq6IEb0)=x~iDtAVAPFCm{Rrn@R7Oc*D4zEf}g=Nt`)or)s~IEbo45OP`EUGRT=1z2sl};fr;YIc1`Id8V}Jc z*OW+C6Cl5WMG1lCob{UWvRHnQ`dn9n#BUDLN65L3UbzXHc-NIl;wuNqAe%aLB)bB@GzAA(lKD`MsZCzfWwHXZz|82uSWE&DSg4O)JVWknjo z4G3c)*~ShAw@h0%MXCEN>wS=-|5AK-01WsGSwR-2+uc|H!nV}=ARYNj363waCEd=R zBp>O1Rw82J2`Ihs8Qy``vk*|4X3Q;Tli?)sJ< zf*XQnJ^>|3fBZLfH?DUU;guju2W}!uaL?St0pAfc92fURn)8?9$vO4;TiL=x_`u&v zg6x5;@#MneR6R)IEo^nGD#?6HS;4vFic@jiR} zZahE2JSFq+FCsg*ffCQ8>QI{JIje0936M=;8uBO=pj|f)VNiWxd6XX3t11BRR|J$k zQ%Q?&E1{tdfESIh)Qjwn!K)&0ouP$PI-46Sz}$8ZRozzl@-=x z$23iOo?0}*V0>*vJWKx=G1(NTbwXf~t095gLQh->)WQ+Q;wPR*IIJ==Pzy#_#_dK_ zkVomh3R^)xWfukgq=Js$QF@8BP`ACS^m8XWe3c!(qJpN~RaWOb1OGGVMyF5!n{>(( zcD@6(!wAo~(iqR8A*P>~7pPSs3{tEF_zq6)>(V%TL3fd*311+k@2urM>pX-$f=Ng_N3u*(&>7LT%(X!ok z^BgP&c@_6A_LK-3+biJ7=N~X|ApaT_X!y7e1@eU!%b#fXT=qwkh$L6Hp?*QWG>s$5qg`_Y|$Ko|#M@2FO%N5gvhn z6wn*f)aRc!>T2F!qgWZd7s3~Dwo(5-j4Q zekIrT{swAHHGcOSE|xU0f;UHq+rR;o{f!dbngGF3w!^keZ~+YvRouR2SP4Op|9z!* zT#ev@*OfAYG3xzFx4=%udohOkgGe7Me%Tg0MYT1C$BM-+tZ2r%CnvIA|~65cn(Embx%I&a^NDu@|6dQQxt}??E^IHffA(@>hj(U zPb~#VF8itUfik39w#Z!)=HV?qdiYHnChMz_JZEqakeqdLI;JH)8=RYQ0O5ZJr}m`fjuYI{dpC><~&9-u`}(_b9V_S?q+ z@#bTHQybhIFVPmy7D_uE5D(CzcslEVc(&i@HtM{Nx&7;lw;Mb~v}Owa$LutCVz+^N z8U5?;ePr-ttwa<4m(o{l)B)nt`^eo<{WU0lpH0NVouVuL`3Nb)$>7FEN>Terc2Y-+ zKKrcGoYW0sud)mg`*E~8udHEVCT%JXzj11v?)j-r`Vs~T226z}xZJeCy6amSxR3g{ zsMEw=s96_vv1r{#k*?|&;_si+Raf;fSBT7P9T#?~QrfA>!Fo!?NQt$@N=zo*&&haAr|Y zf@f0H9>&7lEGkvhFqjwqR#7{{xu>WDOxzUF`eVH5OA&)Px7lOa4KN=>PJb+?ELF|v z526mZftm>vRw;QUi)|#eDLw4zvFvwfeEojAanA)~+tPi2aiu+p0%9T3v(Fg=ua#~z znW%%C8YG69Xn>m<=raOHV7eYcN<|qLF%sPMcK0(k)!!{7SQ9Z$fB&R`#vqYp<#f?a z9mL)8rT1-Pk!|PkJ8{pQZln=7%H)6FPbuA94HH95^qjkDZWm(Gmc&C}z}iTcD6^{* zZtb|MBgNm!$=gFUi@EzK#Y64D=rcXkXM{!clZR??KqC7n&{G{GzFkf;Jk_{J)Y^F* z7|aEoqFzucDsP}1N4%(tc3{n}6nyC9RP70(Aa>0YC4#GX*@_=ycZYhZYsGHmblFSo zDIWfeBE4;i5A{}iVkUasTb%&sqPLpFv4efoXtCBrLw(dx_RsTCBSlo|didQ?vdxb| z7iDiFK_A-3?GyUeM@$kqDm(Z?I z-!1^_98$REr{YN(jw_%Gq!-|?#>PHOk;lW6Xkt)YgVcLr{%wlIDQ2TC7Wu22 zAC6VRoeJ0KzunVF*@y)O`XQ>-=mSFoRNs~yFs)S3dM-fiXbWx1Z2@q1J`~EAo{hl$ zEkG^m-dw6`F8fs5$eoXL`Qcp!M!cMme$v0vKL?rz+N%|wg)0UaV2;(kmE!UMvLaCJ z@^BuwgC7e-i@IBBMvyuwM=wn=@HZhZ)o3B!I-dWSQ}rmdLRpcG=KqD1!Sglao<&WU z05@%LZu(Eay#+Y&t9`j~n~sQ%(xRvI0ln%fQrK5vWel5pM4gK7^c4%VUw zwYMlZ(61fTZtm}c05?gK%EIQ4DYPRJUi&c(>8K9DI|&;)s$+!lbgQG<3kLJMc2cjw zJiE!PdIV(ewj~a|ypM7IbDeiK+$32l4(rTnUQjHE^9_U?)iB2d-CCRc8czvA1AfD9 zx@uNONo73m7eSfd)74N0%NeSt{|V6LJgvY@J`dcI$Z#K0ZZX_V(stA0&g$?sWj=g$ z;``33#T*00=O6Ww}~uAK`z6F6o6d&Ow-l z8)U~}=^D5}9j5^08Ph{e2+RA(mcJ(b?It4n)QyC)fw;4W+TNjtqa5p@_6W{GloEwm zc_ZFcs?xO@Thr~(Q|+SYX3px34*E7B{9|iYPt{R~a6we=mY&aH(P?8SD}7GiwPPdL zzrM48JKciom164p7gV8xo>d*Gte2{WdhTQnp+(gmW4H`s*vw-X4~v=$Ao%H}RtD<@ z%S7F#V919Rpl-Y6ra$wcZRy{*m#Q976Yw4&YOx6^6|LmdTa6Oq$|$inR**M$(d6D3 zE^qI!zR+7OaNuTaOjaYrupJbcqIUMmhnbFq-1Igd@Wkb7=68~3en`_&z)N6_N>OKs zaUWW5r>L*Akq_KD3xJJ-)HI|n6h;~VC;amvOUH8vbv1*^c1 zse9t|WU@h?_ZW4^L>B7F0n_juqlfv{HrrI}fZTGf`_IF16CSo4sPY?h$TdgcT%%%1 z8H74BZMXIrr2ZtbI*4y+oh6ilhp5lwxRqjGR@)fw25zP)p2+c#@aAFq9l7*t?>Evt zR2>90=AYrB(>3F6LebFaw5eFZIiu%+%Ne}NB9c~kRme{&8hPqtHoTv0c;q@%RfjcG ztKy0RHHRU#l)nYmPoRXM*o?y|mH=mo9p?~mYJh`2t>bXVpE(qhc3>%O9IEaYf7(Wq zhp8#fOHfqq1ytzn7D8VR(?>0x8ivi0CDhtsxGEZX-sn6M^9tNSBQal~_7;uA`~d&E zBh`G@x(F>C-E{a?+$I=S;@+Mf9i{p?BlKVwjCM*Mtp?N5QK}@Sgb|HGPt1Ft_K#8{ z{b!=pw_vZCD|#*4ihXAt4#xPLG!00}AxMFmSEPUC>`6nN!rU@y(&!yNzhEG>lr_Ty5Trp@W!h zTgBA3dUX-jJ5$ur&}4&|l1%jl@oWSg%~bn`)<$TXEzoyCL_Q8d=hTUt?5$A3t&pXT zf|BiPS!xDHzmkQ0;JFAIk&V6tGS6kJ{nQ~PkLOE4hYme{iEVNW%WYX}ojHt@2isk1oViD~FbNN&P(bY=J#O;?`~z;8`g zbD3QBlWLU54G1E*qBuST4e4P3lsu^}fEKdfQ)-H_28}=YDRos&O?FZL`ZwM-c%lt! zQt+R$+TdA%e*^w6tTlL6;@^b-d20-w)%ef;dO&?{6F&YEoAB}fQxiV^r#Inu>{ma( z2_OGv;OlhWNUNXqc4vFS@Pq?U2QE-g9DensR(?cmM;m6SjZk3SFcTAe7pjC4(0`|4 zrKO=U;hMd?e9?u=d#yS^;iH=z;L>;Kn)iW!)Kw|yMs?LPjl@{pSGI^5KiERb1U-sAYXtoE?TGt z3YoNaA=snjBHF)DjU3&%q=7!bLo`JLEcK^mbh#T>1b#IYdNubNKi<(7yG2YKXN_{{ zjsb@H5a5;pF9wyl3vpNkvJ2rcGh(~fA>QiAhWcFK|5`*npHnZ2m)@n&=dlq*K4(9# zb_#w4IAAVxgWC^88=q5$;-~N$aIPa+pI4zU$6b^|^?d3YUE7gz7Gat@^e$~&q(<0CF_de?2vR2&sTt0C0tLYB^`bhg1&2#}4x#H` zRB<(o%f&G{6D0_}_M$pT+^~^`yad)nhgRC@GSvE#+9kFnly%2zJL+b@{6VKZip*OB z-iy3~vov-)qCD>&aWhf;Vl}KKOH&rBm14(@6q=*LXgz1b#L0kQHIm86QN#UPLXov| zbse>XXpj%zVXpedb~%7@E1jI%a}zej=Eg@eYT>}!06Z!a+XYedVkbum$yH6EAd!aF zdyPpTLAK}o2cmPrTqoQF*|}~?Jn z_RO&4^(VWd@f;=%&sYC(ce8a^$iux#L&54m4mG(z?Is$ESTiqxJ}kfpt);pGHQ4_= zDrf0rOL<$t*Y&l@hH~EKa-8Ft6tqF&EyH?k<}2Dg?ELckRi-BNS5It7>rId5~B-!=CI6Te92jN#{}E zQpiB3Z=h*Qk?0fFHj3kAp?Z@r;T z7vJ1KliyVPc)hd%J>a;Z+?F|SJ>zfCt~b>fA(!gjgg_{31Gy{*mwj$MEnKcH7m}=P z-cnB)-M(CBE0V3KUZs!FjknbLA{;uTZ-=1g^y-vI3J71lzV?mzAjQTWhG# zN-+IDuc7hmo>)T*IXr(Ym9E6HnzoMqTB*L^J{-|oZ;c;cYhAob?Iws0>*=G_*!%Ba zOP5!p7i?Ke14%tAzPFB|*I>c?ZXFF-gN1h<;W-G%47}G_{nx5L34t{N6z2Fm#$<5S z422QedK80IsH14s=ed;7`p^ zA1e>TVedhBa;H94K58}Xe@E??UBg(6&09zPwl=m$P*o?c?|B)ImB-<-z>oMhOn}uHbo?8KZU+p8E2j2_5z}xR{arQ6xv&dnu(p+*XvMqgqYj0lr3;;T7kzRs zxfiKJL#w**nNWHzl7yAq_+j{mqMr{|$HG0Sf>xE?g$jz)6fqZ%ZWclAx~U5pi!rb5 zT}3^M)tO=u9>pzI4+$~!%qEQOQPjIceO|2VLe>)WW8AI}*bE_5(tmIl6UShE*3iJs zSo|$2&E5>g(G*E%HlyFe9q^tS74iKt+>^kG$X(QG;Y#}{3Di7`jeLmihl@5rcaPHA z_tapq&no)#Jv9|Fxd-oIV#~)}kS%(#vbL!69EB+Dn5ie7+QJ(tH)@3I7!swm1#{D3 zE4J|#UmChq?IYK<)%+a{!vnB|-jkPTUB6W=7sP*7)97vLx}4)+Vf-lyWBoK=Y<F zpcx0S;O%NBrz#|xhPocQ9pa!6dU?CrtxXM{Kd!fF-_~qbEgsdt$-qfzCYHr2bcyVW zC<^;P?H%|WV0B36OZB@*)l2fu&>R2kNk-L#^;a`N$P`=b;tMcoVcnI*Jk< zZiU0N&LNS257kkw2kn3Y1T6YceX2P-d>5=KJ9j=*dwVoxhXMBN(10E4oaXcy(3F07 zdt3S!3m;CuDKe*jZO6aTAG%W==}^cwqPOl;P2jn|+NmyeeZF7)5D1x>J){tR#QWJY z?A8&#pbUKo?$$DOmH5ru)Mpn~NG`@M?09OU$@r0)7=qJpehz_WjY<@iPxn$;$r^X= zONJWiJJ7g~(Cvq7wD==+%p;+(eA3;6SsFeEcUW$_p(4R>$vj7cmLvLJ5wLguKZJdE ze3ZrW|MT1>q!7aGUV1{vB_TlQp@x=ArwBsmNJ$exkRk{oN-hKxq~(#od{opFik>Yf zc%UK)0TdOC*c*gmLs1YF4np#K&vSQ(d_SMp?~i-kJiD{Ivu$>Ec6OFe_I}kGiCdm= zE3Dl$CyCchcVPBTd)<^2{vKjk{D2d^(0t=RIetPfyl#p~wDi~BU+=nh%OYwZussHI ztV3lrH&bh==}wnlH@(UCxnJFFN`!Fo^={Ky{JpaWQ~uFX$F)7CovJJzsKtJ@{Ax`L zW$a)iJAT%WUU!)K_!jiger~DktEEd0YzlBsI&`mTj#vF}sXZKz?KK4%5~|a;7k`51cW7UXejVp@1FpQjZR*~uKE=;#fh}Aao9?bF(^g#3OH0G|9Czvw z*P6$EiFy+zo}24o?U7~FPvRQCJv#`_M5t9xCwI^$u%@L=|o?^ z4I}e~ZhbM&^!Q?HZw;I;=SxrgAI)PijP$q)Tq?|d$K<|OrCR#XvYTIdV4APKV+wPX zTwKvdFWHwqd&kr@$CVm`Di&Q*?#}s+@0-U?!{9pZ&b?OctHpZZ#Vb$A=bOjkiS7C? z@%!eCAJ}-XU9IZN`PzS?aR*F^uKQgoZdN^ZfOi^ zyNi0%n7YSTBx$`+_F1FyfdWqlhTK5iW6#GZi}Sa{_S3e~sv1+7p(dFkYfX!Y9rzOw5FuEf1LM(9%2B!BW-Q!8e$+!`K5P)8WGqz0W)TI&7Mw z`p5OxKCc|8?MXAi86sHg*R=j!lP$JD%ei9_e>YfrMu61 z9wKuYsO7yuNk<`kT;4#7kLn8ar;g&pWxzT*a?~_lKC%|vFGkfY_^rTA^p0!s32*AwJ>nD7l)<(^8uLr=TRbsv z3mh}}pYYsU;F?=tCB^aMC#KVCME^C7p**Zoqun}NysODN+g@wv%x4$@4hs3)^a=jX ze{RZ(=(n0z7`N**tT5a%3hrz~ucl#NV59WjYI@=eEGhd|JC1*0va69#JmxwOv_XVs zhi)wT6itR_>v}vM_?2muAz?K|d~JHd2fNvemWE#R`qw6l;mTu<&%ZV$8vP%K;L8$r zs<*@cr0IS2p8%)hw%4DJ1BBcZ8FxjTx{%&|~?6j)Q>(GJ@&{Es<< zqq`A6K4Tgd`uD1Tkok_d2l@9iu+qUz!tArA*Hpe}c>SE|QAnUGzK1Aq{4w(X0gGtQ z$LPoprry5Qfe_g*C@L9$G-(m4!uA>4L?kLA8`)9z6)6r?L!Asj$wu3(uZ#Lmwiy;$OE{kDp_ z04!0r8mwrQ{z^3lOz9XrUsD{ww`k1v71s9JJ{&9Dx@C2bm{QfI7HKgP3m(i< z6jRLeF>4j2?dRacr7`73jZfJjbCy~g5;XT1F3q(i=q}*65L--w?g9=gPHDNVo$dk- ze6zHsAzpU@hlR4V0UIrL0S7)+s?^5mF5s}Vm&RD)bQf^%8;VdsajgD&$OnkXRbw@F zM*x|j)Rt$_J_URXaCt?H_Ay{E)6yC>MmrApBft%6kj64;Jzyoat@a*ZEDWVFmC@Q^ zz>w}st+CPCLBO8?&V}zecB*j_a7|s5_I43IFnLOq+$e1yV7>NAl=cQ-z4kGY+UtPz zVFfY28n9mb8lk-mSg$>-_1WWzUi%oK?F6jXzM-|Y4X~^B;aUY?z4m!w8au3iALSNV zPlswx<3q1~YN*D>B6{tML$u9+_1f14Yfk`n)jn9;2w1OuMUch}Td#ekSz7~GuYHBdnG`d30SXvZcFWMz^>Z+Yi!t{*IxD4rUT~MTT_etv?=&- z^}U}q39w%KR9}s)R$YDXtBnDy*S^+AV=Gs^_IW%W?|8DPA^k|tamuzIhcygl9XyJ^0!9$JF0 zQ@`uRKW?0S*4>u3ceK1{I)QhG5Pb>K00OfAfb60E;CSRu)5EHvwu9sPUpTc<576i< zrqJ*s#W-Q&`zR=$CnXGI6VGA|kD%f!CNp0A*?h&+4@=PTD=3-F)%SLmZ zCcD@2BECct91!K`cg?iOXnq+YI@5fb_e)FU3O_LaLAv zS_O$IXbPGgB+@{Q<5m1~+tB4;ojeK+!9TtSxc{f~|G^Ga;{M+0`geQ~B3@S2cC<81 z#HmsAOql2zP|Z!i2Pj4)_##YrC1a9`TE zIomlGxw3r?R`_Z!kX{JVAMayz+OIY5fiK;QJATb@&H$-vldR6!2-EYb?x4*C$)#Pb z&h7{UHT6kn3Ox;<#;w_vow520_gK z(N5Lt(H8f)Gp&auCfcn2Becytccvu>V`-!Bs2FVt+GjVn|%#@Q)S;jfUjK zblf6Rpt}!@6_M%H?X)jph{=z*=fcGZ^su|zEQXb&KfW=qZ1@i6??A;_1m6I;=mQQ5 z;;;~eMX)E@UA|#de@J-I>R1sVeGqr+!fsqlJ7UGikWCnLES9~_MxO@sCGt7{0Qtv> zX@;c5bZ?xPYKJYblz#BqOnOmQEK;ES~geXFAgZ~YTK z_zJN)x}z4m3r~1-6mwK_{jIV$Z(|^T=XVnA!TcWYgxMdykY4E|EO=$2zLS^|rEARa zvX~bf#^y?IXZelhJv`WoA@$IZ&Z1}Udc(sHZ7Ng-Yc|EOmb*(0Qbwa=sx44AD!6MJ z`8D4r+^5^fuyUk~lU8>YG1F>PzDEszUzn7iErdoJcf|9tHgK3VCQ7SESPh=I$F$eO zavKu04;T+&@$N8NZfETXhv6BocJ8q9^3GcALh9N@SbXbSJp9ln?Ulhap^KOjR-G#| z^$yPCbMAFn&Og4w;E>+bdX`VP<6IZv-NIn$`S1%<&?vJ>M6O47`A&WIGEK zt22m33>FbZ)oQM??;dCFw z${qiUN~F=LyqN}6y3@4(|53R&OQ&)p@Xi>ETuNrWpVp;2mu7R|zr!vJ`@dnM{tMpj z+wpueop;}khp?}1#VbOaD+nC;Ul7Z0MPxi%hI91ocnCZEU+_Bo7rb@1XwdD5 z2;6l$BJ4qW>UgeuHXV&fccE~JpHr<{W1mxe2 z2m=1p@%}pjJ8#be_@i&n0|ZR_z8Ia zcKk0hoPqxfANeo89Uu80E&4wc{ZqjGwX7%Z=)g+qnju2N9?Wva-JW?+wsQ@2$q->f5bMmmZAcKLW%57e0Iwd_^Kt z1Vy>a-Ti-3XX0!oHB%H8q1^9>+&*40I^5-M_&+I;_y592xhsILFI8cg&d2X^FKvLW z)7?uO;IsMer44YR4!YY`hr%(+99s?R!Z+##~mqSAs7Go24k(#bAO1Kf40PIjpR_~Tri>{1Kh>8Or- z<<;YYGW2Sf7J#Igp7emDJ?R10deQ^F6Y0@Rr3Dy)Q#|;-oid%$lK>HWJP81&-&!EP zuhNB)qHi}A)G9)u--B*B^J55WkX|dWo6N;d0Rl*UE^k=fMvVmxT^wWX6b7{g+$qKM z@}UEvuz#OFN|+4wvuMRAkyfx`@`g%Ao{kRI|-v4_g2|f!(!`5DHBDwVarUKJW&j8%R2(KxT7}U zqh?y;*-GP}nYYq$#YyCtD0*jDvBzS{7pE#g>3|Es2HzjA1f>B^18keD1nD?{L!VChH3Xw#ALDD&|)S%HCbf&c?x#Y&y&TwAvO0jh90=*--F|= zd+5krBHHiD4A<7GfwX?`6t7MZ!%Vu)BF}9}R)8z0cTEu^y6d%Ene99|&Rt8uWtfV3 zVSxK$ChD~W%zaA@^Miuu*D2zzf0Q6qxxH!3RMDZkUPMW5Z><8w9E8Nb4U?|#-L4}E zOhi4N<0^S4fK)F|74fj~uAeG4{*&EVM9iKha!2Xt#cp(C9v)(cZ}qc((ObUo}L{5j)Z$S2~^TaIGL`(C;HhenT=8Hf*yjy`7YB+v3 zJyamRD1wCj*BE!J0Df_TyHx;>L`&$c0{C0Bmfnh3Jb(7!1Afkf4>-+(54axq%mwro z#`mhh?)2NRrg+i=F52kH03S)73;@@73WRWd%##3ci3cBWf(IY)ZV&#q>CRdYKHw!D ze83SNe8A5GA8d*4yj!d?^u3!tzgrAb7K2v11sJ8%qhc3;;ZV)ynvqWEY4y~CbmcXQ1y%%3mj^ulx zU}&iuyYXuhc@6Z&Y?1u0fNQfwo5cEpFVmeyPjP_vVZP|a0p_I(6|A=aK2NE0L|Q1| zY-j5G|2_qIw1A$PBicZ{uy>AFXLv53vhEYRd~jSDVb42FP4|iA<`D3(H~U+i+cAW} z4NGfEThqq5VsEI9m3lhMx$$T-jYes?aQk8T+A(b&)RGB%vz=)O2cN2E)lOZJ7x#nUQL$3-H;P?|{d7KuJ#?_@iZ-)p8qY@ZjdP;esa1;aFD_e(JI z7E#;?oe|3#p@n(Os)BL7I`swiK6ztV-Sczv9M=|!6$XBIb%_Wyw9KU~OGLE6m`iUg z!Gg3Vk4`Ru`17ShJSbYK>ZjCZsfbiJQ1Vjro{bhP6>AM$a;a&l=nCucE)R*>h8DT> z)I(S*{+doFA41-rPIu%l6a7^jV?Oh+IHhLNBaetX)me1x5s{WyUGQF}bJYla7*(eM z9xz((*J=gu$+3FBR$Bniq2%SFZBJ-uF6QFLCOPR!ipD-Z)!ad-cbNVB0ObY@xK4D0 zqnoc(rT$+0C&QX$?Q$__=-sT?#)(=*`5^t^{4DIwrr_}0`!1zy2J{b~L4tb^3HHDh zJYFJk&IG=y4hC)%l=a~-Scd;_?7Cs8QzSw=9)HZ(NJS8EUrHtu!-L2qQ7inevwzE zvmA2=jH0?=V5alsJKXIJxL}mKy#crIv^U@~4?faXc<=#F@ZbZ!1_q+%xi`c49}f=T zkschtmw+=Ble5}_52#ID398eb>pTenr+E?p{vHW*e83Am_?@9R^WX#Si%ot4Z&sW0PK;{!c0vX87$sc4nxA}gjs=<sh#$Mq_z-d6J9@fQgfT%?+@;|V7q^VkvxG+CPy8>IX z>uW_v^%}KXClb7>*^ueZbt2YF@zF-p=yf8JO4kXqUp2bt;$GxJFRc^dozr}@&p|O* zuNHt^)M{ksx#+^ypMDsqEJ*QwuP0qvCk}d7kAry(Re#$eC=iCoWeo=GJ`rLrps&}9 zh~SNPx%Oub;QO&45d42%2lCq>vI0u=Wdsxa7_QJXXSWWgMH@uh7NwTm>CUnAlr;J*EmVGijVA3Qd)+kP`I89pmw852gMP5K0Z2=&bIbR!@j1 zwI3xuA)4)hRPp5cu2-~;~HgAaI-2OqEj_+-lrjN0-a(ZjzWKwDN7 zplz)Sz}w(r>9A81akBzPaLhf}<=i*;&b|2^W&Z--<@jbU#5k6Q0PO_AY7mAV(8E$= zT4~27QqzA#g==jpK+SeODH0NLVg8F%rUrB2Y`LO&W2G50zL}VjV+!buyac$HpA-PXP8oo%Han+0NmfaKI|UV}PRo-iG>F09ybjVFbDGvz#e6@w1$N zL8t1%&vO3fCO)>6z}LflGsZig@I;{C7*9q&WjVWeG6HOO}m~J!_^n)#?zutbp0y0Os*V~->(4XV)?6M*IHpNra%g|;CG2eZxx}~ z49waplDz5*;XeDht-=b(8cb)miob&TOyEmF|JV(V>E=a+0#B0KhW$)|WDs%!aJ}dsChS8emM4!%jkLG~}gNqLR zio}kw`o=Ah?R9RY;g{#c=8*bv?n85MYUUV7c;diB+EOmM8BmXR%SE4rhHz~qG$oUf z&!5PHn}Ahf9u?ylG=rr&nBpqLB=tqdBNgHom7B3j%;YRSsS<!V$UwJp%o#P$TUJyU4iS>##!?^{+9z(m{0yrKV z8$-NasY!R1dcpxm(}EX8e^WJBV>MgphZRI=TdShztrtb6`Z=jDi917fqqlSQdtB_> zFv@PgAbWKj&3H-lfOiax-wL~yjHjaXiEH za3IKASY9vLUB^n?G~x9#81o983qpwz&sQk+5)5EVE;}6zwzEr*s=i*%Nn`X8n3(IO z^gfM6UJX=s7a$FjQ&8TPetAX2wgDsaf_{P-SqrF((lJTCufaqa-ON5o5?>X`+0~qB zYHp0y!=0fOm)iy#t1iu$F!JgtYTr(NMk5bi`8 zB~FY&h4vhr5@%Dh|{$7v$F61|2E;Ir+4%i6GPJ@pbOn@qLeN zctsC0i8lm#+*#Ca-s>XR{K4o(dKW}8 zyP+XJOow-a)qhN4kBIDkFUUO56B1}&Na?u5z`NKf2z#S1?)PE#@IAfS0XX#49pr`B zsXoaktVr)!a6xEIv^`s(IYT+vNVtfsXsew@Dvh^O5PCA9kA0tW8xM3SW0X;0(%qC#9X8nHGjUZQnnfD9sb^fTN!1*;TzMh)#54! z^2C8hqFQ6o*o2dDu9Kfb3=D{gMXsT`VJDP64iQsivuF)>C}nK5gEhXspfJPPF-4aZ z>eB$9N^|oiz$>t1>--9^31^o&eur#l8xKCuHb*@#iPG2Q;X8C-!bBd=B zz)-916-fc57=fi>RqeDZh6F0wD|*XQqwwx6j(}ox$uZde%_usuS1j#N%1zI2hE+oM zUjPg7ZRm!qk=O*GIj|z=@g)uMbk9DK&=u_JcDbtnxNP)|`EWBY?#4Q#d265O(79CK zi0FziygXv{(O0e%G`J0&slcX#21jRATL6#7iR+DJuj=+? ze6ctg;mp*TxyLx@;G2-K9hCN#=o;SP&PLLc#bh}nkqpgTtpI+E*1RQ-$5itSJADr4 z>2M&3`K(v^G%qh`IHRQlEqPlcu=2#M0->F6i+HP^ssgFHB9*79JgMqpI%wN?E01Q> zO9oy%@NPDLOb2SYUv!6u9G)j!78}X7c5|Y__>GSA=(=myf5u32#bacOn4J@rfn8lXp>JxJA7il4S7*~?}itkPFmaij? zen&(^)h|Xqo8XHOwvxZ>L0as>wa>Ao-gCx}9(zZ0Z&6*`&|V9q{qKlAe3uLlKVn;c z{T*oYuTb~_oUxy$5eGzfgW^L)2gFq9_P#qHdJTlp9`7T0X0nQyH~KJLD&uZdz~NX) zHePpu7-D~BWFzHaKv*zzcxn8RM$}-_nCy6{Mx?8QZ;D1i_Rpmvh9MX1d`qE5sJ{!F zE8gi&hG=#L++rE7PO@mW0&zU7Sc7oAR*X=BSm@c!*A{Bugrk@Vdo9MOkGn$atU%?b+N6a5U| z-$Bp5CvsdNf4(OkG^c}L?s7H?tie_j%wj zX9df;$efj}S9_y{Si{kih4@mn2i1Kb7Ia8OPH;JTv3w!>bm*kzLryHgh**ic;zQ6w zY{A(83r@OtPs=b`^dYnmr%C$|!}cXQ{GoW!t1tJ~qGRGE^)Ip<7YSI5P(KBcUG z0PgaSU_JkZqxK_F?`?>|Ym=Xe!Ql`ZS=qpa?5{%UyQHr%Ye2C4Q#I{by` z>;Fy$Yp;XtFAkv=UyAIz0`N+FAD!KnrU8DbKin_#ei`tcV8beJQ2~E9Pzf>uE;yIr zJP&*W;55MH9(=&*9(=$b1E1y}H$~B*FU3dU^*jo2Pbw!L;^NtwB+Uz+w|k&MTORWZ zio$TXiNKCx(rc6S;n2>FKo`Ff0|M$fz1|?TN!0giv7r5qVT}Y6RlMe+E~vy^2!4_f zbKquPY1j+K0r{h^MW$ixFberbOoc-mo`1+{1@Am-lBnbx(GXBy>&~1*=6x&5TzIE% z!83m+<^CPkmZ9_?Tj*-wd&43#O4WewsEJPzrn zwvXD2YS z=#pH`O?moegY?q905zxbTo1MfW;D_wozVo@TLNCF!)CiLVD5E#{=A5E@7ikcHtl)Q zuS2~h7k64gasi0Tv*Kbo;5PMY^!TJ+VLw^xTuB~1zhK;LRdePcn z#1vPkifQK#bzJ!cb3a!n*@BtJP7;i@xB-nzf1^P%FG{z{Vi-sN;3D%l;IcrUrB}~v zXC4X0d=uvk@;i%qEW9Ab8T+R<5+2$NriKe5yGUP(K(%H=aITNi3k%If9vZ3TQd@?w zniei=cMi+THEW9z7K5;rn9dwl48`mMgxR3X%tVL!(K^U9a zuXSgbS8LKnBCG~(aqe*A6`$^{4Na%O-$f5skJi=pqU_)Qedbj3yO`?_d9$D#1Fc4( zE5D0cujOgDW!3Pv2%`FnVtbz&j3MkK23lQXXgFg1Ai|{Dnu(SkTLoXTLHBu={-9-J7NK|3ys=Rz^o4)t^`osXq( zQ-s>Lq@tm!lSCL*|0%peH{jDVL@RhWqZSyVwDC{TpGo-OPrl>Ti+=x8bPVz5;&3mc z0{abSExiAD1atT=(ZlPar8I;J{t{(g7nSl5+@FKRK+8|@`rS@0H^@$ z^b-hw7~x?4^*qH>|0Mer*rYgV>Q!;4p;bD)auqG`dm1G;#jMuuryX1}IWC+$>l7iO zYpodD@Slc7yM9j`JK{kX&hJPcI5DGd(9cdWA!01Ly#>0a#t^plT_tq53Y;^b|GbqZ zUqihz(`flMm_xu%{WWoKYEuR;?71qr{~QEfAipe2eeT4 z=V92=>xKvjBvTt1?I)f%;cC`GnsA~QnYvPx@T{4TScyGqsU?Sr7CS5MMI^RN*|4s-oCy;)?_H!N*$%cH4X0X%$ibLfu<{}FIIHo~IdG4efZZBCAn1^7!F zEAPRdeXM*mVrvIosb}X$++AZg(*C(2Xzk;jXxKQJU>MSo?jI*7_}0d0@eo1V(#PXu zsL}Lf6CHR-gwWJoty)sRc_V?dGBdDJwaYpkJ4uoWqX_n-oRh@$pcMf zZ3QZ^0pyJ$&oYZ*Uh7SRCduLIU9@JBT!O2*>SWoe$I<_|F2MSO8GMKbqM;rywL!XJ z4j2nEs*2;aLY)6MwR17ehiU3$Iibiu9?M2&MYgRmEU0a49@`7wHPX6|uOVXG{gVaD zbw9#=l~FF5kKd)_!5qfffE$O??XH^aW~WRdR51Dg&oAJi03`k!dv2*kb)IZ z{lwaGcD8HlvLLzp76i_q3N_gVTZQN7o?|hA9b@G)?v~__wEf zr%6kQ-Xy8+CA`4ePAddSzfi?Ad6(h)1UMR&ZCp62M?eHl24uB&smF8~>Hn!0KTm)y z?i-F_6#?B;ED{e@1|*svOu*G~ESE9ZPgcOdes8-*a#RMy()YPC##c$u&iUJNMp3Ig zxzMn+onu9w^jDz?S)VT>)%WOyeAzjwz3U7G0^07}7P#N4S2fuFC#pM{F6GN?wUUwx zWK@8fpdG>_}Q5H?O3M0@+hNNuL$SPO3&~p^Rr* zR-(ICQlw!Dp!I{&(G~B(PFjKbizn1Ni z&^orKZ`Wqa>6ASY9& z42O(sW@BWO{F{h8q~mE+fOO|T(6dZLsN>h!a;zH2l;YqnF}EgBdnV2?@;>=8?(xF5 zBazRoSU1ET(rkEUeV!Z~3u#y>J zLUDuH$;I43Z5GHdLwO?gT_B^eI~%`1#ugco@9%=Tr@PRZL5bfi`$NHJljypc>N$u@a}J0ok8=zrF5n<{j|`YTNkzWD%43Wb$si-2QQg4 zRvYyLbz2}imI1~X@W<(4I0l3{aTTfe%dh|y1jGFT6YNjz?w12wp~blIIpk_vntQ(t z4dWneYdPq5aL+z^ULlD`>6!awi~)=6f%|3f-6s*nD7$)EoujZjGOXyTsW=cnYZUtM zo1EE9IcRSyx;WL)8QK`Q>Oxt-w1AJa5eBAB^7i1AwcvrqI3k`8b>lWwUBbKpxj0 zkcq9Vo%LHh%u9R4QPN`BsRiz6&p~v-VwsR>>#XGgwqbM0LzQP_F%*bX5C-|WS3CEP zxB_>=Cm<{r?!Fs}tgo@Fp4<>TqY33iyEr<&SPlp;@1m7=QugJ8yKpu}e&Bk3A8lPM z#V(NvViMdrHK27X@G_e1l}u-$W6}}`626BY(`AB0w)+ZAzNnb`XkR=EE4){{aWxqn z5Oxo`9tsSq*san?Kiyf&h~(!Qyc5SqyOYm<&NsLP%B*VJNTEw*%z%34X`Uo;Na6)A zidT#+5>t@mGgRP=pHgal36{XnfIv9EIQ=DWr=_}&*8C{lzf{i6ia~{WtHrGAfw8Vz z=jWia?rn;6ZFMAWho?aolMpq2b*c77BTM--=SK%L->()hWjA^7F zSI92y;(*M{5%)HhBfYg$_qtNo&|g~_13fDxm!K-IQ6B$oaI7hj8@z+63$491+n2dl zSq;UyfpXg*7|6zMEerq!ekpqJOl2v;5!SRp3S$LnN{)bnK9`8}ZK?Il)c zIQ3pHH$mJvx?Vt)DEk>(ieBtGcd?l$wn|Ni ze*LUb^Qf*4*0^x6LT->VVv!Dpk*Th*8G1Uiy)DvVRjkizP_=6MYJ*G&)Jd}#2lERn zIaSnZqfEn7=iHcQ%rs%6Y?pl(T9KI&2VM?ScE_T=si-#M1Ag6vZs zYoaU^lIFI*9*e>_<6<}ytJ^5c{p%SkHC4rF+kK^22`t@dW2qcuS&W2CF(Z$CyonwJ zrvyvWsjEO?o#;ZT3>A^?GLKxCre=@N&;bf?fK z`1b^fh+?Dq)AL2W5lycX^t zH&EUtX*RYEZ=@xgV>ajtZfIu zjtU_*&j@vC@lLt>Q|F)VwXc9v0%t0HRVE8LpF@xq(M8nbGsI}T-LOSY^aXW)gSTMzY>^S{a5L1NYE$(iXFTh$MQ()nHI5`Krm5q9uvrZu zzbECr9jm$c3dk^Luop7o5YY=7VeZK8A|dqNxWTBc&((bwu+gK)?MH`7*PO-|=RQ8=gd zp&n1ki0GT~E;-px+XlSLMwxgmxS8IkR2djbwx?vg<=mzw*4XMN2H5B)8c>mO=&v`C zXY(4w(Z>a?%rt*MYf}#ei!9?rprsg(`}87ktWB;rb^B~?(k+3Yp3@ae`zics8Eq=% z6Qy{4feyl=okH19%Qk%nZE+!c`_v?V-|}kT6l2@jFZ(NF2cYmD@N17>KObc@Ds^HR z43WQp*UG=(r~2uqytrbZ#>U61%q|a@tu8i??dp!J1tW?@W45F3wqkKAq`RMy4@K&2 zYJp6gh7K;sYpKO=b6MsE;}x*Mt)pneq<|I_^{nh>(NRlsTWXBXn*EiPF4Sv5`bl{* zSt|mA>E#IlEot4ea#P67ymb`-5*Ak2a*j~%=de%vp7NfPArUuGIKKj*aGu!nCBEv= zo|DT|^&GXT08hb4>sBFS13=)p|1gGM;y{{OA-j)48m~>ZoL*p^T|fuBuhW&_7{5$w z9%!w^Fv=)H%@JRUc(6;oT#h@4I4-wvv#Tyq^j!r6;sWGKt`IY+l`_g;3!t`@@~H8A za3lRvDJxKe^;L3|329Gr^I;mVTndl0bfHSd;S#IZCZ}Y8TrZm~XR+C(ji|sqU*1~i z+lrMP$8Ur_i7L?VK7DXxs#k+k z8&G^5QWq9sq?2FUb|^WIZ2_%;$W#Q6T;*g3EHrr+51(W%&_s zO@}ghmr|(&cI|UB zj*o5ALD;s=P_vnE+Jbzc1il&1Y0olkF;KHn$5-XBqJPCP-P>@}XBX14X3RtTQeUO4 z=GW%lm^3;*Pa3@;kY8bvEoVFMnayCd{VPAc%b~w~2Jw8Z3Yq2K@wq-|#cp_zz~OvV z4pezC6=DyNL4$V5YW_Nxf>nY3+68q@On_F9764Jp@)`yjDA?8my-%61$wj`XGe2o{ zmTF&<8T@rF(UwzBtzMVgct{p@0FAWob*!)W@*1RTR9}~2jOo?amb1yB?v|}pST=|~ z;I7|M$35~+h^I^U$eB7#6YxAH{k%uc@k6=i?y}`H2GX=Q(ZFS zn3!~f#?pD$Td+LiY-P4BCrQVm?fYctpw749lpv>!p|+f8kO#>jkuM%3+=_!uLLI8e zkEjNdbDzA^7}2_shQBF)Ge~fhw`8%ZI`+Q>UA1ria#lkriDcT3=jA5umnL-t&Dsw} z^#`rlFPnWjBICqj6K#A)uJN(pBevY+XnR2JQPqd&vl=kf5Qnoy`l!&>sR!jwAsNf)_*8@G#vx>Xnc5si;x8!mux#IM#KTQA8EZwvU#{mc zhT@xtH%vzpVO9x^Ph{d9wEi#>{!A|)mSgbfgnC5A4ftSL6IJVoX8Y3%;lZH`jfv{slQX^Q#UCc>c2rLEs?RhDT64Sfe*;? zkv!>JwR+3M>eB96=Xj47Ta1=>z)yw427ya~ud}r>(=H2=5WXMXxK4{mLA4|*d zXWWtHzx@;00g=2zR-xnJqhP5jWicRb1zLz*A(pz+C>Q=o6NxlSK9-tVMSdsb*rFH^ z8V`dlAJ;MjKQy6L*ryf@fx_i#b7&>tG{6y!Py-|DV@sPtf51=2xtig;%Yy@00LKcP zLx}&*gEKbU2^Fg=AHcqhgGPA^@t@*Xq-V4)+d0&O1i1M+=toAc0pSBrM&D*TtsWe} ze*=eG_XWfs^x(`-clPz*0KUNaK!sS2_}O@Bn25Q1j0H`Mt5X5RSyne2XL&wxfk&z9-Qvk&Z}44O%3=J;MjnZhxms) zIAs~m-#s{hw-*7a21pZuu)u?~GQ;_U2MO?2;FMz=D1cKiJ}LlP0Au&-8V5gRJHPhe z11|O81Mca;2aI!Y7ygIo&f{+UqBMN0^dtb>-je|E9#4W^na+cr0sueg!3P}a!3X@p zP5f-<8#nQ@opWyDXFFTp#LspV4GZ zbBLc9$@J>yazWc~0Wb%P#=q^}K3A=}l|eA8s_m^X*;2m10WsLb?_bDT_`TZorJN2Q zyy7d_$FWfOz8>d4}WT-plP*WHTq@0yApk0Y}>^vs} z4F)CJ;rKx=#%fPpf0FH@O5esS6+vFu4?%4H0=6HY@P$V_9`lYNhUWbwd#gQZ`%iLu z>$!`YsI0w`oC?MCONcZ7EEgEAFQP|(meGNi7c~*q(LM_L3$IYT_Ol!hSI&Otak5`a z_nntx%r61MdZoE<3^4exWQehmJ~=NttMyxcfhG}mi++(5-2x`Bjm8Ch7ri51Cse!? z5ro5X7J)ArU{~^s9M;>r5!ycmGC&k|-I4Z@$QZ{-iL9#IgiKjJfVp50$MMavEX3ns z;%UFi-tna|U_*R%rtjfwG5S&JELHD*$@=P#P>2JVelu3N2HQ^h>sJ}q1xK;&+oNXt zM0eDa_-AD-kIgNB`Q8=7n<(>wjPpC~Mmt3dE?{K8&pF^&0QTNFf1o6nR3B z1q6Q^X+KcIJGfKM!vA$-YQ?>()2P)}x^Y29iZ2nY_$j>_5ya)~qK?1Gw&8U+gD$_y zvJxIw#y~rR>oI)u{Zq>O4dS$emi{IqySxj%hxKp9a$Q{JBbFTyGs+=los!DF%^;7h zbU1zk)gp;_644e2I}Mjzg4l7ofDG@B0~u@^G!7T(T&Gpx_CpXIJvj%VVl|hW^{Lw% zxy}XtdQ?0L%Qg>y_K?7H5uS<-F$)N1trq=Fi?@|#D%Kk)#2!tvewX+3PDfS^EnHfn zWheqIofrdSLazNDqe0sauEFpR_~!;=_$+x}M6-YW2+?;g@9L)Sf7ci?+iU27KS7Z%Rs1QyJ;)G(!7WFRh;t=bmLFR`J2h|mmGqbfA3#1F}M}T@Pl=4ZcC-taN|92auROu zOE3H-ml!XqjTHB{oT{#&;=g4#I0V}Dw~QP70}X0sp8l zGYGdo3_J|VL}VQvlQ?;!iSVkRxfehmN2N_acM-$(K78puKRBeb+prU((IhF{jI9~Zu+x}ftad8E zkS!bmPiu6#NiGusXqT8@ntOkN8_8T~F5TBGJGDw#)`VWd<9bM0fgKkL(KctA?@|q$ zE6i(K{rV897s%C%z{E*b&5^y^APD16ujM{mDrMDmwvB5RYF~|i*ZD=LeHCCA!wj|K zWop$tL4_^1Y90=!0$mK|IBW+;8_ajAGpNE~&Tdx>bR4G#wRTs-0=}JwZTMMqTH%u} zeKWKRMsqh*e~{4}7K{k5r))WIUvDC~b`S0I1V;IFdc|lCQI}J((aZwD3r2G!q?yC~ zrP2ldi=kjI^Yj*f;4IsE*@fPppwc!Q8kf=zFY{paBz^B?z6UDK5#Huat*$-jS#iSb zSLlMbIWoB|b0}^@{QJ2(aVlW$(3bA+N%-cbsGROPZyKY((>|rPFn@%K3m|>5=H6JnHO&Bz0yAK`qG4F&O+I_wtK7=;=ng_JG^k7q{zyS#N zcdfg>y&Pa}E9^@!Hu2CDQ^$+P4*D*@ z96B`~?PT-0+7~-zo!>e1Zx1*c=SJnQ5_AsO zs{0!q-knu*$?$0p7QN*UH>JXbS43-@rlcf8#{^jhnf54>V^KdAVC86aTI;9&Aqo z>}j18!2BR66E_erxU3E*19tJpV0$0H%)1$yP89gFMa`T?W7|dLO@6hmVm6!#quegqgrz5M} z2&Fd~HIW~r;vp91qlgC)&K2YSv+1@yA@;0=An8{whDF5?dne2_1>YDidJPZIE{TS( z0yQ<~n|p<0`nj?UwI?IX>2w+tP3?kQa)0Jr*tu<}T_Tr;pE#Fr7l%0QfP)p-9*6%Q5yr6fT=QY)HFaN4}4;wyl zpA@4{B=-qMhJQ;doi&@o+ugSwopPzUx37-m+ImEz4z>o)h&wLQ-iItfX7kWX+$5(s znB^#*leh@abvWrk4YPLu4GrF0-LU^h*?WLTS#*E@_ih3SC6F+8DuHYYEtC)ly=_P+ zDkxPHP|{G4B2}?wDJlqP7L`FCOBx6(XwX2wngBjv2Sf#HfS@SRV1a6eq66tPIadBR)Xf;$g{ z>1>;`{zEcWc-GtJ0AU(xd;Rt_@b|zA7Z+ z&N~;u)sY5y`Swg6*0u(h z_T1&Rm zx)#%|PywyhQljG{m9nkYeIiwoeSdK-_2nqK_E`N^v>Ikh)R&`GKij&B zJ~8T3TeHs85Glrv6=AXJZd>$91ewL;W4Yiyxy#!3qTd6$s2wAq`~K3q+o^$JbN#{Y z@CTcvZS7T}z3m0vvAt>^KSruFCLoIv)JF5Wnpu!gT+ScYDYsYC;u)ooxasM2kFPj5 z)Kz{r!A1PO%$#hGmhMa<@66$KT`5@oSN3|ZMLg0$*~Hol{9~=1GDVL8ytFX9KF|U{aKvq6t)&(ciigSD+JTo z&>5ve9CVJ8;8OOg{7%;|&%%j}Wg^^Lr#sZ3kdJTmtt-C9iOCasjYB1dy@!+h>`m5% zlMnS<4z)OXvOn7!LFw{bco)Sv>(}aQ;#FMWNt~^nx!M)4dN%80g_hoXFTS?F^oe+t z81N>pbs-_qribk2X-sJM+Y!BrjpAQ+1FDs zE3Mib?fDHqp;CySbPf~sfX)o>9eQ48)vwEBlnMMNUr#KWN1LDh)mXk;AWF^4NFvtj z^hcf5w-E(dh@gn+!zm0h`!f>VrQI>n>Z&fP}`BWdM1Lh&AX5`j@hxG1G{N5jU+uSS#=n1^9LFZw)D@BhVk7nR~pQ>)l#SmHoA^Z zRC-sCZ)Cd;zbGkE%4H4Tg751i$x1al3m@{ci~c!T^$ULrU*u?2QlH9Jo}PL@SIXiy zJ-MsuiaK82mG0=Ie!43<@(z8Zt5Rc|%qJQ)vg=5A4jqOIOy}(E zxrbVr*o?X%^OrwSVB#fuG?g7#f}au%hV^$Z21f_(gs#57OK5C#B<)=)!AZZ7^t3(6 zorJBNeI_Z)4A1NMo+`Gb!O@#Y4z&<)xxS{Sii^Gp3M{lPly1oxBx3+J>NYpVU#FM% zRK26qXvT$CynXu-!*|dR?^ee6{`#YyDy2gL-mMXFbRTDZBi>eHdRHANQDovE(ZAXVUx`u--gKQ$?WP zeVGgiamOqKZ7(&@ zKJ-`Z>4lE|L;uoC#n^ZMrknRxy>97qBQJD~VzWHQc_htTeoLR(@OuWorJ30MPq|LB z{Mow7=u*N@;kTW~DrBlBzvXU1k+mp{=k?RQRT7KuZ}(O)wrG8#x9Z$7fKy9}Y_MRR zy+DVg(X|~UTUi|8lv#x|hVeQ*O?7K0)gwUy#w0H#Z}J@IV9IzY_~m*1XqpfCMt&Oy$SP*Q)mD<^zZLc=V@E`8^NLmZp%^<8y!q!j& zL^n9CUDOet*NE>6t33M%YsC9zV^0%KYIsH;)g}Kq0*O5#oGeHJ^1C5{?L@)~U?m`S zqgnn0Dr1dZC`u$A={YO|8YITK-$;qSp7;_+{8B8xNY4UL<`d#Jk8htLDAIGs;wuT3 zDin{~@$i}UB0YJ0`%He3o@^b`mto!%o!S?Daa@m;U+H>bUo|oM78tB1v3EF3Rp{Tz zAdHRB-}F^c!Bvz22a4D#-IO4`X|4(Dez~G$fA+g`e1%ncPUP-049MI?D155Z`@`@s%;GNA7G_w(1xy>TG+)o_ zuaf)5?{p?zYTx%NU{`cTlPXX)TTGcy3?Adaa)%)0pamg++=r*-KwcvFgZYl zM|>jzZ5R8w7!`45wNExj8WLmmGXqr29czWb@4abGtL8|T&!Yik*5GAaXlSuRO65W0vE%=}wFi^D(sU*5gVkKCf z&K{^D!@kGKb;_I8*J8ab$N1I^R9(}z%Gj6zWgraZz<5UCsCwDr)U=VrWbgBSB)W=i zVqgBuu+5T&FdXf1=syS2x4oe|3{qV~k|aCUmL27JP2Vy|MK)a~tbD0o?uQ+Ap>_|V z@b1t%2B~2KE|Zr+Yr8H6Hb@oIVGRo~&l#1x4N+}FH^M|4%d8UZ zaq_KQF)d>|H1P{kHtWg4V+n$+>F=5_2tm?}QF!5=YCUg=N{F!rU=ps_FYwa7t_jJ6 zGxYM9mTj+*u9>c@U?n6Zm@I@Q4RTG0B?xD8P)*^UI}nr@&>rSD-QZP{Qii$2D`n?h zs16y5Nw|s59;#HbozazC>gtmn1Lh}e?p-A|x0pqLVn7oeUbO2LR1MY!g4#|!*4_^(Z3E; ziQ#Ke^DeY<(REIa+sb1J%JYcs;zU>7uCtxYUYF`3C;j0ReFn$W8)2qlfp0S3!n9aW zB->4(Re90dClnF+hEB>eMvqNb6I=BmXuQ>2xb)#?{c^gBN$-kVA@(<^0Lgw*McC?u zR5-r{rFIwhw!2Gm?d}k`KaaFAB2hDIa2k_r6N2F^*6)Sbs@dcAXM69 zIYU~g`(&tYw(^Rc4E16V*7oMtsi{2@&t2lGg;%zng?+hd;cTa-^F}iYru7y4loB+r zHp965jyCqn$k5|1e2i&f^jKOO& zUM>b9zF1Lw4xRl~`*70Q^mc_ZS3R%++Hm~(viL=kTp70cO z1K327&T-W}){u_!BP0JgMClCFgADph*+dAs!rmIfvD!#vD zsWFF_Zj^0=HrYy8&F`c?0d1Ta;?`-dL~C!o~K)HQ(z8Z&7VW|9D9n+|?Zv55h(kTM5N- zo@HG_ENi%?XD;FLIWc{j8x|Z`{)%#KY*FDbUvs1WuJdvI!}Uq1**pB8uiT!r8S4}7UN->OCp%fO5-lY3VSF@-448WOR=jI^D2Ms~8x zG>eT5*<24SyL|qnbpCd5_W_!tcwZOYb%q*h2j|Q{KY@CN>L~cm42H?zr5Wl*vntgc zNFV<|jkJwu&m|U6Sc`wDRlM#oIjpH(m!92P{l<pTnq8k1Zg-Rtay4|S%jkN+Qy2m-hD0ea= zI9_u}7hY%7e~(+`P@{Z5)oVEJ*_=k5s&C2T+P=&8>*73>(5lmom}Ra64UiHs&+4Oj zYO$5QnLgp(Ia9^6VaGjFnO!PV-BnltPEj^V!{zi&6HkZJB4^W60t1DpY$sJd^^E>_ zrfNHuW4torltrIsg1!1I#pxufZMj_I7UM}Ls_G?I3HYM5M~2dBghX4ug`sHBAWriN z-S;*%MHqYhHlN&IxlJW>q$FFNn7iyT?~K0h*o*kZ`f7#YX?|kfvg?|(Ym=Yu^IzZ2*?&G^ z@^4ptCH;!q(L3N*x2yI-b4L@yee0LG%dQwveWjz{kIu-(U(NE>(qXey`!XtpoSu712>HU^Wmr+q3U ztF2M~Dx#kez{P-!7N^>ud8USTO*?n5AdK}!IBnTMxI*sqlQ3W7FA8-FGf3aAsiq!7 zzdM^*Uyc50HhRjYo83VR=5g#hR7!qX?!HuaA(kvTh?{x6wbFj{{K+f&14ex>BcVIV z$@vrWm$hk%WQQ9Ii!h-5Z|=0a+7IWI)lQ6`K_ z#g#op`}e2153v7U)KsM&JBQ5$&+6yqsE+wpgW0WtR;oK`3@0SWqnv&Gp%EFW|EFmS zt2hJkJ9Yn0{+=M*0{?sL-~vjbGA4*Mw;>*B1sF z%fgC_Eb_*=CQQV?2mZXacs0JoApWbyyCz(Re@Fa9W=UY#sY`m}pJCzLp>VjEt3=|n zLfnaZ@;sH;z13t(A0#)vc;!`jASB{=bY9N z^VP&~(O@|HHpcn9#-G*?&S$J}M!!B^rTPlYIvEbZyy;ALt0i%jEJqccm{DwdGU^k! z&Iygu#=2{-nNgMi0|pnBCAhi|Ffbux5H62!v-x|7uv?bJahZs*SHg?m?S8+r_%*c| zy&C+Sf%(SaL>KDJpGc+=(ENqK(1q2JFT_Y>NkkGD4v}=ijN&g5B6-Wg+te7o1jKKI z-){?k2aJeb4StdV*@`ctLEF}h`fO^G!3_a7oxH>wH^F^JG$BCo9{tOmtWZOvna#O3 z+19pKbC@qQI`@4Ex4F2jx3%jv&vNV8_vJmh#{!kpuId&`P}aQqhg+FE!e<165taLv z-myT%_31IgG89^?09Dqpdga+nP{ZHN%al9_GA_%m;Iq>)h)3ytzT%x@WVIQZ@2jXZWQmTyA&zY9s<;5o|kH_6FD#16Ey3%}*C@u%Lo zP+jNvj_8bAWDUS#dXGPu`dnZ2v!24yJr^kluXm1Lgzf#1p1DX}7dD-2F``U!LCeOt zXpgR1#AITWZn9YQi|CH8;}35iITIzR$xOg|x1O+A4YWPPn|Xwsr;jYgN}Q)JFIJ9_ z?V0s|f5P!GNuR?GiP#!>X@gaf0t1o`3OuSB{~xXqo-wX@k9 zjJ>bx9ZRq^x7P12QJJ<$y7^L-+Y+LdaQvhu{4=DnK<1o}pRM z*ISp6N^32t?&U6R&ajENsd~*)b^@)_JC`y<9jlKlWhX#4AtZ8~4s!2rz99GhJ|M^` ziTeaO33rcRduRRKf(g$0rGjvMkN?iwh9PINs`OO2hR$KR#WnoQ2D zPj07gof;aci|$gfWby60kWp&2{`M}_qiqMFjGPle$#Mhbud3;`T5%qA@ZC%nC+Vqo zGyR)XvEgpj!`5;Mo`oF7TSyO#>nM$+I{7$#ON8QSm%@5q8M%jky zckfYsTa?wHVbAb)c9L#-uj;}HvYz+CO@tnMuZo*I`2u%4WZB)1fsNl75i^4W3*_6S zzQI)`byeh6%>d>7X;l4WW3T)k3-_*p(y`)?d|mjD)>Zc^)g?o`7&8~jLMS2@uc6}B zifta^hPY{b1#kZy#0veSfCu}5w&e*Nm5gx1yMZS}{FR!wa^b=CctaH{k-_p{J6P=`IBx`u6> zDuwE^v#g-vpU`6;P#MiuS;ML6;9%l`bSw@7XTXuty zD8kc)@4`ohek%gUSAl zaL=Amef4K6)o5hW zewA9pK1uf~l{=(xGwsUSH7NTUtc?jCH#N2rEh{VizWrU%$+uz(b6^51VsIhbz6-(o zbm~K@(|`_G=)}ymm#Z+uTV^&ZZbk$sb-Vw!aDDp}`UH%vMcRp2qdZ)V_K=E8{|z=> zSa#mHslg-@Lx!U~>j=)cDDCyN4Vm`sU42-{;BK=>$9T@@UmsG_Mr?(Q6wr@!1#_tg za3RQo}c9QLDRT4CBue@tOQf_ZP$36H3bsS&tKLpKFcm~Fs9C_9h`Vy-VF@9pH9 zR$Yh@Bu3x!h+2zbv&m}JEjWv-PdU5$ke>IbN^BwuVyezwt>VVMOP~b9s`mQhR`}!Y(jTo>iP7(2S`kHIWArDZ-NbCJ zcx5^~-b#FkP)vt;PFD4i?`$&l3%{M0ynQRt!<$L1nr&wC-4Az{|69V<=-F#%+;jDF zYiQ~}=)D5f`m;4^TG&zHie9w}n!?@7I{i_lVh%OpW*^)Hz>Q3WFP_lzA5{tM4mR@7 zA%mw8RbWrwG4Hc_$D?Xgv(8rjB0U}Tlo?n?SOVh0b3kNytf7V0RF(CL>&tAuzHwOk~C!KFuO*V2xcy=IF z+3X(86+M#8{bXCFBe{}YRxhN$*eZ84_XOdvH}1AlFg@j5R->K>TW9@@_B;wkQ7sng zrR&iR8}!rbRmuP%CIn7GP>2iB1Ds5fkx>i;r8t%ob5l#7(d9uuHO@*sMumB|QFN&= zB@&%MM4%q>7`ZCcvk5g~Ai1in_m;1)q~+Ug7AI1*WE1T<2vPK5vJ3wMe0%N2oI^;r zad@SVJjU4lUtDQ}*6u;5r!bOaVPoma_q}|}Mf~gN97VlVpZD%M;OA{6JT+vmA#1yi zvp)%=-Hea~NBW=JDN}(HXsALGIy^^^xycy=1}g!y`x4fApb0 z0v-z*BJh3XV}AtKsQMNS5%{iZ2+wz3LwJ|I^0-Q9UNlPNY1$z2AYpfABpD|dJvMs(HGigb?L z%FS?$V{`-?03S1BVHd7m)i zFRK$7lC5qia{T39YpKE#M*OXXc?5T$GuxQ(mlceU8v9eNON5QiF8hRSdfOAqAzam< zRk-!@36?(jRoaD9toqj{kj((y>`B$Rvrr_(hoC6ySd!Wis0ufdY9ivv6RV-V`AIe9 z+9_0R8G1Q*H3qQp#?RPtP7GQNI}yfuyCzH_87be}PUyd% zR9(A4-3r1e?m$ngX&xOx5V0G`?i&~4_Vv;c$vgGxDdf`(lG3NJ|u5ewZaZbh> zr)W>U6^KaBkgxR1PpOW!)B3ZgRPPZhN29{wr$JDX*b1^}32K0ALNgMRn_(LSE&d5G zlZ#kZrAnq zN`RW7t_ghz@Feqx<#e(_ES^EKB%BMg@>>SbLfj%uo0oW{aXxW$)VrQ$aqm0b>=|ZK z+jROfDkjIuP8C8BHUp4pV7kvP_Sa`uv}8xP_%{?KjKv8;%f#?2cA%dLBiW%3ze-2M za#}KZCYfue<+CrP#y1(6|0eb)0gy$G;6g_M4HA$j+)g5GW$S z10y-pP9lY5ch47>*hFd2d#hyGDvo`yxF|K!+F@l^LgU= zx|#a@GR(bo`o}W#PPT5gQziD8c!d7GjgP_-s+>@m1cky}pLu?~eBbW-zW%75x|1Vc zIEfi47iE^g!#RlWa9)DpehdM;dv8X)Tpai@QXe6W8FEFgaQ8DuwP&Y_8FK#}ye-W; z3gwWOcc*1cEn$uz-MG%iLI<>d`r?HcTkVMY6zC*#7DN2A*(bbB+g?>Yoz4jN-EiP! z{eF}`g_D&L?nSt{I0rC`QTHrF(jcxI5m(`_-d&>QZ(tU+MlXC-#dbS2zNe&O-{T)%U>EX;&^?$LW+Rc(_u;Z%s6ok*$n$bTgCqkQ`%^gZ8G zEA*9D)s4wfWVMw)s~>ZRVnbHv`Lmkh&+7S^`oY&!TN94t`tO(EsKG$DNbh(}4IYh8 zk^@DDkL*zD(4vzLixEF38e8k=ZZV8|9x^3ZdZVCUE-&vwPFjO>1;*?G;XVCkl z9$T)W+WEQY>gQta!p!=|A$BXozCNs1l&j%EY1gvqoqk2PwueUB`sp*}DlVXF#+9dL zgof+bU8-4V^#Hd_KTaV)xf^e!?z4;aZk{UGrFwtsyDj`NUQ|V7F@9F-CE%i|ovn zdZJuM3poUQ+waoaBRn=2gKNIGaTWG%HPW_KSM63wCXA-TXac%2uRFa-ZlL=!U60QY zd}IJ4F7JKpGfkj!${c8nh8X)L4C9R71A>wz+&hHZkC-|hrmQ(A#N81 zQtb6gKUJXyjVz1sEz64T9x#UsRV|Y!XMVXvuwiG*9CD*@--wM!CTdc>Zl_Ux>QjQA z<-2vn9@YKUvR$8#s6S4!LQKY5m0TEiQU-j51KrZM3Cjn#++Z2(Nf-9+j9sXt*zGW0O95vp`7OWWxysol9~uQk`NY!;%Q( zInpHN-Lmf?n~t8X;e9E2Iowz_k`;rt6k-sC*whmo`u_}j?SBQ1Yvzsgt~8ExfH05A z9YuLV#FxP3`)u1TXYlq9#0$+)_1vqV!_H^+7hs;2`Fmr^JnUKc08Lc09U3F|-CYw=Zd{~VX zvUlrOU&l1|jXwFhN{MjgSdW>ZztFeV^=dK6vw1q?4K<<5LTaHk(ZcT$%TKm3MR;z) z4iZB=na)Yu8Lf-nP;>If_=CsO;$%u$|LYYk^)8+Yz%<{g48y5!0YwAdHLMY?Le-FL z@*cvVn#yX9ji{G>>QZqe&MCr5rO9NFBNb_xFTCeESfPGSkXJXq{`iuXvi>Q+t}nc; zx>xLZ6QivyLx1)b6UnnW>}^(1t(4OnRl_{C?Aj|vysd`Y^8fEe-AJm9g?g^JSHF{C z9Jzd7`Zkhw%R){f?B`w_Q6KV_H!^|m;e79}j+)6Pes}X zexzUDrxH4()4gDJvHGZ8*3g5Kvf{=HHtyC?q`$W9S1N1~&Mw196XMIMGYfTx{mL24 zwVbP9bdR35U-fG@cfys(iOiWlg;qvOXT9uVY2aX{uG+6miBKBvn((atX1}_x*-<7_ z(qO7}_5p;jPp=m!)O!!8&Jy$hO8;j4qd2b7;qR({@udCEchv{OCNb0g zLGS#xx`E>xwu5Sp&93Jiqz)|7>kq2ILL~`h$%OTwn$~RN^^#z?=L_BE5O$piee)s4 z=#koeh!J}yeddrFmVc8!%+sK6KQa9U-&ihb_~D)>_?D9u)#UOstP!FX#iS+X#VsR| z9uGWAxN5=`(O9<7nYs{}te)f)rlOHeo zBMK2~xKHFf=4uy-5Km;eWo>h#FfuJJAxsU^wP^h1Li-(88T8qHAJn$@nW}%Uqu(e0 z+bf2=uU6S?A64x8Ks61p_kCZ#|FP;7+Wv`#Njc|Z-oK=EVJ8kJl#o^y`eQlOTlmS% z8sg4mb!5Lz|3ux_>X!|^jdz7i=3a%+Cu%Cyy2D}BweK-EbBnIlokBFVh~%@izTb~R z`{;GOBL33)5zpk-_u_nRxuqPBAZVC zrba0PX|pSEE5y8Q1o`^%Ti@3)M^wsm$53}Enox4^4rGQL@->kHKW}Whwsez@9Peqveo04_Za&#ke4Mk*#X^2(&qcU_bzFvHj+*iX-m5MtB1M+NqgtP zE7ra64RLzo7wwPt2Jxzx6o?G>*n$XsVR-=l~fOHZoM4I3{%?Ur|2EH zlVRkO`tqk}C`k~3t<~|zR9CzEJ$?N#6%+FDA>URQ7i#FFUV2Oov)}!m-hGU2qFn!W zOkEdUILw{d30oM98qh|M7wozry?#=;zVS0Pu_f2}7Ed$kU)*ohyY;TmRPT_l=&1fK z?%}>W*Kj|m|NIPby{N-KSBZU|PVwp)0meCdurVo#iJI)*cA;Um;La%zO9$@!;F4~V zDO=lk*N!^!sGj$^%4jtQnPgekp0=K!59+r+SIK=!`mk)lMu%>#SsqL`+=}8z)ktX2obQ7C;DmwxXH z71zcIQ$2|#D`LiQ!+p7@{`(7+5cUrgC51v1^ghs`yB{Z(p+_87aryDYiVb$|m9tlW zP~Wx%G=lP@f70D zEgt3$?94Fx-&b^kXn;ok*7Uq+n0r;STn*ebc^Y9(A6N1DKfweVzmLJDhth+We7cSv zAi^-Hn1&}dn2ipwUqU#!LZ4GmySg?r4*wAln4DGA!(B-hMgNVba%d85@6T=(Cg)Q< zHdYtjXSd5hxETs zD2Jno`y@VD{^9yYYw7AgolW8)-SkT}Fz9dIOPE@cqDOtHQm&CCwtNNaa&g* zku`26{irmUVj8>{04e-Q936Ix|NV{PtYkZtxZSO*zEqJNdyx(4h6zqb8RNN+eFoPP zTvn7SiGB|g>n;cNl`p9Q1^>RJpT47Se@R+MB>v2$UW`%2|E zJ;HT47Y^#XzE<%)t#CzzS%EIeCHw*U?^#fmiS6qIl;W1zje$+Zn4YQM`A$XXZ@yNo zZKw3lU#rA+rDUd>5rQm0*lCOV7#qznWQ#hZ2i^S}s&wf%D1Yo358W;MKsuj1HPX91O4l_3LE9ODnt^+c1W-|+h!g1o$B1X3R*BLboLS810*EBgUPH%pv(pXLZ^*fc6HafF@*B-0g?Ok%Se?E$oV!Go-<#AaO#WRqXe2P!KNC zo~fIiR&(sl?$_7Ws06*~wCdLJwRbOBo1+_csz{4|`CY0E{51>)J@4wDPP297n7*cl zftR75t6}hK*C%Tjjh)faXH*5_wQx8~SB9mpp)_C(w zZ}!?PPO!U|*qdO0RG!7fhWlMMHRs#Sb7L~5_B2vyY;VURolMjrlSR@(-I^AD^>3OJT&;KH`31caK0DpwzR}y zgKzb^H`0bXFUbu5Q9a5~;G-WgM_1^OpVY*VxBq0jb~+gq-me?KbVK%Q`{F;(B+VZjMh(4{cDI5j`kBnv9(H0 z3fuPU`9G`3sQs8y8Fh_CcB0$&HhCdNqE+hWex{l?(VW2+ zYZ+24*{_HHqWUEjHF3L`RNBxhr>OD2R&wZ{tX>0qPUyy;?COry&;6o04f(XMS6`m$ z>v%+xpYi+0UcRMWCsz{<;O}6ruX+~pJqymQ{p+kkhG<(I8}_>B@H#c9%Z^+YbJ4^? z#m*7+VOVbI4w9GKeP@C*`Rzc~bM!rR%)SbnSZ^I})jR5By4J*c50H^$or=wrU)1U+ zU|Y6Q41qrp!Nc$+d!ko?RIQ`;P?M$elB}*Ij$~I_t~?^ON)I`&`X$V9`Pdy!&ZTd1 zRt|O-ml*Er9~6?NCx4&bcwQyjZqilfm8qOV+=DD1<(a#WSp+wk>YhI|HT6H|(Y)N# z^DB1G^EX)PmYoAW!^;y*FZR2Pn+z#0jQ8qH*b@zmc+t6 zH(;=I}eWJArr6Ye+qhtOP6ItyiW@$HH%s;uDP<2bd80uhq>k5VkIkf3Ghq17@ z!l>^|ofV!R%4(_){-)w%9_?{Oqm2$rC3IFb!$fF$UVXr;7w^{g-_;Czc3YkMyNXZl zdxotL8KEc^u@gsn><-t_8_|Hfn#;u@QPywq8-GB*{JV;|rUT&{haE}SckD6ePV#I` znUx-wSq=B4w}kZMYL8;vg*m5_w_c23i<<;0KXNcb9e*@o(Qxn}HPK}9`!?>P zD=Sw9yR-e#rr{@>8&YYTuL?=KFR6GM&(ru7<0lVG(N7$%uJk1(zc=6~8yh z-|{DOt#|a(f2xkbJn6^Dlmg21PmWBu+G_8gDj~G8nY-ItUY$*zr4GHWQ~y$qK%=?a zp>2OLI-2{JYG%)9q3`}n^$1?k!fhvDbIYs6DnKlw`~#8$O%UwqR?>vXQ1 z#x_MaOvnf={Ox@mazQ!lRn2wE1$ZfH;m%JOTgNkxrZttJPq^nTR@-{e zu&4}Ww#ue%$LPEM>!e#H4Qi5Jcu|@CQLR3sjHv5KPj!lK$(|xFlV)e7B*Oz~c22Hq zAf;1CK19EDk%4Cu{o_T{^e)}KUd4`+FubZTj4;&FGSR*1u9nnL<+%el9*K+;b;%fN zLTi>i9Bln5Y--fYreSf<4suOcPl?LWSxTUMvVOW=^&7b4olDm61MOcPjhR<^7Ovg$ zeET+L*gFRF7jnY-YZT1Szxf7x@;jkYH~(A3B_X3smZ^i_U?nMCkB*d7jlX=?d~U|R zF;I{FTR8^9e<1q@en*0TzI8>H5PElGIWT_RZ-*Ky=Re~=+u}RQBVnG>+n_KMUy+(v zk`w5Oz9AH4TP6~yDs1T%i3G!k>^NM3f|E64+Oj3-l}3;bx}*|<;kT4s2t1p5N%ifB zd6hG}G``|aM*TFjb#W&)_|Y|sgvBr2Xy%@**I!aY^R3_6G{y|VWssJHt!C?vq#z^zwh`3nhaYa`VTof7HaOr#tuz{)Tla z1q+%)dIQ=67)X4JpA0tc%MEeoFvRu^D#AVIaF;&EK;Ot_&ok(bO0Mp5F*tBpQ-QXg z?eFNE%PJvceMj^(BMWI4`?dSBx^6@vrVZ)N;xBvq8CbqH^V?u*`XS9m2D*hS1TTw2GZRC-FanzerwcQaZIrx=X9`V!`!<{_%?H zmwyXf38%h|v%J4ba1q*G{%*qW1%&qbzF_x#D?{7^5MD8(KcC$-+>?vHWfQlA7vZ@D z;W4`GBg6GVOL)8 zK=MD4{14|AbuyCe&qywUsKMg3^r?Hyl(0*@4=t-bF6L|rNW0}zd(FgV@({BW*Dp_< zG5ZT0#hGZ6_wOu1{$Y<03hd1t-g>gl?CdC{hCCK`QCiyMd%2bwrezf5%yL-z=QsVF z&5Y`>dQ|JwEEwe`DWd`3rzh;ff%i>q-FKy?&#Me^$CIBN^u;Q4`e$$OjxAh|;%^0WMwTZFR*{pELc{$q#ZxJbDa&x5sWjYw z6ZTl+n&hWt4GGay`|uZA%g1{B^fpm?W`LPtdxSe>%~4@Xy8AZsR&%ITR1t5V1e%J+ zHo^lNIY6Bfdi$BI~wi@@95W?n2EH}Z=0AIw@B!g z#;;P{eq?}mHHIV7y@JNx6aPvI@Vhp~uRlW3r(d~c%^B$~#=kTE4(!j1c_eibxv^7S zMXzLWuCxAa{a{m*BUk!JQ!_0sE7C2mEyaSX^EWSTvoDjDA$q5emXfAxROYn8EyzeHcK~0ur+#eusM-EK-+@NPGQc0K0ch5 zwo{%7`ed-#+g|d9j%a3f=W!{Lm&HwC=d@5~%05Kj+|0a=TC};DnHciOJzlFLm-_Xp z{;ZkVt9gNZrw_=i|3Zf~H$6To*-+VsZV1RhXncRCk2E(Eh8BqX%4{+WmQp_?#Upzq zbK%L){Nh_l>P{YBrjm)IipawlIh1TU-jAV(6cSmKeBpS~Pf~!D}hm zt6_3TW4{y}VYd>-pz!1kABIpCF9G=FQ1wa~b_p*p_<5P-=OxK6&*jx!-G?kc{aXw3 zdfW3ly`?#yC%1@GB+Zh)TxivB4NeZ>nBNqX(iO)OU-A)8e5@cWv@&09ULcdb^gl+_Kc@S%HgkMs5l{YdWTphwz*OX*ZK0;pm95RLz5q6VfD!_% z>cx~*0_548`nFK>uCQ(_X-Zx8S+4ePU88>vHRDE{a`^fx106q*M$_SE--OZEt44aB zWL#GqFWj*up0JIztTeDwXxi`f_%JhaW}E*J^%xUG`rCr|>QVK76O{>$C7yKYBSbS5 zM!Pd9*sgmRk)oYCF}5g0Ls9w9Z$U$K0E^I2l?eVcTB=Ev;U1?y3Nr_X64RnW1rLN$ zh>mV!Cb5<}w2j%L?+c_Qqh_0B00{SN?&zy9q9bJw(8o)CLSNy}P9o;;3%hl38#B4b zHG41V0NMHd^~m}$TdlsRU^w4)`XvK*gYV6+Sbb4J{MY*LHfH-S9$L4Icd9XZh=d=c zb^mA7?rYS22~()Y-`+ZML^+=gqOg&DX{EW9G1eM7hS#IJDz0cbzl!d)#I+JX3Aci_ zBAWnq;Qy0$hX*NLrpzeEUweFejh&R#Vpip)bCr&^<_)H+cl7SB3s<%7tV2yRI#^Pn zX0un(G&^I`nrfPfW=5>LXogWQGZNn*B%1qh-T35(ARy6qITVghm{FcK2$OGSPf?!8 z*L^8hl42;Cwj1FsGE5_EF>6;Mh?o4FxtK1<1Y5Y0VMveha_%X{`Yk>3IDS|8xt8B! z_zlfg^;0N~&twk5D3aH_!c7yVZwxnkOg#|CFsZSSTy5R))C3V`4T4HWNJ8o-!W6)U zRSy@8s$aQ-yKJO<`7U_TU%q^ge92$F3-q_)W-qRJ4vR2VyPYH>65vS>tB8HABF1B4 zak^Ef6U07kuf8$D9G*U$RAk^L%L0`QS0zI`DmamNM}Pk$h*PrXSfwJ23zLQjXeHs! z6HoHDP@jk}M@KJj>&`=oy|919*IMMMk{xW10O__%sE5PqB8n2kzv;}`U+X5+@c)C9)jqM0-!d@Ay zeNJ5Fgcj`vx*4RMT|+C@R=^m~Q36>~?Z!Jx4N~R1!sC}J-&0@qw;I0B(wZ7hDaT{l z>ED5QEeT(~ugbb%b z_RE2KX0$mdWQ)tXHP0g_u1viHr|=u|tz&k{D`g1X+vdiYwD&ZZ*_tWg5By|#d5T%- z7Y!Fc`y4{2-O(6%8#2~zA&P`YK$t}8m_=hop(D7EA_byZt4?wUii0P1716yU>+ zNK3r^LYhjlfq1gLc9q|MCGJ9dA7PS^?W6erTc6yAsu>(>wzKWkQ)A8Heby0N#Gfre zA+vJ1!`j-vWxp}torA`JJff{9j1*~6dc3=Mzu|sdABi;wrAj8x8gXvpnymk_c|6vL z$=C^OX@R{oW^$$0;(L%ac1v%u?HsQgc$l=A7J6c_cH!-Ackp_+onF z8p86VaC`Hypu-0PjIy&X{qOeXFouLpGr$F?~A9Jx{hwbomphs2ETjyDVV^0!=8%Q z9gI4seMPI`~sbV7}Kw`)mxIx zzMQ}LCdup;`0>bkZcy%E-pziLhdP)kw&8kL2QwokHR*~Dr;qvI@ASR-HgnE8I&e|; zdF8rIM{^)2ipO>|XSCUtctxkPY@Z{$59z|XSLnApnjM>;D;JF$>-n)<|I*RyYInuy zww=uA@HZfvCB2P9x-0C%WUsfrrjyw%n2a6Zs)%y^KqqqscZq$|$&3wMfn2$e;)z$; zUB$`Lhjp{gW_n_0_w*y!usAEZNd}FgrI4W2TB#CAGcmq!rLGy-;lu(~LrIP!a=U2Q zSA*KAvjHR+coRusIQPS=cB$lR0->1!JWlUZr5w2~XyKnn|%u<#qRoe5l}xUq3K z$nA&K%t@{ZV|8>FGp@~z2;f(O8we-sb8k8My0(j%kiP_Dljgzfjrh^VuX1#Xeni^% zfvK(uDI_IVtW#63`maC_B$7lR(&&W$Q~x8r9e;_RIoUNK4*&J|qh7DZPoTLaE_Xz@ z^QLeYECJ-+lZFy_NZXRlzWuHSE+*e45L-2aN=(@Kgnhg*G3x4R@y}v^*-kw_*=%oX zuh%D=De-^4c1cenctgQtGhj|2ZvhmH91;9le?#c}t4T?<&wx}QMgPgpE4n{%pKg@Y za9Bx{LcI-xApU*uf1;7UHL{ahGJ%a+_^06CxCkwO=;uvyO{l=%f&U}6evJepd7<4U z<+vuiLV$JzK)qQEuEbqx);^fX%ymuR^1-g=sK72UY&$+&8`_gL*1emV(mD|bgFaT| zIhYlVVLykC4fv9e$A1n@(L+V#!TUP|em7ug$L~avh!Ad3?8nUul#<#FfFsr~1e4=BTkxM{@%$y{!zD z9GASiBs*E6t%=q^LZV+T^Nm5|v=AEYY7#k!q=c|C$ooS-(8KK7%o`^`P0tj)vxhl{ zb4u+}%*dqv2?&%`uLl0A=mso-6Ipcq+a#bvKW`e_tUe$rnPU=1N9qSs%o(W{;Lyd? z<^LA(Ng|?aCrHPNd7=Im9n#ax3WcmBAt&gPFaa#l5A-yr1zt0P;wbAC7NxUN%}^bf zYR2-WV0@~%B$x=Y`JHXEsVK%^{Y|Rb&$d#B_c8}J!!L=6nnZCbGCwt zpZb~)*;#}Q-4n7lr%k4(c2b&AHNYs3{MOi?He?Jq1 z@&Ucz| zz++Cc#P*8rm5vRhOh25?wELBcztgF%xJG1{8TQ1^71J`zEAo5l2;#g_aqkH8ZoBPe z{o5#Ws(t2;it9%c+4gcp@iiv1(t`NHE_&K^K@H+EM=K_t?exGQwu4ul<+F=j#&+e`Z8@n$|ZQug5La=SBGADlqf|B@a$(frLm z*Q0w)G86l}B>jw0@Mkdlk2+_H`F2;~zB>mvuv5MAw^s)-<0{;j;+72!*y7yrWo_L@ zw^lql$qcaBJQa^khN8V*|^uba%Zz}q*Ob->FvQxYEi%v4(IHvRro^SkJ6 zlAiBU9aOB2i!~NHIsfV0RD!0R*U(zfcDEc14| zD_O71q99(Bg6O3S)`bP@p4n!RZEMBRY;#J}fGzBb%bMKMtZ>dUO9Cj2nmJ}(#OKAV zPiL^vhpWT6yqlqPxaUZ*zICp-&py4RB4M7n*q%|!p12jP8XBSfvW7eFiHmKws2c7r zkoyb8iEc6HM>43mU^m6%pl(Rk>x=69C;`p8BWZN)g>0%J=%1Lz_uBPq| zP?m374R;en81<^gsNa>GS^pVfWVg_tY|M~wm+#xZwN1&TNL_eWh^bu*%_Mt%k>0Y< zygeO?m4wcMN)cyRBy?@bC0&FWM%?UBPB4vn8iP5TI$}C^7fmA~{H)4E(N-~k8pG?;GE;jqx_Y~<@ z7gPSp`rE~3B+m~2wb<0*Bp^#5lQ94~a(z zvG^#%_g}mp+y9T>kvjS=vs1J2erIRJfV<44_KMxh%BCcuDr{GZ*XYSDQluQ%2lyeZ`}z zso9Yu=VmXSHGBT;jzu$b@4Rc~qI-Ju=wU3%sfb-?j<7{$=NOB+<`~)hGn+ff+7i8zoUUH9-0z26$#`Pm^nCR!Ed(R%d^lNL(?7*Bm@0_bc*P8L#x!P=| zM?7kduh_8O{La=E796t|J96)wKYwQKl9_pqC3iX&+<716O)nklHk((}J#M~i zYuckn3jgcp+-9|QZ7>}H@@o$ty2lgdu$U2}#$?W3ykKtjJ&xpV4t`Bsy6Cp-+?kGK zJ?9DYoVGtW+*4-Du~UquwuXO( z|NFK^ZsM2i|2-X?V;F56Asv!K{+It!Do#9QcC`EXuV9nLgEo7Iyo&puHcJCrMV3Xj ziEM6kR0ECVaHsD5yqT6CKJ{i}YEuW+A44}8)nsv#h$hy5ZJPP8iP3-!9&H*N8qjVu zFpH;gDF*|^s3`!}4go;+&R@H@$9!*}1Szgrre1{*Yd!`{>`(lJc?G}~*o z>BhbG{W$Dod*meB2xEc$A-ym)l0MYgY<5LKk?FKmd|Yg{3eeS?%}V{|7IV_@=3gWZ zHjIc&i;Sp2buw_*DJ*#laJL_{|Hy5bFN(yDb-^nZRg4GIm5X{-CbXx^(2y=c0u z(jL9ld@OSI{3VXXOLCShnK5eSl2LQ-Suktjtn39dwQH*xtJ`nK{Ca1Z85Pu-I<&0d^Yzfi(=_!Jgm}a16K%%mVKRmw>Cm)!>uhv*5E}8CVJ)0Jnq3!E&$`JPQUt zO3@9h&G#np@%2DN3r-(Y>&=tj;3^3)xYk<=mV=dG%OSPiuff4XYrW^eabVzD$`XtM z9m8t9-N3U>7zEAXFa~x8OTlH}hu~K5EEt%XU+Xm~>(Wf>0Jv!c5y7paU;w;0y4HIL zTy`xI0S{b9LhC8>F-QXZa4ez}yn#9cR)dGYp5tH;{CXmFgt}4#ZU>X5k}#MC{sW%R z=fm+hBASK-z?RdI0GJ1^0(;&;bORqHJPM`u$6 z;7#BGa29wRTn5&Ht3ktU82Ov{F!|UDb_Vx=gTX`KIPf@_2Udg2z_Z{w@H|)ux^hSW z49$fxun=sy0cD&AJ+J`G1iQ^dvS1~6KREa{>dFS%|5-lX#9_f~2!Nd_5(i_Ebt`MV zqe0gy$`D-kFtr?9vIYj21}%FO$$*9HsT1JYjbvmK39t)4>RFoUGc;4eXMxpV9{2}1 z7Yu$9hW|xfd6M>@$;W6MYQeeSAD|1|{w$RSocZ0E91LcGncxy| zI=C9l0-pu*z%p<(_#wCstOg6fKfq03Fp}90#)6e#Pw+gL30?&AZ{p)0KIVc2n|T`% z5teVE%)xP6DRa=+MuK2}a1S^b{1D6n&w_d2Kj17d^l6F`Oaej`n6s&v`#=!$`Aqnu}oI3A^;H0^A-ao*e^Xj~v zUm*VcI&T)3Kb?;!`6vV{!L&Q;yfxssg>~N1g@_tl0>&=ir-<;9g1*tgiDGfWhnQyuq6x^jMvD95@bK0_K6M!DZmH;Qe43 zSO^{iU60p!%`If4pw2r9JP#IZ$)}9nb>2NVq-}uX7ZKGHBnS@Hb>32N`=&bYd2kOH zxRsoOQQ&c~8(8))2!RU3OvR`7nX94r7U!BX%;a1VG4{1E&atOh5&ROb!dPHWmx z=ba8_zD3c3&UYx%9n__L{06hY{EK{4^3n5UboPD{1UnxjLGS=r0QNsbf}r^x34pa= z(ktZnL&_X+Q3*f69UOO zP9Q1y4IT$;L1P!KWd~~jX z!@YLyJ0IUIBzYy*%D%JTq zuM0GOMf6}GxCd+r9tM|y|A1S;(6CV{nJ|F>!XqyM0c{|`;~1K)T)CyqZm)3w>v z-7Q-?MRvC+idtcdq6mtxLEZHTdK5vNSVd8kWa(0_sJk%XilT^9go{%IU5cP6TLfLY zbO}>7Gn1Lg%w&9i&${n#9*=!IU-|rb|9QP%?@zkBoy39kNl!LTvB4a}-*h7*>^fy; z>}QHC78q;UPAqbd+w5L5pwkA(IET5x6q9G%$IMwvkrhs(?q z)ChLjb+8e{zNJVz8o?O1&u;`P3|-I&hQ6(4nBoYhnczHUxWpCif3re^+g!T15oCwf zbu378_L4@BXXH{Bu+7MKyuL#t$S`roMo?gzn_Tx5&Z+O3Nnaya=O&x%xTpKRXQ?>K zZO(AG-+ipHvudLEX=H;5LHd4;pvX0Dv&sf11{y)f_uarA);Yk){bhhXS2u!XMjs$U z9EiH^2Wo`_?0%q$ao|CXpu`pKuq!9@Yr@Hq7wh zX3jk>F#3o_P~q^fneO{21No7)f3y^HIo1ejEIg(WBz`PYk81>L9DTg+O8kk}&oN*& zGmXGsfe0;RUv5nWz1K+*^IT=eWFrXwR0pqY1S3qpsu9d`@zu_AcB&C{{mg@jLoB|= z0NFn+bKHBq<2T9R8y)8c*SX2s{_8i((3bsQm4OLC?Rqog#9JG|#lJuV$O8tkxi=c7U2A58R$qd}e% zR~`+rML|Qb&G3DX2FYD(egC6DopV=f=vMpp8XYn^=sRM$#58LUIT{pMf2e^nJ!D3I zH1j8Dhsh@%4Q9B`1=iz7gDM-`=I~RGW`q7eDTb$NnCnk7GB!t#2Ak}9`q7}t0ru1t zBV*j*BpaM%@)-ueP1f1{OauS3UBD48Ctc4r7uoSF8D{-iStAmRK3j^p@EkY%B@_z% z>(QXV3U@g1+@nGN5kL1c$;Ib6&mvb?;~FCqM}s{MFtn%0*uyOjv&9MSJm1o=H~WI4 z!IGdSWv1NV;9t!kZDt%{i6w5c@-hwn%|J3{#F3XD4VJmg8vCy^^V@8<$)mwM6I^A5 zyWC=n!>^LbhW$Sx7!xFz<``!<&IJy<{%FuJoE!tsX_Gr*?Ty1cOqc@n~ar=KwPBa@8e}-~ zbH&HmUmDTQQw|`>Cjhwtil``^sPpX6G zh1Qwm9y84SL5EE2N+D~vD#{M`{aG=x$wdwym7()>bWF-QaKeL%i>z^*{(nYj^i)<# z1Y4($2Gi_0Yi&8g&;{p(b~(gITL+ADinVhFz&dw1@b{xZXZXBOii0e3f|vH!Z?`HRo<-;Nz;iQ!Am3oSp;K$tBGmIZSUIu^7z ze9f_7_)-JnDCd}B?jgs5BIA#69VZ@jESTszFSPXNW5FUrk2w}>F*#yjcaYjA9t$#D ziklEa*E)Vjnc)<-pK>gy-0{3@X!NPag0=%Y?7vI~o^~vlW$QY}8Jav6B)iRkGaTX) z(_H5q>s(-)1$N!(yioX+GRnlOwZ~BwIK~xDaP3Z6GZXAOP-6IUzwp5Uc1-!^bS62+ z2`;h34R*ffSkPpe5g$d9dab2mapqW1?&6s08@MWEi>kaVE+I_cyWd%Ee zG7Il96UN>rb$3xb%(49bW5EtL{c`ruU1f%&Tq!uut`C?IbKGI+gU15D>=D{yj7^Sl z?!R2m#D`>xyUa$faN$Rcgs~-S#c=UhFnFZ~nPKJAI$-|46%jYsag|#6ycu)7WCCn| z;aIT8{1=Y}pSfK?;%6qIu?`|`?eWz^Lsk#vrDRql`ZZv`74>br*?L{=HRV%*S!?sAFWMJ z(Dx_1fN5^B$Tk~wyW!rp*Pji53C?khi%g#~)Bf{9YaHN6%XLh1mKBzmJfl`P!=C%d z#Mxs(oc-Bz8WfbyKOThdE4A!p{C2*ilNrX@eZlcyj=kaI!4?Nu=MvkD-tTyjzMs@H z&)$LK!5X*ke>?~c=}K{wOU<3W;3%rM*epyR=^Aj(zFbCZk1$Aj4Y70Evz4{~fU z&lZd98ap0T*uzcsvd&u4fVlpw<3ZQeCid*(K|lMSb37R4)N_vqqxj`>(^2oc){^to`YOsjAf3n$^^GL#s#>;J2x3fejA^FXoU|lty;{*cSc9)oE8KmpwPt==kv_z3VVoVWKORi6 z!XjtiU}F2{Z#W(#9;zld!5XKy`nKcQpd?s&`|+T~+&c_pNCw`0JeXzY`_%$71tWf# z3~_|xOFCfnW5a>!R#N72YrG9(_H2Z=XMn#%iLl2t!DZd1L82le>5&Jr)hW>1AAFC)i z#$C>_`!C0X5}Rx?bi{M!aeiXrAhR_=TCmF*#{O!itg&;%2>*6G7-Ebm#yQPA=efuw zF0;&$hM7HH2S?qSxwsh&Kgmol(I6MQ znn8g@uCT;4u5ycOtaFELw%PS$_us*QIm}_MGtD+{6 zdu%Y0wEtW8wRTA-?q}`TJ7DcN#x<_o->!I;j@iwTt1S^z9A}LS+~YDs56}_2xxs$! zaEMLD7=E@|Vk9e=j7k;PSY(wIZgP_~?sA7M*4gz>Wz;${to3V`|ty7bcu!}Jc zaEztgqficDg1a+xDsVUlHLSYeLa*J_We2?KhO zi9AJ3ar~*?4Y|W5ETl*KV^WW@eM%m;D z+e~uqxtHW_-U8(%J^jBuQBPI8d#Nq1{9S5iUyfEp$*SepzY5Tt^=zfEaU+G=x zjZ(#_86)NDn>6q$skTiQSz(FWT<6&J_V=rupOpc2y-fzV!C9u}43LR;*cDS!&jEJ6 z)2`s^J2jLOO#Qp<#nE|1!|1ydnX|$oYwwX#PJGbw|E+ddWcn>SO6)Bzy(%V<|ZrL%0WaEbG$b<8z(zC&?xkdtS; zsc?q#+&pJnGJ5bt(EU#5FE|lQv3~m#L6xHyp9nhtU3-_D2x9EM^h7qu2wHbO;rDVi z6gd%e&8zk+PXy!a>~|v@?0A>!1{`PK{Z9mQoO{5Dpv>8!6G7?!6c)@C;Zy2 z404@yHkg0pi6HtOnR)byV2#6%&1!f-4LtUQU#GRNIl1(_bDfWJkw9pA%{m#1T`)`{e<6w^#jd6X_sqUWbd;~^glhKvw}WB;@KyH z6w6#-^f?-0YuwE8*7RScjN44J|G6iE8BTG59nW(;C!T*IXmRBQQvE(l$X@op@I)}k z0md2SIJ14J6TymL=tWY*1@^z+OgYNvi*>{yE^wY3+-1jM$6q3)jB$ib`=3a-d-UPYPlVONiK1k zW#(Ar9Jjf^#s}>Gf}rDrI%E$k9N;En+~yb?OtZ}y4rdIEy)QrEmr7-d;r}uqMmWMK zQygQ4X-;v5GhE0DW(CWf=PFmY!8PtMcbytpbRCB{#{~17;0C8S^okQfiE*y)pMRwR zeaL$ThdKHxyMx77D?-jsod~i`!N_Yg{9)VewI_mE#<;=+*SN+H z^LlH`nYUQ7kK5l&F!ok8z&6)7HhUu2;~cw}WrY1KGr{((j%Ngs8#Ks1mN~^8ZnFCm zI+`;8cD_S~IKdK^S!0QN++^1$)e84NC9&~N1LDxXp9qRfa)Z-su#gpWf6B}_#L;(I zOAfrpg$yq!#-ahfS3?~952iY`!6$CaU=WL;4uBq+F+DXPBFtJE^w7oACe(1e%J&)t9CwOn=!rQI89$mNZ!MgyY;7 zyypKW4@;R#;%^ z>nDOO4u3=Smu=HE?;YH}(Y9sBx82WvhQ1_I>oUy9cV(EfKeLOt@pJosMKJ$6Gw0Cn zUGTqVcB^V-=1&@8x^5s}_WCboz?CCXx~do(Qpj4<5`0CaA%9TV)l=wvX> zj!pyMB13CZ&p}2mJ{hDr&P8sp#;!|TccbmiA=a5;fA-Ro!LlID8k=`8pl{h;cRU#k zbBv>$Ws38hW}frxzU*YM$t2sHW$(8QmonC6-xdi(TJw{*ZyQ!AYiiEGa{GJ{jzBo&(=C;JY~gUHgARFzY~? z1x|8>(_CZsT~GR@QftS7?@2kwI2(}x4qss@m}Y~^?5HX}_Aqqi$soolrdi}7x34nr zYSxqLZccpP4DNn1D08asWDxyLDi`l(rd(!t!wrnE#wcS0YJhQ0bCmN;a)}cxGs7yUxy?;>{zyCQ z)MO=Kmeaq!182L>G z5;rhzKS_-+cC9tv^59`FlN@G>NltQ#GhE;tSD3%n{;vv_9N6UwLqGRs#0b|JEymgT3)?#@=oL(GkQv4~&2i3hk_(*WA`2{X zg;lPx#a%|8qIQ01<{ab>GwgY)nX`|}jB=IPVZo*#!Cg)Mlzn5H{1VHg1+Cn zfeH4#T(NM5i`?Qm2d*;!&eC7%4{dXpgRihH8RIk)oM)0tOtH*KRyo6M&asgdGh#NEzYGSG{?$ z%o*;n$f2*fp0Tgl|8+s!fi_d@y;VvpYJszy*8bDU?1W%jJAdM4Oiw|3u=F_t;Q)$f`a z>)d3=_bdsMjQrU|IKp^UyBy;ZGg-m<{spYFz|Oze-|S_HL#!~tDkr$bDeiENdt79T zC3bvYyX^%p(8R#pWPO(xX31JY;%u;KQO>O_i>O3#yQ4u zrZ~wAXF0_JXSu?8uI<_XdBK(g%dB&SZI;>fS8K;UHhw7O?AWkGT;baO`5!5|zj;pl z*#2kVPwWyVnBy4pTwsM8+-2{k-F92nje>#OR4XUA$~>E_viwtPx&NB|4GsRx4B29V zqc?eT;x0o+Wp2wrxchT!&Ea2I3YOU5;4e++n0}bd3WjSg}eXnj^g4Lr`hH*W4D+9*V$&3T_?Pmv5z%ohXhT*1pEG=csRgyuCc}F zt{YC;6}Ni7=LYkvbCqpwu;Y(*2}c+{WeFJJJV%&kk~QYI^GEwXFQ_|EWP=s9xXJLJ ztQD94Y>8U7;So1-eou$oW`n!zIBgfOhYd#A^H&{mlsV3^$k1)>ITob`NQjHRai%W_LY%%9d_TP>Y)oH3R;$tp{K_snM_a6O|3P6b`( zEN%ASsi05Ld%IIXnjIIN3Q8R34r3Re3Yu&%{C5wOOHTz+E^~qnE->A7Dp+QYRrXx2 z-N1I^C|5YmkwdQAf8BE`*kg9}E~orv_kqwRyV(ndEh=xqmhQ?y<{!z;RB)3=edFH=bs7|+518rapxtcg7FJA%t_Awo2B78TU>g%0bg_= zw80z)uRG;exMk!GGIsj|q1KyE1qFt)mX@XK-N*P129WKPnzy-trFWhRdM|e2{HY+t zZca1*9vyO-O^z&_3I;B5oJlS*!xiQ@|6T*&2KU(iAE$zzOAmw+9OfuTIn8WJkP}R^ z$a$8y#2U-oVU^+kv{dY3gWc@tQZwvfi~}q&$xY5Ml~*$?aF;Fi-r+!K;r*ww!Gd7r z{fdoMu5ynX3?DXg_OZ!0!*|pmBg`?%WsWdZIOUhi4}>~7$5ECz#&u>`=K|YY`hYbV zxJ*%f&>FL}Xerq7Ap>CI!>5A5?gOE5#u@pD3~_Bq1~~mu1G$r#GS2CbSpv>5&m4=K zWrcIxV2#UcaD#2`aNrAO9yt&iVuWdqaD{31 ze^Ie=nKkzQkC|WLdiHUYLmXp*NltK_Q&-sk6M{JhQe5I%`BbpQD(l>0oBdys@+)QN ze{DB*Gsg(?>|>EVUv?jt*msrVt1`nC<{ABp-NaRPWP1;UhQDfrT;~+yU(*mbxx4Sz zJ!jNDHKe`|?2 z|2u2U@f}MvAS3MOGKbmbB$L@&RK1|aZBGB*qw)TV>JL)SK29;kB3HP*|9V%0S6dQ} zGkmMH=KLQG;4dyKN$L64jkap$&^g;}(60Eq%yE-T90)v5xWUp5F?FSz(6Dw{xDU3tB;oX?8tSDmlb0PB41=RlrLACrJ6z^!S1V{Re+Sn++#26e!;Em2BP_DXT~1xr z3L=k?Sw@*>oOO0+tPMyN2d*}94sxB#50DXdMRo8< zGiQ<;TxRJSnPY<+Y;uP~gRP*+;lWlm2tUfcbRfbEW87n!ks%#&{gE>CXx0CiRxrl# z$D1kppU?^_?0cfrGs-;=xy&NhxWTPg zDc&dQ=hcdw+45_3Bxp`s8+N?j+Hip3xGLu$!*5XK9OM)yIL8&1*kX+%Z?sfTGGO+z z!eQ1q%E1|#V~$Htvj1Cx9S0`gr0AY(yD-k^n^iZ*Im&ozdP~G9b|kVMk%FFtqGOChZ?PmSvB+&!7=EiF;}~09V((MD-_PoZ z)0|_CC3f6kmoUm2XBc{_rDH#1Z_`g!FfUkOjjQZMecsW~07#WJ_w zVZU?nor-kS^J88uvA$r&T=`D}eYzPRw$z*{*d-kNfc-!4PaY&oPH=;}oc^ee{@F}F zA$9Ehq#3YKw3cK1v;naHGX}~%cK(Z0ugD;KKWmLy;|ixfXCho;lN$^_L*_nj|3?L> z&wFriff-hqW4L4qIL1xpxXTr`*kbQ972Oxq4Cgt;0_V8QMV44%g;h>`(EyTaWL2@u z3Nl|+Ossv~44-AB-%xzad{btaxKYO({g!?FY}@JE)|{yy$N)!vXh3XjI{qB{np2$l zsR=OgGtUR+86KCho3zjF?3St)B)GxUFKoAeweJ~chU1*$Bpb2wA_E*?nlbKhhI?FKi_7e|{B*F&E^aWw9rm-y zL59=zJtIsoniV7kBTO;LNoJU1jteZXeHR&F{z@}^sr&A6I+$ncUZ;aSHu_HoiGMTD z`<@Pp3|)OX7hCAG2WKzeEH8D;+PUg7sxU3Nhst%O7$tw4_ z&FK*xztV$)QPv)RI+*4j=NW#2`{}#6f(E;us90ZRpd95or|5ggf&$yDuqSR{jAR8( z!4P|1ZH+k0NltKzQ`};aJ5N%SQ}+Fnb-)^D*>|msao{PIgyTYek*T5S*7?@$4IhL=}5i_sU&>P+GDg$Kr z)n>%R)ajsWMwP!t#@O{*nPM;JIKV{?vBVLsv&J@OUZ6z%0K>KUqP?n-v8|S?3lb zIs063Cb`56SD51}^IT_vweyg=( zFXuSO9j4j$R#m@$oV(m$&#W4mwIm#2jx#K=${n`Yd4mVs4N^2DNZ#O0h>^EhJ65^P z)Y}!=+sv4KT;&kgm|$p52aLW$!z{g12HtMq^WGbne3#=Kf43r@v&8R_3APtJpxBXp z@9AJo(92!+v&ASo-=TWh%NPe4XPl#)VDfz)SS%LY$13~YY2Y8w5m&gx#0S+D3+(-O zOT#3yor`8HnBW%YS!acv^HTjG&vcG{*#74@mzZXmGpsVlZFYae0N!O_Omc2X`)qNG zk&oF0?^dLYz1#ku|G1)aV2QKr{G?joYEkOnqocB!aFRKezhoaXRk4j0_)Tle4A;5$ zExYHvmf+hu;0VWN_UFDHb@(6>hV}*!N}VKMjOKSwT&ZVw>~q_<%3f}>pAAOYkvDJ-af%5R zImOD4bjUUCG5uq2PVX~t##v-`ToC_>RB)Wj?AtVB7TEiKBWIj#j&0^=q3~6>P_~4sNhNFKsPtp&pLJ3Tx9-NmXcM5Kd7Bw%M=s8&e}$TiUWBL{6?x-V3Te3|Ca{0UB?;D zGIFyTVTz$eYtJEW{?>WscXY_`EhhFM{$3GsmkS*IgMQe`3fh9yuKoRCsb+@pTP+30 zxXKA`u*uGksOmqeZWjJzrd;MCODwU%byiv97WcTr(2}3D*v)LME@gtAKl_1zQ(WRY zYwZ1tRDV>}vX9do;tCVo;sjfqV)TdsF~vpBv&1E?v&n zZD#NZ4X}rE9N;ozT;mwGnP!7C>};3-d%4VEu5y&w4Z*UY;&oTQyDd=|~!v zJV+R0gJbOZyLPzD5=&fXnKgC>miV(eW}G`5r_Vq4EElvmyMN-qnP7*tjx#~*bJmb! zY%_ zAa6IFaE1L`;~;B{bB_h~e#IK!)qRXd&IGG0aA)5u z6!ljv!Id(>&a1LgAy~gkLmcQ;JYVz3<;cGGF;a%_dnQjW(&yKGfP*%_*SmpprjIqKoR+;7&XSl-!?s1tduCn85+lpP>VT4Wg zGyDyiVub4tF=1}9$ZX-Ewv`|^q#Z9&zubppuFg-yAS>p_MxxfaOzn!(lf>j5?Pn1G-bBDcba)9A=Z%T}Cgi(%i zgyT#y%?ziQV~%;wv&dyu*kW`4d|bQP??{m#!aYWrc#=mZ=Q+(~&a=WLZm`U`Co4ks zUhBT^s&c7fCtOFLpntSZ9uH&a>-BYU;)If4?C0 z5^Kjv<~YMV6EC&De{9Vd=k&{DhT|`nF?PSg0Dj^)r@6p+E^&$BNlV27ceuhP%M5SY zuGv>ABEd4J+29gmukzqvj!pKy+CYEm8O|}bnPdNyDrTCitg^x0*LV{C%>7I-|2i4r z9&2oJkJ+{$bdv|j^qHWWo$Tir6Z^j2(y%B~bw+Zo+frN{X4m!Bk`c~wi6tiA>Us{% zYVYTE4Tm|(QI0e9bNfFnn08=_^UQIH^DMK#D!XrxvR~-v?Usu3TxR#2)UwFlUwZux z1LqRw*kpw*ZnEQ@-j-Qlq-Otj&D%CL4Zm9oxx!u6-eab}^2l8<0}ka4kaezc>wUJ> zuf2Z1+Tb3?89po{?By)ySz?RZoce%){>H$V$qHuv%Z&FAaEs9oo9VWhd_==+ELl4y zKI%M^tTXg6?;SULqA|(gkL!?SmYH659qWw#)_tEaFivuotxwwjYl7UT6dAjUX8Jod z@M&wquD|M--AyUv)JZemu?^2CT5kPa5psulHdth5;Cl9OlYOkSpKY#(&IZX_EWv@Z z*gO{BR%8Xr>)v%!EK+mn#>`rHW!nsE!)9kwZtiN!e zxVXpEp|e5n9}Soj?CLoiOmTp79OEMASz?tncHH@F5c-puGs@Oo44BRARcC$DxwZ6- z#C3MC%`m&_X2^b)In1rQoeieB$9cB7#Ll~$5qnr=AGaC0hj#ufV~jJ}XTVI~^Q^yj zVE@kvYJ$#tx$rL@sc(r|#esPpW(#?0CIU;|-{WzId? zb$|1OF?OL9^JuQPMDSz^buHRKArPRYpY&jvBhahi*7a2@C0WNBJ< z1$(){5$4`}HpmtP^MVx?xW*-JahY|N*k*-Yr&TfgSmhA6nBWd4SmzY?IL8(j*^xCM zc56qB50iu0W05~o?_46B^uHuG$7ksW7E zG%M&4tZ;yTf207n?j3X+0h zW*BFVqs()RMNY873^zH&T~4#bS$3YYz1Yh|4zkEN%N*w#C%M5{W^00iV3#XwaE)zl zF?_umU^m{E!(r|)!^O91fSFkX3LOm1vX9d@7y$P;&%w7@B2I9JyX-peV5rHy^Rfp+p|_iX z16@q8;~i4N8cW>cI$Q5FP)^Jn(1C-YbtYM7hO6(kRNQ2Ru>})3c+f{RC|Xvyz|Oqu zxch!fmlaeCF6cNITK+F7V&Nl3cK*T8&_`7_o1aolY_DkGb~-4j-U|-;Z5M0H+^U8c z`>LV}9}GplWf!oxZU7e^3{8GtJ1ldFd#rNk2ljtkup;Qc=wK+dVOufsBin}s);aoP z=Wl;7G|m{uHqDR|++=}m?roV_=fTjX`ii7>Q06YH91FLD&dUz^k5la+&aMmF!4xN0 zWa^@J&|-m+ZcE4*)0eh`MYg%ckvq48p*uOxNp5hKJ$G#fH4bD2dxB|(F4rKtSz|w^ zBkdr`kt^E4JWE%(k^Q}{JEXeV&lqD|x|L8mTeXo9@YW7xyB+}3_Z%4Uv)4v6_Z)c zKTgf;zaD7^O>RBjlJ)WlmNqL$#HF6)f0jx{o^1eklhWttfJN3>o@fWDyW5V>Hvnc{ zs6*ycs`?%tEH5%p4sn(#7FgmM+pM$y#ciLKuQr(N>Qgj=A?DNVV1e6QW#3EN!45MF z-_rmX<>bHVh^s6x^fDbV&N>&^buaC3h;=5|_kWQw6lnPN8^jIg8MfZ4;^D|NX4`qd`H7B|^B)ed$!{#p~ck79hC{XZhu zdY!f4>g#PY7T(|nPQFoX+*j(D_CF(BW%Qb?VtT)Z9T?y=hdIv#mzd-#r?|l!ceuswK^Z$NbDZG# z{_BGM&hQ6p&;8?zs{O&1;zQbF{=){ufsdMC_95PW1=DPO+{_5xXB!MSzwEyubauEto1i!iaRWGk5#s~&5m#CkX;Nv+LMoiOsu(&>o*!WH(BHM zjrRYZpzeTAm=87C&CYc~>s8fG`UN6dudY;l1jzcK(WF!XpG{#t6e$Lamo z+cL=2n`Q0^GV@#abB1|VxyJ0|@2s_;!rmupfC;uZ!Q_tZ#Z_){`W7>ZYk*PKZ&m%= z{j=-Y`4`pB1m`$>q#aZ^y61k*v&midJjwoV{8fif(jg}}`Zo^-CRt#HE1cpQXSl^# z*15vYCwmWJFDo46;BA(G15E?qXiKKAm5IN50I@4{E+}7{HDf{BfuZxx1^o#F;S_fd zoC~U~9XuC=pJHtp;n?}-f;Gl(cP>ah)lyvG{L{=dd@fkw1UDJI@LZ4{H4)CRzy+4M z%&Cjc1v^+uUIP;fMX^ z&^-bdudnh8B^~SDKj6=xe|!PjKaRD!4u5X@ z&^-^oZ2Qo~2Yas7`}U#x9~>S%a`-dbhaPxvdQ3mthwgK5`WZ(K-~Q%9R~#CA=8>Rd zzZHM_{Nr;2LVeFXa`@3VAG+uHUCATC(BbFr9lGqoVgK$q;N|M!$J~7APKQ5u^P!8* zUwhV(VB+xef8+Fw(;d$~;zKU4|HGln4%cozbm>*EkNsc6k-K(Y6-xZS_Iq8laH(%q zeBt5S{r1qKF79RAa7Nc-N6&egC>6KRX=Ua_CN%@AsT`V&L88%J47u8~De<-KqN@ zT^1ZIzvoD>c%idD{Mq4;+;Zrim+g;b(}|uB9|;EC5PsZE|97H)zi|h;myQI>`|aKP zro+$s{h=!^-M?!7qelXthhpS69lq`Nhwgk)kE@%e7XSF+&;9<;l z|HsSyRlYFd<(ijc|95uS%chro|EPfrlU}yHY#hE(h5Tcorybh(~FCN1z>{+idMcj z_-HVbiY0PEfyvbzk1Ur8HuCC3mJQ|tV{yJ%t^kH!6)OYldi89~1i@;+c0WOmZv$8h zSOOjT5+&QNxEm`{in0&JL`17lDN63X45|Aw|ib9yYZ<(8KURQfty?6H`qb;5Pg>xe2u4c8u{ z$TJpcas>ox0r6>HG{?#HFgC%M$zDjbr^ga>wGHyg$gaNsJ3CgxZa;k=A>&H*c0dL> z_*}^3G@TuDv&_fu)4D#4646r-^}o}uK1)PU3ZBE>q=+6%#8fV!e3*@UxrF4f%VD%P zbN+vU@r6PVw%neYz>EHIb}Uutr?bGPaVgXuK0C&PgyC|8b>1?YV;elJ2sU|dp>A;= zO_6QFgJU7)L=8-7p<_Lkn4o+-iz7<5jKG2Eh$mZKY*(_S5dw*T4!I!1J7Dao@Ktsj z{Obkl0K-R+(adLY0TdwjbWfp|#k1k+cJx~dzPDI{98=Nco}#13gUewf7jGt5(!YGw zJrTSc&K+P*bPR^C-jjRVaR>Eqkno;w*tEexEON#H){JMvq;^`@Z<#ec4Y17%e|!&- z;GXR=LkLEsc8qS2)uee#E=Zq(QsdfhhkXs~Gr0C!LK@*q7mV$&GQ3O?XDrsBe25gi zPm9l>8!g9k)%$1h>1XZ=DgTT`H%%Z%dci_D>u-OL3&l#$ov}=so&uY;V`s;z*tZ)v zPQI?ufT1(t1Fugr?GUMicnMG|i%)uw#?Dy6C#OSBbifaq{+-2ATmWMQj9mHo;(Hlb zxr$YTm8n<*SgDG&f|aOP7g&*s^@A05oGqRZFo#~C666j!U&ZWTd0@zM`Qk_?;ZL@T zrGcgUF&pGMPytfFD)4OhoU-~Y<`6enqnEuav*`jQV>|AVd-dPQYq|gHfS2XKg^IBs z#y+3XFdc3D1T+A}HX6oO7%P>|(g|bIhiB1uVjQ+i&W5oH#(KGWPwPj3(VgfK(JL6f zZIg$6%KzS?n;|$)Poh1{g3Z}B?yq)rTcSd^t@OeZO+Qpa9Ube#F!_D2WzuBh3ww?)x{_Fdq20&h)~nc?dlM$6_6=IA@7i zPz$$(LH!fPs3x#nFmDmq;I|$@4z;s~I%BbH7qtQ=ZD1TcU+gv&tbJ;K%!H!M25g3)P8L&=T>w@O=810wjE#OG>{l&V zt%`9CtpxLrZ#!5S7?L7i?6&8>Ft>*}{NxN~ISl&*55oYf`~v2(cYq-f8XLr5nFd48 zAVmyWtTVb%^sT7Rc1#ltpZ<&64o|f_8oLpZYCaDw7K4}J^MA=h#Z>mM3tqHeJUiB< zD4M39peK%ir6b&EWnj(fwoIZ;-$C27ThOJTG^|I>FMwyxGo0-UpTpmVoDR6$8T*+v)I! zWAfkZY_KbUT?uk(c-S(1QxZUzpXVHjG_ZCs3^4M=EC;L=%$pu&g;Rt{F{$6(ad z;7=u(C*933R{M#tR~=yGD%J~D1m>Ua5iriPB)CzhJ5<78_y4hTz^(yy>7H~iPX*`$ z;K2Ffdp1}vm^VOX1z?;%-gL);xlvWxz@oXE_#etTZ;6`R1i9wv{fde^b8;t)E*KRZ z_ih)Au`}QTuK8l0byn0PFt5+d1Q^SCV}R6ZV!>=+&3M*mt2|1HqK~A&t_5~w@^F7+ zE{yh>KIiOZ5m=atRe+hmywTxcYQbz^PI+*f)B`vI}V3(?l!Y&vSU`&_W-2x-pcOHy3_`(-wfeow>%$w7k z>;$k}uxQrd1%;1bV9f-}vGk91E6Ge7fx0$=k~3N1A4l=8Ej*ZpQweM)H$z%88?8hh zc9h9xFIX>Fns1_O2!{vZ{bMkmK}dA+CyP~Eb&Q6`Ps5m+i`+6|7?lVIzFTWKU)@S zn?Iz}KU-Gm?VabwdgzOvp>d>+T9V8SFmuJ{i_0wo-ECVZ9T>I5=nWs8!&HB3k7S|V zQA?t>_9Ke;#j?+clDi93V10U)=B0{p}W2l zDAW@imw6|q2Wr;mVcvRRgWM=sYu`EgV40Af$rJ`X3`qOdOQl)Q>=N_zIp3XwzW2ox zVR@!SL~C2Vd*&OlNSkqn3nqe`0m7gyKSRp{#44@rEFB0Ci*eG2P6vq9+KK^Ms1?f> zH@ePE=t|Qt9MywyMdyp7n*-JW=56@dV1;0{E;_6g>$PH-q5{Pu=CmJuer2)@WP#lR`lZ;;O)GJUq@1Wq9}}9+uRF4vd*RbwExJl;T=3FjkFl z`C`@$7Ap;m703iV9qul$aADPp0%$u@vq z<#>XaMVr@H!)VtO5v(npLyt{Cg>0EKfCaL_Oc5zh*sGv|>!RrN6cli56onW?ygoB( z06oy)Ofi!(jKWr20JFEwbK+8gPY#f@-ivuu7$cU6?AO<{J@z9u4?ncm0qF1w#XnFFXH*0?cw{ z^u;e&3&;#Xea?j$^TSawn<_$tQ{On3&2w}p_%k8G9OQ@|z^N^Yc+e^+Vj7xqSu`!2 zCgQbi(X?@zm>1X^Js|g7R6h+}7fk4i4_$(CZ=WV?+UiT_+%$AZBbQK|NgU9oUrNVJ zVwt}E(g7Z}wbt2`FkRT^C))?cRRNBEEPAGNKb8RI1j_-#%Et^5Nj=krao^vCZZhkD zr4x9lR134Wn3CYO6*5&|m9+I|B;7Vc*tPw3T0TR>OG%gcWI3ByFLQvU&_8tOpz3Gf zQ>v+#(cu|r7tP>_v?LtqGtLyT`i2-ZP$fIlW{S|55tzNC>I?;T8t%sy=atNV|OTW_R1DcCQ7l{;sc?%Fo)-}Sw6RxE7Lc}c2 zhdsxbFHT`5>?*(#WumZrux3BM(_mK$R(~ZO6&R%(uc8P^tXNulwXc10_(?YC%6^Q! z!jVTfsg6x;B{p%y@*11v=*O4Tg`(_KTy*w^f9xWdU=mua>T zflb#8(7NX_PC93cXnn<^0qA{)vM~BoR0so=&K6be0ew#c23vs@U- z5GFz;(_&vUaU#tAD2(S|Sh;*u*yy{j#1zVgpf-6i?FbWV%x%tru@O(?(s8eui!5G3 z--JQ&vEM+8!^LCzmKz4JgLU_y2&I4Q5YxyNE_8Qv0D8-qQ`(ATx2jkdSQD7T69CKg zgLV2bIkzsss0`+$O-rn^gEJsz2Qntp<_NJypMCQHrUhR}QY7_92xDOB%>%S0SInWX zNc5I{u&q*t@|Y{dbhu#ZoktpT*REn{o!AIXp>uqAM zHe(I_U=vyTnzaMa?B#APZw|_#bFHUT({il3pj=dzp0#vvj))IT%o?C4U$V{#PD3o) zV3CnUAyHygU{3Y`MRH%aGfG5hTeIl^s6OfL0Vrv2uR;+T<_d?lX+15PE8U{!uul?Il6&%pSu2xngoSQ8jO^TpX$2-bKH9iGc-1?)!U3bijUT#!~hJ_O5 zVbo~YNLlkx!!(=d^?B%y(l*n@dC0Z&&9pf|M9KZLAr3RZ&9vfD6qj=gJ#s0EsV85q z%5$w&3bc#)TFo|!w_`+U-Nu^OQ-8pSQeqde+Spz?Xon`1d_SGGi*4G3?X>DL+(UQJ zJC}*g+O%?77=xPCUk!CpDfVo=&{2I1<_0Ox(TNyL4yvD{kjruJe2$i1jymK%K>OM3 z`XimZ9CfR^hRm@T#JiuT<*{OQVBQPp7q_D)Xo3{=yTK_7YWOGsj&07HXnTKfg0jsG5Y9FS!W2aBD)+3=+#UKLZ^35fF^w=%uU=OMFz8H_G_^Q^eNYz7(Kod zft;0VT4RC`+KSKUSORjb^fX0XC3fjelU=M+KZ60X<0C1Uj$DP58K$_#dX+B3ybxnR zBh2VpFCqul4M|feVF{r`v_G`o?mTXui1Mr*yZR>0C}cG1Vzpcz-2>B2Q)pSI^R+PerOBL{Rp%LZ?lRWdnM=SbB`_3G?Y7-!taZ3BE(O`T=)+*?bqYPPzIxk}v`_&ZlKb zVvRP%K`$hU^+Ej(*I1$s?bRAV_UlASP*Z|y%%r7bmq2|hzYe`d=|Xz_I*4tMi5{j;x=7g$mT;<|D+g~h^!CaqHZ$e3~qPq9qWV()g*_2HNgjJ}CVoxDVZn#Fq8_yC#$F+2Vk*VE=D zVtJtPH!fQDB-DToNTTEAnkP>uE-pb@?71{=saO;kcCU*D>amFAcwW*`$x@*U4E3U# zrNR(sglWqIB77=O#mjF-4Z7Eb)v2xTNul)JQs}q2Fmo>Om5N^nWOBfAY5s4dOUZeI zh&C5(a*dBbT*nfYV=&xAJ8wWtMmNz5H(;h(v)P3PDVJ^k4Ty2<7XPv~Uc+JZ!CeNp z0ndDe;x`JG3f3zV{KRMb;+1DByUBj(bgz#$N(Frz@aU%S23^y}*}ooRC!5MT3=iXKhEP#J z$8eV_AlJtNxY*wo$mDG2#BD7=w`aQvQ>DV~6n_)chp^we@KGsVwxXJwM08LE%qf9% zU<_-WU)}_Dq--a8p&e24lros47Y*VmWfLyo9rUFdgpiT`s0b z9WV=y050xvl2@Wpf#uT51XQ)>my0V_xgYcuJ?C%@WcpOB5v*Iq+Q2&eST5XlgS9?L zQMZVVT6-DoxdplEC__%cjxWyDl2vdA=Ie5d@>)PW_$W9gUh*ZE0GRGkbU(B*(i%$P zsmKEp%x?PPdF0vhRIx%|{kRJ%j67*=NJX9`JV7VGgIrI#@FEo*NJkM}cdPi7-uV=Y zh~6#|Vf43K;ZZuw&Ety!A>_IhI!5bLWL|+mSGSjztq@DKHT&qX6;NB<;Xc$*MG%`oc%XxChn#A~;~pUmgzhubjN>t3LxX<~!9 z>rbw6^`0A6;jb{Of&!6-u#JDFb7|<+^Zrb6E76E6{>-&P?q+tb~$KdPws|!mV%8JS@ zQV5ySg~43X=o=%sqwRwSC5;r9jv>A7Z!YX$AO8`h@NhaxA?$UI;OWNT%v&qiy<(6BRL)3vCqKcG`t$A*KXox@#?Fgiru?tVQ4F0(%&EfUfRyLP3RQnPpeP{S7pBak*fjaqgh3(Lrc zul)-GWXV=;tN_Zd$4B8iHeO>kkxvkJzBixk&r(5sw6pXa;F+j+hhZ2pFWBa>Si_w{{Tg8L|r9 zl!IBeEpU)N%)u(Z&=1lrzZToI&C}?}uTe@)(;zxJc_A)*gRtncVJ=Y;m%0Iot25E& z4Vb)WrqkgK=%ezdQ_ye3s+g1+gYp(1q9(7u*f*mZ&m0_ArAxq*WJbGxBX(<>trV1t zI44EY=3Jh`MAH6T?9UkI4vsgQG`MkXK}JN;!h10$m%$EWGViL@-Ye`eBQSG6#}|)m z)%mzbBOVNJIq_=%3yY>7?nN`{m`95?BJL@d(_+o#!?IQLAi_K`402` zd|{>hEy6Ir>aM}@9)?qwvIF{sALEo~f|Y>fE324qZh>aiau=Q0B9<<0S?kM5cHaxx z1{E6ts{u2@o-Z4I#@}MGc`dEVM}#WZ(hk1YtmTLyf@|q;KB{EhTKXnm#D}-Rt$`hS zE<5i1aNh);rgZKpThY9_*HYG2xHDz(Jwjf>$t{Gwl0^r%qR;NnBJDOb*S4HNw0n89 z*}V-TVa~5<|2B+(l^ZDNe&_;azZt}`fxO;da6gtCx^n4-`>}l7UNFe}0^FP(1qd&C zJJ-%IT3-N9>bBF)0#zNHv~9as9bQp1INl3$nmCiI zi;zj+9(8bZJ36H3-w&d@l=W_20}OURZUl0fzo*4JFhW(q-k}Vmb(XyRlq1mu^aD0V~*D&t<-yAw^f zZ!aC*iDs1gG+o$vv+2rI65^Aj=o$PwsB0Kr~2y462MLUw08gC*od;r8vJ`~!X#A>j`h=niD)ldelND_ ztDYOg6boy%v-j=dt)K&gW1UJ>TC)q;lk`X0vrBB$XTLZIC5pGF>9M=4A!I8?@pJ>` zDQ)QXV$8#hwX~xc^-?s_(PHt6*7gSNC_x7>dYF!spa)5Bp&1W~sKCOOLE4fa=1k>0 z2`j^FzGaX{;9oF)Jn*2HsjY3HJr5$^>))nhaG-5?n}!|~^UTd}`^rBXZu{UCc5%Cr ze;Doe?&h)T13J7LGmY*KkR{#N+pJiC*{10stjhrL!YuED#Xf|}qU(^`#Yqf7HBVag zwDuu!X<+7YkGqd$D;!)Wp?V|3wR5feBvhAe(hnlqIHGCl#tMKgo~#KLYkZF@vSSUUrT z#zz4sWU?XC505n7?y^VaCj`+2(F9wCDaDi2A26qz!{qMD0Gsp1w%^pSxQ-( zBr~NwDs&q=06kHbqZeHP?Z=P77uowH@Op6nJWB(s0duktE{;YHSi7HG0$3qf%K|$5 zC{|W`7tjxnih0FVh^oI|{g5g5i$43Mc?w%lVBYvK3k54sxwV7ks#p?Ori!J3r73I% zdoQm*VnZ<#eiBs5`&W^Y2nv6Vx>kub!wEAB)vhS{_= z3ADZ(V?*lIw6|QutZKW)SKu6Q`P0a06{`VjQn5y`1~4bw@RfsK8(8->6!HWHdEK=` zSoDP&H;eW>A6`C@B>S1uIlBJ6NuYC4ptASQ=Q$1co6p2QYC0L;zrR6)Oi5Dpmt# z@MApUHiC^Tq6>R4)3GNZLG()%c06`IDK_h?77t^?a|knJ@78C6Ib-S2xDwA*t&)(arF5zSBUIT^3VI4dv+;%@yk917q~HD&hR>=S zXvb4x!~FCWo=ySoID_k}P))%?@yu5uek~r>qo|8vdl4tiZ9`*y%HmMvv`f zeS0OH*b7Cz;0`iBjR`^QT6FXDg#k7Cv8OQ$OkFpGrLXCiL-YIh)6l=m*3rqQF{0LQ zphcCqH|ElTN+=rz+v!3jG#2-7Y2hBy@BZO=ek8ZDyJ&tUk+vRnKvt>Sb?EOS>O7e zpc04*(pEvC)9j`7RoK0uas-F`c)Pw0NX{ZXRZrV=^|A5ti!e?pE zAH<57zGo-)a`iQ6V}6Vy&;r)+ECuaHE;_3zem?^4c!Bor$G$+%3q#NdyzSpe+2L3r z@7<3Ta{G(ER>i|^+w+(jyhtI>A}?BBq!rIXlWBjEwml19aop#?v)pUc(y?bz7b;8xy z*-=kN|A-P#`3ptWpaxVNqzyHwm!XH~jT-E!Bp;gCzM5W!P5~C}i4Wh~!LY+P<9STK z%Kl1=o)^2cnSZA@o<|}J{!XW#M|-GvlNP-I`{p-k{R?7OapsYU@o)GOh8-1a1xp6w zeBg`kU0_ZyZzePA2TN4RXiv<%J%{=x`_RtRK0Bn>AdQRMvz&gP2{^3?k zjt;zt)y;-hpK_H9nQF*1w$hg`ie<&4?@Wx)2<+To{sn3LGYUh+Y+&6gmH^fPX7j{{ z6PV(W3-d7U+%my>AqV?QJy=Olfk)Wkp?2KMz((GoW3^alOMlm=r?Ooe>`NC9hlm-hTG&Y&i=O-ykG?CdI53l^qgO<*P! zYX{S*SP$3;!uRGXhwldK2Xo>KYT*6WOXTyG_P?+oZGH)TMoJqUcu6c;Qmyi=4l)%g z)(lqa$6^sc2UsDPyskb*`OnY~ zL_3-PETW2|+kHBT32qIqAr2}Q_FtIezp!Kv^Tvh!%K#Jb&!6Ri8I>@6B~jvoa+a{; z%KyUZ{tIjNF#kY0z%;6Wd%@hu2%p>*6b)b>pjR{FfQ^4um`@Nb1gu*nm*8PM+VI70 zQ^5Km=Ve^%nP8(}o`nm?^;RSGZ?T%Jm9XIKF|uo1HvHrr&rJ%>-k$=S8 zU@myhf%C<8L!%N2f4MNQ9+jK}j1%RRv%zgLSO*xYAq``ze?cxl8$bpu`QiYIz_<(@ zGEt^{6<~I-Z25>e>@bGQ7YEi2I~SOLq+DQqek=iUy8lC> zz%pq;AI=*h->|Ip!MHhgw`7VdfQ%i?->)(-8yNe+mkqyaFy{yKWdpR_G}yV7HTg>p zq1QEa_zIfiXJ|s$Di#Jdq6)_W=2Ed_us$$v#bN(4z`9i|53ECBEP~9!uLQ95gCV+N zpL7NNa0sWL+7XRfWk1*cny~2;j}PIOy{}>BP<5Pky@p}4{Wu+bO{}`SUG z{Z+(SEAi}xy$zf%wyy)ze8l$g#ms8|M= zNyYNO41Uas@JqlnU{yT8Wa5Z_UlW>qIum71Zu>jlJZkiF#VIkhU`+rl6wiDyi*8Yv zHwTy{g4ICIpQVCTs#rEynTi#F6)DWu?Uw=O`w6CM(9MG7bkUc87b}WePE8C<^ESE= z6$=HcQ!zVOwTdNyRj61RSg9Z5V$K081alw@Uws4XP9>-4#2YweT>mL8eN${$($hV$ zyb6yX%fWPT%opcWIanK5m`pIf;9djP0ai}WAHYt|FK>#OlH)Vq^0^Z-J&>scOH*1> zQZu$AYfjU~X6)wcz8I3fD#Bi7;#c@jWX2bCxLITs7kq_*Jb-PK@cUs`){8Y01<7&3 zzckR;z8)HL`LR&2QLsEeW(Q0EW@5%Cfu*Qe8d#FT7Rk;z;W>Z~m0%%QG#K0S#a%`@ zm<>$X?!@URc}vl_?=U)xRPZV~v<2HN(T9bpxJl)o?q8^yDki{cR4f*(QpKELWh#~q zR-|INVEGDLCr6qiUj&$=6088rP_bGtPK19uX##Wlu@v~%4wmo@&3Fr|fQD}=>n%RV z{ViQ=5i!*A7ILEPTUKlb|Ap<_;3HzjZ_ox4-iBayzam)JhE~-- z9u?i>dVtn`dG6_nj#=OPJ+E-e2S5^!ASwyx{G(!qOX8mogcG<)yn?T znN|^F8HJs<`;3NNFYLhR$(bTtKC@$N2X*@bbiil>bHic1qDemdFQ{XAZrcAZtj0C{ zK<99m@_zL7B2Kt5y^q}_FucMw7f1Fsy(2EyR*lg9cd*S}_45#Y&Mz2`zJqnX-k&Mr zT@kavFzRc1oD^{k<0hDYcEo~>{ydR6!Q5c%hA+OSgSo)G*~ZzB3x=?;iWC!LgumWw zVEH=OG4qDSS|8DK#fYU35+wuKah5?J{9W$>sB#0Sci%kI?$xRV&zad zTnrasfb7@{ImaAe?w{$vzj0En;}B+j831CGL5wzWl#c!zTiX>EY2i_^E6|`DrvE!C z9t`Z#57V{piJP_EljxE6aK50;Kquehb1#!=X*(8v3xnwq`96h?wu|*KBgWw|+jv}% z{0~u3Q++HEcBW4Jrqb&7`DjK6?R{UYnV&d)c&xy0@M(rj)r?`~(-?4*fL{lgbLKGm z_2VaT=pgo94rUVd?n#m4%P}*uWa!}oba3tYzKFk z5tedF-2MShtTw^iExSbJ#69#R6eA0*`2Yts+!mIVkJWX5fXQH~80K}juc4Su@4$fE z4s*K4Eyvppw?=7rEQ}6CVlykP0}ab1(Y6k;Imi%=aCEfhEF5c(i)ArI_TdSYLv&#f z@naS6FcvJwPTP))y?PM`55^OO*EeBydIIM}hkgQ$0Blt0-V09P{C@Qn!{e_XWod| z3}1Hq8hfD2q|t>>u#jk4IgGPNa@|Zig$={*m9**6vFF(Igiishf~m}Xk(h&De6s!;S0Ao%GH0@@K`qN_{zku5i*IH zbfH^h%`dupVnNt@p>>0W%F-BAa8L5E1lr2)$Kqu!9aVoOl5Wpl@5?ZbbR7gURje5- z1I*#^kmWkS3c$RjZ3F8C%UwV0d&?%s@HN&Y*3*j9*tg19PuotTDAVrYR(bd5I9q=H zw762+okKC7W4$-?*Oc`+-qUH?Fifwml;+GX`Ub&l@Z}8$Q32KlfoJpaB9H5HoVaZD zli-N8L82MV8!@g0-Czx1DRf+q6CKy|h?z^;VUC6!U+gaITgdsjW99(k7v!OJfSR_~Od(ul)`h z7nlvtd^zxI0;}9Y7r%sx8l69k_XG~z&o2e7!3&+KU*SI|)Z`D#3s1qE>Wnj}i}`fm zE3}1XNEa%b!hK)ixV;NzZ?D09c^72+@+qPh3a74sR`;Sy41IuJ>P6S-E~22X(JzSy zY0cLd8@-#y&%t%%U}K1=()#b#^eAL-n;@CSEmAMWkX)3QEv(M7M&-abq&^YB{dcSu9U zU(k+}PR#io#-~=8{oZ+z7u%9tP{P157V_ED>hJIdO6Ea2@*TSR&<0v{Ml6*aulbry zGSZ$ii1rSKt$9A_+jT}e3VWA_`Qy(b>e6gXK+?|Pykibv8{Iu0 zhYDUdS!c<4n|dC3+s1wNgEkyE`|~+*i8lM+bmE+tH$U&+!xJ{;+aO!($GG-(gLQ*d zD2rW72E@#u#G}w}aJW|BrIBp|!n`579Ul29Oc_5wVS0aJA>@J8f^n1PiwmX%tRKu< zFw82!y8RgEY#mrTUK<%e12Prg_I>;|g=OIH&3$z-O`PSuI$fiZy|C`>_m{M_Z+Y?uuu*V7qi0u!pc3&+sm?C4OofF zZKH>I<)Sr6QX635aSA!l-5wmsr}waEab6@Wjy^FlLg}L@12F%Zp9^O4ld~c4A~53# z3K_#pspq`V6&oPnpM8xG7)4gPW((4kwajq_+EMqbc3xwLPIa@z602)8XPB?afjUo`J!}u&0rOtv*o^t_ub#xc)ynwN{yo=tsfN5CYDd_dIG9L50 z{GV}PDy)0h`#wnP&%&wA_>3ERg#30vpEf{~^BKjBiZ!z`Py15IvCRk!(BOOa0n%)8 zA-4J=n9~$9B55?IK;By%4#+pbKKV3V97S&DoTm6+pebd3POtm|bLHpw1|M?2<#P(Y zh(n4AJ#3DWb)H0hfF`?#b9`lta-d9QxPNL46{E3-Ucx_!(T9D-!<#bI3DuXtlrF1-&%{ch zfpuRE^I_mQ*62wAnpW6(tAP#SB!V@6h2o6THhm?>@tJ1Hpl^hjMpgoz>5=T({9b%! z5Nd@R(q+9|_(8&e`qN8U0dQF&BdQ6IblRd`*%xXFkPO%?hggS;8o- zgs%c(WmPL>X*<8gNBgAZ`szOP<;ry47AS@4%f3TXRdkTFK*_GpIK%0d&wKtMP?{o@ z!R$>17h6GafTjctr*P7xF#04=nyIgbxllQOXwo4Yy3Y*LeQTxgo4C9UQvx(DKTnv2 zf%SpO`42NQ2iPc>3(tJ9T{2kL*+4daJh+$P zi}bqh>6l(xSZx2^S9>^^PS}Nkd9#RFA6O_Dw|%~tje;ep{=HRfK_aaULKf^y8x?kQPw1BwKji{UY{hz z=`};hBBfSp4N{!8Wr*Sp(mcHjJe%G=i5FY%H%N1|p>En|kmAjCKlp~EO)H3p}^O(J;r2<@7TTHpA~Fm_<^xgSAaPnIIheK5y* z;>;DT6SA6%WDS;L^r;tlq9A_>ab2)9M_&!IQJL)21WU2n%rQC^EG?Z~pmC2E6MI#F zU+;9(N{yQ?pCWD7mj=1fEaca*Gk1DkXe*n63=5)TQ>1u(KkOBqljMUth7hR8Nk%kg z!z7l7p?nzh(UaV0ZSo@BAB@sWt#c9`G)nj|>Lfa6L<`3PXUtS-skYKUn{n6o8{9mV zo`PZH!>Q7Ay=L-%1Y^^O0pbV;f3aQ8Bg<_XLeT+Z>?DnC2d<^Jw`_&K&He ztdeYWa=Nrx+YnF7W=JcvHCNKU8Pa}j`PCFZQ`)Vszt#<ba56ERdypSHcN}l?Kir|I0N|Ns+JNS zpc%Q5_Lx!Cl9#!08b$uf=?OEMOYTh+V*#(YiHlI4Yw}6!84KegsV)Y3s%&9mlca(E%>9Y z@eu=m^bFSV+NM;Bn~gftpGq5NqqGdSBAXTMQf^GPFv%2D8U+pNRysNxt*zic1wyq& zx3X`MbVnE(R@tqzF-%&qq4hTR_$s*EUCu@SpXQ#>$5(@mLeAk=A`M^ya{i^%3TE_U zPRMtGK{bj9mzLtcVY%heE!YN&6nwlpJ&pE+BO5Z)=(TVu#+(nw-hqUB-+IVYq|s2g zG%u#c&tr~gAM7gq82dR2R+dIfBcv#O9qf{n#jBzSjQve8XVUj)@u|;-2r2g7wv`hj zUw;Xzj*7K_HK1;@)9LUWX`a@ZPT$Ot z7HVDT6cHsY49vg7&7T6B6VFAGbXkA~V1lln237^;9e}u4bHEzzpopbXgskP3!`yTS zorpr!)~!YrP}CP`F6yanHO0+E%jpL!DX7uYiCPB+$ktVBTV4e~Z9s*3pr9QhafzO1>3#Z7S9U)~sUvU=1p! zi9-tl^Uu&wuxdZX@vwt&JTq`S=l)Bj%NDCW&x3&4^AeBe-V!W_N0nez>*&;_(jI+A zHh15$F7Sw5!WZ1L=>PjNcg!|ZP%Oq5+ZG;~<Ja5(ni2pG{oF_k`clu{g;bly_BtCff5{ zhUZZE*{ankY~K|af!sS3*>2ePdY(t{+_{4mUx6HJRT$;7aHC==)LuFpkaHi7^Cm(~4_Jb$d%;;zIL!To?6o7D^M!^x`0 zu9V^zl>N?^7aW=LMVRFKF(7%@tQNcgJVRC@_9bAhTnVFRmWc1^PLXF`hHFvte@814 z(3XwAr~Q1dET(S~&;vDfPvZGbHgkbn_~f3YMs1*e`8q2}Mz{k@l_FauEOe&?| ztECnC(f^rP@I`DX%IJ}+(bp7})48jq9ooJpXip*%mvTKc!ae*vPn#m&qk^iy3ir@y zW_2Fc2iCQR;;sQRJgK-%bRr#3(k^DX9##fc^&}kwD{gyoVqUbuu0_SVz?xL7AFM&e zG)pkORevC6*?)Sh8z?&H0VpahrDlqTW z%1CClVCj1?caxb-5o`i%t;Bew$jM*qYiAFip&8ery4CNaHP>Rc(Y%iyxmJ3txb(yC zCM=`(EJZ47Fs<~s=fK@y6=42@vEc?JNX5dyO2E>Ub#6J54zQNj++&T?6%XyWC4*(R z!oL6w{WTI_b*@Q*^6mVW+xs=+V@Xga?eEYxNm7Jaw7JI*q_Sq%3D@~;WW7$B7o_<& zeAd&R4LIO%&vnu@+Kgj#;5sDFb&QT)C#{hRI^E;j796xY8Ce0As?3bi79-$Fn4^_7 zm*T~eWG?;4rwcjYCig~EP#pSSj3GbzB!yg$fZMUW$pyJn3`C*_N;j z3%-8L29^Sre3JHD549l)b{)z@?cse;)WtLO?@KWeuW@3A-uww2b4si9MW1p%EboXVE|Ef)w8P9XN=mt`L8O2E8n2a?O7 z6g=NA2zFBimaAg*VA(3x0+yj-onUFF-Nh4HZXaNZN^lg+sbZ#7^tWK%i1R%fECI|L zab}5Nb`?tn3mbQPi;}u*K%o*W05hss8JK3=u`v4@V(Y+MVE%5K!TMEl9bi2w z)(h6Dxb+PdBY+($LE{QEJr%QoH7Smf6eU9wz#3I@DPVOfmI+o3=Iy^@dA~Iuu<|o{ z{U)qiD)rR5F9kz4KBX9(A}!PRB8RXK!vD@`a|-4h4WDz{<1Ha-PC>8P12aw{hKk55 zIWwAW!zkJV6-i%DWk%_w>-=o3Yqc z1A|%fh0iS)U?IfavOv5(6n06+duhe3QXDm;aMLVi4i{$oXpnnP3fI-cn_`e6U(S#wA?}R@F~OZ$pli!_J`$u~X8dtIT=d``mL@nSO;1 z?R#3ChTLv}o${4js!2md)1Bkxe)&*PM;bQdOatS?w`nDos~rP8oLb4bQZmHYVaYu# zUmP)!fzAoc8(EH6ELhk89b73zS<~^Hpt8@E-LU;Uvr}bPE6dXv*xj4vXUAdnz%E(E z++c|+X1EixJQWKAvw^Wcd?n-O01E@FRz5>nLog%Q1Ch^v}>;LLG5M*5~< z%DP>Ox}kU2msa*GZ4DG@KPKy)VC`VuLgnx{Uy8t+hTZZp8S1&6+Y3zmiE+waV%1G* zhkcuuIMPucyM}2|I{FI3d5)#5U*Mky7^yZL<(3ENIn4h_I#%f_&eOScly4I_z7skf z|K{QPJEU3qo(Xc(CMRcNe)rjiPogd%FF38^Z?Qqv1=;55=jp9@%(~O=L@6~)r!{wCKd0Y(9;YAP=6^KUekV3PVlC(8 zvfj4_La`PKUV{o&Wub*@q-FD)#Q8C!U$j#1Myt2_GLrkuY_LYK6y;;K|5zi<)way0 zFV~=gMu&4?*rc=4?RQDDwAtab@h&WFjm)JZcS(nEdDH^jcbwQ8u=a-Q~-t(;sn?X?Mu!p)i*5* zqe(YH@OA@y(!~C2jJ!)|a~7&f_fk5TB`un7NJepU6mW4BXo3tgArs};Ogoqn%&2@6 zDt;aM%uf76f{i$tkgx%M-bg#w!B5jo^u{_=$A+6JI9tln*WAiEf<_Wa<=JQ-oj$Yt z0)Iy~iovjgPGw800}F0D&)>Y0DD`g8qT6Wo-56+E@r|mxv34D{ioUs9dPCp4`aDis z$p7oBbv?R5&9CUxdTEt5<4%gZ2Wt$DHMH{{X`8ty%a^%%NJ{fY%!2Sa)EsHEwKn_w z_+B`tlABlZeHgg2>9HIsE6{n*d46qa&g6E$IRNePJcQ&bbBSDOe2+ z9>Gzcx?E(9X*V6tm15>6?DqL1moQ{w{TRD%2a5*lQMP4zp0ye&;a;?u_TA@Mf0!SX zn2&CCH|@HYrx6d)EB8XlH#~HHyh~-Dt06N2U+j41i&+Dh5pv#o$gCAi1LiN+1s1B3 z>j&d7{N*%TF+?bGK9w>Q(4-QygGH-6Oac>NI*uJKj!YVuIw3h={t4j-6oPR=^4Z~% z5ZiM)I*JCMO?!wNLX;~z@LOzl3DNykI<+I{GtM@r96 zcs0Yd4LS1gM5enR5d-7CfiI4%023;?STLK4Il=5Ix9MPsirm%X9_9i%RgR0mQv4jp zLb?Jh<6%0PC&igdVdvj*b;7RbVX|(5_D}^oZ|>UQ&QyR!lZWZ>LsEn_0nbG$e^bE9 zAErH<(7)$BLWlXD`9E}S6V5T29_6+!pE1HW%w}pGk5blVX@lAHn6L6X5k}>9l+0sv zYBQEM%O0bME!a0`dz^M}K~+sJr-QibOUk(svhGf!TcprCTrhj%$r;&wQLbXu)z{KGNjg!`+Gea%#d> z$zCifCKh^ZAqo@BzqvTULRBms%mC(}hFq|bCw+{&{35VEFf6BXt?dYS&U!$?7DV#X zqS8X4^yyaV5^XQOowp5(DK$@>_ZFFg0J{Rzbwc)+|p4$G&2b?l=(kk`9l*Q>0~ohp=~ zmQ>M1_wA4^SFs+j5L# z$0zRuH~oR;?F7&M!?^qd%B3g_XF-4_HQ&g%LF?Uf^j2KVF%o#C~h!zziD(Y3yQcEpbnxdkm{-{MuEw!kq z1P;qDc|PBrS#EEt&+qrVUeCT>@V$A@Xa4N$?9A-!?(D;CAMx=h|0nUB{Vd@Y@X-DV z{Ux`!XD9T-t>8t8op`11{#)Eqr8@g&R>j8G8(!C+c`&hK-shIlV zm--k>yVbpRZR)|OAH|d6K>7#{kpY$d(4^(T&EV{JE%LfW~-@)S1uKzYS4&7b;C7 zRw_qJ>3j-Z5H0UIht1!OyJ>B3V|mwiFm-g>Zgl?XPanneQu_O6?YrICwko)b`C~U& zJ>HYn47Yi&9d~0k!NfesWeONRj(5#%7+lmo&Gz2r-mo_H+1L_qfW{-SFqq54QV>@s znB!S?;_b*=2K;a}N)Nvk-tKm~3*a{LqK_r_;MxsLAGzy`7~5GdhQ9jqNfq!6JWKug z{G@VIKpG=7!>{C7HgY@q@UCasqACK&ukpR)t#}{m-%eRTw2THAfFq=RIgD zxSRRzz&wrfc`Chm^u6Kjcc8-vJkR#s;of2Eec>o3zn@=@Z=KA&6PLfOFS4z7;+W;P zh^wCFJKd_gxFtF~pxRS?FJ@Z6^k@8??C*EFXWOdaE@Vq+mgw|UERULg7m{rP4Dfy{ z_b#;d!!2ybUD$`bmyY5wwq>)?w|Cy5I`?4CBd6h4-q`UF7W8f7!wLfXcYQnGHO*aw4Z2lfx zQnvi^D4uB3FCA+3xXW!NuTjD1FUY#?!5m2MYiz?k?zR5LU&S`&`43={UScI+%@V5w zYmrzGEG)4GuvUqM!P+?6jzZw$(@wy4N!SP0A+cewPKl`xqEQD+)nmh?6>KtCKUk0* zr1vbE54r97sGnM!T=-?TMGpnBBCt$}m4l^&8661es=-nuT^*Q9V$EQ76T=+9B&8it zX=79Fb+1Wlels>=XD#Z2iP5A%Dp>uSYzOo<>u-+omqzgEvU_oRI0(00d;raYb}J$8 zt)s`gE&PjUn*c059dxGPv-fYam-ixuhPP=&%6&MUQ{SPgjM0{por`Z)Sqk1^ z+wOzDSpF2Fyds_oq|_Nz4dMzn-_GSY;znrdVG++qdJ2X z1>G68X1MWTE@~s{{_eKxbGFqC$Lt6@5=5qQ{>Y96QK9?)$Tr^ZUaJ*%MSFkju|A(s z7{ax07atV0-H((DAj)Fb-Rzn@r4*Vb_?LFEZ|-;RNGfyTu!#+LEIjzf;*R;F$<3~7Cnge8}IU5^B`S}fd|?1 zcC^ojA9N=rsUL_7ImAOfUhRH7V(|g{=t1`e_aOXeN`ST;{0+e`4W2I`_0f%BRXyy> zhtSYQ`qNcK#3onj7&fIe>J>Rf58H&FLyp}iU8y3*#&O+`Kzvo*F z+)VRr*2gf4JcmPP+N@zWH^!NZig|!r~3mksfy)q%sGIG2*3Z}Ce``rr{ zH`zvxcOqWeC?D!U)T4xvIYZBYFAI}D*Ph$IFZOM~H zP?`92|9(8;8dllJe(FP2w&)QIQ3|KBYaYRUj{XzaJ7n!MSy~;Y*M{69s4`#I;dQIV zI(N3keiHk#4o|laEEvI5oqmRwJnGJ})Tgi~A4PnvDQxXK?zDXeaALHjuqg-JoBa7F zk4*Gsv;(P6pqhcvZ`#Oafn|f`>V&gAuu3qau_j$HSP+bMnl@q;V6|Y$I^nDatPTv- zJKA&93n8GsQQ#J^8VFSr>i`Q#tQV{tjKa|7!`~2C8JK?83NKYY=1xtjNR4Kg&hVTk z5q~P%`xpu}`4sl$W0)w&JY@uTzOI{&mJrQjs;w#NE+e-mZRB`2_irY53*7h~9(_IV z>w5Qs`0=!niRBg4_+jCiLRoS(;;v~L+jbDGa_iy|JgcR@Sr9&mYvhi_?8rg%{OYM} zN6t4HdjPfR%50(s8I?*{gErrY2TZi0fi|WDCp`ne!w?P{=F&Y$h zKgD)Dg|l-Ue#7j#r`!uBr96#3aQO&(>}|RQ^0?bNDHkNmAkB}v)x|~2W23HyqQb-| z>N>EX2(_;P(*-R?6hlwCt&<1g-Gd+%G?qzX=QX$&+8n1%xbK16l5-mSsDa*lL~u($ zcPv^QhRD2IUC&_5U}BVZKiI%&=6$d?p~c7$r0faogEu2Ko*XE0OpM|w1S>K^wINh| zmEqENq6z+u2qShP@kwO5FN0?~?@46ZwSsMZ(!FSL-ip}7@}5PrX=0REF<4-QIny;D z4F*AiSPTteq9rzmd4GXDQC7xAt{%n_G%<=i8O*y@q>_{>Jt4C<*4O&fX@6)()39MmHK8-UJ>jX`E216g0 zk8OPhw|A=6vlpJhZJmy@*~%vLAk`b#t|oMx$~o+fCfptXi zf#)!B;QP@C-k8zfZW?$Fmn!u?VpEzCUrGU63%j_cAhxi4ub?uS7!_7NSZjg#KvjbD z8Kkcng>JnhHl8pP$tFhebb@7EBI5Brk3ugnTxc(>rzVHdRhYt1bL0i9H8F}O8?4C) zsaJwhkS>E@-7nQLdxNR5*Z`PfVl;9Z2a6zGqnDxZG-7i8 z5=}EWK2AFoubln-1>D!m+sgL8;NEGex|}7wh+|TD1>5-|ZZ*{wvm-B}tW&RKmKNBy zE7{5x%n1}-J%Ufd=pV&=panA$$tCO!@-O%a`=-T>^~rw5w!H+NUB>pjgnKx_pF>X> zz~;qYTPvCXumE3Bu*il-vpg@mUA9iZE*hNUtD10IN^WF3UPeS!H?sXNyRV8bziEWu z!S=j@A}YU0@8zcyBTCmBII(YH+g@>Bx))CBg|uHd64c*fEPRk{dc&O- zKQ17ve*=2;kkHpa;^dBb`q!<(0G>na*c&K=LftN9MZdyBI3eyx$bSn@W9h%~YTXu> zb#^s?*vPJE@N4R3k+AU2LU)gk3~IQ31;2jm1xeVlD= zL$l?;S8UoaDcAS}`;u(vDYo|4cmv6ESl@|xCs8C79Vny2(TM5#uLg`n*IuWs@OQvb z2!V0ZQlMV2e2EQ#frEcRK#e83b*SOS(Tu}Uzf#DZXU zi8X*(B^Cx7f7TcPqHUz}s}nFX0Rgb(;;$ck=vkKb8z3W zaBF>??IK(E2K%@j)i?Yrw&u6)z42{t^1-V9plD+!hKO%s(M`N^*#73o#5FJ-j{*4E zf5Vo(g)7OF_UN&qu~_CGaE`XKU2oxh9&Bfa-*T^CocY_4iN`tUaJ50xWMUL&H<;(G z5n8Ez1DFt^+IHzk`dBzFQUXstCU8&a`EJYIb||SATj) z_cu28J-mY2(N9ww`ekn5J-63Z_;<7myr$uSW;^SC4;^~b-`VFR_WWZ6ck=WMS;5t6WXl@KG_6*z@Dg6_M{oP}1@1Ia2zVAj%&xw21<-%<~oL~sUHB99@e=C1 z!JHCPKSi@Bv1BkSXVFKNyny4!Vl$HsHY~9MutABHg7r%*0M;w9TCnaIh5~K`>@-0S z%C!}&{TMsYi}@B$uiNTxHwoxq3`5W=G4*da=n_i?Ym%53tU+SgV09)&nJ56O1w)U< z9`AL}@sq<`^MVl6NUQ;@3e4OMg~2K$)(KWBu|BXOi4BA0bH;mC+IzJh)zu`V+$Mu% zp{nWYoZ`#!c#Y;SZtK~ZCK;W9`H-cX7?9owmx3pQXA{6iXHftw7YsKl#dksy+0b85 ziOY_$@BV@|sTh@re=mR)eT?TR>)^)gA#U8o#LGY@BozN0rGK1#{4pMqrwBuEx9INW zwpM5}*(V>nJ+w#Z_#20BJ7_Nd+*jdWaWeHCX9xa@m%R!;Lk-h^r^OE(AJMM{*x+9= zgE5E@?Yu>|_u*=$LK$VJ_PNi9@5hgy^|_awnHx76Ge=kU4-B-xXf!|@rC$YB0cIRF zJ-1+`aii?7h$J4KY{n<<%i?n^qwI!H+~>zv#E-Jy5NWWEvIU>I&$pG?MsdNd4Rvl5M~x=rLE`q$ap=@heGLRw_BT}b43mPgmkmX# z#0tQYB~}XNkXQiBYGPCiYQZ9tqPYOlzu(&gJ}_yNefu}}m6qy6wzVGX3(2GZ7-|NRHYG@ie){oJg^@LG8@2T@mf5+|@!Yw`tihFiWTUm_T z&iek2!&e2E%I;r_2TZJ=p^Qo#Z0Tq2l}S~O=t1)!cNt&c1a+{TpJABT=wJsv!^~FI zbau?EE!EeP?16vl^wF5}a}caWV#=4Ol3?cE$SIgH=%RBV6|8PL+wl)PTR#AOHk|`b z_J@C9P!xe1uTsz&MR5b}#g_gP+0p^@ddV|J@fITnBQx2q0XzccaE{_#Kz%rPcmTt} zdbk_-BVwP!Kgl^Wnh)wty1qjDJ(DH<6Jv{wOU(K$jsa)U{>KGa4@jAyjchttofOyy7L-^% zSe3*|z$zqG304}z(EkJhi%gK3g$A(vW$g1oTnzLqkIhs+{JKqy^bs(u@xJy8oDSp5 z*)?CdHzqk(MvpFOs)liNSF(3VQ@WCke1R9HOQ12D9NOVQXbL5!9L0DA%-r)h!Ez*B zDp;1pvcSA1=0zHLU@2f(=+?f?$JL1b;oK_Fbd!=gn-G|1CHweG+>cCO$r8SDZ%^vY zL>mV`+DMZ*g5Eom?fMFrQMs!TD}O##kFyqj`Cx{gQf~yyUX7J-ahtape#Uv23%?=w zHLqqXhtRd8t{KHMo0tVZDUp&X9mU4{J{c|J;jeK4kaD_y z!XLverOUs;1%T%p+*q#!#8W*2F1x51Zu7A%8pCZIiIs!ZgPHfP8ms|~N|m-k{MCWA zfeq06O0)NU>-O1l)>31oUrQH!iyk$1E!**}d-;-TaC5=?!y9bFVVrH;*qzX608T+5aYV;!lcGe`Ah!C4SWTlmaTJZP*x zD%3pePEYEE8)u)sQ4CH0Mh|}`TXYojC&@=K$nf~cvD{YZ8#NyNDm#iDsPnN`Nz_cD zPTjFGKH}56PdBrVAgv(;spq#;mXF|c!?z8#jZjqUM)4jSm4*I&BYKjAwNZd_cqFrB z``k;|<>OdB%{~g4y?zuU3%xsEK8pGDrn9I@o`0IAe;Nf3(35BoP~j`Iy)lY&pecKl zE-*LZ9=J8)PPXJ?S+xjeVe%pn2hJX)<$q`$>uV2c)9D!nYeLR(46=3A%J|d`*o}H^ ziGJA@hDXT;b}ZsvnO3(Uwvt#Ci&AT1IGJ&8-=frPVB5wp`O~+79T>wNk3)k;*6G_r zgJbS=znT*p&j7+G5*r7LoD-{a#95RfiKT!INGubqPhz=XJzzLZ`KknTt``Az0}imS zPr&K&=67fhN|6yC{Ai<-z8#uS4x93Clxrva^7vBn6@PL&CZ|{|NXq;elg-07Qpj3fnf>D1<8?g{r0T@+z+K4rQm4Z<|Xd~7JRw>2T4OY+N zi}qy$fNfHQ<6zxjMuSHYI^zG6rF;*|{2rG39}MXi{RhONBHzQRzlYU*4{QD&*8V-L zhnQd5yTR`fD%StpW9Rp@#Ys8k9ifYyz%6|Pb+ zbA&-KyQFIn%&ZH8IVD}EV7iV@Yf88eFj*1~3ucZ`O|U2_CY={ylLgCX&riqj`sU;A z+5T*3%;Acm$(2|ISiZz+zzQW+4^}L(7O+w<^O@Np7}CYk3D{`IdI8HN;gDeF3|c3l zoiORBt#Rp$O^ef(KNQrg{*cL^;x2|iF>^c>VD*x&MliFk9;{Ic+XB{X3QKwD5G)@f zzZr4bGJmH@K$&o=7KNBO@>H;Hla5L$OE5zRq!&;=cn`GZ;YyV#$xIX1KTQ!Gll#7e+YBvuKQEU_S%6U@jf*#@Y-?_7SXh6i~K?O8IhAMgI^7pG4`bT zR0S3=F(AD@)q$6Ro9k0ESc$~i!HOi-16Htk^un0HgMgG-bA-xNi;`nvlp!aW56s9o zWr#)x>EM~0+4Tt;Uhvq=4kT#HXVsa)dZ4L?rWU1kW=M1Io2234A_!{u6M6F{X(ufi zGzFjp9MjOffLZaIHcBW3tQ$;xX(lj9bJ~!EN4=Mue%9SSwh$ zi4`F3F0j%qEJ@Y2+9LU*Sg!EDug3ICjjCn)gBM44n(|hE0*)4#Ih_`;Dv5P~RZ6TE ztlY#h5Z@43DOd|VQ?YJZ(WCYQiR-7%S;rF2dPv+i!8xof5t(ZSED{T4 zCu%b+y<6GgL~Xq-^-{VB)K@SfWfG%~Eu=i2dly7w}+WvYhndBfja8u{?clvs(b zkJVLzrAoRWm`7p_U@nP;!5o~KT0TI^tT{7%U<#OV`jH(58^=zXb?QuvnIx7BHYhPK zSbq#d`q_ZJF%T^uShvJV!8#=t0Be_6Em*6>8o^p5)(X~iiUhj=8%!)4d)yCJSIE*% z&^GwXq!RKap%s)^K3I{&O27&vRtc6Tu^?EE#2UavHQ`rKbQr>bay{t;^CGZuxTp*0 z153YbRDTXke{4scMSyK`X!Dm)j*Rx70{P&VYhsjKJ{YCm!e^B6J*c_1Fx)xp`BcoO ze1-2rUDE}(F$SS#yBlG8z>GQqr1v9(;GHI}XVis5C^08ktBFxdoC<~|dUs6M(vmt% zetI(izqZTR;pu1wyxZ89uxa(%VlOVoNn>KvpgG*=owu>QCu&QX=jT|YJqN&XIf0e& zzRO2hVzD-FQX^m?9Q5@L=9r;buc^2^x^J`({ZN!iECNJY1;X zG-;lxVSVi@*@rW=Yqn(Xh~0O`9E*}Au@tZjiDiPNn^+<8kqefxgFTR>ZA(zgMvwO? z>|+gG;M7^#0)HcbQGxV|G8dz8i8;YS5=#XON-PVkT4H%%0f`lZRd5z<87lzGBw-C$ ziNxx`iX_$oRv@tsusn(Ng5|_8q(21ci-A}R_9UG55_5rhC6*4BDls3JM`HP4E)y%q zVJQJ~#FeqbF6~BlYDM%g(785Dk$_lPtx%e#GP|6Hfy_W6p!ubh1@$wOZFGu9=ih_2$L_dUa(w= z4S{7#%(@T_gT(O7KqW(B>0s%cMb9}OV2UKn2TPV%37Au2m0)&>1;MNmYXBQZ0Yn=a z9M3S|a16vfKCnTF^?~(EY#6K;%%vX(zFMQY2wlu=Y|}~F%5{`jweX`VoDaV;WGdan zO2DeYe1cI|PzlxohE-$k!3&LlK1rK>QJ+aeakWEZuZpHktOv{?u|Y5=82Qsi-Jo(Z z*R}F_-4c)HwA5DNGYaTR2B5`#;pfmQ_j)vkrN4@O=|PuNcn3{r>mNrmzJ_dNdGj=U zdg=~#@jPv9{Lmd3b*y*ukGxl;;u;!3jL`<|Rt?x7SP7rY|9YM_!{)h@?p0&1e+CN% z={fiL=6~^!r(P zCu`1&Yv4BTe8y4~pu}>(Dou>WJB487CI+P6!72wYd6>O=vbKK7kjbC&*a^P@6DtAh z1M36pqJ=tVu&h)q-;(_ZdmvTYU~7DYF4Xi7UVN9T&A0T|vAL&cn=BOv*p5@QZI-Ub z*pXATHR~deNhc82wi^dCP8PC*V5FloX``}LmZ3?kAH|!*bosjyfRyQ=&7icGv=Q?O zrs@QvJlK4&hI&lzKu6PX!J2Xq-$Bq8#pfIxWhZ~+o;TUK z9F508G!$(23+RW-7i$h%72Ngwxt}K%BM{yccy+Os7GHP>kKkmu<|TTNTqgpS0~j|C zt<0OQS>2U~qKytU3f9vwnF&_J7Y!{zBCr7yqx_bG^)|3qm*BuDPq2@dpe1N| zf~76hHrc|@&;;18pT_D-Sx9s&Xu=518|q>tJqGVS{Ta2_0jX}V@Ts2FQ6DJ+^4XiM_txs z>S_!xUx?0&Q5htIdBBV_o@$I2%mr48%zI{HztWJF3EWx5qC2xj!pdPM-M1;e*6>H8$d=5 zAHt?)q2GL+?O1_!KlcqW@3Vjv?!h;$K3k#THNZF6u@%T|_pkKnC%QI1Z>8o=aJAuK z3=3QPGHx~pR%$Mr=graM{e05)g_XE?Ylpj+F5YIap_N*W&DTyBZ~6`Tyj7ahT?V&N z%<0HU##%ItV2%8Bu;41h*#~z&Uo!BwtF#4{s^7BDS7Cy<`L~oA{q?G)naE`1w`@Zu zGFkDK-XPM~DE4KN4sOiqCE|6Zzhr6)+rC`oU|92rzW%;!wRV!t+d*!A z6MePjwpGC$RtWYG=k6{4R@^3Qj?0NMvhx2AyRBKy`rwe<&cwY zT7w?8B#G@?gX&VQu@Bd1Yy7!$BNO{hN3ajtY%uyw8`)tnADH<_tLt$&WeQ78a55O_ zjIuPsXMksbTM1w*z+Vnn%G?OM?{w`FOYuqU^V7BKE$tq*Elb<9v}ayq;vE=@xbiHV z3-corE0R$pdHAaZFP+am%F?!2au%|sXP}^K7e=UsrWyO|&%jlVbx{QGn_YJ=J*jzy zmT1d|yN3H8IYZNIO>j4pdlq}itDV5Vuhx@|YrB)#+_gB7YEEVw*WyHKI3+UirNvw% zo^v)@`82k7ExNh##q8s?xYTM{%(OGLGQFf-5X$dc7PoJr+ zNoqees->gV0&VN5?7K73trmDGjJ`8leQ2Fqylj^bwJU4c1b@e;E!t8GHx(3Zbi~@u z!8r$JK4RTqbzpQ((nh)gux2o-fwWOeI1bjmjICd%EwT(OW7oji#-VBBwfyOIDAbze z5zII*TY;fU?>fzADLxHr=4Cs>Y&dBIY_e5=`xvoJq2u$mn@3tfPB4g2UUEiIvC4GJ@k9mq$kIWJo~ z&0Tjoa*05+W#BL6JaqbCRlNNPWNV%+!*H7uErVuIVpU-M5(|O#ni%y~O<>)pvv0Ds zwM)vfV&heE(XN5fQKrp@KPOlP>3I85ezuls@twgAoQ>KXI)i<5wzeUu=Zt7gq5>E~ zn7%XE$_=QADQoF;(yy9!Z_pMbmBU>I4Q+I!%FjoSx|Y4VL0jW?tc&J{&Wd*UsbJ!) z@SKCQB5xhrdXBa!scC&wn*(jdCJf=$vp3GsHm+69LKsva+UOwlz_04;$ZJ+Ar&+Y~^{{)+EPe(Su%$ z3>4wDq2$ZhljmtyS^6($({d4}rkHKdr2*Yf*&DfNW*j@%=egQW%Xk^P>U`}1Oa1li zyYn#|4P77M-zcQ>R=o)4>-B8YCNy+qH?0nCRTKvmQS-&zbTQex+1$TBX3%VB=M> zdt3)L3}((?GuQx_d5_z{dZe&DU|oXg<*zpkfE`kVN+G&jDMBY$lN4bpScAl}!0M#< z^1yu@T~K8xE%wwgW6zV!dG5RsPr_90JUgBD7wH z<0%Dpfq5jB4(0+g9}*v!U5YOsZ2Wd{IH~-p_)7qX4JcS8*dUlW!XQ{5nE4ntfOSb> z!(bf}>jZ0);`8?bwnz~UgEdHj)onPQ5=#cFl_K{0G5h7H3lj5yc_fwr=8{+r zm_uTPen3@%WnhZLs=y*>^UbYZ2y94VO<)5OYXj?(ST|S?nBN@X0AQCS90%)=n4<_4 zNn$BrVK6F9+Q?>twSbw2;JJcj>ni0mU04K2J(`b0ot1-8anb0FwsibegJCg^BbT6O z#JBp6U7}rV>w-pn!E47>Ot{dw@6to?kyhCis4HN@{5l(7&9<|it+;e`pqa%B1`Bcd zixp7q`icWRB))^qy%cj-<#*sR3{yJH_Z$}LN#D-9m@0nRvG-oriR%l&IuVO`pUc2H zqz1eStj(mO!B+^Z^$zy&rRdx%?uy`Mi2j;!dZFfA;;D`;Gslln!@%rfAeW2qDPXR< zBbdX+tm7Mws$F>{uZ#uhg1oG5MfTi_ucm zuuYd~>n)jBW8^YSat+-_C3IaiCJ_F8nYK_%2}X|RiTKD+K86vlFv!+y!{uK818mPW z?P5z=E&FsECd(AYmR_#iX)E1N*Pi+;=!ci%>LC0GzQ%wtUF0CUvq;--DSnd8ze2m- z*8UWY%$5Z(VtV-s3_`P>W*=Rl9kvCU^~)?;AhLeDmSGuwo_)9-&n}h!lE#}qeFWFA zn}4jGX{mpWJ@8`;VuyakrWE5c&ECeA!`hPDBADCPzg&KEF=i(-+SuM=3>7QEaVMH4 z7CtD(#6slPy8BmHHF3t3+A>?wn{)eS3&>KmD&Q$^PA`iN##+2 zznW6?>c3&{U8(JK2iv3msqjnwDcVM`Om@Bnw>2uS!flP(c6>Qcd)kuK!PZ=@?Xb0V zMldC$FZlfS)!OW&A-Iimv>0);?7#`$$-cWhG9i-VBy zFE(;5Ce_M@*w#{1D*M+sr}_J&ZDDI=Uwqo;g-5z%9PjMK1a2N8!{rXR}*|s9Mi}=(aK9uc@ zuRV%OhwCxP=-q)?%jTnO%?|8K@d(?q1C_3PgdHXuz&eaOP$uo)v86x5#g6CS?5dw> z+ih0s7_L(Fx4j2{hFP*axUG~OY;om>MoWSN@hcgcg zHC}U_wq}`q^4LV}p;oxO0>euaqey-Ds{xOwV<;wl<)AOF(@suuP8pjRdU&Dfhen;k z(yqrD9GJqkU9ZiLub48XuN9O~ax*TFrm(};??*4BL?Z~+MlQioCQE5lJinmLjoQuw;off;lDD3TBsB7nqf^HAs?If_}hpgew_-Q|R>W8Q+HoU_OPw~xZ%a_qR0)B78hi6bG`-GQZ0$|BoUX(xyf@*pyK**L zRH1G6*UgDdsKAdQp2SMQY9tl_tCCnPSf#`o!OA7p3RcS5CfXUj>URMaOTvDzLWxDd z@=c7|L3;qheXv@-UU1J0JT4lz8RvTA9Jc3X%<{I)W$)aKYOKs-$8N?vv+j(6EqdsQ#SDwkcRLwr?l8gz`mHm5c|Vrn6bMU;?_~ zWVZYkOcddT&>gp+ImPRdAKii`uzWRJTL~Us&30C5JL7ZKqB1{+hRAa(HAHK%hCS{H zmipM9TQQrGvyP&k7@z20_-n1g;Q*(GfHpe*U0_WnMh$R3So=D}KCx=1{SNdS1}WR6 zsf+FFW8=wzBE`fgoVGOqneoeO_cJ0=*q>OW-EeQ=COR6!>KZhNL zU%cy_G2UHxTzFY844;g1*s*zt1H zBwrAIRhy#S5~bAuR=$aSemnA=lE>y&Y3mc(^2Uz$C~VgPG<>&JpFGK_+z*d02PG~B@%K7Phul3T`+}^6zw4VgF#U9*dXv)FNakYb$N~{O0SYm@yz)JWcQq%9zX3y$@n}#2>dGI$54VdXkfTDXeYf>L%K6ukcEnLO}=&*{| z&U>__wu~am+jVp=w(TBF#^cjypWlOVM5Kr%)o9z|tGAD_lYZw~=r4Q_&EfXg<5LD! zZ(@{}DzI7;qeQ7*)PYxl8~G*HESOQp$gdr&20DWQQFy!q2#+8<%#~pX3^|Np)>=$_ zNz4USA+dC@GKu-XO2DX;XroN#>+ziun@EX>(8#41!b)8@#{TNYGah(`>I61)FJ4Ha z!Z63z4jC0B#Z4R89F~qNlEq}M_U)Fri~DfZ)acbMF-ggzb1Zpdf|QA3X59I_S~oKwDn&#cD#Xi zoXJ7lRWH1n8hc|jK80-wq74j{usefjX9uqtqnGjNiPHWc2A=8HvMKj#PbYMijvdd7 z=WXMM_v6v?-k;I9{||9kFJZ<5+7h?(y69M)+8oEjXpq5N^pxWaR{DUJZRx!p9}2)V zgrl5Idk{IUFGr*kk3l&vYKPk>3M!ub{b+wARsz-{u}ZKe6QlHlU=3hc{F5G)8hTLk z*}^}kA%uRPbYm^**eM=&VxoQmcRYfMeG{AZ z5Ly7N?uFh79}RP|OCHh|ro7TIVp+&Y30NLhQGEym1 z1Psi}9m6Uzk41M3H?;;-Ah#BlAGzKfcyzpTRHb%fAH4l&#aDU5-trDhjf8`3oW zErkdo3F_|oX|>Rqn*r}*XfnWz<}L$?W`l)xu{|MN!*swegAWEj4$(D^pG|pKTXRWD zAoegj>oGo%SSpy)#36gX%;8=@|?&s4rP4mO3g0nsI_D4mTb2hAMLiX`U9w15h%pcNN*lM z709h+Umn1TR8*_a2z*V?i~Sv|7dW3pF+^GAV~DL9v3*5(dipU8g!3L6W2b)RUb3$q zml>rGQB$YSprzGQ)3*Wo>{_8uWE=ef5aOU!bjJ?8|!8%)SY) zsa}+!y%7~CG-g_g!fh*un}<$Jg`^ac+R&K3&el9S<3a!-XpHvC2i61@1S{fq6`hB0 zG2NuQX-$TyH0n-%3iSx6O^mh=X=(m~htUke&)BH0S3(yA_ZVYIFygh~p-0D#kH;Ho z-T*X#R~{UTd2FMN;sEmrDeY=ESS#2Nv31jYkE#dQBM-YKGw#Ah1CzgFc|FtZNwsi z85NqC{TVdmQdkdIy@`3C%K)owU^^SM`Dr1OAH`7$zZw&xrZ4~&Xkc$OU=ZKhz${N- zPN?K5w&@AF5B)6L_XGy@4KJ|IpFro7-@-OL2|m!m_CAR!tG>iueG>Z0msr9tpmV;= zw*Ep}o7C}gwC%4)8YPFZk1w;szt9fZYF?rCeXLPSVK+Bww^({#VIz&&AxlP>?SBfk zI?UESjk1K@{i^?^4Z-X<;CQvMp-)P%F7^EK2n z&g<~`3|n0*RqcaqZYO)YNjo*E<@IPMM7imB5!WuSvuV#_3L*GwI`Q?n;VYljW?3S? zX1kun_`>-c>JtzL9&meBJK17wX91>*#v?tYB;23au;1hCJW4=Xcm|Y)-h})Cx-N{N< zavP56@#As(t@wgBP6>+|I9+Lu_p9}5lyE$jn^%UdYWwL*z-DheUFo)|ZL5`D8`_cj zgxa{S)0LJ<>i8NZIN3S4MroLw89H65nWA>BQ9@Jf;Wf(e6i3Y(r9aUTS*=t}Rq?xK zDn=w7Q&oVjsbzR5V49r5R^{f0!^NDKz3Z>^nwQiMCJHruN zrSv(~;A*9IraGRfbk4N)XDYo(YE`BZoTUz}Qrc&!-K&(4OGR|`E+o?HQW0mr3yENn z*Q!-Yue%1jGoY!%E0rNF4{6VK)gXAXqdHS*PPPuNQaX~YwWp&{RR6#lrEZR$9CK87 zG|p99Rw+Gm)!vm#$4P4I3Z=oLR%a+Z9{ccVN^qXFZMo7lPYtiYOGawL3MD+>+LxgW z&R2Ugl==nsb|@EE8%|Ri7OD;Sy-@90t^^jTbs0){kt3L)jGwG_o~Bf#R-&aiMQuIJ zuT-Cc9QK^z8egHbELMZ3DFchuq2)?ly0sBWEm6BxD1oJF%?d0ZXRleMG%d9bpRTlm ztWt)Ss*wz(;Z$qyX-ea%4LGcw%hZPDcvwz9dduiI^e>}BFu070Yj_!z)c7(x3aNUz z9mP|7!g9(_-Ew3_X;>aiWY@ij7b72k9?z%X(IA`67N=KYJ zK3y4)Q~RbXHSua>x>6foh4Kzr)v!aUx3=SVzpXp2??k0lb@onIx>RQ;0;p=kbftN+ zwZnlr<3zBgDQbAS(l^E0=TN#6)jEgLOZ{J!-4UFw3`|XT)*uurkV9#nX03PN6Y!pp zLkT!2$!Z5B7IaXkkfSP|?SD}_KJ|E1yWEDs}N{Lt zpBPtX4dV&c?nHZkV%%_|J!p>$*fA< zrP-;5Pfs$Xhe<--)BVBb78-mJT^kc4y80xFITNO5QWTqauN4QfB zF04=39AWc>EfBUy*b-sOgstG#uLK0B7B(boy|B%~wh7xIY>%)5!bXHuujV`85;j#> zudqI0b99RbBk}|&61GHGRg_GHa90Z(61HC03Q=+aVXK7=3L6r(Uf4!qo5|9HF<}AP zgzXTvOV}P^`-B}ZY%$-{K4E)=?GkoK=seeRU8=BNVSTWazLFIWYG%7nW@ z*nqIr!Uly630p6$5x(s@o`DWwyM*nz&Z(!b^a(H^?2xb#VHFXfDy&0Tm$0FoJb~;y zRZp|BklXPKxHU48xrw{;F6P!=IGz7+ZkVtSz8g2w-+DH88v)NYegOOMd+08n;9~r~ z!0>}j-Oa5ADIP_!AwBhOzJnDZp5L|u+|hsG>%10{<6$usW!|l^^E$Yx#1adP*A zAH=!itKZi5{j^>YCgpvuP2=4mf>2dQ`y}Gl9r)+^v&#Fywl4H=1GPM5s;0CVJEA@m z%Z*4Kf*bkbX()X9Te3LV z$aCiKP1e1f>$zY*!{-TGBy5SW6_Pt3+||N{ zgsm60S=g|!1;6C+5ANjoQlH>A4ur`V>;KokF~qdQ?GV-oXY7X~d$#`5B3duQ z9UtpnswlBQiIdzzU-As$0LRDedusly6TFBxApRm>I@yoAwI%V&S5EdI{cz#OZ}4NP z<0~HUGz7G;KXhvg;=S-&@B#c%h2Lu3Z^;Mn%YonR@QW|Pj~7Yg6QZki(Y+8&EfDBh z9lid6mSUu`2ZT-wD_hp1c??=JL9Z~;dnf3!4=|_=BfYua)(}x6_)TYGK31wl|b!#V0SBLn1PoBW<67~o@WddLKk>;@rI-Mx{ zDGF(7o7@#?+A%1?@ga&okX|`4XJ(-OpplUB+-bu$B@uDF^P7l&rI;H|13P6 zU`DejXvI-p11JD(!J|%Ax@;D{_4`*%^_N7r@30Ru8`uiYl73~uX$ z)dS(*WHE+m6!8t@a9wyKw^hQHoWtD}*}C;B?PqaNAZ(7XRxxO577;dGz;&Tb+**!EAfrL(iAad(68 z?@_qh`QLW-%qQByi3A45c&bC6XzKh5J69P=6j7|NX8``P+YHCe3H}cqrYh6Jq175Ia*dlXIt&-DVD-Cw8XmZ<^=- zT7HTB-&1~h{iY%?3N>hk6Y&FX{J$I@%DdwI-|xhlzncodNTmAj$WEh6?5TUIUb8yP zu)@Wm`Wcj+LKzgw9D*qt4?fP}c8|jAV9ngvf-MxfYGG@Wx&NS>+iWF;pELTNVc!;W z-s|DEej&G=^V#R0X>+$!r~QyW=T#zHh7@n_4~An~|A9q#s(vtC9DBF7N@+R=?Hm~KOWKj%ioUWYd( zLzO=qFBQ<1nl=Bsczsg5Rk1s2&ad`QZLXH_gYoJI++Y4b?2l8FTZSXHoVtH-e`3o) zu7K&W`L&xeJe8gB?d($??2EJdoA2SV^xw^Gb~U$M4&M7yd#ty~u+)2XP5*wL_e1=| zAJEU#xnGamoIv0N9)PZ}#8nng*!letb@7N$pD_i1KiVjxMIs*R(L}GtJ3@vP2Xa!lodq#e?t|e~3plENuTnQ`x2DQ7Dx8!e%4HJ>=0OlzGBh z5#lv?%x@4NN7!MJ2_JT~2!9Gz?a&~QyN{o;MT{ncfZg) ztm`Xn{ww2OX~l6CM=txkcJ^GqdNP+F8hy)2a^}>dQ?GUy{*a2Z9!aCA;0;$4g3Y#Nrfv_dQRtQ@yY)H45EN>Q| zL)boHjS?xx5Bf8fvcLS$2M6iHLZJO=F9PwK;y{K1<#bUPcX1@Q~`$+mYY0 zKhAAdqwp8J@(_0$IV=|Li12s)g8L5%cj^J%ouSkUkRxo0utr24E>xPHTbZ`Yea3hq-NPBF{PT`MO=0Xm8@Y`dNMd&t9DM3%wK+dFE~LY!@(lI9!vkden%jVIrwVuL+nf({aGNZ6>Kokc5!NNF{S7@Q zD^9O_lMAfEqf$gL{yOK4zvZ^<_uS@P$um@Nx`1E7XCqD zsr9FOvI&x|S@?&ArGrBk0aGQNxWq=YFpDQdT?h$hNTlgMS3nA4Q z5*A1i2A@dM!-RzH1fjcB(lrYIW?^Y4L-B2k>UjDcLeM4bbRoPVDg?oE3c`O#So%~I zMOZB9jI&QY#OurqXsCW&E$goK^F3Ct=9c7ioUfIH4&iTDQqwWMLDG4I&ahNYq^p#4 znL?N87e8hR;T@7NPxu?wC3JfwU764smTs|8!c5Xt3!P#8nh@4Y!g?VzEZq#Cl6gwf zH42?!@mP(X@bi)`EOc$c&Vdf6vR`>s5_Skdm#}lWQ2CXl>kwaCwBC4<((DN2FxD!rv$C0t!7fPq>Q6K6r&X zdv%#06~Zn=TvV=qmf{Nt|7u|uQGC;b!W9zsWcKxcYpxT7t5I0C`@n2>k(h#P7Vs1# zLT%?KQbJ+j-zIFD(0wN9dW8Rgu!|`}S44zM{RuC$bcCke`Ii*hCHy_YE)l7GE9p{& zf2OcYDHVT?a2fVgkxE1gohNjL^+HEyfwGC`j(*ZsBy@&d21dHclCFa5{EGOYEEmEP zC1JIQ(6G2=rAIhh(uIW1uo*&^BIz21j$1U6D}-=~By1Bx!_xY)v?nViU60Tic9qbb zDd~oU&am_ht=>uHNJ7UoyhuI5;zpd_lWvxDKH;AyEWI>M6{JAYl?nfVu%`=M5p>j6 zOl%<`XcRU}KQY3>)gkN|I_(jz0b$qbG$LH;wR{)OWLNxYw#zT3^i|Q_`;a1?FC|h& z!@|Eq*mclQiT_m6{w4(iI7R!=5d4 zcT2hwp{wB5uWS$rKOhOKg)k)SIU+(P>6(Rqo3J@TS1;*$g#UoB=ju9C@~0%BQpyjI zOW2Jf!WSf6rtr@Z_B^3`P0|$!|1x27g|3}+d?W&bty%~|!k!OC$M_FYgkj;|A?zlh z`%u#L3I8EsFA%!FnsoZEI)2Lc*duJ7-u!um%dndfoCbOWrr>ZYnMNpKw}8>`=yOR| zCj0}!UMO^5NV*XB$D`Lmm@kAwlCVqo_X&HE(0wcElpTEc9Kv2KbR&|^EBteGizD+R zAsmy0B|=ysY=O{?OS+)&Zxr?tp*t?=I)s0puvfE&pCeb?PuJr3VSIi)exJc za|nNzu!VXH}dpS~}vFx-9Vsn%y{EG}LbSFx>GT~n# z>=kTx_iUGu&!C{&^?}7T!qq73j}a$TsH6*G(+&&&Heri}&MoOWguh|06uRUK^vm@X z{vIJ15*ANx=n0-AMdT>s8Sn^O0v$Eh^Cg{E_#5^oBEFL)osaAMiuj>iBZO&^Fh@ja zSUg9fXK;z6D=;!9Y$9grzQscJW3@r*eP4 zB7P_Vi0IH&Nn?l9&j3jj2AQ}Q;?;;`oUXpY-D*Uwtu2zU zO!xLTVu6HwzE^rmaUrWZ1)Cq)U)=143um=b)iJb+V)z5<0^+la8u_LlQ=W z&{4rN^gJ|FLuN@jukbhQ3qp62q{|e#9ARG+x|5+h8^0&E0wE|7wgo`Qu0sur%0urDJd-ECMUg>Dr7&BDF{4V7!Ar0Wp=UBZT;q5kA_N%w!+dlUG$s`CH; zb^)dhg-N$eJG7kwtwFXa>##Z?V1$AL6bPkYSREE21%$B9fEA`}rffGXLO_;)!goN_ zun1uh10qflH9*yXh+$C!R7j!d|D5~0pJejTeEENu-;3Al_xjye)6bmqyw7vid+v7T zPLJ3NK`-Eg4)Q}hYruZ&st-BFS8p%F4Zx{B47Z=*g0rN5Vv)L@e8ho%-#OTTaX{6d zImQp+uNy7}r}`+|@rFyosXpd8Kax%}U=~od3y0?!E(fRjINZgCYl2gK0&bb(eEx%5 zGob2|&f;r)gK=1dQ+>)Y{=j&<;o9I-e-2k3;w1kvpz70r4-bJZ#x1~rQ~d?p(}wGX zQ|*RZZn)rVPHKX)Wl%f=xWa%b?5fYg{nc<;IMrXmy=S;4xTXRho&)^EfGyZne+3si zVEDAx3a9!!+$6(wz^N8~4LH+)U4W_;xJ?Y#1E;ziZX3h(!>PU?Tp{?90psUL%~XGb z!@UichEshJ?jXbE;8cGL*A#J8=_L8i%cLs=tRj!*CsNsy%QQRC7N6Za~$S z057WsU0ffW>dSDU;bP}X3#z^XcdOx2j*IH=Klp70;5`P+VpshGT&Llh;8gzz_oU&9 za89ND{{;BF0owspd*NO(To;_`t8lLyt`|=AHD7-}bN$1B!Fkdms(;4eM}|wmslE=k z)`6sVVZUYJRR7}Qe7^C50h<6--vCS+t_Y|4SGc)`>wr`3gPR8@?e8MH0af1w+}Swn zgHwGA?kk3iozEad--bJ2I9CYL0IKf*9zGlla&W4DgUcJP1y1$vaHkorJ>p#b<%1go zfae>q3x}%xa7zu>1E=~f+|`B~fQ!_(|9gNp8!*AaN%eiWyA79yQ(X!7W5YGTss7V( z1wRVA4A=yy`T-7qX}BVs>W6T@Gh7>->HyrU2eSXWaI}>HRad!KU%+>a!wQ`0M{pk+ zt{+bIW4O@^boXTZ$BPo7x*Bl8Am}38mWEUP#KrjnCJfgIr}{6rjSSaP0Bk}34Y-8? z+p(+qb9A5a4uR7mih8uuG z3&C1|M;b7=fIdRkhRYi+hF#TvvB_8D6vM^gRQ*p&uH)zbGYpsjR2_%I^9+}QQymYt z#BlX+sx@$zdXDku%IgLfpsN2d315>djl&F_>IBF6KEBRyIXKnz;BKknqWtrKs_O&Z zRR#J27U5LmaQ7Lm4NkQd?m@$KT)_VCK6wAZM8L-l*oj?r65KO}tH7!H7svUQS#G#K zxV{URAf^DmWWWJH)v0i=8ZL36R6w;3?oGpG;8YU@z;_Lp15}*`x5{wMaH`YcMjgc7 z6Sb@BIyluNTw$C6TLD!!0IW4!J6su^0XNNXUD#D;!p#P@fb213#hs`;L>W)aRYFw`@k(TT>N6`I@S4b*BP$f zaZ&yK2fytLc#8qE*j4?zj{Hn}m*E=WRKEsypW&L}oJ#xW03S492~c%^xW^6G4ySqm z+%twN!>JxP%H?(r~JW!i_pa@{#s;ec1r0x)5+2pdTN8%fqQ223KpiBAn_XxM{<=4T3g6)x!a2 zAHq7WGJxvW0X7-#Dd>VzZGxL;xL!EbBjI*1T(C51BG*FlAvg+fHv^`ys~!#aRl{ZA zRF8q%-*7oNQJ4R*fQK5e2~hPoxFZeM45#`HxZ@31f>X_V&X17A25bXVJsyW=8Lk6P z^#r&J4A%u$K~IER>bSuX>PKH6KtFmC;4kd*5)~yrxdI(Bi%?9`uY^0xaDCVZ(5pPRvCH^e18NVcUM)S9 zxI$XC9=*n;_am%el4r21Uh6o2KXr-W8sJnzxJwO}7p@TS!M*658?**&!J+DPj`KZw zo#9Gws@KEaVz@RqQP)#90N!Q54nWl#;qEhBC!Ff{;2tzwH=OECp7VS6;|A;jRJ|F8 z&ls*$Ctau7?l|8i%MI6uzkc)<$N8P7$8pi@;yy=P?7QNyg|C6$3izsVn1IW`eIM>E z!__N?-Uj#n5GVOJ05qbv1FjwdqXOo!x1e{xt#zmroO%Q$>}}|saO)Ya!~ERzb|CtM*o!hj8Jazs(R-+}I5 zaIE1HI8yzQgM3AfGh7Nz^#RE^I6mU4#(zDa>W>}hCz@vCFb${r6UX`8sl{*&aH>Cr zyP%r$`8NTob^=~f4f+h=R3C)9%5Wt()rTDC5Art}uFY{#{rv~OJq&n<0Xwm)J_1)Z zTsNHR&)^<1To0U6Y5zw7pE6)Cpz33A&l|2EPPGfJ$8ZC1s*n5oAHHc`GhpmWX%W>Y zaQKel5^$o;5lPW2CP9~rK< z0N9KE5pe8b!{>!Q?5cl)ThDOr7o4P|XfIsCaB=Jf{qQQ_h6YRls=fxdnc>oKs(*&t z&Tv^cwBUXaNT%Sd0UH5T{{pwS;qq{*Z@?`uToF$7uMy|^{|E!N0;=}mFmJdHIMp}d zPBmN?oa$R}=X#Fu7xh^Wpz7Oz7a52BaH{XXwHhwChOvPD4et6XF3LXvp!#>f+p0ic z!g@H>f56>qxD1?XKU}Bba@Xkd4-&i!_=ExT*j3+yd(Lo0IMw&zerLEgxVCFJ|6d8% zYrqab)qldhWwIZNu4c85)`eDI={;c(12J8jwM+Y3|FUvPIWchG{ZH)sea-(U*VK+{!WE#Er6>30^Dd3 z&p}E6t*F0=>F;CCH93~CccG&k*^)eYh9sOEhB?SQHq0p48=I<6B=bz``D4Of9vodb8j;rbjG)!%>c+g!k(7%;e= zzC*tN_mJTd*j4M{9yMGV&Z)HjCV)>EumMoj|1_1Kf}b{A6P)U%aL*d91x|Id(Jp`Q z@OcBa0;+C~!xs$K0jIhJ-0uw61*f_t+{*<6_5iA;0sm;YemK>6aIYCIb^|jex)t0T zaMJ#+1yTU2TLZpj9A@BDw}Jb+;c{@Q+rqs!oO4eq09CgG{9rg36ya32hx^EIt#GOt zxPKY0BjQ~B<%9d40^sPw8SSoB{MLm-)g9s1He3&!>P~Ru4c8ABsc-+C0oOBN>_++y z-34x<;ZoRDcZHj3xD1@?mmKGR)GU~8z#O1z7Kbwpmxoi`4Q@lj72#BOhnsu2xl_>w zsQP8VFB*qsIMqGiwlG{5oa&x%TMcrI{~kcqy#Tix1pP>GD@EW`zXG?T;ezimhR_DM zT@9Bg03^__0`6|WG5K!}Y_d9uRS^|Bo|Z>?U?Q^gtY*V7L@^)dg@T z8!iKHo@4w)gDVH9dNAM_#$hv@>LGAv8?F^jwGr<8DlW>u4A_Mp3V2}^=u6mx zy$@XocahDZ=4VQsyK#zdC)^JVOn{F;h z#$N}#-hj=3s!eb=8LkAUdL-PfhHHmYJ*ohBhXFeQRgZ?d+i(>))nnl9HC!K@>alQz z`wch%sCpdWPYf4tmzGog2HZo2OT($=;T{!kX#6(-svZycgmKser+Nb1(}rt-Q#}#x z*5!LE8T-0uw6@42Y{w@6c-0{F546WCRo9p~>_ z{n2n~IMu~)e>Pke&TEwasepY3Yy?z24eoD-Ylc%j9qv8DmEcsrHQMFxYx1E1+W}S2 zz~O4cb;4E9Gacve(~UYpS~Qwe+<$%82hbL{b&e0R} zA`Z7STpYXV1#nv%u3or8z=z;M2l}zFy#X^gY(T&5IKO~kXTvpOS6$*bzkpy5!!^UT zMCxu~ekWW!udc4PNPH`LQ50QhC)kBv?A*G0sKLI*Z7=o#wB$Jd6mUPoC2o^;OrcBR z8V%PV_VGa@;3ZPbJi!+9Qi(1RY(p=T=njIN=;adKO|S>OLZbT!4xrza=-BO2sgdvJ#|LL1zfhKpmbN3Vk`7%qdoAyT*dU++L)US!(Ib+VOQ;NoFA-zHe4^9>RpcW zW8rPX^}+QO_;5GiN(1&|SN#FpCx#nIUVZc7@st?1RZ@2+C)kokiGF+^KLD<3N=g$DIFkk{u^-;KM4Ob7R`WW0zhReXI zcKO@S{+#Cy12zDvKJFZP?gxfzgj0P2u57qGoa&QsKQ0)s1yJ=Vz=sT1f>ZrD++&7o zgHwGP?kTvz@!tWc`U}8kjKfYi)o!@w4c85)`V8D}hI56W2T=7{z@Fh?&uLskOA8PRbPi&Xt+)|)xW@f-Eb8+)i)x}_5U#j>;qK&D-Mr0T<`;S zFSHNtWWyz}tG)?$n&%jQ(dbG8X3@7C=x;%^7>AA6^XS`-^Jl^58m@@F4Sff$P{l=6 z=mh9S{}%3cxcj{iLcQqU<$|$~VDLk!{y&^o|CX@}tGxQ^B(SH^ez?mG*MPkVeHX6H za4ljl1g(JYInbYjf8T%|*t^j8;eKGa9_;<-O1K{xE_RPpG!?1quzvzRY`_d)4*dY` zNyFu_7ts&lerdQi>}7PoaY6X4d3BR&yNT*WSB15wxE>=EzgJ59kzD!L6U?F?hs%#} zFrj92wZJ8U?dT`rea>@%PzC)LMgEN`av%2KKcoczhI_?u3G8XqkKgEe%5V+XkIwU9 zlmq=(f7^hq*vsf>xW5~&2YWv{2JYP^S&o;Cm!;$hbS($?JDMv6IJ}U;kVaz;@J0W~ zc(RJab8?Fm`1)Tu5q2YS5 z4@Bz5|9TGe7qwqBVEjI*SqfbrZfnD3v8%?(cxS^k!sXFg&-n>+4+FLUs7`dCpOWSq zt_@Cg65Jt%E5oTycAT&9QI4ygu!Al@)hU1{8iy4))v0i&8?F~lwa#(==Gl2eoa8?M zsG0y=G6cG0?%lC^2L_$yI6qh~HC(;k(LtxfU1hlJ{RQdcEMOAw1_L%?SKR>a`-W?V zQ=I|#1H%>JiUmH*1pJW!Td}Lof_vC-?Qp6oxF-!)hEpxf2K=P~y8u-;betbFzcE|| zPIV)=6^84DQ{C8cZXzlKe=%S`pz0h4`m_4C4Hx`~i3gnv*KfEu_6+(3$vF6D#8r*| zCV&!J5BRZhSjOIkZUQ&zsNpkV1$!U*MYwgUxhVe!Bw-xg6mUW{=vts2dm7ygZj#}$ z*c;Hz;ieg`(b@g(7`PANIcFx_Ph*p!1>KUAvrNiX>>X$tZjRx)u=k+z;5Ic}zu4WI z@qR2#u@&Gv1E#R6ZtXZ-;)vv%kX}Cr>)j|W{ zvj!{zs(ux2x#2qCRQHDKFsbsymh!JiBmJjhr;=i~4V!=gqvo#dh9uL0o-iE6`lQXU)T=7g8(-%U@!LIVafPlxOs+a*;MRlxI@AV&P>)7 zG6WmYMwi^5SL|StH(_r^4|SaT7wm4h67~*sA;sC#a9v_A1bhe%!{NRLtl&s>5nRr2 zeQ>IW!yRb20XR|D#YX@hY{1wf(qO7zhdb18^>C_9aElC=fm1!wbAE_@-GB{%sz>4Q zD8uF9RF8%`)^H^_)nnlDj;q?m+)61x)nfrqG!Dyfs>i{dY`AVX)o;Kp9^xebUO?46 z;ORr4YbUpp!Koe(cc$UuKa;LgJpt})!=-=5Atp_N69LaNUTM4A%muT38JDT?3W?RZoSx(s1o?s;9wSW4JCj z)zgJ51Z@WF0aX1K4sS4AKb-0ra5ot)_9(kCdM4a05mz<-Qvj+hfVUZkX*kuh;O;bB z7EbkSxVx)4pMN8u>N$Y-RD+IdhEqKku57p#IMwqU=kHhi$Z#dcO>pr+D+$i`hlE6d zPzPFY$^8-GQIotAdpBBy`-S0pu&Z7GS20|_<`+CBJ$51BO9qT%Podw2d(CiZ?5a!P z-ZoqVT%%|q_zvJo1Lgr+(2L+cFcwztA0rj>ZSJ>rxJF)QRC1iV1$)t%$%(aP zY+dNm=x|+IA($u0CE>E~xGp2M7roRu@;$!3$#4L>>Sb`#4HxfX{zNZ_n`5|o?1d~J zu5h4#rjRyZBlafryN>f?Y8%7lvA3YDaJv|;guP94bg(RZ{9 zhrfdj*Dah|-bRA!0l#j*9_*?&z~v3s2d8=?++xEGz=^uq>wAD_8!+~Sw5sY&aNjmu z0#5a2xXTPz52xDhIX`<|W55ic>Mc0D$#4yDs<*=3X}Cr>)$hZV9anYqa7z#YRc`}) z&^T;?Q@tJT3B#4(RPTWMEvGq?7*&iFAmo^RtoG} z#cw@us{a8u!Emvss4%*J8E}#TGXSdh!A&z<9!~XsnS)x0R{fF8Hrd}u_VdxJ(MGfx zJqG7pXL+`Jy$wU{@_q7}3U?M3_0eslm0 zPL=dAG>#_F)De?iK6Aph?5uO(q5-JKtJEWa4d~d`6gSts?7* zY;}>-)u(Ocfn0d^jmcTl-PLyy9;f}YX$}U{}q>PHykBZuS`u3M}(QSQ~wi!P;{B(~{zTm)c z$1B|!jJ-3w`dZI+^2>yaZ<{=6orH6@!DI2EK|HQsD-aFRWP|ae&6r={n{meUdhE9R ztqY=dOeX#|yd0W7dr*`Q&*9orqpnES9oj@KwTq+>?ozmEc-Lj8 zNmzI2PSZLvEd)XD5yGtf=EjbM)*7ul2T18Yv-d93U_(?+m29v9vn zCTC4swdUk4-v}4p;EueQZ6g))(ny())|@<@m(n+kVDCO&?ES0PoIWo0F}cvqL{V{7?c=o)y^{?t36(3W)V`_NXP04M?WNx1t z{=k3ey=|)B=QeTXb;k@01;$2mUv1)c@u+>dwwo5eFs8+&zVzngwzWOR?9bW0kgUIB zcp}|PvL{3XU_$q8RrY1~&5H6aIiDxCyAn0uG4-lHtuxz2P9D?cB46>5_3p!@Til1d z`>>DukZd$rYbFWFWK5^4%fk+=?KfaD+&??6eza?eO>cGPj4A8};qt#G>qon6XqK^I zb9XXU8#8XEMlF$WZfd^o+%y>Ty5YQcof~I9$C=};CYR{4%vG^=Op`<2cF34Em*q}3 zCFe|P-dJ{aZSx-2Ansta(d+w9jG}Ht)gC`U;_LUH=((XTAM~Wtjq@Z~q~=H#uF;}9 z0jWEqEH=FwSGO7MBK*Jt$*O$7#Nm##EQvd(hTpzDIp@H{uZ8UYm8b$Mo|mu|NoUCX z3CwVS@wpQ2Ae{KI93z_Eo;Y-jm>vJ-@KnuTkg%SObc7fDVtU=U*!vVBocC%nv5>6v zNRqRO-jORCTg22!;#||^DWX;({95zjDp3->K~wo%BynKPo$@ zZGnN4!@WD)#nHge)@)Co99;lUZyCYfcS6gDkmqy8_u0NV|1oj zruxni9F?%g9$Rxkda&mnU$Z@ZTI9db{-oHoVfzWko*JGmML3P>5Xcg4MD-jiPq>I` z2euLJ5Irnf59c%Q#85$Xxbzb4NA)CYfN<>RQc%5oO%SgCdH8Z$a&DowOY9lqwWa%s z&l0Z{ik&6L*7OsSPAk*^*NAF`^c=K_cs*%smhjd=3kI!Fk#H-j6>1|~jtV}rCRLOX zyg_l2A1a&FKTSnYt;pweva9XgKyeyT?!Igs*t1~0?)lV7aOqoeR@7!Hrn5?aOEgrI z>0d|#=up+;UG}UfeIbFp)GeIvA>T-P(&HQ2hxH`K+kJ1f!uy`~qd-rNJRgOt{P{}g z$&df+|Jub~h}LxYUe>cG|JncPNsM<`=l(jXGW20Rxmn+R_9yLS?4I}G&MMv)x{I)X zOy$FsDC`bnJ~Lm79su7LKCEX)J_CP2+lSpJ_ThfQp7m{~XJ0Z;(=hMAhxK&LKQf)}{^CA?+k6duSWg3e0sW{?VE5^LxSp{0?+;CS zy6EjboObr;Fzz$(5m^%Wus{6d2>TZD;YPx~0RDi`#QCG=eOS*|{V4b2unFE5z=s>* zeYn>B<)4`vJhO*?qW;urJVBF5F%fUfYE`s>18IaJecx z)`dHtDM*w0K8?AEE&yL+AMSKoy|vDh!}4wZJ2P&}M&Ds^HD|X{Rj!1+f?9w1y>a-Q z|I&=xUPRTAY94Mi_BalsMDD*+*YW4jQwrI22#JZnG z+e#|9F8OS{O3KxMWmhe+(WOVnWIW8eTD0{PaiahSSDtNkl!m8Ja=&Ky5+i6R!nbKv)a9h;UI$fDUXe zEtd8}!Vl**z-EAc#)g8E*Omfah8D4_D!1-BaH!^cVpR*-F5bfXQZNJP-S|$?zLpMh zgLdoik{`L>R@Qhs2DLz{%8fJzzej$}w1}3YbsK3RcNa8@ItHbu+#7pnu}3hxGfu#f zx+)kicI~Q0!rE084O4=@P%s@cTCn@ z-%dJ33hKsfj)-;r8aKC1MmIY_!VCOTHMf0M!E8&NrGm7g+J5^Q$Ve-4qmet{g-zl8LNKqZz)}1yGZw9RiJ-$CPk^!{F8!-lh-`L1LE@(kOV=6aNaKpbz3JI_lrNPwrxy!yUEO9J4=N#*t6(r zbctUa>NdMeYlSbvZfA45gIo>QiBdGT%65bbU#JzPfFua=|HA?gpM$7l4P}wd|E&VKCo{D`Im3`b%Ei^@LXsKy6B%a^B`K8wmenT!__Z?6}1 zP-#H)^;M#aT&%yW|Ih4M7$?CtWBqLpH@WWa@4>h$wFc4Gza+YPg4o|d%Wp%8?y-l2ON8sUlJMAV zMHk>#cFZ7HMEFM3H-g&=LDSX#R!9(}qW^>7B*Iz3O9&SUw-SD52PxQyEwh){OM8g6 ztd!pMcYgdL^{&zAOAs>GduLbx&no(3G`A@sVx4h3kXyM!A zL7m)@&I&i!75OtHK8D@D!_jXobcKD#V>@>3x;Fgl%P0LiCH>~QGRpr`FP-!+ll0q- zWYCENec9xxVh%d6r?ued?$~uK<%n-Y7Z2JCGWhZsTF`bnUmcW)CtdU{ME_X_Z=0q= zcN@$={C5)Hjr!Mg`mLov4eWb7{R>3>rcG#HFzR0%>NnjR?2AQj!mcf7-zVx{#pbtt zVyAFqkZ|CCk=t*vZ%TYTE)$o3)tcXWh?h_h_*bj>t?LwjpqLXqz%8_QO0~Pu;6VwO z9}>+FKBksg5#3|5gd559DRg7(H_j4!ZmMWATAnE3f!UFc4f^ZW^T*en>gR}|ce>~g zzbN{gfI+aSgiqfP`{tsREu!>=+a8tz2aljq*;!)j4CE*Mz^C3amuaRA43c z&uD<1ga2j=1jRQe_y+j$|DXY)s;1ZW4Kbx=GkPX5*@x-o4XD*fwTz{tH9w=4|J_Rd zuXS^E?fiMlE;Xf-WyULS?4S5d2~*46O68t=rJnOp3TCbE9Ec)c`QBvr@|ov)SXYZ!U&ydaO2b!O`Nwj4fM zv7eNZk!S5!V(*={X8SVi$W?zDHEw*F#noN$@RDC8XO8b03ZMOaa%N3sFg#Sp+-XwB z3@sPcap1DS$jJXP*Qj;l`v;SY``~45p3uABIziYqp`@a0dM)9fSoy7fh;x2t3^skA z6d`K*H5IF-s#sAk$FFdm)L)X0(+c<{kTtD*qedf}I$UJBZLn5R^2)DWWc=1)$tPu_ zBKika!{WnK#lfke$Y^mv&2y`yH_NM{mE&Jdd?4ZWm7*Q*iN^jRy2o3hKYT;^l(uQMGd;`bxLrJ3=hqpX7xo+LS>;_?fZ*rU_XE%uYr-$Ud(OTyz*WQpEr$tW8 z&?5TPgA@88qv&P#O^Vj2)&{Iy&aig-nsEP)WL-_)wbDi9iBW}W(#;ZPuZ(up2?^2; zdd%MC3TaYyl5G%qa^GF}bVb7EYh1clC5P^fKGlTdm%DwYk<8MwhW42}ajhFA!$r%J zGiowKXt9U-Axab#yH-=BHj?%k8}5ILTVLBfNrH^Kpz_WXaoWLx$;L^^@T7TlGso-t z=}FQyZG?4p>iwIm4RKPNDWTt+2lp>+#Avq(SOiQ5O0UF-3|Mk~sq{+K+!pPyz2s7! zEYgPgPrs++Lu zv8aSg83&xE1zEy9gIu`dOKx1+J*5?UA5Ah+pRBP(#t)FXJSCdiCj=}ZFZ(6z%kE3o zCWz4a=kl<2d9toHWuixg?_TYq>xpipQlp}^Q{&S_w{8?Z`*Lz-ZHBOGU#Yw6@VeR| zN@6b$m;K85)OL?e2M#ZI-pv>}e8}LQQCnmsc!`71*l^SfZlWX>YJ7(EX zUDBVe>{*iBX_W!(CB(esRGg02bTMEBN(etxP=5!U)fBfPem zCEIPR_+Bb)m?K&T+vQOkCSycv(;mtZJ2ovU@Gdni>-wb(L9lx5+Gw9Fet&W-?7Ar# zuWcu36B+$y*^f^E56ldw|H+O0`oS<=N<--h1NR()2Dt8x!V_G&FK0$brz@=d$`!vA z4fhR+4o0e1jekz>ueK{%@g?g^#bYt4cx!JmQQM7MZ7%n9@o0b&onk^Sh5P@(eaD$u zyoF&~61bgc9blz!@g2#!t;#l<5^Ia-+Nv(NrrF`yuez435O%Y9l%hmBZ4ph^3s;^V zKI_x5Uvslhim;mwrXKVq6RADaG=qBr-`}zEz!goqD8b1&7CRnooK2>!X0^d{KUT@;nu~X z18DcDQMeGapDl(8-+!qGsC-@GJ5Lvlog<8JuBx7S5#kyxrdJD0hzNxp)89y)}WpuNvpQGX_ z!tM|sx#e85i)cMB@snq5kFrTE;gP>jCdRGO^T6<}KMZ}1LaVWi>-cUd(Y7_`ZYd>t zeM?`W8Q1>R6*t&Grr$9q&5J5=ReI*w@T9*cC)f7jy`7V5nJtq8CfdKV*>4$fv~5kp zR+7tRTi5!DecPHwzMkQB3zw~2hSoF>MMnEdQorQUyn$5l0C5}08PJ@XuKD6Nw{PTj z&)TY!@(3Lpb!M`UFMD+0=ey46XRlr<-!3&fA1IDuUyB@VUNb<7>K3mFK9RQdXS41+ zb4HE(dO(zo+eu~T)-NTY^xtkz!5$;IGM38D^&&clYXlKkaja4>(# zcTIN?YO3xajO^}zR>J>M>QA-swb8C5cQEp-Oqb4`QImaeuwMrUV{P+LBwgfA*b?JO z%0o<`;UlzHQg?av?Ui5ds>6J-z%HB-AGO#|~ z`RO-Y=fiZ?N4*zaea4B4OPmY{o$_Qini8Fu*Crr!reH{>hNAtb8{bHn^T8Uo3O}kx zKN&=&?WPLD_U>LH8zOQ>O@d|jT8b!Tib(Amop9V0Y}7UF?&4Ix8m5=e3ta*H-rPDh zDU(Y)FU!6=kBOFjhsAf@q?VnIb;U_yec+79T61tzezzpa0ymy6$#d^jB_HFGyOPYQ zIfP`DP4JsKOZ>KXI2QKFklkf9c$+I8+XUX^djO15!#YWED ze~oQyclBbe_s<` zk4GnJuOpm_%Hc}#m2mv(hopdJ_=S%e| zevl2{bk^GV0TQ97&hc>CC&{mkDu>5^;?h14F8w4~DCABO=yTFS@Hu5nzV7Ma=UM>& z^z!p8K=kzVb1Z;7z5VGDzPn%W|MvgSb@z)_Pker(-~Vv)=Q{!Yzy1I7 zoq+!D+y9%n`<3NJ`2&BJo3^>9Mfdol=r+-}t7ZH}XIn4!`mg`FuQd863~uY{5wNm{ zgwLHQXM^QaeNTlvo7GGVuQx?4G3QBz( z*QAaoNyd#+#bHVdsNYWiy%aQimT-E@wPT*}?dM7S>9jzWie(o}m;L{kqx_c>-Mv-r z;BEYbBwh~?o;%>|9$4C*NY zvJ#}Yj%29IZQaAOh|RNXH}{e>eTiFS?jk?3yE|-=KEj)|g2NcR6u5qcg!Qh&>4djl zaGpH(cMp0Z2ko_@OKAFy*OexWjP5_Tn#A9qIJ%1#>Ls0fCLAI9)Tez<3A;y3QGDmW zC7%ZJ(|a~eFH6DniCf!PiHiM5hJbs(9mQ|ME5!6>Mc~s*Om^rn)LI(B$rFE)+oLEY9;HM+qM&j2{8n**Q7%2&x(Vn6z;#K z<+3v+=&|&pQc!o-Btmq3LE>JCZ#hu>y#8w%C?}lwbNk2YSH)1F0T>vYw~UjMeC7u-`xXsCkMSwC!A7LN`$|!*(7k z4~2B8dDFp+Ip(LH-%0rOw`IC0GKR}(@z;5VOq>I833s^)NAp95DZ95tnz}25)*>0EC|Ec1j&kSDmln`llq+A7y}vg{3v4F-gH;77>Ex}YC;w;m$m7tw-ae=LJjSMj$|<2)^=1?)Ub)_4a6cDEPrmxS&KOT_f> zV4{VitUeTLS}ZkCMpg@H-_TxA&Ls@+X2TS$_ zz4g;XlW%si48nE}hD9bwT|nY)BSsnN1Lu1D_AZc?PMjbW;OS@~Sg}x=;`Ga9B6Lr5 zA_r+|);CY=ditC4!`Ms2Tj8ROQCQXqbgDM}SfPFGxXLA(Xm1L%*M{e~C3j)t_H*MC zgY((V(CjJU+1tM( gxx0?LMZ!x*`3{;IR(6~_JNA8v`*&FTesb3T2WH#Zk^lez diff --git a/installer/updater/updater.cc b/installer/updater/updater.cc index a76be8b8fd..ca0b9270b8 100644 --- a/installer/updater/updater.cc +++ b/installer/updater/updater.cc @@ -10,6 +10,7 @@ #include #include #include +#include #include #include @@ -33,10 +34,10 @@ #define USER_AGENT "NEOSUpdater-0.2" -#define MANIFEST_URL_EON_STAGING "https://github.com/commaai/eon-neos/raw/master/update.staging.json" -#define MANIFEST_URL_EON_LOCAL "http://192.168.5.1:8000/neosupdate/update.local.json" -#define MANIFEST_URL_EON "https://github.com/commaai/eon-neos/raw/master/update.json" -const char *manifest_url = MANIFEST_URL_EON; +#define MANIFEST_URL_NEOS_STAGING "https://github.com/commaai/eon-neos/raw/master/update.staging.json" +#define MANIFEST_URL_NEOS_LOCAL "http://192.168.5.1:8000/neosupdate/update.local.json" +#define MANIFEST_URL_NEOS "https://github.com/commaai/eon-neos/raw/master/update.json" +const char *manifest_url = MANIFEST_URL_NEOS; #define RECOVERY_DEV "/dev/block/bootdevice/by-name/recovery" #define RECOVERY_COMMAND "/cache/recovery/command" @@ -96,7 +97,7 @@ std::string download_string(CURL *curl, std::string url) { curl_easy_setopt(curl, CURLOPT_URL, url.c_str()); curl_easy_setopt(curl, CURLOPT_FOLLOWLOCATION, 1); - curl_easy_setopt(curl, CURLOPT_NOSIGNAL, 1); + curl_easy_setopt(curl, CURLOPT_NOSIGNAL, 0); curl_easy_setopt(curl, CURLOPT_USERAGENT, USER_AGENT); curl_easy_setopt(curl, CURLOPT_FAILONERROR, 1); curl_easy_setopt(curl, CURLOPT_RESUME_FROM, 0); @@ -149,6 +150,32 @@ static void start_settings_activity(const char* name) { system(launch_cmd); } +bool is_settings_active() { + FILE *fp; + char sys_output[4096]; + + fp = popen("/bin/dumpsys window windows", "r"); + if (fp == NULL) { + return false; + } + + bool active = false; + while (fgets(sys_output, sizeof(sys_output), fp) != NULL) { + if (strstr(sys_output, "mCurrentFocus=null") != NULL) { + break; + } + + if (strstr(sys_output, "mCurrentFocus=Window") != NULL) { + active = true; + break; + } + } + + pclose(fp); + + return active; +} + struct Updater { bool do_exit = false; @@ -166,7 +193,6 @@ struct Updater { std::mutex lock; - // i hate state machines give me coroutines already enum UpdateState { CONFIRMATION, LOW_BATTERY, @@ -190,9 +216,15 @@ struct Updater { int b_x, b_w, b_y, b_h; int balt_x; + // download stage writes these for the installation stage + int recovery_len; + std::string recovery_hash; + std::string recovery_fn; + std::string ota_fn; + CURL *curl = NULL; - Updater() { + void ui_init() { touch_init(&touch); fb = framebuffer_init("updater", 0x00001000, false, @@ -218,7 +250,6 @@ struct Updater { b_h = 220; state = CONFIRMATION; - } int download_file_xferinfo(curl_off_t dltotal, curl_off_t dlno, @@ -251,7 +282,7 @@ struct Updater { curl_easy_setopt(curl, CURLOPT_URL, url.c_str()); curl_easy_setopt(curl, CURLOPT_FOLLOWLOCATION, 1); - curl_easy_setopt(curl, CURLOPT_NOSIGNAL, 1); + curl_easy_setopt(curl, CURLOPT_NOSIGNAL, 0); curl_easy_setopt(curl, CURLOPT_USERAGENT, USER_AGENT); curl_easy_setopt(curl, CURLOPT_FAILONERROR, 1); curl_easy_setopt(curl, CURLOPT_RESUME_FROM, resume_from); @@ -319,92 +350,78 @@ struct Updater { state = RUNNING; } - std::string stage_download(std::string url, std::string hash, std::string name) { + std::string download(std::string url, std::string hash, std::string name) { std::string out_fn = UPDATE_DIR "/" + util::base_name(url); - set_progress("Downloading " + name + "..."); - bool r = download_file(url, out_fn); - if (!r) { - set_error("failed to download " + name); - return ""; + // start or resume downloading if hash doesn't match + std::string fn_hash = sha256_file(out_fn); + if (hash.compare(fn_hash) != 0) { + set_progress("Downloading " + name + "..."); + bool r = download_file(url, out_fn); + if (!r) { + set_error("failed to download " + name); + unlink(out_fn.c_str()); + return ""; + } + fn_hash = sha256_file(out_fn); } set_progress("Verifying " + name + "..."); - std::string fn_hash = sha256_file(out_fn); printf("got %s hash: %s\n", name.c_str(), hash.c_str()); if (fn_hash != hash) { set_error(name + " was corrupt"); unlink(out_fn.c_str()); return ""; } - return out_fn; } - void run_stages() { + bool download_stage() { curl = curl_easy_init(); assert(curl); - if (!check_battery()) { - set_battery_low(); - int battery_cap = battery_capacity(); - while(battery_cap < min_battery_cap) { - battery_cap = battery_capacity(); - battery_cap_text = std::to_string(battery_cap); - usleep(1000000); - } - set_running(); - } + // ** quick checks before download ** if (!check_space()) { set_error("2GB of free space required to update"); - return; + return false; } mkdir(UPDATE_DIR, 0777); - const int EON = (access("/EON", F_OK) != -1); - set_progress("Finding latest version..."); - std::string manifest_s; - if (EON) { - manifest_s = download_string(curl, manifest_url); - } else { - // don't update NEO - exit(0); - } - + std::string manifest_s = download_string(curl, manifest_url); printf("manifest: %s\n", manifest_s.c_str()); std::string err; auto manifest = json11::Json::parse(manifest_s, err); if (manifest.is_null() || !err.empty()) { set_error("failed to load update manifest"); - return; + return false; } std::string ota_url = manifest["ota_url"].string_value(); std::string ota_hash = manifest["ota_hash"].string_value(); std::string recovery_url = manifest["recovery_url"].string_value(); - std::string recovery_hash = manifest["recovery_hash"].string_value(); - int recovery_len = manifest["recovery_len"].int_value(); + recovery_hash = manifest["recovery_hash"].string_value(); + recovery_len = manifest["recovery_len"].int_value(); // std::string installer_url = manifest["installer_url"].string_value(); // std::string installer_hash = manifest["installer_hash"].string_value(); if (ota_url.empty() || ota_hash.empty()) { set_error("invalid update manifest"); - return; + return false; } - // std::string installer_fn = stage_download(installer_url, installer_hash, "installer"); + // std::string installer_fn = download(installer_url, installer_hash, "installer"); // if (installer_fn.empty()) { // //error'd // return; // } - std::string recovery_fn; + // ** handle recovery download ** if (recovery_url.empty() || recovery_hash.empty() || recovery_len == 0) { set_progress("Skipping recovery flash..."); } else { @@ -414,20 +431,50 @@ struct Updater { printf("existing recovery hash: %s\n", existing_recovery_hash.c_str()); if (existing_recovery_hash != recovery_hash) { - recovery_fn = stage_download(recovery_url, recovery_hash, "recovery"); + recovery_fn = download(recovery_url, recovery_hash, "recovery"); if (recovery_fn.empty()) { // error'd - return; + return false; } } } - std::string ota_fn = stage_download(ota_url, ota_hash, "update"); + // ** handle ota download ** + ota_fn = download(ota_url, ota_hash, "update"); if (ota_fn.empty()) { //error'd + return false; + } + + // download sucessful + return true; + } + + // thread that handles downloading and installing the update + void run_stages() { + printf("run_stages start\n"); + + + // ** download update ** + + if (!check_battery()) { + set_battery_low(); + int battery_cap = battery_capacity(); + while(battery_cap < min_battery_cap) { + battery_cap = battery_capacity(); + battery_cap_text = std::to_string(battery_cap); + usleep(1000000); + } + set_running(); + } + + bool sucess = download_stage(); + if (!sucess) { return; } + // ** install update ** + if (!check_battery()) { set_battery_low(); int battery_cap = battery_capacity(); @@ -601,7 +648,7 @@ struct Updater { int powerprompt_y = 312; nvgFontFace(vg, "opensans_regular"); nvgFontSize(vg, 64.0f); - nvgText(vg, fb_w/2, 740, "Ensure EON is connected to power.", NULL); + nvgText(vg, fb_w/2, 740, "Ensure your device remains connected to a power source.", NULL); NVGpaint paint = nvgBoxGradient( vg, progress_x + 1, progress_y + 1, @@ -657,9 +704,7 @@ struct Updater { void ui_update() { std::lock_guard guard(lock); - switch (state) { - case ERROR: - case CONFIRMATION: { + if (state == ERROR || state == CONFIRMATION) { int touch_x = -1, touch_y = -1; int res = touch_poll(&touch, &touch_x, &touch_y, 0); if (res == 1 && !is_settings_active()) { @@ -678,13 +723,11 @@ struct Updater { } } } - default: - break; - } } - void go() { + ui_init(); + while (!do_exit) { ui_update(); @@ -718,51 +761,37 @@ struct Updater { update_thread_handle.join(); } + // reboot system("service call power 16 i32 0 i32 0 i32 1"); } - bool is_settings_active() { - FILE *fp; - char sys_output[4096]; - - fp = popen("/bin/dumpsys window windows", "r"); - if (fp == NULL) { - return false; - } - - bool active = false; - while (fgets(sys_output, sizeof(sys_output), fp) != NULL) { - if (strstr(sys_output, "mCurrentFocus=null") != NULL) { - break; - } - - if (strstr(sys_output, "mCurrentFocus=Window") != NULL) { - active = true; - break; - } - } - - pclose(fp); - - return active; - } - }; } + int main(int argc, char *argv[]) { + bool background_cache = false; if (argc > 1) { if (strcmp(argv[1], "local") == 0) { - manifest_url = MANIFEST_URL_EON_LOCAL; + manifest_url = MANIFEST_URL_NEOS_LOCAL; } else if (strcmp(argv[1], "staging") == 0) { - manifest_url = MANIFEST_URL_EON_STAGING; + manifest_url = MANIFEST_URL_NEOS_STAGING; + } else if (strcmp(argv[1], "bgcache") == 0) { + manifest_url = argv[2]; + background_cache = true; } else { manifest_url = argv[1]; } } + printf("updating from %s\n", manifest_url); Updater updater; - updater.go(); - return 0; + int err = 0; + if (background_cache) { + err = !updater.download_stage(); + } else { + updater.go(); + } + return err; } diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 1a1c41706f..af5483562d 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -1,23 +1,13 @@ #!/usr/bin/bash -export OMP_NUM_THREADS=1 -export MKL_NUM_THREADS=1 -export NUMEXPR_NUM_THREADS=1 -export OPENBLAS_NUM_THREADS=1 -export VECLIB_MAXIMUM_THREADS=1 - if [ -z "$BASEDIR" ]; then BASEDIR="/data/openpilot" fi -if [ -z "$PASSIVE" ]; then - export PASSIVE="1" -fi +source "$BASEDIR/launch_env.sh" DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" -STAGING_ROOT="/data/safe_staging" - function launch { # Wifi scan wpa_cli IFNAME=wlan0 SCAN @@ -54,6 +44,7 @@ function launch { git submodule foreach --recursive git reset --hard echo "Restarting launch script ${LAUNCHER_LOCATION}" + unset REQUIRED_NEOS_VERSION exec "${LAUNCHER_LOCATION}" else echo "openpilot backup found, not updating" @@ -81,24 +72,20 @@ function launch { [ -d "/proc/irq/736" ] && echo 3 > /proc/irq/736/smp_affinity_list # USB for OP3T - # Remove old NEOS update file - # TODO: move this code to the updater - if [ -d /data/neoupdate ]; then - rm -rf /data/neoupdate - fi - # Check for NEOS update - if [ $(< /VERSION) != "14" ]; then + if [ $(< /VERSION) != "$REQUIRED_NEOS_VERSION" ]; then if [ -f "$DIR/scripts/continue.sh" ]; then cp "$DIR/scripts/continue.sh" "/data/data/com.termux/files/continue.sh" fi if [ ! -f "$BASEDIR/prebuilt" ]; then - echo "Clearing build products and resetting scons state prior to NEOS update" - cd $BASEDIR && scons --clean - rm -rf /tmp/scons_cache - rm -r $BASEDIR/.sconsign.dblite + # Clean old build products, but preserve the scons cache + cd $DIR + scons --clean + git clean -xdf + git submodule foreach --recursive git clean -xdf fi + "$DIR/installer/updater/updater" "file://$DIR/installer/updater/update.json" else if [[ $(uname -v) == "#1 SMP PREEMPT Wed Jun 10 12:40:53 PDT 2020" ]]; then diff --git a/launch_env.sh b/launch_env.sh new file mode 100755 index 0000000000..9a86d315ce --- /dev/null +++ b/launch_env.sh @@ -0,0 +1,17 @@ +#!/usr/bin/bash + +export OMP_NUM_THREADS=1 +export MKL_NUM_THREADS=1 +export NUMEXPR_NUM_THREADS=1 +export OPENBLAS_NUM_THREADS=1 +export VECLIB_MAXIMUM_THREADS=1 + +if [ -z "$REQUIRED_NEOS_VERSION" ]; then + export REQUIRED_NEOS_VERSION="14" +fi + +if [ -z "$PASSIVE" ]; then + export PASSIVE="1" +fi + +export STAGING_ROOT="/data/safe_staging" diff --git a/selfdrive/controls/lib/alerts_offroad.json b/selfdrive/controls/lib/alerts_offroad.json index 7cf5d8229b..f343f4cd5e 100644 --- a/selfdrive/controls/lib/alerts_offroad.json +++ b/selfdrive/controls/lib/alerts_offroad.json @@ -32,5 +32,9 @@ "Offroad_IsTakingSnapshot": { "text": "Taking camera snapshots. System won't start until finished.", "severity": 0 + }, + "Offroad_NeosUpdate": { + "text": "An update to your device's operating system is downloading in the background. You will be prompted to update when it's ready to install.", + "severity": 0 } } diff --git a/selfdrive/test/test_updated.py b/selfdrive/test/test_updated.py index 08eca5bd23..8ecd27456d 100755 --- a/selfdrive/test/test_updated.py +++ b/selfdrive/test/test_updated.py @@ -13,7 +13,7 @@ from common.basedir import BASEDIR from common.params import Params -class TestUpdater(unittest.TestCase): +class TestUpdated(unittest.TestCase): def setUp(self): self.updated_proc = None @@ -27,6 +27,13 @@ class TestUpdater(unittest.TestCase): for d in [org_dir, self.basedir, self.git_remote_dir, self.staging_dir]: os.mkdir(d) + self.neos_version = os.path.join(org_dir, "neos_version") + self.neosupdate_dir = os.path.join(org_dir, "neosupdate") + with open(self.neos_version, "w") as f: + v = subprocess.check_output(r"bash -c 'source launch_env.sh && echo $REQUIRED_NEOS_VERSION'", + cwd=BASEDIR, shell=True, encoding='utf8').strip() + f.write(v) + self.upper_dir = os.path.join(self.staging_dir, "upper") self.merged_dir = os.path.join(self.staging_dir, "merged") self.finalized_dir = os.path.join(self.staging_dir, "finalized") @@ -43,7 +50,7 @@ class TestUpdater(unittest.TestCase): f"git clone {BASEDIR} {self.git_remote_dir}", f"git clone {self.git_remote_dir} {self.basedir}", f"cd {self.basedir} && git submodule init && git submodule update", - f"cd {self.basedir} && scons -j{os.cpu_count()} cereal" + f"cd {self.basedir} && scons -j{os.cpu_count()} cereal/ common/" ]) self.params = Params(db=os.path.join(self.basedir, "persist/params")) @@ -79,6 +86,8 @@ class TestUpdater(unittest.TestCase): os.environ["UPDATER_TEST_IP"] = "localhost" os.environ["UPDATER_LOCK_FILE"] = os.path.join(self.tmp_dir.name, "updater.lock") os.environ["UPDATER_STAGING_ROOT"] = self.staging_dir + os.environ["UPDATER_NEOS_VERSION"] = self.neos_version + os.environ["UPDATER_NEOSUPDATE_DIR"] = self.neosupdate_dir updated_path = os.path.join(self.basedir, "selfdrive/updated.py") return subprocess.Popen(updated_path, env=os.environ) @@ -252,5 +261,40 @@ class TestUpdater(unittest.TestCase): self.assertTrue(ret_code is not None) + # *** test cases with NEOS updates *** + + + # Run updated with no update, make sure it clears the old NEOS update + def test_clear_neos_cache(self): + # make the dir and some junk files + os.mkdir(self.neosupdate_dir) + for _ in range(15): + with tempfile.NamedTemporaryFile(dir=self.neosupdate_dir, delete=False) as f: + f.write(os.urandom(random.randrange(1, 1000000))) + + self._start_updater() + self._wait_for_update(clear_param=True) + self._check_update_state(False) + self.assertFalse(os.path.isdir(self.neosupdate_dir)) + + # Let the updater run with no update for a cycle, then write an update + @unittest.skip("TODO: only runs on device") + def test_update_with_neos_update(self): + # bump the NEOS version and commit it + self._run([ + "echo 'export REQUIRED_NEOS_VERSION=3' >> launch_env.sh", + "git -c user.name='testy' -c user.email='testy@tester.test' \ + commit -am 'a neos update'", + ], cwd=self.git_remote_dir) + + # run for a cycle to get the update + self._start_updater() + self._wait_for_update(timeout=60, clear_param=True) + self._check_update_state(True) + + # TODO: more comprehensive check + self.assertTrue(os.path.isdir(self.neosupdate_dir)) + + if __name__ == "__main__": unittest.main() diff --git a/selfdrive/updated.py b/selfdrive/updated.py index f63da54475..2059068067 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -29,6 +29,7 @@ import psutil import shutil import signal import fcntl +import time import threading from cffi import FFI from pathlib import Path @@ -36,17 +37,20 @@ from pathlib import Path from common.basedir import BASEDIR from common.params import Params from selfdrive.swaglog import cloudlog +from selfdrive.controls.lib.alertmanager import set_offroad_alert TEST_IP = os.getenv("UPDATER_TEST_IP", "8.8.8.8") LOCK_FILE = os.getenv("UPDATER_LOCK_FILE", "/tmp/safe_staging_overlay.lock") STAGING_ROOT = os.getenv("UPDATER_STAGING_ROOT", "/data/safe_staging") +NEOS_VERSION = os.getenv("UPDATER_NEOS_VERSION", "/VERSION") +NEOSUPDATE_DIR = os.getenv("UPDATER_NEOSUPDATE_DIR", "/data/neoupdate") + OVERLAY_UPPER = os.path.join(STAGING_ROOT, "upper") OVERLAY_METADATA = os.path.join(STAGING_ROOT, "metadata") OVERLAY_MERGED = os.path.join(STAGING_ROOT, "merged") FINALIZED = os.path.join(STAGING_ROOT, "finalized") -NICE_LOW_PRIORITY = ["nice", "-n", "19"] # Workaround for lack of os.link in the NEOS/termux python ffi = FFI() @@ -57,7 +61,8 @@ def link(src, dest): class WaitTimeHelper: - def __init__(self): + def __init__(self, proc): + self.proc = proc self.ready_event = threading.Event() self.shutdown = False signal.signal(signal.SIGTERM, self.graceful_shutdown) @@ -68,6 +73,12 @@ class WaitTimeHelper: # umount -f doesn't appear effective in avoiding "device busy" on NEOS, # so don't actually die until the next convenient opportunity in main(). cloudlog.info("caught SIGINT/SIGTERM, dismounting overlay at next opportunity") + + # forward the signal to all our child processes + child_procs = self.proc.children(recursive=True) + for p in child_procs: + p.send_signal(signum) + self.shutdown = True self.ready_event.set() @@ -79,7 +90,9 @@ class WaitTimeHelper: self.ready_event.wait(timeout=t) -def run(cmd, cwd=None): +def run(cmd, cwd=None, low_priority=False): + if low_priority: + cmd = ["nice", "-n", "19"] + cmd return subprocess.check_output(cmd, cwd=cwd, stderr=subprocess.STDOUT, encoding='utf8') @@ -93,7 +106,7 @@ def set_consistent_flag(consistent): os.system("sync") -def set_update_available_params(new_version=False): +def set_update_available_params(new_version): params = Params() t = datetime.datetime.utcnow().isoformat() @@ -132,7 +145,7 @@ def setup_git_options(cwd): for option, value in git_cfg: try: ret = run(["git", "config", "--get", option], cwd) - config_ok = (ret.strip() == value) + config_ok = ret.strip() == value except subprocess.CalledProcessError: config_ok = False @@ -168,6 +181,7 @@ def init_ovfs(): # and skips the update activation attempt. Path(os.path.join(BASEDIR, ".overlay_init")).touch() + os.system("sync") overlay_opts = f"lowerdir={BASEDIR},upperdir={OVERLAY_UPPER},workdir={OVERLAY_METADATA}" run(["mount", "-t", "overlay", "-o", overlay_opts, "none", OVERLAY_MERGED]) @@ -176,18 +190,23 @@ def finalize_from_ovfs(): """Take the current OverlayFS merged view and finalize a copy outside of OverlayFS, ready to be swapped-in at BASEDIR. Copy using shutil.copytree""" + # Remove the update ready flag and any old updates cloudlog.info("creating finalized version of the overlay") + set_consistent_flag(False) shutil.rmtree(FINALIZED) + + # Copy the merged overlay view and set the update ready flag shutil.copytree(OVERLAY_MERGED, FINALIZED, symlinks=True) + set_consistent_flag(True) cloudlog.info("done finalizing overlay") -def attempt_update(): +def attempt_update(wait_helper): cloudlog.info("attempting git update inside staging overlay") setup_git_options(OVERLAY_MERGED) - git_fetch_output = run(NICE_LOW_PRIORITY + ["git", "fetch"], OVERLAY_MERGED) + git_fetch_output = run(["git", "fetch"], OVERLAY_MERGED, low_priority=True) cloudlog.info("git fetch success: %s", git_fetch_output) cur_hash = run(["git", "rev-parse", "HEAD"], OVERLAY_MERGED).rstrip() @@ -200,46 +219,75 @@ def attempt_update(): cloudlog.info("comparing %s to %s" % (cur_hash, upstream_hash)) if new_version or git_fetch_result: cloudlog.info("Running update") + if new_version: cloudlog.info("git reset in progress") r = [ - run(NICE_LOW_PRIORITY + ["git", "reset", "--hard", "@{u}"], OVERLAY_MERGED), - run(NICE_LOW_PRIORITY + ["git", "clean", "-xdf"], OVERLAY_MERGED), - run(NICE_LOW_PRIORITY + ["git", "submodule", "init"], OVERLAY_MERGED), - run(NICE_LOW_PRIORITY + ["git", "submodule", "update"], OVERLAY_MERGED), + run(["git", "reset", "--hard", "@{u}"], OVERLAY_MERGED, low_priority=True), + run(["git", "clean", "-xdf"], OVERLAY_MERGED, low_priority=True ), + run(["git", "submodule", "init"], OVERLAY_MERGED, low_priority=True), + run(["git", "submodule", "update"], OVERLAY_MERGED, low_priority=True), ] cloudlog.info("git reset success: %s", '\n'.join(r)) - # Un-set the validity flag to prevent the finalized tree from being - # activated later if the finalize step is interrupted - set_consistent_flag(False) - + # Download the accompanying NEOS version if it doesn't match the current version + with open(NEOS_VERSION, "r") as f: + cur_neos = f.read().strip() + + updated_neos = run(["bash", "-c", r"unset REQUIRED_NEOS_VERSION && source launch_env.sh && \ + echo -n $REQUIRED_NEOS_VERSION"], OVERLAY_MERGED).strip() + + cloudlog.info(f"NEOS version check: {cur_neos} vs {updated_neos}") + if cur_neos != updated_neos: + cloudlog.info(f"Beginning background download for NEOS {updated_neos}") + + set_offroad_alert("Offroad_NeosUpdate", True) + updater_path = os.path.join(OVERLAY_MERGED, "installer/updater/updater") + update_manifest = f"file://{OVERLAY_MERGED}/installer/updater/update.json" + + neos_downloaded = False + start_time = time.monotonic() + # Try to download for one day + while (time.monotonic() - start_time < 60*60*24) and not wait_helper.shutdown: + wait_helper.ready_event.clear() + try: + run([updater_path, "bgcache", update_manifest], OVERLAY_MERGED, low_priority=True) + neos_downloaded = True + break + except subprocess.CalledProcessError: + cloudlog.info("NEOS background download failed, retrying") + wait_helper.sleep(120) + + # If the download failed, we'll show the alert again when we retry + set_offroad_alert("Offroad_NeosUpdate", False) + if not neos_downloaded: + raise Exception("Failed to download NEOS update") + + cloudlog.info(f"NEOS background download successful, took {time.monotonic() - start_time} seconds") + + # Create the finalized, ready-to-swap update finalize_from_ovfs() - - # Make sure the validity flag lands on disk LAST, only when the local git - # repo and OP install are in a consistent state. - set_consistent_flag(True) - - cloudlog.info("update successful!") + cloudlog.info("openpilot update successful!") else: cloudlog.info("nothing new from git at this time") - set_update_available_params(new_version=new_version) + set_update_available_params(new_version) + return new_version def main(): params = Params() if params.get("DisableUpdates") == b"1": - raise RuntimeError("updates are disabled by param") + raise RuntimeError("updates are disabled by the DisableUpdates param") if os.geteuid() != 0: raise RuntimeError("updated must be launched as root!") # Set low io priority - p = psutil.Process() + proc = psutil.Process() if psutil.LINUX: - p.ionice(psutil.IOPRIO_CLASS_BE, value=7) + proc.ionice(psutil.IOPRIO_CLASS_BE, value=7) ov_lock_fd = open(LOCK_FILE, 'w') try: @@ -248,10 +296,11 @@ def main(): raise RuntimeError("couldn't get overlay lock; is another updated running?") # Wait for IsOffroad to be set before our first update attempt - wait_helper = WaitTimeHelper() + wait_helper = WaitTimeHelper(proc) wait_helper.sleep(30) update_failed_count = 0 + update_available = False overlay_initialized = False while not wait_helper.shutdown: wait_helper.ready_event.clear() @@ -282,8 +331,10 @@ def main(): overlay_initialized = True if params.get("IsOffroad") == b"1": - attempt_update() + update_available = attempt_update(wait_helper) or update_available update_failed_count = 0 + if not update_available and os.path.isdir(NEOSUPDATE_DIR): + shutil.rmtree(NEOSUPDATE_DIR) else: cloudlog.info("not running updater, openpilot running") @@ -308,7 +359,6 @@ def main(): # Wait 10 minutes between update attempts wait_helper.sleep(60*10) - # We've been signaled to shut down dismount_ovfs() if __name__ == "__main__": From 5993055d6663c9e704d438f64559c04dc8568f07 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Aug 2020 12:09:12 -0700 Subject: [PATCH 615/656] add background download to release notes --- RELEASES.md | 1 + 1 file changed, 1 insertion(+) diff --git a/RELEASES.md b/RELEASES.md index 089e9dd69a..209d3ae2c0 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,6 +1,7 @@ Version 0.7.8 (2020-08-XX) ======================== * New driver monitoring model: improved face detection and better compatibility with sunglasses + * Download NEOS operating system updates in the background * Improved updater reliability and responsiveness * Hyundai Kona 2020, Veloster 2019, and Genesis G70 2018 support thanks to xps-genesis! From 100f2958fc08f58e6b175336b91c66850107051a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Aug 2020 12:47:32 -0700 Subject: [PATCH 616/656] add missing agent for jenkins job --- Jenkinsfile | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Jenkinsfile b/Jenkinsfile index bae3469b54..dd0e2c12fa 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -38,6 +38,12 @@ pipeline { stages { stage('Release Build') { + agent { + docker { + image 'python:3.7.3' + args '--user=root' + } + } when { branch 'devel-staging' } From 0394b8b921b55e44681f44251ad72b3a60f4c1b6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Aug 2020 13:50:51 -0700 Subject: [PATCH 617/656] fix get_git_remote not returning a value --- selfdrive/version.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/version.py b/selfdrive/version.py index 9ce31ddbe8..4fec0b4cc7 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -34,7 +34,7 @@ def get_git_remote(default=None): tracking_remote = run_cmd(["git", "config", "branch." + local_branch + ".remote"]) return run_cmd(["git", "config", "remote." + tracking_remote + ".url"]) except subprocess.CalledProcessError: # Not on a branch, fallback - run_cmd_default(["git", "config", "--get", "remote.origin.url"], default=default) + return run_cmd_default(["git", "config", "--get", "remote.origin.url"], default=default) with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")) as _versionf: From cf5ed9e962e005b065e5a902cba90e47408fda25 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Aug 2020 14:13:47 -0700 Subject: [PATCH 618/656] add date to release notes --- RELEASES.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 209d3ae2c0..0c6dd3d4fb 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,4 +1,4 @@ -Version 0.7.8 (2020-08-XX) +Version 0.7.8 (2020-08-19) ======================== * New driver monitoring model: improved face detection and better compatibility with sunglasses * Download NEOS operating system updates in the background From 9bc0b350fd273bbb2deb3dcaef0312944e4f6cfd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Aug 2020 17:34:15 -0700 Subject: [PATCH 619/656] add launch_env.sh to release files --- release/files_common | 1 + 1 file changed, 1 insertion(+) diff --git a/release/files_common b/release/files_common index 012ebd59b7..2b88a9d8c8 100644 --- a/release/files_common +++ b/release/files_common @@ -1,6 +1,7 @@ .gitignore LICENSE launch.sh +launch_env.sh launch_chffrplus.sh launch_openpilot.sh From 502cc665e0bad89eba0b1c344c2f4f580b153ae1 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 13 Aug 2020 10:10:50 +0200 Subject: [PATCH 620/656] Pigeon abstraction layer (#1977) * pigeon abstraction layer * Fix string literals * more generic pigeon class * add TTYpigon * nicer tty error handling * close tty fd on pigeon delete * pigeon receive return std::string * use sizeof * max receive size to prevent infinite loop * remove namespace * add unistd include for usleep * fix is pigeon * Handle tty error in opening * fix printing binary strings with dump.py * fix pigeon build on macos * Handle errors seperately Co-authored-by: Comma Device --- release/files_common | 4 + selfdrive/boardd/SConscript | 2 +- selfdrive/boardd/boardd.cc | 113 ++++-------------- selfdrive/boardd/panda.cc | 29 ++++- selfdrive/boardd/panda.h | 3 + selfdrive/boardd/pigeon.cc | 226 ++++++++++++++++++++++++++++++++++++ selfdrive/boardd/pigeon.h | 43 +++++++ selfdrive/common/SConscript | 3 +- selfdrive/common/gpio.cc | 75 ++++++++++++ selfdrive/common/gpio.h | 35 ++++++ selfdrive/debug/dump.py | 9 +- 11 files changed, 443 insertions(+), 99 deletions(-) create mode 100644 selfdrive/boardd/pigeon.cc create mode 100644 selfdrive/boardd/pigeon.h create mode 100644 selfdrive/common/gpio.cc create mode 100644 selfdrive/common/gpio.h diff --git a/release/files_common b/release/files_common index 2b88a9d8c8..b84e93fbb5 100644 --- a/release/files_common +++ b/release/files_common @@ -91,6 +91,8 @@ selfdrive/boardd/boardd_setup.py selfdrive/boardd/can_list_to_can_capnp.cc selfdrive/boardd/panda.cc selfdrive/boardd/panda.h +selfdrive/boardd/pigeon.cc +selfdrive/boardd/pigeon.h selfdrive/car/__init__.py selfdrive/car/car_helpers.py @@ -211,6 +213,8 @@ selfdrive/common/visionimg.cc selfdrive/common/visionimg.h selfdrive/common/spinner.c selfdrive/common/spinner.h +selfdrive/common/gpio.cc +selfdrive/common/gpio.h selfdrive/controls/__init__.py diff --git a/selfdrive/boardd/SConscript b/selfdrive/boardd/SConscript index 0ccbe6bd24..94e630a641 100644 --- a/selfdrive/boardd/SConscript +++ b/selfdrive/boardd/SConscript @@ -1,6 +1,6 @@ Import('env', 'common', 'cereal', 'messaging', 'cython_dependencies') -env.Program('boardd', ['boardd.cc', 'panda.cc'], LIBS=['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj']) +env.Program('boardd', ['boardd.cc', 'panda.cc', 'pigeon.cc'], LIBS=['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj']) env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) env.Command(['boardd_api_impl.so', 'boardd_api_impl.cpp'], diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index a3bb2b0b4c..e1b275dd3e 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -28,6 +28,7 @@ #include "messaging.hpp" #include "panda.h" +#include "pigeon.h" #define MAX_IR_POWER 0.5f @@ -43,8 +44,6 @@ const float VBATT_START_CHARGING = 11.5; const float VBATT_PAUSE_CHARGING = 11.0; #endif -namespace { - Panda * panda = NULL; std::atomic safety_setter_thread_running(false); volatile sig_atomic_t do_exit = 0; @@ -468,82 +467,13 @@ void hardware_control_thread() { } } -#define pigeon_send(x) _pigeon_send(x, sizeof(x)-1) -void _pigeon_send(const char *dat, int len) { - unsigned char a[0x20+1]; - a[0] = 1; - for (int i=0; iusb_bulk_write(2, a, ll+1); - } -} - -void pigeon_set_power(int power) { - panda->usb_write(0xd9, power, 0); -} - -void pigeon_set_baud(int baud) { - panda->usb_write(0xe2, 1, 0); - panda->usb_write(0xe4, 1, baud/300); -} - -void pigeon_init() { - usleep(1000*1000); - LOGW("panda GPS start"); - - // power off pigeon - pigeon_set_power(0); - usleep(100*1000); - - // 9600 baud at init - pigeon_set_baud(9600); - - // power on pigeon - pigeon_set_power(1); - usleep(500*1000); - - // baud rate upping - pigeon_send("\x24\x50\x55\x42\x58\x2C\x34\x31\x2C\x31\x2C\x30\x30\x30\x37\x2C\x30\x30\x30\x33\x2C\x34\x36\x30\x38\x30\x30\x2C\x30\x2A\x31\x35\x0D\x0A"); - usleep(100*1000); - - // set baud rate to 460800 - pigeon_set_baud(460800); - usleep(100*1000); - - // init from ubloxd - // To generate this data, run test/ubloxd.py with the print statements enabled in the write function in panda/python/serial.py - pigeon_send("\xB5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F"); - pigeon_send("\xB5\x62\x06\x3E\x00\x00\x44\xD2"); - pigeon_send("\xB5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35"); - pigeon_send("\xB5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80"); - pigeon_send("\xB5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85"); - pigeon_send("\xB5\x62\x06\x00\x00\x00\x06\x18"); - pigeon_send("\xB5\x62\x06\x00\x01\x00\x01\x08\x22"); - pigeon_send("\xB5\x62\x06\x00\x01\x00\x02\x09\x23"); - pigeon_send("\xB5\x62\x06\x00\x01\x00\x03\x0A\x24"); - pigeon_send("\xB5\x62\x06\x08\x06\x00\x64\x00\x01\x00\x00\x00\x79\x10"); - pigeon_send("\xB5\x62\x06\x24\x24\x00\x05\x00\x04\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x5A\x63"); - pigeon_send("\xB5\x62\x06\x1E\x14\x00\x00\x00\x00\x00\x01\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x3C\x37"); - pigeon_send("\xB5\x62\x06\x24\x00\x00\x2A\x84"); - pigeon_send("\xB5\x62\x06\x23\x00\x00\x29\x81"); - pigeon_send("\xB5\x62\x06\x1E\x00\x00\x24\x72"); - pigeon_send("\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51"); - pigeon_send("\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70"); - pigeon_send("\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C"); - pigeon_send("\xB5\x62\x06\x01\x03\x00\x0A\x09\x01\x1E\x70"); - - LOGW("panda GPS on"); -} - -static void pigeon_publish_raw(PubMaster &pm, unsigned char *dat, int alen) { +static void pigeon_publish_raw(PubMaster &pm, std::string dat) { // create message capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); event.setLogMonoTime(nanos_since_boot()); - auto ublox_raw = event.initUbloxRaw(alen); - memcpy(ublox_raw.begin(), dat, alen); + auto ublox_raw = event.initUbloxRaw(dat.length()); + memcpy(ublox_raw.begin(), dat.data(), dat.length()); pm.send("ubloxRaw", msg); } @@ -555,38 +485,33 @@ void pigeon_thread() { // ubloxRaw = 8042 PubMaster pm({"ubloxRaw"}); - // run at ~100hz - unsigned char dat[0x1000]; - uint64_t cnt = 0; +#ifdef QCOM2 + Pigeon * pigeon = Pigeon::connect("/dev/ttyHS0"); +#else + Pigeon * pigeon = Pigeon::connect(panda); +#endif - pigeon_init(); + pigeon->init(); while (!do_exit && panda->connected) { - int alen = 0; - while (alen < 0xfc0) { - int len = panda->usb_read(0xe0, 1, 0, dat+alen, 0x40); - if (len <= 0) break; - - //printf("got %d\n", len); - alen += len; - } - if (alen > 0) { - if (dat[0] == (char)0x00){ + std::string recv = pigeon->receive(); + if (recv.length() > 0) { + if (recv[0] == (char)0x00){ LOGW("received invalid ublox message, resetting panda GPS"); - pigeon_init(); + pigeon->init(); } else { - pigeon_publish_raw(pm, dat, alen); + pigeon_publish_raw(pm, recv); } } - // 10ms + // 10ms - 100 Hz usleep(10*1000); - cnt++; } -} + delete pigeon; } + int main() { int err; LOGW("starting boardd"); @@ -606,6 +531,8 @@ int main() { fake_send = true; } + panda_set_power(true); + while (!do_exit){ std::vector threads; threads.push_back(std::thread(can_health_thread)); diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 5820fa4004..52cf1e0b71 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -2,10 +2,33 @@ #include #include +#include + #include "common/swaglog.h" +#include "common/gpio.h" #include "panda.h" +void panda_set_power(bool power){ +#ifdef QCOM2 + int err = 0; + err += gpio_init(GPIO_STM_RST_N, true); + err += gpio_init(GPIO_STM_BOOT0, true); + err += gpio_init(GPIO_HUB_RST_N, true); + + err += gpio_set(GPIO_STM_RST_N, false); + + // TODO: set hub somewhere else + err += gpio_set(GPIO_HUB_RST_N, true); + err += gpio_set(GPIO_STM_BOOT0, false); + + usleep(100*1000); // 100 ms + + err += gpio_set(GPIO_STM_RST_N, power); + assert(err == 0); +#endif +} + Panda::Panda(){ int err; @@ -39,8 +62,10 @@ Panda::Panda(){ is_pigeon = (hw_type == cereal::HealthData::HwType::GREY_PANDA) || (hw_type == cereal::HealthData::HwType::BLACK_PANDA) || - (hw_type == cereal::HealthData::HwType::UNO); - has_rtc = (hw_type == cereal::HealthData::HwType::UNO); + (hw_type == cereal::HealthData::HwType::UNO) || + (hw_type == cereal::HealthData::HwType::DOS); + has_rtc = (hw_type == cereal::HealthData::HwType::UNO) || + (hw_type == cereal::HealthData::HwType::DOS); return; diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h index 3586cda74f..c3e2dc981e 100644 --- a/selfdrive/boardd/panda.h +++ b/selfdrive/boardd/panda.h @@ -34,6 +34,9 @@ struct __attribute__((packed)) health_t { uint8_t power_save_enabled; }; + +void panda_set_power(bool power); + class Panda { private: libusb_context *ctx = NULL; diff --git a/selfdrive/boardd/pigeon.cc b/selfdrive/boardd/pigeon.cc new file mode 100644 index 0000000000..4ec7ebf8ce --- /dev/null +++ b/selfdrive/boardd/pigeon.cc @@ -0,0 +1,226 @@ +#include +#include +#include +#include +#include + +#include "common/swaglog.h" +#include "common/gpio.h" + +#include "pigeon.h" + +// Termios on macos doesn't define all baud rate constants +#ifndef B460800 +#define B460800 0010004 +#endif + +using namespace std::string_literals; + + +Pigeon * Pigeon::connect(Panda * p){ + PandaPigeon * pigeon = new PandaPigeon(); + pigeon->connect(p); + + return pigeon; +} + +Pigeon * Pigeon::connect(const char * tty){ + TTYPigeon * pigeon = new TTYPigeon(); + pigeon->connect(tty); + + return pigeon; +} + +void Pigeon::init() { + usleep(1000*1000); + LOGW("panda GPS start"); + + // power off pigeon + set_power(0); + usleep(100*1000); + + // 9600 baud at init + set_baud(9600); + + // power on pigeon + set_power(1); + usleep(500*1000); + + // baud rate upping + send("\x24\x50\x55\x42\x58\x2C\x34\x31\x2C\x31\x2C\x30\x30\x30\x37\x2C\x30\x30\x30\x33\x2C\x34\x36\x30\x38\x30\x30\x2C\x30\x2A\x31\x35\x0D\x0A"s); + usleep(100*1000); + + // set baud rate to 460800 + set_baud(460800); + usleep(100*1000); + + // init from ubloxd + // To generate this data, run test/ubloxd.py with the print statements enabled in the write function in panda/python/serial.py + send("\xB5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F"s); + send("\xB5\x62\x06\x3E\x00\x00\x44\xD2"s); + send("\xB5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35"s); + send("\xB5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80"s); + send("\xB5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85"s); + send("\xB5\x62\x06\x00\x00\x00\x06\x18"s); + send("\xB5\x62\x06\x00\x01\x00\x01\x08\x22"s); + send("\xB5\x62\x06\x00\x01\x00\x02\x09\x23"s); + send("\xB5\x62\x06\x00\x01\x00\x03\x0A\x24"s); + send("\xB5\x62\x06\x08\x06\x00\x64\x00\x01\x00\x00\x00\x79\x10"s); + send("\xB5\x62\x06\x24\x24\x00\x05\x00\x04\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x5A\x63"s); + send("\xB5\x62\x06\x1E\x14\x00\x00\x00\x00\x00\x01\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x3C\x37"s); + send("\xB5\x62\x06\x24\x00\x00\x2A\x84"s); + send("\xB5\x62\x06\x23\x00\x00\x29\x81"s); + send("\xB5\x62\x06\x1E\x00\x00\x24\x72"s); + send("\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51"s); + send("\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70"s); + send("\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C"s); + send("\xB5\x62\x06\x01\x03\x00\x0A\x09\x01\x1E\x70"s); + + LOGW("panda GPS on"); +} + +void PandaPigeon::connect(Panda * p) { + panda = p; +} + +void PandaPigeon::set_baud(int baud) { + panda->usb_write(0xe2, 1, 0); + panda->usb_write(0xe4, 1, baud/300); +} + +void PandaPigeon::send(std::string s) { + int len = s.length(); + const char * dat = s.data(); + + unsigned char a[0x20+1]; + a[0] = 1; + for (int i=0; iusb_bulk_write(2, a, ll+1); + } +} + +std::string PandaPigeon::receive() { + std::string r; + + while (true){ + unsigned char dat[0x40]; + int len = panda->usb_read(0xe0, 1, 0, dat, sizeof(dat)); + if (len <= 0 || r.length() > 0x1000) break; + r.append((char*)dat, len); + } + + return r; +} + +void PandaPigeon::set_power(bool power) { + panda->usb_write(0xd9, power, 0); +} + +PandaPigeon::~PandaPigeon(){ +} + +void handle_tty_issue(int err, const char func[]) { + LOGE_100("tty error %d \"%s\" in %s", err, strerror(err), func); +} + +void TTYPigeon::connect(const char * tty) { + pigeon_tty_fd = open(tty, O_RDWR); + if (pigeon_tty_fd < 0){ + handle_tty_issue(errno, __func__); + assert(pigeon_tty_fd >= 0); + } + assert(tcgetattr(pigeon_tty_fd, &pigeon_tty) == 0); + + // configure tty + pigeon_tty.c_cflag &= ~PARENB; // disable parity + pigeon_tty.c_cflag &= ~CSTOPB; // single stop bit + pigeon_tty.c_cflag |= CS8; // 8 bits per byte + pigeon_tty.c_cflag &= ~CRTSCTS; // no RTS/CTS flow control + pigeon_tty.c_cflag |= CREAD | CLOCAL; // turn on READ & ignore ctrl lines + pigeon_tty.c_lflag &= ~ICANON; // disable canonical mode + pigeon_tty.c_lflag &= ~ISIG; // disable interpretation of INTR, QUIT and SUSP + pigeon_tty.c_iflag &= ~(IXON | IXOFF | IXANY); // turn off software flow ctrl + pigeon_tty.c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL); // disable any special handling of received bytes + pigeon_tty.c_oflag &= ~OPOST; // prevent special interpretation of output bytes + pigeon_tty.c_oflag &= ~ONLCR; // prevent conversion of newline to carriage return/line feed + + // configure blocking behavior + pigeon_tty.c_cc[VMIN] = 0; // min amount of characters returned + pigeon_tty.c_cc[VTIME] = 0; // max blocking time in s/10 (0=inf) + + assert(tcsetattr(pigeon_tty_fd, TCSANOW, &pigeon_tty) == 0); +} + +void TTYPigeon::set_baud(int baud){ + speed_t baud_const = 0; + switch(baud){ + case 9600: + baud_const = B9600; + break; + case 460800: + baud_const = B460800; + break; + default: + assert(false); + } + + // make sure everything is tx'ed before changing baud + assert(tcdrain(pigeon_tty_fd) == 0); + + // change baud + assert(tcgetattr(pigeon_tty_fd, &pigeon_tty) == 0); + assert(cfsetspeed(&pigeon_tty, baud_const) == 0); + assert(tcsetattr(pigeon_tty_fd, TCSANOW, &pigeon_tty) == 0); + + // flush + assert(tcflush(pigeon_tty_fd, TCIOFLUSH) == 0); +} + +void TTYPigeon::send(std::string s) { + int len = s.length(); + const char * dat = s.data(); + + int err = write(pigeon_tty_fd, dat, len); + if(err < 0) { handle_tty_issue(err, __func__); } + err = tcdrain(pigeon_tty_fd); + if(err < 0) { handle_tty_issue(err, __func__); } +} + +std::string TTYPigeon::receive() { + std::string r; + + while (true){ + char dat[0x40]; + int len = read(pigeon_tty_fd, dat, sizeof(dat)); + if(len < 0) { + handle_tty_issue(len, __func__); + } else if (len == 0 || r.length() > 0x1000){ + break; + } else { + r.append(dat, len); + } + + } + return r; +} + +void TTYPigeon::set_power(bool power){ +#ifdef QCOM2 + int err = 0; + err += gpio_init(GPIO_UBLOX_RST_N, true); + err += gpio_init(GPIO_UBLOX_SAFEBOOT_N, true); + err += gpio_init(GPIO_UBLOX_PWR_EN, true); + + err += gpio_set(GPIO_UBLOX_RST_N, power); + err += gpio_set(GPIO_UBLOX_SAFEBOOT_N, power); + err += gpio_set(GPIO_UBLOX_PWR_EN, power); + assert(err == 0); +#endif +} + +TTYPigeon::~TTYPigeon(){ + close(pigeon_tty_fd); +} diff --git a/selfdrive/boardd/pigeon.h b/selfdrive/boardd/pigeon.h new file mode 100644 index 0000000000..667ac70610 --- /dev/null +++ b/selfdrive/boardd/pigeon.h @@ -0,0 +1,43 @@ +#pragma once +#include +#include + + +#include "panda.h" + +class Pigeon { + public: + static Pigeon* connect(Panda * p); + static Pigeon* connect(const char * tty); + virtual ~Pigeon(){}; + + void init(); + virtual void set_baud(int baud) = 0; + virtual void send(std::string s) = 0; + virtual std::string receive() = 0; + virtual void set_power(bool power) = 0; +}; + +class PandaPigeon : public Pigeon { + Panda * panda = NULL; +public: + ~PandaPigeon(); + void connect(Panda * p); + void set_baud(int baud); + void send(std::string s); + std::string receive(); + void set_power(bool power); +}; + + +class TTYPigeon : public Pigeon { + int pigeon_tty_fd = -1; + struct termios pigeon_tty; +public: + ~TTYPigeon(); + void connect(const char* tty); + void set_baud(int baud); + void send(std::string s); + std::string receive(); + void set_power(bool power); +}; diff --git a/selfdrive/common/SConscript b/selfdrive/common/SConscript index 8ecf786ffe..0ba5b1abcc 100644 --- a/selfdrive/common/SConscript +++ b/selfdrive/common/SConscript @@ -5,7 +5,7 @@ if SHARED: else: fxn = env.Library -_common = fxn('common', ['params.cc', 'swaglog.cc', 'util.c', 'cqueue.c'], LIBS="json11") +_common = fxn('common', ['params.cc', 'swaglog.cc', 'util.c', 'cqueue.c', 'gpio.cc'], LIBS="json11") _visionipc = fxn('visionipc', ['visionipc.c', 'ipc.c']) files = [ @@ -42,4 +42,3 @@ else: _gpucommon = fxn('gpucommon', files, CPPDEFINES=defines, LIBS=_gpu_libs) Export('_common', '_visionipc', '_gpucommon', '_gpu_libs') - diff --git a/selfdrive/common/gpio.cc b/selfdrive/common/gpio.cc new file mode 100644 index 0000000000..7b080b0c50 --- /dev/null +++ b/selfdrive/common/gpio.cc @@ -0,0 +1,75 @@ +#include "gpio.h" +#include +#include +#include + +// We assume that all pins have already been exported on boot, +// and that we have permission to write to them. + +int gpio_init(int pin_nr, bool output){ + int ret = 0; + int fd, tmp; + + char pin_dir_path[50]; + int pin_dir_path_len = snprintf(pin_dir_path, sizeof(pin_dir_path), + "/sys/class/gpio/gpio%d/direction", pin_nr); + if(pin_dir_path_len <= 0){ + ret = -1; + goto cleanup; + } + + fd = open(pin_dir_path, O_WRONLY); + if(fd == -1){ + ret = -1; + goto cleanup; + } + if(output){ + tmp = write(fd, "out", 3); + if(tmp != 3){ + ret = -1; + goto cleanup; + } + } else { + tmp = write(fd, "in", 2); + if(tmp != 2){ + ret = -1; + goto cleanup; + } + } + +cleanup: + if(fd >= 0){ + close(fd); + } + return ret; +} + +int gpio_set(int pin_nr, bool high){ + int ret = 0; + int fd, tmp; + + char pin_val_path[50]; + int pin_val_path_len = snprintf(pin_val_path, sizeof(pin_val_path), + "/sys/class/gpio/gpio%d/value", pin_nr); + if(pin_val_path_len <= 0){ + ret = -1; + goto cleanup; + } + + fd = open(pin_val_path, O_WRONLY); + if(fd == -1){ + ret = -1; + goto cleanup; + } + tmp = write(fd, high ? "1" : "0", 1); + if(tmp != 1){ + ret = -1; + goto cleanup; + } + +cleanup: + if(fd >= 0){ + close(fd); + } + return ret; +} diff --git a/selfdrive/common/gpio.h b/selfdrive/common/gpio.h new file mode 100644 index 0000000000..479b4f7e06 --- /dev/null +++ b/selfdrive/common/gpio.h @@ -0,0 +1,35 @@ +#ifndef GPIO_H +#define GPIO_H + +#include + +// Pin definitions +#ifdef QCOM2 + #define GPIO_HUB_RST_N 30 + #define GPIO_UBLOX_RST_N 32 + #define GPIO_UBLOX_SAFEBOOT_N 33 + #define GPIO_UBLOX_PWR_EN 34 + #define GPIO_STM_RST_N 124 + #define GPIO_STM_BOOT0 134 +#else + #define GPIO_HUB_RST_N 0 + #define GPIO_UBLOX_RST_N 0 + #define GPIO_UBLOX_SAFEBOOT_N 0 + #define GPIO_UBLOX_PWR_EN 0 + #define GPIO_STM_RST_N 0 + #define GPIO_STM_BOOT0 0 +#endif + + +#ifdef __cplusplus +extern "C" { +#endif + +int gpio_init(int pin_nr, bool output); +int gpio_set(int pin_nr, bool high); + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index cfdb387b91..112ca96a93 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -61,4 +61,11 @@ if __name__ == "__main__": print("{} = {}".format(".".join(value), item)) print("") else: - print(evt) + try: + print(evt) + except UnicodeDecodeError: + w = evt.which() + s = f"( logMonoTime {evt.logMonoTime} \n {w} = " + s += str(evt.__getattr__(w)) + s += f"\n valid = {evt.valid} )" + print(s) From 09e7d17acf91944dec364e4e0c2d8569cb042045 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 13 Aug 2020 15:02:17 -0700 Subject: [PATCH 621/656] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index ed0621137e..ecef0a19d0 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit ed0621137e65a08b8dcef120fa018a14e4c71a34 +Subproject commit ecef0a19d0f72d8fd3151593b7bd1a112d5f63e2 From 5641aeee7ae896e2ee4e24f68e24d47e497031ea Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 13 Aug 2020 15:10:00 -0700 Subject: [PATCH 622/656] increase CPU test timeout to allow for installing new APKs --- selfdrive/test/test_cpu_usage.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/selfdrive/test/test_cpu_usage.py b/selfdrive/test/test_cpu_usage.py index 2f260ec8a3..16f205e824 100755 --- a/selfdrive/test/test_cpu_usage.py +++ b/selfdrive/test/test_cpu_usage.py @@ -71,12 +71,15 @@ def test_cpu_usage(): try: proc_sock = messaging.sub_sock('procLog', conflate=True, timeout=2000) - # wait until everything's started and get first sample + # wait until everything's started start_time = time.monotonic() - while time.monotonic() - start_time < 120: + while time.monotonic() - start_time < 210: if Params().get("CarParams") is not None: break time.sleep(2) + + # take first sample + time.sleep(5) first_proc = messaging.recv_sock(proc_sock, wait=True) if first_proc is None: raise Exception("\n\nTEST FAILED: progLog recv timed out\n\n") From 4a9228fcc776d898287ebc015cab0a11fd3cdc64 Mon Sep 17 00:00:00 2001 From: Michael Honan Date: Sat, 15 Aug 2020 11:03:55 +1000 Subject: [PATCH 623/656] Setup script improvements to MacOS / Ubuntu (#2012) * Setup script improvements to MacOS / Ubuntu scons isn't actually required from brew install pyenv init on all envs added installation to .zshrc on macos with better dir logic Using git to detect project root for ubuntu bashrc install Check shell and determine correct RC file Update tools/mac_setup.sh Co-authored-by: Adeeb Shihadeh Sourcing RC file only if it's found Removed unnecessary source of rc file Submodules should never have been bumped... Output the $RC_FILE when successfully installed pyenv init every time, and skip RC install on CI Confused bash conditionals, opposite of what I meant * Was missing libusb on a fresh MacOS 10.15.6 install Co-authored-by: Michael Honan --- tools/mac_setup.sh | 38 +++++++++++++++++++++++++++++++++----- tools/openpilot_env.sh | 3 +-- tools/ubuntu_setup.sh | 3 ++- 3 files changed, 36 insertions(+), 8 deletions(-) mode change 100644 => 100755 tools/openpilot_env.sh diff --git a/tools/mac_setup.sh b/tools/mac_setup.sh index 5097000196..a795624598 100755 --- a/tools/mac_setup.sh +++ b/tools/mac_setup.sh @@ -1,7 +1,13 @@ #!/bin/bash -e -# install brew -/bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install.sh)" +# Install brew if required. +if [[ $(command -v brew) == "" ]]; then + echo "Installing Hombrew" + /bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install.sh)" +else + echo "Updating Homebrew" + brew update +fi brew install capnp \ czmq \ @@ -10,17 +16,39 @@ brew install capnp \ ffmpeg \ glfw \ libarchive \ + libusb \ libtool \ llvm \ pyenv \ zeromq -# install python +# Detect shell and pick correct RC file. +if [[ $SHELL == "/bin/zsh" ]]; then + RC_FILE="$HOME/.zshrc" +elif [[ $SHELL == "/bin/bash" ]]; then + RC_FILE="$HOME/.bash_profile" +else + echo "-------------------------------------------------------------" + echo "Unsupported shell: \"$SHELL\", cannot install to RC file." + echo "Please run: echo \"source $OP_DIR/tools/openpilot_env.sh\" >> %YOUR SHELL's RC file%" + echo "-------------------------------------------------------------" +fi + +# Install to RC file (only non-CI). +if [ -z "$OPENPILOT_ENV" ] && [ -n "$RC_FILE" ] && [ -z "$CI" ]; then + OP_DIR=$(git rev-parse --show-toplevel) + echo "source $OP_DIR/tools/openpilot_env.sh" >> $RC_FILE + source $RC_FILE + echo "Added openpilot_env to RC file: $RC_FILE" +else + echo "Skipped RC file installation" +fi + +# Install python. pyenv install -s 3.8.2 pyenv global 3.8.2 pyenv rehash -eval "$(pyenv init -)" +eval "$(pyenv init -)" # CI doesn't use .bash_profile, and will use python2.7 if this line isn't here. pip install pipenv==2018.11.26 pipenv install --system --deploy - diff --git a/tools/openpilot_env.sh b/tools/openpilot_env.sh old mode 100644 new mode 100755 index 95f3b12ece..ca25706b83 --- a/tools/openpilot_env.sh +++ b/tools/openpilot_env.sh @@ -4,14 +4,13 @@ if [ -z "$OPENPILOT_ENV" ]; then unamestr=`uname` if [[ "$unamestr" == 'Linux' ]]; then export PATH="$HOME/.pyenv/bin:$PATH" - eval "$(pyenv init -)" eval "$(pyenv virtualenv-init -)" elif [[ "$unamestr" == 'Darwin' ]]; then # msgq doesn't work on mac export ZMQ=1 export OBJC_DISABLE_INITIALIZE_FORK_SAFETY=YES fi + eval "$(pyenv init -)" export OPENPILOT_ENV=1 fi - diff --git a/tools/ubuntu_setup.sh b/tools/ubuntu_setup.sh index e46d7b29fe..8de9152175 100755 --- a/tools/ubuntu_setup.sh +++ b/tools/ubuntu_setup.sh @@ -61,7 +61,8 @@ fi # install bashrc source ~/.bashrc if [ -z "$OPENPILOT_ENV" ]; then - echo "source $HOME/openpilot/tools/openpilot_env.sh" >> ~/.bashrc + OP_DIR=$(git rev-parse --show-toplevel) + echo "source $OP_DIR/tools/openpilot_env.sh" >> ~/.bashrc source ~/.bashrc echo "added openpilot_env to bashrc" fi From d99aa16b7d92c1fb37f683c2375dbd4629025a9c Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Sat, 15 Aug 2020 12:55:26 -0500 Subject: [PATCH 624/656] EU Corolla Hybrid TSS2 EPS f/w (#2027) @Lexdaadler#0295 DongleID 940e337f5fcf4d4e https://discord.com/channels/469524606043160576/524327905937850394/744162927954755615 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index da18bfba96..c034e5385d 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -593,6 +593,7 @@ FW_VERSIONS = { b'\x018965B12350\x00\x00\x00\x00\x00\x00', b'\x018965B12470\x00\x00\x00\x00\x00\x00', b'\x018965B12500\x00\x00\x00\x00\x00\x00', + b'\x018965B12520\x00\x00\x00\x00\x00\x00', b'\x018965B12530\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ From 70c7a72d4a4201cc649389d553b064c13873d1c0 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Sat, 15 Aug 2020 13:48:27 -0500 Subject: [PATCH 625/656] Add fwdCamera f/w for CAR.COROLLA_TSS2 (#2028) Nv#6820 DongleID 4dc9a71c543a576f 2020 Corolla LE ICE https://discord.com/channels/469524606043160576/524327905937850394/744254107874885652 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index c034e5385d..73b8fb742e 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -573,6 +573,7 @@ FW_VERSIONS = { b'\x028646F12010D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F1201200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], From 862259a94b6c6c8fa758c0656cbfbc9ec08d4f54 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 16 Aug 2020 16:11:09 -0700 Subject: [PATCH 626/656] exit camerad cleanly on PC (#2035) --- selfdrive/camerad/main.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index 658ab55bae..cc1b7a6dda 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -1244,7 +1244,7 @@ void party(VisionState *s) { zsock_signal(s->terminate_pub, 0); -#if !defined(QCOM2) && !defined(QCOM_REPLAY) && !defined(__APPLE__) +#if (defined(QCOM) && !defined(QCOM_REPLAY)) || defined(WEBCAM) LOG("joining frontview_thread"); err = pthread_join(frontview_thread_handle, NULL); assert(err == 0); From 36801a70eb8f599baee8e07aed0ec9c3b6385595 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 17 Aug 2020 07:31:53 +0800 Subject: [PATCH 627/656] init and destroy transform_lock (#2003) --- selfdrive/modeld/modeld.cc | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 33dafc86cf..65b702dbd2 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -78,6 +78,8 @@ int main(int argc, char **argv) { signal(SIGINT, (sighandler_t)set_do_exit); signal(SIGTERM, (sighandler_t)set_do_exit); + pthread_mutex_init(&transform_lock, NULL); + // start calibration thread pthread_t live_thread_handle; err = pthread_create(&live_thread_handle, NULL, live_thread, NULL); @@ -249,5 +251,6 @@ int main(int argc, char **argv) { clReleaseCommandQueue(q); clReleaseContext(context); + pthread_mutex_destroy(&transform_lock); return 0; } From 160c89cde619b0eeeacda22eedb55e09d0d8ace5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 16 Aug 2020 20:13:08 -0700 Subject: [PATCH 628/656] remove old test runner --- run_docker_tests.sh | 24 ------------------------ 1 file changed, 24 deletions(-) delete mode 100755 run_docker_tests.sh diff --git a/run_docker_tests.sh b/run_docker_tests.sh deleted file mode 100755 index f208ad1b9c..0000000000 --- a/run_docker_tests.sh +++ /dev/null @@ -1,24 +0,0 @@ -#!/bin/bash -set -e - -# NOTE: this may be not an up-to-date list of tests and checks, see .github/workflows/test.yaml for the current list of tests - -SETUP="cd /tmp/openpilot && " -BUILD="cd /tmp/openpilot && scons -c && scons -j$(nproc) && " -RUN="docker run --shm-size 1G --rm tmppilot /bin/bash -c" - -docker build -t tmppilot -f Dockerfile.openpilot . - -$RUN "$SETUP cd selfdrive/test/ && ./test_fingerprints.py" -$RUN "$SETUP git init && git add -A && pre-commit run --all" -$RUN "$BUILD python -m unittest discover common && \ - python -m unittest discover opendbc/can && \ - python -m unittest discover selfdrive/boardd && \ - python -m unittest discover selfdrive/controls && \ - python -m unittest discover selfdrive/loggerd && \ - python -m unittest discover selfdrive/car && \ - python -m unittest discover selfdrive/locationd && \ - python -m unittest discover selfdrive/athena" -$RUN "$BUILD cd /tmp/openpilot/selfdrive/test/longitudinal_maneuvers && OPTEST=1 ./test_longitudinal.py" -$RUN "$BUILD cd /tmp/openpilot/selfdrive/test/process_replay/ && ./test_processes.py" -$RUN "$BUILD mkdir -p /data/params && cd /tmp/openpilot/selfdrive/test/ && ./test_car_models.py" From 1b52930a52828b1423c59c677c9b42a5ff76125c Mon Sep 17 00:00:00 2001 From: Chris Date: Mon, 17 Aug 2020 03:16:52 -0600 Subject: [PATCH 629/656] Kilometers per hour now displayed as km/h (#2032) Fixes #2031 Signed-off-by: Christopher Rabotin --- selfdrive/controls/lib/events.py | 4 ++-- selfdrive/ui/paint.cc | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 205c6a1722..193efc8c63 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -176,7 +176,7 @@ class EngagementAlert(Alert): def below_steer_speed_alert(CP, sm, metric): speed = int(round(CP.minSteerSpeed * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH))) - unit = "kph" if metric else "mph" + unit = "km/h" if metric else "mph" return Alert( "TAKE CONTROL", "Steer Unavailable Below %d %s" % (speed, unit), @@ -185,7 +185,7 @@ def below_steer_speed_alert(CP, sm, metric): def calibration_incomplete_alert(CP, sm, metric): speed = int(Filter.MIN_SPEED * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH)) - unit = "kph" if metric else "mph" + unit = "km/h" if metric else "mph" return Alert( "Calibration in Progress: %d%%" % sm['liveCalibration'].calPerc, "Drive Above %d %s" % (speed, unit), diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 8802526cb8..dbddd50149 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -516,7 +516,7 @@ static void ui_draw_vision_speed(UIState *s) { snprintf(speed_str, sizeof(speed_str), "%d", (int)speed); ui_draw_text(s->vg, viz_speed_x + viz_speed_w / 2, 240, speed_str, 96*2.5, COLOR_WHITE, s->font_sans_bold); - ui_draw_text(s->vg, viz_speed_x + viz_speed_w / 2, 320, s->is_metric?"kph":"mph", 36*2.5, COLOR_WHITE_ALPHA(200), s->font_sans_regular); + ui_draw_text(s->vg, viz_speed_x + viz_speed_w / 2, 320, s->is_metric?"km/h":"mph", 36*2.5, COLOR_WHITE_ALPHA(200), s->font_sans_regular); } static void ui_draw_vision_event(UIState *s) { From d1588376171d8ba1d2ec1b670e085d6e15bd26c1 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 17 Aug 2020 17:24:39 +0800 Subject: [PATCH 630/656] add function cl_get_device_id (#1948) * add func cl_get_device_id cleanup * add fix from review --- selfdrive/camerad/main.cc | 14 +---- selfdrive/camerad/test/yuv_bench/yuv_bench.cc | 23 +------- .../camerad/transforms/rgb_to_yuv_test.cc | 9 +-- selfdrive/common/clutil.c | 38 +++++++++++++ selfdrive/common/clutil.h | 1 + selfdrive/modeld/modeld.cc | 57 ++----------------- selfdrive/modeld/thneed/debug/main.cc | 13 +---- selfdrive/modeld/visiontest.c | 24 +------- 8 files changed, 53 insertions(+), 126 deletions(-) diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index cc1b7a6dda..8038b82322 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -1010,19 +1010,7 @@ cl_program build_pool_program(VisionState *s, void cl_init(VisionState *s) { int err; - cl_platform_id platform_id = NULL; - cl_uint num_devices; - cl_uint num_platforms; - - err = clGetPlatformIDs(1, &platform_id, &num_platforms); - assert(err == 0); - err = clGetDeviceIDs(platform_id, CL_DEVICE_TYPE_DEFAULT, 1, - &s->device_id, &num_devices); - assert(err == 0); - - cl_print_info(platform_id, s->device_id); - printf("\n"); - + s->device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); s->context = clCreateContext(NULL, 1, &s->device_id, NULL, NULL, &err); assert(err == 0); } diff --git a/selfdrive/camerad/test/yuv_bench/yuv_bench.cc b/selfdrive/camerad/test/yuv_bench/yuv_bench.cc index 22e71c4128..62860ea7cc 100644 --- a/selfdrive/camerad/test/yuv_bench/yuv_bench.cc +++ b/selfdrive/camerad/test/yuv_bench/yuv_bench.cc @@ -38,27 +38,8 @@ int main() { // init cl - /* Get Platform and Device Info */ - cl_platform_id platform_id = NULL; - cl_uint num_platforms_unused; - int err = clGetPlatformIDs(1, &platform_id, &num_platforms_unused); - if (err != 0) { - fprintf(stderr, "cl error: %d\n", err); - } - assert(err == 0); - - cl_device_id device_id = NULL; - cl_uint num_devices_unused; - err = clGetDeviceIDs(platform_id, CL_DEVICE_TYPE_DEFAULT, 1, &device_id, - &num_devices_unused); - if (err != 0) { - fprintf(stderr, "cl error: %d\n", err); - } - assert(err == 0); - - cl_print_info(platform_id, device_id); - printf("\n"); - + int err; + cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); cl_context context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); assert(err == 0); diff --git a/selfdrive/camerad/transforms/rgb_to_yuv_test.cc b/selfdrive/camerad/transforms/rgb_to_yuv_test.cc index c8b8751058..9d68e5b9ef 100644 --- a/selfdrive/camerad/transforms/rgb_to_yuv_test.cc +++ b/selfdrive/camerad/transforms/rgb_to_yuv_test.cc @@ -42,14 +42,7 @@ static inline double millis_since_boot() { void cl_init(cl_device_id &device_id, cl_context &context) { int err; - cl_platform_id platform_id = NULL; - cl_uint num_devices; - cl_uint num_platforms; - - err = clGetPlatformIDs(1, &platform_id, &num_platforms); - err = clGetDeviceIDs(platform_id, CL_DEVICE_TYPE_DEFAULT, 1, - &device_id, &num_devices); - cl_print_info(platform_id, device_id); + device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); } diff --git a/selfdrive/common/clutil.c b/selfdrive/common/clutil.c index 9a80c9067b..00d63cdcac 100644 --- a/selfdrive/common/clutil.c +++ b/selfdrive/common/clutil.c @@ -36,6 +36,44 @@ void clu_init(void) { #endif } +cl_device_id cl_get_device_id(cl_device_type device_type) { + bool opencl_platform_found = false; + cl_device_id device_id = NULL; + + cl_uint num_platforms = 0; + int err = clGetPlatformIDs(0, NULL, &num_platforms); + assert(err == 0); + cl_platform_id* platform_ids = malloc(sizeof(cl_platform_id) * num_platforms); + err = clGetPlatformIDs(num_platforms, platform_ids, NULL); + assert(err == 0); + + char cBuffer[1024]; + for (size_t i = 0; i < num_platforms; i++) { + err = clGetPlatformInfo(platform_ids[i], CL_PLATFORM_NAME, sizeof(cBuffer), &cBuffer, NULL); + assert(err == 0); + printf("platform[%zu] CL_PLATFORM_NAME: %s\n", i, cBuffer); + + cl_uint num_devices; + err = clGetDeviceIDs(platform_ids[i], device_type, 0, NULL, &num_devices); + if (err != 0 || !num_devices) { + continue; + } + // Get first device + err = clGetDeviceIDs(platform_ids[i], device_type, 1, &device_id, NULL); + assert(err == 0); + cl_print_info(platform_ids[i], device_id); + opencl_platform_found = true; + break; + } + free(platform_ids); + + if (!opencl_platform_found) { + printf("No valid openCL platform found\n"); + assert(opencl_platform_found); + } + return device_id; +} + cl_program cl_create_program_from_file(cl_context ctx, const char* path) { char* src_buf = read_file(path, NULL); assert(src_buf); diff --git a/selfdrive/common/clutil.h b/selfdrive/common/clutil.h index b87961eacd..abbda8c806 100644 --- a/selfdrive/common/clutil.h +++ b/selfdrive/common/clutil.h @@ -17,6 +17,7 @@ extern "C" { void clu_init(void); +cl_device_id cl_get_device_id(cl_device_type device_type); cl_program cl_create_program_from_file(cl_context ctx, const char* path); void cl_print_info(cl_platform_id platform, cl_device_id device); void cl_print_build_errors(cl_program program, cl_device_id device); diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 65b702dbd2..3df4078a7e 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -6,6 +6,7 @@ #include "common/visionbuf.h" #include "common/visionipc.h" #include "common/swaglog.h" +#include "common/clutil.h" #include "models/driving.h" #include "messaging.hpp" @@ -96,58 +97,12 @@ int main(int argc, char **argv) { #endif // cl init - cl_device_id device_id; - cl_context context; - cl_command_queue q; - { - cl_uint num_platforms; - err = clGetPlatformIDs(0, NULL, &num_platforms); - assert(err == 0); - - cl_platform_id * platform_ids = new cl_platform_id[num_platforms]; - err = clGetPlatformIDs(num_platforms, platform_ids, NULL); - assert(err == 0); - - LOGD("got %d opencl platform(s)", num_platforms); - - char cBuffer[1024]; - bool opencl_platform_found = false; - - for (size_t i = 0; i < num_platforms; i++){ - err = clGetPlatformInfo(platform_ids[i], CL_PLATFORM_NAME, sizeof(cBuffer), &cBuffer, NULL); - assert(err == 0); - LOGD("platform[%zu] CL_PLATFORM_NAME: %s", i, cBuffer); - - cl_uint num_devices; - err = clGetDeviceIDs(platform_ids[i], device_type, 0, NULL, &num_devices); - if (err != 0|| !num_devices){ - continue; - } - - // Get first device - err = clGetDeviceIDs(platform_ids[i], device_type, 1, &device_id, NULL); - assert(err == 0); - - context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); - assert(err == 0); - - q = clCreateCommandQueue(context, device_id, 0, &err); - assert(err == 0); - - opencl_platform_found = true; - break; - } - - delete[] platform_ids; - - if (!opencl_platform_found){ - LOGE("No valid openCL platform found"); - assert(opencl_platform_found); - } - + cl_device_id device_id = cl_get_device_id(device_type); + cl_context context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); + assert(err == 0); - LOGD("opencl init complete"); - } + cl_command_queue q = clCreateCommandQueue(context, device_id, 0, &err); + assert(err == 0); // init the models ModelState model; diff --git a/selfdrive/modeld/thneed/debug/main.cc b/selfdrive/modeld/thneed/debug/main.cc index b9848705de..cf96c61e39 100644 --- a/selfdrive/modeld/thneed/debug/main.cc +++ b/selfdrive/modeld/thneed/debug/main.cc @@ -1,5 +1,6 @@ #include #include "include/msm_kgsl.h" +#include "common/clutil.h" #include #include #include @@ -601,18 +602,8 @@ void *dlsym(void *handle, const char *symbol) { int main(int argc, char* argv[]) { int err; - cl_platform_id platform_id = NULL; - cl_device_id device_id = NULL; - cl_uint num_devices; - cl_uint num_platforms; - start_time = nanos_since_boot(); - - err = clGetPlatformIDs(1, &platform_id, &num_platforms); - assert(err == 0); - err = clGetDeviceIDs(platform_id, CL_DEVICE_TYPE_DEFAULT, 1, &device_id, &num_devices); - assert(err == 0); - + cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); cl_uint tmp; // sweet this is 64! diff --git a/selfdrive/modeld/visiontest.c b/selfdrive/modeld/visiontest.c index 325e257e86..2ce68ad9c1 100644 --- a/selfdrive/modeld/visiontest.c +++ b/selfdrive/modeld/visiontest.c @@ -33,28 +33,8 @@ typedef struct { void initialize_opencl(VisionTest* visiontest) { // init cl - /* Get Platform and Device Info */ - cl_platform_id platform_ids[16] = {0}; - cl_uint num_platforms; - int err = clGetPlatformIDs(16, platform_ids, &num_platforms); - if (err != 0) { - fprintf(stderr, "cl error: %d\n", err); - } - assert(err == 0); - - // try to find a CPU device - cl_device_id device_id = NULL; - for (int i=0; icontext = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); assert(err == 0); From 7555379b2b1da2f800e98963ad4436b7fb91cce9 Mon Sep 17 00:00:00 2001 From: robbederks Date: Mon, 17 Aug 2020 11:56:27 +0200 Subject: [PATCH 631/656] Car power integrator + power management refactor (#1994) * wip, ready to test * tweaks * fix * fix * fix power monitoring * fix param writing * no forced charging on high voltage * reset capacity on reboot * don't shutdown unless started seen * fix unused var warning * fix linting errors * time is always valid * QCOM gate * Local params * decimate saving * fix linting * rename param * Log car battery capacity * fix put_nonblocking * Added some unit tests * Add test to docker test list * fix precommit * cleanup * run tests in CI * bump cereal Co-authored-by: Adeeb Shihadeh --- .github/workflows/test.yaml | 1 + cereal | 2 +- common/params.py | 1 + selfdrive/boardd/boardd.cc | 47 ++-- selfdrive/thermald/__init__.py | 0 selfdrive/thermald/power_monitoring.py | 193 ++++++++++----- selfdrive/thermald/tests/__init__.py | 0 .../thermald/tests/test_power_monitoring.py | 221 ++++++++++++++++++ selfdrive/thermald/thermald.py | 17 +- 9 files changed, 382 insertions(+), 100 deletions(-) create mode 100644 selfdrive/thermald/__init__.py create mode 100644 selfdrive/thermald/tests/__init__.py create mode 100755 selfdrive/thermald/tests/test_power_monitoring.py diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index f8bbb1bc8d..7d0ae1f456 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -146,6 +146,7 @@ jobs: $UNIT_TEST selfdrive/car && \ $UNIT_TEST selfdrive/locationd && \ $UNIT_TEST selfdrive/athena && \ + $UNIT_TEST selfdrive/thermald && \ $UNIT_TEST tools/lib/tests" - name: Upload coverage to Codecov run: | diff --git a/cereal b/cereal index d66afca4ac..0d2ce45fc6 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit d66afca4ac316456711cb80c8e8e2fe91431e1e2 +Subproject commit 0d2ce45fc681f90b33fbcd11e5d80dd294ef751b diff --git a/common/params.py b/common/params.py index e106705022..d01b1b4ae9 100755 --- a/common/params.py +++ b/common/params.py @@ -53,6 +53,7 @@ keys = { "AccessToken": [TxType.CLEAR_ON_MANAGER_START], "AthenadPid": [TxType.PERSISTENT], "CalibrationParams": [TxType.PERSISTENT], + "CarBatteryCapacity": [TxType.PERSISTENT], "CarParams": [TxType.CLEAR_ON_MANAGER_START, TxType.CLEAR_ON_PANDA_DISCONNECT], "CarParamsCache": [TxType.CLEAR_ON_MANAGER_START, TxType.CLEAR_ON_PANDA_DISCONNECT], "CarVin": [TxType.CLEAR_ON_MANAGER_START, TxType.CLEAR_ON_PANDA_DISCONNECT], diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index e1b275dd3e..1c83abf292 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -36,13 +36,6 @@ #define CUTOFF_IL 200 #define SATURATE_IL 1600 #define NIBBLE_TO_HEX(n) ((n) < 10 ? (n) + '0' : ((n) - 10) + 'a') -#define VOLTAGE_K 0.091 // LPF gain for 5s tau (dt/tau / (dt/tau + 1)) - -#ifdef QCOM -const uint32_t NO_IGNITION_CNT_MAX = 2 * 60 * 60 * 30; // turn off charge after 30 hrs -const float VBATT_START_CHARGING = 11.5; -const float VBATT_PAUSE_CHARGING = 11.0; -#endif Panda * panda = NULL; std::atomic safety_setter_thread_running(false); @@ -279,7 +272,6 @@ void can_health_thread() { uint32_t no_ignition_cnt = 0; bool ignition_last = false; - float voltage_f = 12.5; // filtered voltage // Broadcast empty health message when panda is not yet connected while (!panda){ @@ -306,8 +298,6 @@ void can_health_thread() { health.ignition_line = 1; } - voltage_f = VOLTAGE_K * (health.voltage / 1000.0) + (1.0 - VOLTAGE_K) * voltage_f; // LPF - // Make sure CAN buses are live: safety_setter_thread does not work if Panda CAN are silent and there is only one other CAN node if (health.safety_model == (uint8_t)(cereal::CarParams::SafetyModel::SILENT)) { panda->set_safety_model(cereal::CarParams::SafetyModel::NO_OUTPUT); @@ -321,24 +311,6 @@ void can_health_thread() { no_ignition_cnt += 1; } -#ifdef QCOM - bool cdp_mode = health.usb_power_mode == (uint8_t)(cereal::HealthData::UsbPowerMode::CDP); - bool no_ignition_exp = no_ignition_cnt > NO_IGNITION_CNT_MAX; - if ((no_ignition_exp || (voltage_f < VBATT_PAUSE_CHARGING)) && cdp_mode && !ignition) { - std::vector disable_power_down = read_db_bytes("DisablePowerDown"); - if (disable_power_down.size() != 1 || disable_power_down[0] != '1') { - LOGW("TURN OFF CHARGING!\n"); - panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CLIENT); - LOGW("POWER DOWN DEVICE\n"); - system("service call power 17 i32 0 i32 1"); - } - } - if (!no_ignition_exp && (voltage_f > VBATT_START_CHARGING) && !cdp_mode) { - LOGW("TURN ON CHARGING!\n"); - panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CDP); - } -#endif - #ifndef __x86_64__ bool power_save_desired = !ignition; if (health.power_save_enabled != power_save_desired){ @@ -427,6 +399,9 @@ void hardware_control_thread() { uint16_t prev_fan_speed = 999; uint16_t ir_pwr = 0; uint16_t prev_ir_pwr = 999; +#ifdef QCOM + bool prev_charging_disabled = false; +#endif unsigned int cnt = 0; while (!do_exit && panda->connected) { @@ -434,11 +409,27 @@ void hardware_control_thread() { sm.update(1000); // TODO: what happens if EINTR is sent while in sm.update? if (sm.updated("thermal")){ + // Fan speed uint16_t fan_speed = sm["thermal"].getThermal().getFanSpeed(); if (fan_speed != prev_fan_speed || cnt % 100 == 0){ panda->set_fan_speed(fan_speed); prev_fan_speed = fan_speed; } + +#ifdef QCOM + // Charging mode + bool charging_disabled = sm["thermal"].getThermal().getChargingDisabled(); + if (charging_disabled != prev_charging_disabled){ + if (charging_disabled){ + panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CLIENT); + LOGW("TURN OFF CHARGING!\n"); + } else { + panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CDP); + LOGW("TURN ON CHARGING!\n"); + } + prev_charging_disabled = charging_disabled; + } +#endif } if (sm.updated("frontFrame")){ auto event = sm["frontFrame"]; diff --git a/selfdrive/thermald/__init__.py b/selfdrive/thermald/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/thermald/power_monitoring.py b/selfdrive/thermald/power_monitoring.py index 6bf26ee0ea..cd4bb7d7bc 100644 --- a/selfdrive/thermald/power_monitoring.py +++ b/selfdrive/thermald/power_monitoring.py @@ -1,4 +1,3 @@ -import datetime import random import threading import time @@ -6,10 +5,19 @@ from statistics import mean from cereal import log from common.realtime import sec_since_boot +from common.params import Params, put_nonblocking from selfdrive.swaglog import cloudlog PANDA_OUTPUT_VOLTAGE = 5.28 +CAR_VOLTAGE_LOW_PASS_K = 0.091 # LPF gain for 5s tau (dt/tau / (dt/tau + 1)) +# A C2 uses about 1W while idling, and 30h seens like a good shutoff for most cars +# While driving, a battery charges completely in about 30-60 minutes +CAR_BATTERY_CAPACITY_uWh = 30e6 +CAR_CHARGING_RATE_W = 45 + +VBATT_PAUSE_CHARGING = 11.0 +MAX_TIME_OFFROAD_S = 30*3600 # Parameters def get_battery_capacity(): @@ -36,7 +44,7 @@ def get_usb_present(): def get_battery_charging(): # This does correspond with actually charging - return _read_param("/sys/class/power_supply/battery/charge_type", lambda x: x.strip() != "N/A", False) + return _read_param("/sys/class/power_supply/battery/charge_type", lambda x: x.strip() != "N/A", True) def set_battery_charging(on): @@ -60,91 +68,117 @@ def panda_current_to_actual_current(panda_current): class PowerMonitoring: def __init__(self): + self.params = Params() self.last_measurement_time = None # Used for integration delta + self.last_save_time = 0 # Used for saving current value in a param self.power_used_uWh = 0 # Integrated power usage in uWh since going into offroad self.next_pulsed_measurement_time = None + self.car_voltage_mV = 12e3 # Low-passed version of health voltage self.integration_lock = threading.Lock() + car_battery_capacity_uWh = self.params.get("CarBatteryCapacity") + if car_battery_capacity_uWh is None: + car_battery_capacity_uWh = 0 + + # Reset capacity if it's low + self.car_battery_capacity_uWh = max((CAR_BATTERY_CAPACITY_uWh / 10), int(car_battery_capacity_uWh)) + + # Calculation tick def calculate(self, health): try: now = sec_since_boot() - # Check that time is valid - if datetime.datetime.fromtimestamp(now).year < 2019: - return - - # Only integrate when there is no ignition # If health is None, we're probably not in a car, so we don't care - if health is None or (health.health.ignitionLine or health.health.ignitionCan) or \ - health.health.hwType == log.HealthData.HwType.unknown: + if health is None or health.health.hwType == log.HealthData.HwType.unknown: with self.integration_lock: self.last_measurement_time = None self.next_pulsed_measurement_time = None self.power_used_uWh = 0 return + # Low-pass battery voltage + self.car_voltage_mV = ((health.health.voltage * CAR_VOLTAGE_LOW_PASS_K) + (self.car_voltage_mV * (1 - CAR_VOLTAGE_LOW_PASS_K))) + + # Cap the car battery power and save it in a param every 10-ish seconds + self.car_battery_capacity_uWh = max(self.car_battery_capacity_uWh, 0) + self.car_battery_capacity_uWh = min(self.car_battery_capacity_uWh, CAR_BATTERY_CAPACITY_uWh) + if now - self.last_save_time >= 10: + put_nonblocking("CarBatteryCapacity", str(int(self.car_battery_capacity_uWh))) + self.last_save_time = now + # First measurement, set integration time with self.integration_lock: if self.last_measurement_time is None: self.last_measurement_time = now return - is_uno = health.health.hwType == log.HealthData.HwType.uno - # Get current power draw somehow - current_power = 0 - if get_battery_status() == 'Discharging': - # If the battery is discharging, we can use this measurement - # On C2: this is low by about 10-15%, probably mostly due to UNO draw not being factored in - current_power = ((get_battery_voltage() / 1000000) * (get_battery_current() / 1000000)) - elif (health.health.hwType in [log.HealthData.HwType.whitePanda, log.HealthData.HwType.greyPanda]) and (health.health.current > 1): - # If white/grey panda, use the integrated current measurements if the measurement is not 0 - # If the measurement is 0, the current is 400mA or greater, and out of the measurement range of the panda - # This seems to be accurate to about 5% - current_power = (PANDA_OUTPUT_VOLTAGE * panda_current_to_actual_current(health.health.current)) - elif (self.next_pulsed_measurement_time is not None) and (self.next_pulsed_measurement_time <= now): - # TODO: Figure out why this is off by a factor of 3/4??? - FUDGE_FACTOR = 1.33 - - # Turn off charging for about 10 sec in a thread that does not get killed on SIGINT, and perform measurement here to avoid blocking thermal - def perform_pulse_measurement(now): - try: - set_battery_charging(False) - time.sleep(5) - - # Measure for a few sec to get a good average - voltages = [] - currents = [] - for _ in range(6): - voltages.append(get_battery_voltage()) - currents.append(get_battery_current()) - time.sleep(1) - current_power = ((mean(voltages) / 1000000) * (mean(currents) / 1000000)) - - self._perform_integration(now, current_power * FUDGE_FACTOR) - - # Enable charging again - set_battery_charging(True) - except Exception: - cloudlog.exception("Pulsed power measurement failed") - - # Start pulsed measurement and return - threading.Thread(target=perform_pulse_measurement, args=(now,)).start() - self.next_pulsed_measurement_time = None - return - - elif self.next_pulsed_measurement_time is None and not is_uno: - # On a charging EON with black panda, or drawing more than 400mA out of a white/grey one - # Only way to get the power draw is to turn off charging for a few sec and check what the discharging rate is - # We shouldn't do this very often, so make sure it has been some long-ish random time interval - self.next_pulsed_measurement_time = now + random.randint(120, 180) - return + if (health.health.ignitionLine or health.health.ignitionCan): + # If there is ignition, we integrate the charging rate of the car + with self.integration_lock: + self.power_used_uWh = 0 + integration_time_h = (now - self.last_measurement_time) / 3600 + if integration_time_h < 0: + raise ValueError(f"Negative integration time: {integration_time_h}h") + self.car_battery_capacity_uWh += (CAR_CHARGING_RATE_W * 1e6 * integration_time_h) + self.last_measurement_time = now else: - # Do nothing - return + # No ignition, we integrate the offroad power used by the device + is_uno = health.health.hwType == log.HealthData.HwType.uno + # Get current power draw somehow + current_power = 0 + if get_battery_status() == 'Discharging': + # If the battery is discharging, we can use this measurement + # On C2: this is low by about 10-15%, probably mostly due to UNO draw not being factored in + current_power = ((get_battery_voltage() / 1000000) * (get_battery_current() / 1000000)) + elif (health.health.hwType in [log.HealthData.HwType.whitePanda, log.HealthData.HwType.greyPanda]) and (health.health.current > 1): + # If white/grey panda, use the integrated current measurements if the measurement is not 0 + # If the measurement is 0, the current is 400mA or greater, and out of the measurement range of the panda + # This seems to be accurate to about 5% + current_power = (PANDA_OUTPUT_VOLTAGE * panda_current_to_actual_current(health.health.current)) + elif (self.next_pulsed_measurement_time is not None) and (self.next_pulsed_measurement_time <= now): + # TODO: Figure out why this is off by a factor of 3/4??? + FUDGE_FACTOR = 1.33 + + # Turn off charging for about 10 sec in a thread that does not get killed on SIGINT, and perform measurement here to avoid blocking thermal + def perform_pulse_measurement(now): + try: + set_battery_charging(False) + time.sleep(5) + + # Measure for a few sec to get a good average + voltages = [] + currents = [] + for _ in range(6): + voltages.append(get_battery_voltage()) + currents.append(get_battery_current()) + time.sleep(1) + current_power = ((mean(voltages) / 1000000) * (mean(currents) / 1000000)) + + self._perform_integration(now, current_power * FUDGE_FACTOR) + + # Enable charging again + set_battery_charging(True) + except Exception: + cloudlog.exception("Pulsed power measurement failed") + + # Start pulsed measurement and return + threading.Thread(target=perform_pulse_measurement, args=(now,)).start() + self.next_pulsed_measurement_time = None + return - # Do the integration - self._perform_integration(now, current_power) + elif self.next_pulsed_measurement_time is None and not is_uno: + # On a charging EON with black panda, or drawing more than 400mA out of a white/grey one + # Only way to get the power draw is to turn off charging for a few sec and check what the discharging rate is + # We shouldn't do this very often, so make sure it has been some long-ish random time interval + self.next_pulsed_measurement_time = now + random.randint(120, 180) + return + else: + # Do nothing + return + + # Do the integration + self._perform_integration(now, current_power) except Exception: cloudlog.exception("Power monitoring calculation failed") @@ -157,6 +191,7 @@ class PowerMonitoring: if power_used < 0: raise ValueError(f"Negative power used! Integration time: {integration_time_h} h Current Power: {power_used} uWh") self.power_used_uWh += power_used + self.car_battery_capacity_uWh -= power_used self.last_measurement_time = t except Exception: cloudlog.exception("Integration failed") @@ -164,3 +199,37 @@ class PowerMonitoring: # Get the power usage def get_power_used(self): return int(self.power_used_uWh) + + def get_car_battery_capacity(self): + return int(self.car_battery_capacity_uWh) + + # See if we need to disable charging + def should_disable_charging(self, health, offroad_timestamp): + if health is None or offroad_timestamp is None: + return False + + now = sec_since_boot() + disable_charging = False + disable_charging |= (now - offroad_timestamp) > MAX_TIME_OFFROAD_S + disable_charging |= (self.car_voltage_mV < (VBATT_PAUSE_CHARGING * 1e3)) + disable_charging |= (self.car_battery_capacity_uWh <= 0) + disable_charging &= (not health.health.ignitionLine and not health.health.ignitionCan) + disable_charging &= (self.params.get("DisablePowerDown") != b"1") + return disable_charging + + # See if we need to shutdown + def should_shutdown(self, health, offroad_timestamp, started_seen, LEON): + if health is None or offroad_timestamp is None: + return False + + now = sec_since_boot() + panda_charging = (health.health.usbPowerMode != log.HealthData.UsbPowerMode.client) + BATT_PERC_OFF = 10 if LEON else 3 + + should_shutdown = False + # Wait until we have shut down charging before powering down + should_shutdown |= (not panda_charging and self.should_disable_charging(health, offroad_timestamp)) + should_shutdown |= ((get_battery_capacity() < BATT_PERC_OFF) and (not get_battery_charging()) and ((now - offroad_timestamp) > 60)) + should_shutdown &= started_seen + return should_shutdown + diff --git a/selfdrive/thermald/tests/__init__.py b/selfdrive/thermald/tests/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/thermald/tests/test_power_monitoring.py b/selfdrive/thermald/tests/test_power_monitoring.py new file mode 100755 index 0000000000..af46e447e5 --- /dev/null +++ b/selfdrive/thermald/tests/test_power_monitoring.py @@ -0,0 +1,221 @@ +#!/usr/bin/env python3 +import unittest +from unittest.mock import patch +from parameterized import parameterized + +from cereal import log +import cereal.messaging as messaging +from common.params import Params +params = Params() + +# Create fake time +ssb = 0 +def mock_sec_since_boot(): + global ssb + ssb += 1 + return ssb + +with patch("common.realtime.sec_since_boot", new=mock_sec_since_boot): + with patch("common.params.put_nonblocking", new=params.put): + from selfdrive.thermald.power_monitoring import PowerMonitoring, CAR_BATTERY_CAPACITY_uWh, \ + PANDA_OUTPUT_VOLTAGE, CAR_CHARGING_RATE_W, \ + VBATT_PAUSE_CHARGING + +def actual_current_to_panda_current(actual_current): + return max(int(((3.3 - (actual_current * 8.25)) * 4096) / 3.3), 0) + +TEST_DURATION_S = 50 +ALL_PANDA_TYPES = [(hw_type,) for hw_type in [log.HealthData.HwType.whitePanda, + log.HealthData.HwType.greyPanda, + log.HealthData.HwType.blackPanda, + log.HealthData.HwType.uno]] + +def pm_patch(name, value, constant=False): + if constant: + return patch(f"selfdrive.thermald.power_monitoring.{name}", value) + return patch(f"selfdrive.thermald.power_monitoring.{name}", return_value=value) + +class TestPowerMonitoring(unittest.TestCase): + def setUp(self): + # Clear stored capacity before each test + params.delete("CarBatteryCapacity") + params.delete("DisablePowerDown") + + def mock_health(self, ignition, hw_type, car_voltage=12, current=0): + health = messaging.new_message('health') + health.health.hwType = hw_type + health.health.voltage = car_voltage * 1e3 + health.health.current = actual_current_to_panda_current(current) + health.health.ignitionLine = ignition + health.health.ignitionCan = False + return health + + # Test to see that it doesn't do anything when health is None + def test_health_present(self): + pm = PowerMonitoring() + for _ in range(10): + pm.calculate(None) + self.assertEqual(pm.get_power_used(), 0) + self.assertEqual(pm.get_car_battery_capacity(), (CAR_BATTERY_CAPACITY_uWh / 10)) + + # Test to see that it doesn't integrate offroad when ignition is True + @parameterized.expand(ALL_PANDA_TYPES) + def test_offroad_ignition(self, hw_type): + pm = PowerMonitoring() + for _ in range(10): + pm.calculate(self.mock_health(True, hw_type)) + self.assertEqual(pm.get_power_used(), 0) + + # Test to see that it integrates with white/grey panda while charging + @parameterized.expand([(log.HealthData.HwType.whitePanda,), (log.HealthData.HwType.greyPanda,)]) + def test_offroad_integration_white(self, hw_type): + with pm_patch("get_battery_voltage", 4e6), pm_patch("get_battery_current", 1e5), pm_patch("get_battery_status", "Charging"): + pm = PowerMonitoring() + for _ in range(TEST_DURATION_S + 1): + pm.calculate(self.mock_health(False, hw_type, current=0.1)) + expected_power_usage = ((TEST_DURATION_S/3600) * (0.1 * PANDA_OUTPUT_VOLTAGE) * 1e6) + self.assertLess(abs(pm.get_power_used() - expected_power_usage), 10) + + # Test to see that it integrates with discharging battery + @parameterized.expand(ALL_PANDA_TYPES) + def test_offroad_integration_discharging(self, hw_type): + BATT_VOLTAGE = 4 + BATT_CURRENT = 1 + with pm_patch("get_battery_voltage", BATT_VOLTAGE * 1e6), pm_patch("get_battery_current", BATT_CURRENT * 1e6), \ + pm_patch("get_battery_status", "Discharging"): + pm = PowerMonitoring() + for _ in range(TEST_DURATION_S + 1): + pm.calculate(self.mock_health(False, hw_type)) + expected_power_usage = ((TEST_DURATION_S/3600) * (BATT_VOLTAGE * BATT_CURRENT) * 1e6) + self.assertLess(abs(pm.get_power_used() - expected_power_usage), 10) + + # Test to check positive integration of car_battery_capacity + @parameterized.expand(ALL_PANDA_TYPES) + def test_car_battery_integration_onroad(self, hw_type): + BATT_VOLTAGE = 4 + BATT_CURRENT = 1 + with pm_patch("get_battery_voltage", BATT_VOLTAGE * 1e6), pm_patch("get_battery_current", BATT_CURRENT * 1e6), \ + pm_patch("get_battery_status", "Discharging"): + pm = PowerMonitoring() + pm.car_battery_capacity_uWh = 0 + for _ in range(TEST_DURATION_S + 1): + pm.calculate(self.mock_health(True, hw_type)) + expected_capacity = ((TEST_DURATION_S/3600) * CAR_CHARGING_RATE_W * 1e6) + self.assertLess(abs(pm.get_car_battery_capacity() - expected_capacity), 10) + + # Test to check positive integration upper limit + @parameterized.expand(ALL_PANDA_TYPES) + def test_car_battery_integration_upper_limit(self, hw_type): + BATT_VOLTAGE = 4 + BATT_CURRENT = 1 + with pm_patch("get_battery_voltage", BATT_VOLTAGE * 1e6), pm_patch("get_battery_current", BATT_CURRENT * 1e6), \ + pm_patch("get_battery_status", "Discharging"): + pm = PowerMonitoring() + pm.car_battery_capacity_uWh = CAR_BATTERY_CAPACITY_uWh - 1000 + for _ in range(TEST_DURATION_S + 1): + pm.calculate(self.mock_health(True, hw_type)) + estimated_capacity = CAR_BATTERY_CAPACITY_uWh + (CAR_CHARGING_RATE_W / 3600 * 1e6) + self.assertLess(abs(pm.get_car_battery_capacity() - estimated_capacity), 10) + + # Test to check negative integration of car_battery_capacity + @parameterized.expand(ALL_PANDA_TYPES) + def test_car_battery_integration_offroad(self, hw_type): + BATT_VOLTAGE = 4 + BATT_CURRENT = 1 + with pm_patch("get_battery_voltage", BATT_VOLTAGE * 1e6), pm_patch("get_battery_current", BATT_CURRENT * 1e6), \ + pm_patch("get_battery_status", "Discharging"): + pm = PowerMonitoring() + pm.car_battery_capacity_uWh = CAR_BATTERY_CAPACITY_uWh + for _ in range(TEST_DURATION_S + 1): + pm.calculate(self.mock_health(False, hw_type)) + expected_capacity = CAR_BATTERY_CAPACITY_uWh - ((TEST_DURATION_S/3600) * (BATT_VOLTAGE * BATT_CURRENT) * 1e6) + self.assertLess(abs(pm.get_car_battery_capacity() - expected_capacity), 10) + + # Test to check negative integration lower limit + @parameterized.expand(ALL_PANDA_TYPES) + def test_car_battery_integration_lower_limit(self, hw_type): + BATT_VOLTAGE = 4 + BATT_CURRENT = 1 + with pm_patch("get_battery_voltage", BATT_VOLTAGE * 1e6), pm_patch("get_battery_current", BATT_CURRENT * 1e6), \ + pm_patch("get_battery_status", "Discharging"): + pm = PowerMonitoring() + pm.car_battery_capacity_uWh = 1000 + for _ in range(TEST_DURATION_S + 1): + pm.calculate(self.mock_health(False, hw_type)) + estimated_capacity = 0 - ((1/3600) * (BATT_VOLTAGE * BATT_CURRENT) * 1e6) + self.assertLess(abs(pm.get_car_battery_capacity() - estimated_capacity), 10) + + # Test to check policy of stopping charging after MAX_TIME_OFFROAD_S + @parameterized.expand(ALL_PANDA_TYPES) + def test_max_time_offroad(self, hw_type): + global ssb + BATT_VOLTAGE = 4 + BATT_CURRENT = 0 # To stop shutting down for other reasons + MOCKED_MAX_OFFROAD_TIME = 3600 + with pm_patch("get_battery_voltage", BATT_VOLTAGE * 1e6), pm_patch("get_battery_current", BATT_CURRENT * 1e6), \ + pm_patch("get_battery_status", "Discharging"), pm_patch("MAX_TIME_OFFROAD_S", MOCKED_MAX_OFFROAD_TIME, constant=True): + pm = PowerMonitoring() + pm.car_battery_capacity_uWh = CAR_BATTERY_CAPACITY_uWh + start_time = ssb + health = self.mock_health(False, hw_type) + while ssb <= start_time + MOCKED_MAX_OFFROAD_TIME: + pm.calculate(health) + if (ssb - start_time) % 1000 == 0 and ssb < start_time + MOCKED_MAX_OFFROAD_TIME: + self.assertFalse(pm.should_disable_charging(health, start_time)) + self.assertTrue(pm.should_disable_charging(health, start_time)) + + # Test to check policy of stopping charging when the car voltage is too low + @parameterized.expand(ALL_PANDA_TYPES) + def test_car_voltage(self, hw_type): + global ssb + BATT_VOLTAGE = 4 + BATT_CURRENT = 0 # To stop shutting down for other reasons + TEST_TIME = 100 + with pm_patch("get_battery_voltage", BATT_VOLTAGE * 1e6), pm_patch("get_battery_current", BATT_CURRENT * 1e6), \ + pm_patch("get_battery_status", "Discharging"): + pm = PowerMonitoring() + pm.car_battery_capacity_uWh = CAR_BATTERY_CAPACITY_uWh + health = self.mock_health(False, hw_type, car_voltage=(VBATT_PAUSE_CHARGING - 1)) + for i in range(TEST_TIME): + pm.calculate(health) + if i % 10 == 0: + self.assertEqual(pm.should_disable_charging(health, ssb), (pm.car_voltage_mV < VBATT_PAUSE_CHARGING*1e3)) + self.assertTrue(pm.should_disable_charging(health, ssb)) + + # Test to check policy of not stopping charging when DisablePowerDown is set + def test_disable_power_down(self): + global ssb + BATT_VOLTAGE = 4 + BATT_CURRENT = 0 # To stop shutting down for other reasons + TEST_TIME = 100 + params.put("DisablePowerDown", b"1") + with pm_patch("get_battery_voltage", BATT_VOLTAGE * 1e6), pm_patch("get_battery_current", BATT_CURRENT * 1e6), \ + pm_patch("get_battery_status", "Discharging"): + pm = PowerMonitoring() + pm.car_battery_capacity_uWh = CAR_BATTERY_CAPACITY_uWh + health = self.mock_health(False, log.HealthData.HwType.uno, car_voltage=(VBATT_PAUSE_CHARGING - 1)) + for i in range(TEST_TIME): + pm.calculate(health) + if i % 10 == 0: + self.assertFalse(pm.should_disable_charging(health, ssb)) + self.assertFalse(pm.should_disable_charging(health, ssb)) + + # Test to check policy of not stopping charging when ignition + def test_ignition(self): + global ssb + BATT_VOLTAGE = 4 + BATT_CURRENT = 0 # To stop shutting down for other reasons + TEST_TIME = 100 + with pm_patch("get_battery_voltage", BATT_VOLTAGE * 1e6), pm_patch("get_battery_current", BATT_CURRENT * 1e6), \ + pm_patch("get_battery_status", "Discharging"): + pm = PowerMonitoring() + pm.car_battery_capacity_uWh = CAR_BATTERY_CAPACITY_uWh + health = self.mock_health(True, log.HealthData.HwType.uno, car_voltage=(VBATT_PAUSE_CHARGING - 1)) + for i in range(TEST_TIME): + pm.calculate(health) + if i % 10 == 0: + self.assertFalse(pm.should_disable_charging(health, ssb)) + self.assertFalse(pm.should_disable_charging(health, ssb)) + +if __name__ == "__main__": + unittest.main() diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 093b832da0..1a856e0494 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -144,9 +144,6 @@ def handle_fan_uno(max_cpu_temp, bat_temp, fan_speed, ignition): def thermald_thread(): - # prevent LEECO from undervoltage - BATT_PERC_OFF = 10 if LEON else 3 - health_timeout = int(1000 * 2.5 * DT_TRML) # 2.5x the expected health frequency # now loop @@ -402,15 +399,17 @@ def thermald_thread(): off_ts = sec_since_boot() os.system('echo powersave > /sys/class/devfreq/soc:qcom,cpubw/governor') - # shutdown if the battery gets lower than 3%, it's discharging, we aren't running for - # more than a minute but we were running - if msg.thermal.batteryPercent < BATT_PERC_OFF and msg.thermal.batteryStatus == "Discharging" and \ - started_seen and (sec_since_boot() - off_ts) > 60: - os.system('LD_LIBRARY_PATH="" svc power shutdown') - # Offroad power monitoring pm.calculate(health) msg.thermal.offroadPowerUsage = pm.get_power_used() + msg.thermal.carBatteryCapacity = pm.get_car_battery_capacity() + + # Check if we need to disable charging (handled by boardd) + msg.thermal.chargingDisabled = pm.should_disable_charging(health, off_ts) + + # Check if we need to shut down + if pm.should_shutdown(health, off_ts, started_seen, LEON): + os.system('LD_LIBRARY_PATH="" svc power shutdown') msg.thermal.chargingError = current_filter.x > 0. and msg.thermal.batteryPercent < 90 # if current is positive, then battery is being discharged msg.thermal.started = started_ts is not None From 934506e1545acd30bf65e9544e565005d6c56fc6 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 17 Aug 2020 17:59:27 +0800 Subject: [PATCH 632/656] fix two little bugs (#2033) --- selfdrive/ui/paint.cc | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index dbddd50149..baa9dd042b 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -187,6 +187,9 @@ static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) vec4 p_car_space = (vec4){{px, py, 0., 1.}}; vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + if (p_full_frame.v[0] < 0. || p_full_frame.v[1] < 0.) { + continue; + } pvd->v[pvd->cnt].x = p_full_frame.v[0]; pvd->v[pvd->cnt].y = p_full_frame.v[1]; pvd->cnt += 1; @@ -286,7 +289,7 @@ static void update_lane_line_data(UIState *s, const float *points, float off, mo pvd->v[pvd->cnt].y = p_full_frame.v[1]; pvd->cnt += 1; } - for (int i = rcount; i > 0; i--) { + for (int i = rcount - 1; i > 0; i--) { float px = (float)i; float py = points[i] + off; const vec4 p_car_space = (vec4){{px, py, 0., 1.}}; From fe43d51686da19063c4ee3ebdb09eadfdd3a56ad Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 17 Aug 2020 18:06:09 +0800 Subject: [PATCH 633/656] paint.cc: remove redundant calls (#2025) * remove redundant calls * set MODEL_LANE_PATH_CNT=2 --- selfdrive/ui/paint.cc | 4 +--- selfdrive/ui/ui.hpp | 2 +- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index baa9dd042b..6dca88f5e6 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -305,15 +305,13 @@ static void update_lane_line_data(UIState *s, const float *points, float off, mo static void update_all_lane_lines_data(UIState *s, const PathData &path, model_path_vertices_data *pstart) { update_lane_line_data(s, path.points, 0.025*path.prob, pstart, path.validLen); float var = fmin(path.std, 0.7); - update_lane_line_data(s, path.points, -var, pstart + 1, path.validLen); - update_lane_line_data(s, path.points, var, pstart + 2, path.validLen); + update_lane_line_data(s, path.points, var, pstart + 1, path.validLen); } static void ui_draw_lane(UIState *s, const PathData *path, model_path_vertices_data *pstart, NVGcolor color) { ui_draw_lane_line(s, pstart, color); color.a /= 25; ui_draw_lane_line(s, pstart + 1, color); - ui_draw_lane_line(s, pstart + 2, color); } static void ui_draw_vision_lanes(UIState *s) { diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index bf64ef27aa..24a982db17 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -75,7 +75,7 @@ const int home_btn_y = vwp_h - home_btn_h - 40; const int UI_FREQ = 30; // Hz const int MODEL_PATH_MAX_VERTICES_CNT = 98; -const int MODEL_LANE_PATH_CNT = 3; +const int MODEL_LANE_PATH_CNT = 2; const int TRACK_POINTS_MAX_CNT = 50 * 2; const int SET_SPEED_NA = 255; From c624b408428c09723eb8d02f19a6051f325b7187 Mon Sep 17 00:00:00 2001 From: robbederks Date: Mon, 17 Aug 2020 13:02:06 +0200 Subject: [PATCH 634/656] more panda fault types (#2036) --- cereal | 2 +- selfdrive/boardd/boardd.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 0d2ce45fc6..50d3751489 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 0d2ce45fc681f90b33fbcd11e5d80dd294ef751b +Subproject commit 50d37514897c07ae605691ee602ad6a01b51b890 diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 1c83abf292..146e219f90 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -376,7 +376,7 @@ void can_health_thread() { size_t i = 0; for (size_t f = size_t(cereal::HealthData::FaultType::RELAY_MALFUNCTION); - f <= size_t(cereal::HealthData::FaultType::INTERRUPT_RATE_KLINE_INIT); f++){ + f <= size_t(cereal::HealthData::FaultType::INTERRUPT_RATE_TIM9); f++){ if (fault_bits.test(f)) { faults.set(i, cereal::HealthData::FaultType(f)); i++; From 86dc54b836a973f132ed26db9f5a60b29f9b25b2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 17 Aug 2020 12:49:08 -0700 Subject: [PATCH 635/656] bump version to 0.7.9 --- RELEASES.md | 4 ++++ selfdrive/common/version.h | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 0c6dd3d4fb..3709d0f222 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,7 @@ +Version 0.7.9 (2020-XX-XX) +======================== + * Improved car battery power management + Version 0.7.8 (2020-08-19) ======================== * New driver monitoring model: improved face detection and better compatibility with sunglasses diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index ad6f4b6d7a..718297f674 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.7.8" +#define COMMA_VERSION "0.7.9" From 21a1792f895e006fd70883b5621989e01b539693 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 17 Aug 2020 16:21:55 -0700 Subject: [PATCH 636/656] remove dead code in updated --- selfdrive/updated.py | 9 --------- 1 file changed, 9 deletions(-) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 2059068067..2747e5753a 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -31,7 +31,6 @@ import signal import fcntl import time import threading -from cffi import FFI from pathlib import Path from common.basedir import BASEDIR @@ -52,14 +51,6 @@ OVERLAY_MERGED = os.path.join(STAGING_ROOT, "merged") FINALIZED = os.path.join(STAGING_ROOT, "finalized") -# Workaround for lack of os.link in the NEOS/termux python -ffi = FFI() -ffi.cdef("int link(const char *oldpath, const char *newpath);") -libc = ffi.dlopen(None) -def link(src, dest): - return libc.link(src.encode(), dest.encode()) - - class WaitTimeHelper: def __init__(self, proc): self.proc = proc From 744fe7180187507f9dc8d455b961f882992d0684 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 18 Aug 2020 06:21:47 -0700 Subject: [PATCH 637/656] remove old tests (#2040) --- selfdrive/test/leeco_selftest.sh | 124 --------------------------- selfdrive/test/test_eon_fan.py | 20 ----- selfdrive/test/test_leeco_alt_fan.py | 22 ----- selfdrive/test/test_leeco_fan.py | 24 ------ 4 files changed, 190 deletions(-) delete mode 100755 selfdrive/test/leeco_selftest.sh delete mode 100755 selfdrive/test/test_eon_fan.py delete mode 100755 selfdrive/test/test_leeco_alt_fan.py delete mode 100755 selfdrive/test/test_leeco_fan.py diff --git a/selfdrive/test/leeco_selftest.sh b/selfdrive/test/leeco_selftest.sh deleted file mode 100755 index 27b43a914f..0000000000 --- a/selfdrive/test/leeco_selftest.sh +++ /dev/null @@ -1,124 +0,0 @@ -#!/usr/bin/bash - -HOME=~/one - -if [ ! -d $HOME ]; then - HOME=/data/chffrplus -fi - -camera_test () { - printf "Running camera test...\n" - - cd $HOME/selfdrive/visiond - - if [ ! -e visiond ]; then - make > /dev/null - fi - - CAMERA_TEST=1 ./visiond > /dev/null - V4L_SUBDEVS=$(find -L /sys/class/video4linux/v4l-subdev* -maxdepth 1 -name name -exec cat {} \;) - CAMERA_COUNT=0 - for SUBDEV in $V4L_SUBDEVS; do - if [ "$SUBDEV" == "imx298" ] || [ "$SUBDEV" == "ov8865_sunny" ]; then - CAMERA_COUNT=$((CAMERA_COUNT + 1)) - fi - done - - if [ "$CAMERA_COUNT" == "2" ]; then - printf "Camera test: SUCCESS!\n" - else - printf "One or more cameras are missing! Camera count: $CAMERA_COUNT\n" - exit 1 - fi -} - -sensor_test () { - printf "Running sensor test...\n" - - cd $HOME/selfdrive/sensord - - if [ ! -e sensord ]; then - make > /dev/null - fi - - SENSOR_TEST=1 LD_LIBRARY_PATH=/system/lib64:$LD_LIBRARY_PATH ./sensord - SENSOR_COUNT=$? - - if [ "$SENSOR_COUNT" == "40" ]; then - printf "Sensor test: SUCCESS!\n" - else - printf "One or more sensors are missing! Sensor count: $SENSOR_COUNT, expected 40\n" - exit 1 - fi -} - -wifi_test () { - printf "Running WiFi test...\n" - - su -c 'svc wifi enable' - WIFI_STATUS=$(getprop wlan.driver.status) - - if [ "$WIFI_STATUS" == "ok" ]; then - printf "WiFi test: SUCCESS!\n" - else - printf "WiFi isn't working! Driver status: $WIFI_STATUS\n" - exit 1 - fi -} - -modem_test () { - printf "Running modem test...\n" - - BASEBAND_VERSION=$(getprop gsm.version.baseband | awk '{print $1}') - - if [ "$BASEBAND_VERSION" == "MPSS.TH.2.0.c1.9.1-00010" ]; then - printf "Modem test: SUCCESS!\n" - else - printf "Modem isn't working! Detected baseband version: $BASEBAND_VERSION\n" - exit 1 - fi -} - -fan_test () { - printf "Running fan test...\n" - - i2cget -f -y 7 0x67 0 1>/dev/null 2>&1 - IS_NORMAL_LEECO=$? - - if [ "$IS_NORMAL_LEECO" == "0" ]; then - /tmp/test_leeco_alt_fan.py > /dev/null - else - /tmp/test_leeco_fan.py > /dev/null - fi - - printf "Fan test: the fan should now be running at full speed, press Y or N\n" - - read -p "Is the fan running [Y/n]?\n" fan_running - case $fan_running in - [Nn]* ) - printf "Fan isn't working! (user says it isn't working)\n" - exit 1 - ;; - esac - - printf "Turning off the fan ...\n" - if [ "$IS_NORMAL_LEECO" == "0" ]; then - i2cset -f -y 7 0x67 0xa 0 - else - i2cset -f -y 7 0x3d 0 0x1 - fi -} - -camera_test -printf "\n" - -sensor_test -printf "\n" - -wifi_test -printf "\n" - -modem_test -printf "\n" - -fan_test diff --git a/selfdrive/test/test_eon_fan.py b/selfdrive/test/test_eon_fan.py deleted file mode 100755 index c7e435741b..0000000000 --- a/selfdrive/test/test_eon_fan.py +++ /dev/null @@ -1,20 +0,0 @@ -#!/usr/bin/env python3 - -import sys -import time -from selfdrive.thermald.thermald import setup_eon_fan, set_eon_fan - -if __name__ == "__main__": - val = 0 - setup_eon_fan() - - if len(sys.argv) > 1: - set_eon_fan(int(sys.argv[1])) - exit(0) - - while True: - sys.stderr.write("setting fan to %d\n" % val) - set_eon_fan(val) - time.sleep(2) - val += 1 - val %= 4 diff --git a/selfdrive/test/test_leeco_alt_fan.py b/selfdrive/test/test_leeco_alt_fan.py deleted file mode 100755 index 0a51e94064..0000000000 --- a/selfdrive/test/test_leeco_alt_fan.py +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env python3 -# pylint: skip-file - -import time -from smbus2 import SMBus - -def setup_leon_fan(): - bus = SMBus(7, force=True) - - # http://www.ti.com/lit/ds/symlink/tusb320.pdf - for i in [0, 1, 2, 3]: - print("FAN SPEED", i) - if i == 0: - bus.write_i2c_block_data(0x67, 0xa, [0]) - else: - bus.write_i2c_block_data(0x67, 0xa, [0x20]) - bus.write_i2c_block_data(0x67, 0x8, [(i - 1) << 6]) - time.sleep(1) - - bus.close() - -setup_leon_fan() diff --git a/selfdrive/test/test_leeco_fan.py b/selfdrive/test/test_leeco_fan.py deleted file mode 100755 index 55267285ba..0000000000 --- a/selfdrive/test/test_leeco_fan.py +++ /dev/null @@ -1,24 +0,0 @@ -#!/usr/bin/env python3 -# pylint: skip-file - -import time -from smbus2 import SMBus - -def setup_leon_fan(): - bus = SMBus(7, force=True) - - # https://www.nxp.com/docs/en/data-sheet/PTN5150.pdf - j = 0 - for i in [0x1, 0x3 | 0, 0x3 | 0x08, 0x3 | 0x10]: - print("FAN SPEED", j) - ret = bus.read_i2c_block_data(0x3d, 0, 4) - print(ret) - ret = bus.write_i2c_block_data(0x3d, 0, [i]) - time.sleep(1) - ret = bus.read_i2c_block_data(0x3d, 0, 4) - print(ret) - j += 1 - - bus.close() - -setup_leon_fan() From 963c00db09554e71264b699a99c9a705c80c99d8 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Aug 2020 21:22:26 +0800 Subject: [PATCH 638/656] fd should be initialized as -1 (#2041) --- selfdrive/common/gpio.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/common/gpio.cc b/selfdrive/common/gpio.cc index 7b080b0c50..fd68bcd523 100644 --- a/selfdrive/common/gpio.cc +++ b/selfdrive/common/gpio.cc @@ -8,7 +8,7 @@ int gpio_init(int pin_nr, bool output){ int ret = 0; - int fd, tmp; + int fd = -1, tmp; char pin_dir_path[50]; int pin_dir_path_len = snprintf(pin_dir_path, sizeof(pin_dir_path), @@ -46,7 +46,7 @@ cleanup: int gpio_set(int pin_nr, bool high){ int ret = 0; - int fd, tmp; + int fd = -1, tmp; char pin_val_path[50]; int pin_val_path_len = snprintf(pin_val_path, sizeof(pin_val_path), From f8ab6bd009410a9f7ab9c30ce7b72a82c6d2507b Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Aug 2020 21:26:43 +0800 Subject: [PATCH 639/656] ui: refactor model related functions (#2026) * remove read_model * remove structs for c-capnp * remove duplicate #define from modeld * add function fill_path_points * fix Indentation * use MODEL_PATH_DISTANCE instead of 192 * fix type use validLen * rename left_path_points&right_path_points to xxx_lane_points --- selfdrive/common/modeldata.h | 36 +------------------------ selfdrive/modeld/models/driving.cc | 4 +-- selfdrive/modeld/models/driving.h | 6 +---- selfdrive/ui/paint.cc | 31 ++++++++++------------ selfdrive/ui/ui.cc | 42 ++++++++---------------------- selfdrive/ui/ui.hpp | 6 +++-- 6 files changed, 33 insertions(+), 92 deletions(-) diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h index 111e20a413..77f4a1b7a1 100644 --- a/selfdrive/common/modeldata.h +++ b/selfdrive/common/modeldata.h @@ -1,41 +1,7 @@ -#ifndef MODELDATA_H -#define MODELDATA_H +#pragma once #define MODEL_PATH_DISTANCE 192 #define POLYFIT_DEGREE 4 #define SPEED_PERCENTILES 10 #define DESIRE_PRED_SIZE 32 #define OTHER_META_SIZE 4 - -typedef struct PathData { - float points[MODEL_PATH_DISTANCE]; - float prob; - float std; - float stds[MODEL_PATH_DISTANCE]; - float poly[POLYFIT_DEGREE]; - float validLen; -} PathData; - -typedef struct LeadData { - float dist; - float prob; - float std; - float rel_y; - float rel_y_std; - float rel_v; - float rel_v_std; - float rel_a; - float rel_a_std; -} LeadData; - -typedef struct ModelData { - PathData path; - PathData left_lane; - PathData right_lane; - LeadData lead; - LeadData lead_future; - float meta[OTHER_META_SIZE + DESIRE_PRED_SIZE]; - float speed[SPEED_PERCENTILES]; -} ModelData; - -#endif diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index f58e7b1964..71e4fcae3a 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -162,8 +162,8 @@ void fill_path(cereal::ModelData::PathData::Builder path, const float * data, bo float prob; float valid_len; - // clamp to 5 and 192 - valid_len = fmin(192, fmax(5, data[MODEL_PATH_DISTANCE*2])); + // clamp to 5 and MODEL_PATH_DISTANCE + valid_len = fmin(MODEL_PATH_DISTANCE, fmax(5, data[MODEL_PATH_DISTANCE*2])); for (int i=0; iscene; - const PathData path = scene->model.path; + const float *points = scene->path_points; const float *mpc_x_coords = &scene->mpc_x[0]; const float *mpc_y_coords = &scene->mpc_y[0]; @@ -150,6 +150,7 @@ static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) float lead_d = scene->lead_data[0].getDRel()*2.; float path_height = is_mpc?(lead_d>5.)?fmin(lead_d, 25.)-fmin(lead_d*0.35, 10.):20. :(lead_d>0.)?fmin(lead_d, 50.)-fmin(lead_d*0.35, 10.):49.; + path_height = fmin(path_height, scene->model.getPath().getValidLen()); pvd->cnt = 0; // left side up for (int i=0; i<=path_height; i++) { @@ -160,7 +161,7 @@ static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) py = mpc_y_coords[i] - off; } else { px = lerp(i+1.0, i, i/100.0); - py = path.points[i] - off; + py = points[i] - off; } vec4 p_car_space = (vec4){{px, py, 0., 1.}}; @@ -182,7 +183,7 @@ static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) py = mpc_y_coords[i] + off; } else { px = lerp(i+1.0, i, i/100.0); - py = path.points[i] + off; + py = points[i] + off; } vec4 p_car_space = (vec4){{px, py, 0., 1.}}; @@ -207,7 +208,6 @@ static void update_all_track_data(UIState *s) { } } - static void ui_draw_track(UIState *s, bool is_mpc, track_vertices_data *pvd) { if (pvd->cnt == 0) return; @@ -302,13 +302,12 @@ static void update_lane_line_data(UIState *s, const float *points, float off, mo } } -static void update_all_lane_lines_data(UIState *s, const PathData &path, model_path_vertices_data *pstart) { - update_lane_line_data(s, path.points, 0.025*path.prob, pstart, path.validLen); - float var = fmin(path.std, 0.7); - update_lane_line_data(s, path.points, var, pstart + 1, path.validLen); +static void update_all_lane_lines_data(UIState *s, const cereal::ModelData::PathData::Reader &path, const float *points, model_path_vertices_data *pstart) { + update_lane_line_data(s, points, 0.025*path.getProb(), pstart, path.getValidLen()); + update_lane_line_data(s, points, fmin(path.getStd(), 0.7), pstart + 1, path.getValidLen()); } -static void ui_draw_lane(UIState *s, const PathData *path, model_path_vertices_data *pstart, NVGcolor color) { +static void ui_draw_lane(UIState *s, model_path_vertices_data *pstart, NVGcolor color) { ui_draw_lane_line(s, pstart, color); color.a /= 25; ui_draw_lane_line(s, pstart + 1, color); @@ -318,20 +317,18 @@ static void ui_draw_vision_lanes(UIState *s) { const UIScene *scene = &s->scene; model_path_vertices_data *pvd = &s->model_path_vertices[0]; if(s->sm->updated("model")) { - update_all_lane_lines_data(s, scene->model.left_lane, pvd); - update_all_lane_lines_data(s, scene->model.right_lane, pvd + MODEL_LANE_PATH_CNT); + update_all_lane_lines_data(s, scene->model.getLeftLane(), scene->left_lane_points, pvd); + update_all_lane_lines_data(s, scene->model.getRightLane(), scene->right_lane_points, pvd + MODEL_LANE_PATH_CNT); } // Draw left lane edge ui_draw_lane( - s, &scene->model.left_lane, - pvd, - nvgRGBAf(1.0, 1.0, 1.0, scene->model.left_lane.prob)); + s, pvd, + nvgRGBAf(1.0, 1.0, 1.0, scene->model.getLeftLane().getProb())); // Draw right lane edge ui_draw_lane( - s, &scene->model.right_lane, - pvd + MODEL_LANE_PATH_CNT, - nvgRGBAf(1.0, 1.0, 1.0, scene->model.right_lane.prob)); + s, pvd + MODEL_LANE_PATH_CNT, + nvgRGBAf(1.0, 1.0, 1.0, scene->model.getRightLane().getProb())); if(s->sm->updated("radarState")) { update_all_track_data(s); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index b8edfc4e2e..5eb00a2edb 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -227,42 +227,19 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, s->limit_set_speed_timeout = UI_FREQ; } -static void read_path(PathData& p, const cereal::ModelData::PathData::Reader &pathp) { - p = {}; - - p.prob = pathp.getProb(); - p.std = pathp.getStd(); - - auto polyp = pathp.getPoly(); - for (int i = 0; i < POLYFIT_DEGREE; i++) { - p.poly[i] = polyp[i]; - } - - // Compute points locations - for (int i = 0; i < MODEL_PATH_DISTANCE; i++) { - p.points[i] = p.poly[0] * (i*i*i) + p.poly[1] * (i*i)+ p.poly[2] * i + p.poly[3]; - } - - p.validLen = pathp.getValidLen(); -} - -static void read_model(ModelData &d, const cereal::ModelData::Reader &model) { - d = {}; - read_path(d.path, model.getPath()); - read_path(d.left_lane, model.getLeftLane()); - read_path(d.right_lane, model.getRightLane()); - auto leadd = model.getLead(); - d.lead = (LeadData){ - .dist = leadd.getDist(), .prob = leadd.getProb(), .std = leadd.getStd(), - }; -} - static void update_status(UIState *s, int status) { if (s->status != status) { s->status = status; } } +static inline void fill_path_points(const cereal::ModelData::PathData::Reader &path, float *points) { + const capnp::List::Reader &poly = path.getPoly(); + for (int i = 0; i < path.getValidLen(); i++) { + points[i] = poly[0] * (i * i * i) + poly[1] * (i * i) + poly[2] * i + poly[3]; + } +} + void handle_message(UIState *s, SubMaster &sm) { UIScene &scene = s->scene; if (s->started && sm.updated("controlsState")) { @@ -323,7 +300,10 @@ void handle_message(UIState *s, SubMaster &sm) { } } if (sm.updated("model")) { - read_model(scene.model, sm["model"].getModel()); + scene.model = sm["model"].getModel(); + fill_path_points(scene.model.getPath(), scene.path_points); + fill_path_points(scene.model.getLeftLane(), scene.left_lane_points); + fill_path_points(scene.model.getRightLane(), scene.right_lane_points); } // else if (which == cereal::Event::LIVE_MPC) { // auto data = event.getLiveMpc(); diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 24a982db17..2d6d9ddc06 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -92,8 +92,6 @@ typedef struct UIScene { int frontview; int fullview; - ModelData model; - float mpc_x[50]; float mpc_y[50]; @@ -126,6 +124,10 @@ typedef struct UIScene { cereal::ControlsState::Reader controls_state; cereal::DriverState::Reader driver_state; cereal::DMonitoringState::Reader dmonitoring_state; + cereal::ModelData::Reader model; + float left_lane_points[MODEL_PATH_DISTANCE]; + float path_points[MODEL_PATH_DISTANCE]; + float right_lane_points[MODEL_PATH_DISTANCE]; } UIScene; typedef struct { From a46d2f5b17cc24102f26674a2102a0044b3e84e6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 18 Aug 2020 07:43:58 -0700 Subject: [PATCH 640/656] log when thermald shuts down device --- selfdrive/thermald/thermald.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 1a856e0494..3a72387d44 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -409,6 +409,7 @@ def thermald_thread(): # Check if we need to shut down if pm.should_shutdown(health, off_ts, started_seen, LEON): + cloudlog.info(f"shutting device down, offroad for {off_ts}") os.system('LD_LIBRARY_PATH="" svc power shutdown') msg.thermal.chargingError = current_filter.x > 0. and msg.thermal.batteryPercent < 90 # if current is positive, then battery is being discharged From 266ef886dd778cc7d486349b72279c89c03dad06 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 18 Aug 2020 11:52:01 -0700 Subject: [PATCH 641/656] add a sleep after cloudlog --- selfdrive/thermald/thermald.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 3a72387d44..b17bd72f29 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -2,6 +2,7 @@ import os import datetime import psutil +import time from smbus2 import SMBus from cereal import log from common.android import ANDROID, get_network_type, get_network_strength @@ -409,7 +410,9 @@ def thermald_thread(): # Check if we need to shut down if pm.should_shutdown(health, off_ts, started_seen, LEON): - cloudlog.info(f"shutting device down, offroad for {off_ts}") + cloudlog.info(f"shutting device down, offroad since {off_ts}") + # TODO: add function for blocking cloudlog instead of sleep + time.sleep(10) os.system('LD_LIBRARY_PATH="" svc power shutdown') msg.thermal.chargingError = current_filter.x > 0. and msg.thermal.batteryPercent < 90 # if current is positive, then battery is being discharged From 2476ea213c24dac16531c8798761e34f96e0ded2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 19 Aug 2020 12:34:49 -0700 Subject: [PATCH 642/656] clip carBatteryCapacity to 0 --- selfdrive/thermald/thermald.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index b17bd72f29..d70625c792 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -403,7 +403,7 @@ def thermald_thread(): # Offroad power monitoring pm.calculate(health) msg.thermal.offroadPowerUsage = pm.get_power_used() - msg.thermal.carBatteryCapacity = pm.get_car_battery_capacity() + msg.thermal.carBatteryCapacity = max(0, pm.get_car_battery_capacity()) # Check if we need to disable charging (handled by boardd) msg.thermal.chargingDisabled = pm.should_disable_charging(health, off_ts) From 03ec6af300d1d051436514b194e430fb54d16c6c Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 20 Aug 2020 15:20:55 +0200 Subject: [PATCH 643/656] more init time in cpu test --- selfdrive/test/test_cpu_usage.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_cpu_usage.py b/selfdrive/test/test_cpu_usage.py index 16f205e824..2b76162632 100755 --- a/selfdrive/test/test_cpu_usage.py +++ b/selfdrive/test/test_cpu_usage.py @@ -79,7 +79,7 @@ def test_cpu_usage(): time.sleep(2) # take first sample - time.sleep(5) + time.sleep(30) first_proc = messaging.recv_sock(proc_sock, wait=True) if first_proc is None: raise Exception("\n\nTEST FAILED: progLog recv timed out\n\n") From e115c514521c7705112bd0cb2e4bf865b536501a Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 20 Aug 2020 17:16:44 +0200 Subject: [PATCH 644/656] Qt ui for PC (#2023) * qt ui boilerplate * this kinda works * cleanup * render inside other widget * cleanup * more cleanup * Not needed * Handle click * Draw at 20Hz * create paint.hpp * move stuff around * update sidebar * Draw vision * this works again * add clickable settings button * Only collapse sidebar when started * always use qt on linux * fix width * scrollable area * talk to NetworkManager * code to add a connection * params toggles * small cleanup * add qt5 to dockerfile * Qt on mac * Add qt to release files * fix macos build * nore more ifdefs needed * add icons * make a bit nicer * Hide scrollbar Co-authored-by: Comma Device --- Dockerfile.openpilot | 1 + SConstruct | 50 +- release/files_common | 3 + .../assets/offroad/circled-checkmark.png | Bin 0 -> 2236 bytes selfdrive/assets/offroad/icon_app_store.png | Bin 0 -> 12277 bytes selfdrive/assets/offroad/icon_calibration.png | Bin 0 -> 8910 bytes selfdrive/assets/offroad/icon_checkmark.png | Bin 0 -> 4471 bytes .../assets/offroad/icon_chevron_right.png | Bin 0 -> 1420 bytes selfdrive/assets/offroad/icon_connect_app.png | Bin 0 -> 24265 bytes selfdrive/assets/offroad/icon_eon.png | Bin 0 -> 8624 bytes selfdrive/assets/offroad/icon_map.png | Bin 0 -> 28235 bytes selfdrive/assets/offroad/icon_map_speed.png | Bin 0 -> 29822 bytes selfdrive/assets/offroad/icon_menu.png | Bin 0 -> 635 bytes selfdrive/assets/offroad/icon_metric.png | Bin 0 -> 604 bytes selfdrive/assets/offroad/icon_minus.png | Bin 0 -> 2577 bytes selfdrive/assets/offroad/icon_monitoring.png | Bin 0 -> 58679 bytes selfdrive/assets/offroad/icon_network.png | Bin 0 -> 39872 bytes selfdrive/assets/offroad/icon_openpilot.png | Bin 0 -> 42640 bytes .../offroad/icon_openpilot_mirrored.png | Bin 0 -> 18150 bytes selfdrive/assets/offroad/icon_play_store.png | Bin 0 -> 14623 bytes selfdrive/assets/offroad/icon_plus.png | Bin 0 -> 2833 bytes selfdrive/assets/offroad/icon_road.png | Bin 0 -> 6674 bytes selfdrive/assets/offroad/icon_settings.png | Bin 0 -> 13369 bytes selfdrive/assets/offroad/icon_shell.png | Bin 0 -> 42462 bytes selfdrive/assets/offroad/icon_speed_limit.png | Bin 0 -> 3321 bytes selfdrive/assets/offroad/icon_user.png | Bin 0 -> 15798 bytes selfdrive/assets/offroad/icon_warning.png | Bin 0 -> 8002 bytes .../assets/offroad/illustration_arrow.png | Bin 0 -> 1265 bytes .../offroad/illustration_sim_absent.png | Bin 0 -> 6608 bytes .../offroad/illustration_sim_present.png | Bin 0 -> 6331 bytes .../offroad/illustration_training_lane_01.png | Bin 0 -> 268080 bytes .../offroad/illustration_training_lane_02.png | Bin 0 -> 69907 bytes .../offroad/illustration_training_lead_01.png | Bin 0 -> 1515 bytes .../offroad/illustration_training_lead_02.png | Bin 0 -> 2054 bytes selfdrive/assets/offroad/indicator_wifi_0.png | Bin 0 -> 3038 bytes .../assets/offroad/indicator_wifi_100.png | Bin 0 -> 3270 bytes .../assets/offroad/indicator_wifi_25.png | Bin 0 -> 3087 bytes .../assets/offroad/indicator_wifi_50.png | Bin 0 -> 3121 bytes .../assets/offroad/indicator_wifi_75.png | Bin 0 -> 3186 bytes selfdrive/ui/.gitignore | 1 + selfdrive/ui/SConscript | 25 +- selfdrive/ui/android_ui.cc | 360 +++++++++++++++ selfdrive/ui/linux.cc | 107 ----- selfdrive/ui/paint.cc | 16 +- selfdrive/ui/paint.hpp | 11 + selfdrive/ui/qt/settings.cc | 140 ++++++ selfdrive/ui/qt/settings.hpp | 28 ++ selfdrive/ui/qt/ui.cc | 15 + selfdrive/ui/qt/wifi.cc | 69 +++ selfdrive/ui/qt/window.cc | 143 ++++++ selfdrive/ui/qt/window.hpp | 55 +++ selfdrive/ui/sidebar.cc | 4 +- selfdrive/ui/sidebar.hpp | 4 + selfdrive/ui/ui.cc | 430 +----------------- selfdrive/ui/ui.hpp | 67 ++- tools/mac_setup.sh | 1 + tools/ubuntu_setup.sh | 1 + 57 files changed, 987 insertions(+), 544 deletions(-) create mode 100644 selfdrive/assets/offroad/circled-checkmark.png create mode 100644 selfdrive/assets/offroad/icon_app_store.png create mode 100644 selfdrive/assets/offroad/icon_calibration.png create mode 100644 selfdrive/assets/offroad/icon_checkmark.png create mode 100644 selfdrive/assets/offroad/icon_chevron_right.png create mode 100644 selfdrive/assets/offroad/icon_connect_app.png create mode 100644 selfdrive/assets/offroad/icon_eon.png create mode 100644 selfdrive/assets/offroad/icon_map.png create mode 100644 selfdrive/assets/offroad/icon_map_speed.png create mode 100644 selfdrive/assets/offroad/icon_menu.png create mode 100644 selfdrive/assets/offroad/icon_metric.png create mode 100644 selfdrive/assets/offroad/icon_minus.png create mode 100644 selfdrive/assets/offroad/icon_monitoring.png create mode 100644 selfdrive/assets/offroad/icon_network.png create mode 100644 selfdrive/assets/offroad/icon_openpilot.png create mode 100644 selfdrive/assets/offroad/icon_openpilot_mirrored.png create mode 100644 selfdrive/assets/offroad/icon_play_store.png create mode 100644 selfdrive/assets/offroad/icon_plus.png create mode 100644 selfdrive/assets/offroad/icon_road.png create mode 100644 selfdrive/assets/offroad/icon_settings.png create mode 100644 selfdrive/assets/offroad/icon_shell.png create mode 100644 selfdrive/assets/offroad/icon_speed_limit.png create mode 100644 selfdrive/assets/offroad/icon_user.png create mode 100644 selfdrive/assets/offroad/icon_warning.png create mode 100644 selfdrive/assets/offroad/illustration_arrow.png create mode 100644 selfdrive/assets/offroad/illustration_sim_absent.png create mode 100644 selfdrive/assets/offroad/illustration_sim_present.png create mode 100644 selfdrive/assets/offroad/illustration_training_lane_01.png create mode 100644 selfdrive/assets/offroad/illustration_training_lane_02.png create mode 100644 selfdrive/assets/offroad/illustration_training_lead_01.png create mode 100644 selfdrive/assets/offroad/illustration_training_lead_02.png create mode 100644 selfdrive/assets/offroad/indicator_wifi_0.png create mode 100644 selfdrive/assets/offroad/indicator_wifi_100.png create mode 100644 selfdrive/assets/offroad/indicator_wifi_25.png create mode 100644 selfdrive/assets/offroad/indicator_wifi_50.png create mode 100644 selfdrive/assets/offroad/indicator_wifi_75.png create mode 100644 selfdrive/ui/.gitignore create mode 100644 selfdrive/ui/android_ui.cc delete mode 100644 selfdrive/ui/linux.cc create mode 100644 selfdrive/ui/paint.hpp create mode 100644 selfdrive/ui/qt/settings.cc create mode 100644 selfdrive/ui/qt/settings.hpp create mode 100644 selfdrive/ui/qt/ui.cc create mode 100644 selfdrive/ui/qt/wifi.cc create mode 100644 selfdrive/ui/qt/window.cc create mode 100644 selfdrive/ui/qt/window.hpp create mode 100644 selfdrive/ui/sidebar.hpp diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index aff59903ba..8577282126 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -38,6 +38,7 @@ RUN apt-get update && apt-get install -y --no-install-recommends \ opencl-headers \ python-dev \ python-pip \ + qt5-default \ sudo \ wget \ && rm -rf /var/lib/apt/lists/* diff --git a/SConstruct b/SConstruct index 322bdd5f9f..948708cb81 100644 --- a/SConstruct +++ b/SConstruct @@ -156,6 +156,7 @@ env = Environment( "#selfdrive/camerad/include", "#selfdrive/loggerd/include", "#selfdrive/modeld", + "#selfdrive/ui", "#cereal/messaging", "#cereal", "#opendbc/can", @@ -176,6 +177,52 @@ env = Environment( ] ) +qt_env = None +if arch in ["x86_64", "Darwin", "larch64"]: + qt_env = env.Clone() + + if arch == "larch64": + qt_env['QTDIR'] = "/usr/local/Qt-5.15.0" + QT_BASE = "/usr/local/Qt-5.15.0/" + qt_dirs = [ + QT_BASE + "include/", + QT_BASE + "include/QtWidgets", + QT_BASE + "include/QtGui", + QT_BASE + "include/QtCore", + QT_BASE + "include/QtDBus", + ] + qt_env["RPATH"] += [QT_BASE + "lib"] + if arch == "Darwin": + qt_env['QTDIR'] = "/usr/local/opt/qt" + QT_BASE = "/usr/local/opt/qt/" + qt_dirs = [ + QT_BASE + "include/", + QT_BASE + "include/QtWidgets", + QT_BASE + "include/QtGui", + QT_BASE + "include/QtCore", + QT_BASE + "include/QtDBus", + ] + qt_env["LINKFLAGS"] += ["-F" + QT_BASE + "lib"] + else: + qt_dirs = [ + f"/usr/include/{arch}-linux-gnu/qt5", + f"/usr/include/{arch}-linux-gnu/qt5/QtWidgets", + f"/usr/include/{arch}-linux-gnu/qt5/QtGui", + f"/usr/include/{arch}-linux-gnu/qt5/QtCore", + f"/usr/include/{arch}-linux-gnu/qt5/QtDBus", + ] + + qt_env.Tool('qt') + qt_env['CPPPATH'] += qt_dirs + qt_flags = [ + "-D_REENTRANT", + "-DQT_NO_DEBUG", + "-DQT_WIDGETS_LIB", + "-DQT_GUI_LIB", + "-DQT_CORE_LIB" + ] + qt_env['CXXFLAGS'] += qt_flags + if os.environ.get('SCONS_CACHE'): cache_dir = '/tmp/scons_cache' @@ -214,7 +261,7 @@ def abspath(x): # still needed for apks zmq = 'zmq' -Export('env', 'arch', 'zmq', 'SHARED', 'webcam', 'QCOM_REPLAY') +Export('env', 'qt_env', 'arch', 'zmq', 'SHARED', 'webcam', 'QCOM_REPLAY') # cereal and messaging are shared with the system SConscript(['cereal/SConscript']) @@ -262,6 +309,7 @@ SConscript(['selfdrive/loggerd/SConscript']) SConscript(['selfdrive/locationd/SConscript']) SConscript(['selfdrive/locationd/models/SConscript']) + if arch == "aarch64": SConscript(['selfdrive/logcatd/SConscript']) SConscript(['selfdrive/sensord/SConscript']) diff --git a/release/files_common b/release/files_common index b84e93fbb5..3bff234eab 100644 --- a/release/files_common +++ b/release/files_common @@ -337,6 +337,9 @@ selfdrive/ui/text/Makefile selfdrive/ui/text/text selfdrive/ui/text/text.c +selfdrive/ui/qt/*.cc +selfdrive/ui/qt/*.hpp + selfdrive/camerad/SConscript selfdrive/camerad/main.cc selfdrive/camerad/bufs.h diff --git a/selfdrive/assets/offroad/circled-checkmark.png b/selfdrive/assets/offroad/circled-checkmark.png new file mode 100644 index 0000000000000000000000000000000000000000..bc6b49585d098ca7d82d62a0fb64fa5f3642954c GIT binary patch literal 2236 zcmV;t2t)UYP)+E3`p7_>8uK3-jlRb(hm6oT$lXA1<5bzXmEB^DIUO?~ktk12PjG+?x zM}gHqd&4oHJ0o3`?9;$Cz)1J^`GZic5@WAH^nsVPGAwpbgyS0`~%k z3h>(oe6Vg}^MKcK5*i171k9;dGIQ5MqOn33OH>$u%s3u#W-IGyi~w> zeW?j_lkf99il6dx5B7Bfn1&CP^1OZ9fSy!}9r-4LcYx0(QCb6lE66tkKS7Gw79VoN z@Gs!}1oqVmU=gr8hdtk@s%U`t6u$%ba3b4k2hb0^5wU3$SXNd+FR&}3;GZXw(;CQ} z_h!VloxrRz!oMF8{2yRZ4R*B!_|->j%v)1b=(*UR=uu9D?V1RH&tp3&&4NtLRcT_ zI6Knuf!eH04B+~J4f`Vfeqh*tm{zGreBLvJQDA;;mL>!~xDCZ;Z$V_gmz8;$;(CO7WE&QM)bo3#mn-#!XqFF7_VfmMc#5hiXs0iQ7% z50NlOP#1uUf%gJ7j02bFlyfrhuHlc%B&jQFZv}XR&bg7QhSdrDp#2L;9|$yAfoCsC`gTEin~i79cn)~Wcr`y!P-$BM+-z_^ z0GwSy=3+zUo<^fnjYeZkq5Q#Q03QMN8~kr5DR)L@dkB33mKzQJlG@l*z%R~UFu4D$ zqWr%avX^#A`jF9oM-}BY;~q(&4Trx;`g%qA)=M+LOTOkd1apbfDFC06bVuOvn4}w= zbNef*`M2?`H|Dql6_qCkaGIn?)r<%x<1Xji3kg(NwnrUzFad$octp~ffoIQ2x<8Q~ z>y4cq`maq%0AG{z`M~3SlD_1eJK7E|U9#UQ>uqc+@ENsG)(J_sIOp~xRB2Ui?(b6M zTTV!%H1KQX^^&>+O&)O0J(F0iIrdMJ?YN=`HzY~;8j@A=Gu&g&xvI;y`y_=*EdD6z zn-%4^!fD2{1F-}Ekhna%SAe^6Uhy10Ycm3Nr0WK83wv1ci3!nc)A1u2dp<_jx(uL41drg zgm-`{$DZ=?wm#G2^A`9+vLTF8;(!PKwYN4K-=ArL`S@bR5DJGgCHS6&oshn+vF*3l}uIReZpNoWanUCP_Wv)5?Dc`M2m z-DI6(WnMq7Kx`#;*=Q>qp>84BV0i^{-zn(0ua?zSkk?YG6c%Pe zE{hoRG9^=n_?gxk4kqH4WptF_G#&Uugv*M&!nQ;N6)R&uR(3b=VnqIK>OKnD>j;gVJuCr`0*0$^`hfnVMgt7O2}%vuVf z)PFwk--wOhEhBgqKE|@}CeUAj{9=5S`(b?8acx;y1@$h(AKbI>cgh?|$`mXkehBUj zU}0k0YD4C<*de$PU};rFcSMu`>;V=hvaL4Yx4iNkySy!hG6y`FL)j2;Wdi$Z0dO_( zF%95xQeCToU#!PM6lfkTFO;XK6BIjIK1k~29sV+dS92%_A0%Ixlt4Mo%ZUfK4ZK2K zSE%84G4eWZ9DmGbZY^ZuJRc_i^%<{F*Yz0_NcEBLvu$7)_&M;=T8ZiX{j{~%yBw1- zNV_iU!;g7+CX9&~#qX|OOTuv^~H6xX0FlfMS7zk--?HLpS2CtpF;sG^#c{Z5y^xwT*6^9*^g zQ_^+Lx$PBXqyaulb~h)+#d}kt0_zyyBlE$Ix~DZZ10V0Sf1=?3my1>da1lPYS|mKE zibI*sTFWHb0(|Q6CSVhG#XwmM1J43C(xx%26IXWkNV-V=#A4&h?xL%Uz4BE<&&wau z`<-*{NJ^eDwB2#7fREf8m&DJS@RORM$w5i~kiR7U-A?eFi2niTscqCbm)89N0000< KMNUMnLSTaR3^_Ic literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_app_store.png b/selfdrive/assets/offroad/icon_app_store.png new file mode 100644 index 0000000000000000000000000000000000000000..ae0dd95ceee604d971ef01e037f1f26100b8cc63 GIT binary patch literal 12277 zcmXY%Wmp?sw1sgk(Bj1@6nFRFPH}g4cL-j}hX$9RMT@&@ad&rjcju<}-sk+8%;cFl znUk~k+UwonNHs0T+(`2T#Cr--ZK$1KtVW^JYuG ztmc{&BZI4oHx;K|zlFbl^=g*}r7|*65Z)EH0s3)V*i$S#)e#8-%&5stT5Z#hJER|f z3@%7~4u7vZ3Vu8UU>jl>B{s(n!sBX@z1$YR&r{5!Qchfe_a*_Z4a*Y;nFvV3eBc4GK(hk^TPmTchOtuWH8xN+Fm`^HYj z%`Z)_*CTSy;&rc)hVR!YFH|i4uU;G2l$EyV$Cye0ris>#H-|9S^X3B|0#`Ws5UEc3c2R))dAvrPYC7##637J^pyNw(EtzyeYA!wqz zdhaTv4|~i3yq%Dl0JprDnl^(W=RmcPr@y$3AjKIsGq+ueGU+SgU+^8X)HrL=iy32o z#$C4eIs~{6=csY`76{mG9bqzzIY_^ON0S#Nejbc66%c{1k*i+~H zWlTcgiHSa`>`qmX&nqIUqI(u)dR%)OJhUu$1CBaB-Y)c0$Dbi9)1;{DKBu0!;T{nu zR8`V8ZTM=ko(p_Tj={!$-!2?|I{FjF4-VF5n4!8K$5zK^LaRR)}dZB zwSvf76Pu2w*TbqSNRH~<*6;-!`LfXYzNfeCg@QQ?mKFU@6Qgv`gCX>ob2HNQcVG*8 zKvoIsD+NrY-Upzo`Ua@Z+YgqTOO*uF!${si4?Rhf)oX*(s zxSi(Ts&6)?NU>GkyboTg9w0dxQu>YIcPO@mqp7!r7Yj7$b)8e!Py@q;TwMh=&+5=v9NEt(^8AlUpZd>m@&OJL_-IB)ZtY=V+VZigujZ^dtp_(vb zoj6r(6SmLgj((++7|MWWy5~$s$mVA{Yr7eD-Id;He%y|%l_K%Zk5wEAp>mp%a1f7c zzsbCC+xtwN;7oKe?6fiUxJwO48%t%)6IL8)xtrJ3C+RkP8rH0#014Ct9$-=ck}6qF zh7?2&B|pxz-qE;MC%59MNW(>iwsQ(9rq>{EUd|a@curtjrrcG{QAP?p>J+R{aE*&2 zWu(~F=NOMOk~&_te6nU8uRTZ1|X0vfw64Z4VU zRhthX_V$g$NOcT;i?qT8iTwmx={?@gD0&{rF;xFd_rX%qnP+wdgf*`Fob0jPxcfgf zdFzdt>T#o&i5=<^tX6XyrC#|@n_TtardWKt2D!mLe^D0k5VI}Ydka$Yy0*woiW$m4LrkiqY7%irI^;f zPqdAs>^dj->qCru`Fv98$RYK!Q4F1zvUMM9Ta*2|OKo54Gs-%^F;20f8tp6sbk2B> zU(wi4i9K+x%UQVP-AhzWrR1>!BMJzwG5cRd@>+Is{Ae(^@w;CdC>ZJfvvOdHLIrc{ z&9!Wm_qv;)IF6_1^cQ$D#{J-ZH5m7^JBz$E&$hfi8K8Cx3GDoq1^w4@LO(d5FMJkS zGvrz_JV!que#`F+%A! z&+gJA!VfxClWh#K`$Bjo+S~xO^P_s z8Yp&&@(XZuT`!FDUz`q?8<*Evzd}MI@5{@^N7kCxPPF@ytaZ|u`uwrQ2kG57y}?z4 zEP={$Mux^3j0DXR+X#bdya$8mbE?*D>VKuc&?P-<7@y=K^pr75gEfCBx4XC<-Zz@u z?_-Db8XwagiFC7hPxfslu3U@#o+n`ycJN-{pW3~lOkKgYjplWOhHp3?L>!OS%7K+p z8QGq*3>_K5u1A)c?ivoDJl9RR8M9AmBe*tdpFh{#;y(|*J9msQwKmn@W6}~|?o#YF zeBND6nviO-vu+`ezuzNDGfAu(=R5Hd(2cqBWbW#GzpJbdmCqIuOkpnUL8d>op#?iBqj&aQxF{R+OZLpjl#SJb_79KU7I|jU@1CEf_13q3h^g0f`-kw-qGwRYgZ8hFY zG}|L`V1JevStGvNKzF>IIWD|1u2E-sCjGew*ao*xcRMIw@dv{%bQHMX&El9BTFMD z7215q>OS1iDufuJXRA9d7sgHnuls4dn5TfQQIIb94SJIBs2@(WE+kHJG6$GgG8G- zpM1a7i9)N^a%`Vpy$jX1sC!~J5i$)WeVtDMKesC^Rl_x6bJ&ra1mis2lDYRpVODdS z46~50+eEV9#=dv0oG2cx*k!m&5cjbJn!4cQe<8Uw6E!|#>ff9W7EsL!{q^&zw?BhC zNGhM8bmXR~JchV0#~}!VP2a=@s3AMFfr`w)Bu&WmG@J}fNHP>wthrSnDS_KiaT{gO5@xDAEO3mhFX$a6vC}!d9*@jMgUyepEn@avytC=s3h6TApK(Q4A|$8Gw1}EMN*~|V`fda4 zQAP`1_`@s(t|iKypXhrz@XA|n7XblO{0mZH;Z zW`X7C57P9?`pf!%}~d>yC=&iXDl!v+$i)K6E7{9tskVk6DpS&pPT0#@OzN>Y<%5j_~QF z&j$qzuf`WwR=q#3ZVa*U<|mXlEZZX7!+H)8D zMTFrYh#{CyB<~Caln|EmM_k>k~bY6iXWf(9|yFlWEDQk zE?VBF(Y-%H>fom9H1~tUW_e};IG1y0+m=tndL&PF2Y>X-`FDf(M3l|qM^N`~#1K1@ z3>fTYc*?^Vcy2!Tpjn?mbbB)q9y8Hu)osgV>kSeyXBX+)p_KYr@y=uIgitG4FB4tz zA;+P>FX4_%zhK9fBdW@EDY_}n9P0Fm8!ZGXA^OU;nisW^yFU!~Pw7~DGgJ6V?s9js zWbHP<={sDl;{mS%CE*n4{?KwSvwH`eSQSc?kidZVo9r~ALC^Q8*O__h)E8j;PwH%7 z4Ry9$zX8gsf?6z~kowkFLFy?1`N#Kwh!ES61uwyS`x(i!&RW(SlpIY5FZ@P*^5M~` z+FWl=(b*K7_coTyYKDh&lN>n)u++qGFn#u@7A_v%y4uw1e0`cdFf%){L*3}c8MYP0 z4A(F|Y&(KL_Kq(loo!MbUMo}_tIE9b=%Ng|Wn47grPkE7OhX&=iXmF^&YaZW{Zi%?{fT<6#wLSFFWx&24YX!Rtah)$mT>=(>i$$ zOwR(@VwrmfoYbBI5)l4d{{$~riUn9G#(CVOM~g-!%vsEsqy&|E&zg^x=QtBo*ap%F zD!-DntZ@qCi@?e;cNus)=!h_Se!M+YV#gSqAb2k5d)|40@g5#`Ko3_sTxc31J9e;? z3OjR2=GbG~j2c#8_cKPb1_XQXo$k`I7voPiLXaVO;Ss{gSCp1HtD9Z|vXnTS?i!>U z7}zaTlAh>Z_YElWVSk%XlUX4;6j7yv%f_GjZ0EvRG%+jslue@M?0}=pEy*}*J2r4T zOSYBm8X@r9uOarZWhLxzi;yh;rC;!FRyFk61p3U+-e4qbzxqi1E_^Fqk$fIXrg6a( zXQAa#p=z&j>p}t6F0bpy*E4S+9HXTEO|8sRQc^iZXM1LEzsw!2fFx>>_%3Pb&9CP_ zohUzA;%Eeuc=x|o*|j8c?5}kFhaBkJ%{+rO#nF2r6_uoRsg=-GpknMvpyMk{55-hC z5o?*_DZv0c1dx&?^I;X7hw53*V{&KpHmDmXEG%@27uJTEki+%}`B3>$0uuS_Gm#>I zImXI7Gp)e1a^s9l&e%8GnMzyli`*tF{ff%A{8+^p%6alH)x<)DWgAZR4`6G(h0q8j zu{L}UtZve*+GR7yn!W7zFvWK}tB$PuWXm+O`;}TTm@-I2)`-zZz@h;;9u9#CdhH0` z>u+%vWzg)S3L!o#a(+LzNvnth2k~o{=;@OeF+cF4$Pw~dq4;i&jp}T_ z*ISOZCXdFifX5!v`QNvU_D0c;1xXs)42`vobSR!aD!;iqpT^QwQ=B*gAjO0^A}O$n z9=6>Rc^h*RprnB89QC*V-j7tXd_ks<_&@jQtVC~!!aca&$F&MSW-U5V6hGWyeV0sw zD2+-`Le})r4y+=9^AD{Xr;SI!3vUoA)`UK~yti@T=bNPnDf3y-2(b>+>R@DS3CQc<^z}HnCMl^B?`(9aGxfFq&!!UVPK3E{Pn*YmqNZx!BW1ORqjM znYM90_E=9c69=Edy0d8(7@GKZT_Dq6?ek&=ZX7^)YF8<#l7TH46EqyW!Tudt+#fj5!p5(DfDEY&am zv&vF?y7u)+a;o%o$-h2%>k%~UDu0n8h{nM2`V+L`|8l0^QsT5z!704Pz2>HRpjnQX z?11n)5Pas#iA`z}}v zH*XH+3LE_{<`REF0OXPl5fhr0A#OJZZePLG?=K=()i464{hvtZz4QXJRCcU@^U3rr zpNkaI_ouznP8YTzB|?X99H(O=6JeVleD(6lkz6}_UHCoL?#$*8JC!(pBFrAWv}3|j zH90VMA5DMYdP%*mL9aAat<2UU5o6H3Po8Nk#p?G%Gwpu_k@BB@__#d*eE}q_M5jHu z$Bj9iOVny!lgQ;{$Dx_~n%!)agZbRm8qbqFIdF}ygX>9 zoR!{3N?a&iVxPwfE1YvSb^E!~+K$q!Zaz&BgxYK8uFc+v^oWHLfabcGvyWl)-%sgc z0+oe3`Y%2}uq6>yd;D9i>Py>6F_uV&sm`Ue#diRe~C39Ys;3 zn4J|F{!`R1f51I}WjNS`<8LR#pIA%f$hY3>PQA{JWO8Bt%x$Y3) z6|Lsd(TY+vn927p(TU1Ys#b!%APlhC#E> z0xl}}!SQL@nHcJTu*K^@QT?SWEiQ_dUW&oqF=ru8romY#&8Jcg2z>*seIC2+|>D zVcq8{xAB$GGd7i1)qB%&hwA2gu6v83+6AJORu3UD*ZRZRPdm>^|s=CUX z+PFuTTBB=2GU^o;GOjpP*U;{}2~3+chVwmFnm=ChNNAuT(*vv)z?-MoYuh z5q|QGM=B!DOE-9~8H}hIv<_z^8F48_NT^yUPn%?Yq@^P(1#%7b;))tlYrw`qx^dFd zyy8Gh5z9SHNyg&m;xn`hkl#^CJC@_yM38A0S$%8qDW>kd;TFy9y z{=0{DbL}Lb>8R1*;bQh+fD){=oUz-1MLb#M@`Kd;6wA6dg zk=f<_C3rOs-6G5-PzG8JgO<0jeLWAu7R{p9Yr~auoq#;Ge4hHG8`_RdhWl3lts1dQ)#Ib}s{3bfMTsp?wrKb< znzJkqxY%FheC*J?mn_SsV|ak_T^n6l zGEkqbGFEz9LdCX8yQn$PE?R|khy9W}TIG|{dHC!!uoebEu2lv}*F>hG4x#NVf=0`g&Ot5;v z$LLzWQ$>TEbGE}Ore`INTly^lrQpipJt9*rjZ&wT6QJm15Pp=Zb?(T9H(gUk7u{K-&^lNUT;Y7ybnjEFcW+H?OM!a*un`a-2mWV&4{U8pt@Wq} z{m41Pr4MZqPJf~A_my5+%!S8YFq^Z;=IC~EW62T^p-N*B z^$(_o{&&Z=D@j8);w&bfkTS1-zh9vd?PXrq@$Ly2w7q1R?FVez-$6(V?(fs{eI|7M z!#UD?0mBBAzoJzq6rk+P)XDo*ilmWPIq3yM^NoJRysQRs^I zPRJ#sD&F~eI6D*kH#iVSb0mThg9g1q->GncjL8l-X_6NZilgC#OP9n|k=bY6c24SA z2fUlpoY;6-e`qO<1XpNcFp|zQ<3(f7HS4J?)bqt`yMA;BkI99ocIED2$}z;PULI$xogY^wijilhVWtwpkO>ACPoGib1`{L9HW!?$%brbJ_{ z93ik!zH^88;<9fsbg$$!0tnIXNd%;On$U7+$%Wfj&AZ=zd@`BuVnn-BOl2WYZpX$; zj}DW*fB$8`f#S?T6aqc3zQ^;TKREGuYoga{?*~E z_ShhFhR%O~H0=o%LtryYqbWb^vEg9m)#v5YUzc?HdzC+v?q&TgSrxZ=bHepdG-Fgu zBf?veGO!j6`YG9a*z-4sQ~2qjO?vklXh@f1co7A~pFuZi3T8v)ocy!DMLc|8l)R1< zb_f;ROrk51Ka6*5vWqsndi*EuLg&fZpusDlY)GXI9rB&Jc_eX0P)Pzdga^|gG`fw#Ag zsQ$q~iie^%dNQ@bf4UKDGV$t zaPg2KSp>)QrC|f(#OChOESii>BwiRYx`^n4a0(1EXfnqKL7YN`Es#a{H~NF&cx>yT zZ2d>Wu>SwaILM>)IQj|Wj`h_lJ8Bb@khlELFw+VdcWkDFEWy9QN)=?zJ18)LU+PwJ z{#jaBp5DTwiT)oRtA+fdoRD}TYRURH*`^HB|5bZwR!1=u(btO;5RYLAY+I4G<~E~{ zrj_z_uiko82)6Uo&YK5XP)g9MAsN7l7lK{lJlhPxs0Wj?wc*;HYMXhsJcTzN93Peg zM6OXU040CH(K{XpJ0i|L#3iv1D)rhC6dqs&EnlNK&q?ZzLK*(Yj~EJaY0p-(ih(Xe zy-LDWI9|FMAkAiMznuhI0!C;+s zhl`LK3Rc&F!|m}>nEF}#1V{=2;0p*vW6TdP(9E_t3Wt`%W2Vw(6Jh{ogFw&Bov+t0 zhe*n98PV~!_c8CrXTy@@X2QHzyB3>9|?igx(P*JK#gfm_~lY|fRP@6Ymf@JZJk z;h*WPmu3_JXGb~)z3~!M4a0I~kJ+>j5GUN3)M2l0_!`3HY*)j>3%I$FCWC(f-rOcY z_%+jq!Swfm0x`)T`r1Uh^JeYu^xe3+c3TL95w<5XPbU5?sm6n%dH&0-5EhOrpEpRV z40B2qz8ZEsWnEeCYtTorZv|!D)qy^%%h;0%F%*RitXamCyFRD(lR^*&la2u!=|CL; zJ13jXcwa-IT;qI9^$Q{90o{K;Zg zc-@r*s!MUS+C}46K`~zI>#&L86w65>=h7vaF@Wd%&vxeOqz+G@ezA-P-&nOYI5l|M zOYez?e|ixr1d!fvm>apjY+=5yB3O5b?b9$1uGR0a8bqv%LX#|`i}Get{AU!n-LDLvr&EX+8BmYqKyNJ9RtF-y zs7y^cMPgtNe|6#}f-6;>VKMcCqDOa9`n@%Oq(r7h3>Ae zZ}$Y5Gv0J)CpMNVbvLToB3=*y6f@mhlHc7MjwKl5;SUme{sXFQ8)SVmQGvTy*?zBMcz!*?T&eD)!C0O8RcP>2Y&3RuWy}I}kpeBqG&E!i4r1aotQ4bo zf)XMxLXpk+Fe&qL?g3_ML# z{V{aE5%3{T;7*nI_w;_naUws#g|ZM*&d5l`gKfk|4D zi%QxW9B>V-`?fjCvmMl%t3M|Ds~g7Mno&v)HMTI={M8hFpI}&RmLM)&MuEncRTh8q zT!Fdh*VJHQmqBvgJVs#xr6IZ_7*vMXlmC?FSFR^Bm?g(>%%!t1ZJx2{_ zLqHdhz+4UylUVB{>oAg3-p=C$m}T#_$2*^R2XjFhjV>a%T8qNag&L8K;X z16Q`&HB&Sx|FvmdRJ6VD{PgvtQX3Foj{u+`<)7$#TwK%weD$o+(D?%^2VH}EIK9`S zCp{CFP4q$AYpc)q^(juXeD9YWhOA~$yB6X+&q9m z{bdY-lpkpH`-sUsc?#RxddpBJp-zNxFZ87}IVD8?s|h^g6E%S0G%=J)aL0~eAFR0S z`XD=dJ$}p!S++>GxA9&vPtku}Hk3YrRFuQ!u4LeV((;DuLpKs*3W1BZ8{jhpmTAZ$ zb}nR+azxzKRYU+(o2S|t3GmS5fHw2Q>Az-op zOR9o#U0oi&)QVXd|4^Nvaf_k&5B{?{`55ZkNMLR{Wh^C&I3~XIL1RCGtr>)=?0;5o zg^)m9$IPL$CYNrczCq}nD6A*)RiBe`v2rA`T~CgmDY_24o@JIjXxyXyAkyrieVK53 z2U{oK!wC8cCvKZ8;PnvZj|hA}%)=LDysyg9o4ArExe)oi`CGSYzh4BWs+E3>K~R5C z*y7tcf@D%udao;=$aq@e$M47wW4M(oBM;v@J=FvRPE4MAf(4}aukYXaUN3ueBSa+W zNdoY_NEijm>gRQm27-S)DnYp4lg~J%)mhOj2%~Utb@=t_1DYI~UX>h>CaXCBsp8(QM6rUtk_I zUxp?!By}C>w0N`rbxaL8LDXn+)XfM^D^2)^O9qKtk%9bYCf13Xf>eciW_EiI!L+>bXfa6UCZSSTK?tH_-t*E|zsP3z+W zobSx*W7KDoYQicmQ+BeDHmOq|!snw3}rzS_lv+3A!m zfWfisruG9BZ=nbEc+%LcH!&uK20=qAE1B@*)y{zFE^>NWg}8Zvo=Y${4^5H`f{lOoEZ4>yJ#RNux28OqKYXXc2M)R6Jkm@(Luk`KP;Stwr*x8* ztF;b_%-Pr~2s6v;re&wlD9=+Q>li2cXQ-VlE(Aldu@gt@6RXP+j$A&AmxsX?+jNn zvj}LJImeQ9;*(BT!!+|x$^%Ng_NgHL%Pqt!NQ>BDdRA7fYf>`jfuoeN?Vw`%)?au3 z*RQn}V|3~sixjCfjkL23m)ee>$Y-|+lR*sX%K2lh$0eon$@+6oQ%F5*$K608QDNTV zG1a-J-)Fts_1C4tw7LcW4%obEuP|bd!On;F3tm$|Lz{*_uUA$=X9-iLn?G<=vVXGJ{dzyc*jU7wam~eNZU@m1Vz7YNYh_h_9PSw7Z17w z_isf&)l@>C&p0v$ah8D8B=lS}O_&0V+)}0<5((nLZNFc}6sWo33ri=$^9s;2ajHc> z>?6)EX`~88Lj~AmX?~gpLE4G_zI{~JmGGRVI#I8RCe$$aV*xzJB|=ktMS<9QMm^$c zV&=I=Ewlc6c?r%tuvjVWDp~Zz!h@1jdATZj`f$Tyy?h2#sxvSIb>^<+pYagDb-&TL z7Rg5E6P_s)9cFF`5nS38=*cMno_=vVg zz2hQO9!Pu*QReV-7y#S}Gc<-0+z!pXtGxo)x~@MM?mB0IW%@YhxsZNC9Rj*$Fcg8u zfXS`A#UDz#L=5NEHVks7Yd^-&DZ@HEtt9c{CV2dj9_RCVaj zusJf`_@Zb^>;YXZB0T=ZLQAqX5QQhrX8Df}Ao+;p<}*y4FZ3%$X=R5`5Vqv{lXMjB z;mexA7jbKJkjECCLgN-e7gWdbQ|lh%24TYo)38D96(+*wNsK(V+y%hot|2OUWgm1 zHfJjo!(6>XB+7rlH+LCZ@b?Q5quAOac*A*sShHId=w7f>o1aN)zYJdQHCKhlLcK4Z z7FhpjK*$raa{0%EZvIOmC0`(t0o~WBy1N1OxnicQJZRRcu(XrwfoYSl>`F)%qKbYA zA7BqLAvt3yA_+R+x5(SloRFyfv9MGR+>IrBenL#jW zENH7RlZ;|fL&}RUj?{8WYx|F_t$WR;`9QxjzxmAi@o=QOzijpgB0S!im2`aOdfU)c zf&)KbFHUT%W^11jeSS!B#tef@DlKdpKZoC(i8hL}6JsR72t6gx&A%WTP1|#9ks}_ zvEqF39p?=2wI)8Lq3Ct+&)Smm`OiP2lo_L&c!a$!cdRFU7IM^WYJ0!^PXlLS7QHRF z@%e|vphEZ$xZ#o%80u)D4e~|W<*j7*zseZlwXCs&)~@MKvWXLNDE5I{EVfC7{%mXR ziUT-jiv1rZU59|T-n z4x;c9F||_09i6>NNM!FZRsYFC8JPBzE>}?(=)!i;psUTr5p~4>ofe}FszlbDV82#v zG7xZ_6L$GO|7Bko`BnV5SH-Y@P|;Zb3aAM?q<|?68L2&#PEE4|?!eiRnAf_j$OucY zfW&trFnIO<>RK?+S(-8b!XIy+P}f#RR3-vjfro9EbzU} zPlx2Wsc}U0@R5>;_~{F2h^8!M#OgXNhHc0xCNtH<>ow*7f4vUwoe7>z%U7C2(sO24 hM8uQ=t^ET7JB0tt|B}Q9(#H=aBk@DLLewbue*p6(T1Nl? literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_calibration.png b/selfdrive/assets/offroad/icon_calibration.png new file mode 100644 index 0000000000000000000000000000000000000000..c4ee0d63d46210deafe0797f182e563c50e9f042 GIT binary patch literal 8910 zcmV;5fD*=xekj*lpc za3nYC~>R=7#;_=bLXnQx8a{4|=AI4*41g z{IR1Wg#h2dVovGmBzZF?hUSjTWk?82Hl5?09Z3l}ZClQGi}!A;-b-~u6f77Cu(d_R z9x6tjZFvvk(uW2)YBZ&@%%du&eR&x*aRHc5%labF{}POgN(J=~t2B@^Zmuku4b!{> zU`A5Xm;2>#DbQHO{0El2sG24?O_2D2)uMq}6&UXd*i$|>$sLlDxsbe8|~cvI5Ih@d=59`|?R<^bIXwmBu;2mJ?ZSxP2@$ zyvfoQtiH%{!CuCLIiTRSBs;VVgC0JTea<$#ntr_ph!>cW6d2187+!?oks?Ps~^%d?+pO901f{uY9A+R{vnKdAdH_iGEi;D;~O47!} z1g9~W!FgqJtbPnBGtNtP;r zouqV1Y&oC+rL*}_jkV&ASsZp8?k6V3^{6d0){|_=`UHGPJPBG)9!l6WOWluHXo^K zp$BXF)XtiTsfI%grmmW8%Tym4J}+fM!d;o8YVO3wwPj~u2Bm&CrsqrnLnXro4Yk{0 zeWd~-J6J;*(2N+d9bzUVocICFiGpOeWejq^ctQ3(`|6ZeN+9(O zJPmluKAf`HMA1if?(`N4l(8rH2sFxl%TVS-@!Q7xj*sz4fFMTfV`EHP@VR1PHD++( zfjtf|dMTIm7G(x`4=9K*%>oO1_K)_x+kj^>uq2|HVVr6wVdYSNe~ZB>*$3R%@UfZy9EsRYl;yMCTZQu z*EnSTcOY*p&~qmEnCv4v$%BwZB*;Yg$|OTxo3XFL^Lhr~(vH5X zrP$HuBopLU)M*UHkj=qj@-- zI?@=sNr9!1_k5la9m>WC3o&+fvd_p;gs)0=strTrOj>^yO~z*R=kzJBcgW;1)*B|; z>x$MbSaP}*p>flU9F?J<0|Hvu2!3f$|7h55LNOyWHhMfKSQKNKaz?xJI{h6irUrpd z7>mdreb1s*yu#TaBhyS-2Xp^wrnNMNUTE9f!RSSh87pH|k0Pu_Sy48|mL(6<-j2** zZciHg44o5Xd@oS8!A72JiWw|I8Bs9`%9JJB1RXhSl#O-Q{@Jku)nRaG;$pR%I&R!i z1n&uNJ2;$c=#bU~KXDn_k;674#_9;nv1t|5_aw5vbm_@7*bGvXO}#)l6W&z|@S6+v znL}JT92*pV5s!@#GaBLtCS|ZByJl)Yl9<-^VzLJkY(49m`Dl_+?sH@eudSmmb&T0u z26YKX^~ICF9Ba1!`_(03NqhSlDD-+x9q_&`uM%gnX8bI+u|@7w9< zH~@S(!*bw3PttDm>%AL27o}6<_yS2O_ar82SIINk7^g~_)^Oz7Cn;P=?N1>mXT$Kp+ zGF|zNkmS9t|I?MAAss|~mPiEpm_n{HIQb(&ztmbti9jOI52Ubkk{Gm}J+PCbr6eOj zy#8s$Oxt~KfN^x9}nFA#Sf*v2!nJEhbfiyCa7@Hl@0kh+pvfwwMAKUb2|Z zh;_CNuLuyo*gbTyL3G9z+p*5JQ78h$a+;N_S88yupA1nquvEIYT*z{ZS=W8A_e@Ct zZjl>XmA$&zMqmec@))VM&lS=9!yN4$_uE?hzoB0D&;7HoA=u*}Ar8`w6?&f1fNpiI z98msAV?bUhlys9YP6~>Fbn9FBcQI3aVZ(*u@Z}}?HB`V1FW^~7mwCThAsrV%wuYvZw z?=PS~obRy$zB>W$>w(vv=q;8X8(H<9syLxb^2!_?xUvHLiq6)^o7$6c@xd3#PC&bj zW!V|ipdj0O!+XSf3pOw^+L>bLwgrd#uqGI+2n`Z`w>WZUeCsLxuTN4&OevRTuGV3V;T_{>~kAYf?;5x`wpfGzv# zsy;C0_1v##83518R{vwFyE0>64!{K#v%a3&(AF(eb;2^(^^6RV!*v>h?%T0tgQN|% zUGxX>HJO~8i_eESV4yrS99VaN>e)3HU>_ zYs+xkmOj*%Be;6%s%t1TUAVMh#LA!!*s?C366nESLQ0PSd8d{j(g*hp!M*;NU`@i&R z0WuZ_KMy7!?1U5p{rlb0z3QudJWkj*M8`a&@ff&szl}u4Tfs{~7w8oYI;jp8VDx8Q z9zj30E^pASKmM>E+px{dycMD@n>+Mk@dVKPPrL1a>RWXTsEL3r3xcj+qo1zHtbDZ? zeLR>3+vkt2hXZ5vg6JnwjE*kz*JD|VR*ZZq#n2z7ur`u}?VG09FVe)?4aNvf4@uCS zkv+XoyDrDD`7kj?xhG@ldy z%)QFS)jKM)8jbrHtyVesi~5uZ;@^{&kE#ZDX{NB2M?#6VC6iF;PxJD;@sotJze_lL ztKY~jxKOlmLYaLBV;2$!X9#}(A>q6387vo2us}k|$OPC#691F$jXTWrl~ST0c@h}O zeOlrW-5(t$T{#zy5q3i;&=h^U;8;pV^jU}rf+>4ehoBvdu&_L&XQ2ZwfH)+l&IfyP zDG}hudlEK8gNe)TiP-GWm3s)e#TL|+kRcvKZ0_kPJ`C1Iw+)*PalE>A%?=Rt%L@rg z41S@|;1OabPJ1U}wTPGd4B99$a3FWoyqqn8iCEbeDQ0+yWRSfkzS3*Z2s06{l*{!21YQ#u`A>{0edwH+T6K+&KwNmY>Qd{h|q#Z1c=$1R@}0;9BfAF*=g^ge3V!c zu{$=^cbHDH7~327QlsQ161#(}_@!sF%|QL5ZgFjoD*}la#+P$+E^0HlgtYYR2oS@E ztvFs3}_B4Edo zx^C$Wo}1S0{*yie8o+Z1_Z5Ffjx@j)9}}*}-YvBj9;B7TOFo`8h-VAgqHA?}_{G2l zRL(Vxn#yy~JISG2kA~%eHqc+oW9oDN^q73UdG?0THnGkM8`!ZGm}+G3dXN+{sC1g0Q<`R3YFdogp<$U;DidCbg5Vc8}!Xxovgm! z#Z&_QF-yjZm1Hu0O$?o@Gr*SL48dpv-$z{ z{o2p=b-KWbr|@8zet1!m%;1?9WUb2dQRaNTl4ai`eVHx@Zt#v}6qOy|Dac&Pa-giL z9uYpOEMdrr1-bMk9LDaB67Sb}6>*Gg3znGZ&`E1jk+Gh#iQwwh2U>gDXH-jMU#k5KvN8A(+}h7HdMOp;ODq9}f{YQ9 z7^|0jR1MEor0_g^Jimx8_*Y5tE65jFMDJZIgy~G*&tFZJSwVGz$_I zQGU|m34WA}XU@3UB6?L(dLoRMdNG&Bq&2sJDuXPY>)`V&qdccP(&`W1?Ws(T0m6cd ze=(xfp#M6WU$#h9RqG70d|U$Gb?(W7Xyc0n4qjVtg8VCM#8>E#egYfk7gMdV6|szB8FD z`);+2yvEeSflUaoOp?7#39#(>2l3fR70UHh8ZZG?+s@>-(zf?O<&ZL`h5QI;`Z@S0Sv&%7Cdej&7b5c(#`ZqXwr#&i8>z|t5BqswbX&sp?Vneg}I2<@y_6Ztl<9671)tH6z zK9h5@>G^`GG^l*CLAIos@>*Je#h4mom`|b4{&A8fv})S(RVys0Z-R?IHOL{e*3C_V zs(0Rs_pH7*R*>DS;54qvnlqk zIIy-lT`G&Fu9|~92V1;%CcT3!Z*lB;3eD4XKyr^e3V7AV5a2>_^O=()ACRp}PctJz zwUxgcbsTJ6$gKk?oWI!Loo7HQ1jRaT|6bx zXO<*KVy0uWp!5Jscuyxj32*@hPnFg5@9*O2kzU4zk^Waz@ctfc$sFFdARDbXaIUFNpe zXSb`DZ1!M_BOuE1ZNXDPJ;3M-dh6>{a6fQD)1nYt7B$VdI_=?LEsOqlgL-d;jVsgc zcii;D?p{zkj|TOW+HIUiUZrdy5rKXmkc7JCG)Yt~q+O4|>p z!BII&xx!gJouKQ_Y0d|Wf?jlf5vacx9ACZV)o8@GH-QI&w}VCD1qK`fmT@Ml#^FKI zLSWwu-U1eZ=`imO4%!d6(hm(W&`a6$2D}-dFX#++4yfIm7P^f90o2U-IOq#Ez}VO8 zN8S3;v~k2qFO2#eX#XJ!%}h{yS819rjkJeAtqfkD8P0i~&r;PXbZD0eRUIT^s5epS zQlQW84Dp-0IkoZAO{Ehh?pr+W3ngih~#;*VoU>1C@@y=nrw$ZZSEIQjCaE(8by&1?ceha9r zQWt0!L~odA7GTuMVAe81uN7XpSys2!^g99^^U0ugpj>bT9nF~7FywfbmC*Ig+o9h9 zYvngP0_4Ey89Aav*8>jq0Lrx%&bk+(FApWx<87<8*9ed+%Y#pXF3{^Fss$|3-Dp|& zz)q>wqE_3WM1Z`}?<5y!30lq028urGvI4sH6c-QEwsVbyzU@dxv~{|+2#|BGn~k2QZ+@p?blwc6 zL3;y`Giq%|zal^)E(W@m7L-3$n!P=Px9v)g!0V9pZ(DjXyA5g|0Uj%2u$4iO zx2OIa5n3oU0tb=Er%NI+K9%C2Ql+=TULpib5aZ~*X`}txqy8m?W)cHs{Mnb0)s|xs zSd2nvx-nq3cmPa;e=|IzRuYT_!9zixcc7)kPPFJA0qS3JF?rDSAm_XTHfje0fARlP zN1Sw~8>e@B>9zi@*M(jwrcnW6u`GBls2>FSXQgj}OZ4D>Su?WU*mI@q0`xNOgTYaI z3#ls?gVltB;aXPQ&D!IE9uDF_3?(7-ww!A~CGV5qCrUKjeo1y&Pm#X~`@Re6Q8PVd zaT2Ig?689?ktgE+`kJzT0H(ni!x|Z!T_3z9&FKNBorV2F`vO6HbKN?zhi2pz90~h~ zgFcXCg78i-cnb~=+zxIykd9;fm$})0qXa_sKEX>s!O?o?}E|Ag8>eJD<@aXO611}(P0jlb{n*ARPxRM^*?o^ z4hIte{gpccI7_OWQ5;=Lr#Q6EDsSHBN0h$6njjh^k_~IbgT!W2TKTjo2g5QIa zYOtXfm9CszR5P+`-LXgYz6}n-pWC={ z@{z1WcCDRjJpcq;H~yahzJVbRg72%ujd8x(PKgl8O>Zl`vviC+FPSsIhmQr z`g8AEfk4g&9s_Fj)vm+pwHj1R`OP*v$^1O+du&?6>w99~i^TpZaB|(YVuN;FT>qIJ zB=Xe`BR>!hc69fTjNa8jC9V?qSg`4{FD7=tQyr9XI*aske0~$;WrGRA6@3L zxZ^5vXg7zROGMX&Sf%s4F$kfLq424o5?K+DRD1rA5+*Wcx^t zqd?1#HzzyGXd_que7l50RxFW!1k=kYjQZ7jND94c5=I>eYWeU-aJjApHGAMJ&U9(Z zwP8$Tb0qYG@HvjHmL2ah#FEOR9CD@-=in?C%*Zr!#l&@r_!@@wbe*2@3xgMeT0VRa z9G2ySBfjI(mKEY1=0rBJ(6Zw;4)tvC07LAyM26n>x`ku>k%n%T7HWSBoMk$!QnPY2 zz@q0?F=93FE*M_{Kb$*Yco;@Gk=?P@^KcCDz9kS|{c*b1zW0G^cSsw4g1)$Epfl1a!ag{yo0fDt!BV~ffOl_r*LCp6 zCf6vDL*`Q`A5IylZ`UtV=rIzCcL869sEYv;Vx6Pa*n&7{CuUW-O}QX=G}SXlD-0dp zz7LA-z|%8`D|hr-1p2jqeXd2at7kCrYLbkgV@Co3>(F~=#1XF?gMhEaNx^~o6tpwI zz)?c2$UIt*$BG;+}|Pe04CbA)B3U!c@YLY0KO${U`uNwP;mq2xNt z1~4mYr(!1P{Yz8hT4*Csas+hY38sJ0{tPqwW{b{`w$1R+Kcqj`nYf<2F8u zGiPKY0AboD(ab!{(AqLH0@KraiKEVJe@N?VX&n)`+Bbyt1n~NNOc`gzHM8?WA8+kP=vn@u20o<#ifYuVdl-cIVh`dm}BDW+iv985x&fZ zuTUbJK`7dv`e#hLEjuERHS1>ebqE?Ef^KbCjoiAV8=t#MWGOdbTEqJ^=v7b17AEyL+j5?O{|&`eOf8s8|xumP8m zHS1>e4Y=E0=IdVVEyxw!_4bC>2oI*x64~g&INk89`Q1CT+Sv2`r+b&QNBw0 zDPprIc!MiA-O@`>WEp~?bHLrGP5|!|ZG=EK(SJG3U+B7$dU#sjkkd{h9|Yg;m!Ar3 z-+=?DKXcJqXt};CYnFnGG3WQ7E=}(YY7c&t;5RtCD+#RoPWlR!B(m{;d@X$-BcQFcPjh?)`p4JGl33BI zbVg1)Jj~LELDx>lu)pgf&HZ7Z>4vfok+`M*fGZN5N@wIW!wA5MpmsU*B+9STcv@QH zBB0s#XmEax-3oOlv7%FZBFhK?!FUSX5!6{?bMPV22Na&b?w#a|0ou9;`53ULD_D%L z6LcwgIec0GJPxdM`H;!8O$$0QfBjcpI0U__Gv!dck31CJ~pd zA^kGS|G=jiIefKtH$IpIP)}Q|1?o$uWY(@nlVNI>ak!yN)YoM3)ZC}7vg1MB#3R@R zoKdq)x#}CA$hHRr^jKn0lx=M0ySG}*W;t$9X4MLb)S1Fe0ch0y4L7AYiy{vg|H2!ZsHkOPy!4s zupZTOh93`c^@<$59zFV@`l^MRF!bLWLhYe%2+Fp8gOXPEoDcqtWPPFE3hRbvw}mCFGT+);N%cBb1nup0koxe zBRE}1vi`LRMm5ETHj%qL5+uD6d@WEHa^7U2ZVPx`F-b&0RCodHT@7#*)fHAMNk~Ac0s(&@Aqjy1K}~5oL$TmcesoHKDU8yN6x%_{ zU_}d#AZ?j3Ep(toEMSp3g`yzLAW+Z_AOU2A0s>+w5FmvAAb%1_LP$vH_wBsH+^jGA z-oAI=%O>xhnKQd@f6l%4e0%RX_uRAl?!L>A7c_9UQVDfmIegb`<%ha|=kPsu_RLOw zXh49IZ4*?2`|?}rMDWNpa=^Fs3##oJ^D_z>5YPx9J5^j^VPVgTii*EgS63gpef#z` za2fUwCtxST+UKN*|oScLq zbfXGZF#7=i;GjW+?xhT$EXp(#Werg292%Q~6E9!BJS`aT{9SYU^yyzxhEJ9mZlQ>1 zk^o6(rx}LICjnBWKcIp+R#sN_G32m!#)H|@P49#fqCr$NnMzN{%gcM{)~#D7g8{9s zYjFQL$a(vtTE$xB<)QT10;?jT$xT3CL~_z8~BSY^Ekqf^Mp1Cv$Rg?n7{VhZ8t1&(&af z9g9k5fH}mf&JW8rq)`LXD`~@$u3Wh?(63dr1YM90O+t5>gn*}8S>MFZq&Ye4Z z1DOg(bX=Uge*OB9w6wGw$nFScP@Mq+b;-*NuTY2%q9V!Gveu+YliI?z9d&_~yb{rOO=Aad|R7KmT`-YoCU2C^tarL=mzG zB$Z0#CZ0Tba*Ru?94|j}=FB?C?FLQ(w+0(K2_-~=1W3zHZrHHlQH1NRJEG&_WO;e{ z$=uxB@1f$1z0ywFQ$tw3Aq^U!BFVIq@dE}7xF5?}L8nOu!W0k1&6zW2J_FgEz+xvQ z_G*S#C`Bhpue9tWqB8RX0p#ZVjvYJxgvyGYl>8oJCv_s|lO;e}cJk=aqdx&qHEzIi zy7v6}^P5qQKRd}$fMpxfqyYhvb~54p_utRJ)ZwBNIBw1%5xRKbz=7X~>~yfKhM4)J zCh$}-1d?po$yTjewSe-sxB)A`wN>xD^Ulv9KNI{AnBh8OC!vH$kn~CpuSu6KUCIjp zj;quA_U)SsxmjQ?Hq%b3nFB1_kR}ZXkk&K=ivJ;ys&a*v!^L<#;XiS4aothZR4|vd zB%jCFNlgHX7y?PQ>||bE-XjRtopQj&)hSGAE+b>_NyryFsV-}oX^5bpX-gp4L#$;j zWTCHdg_iThHOrPQWBLc}q%3P0I|*e(f(WF9>ynV8`ie6)?#>=MbcpF6w3D)|W$a`m zP=rhY(z27=wr$G=R9dpo2{{4{`+eyj9Z{CpNiz+J0GI?)hS&Jfqer)fZR7U^v=Gxj z#*G^{5M^Y5?dc!JPHF~JdZiVvLl*iXEhzegtXZ>0P5&_2b(+Cb#R-sBxDM$W&*=mb z@|L48lm4M)e%IX)S9Z3w^3CASnmwA2U$dE?~Z`Wzs)%B4?8& zKw9CtUAuPu0Q$d45OfgIKk`wYN&m1ZJrX|&qztbKQ>IL5hY(w#4iG5=83^b4_3PJQ z(mzBQkx+CrWD1bhGz3}b%XI+>IaLc5EEt7GcryJ%fMWnym=kNV{FZCD^*XVRthW`e zL)Q4OGy-{h@7}$Cg>28Ie+WQqIDw;WiQBw+b6c$I3wb7>XvM;RUva!_?f`g_z^`S6_XVc`JO{ zRZzWzrrM_Xp+kp0fMu;OZS4v9CuCh3F=9ktG&mj1G)Xo6L&}c2K3K5y#<=zC*Qeq$ zB|8JP5)G$FR-4;@#{M-cdQ!;k!*a4880rph-hk(ha zss)^yu;yNH2zCq~KAb5L1hl@MQngLYLZ9vjlaLP~{o@t1tut8CBondk34ehNXGItY z=KF@nLvE$-MtHyxgZSj&@MX^k?)#l;gtsBfLOApPUFXooCoNt$FdM;#O&n51V~U?L@OUY#up z;RK%O^J~|xrLz#pr&xfr?Bu7Pe%cFFy%9on{oaD~kF}^j(Cp8ooW*i44y+D@1- zp_eYZDVl*(^7|$W-&$@09#T!eTcm#!HKg+&VUVw2 zKa3YZyC9V!-(Lg6IaX3q!et`6D<2M^yjMn+#8anEjSi=N_ItN)-##7k#ZESe^bb*p z^<<;+3{7?H(WA$A;fiZ}X+{)djFl;iHc}>W-dNBISg;Mf%4k$Zc@x zA5;q2QVO!f&Au)mb;Bf4l{`S>Oi!^$#jZ0HuQIdD4ESg1hk(C!s^<|4y!C3>h+n z-%(``Q>WBU3>EoDJ*3?wiWq9Zt)?@qW^ zk@Fo0%KsCxgAK~FewLl|Wua^HxZxXkGW`SX4U6o6vgdHkF1>yG_BpUm+P>l_Fr!CI zh5SGsuGGs4*WoXeelPcH*m^SkBPE_>1eEX#wAGuU(KAE;AAh=9s;fC{FE%M}oMxZROP@qtbS zQx;Y#R^!7*^l(`oM}4uLX zD8F5ol0^<|*`FbwbKU01LT`f}dqB>GyJgI|Lx&EJLpC2sKA0?r4-Q8G8I7>pcu576 zUMHt4Rt&dy@7}$jAZ@S430Q@Nh2v00YXJMM91C{~yIg8Z|4?5i;0VNa#smqVb`Lib zcJ68P9&P{N>I1C;cJi%o0aWkbxN#%rw6v3qJ$p9&BN|VW3_*N?Y0GG5xXx#JxCl^> z#uP)_TgWO1I`*;N`7hL!b}|L*>GTiOFDfK}-kC0-R4Rs!L|43Ur1kp%IzXfhOlgX; zv$Jzi$22hQBptb!vXf}9Us3_3LTUx&4;(nKP!|X~bUrvr>|WE2+{H^}sls3YksPyiJV_fAlLf(tuYHE-U$=TPZPu=(>BC-iLR2qszea3v_8 zh3~h%3=p(^U@#a!k^V6U^=Z`0S~d){{!{@~J=_$O(hbX7vx5Oa$2C~&-fm0(uxB!8 zZFpl9Cc~|GxV3`v`0l|f9bh@hKosiYuwldcLcv^0qn%X4b@IS9R{d*lmmN?l(@HyO z*REX--rL;m1V)(Ws+TNT@&d{;c2Xm(DxjRQ(8J|qy;J}G{h#1p@rDVS-`kP?u@Gg% ztevF85)Ha7guM2-47o={GMNgf;@=yk7ba<3kp!gT$`ZWyrAqSoxE*m`wku7c^0*3aA>CPjA|^X%9F? zD{CPY;7370!BVcyK(4>}q_LAxKv@7)gYulR5Rh!7KE4(x^#sB5vx^rmW^RxG$@@9= z;R8as21qC&8bmPb0yGWhy7lbY^NIZY{6FAblFtF$S6o=ey!15IN4Fxz`&x2xGP4D` zfqA_EnTY+E2a<}7Hc6T6L3D~}N9h=mxyUX1JTASA^TcZKEimVfoI_Uln7^yQoKKQT zF*&cK!lF%7Gyzo=FJKWc0z>h1OTgrF?D$Q~^RR?JRW@K-DeJ#XN|jAW@?HuJ5f{A9Y{qr2?n!%lVkz{vU?LX8qxuX>tGn002ov JPDHLkV1lIvc3uDg literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_chevron_right.png b/selfdrive/assets/offroad/icon_chevron_right.png new file mode 100644 index 0000000000000000000000000000000000000000..a3aaa76486170d8659bb9acd948893ac6842ae40 GIT binary patch literal 1420 zcmV;71#|j|P)%Px)MoC0LRCod1n_GxgWf+Fto=@56h^JB+LPteYRG6qnGRgypNCQ%a2Z)rSyfBPN z>%uOIx+uD^@WP<9E-EMl3r}T{q6OMikcv@xD2udk@_^d-ytacuCUw1wf9-Gk!OP6- zz25nrcdfnmTI>J+-JwIdT3cId(DP_FI*GnPYf;^Q+f?08;O{}dqxPzW2bWZ1sKJ2$ zU#PZ0AFHZxkgsk_e}&)w;kkuX6AsvKuMp<)r_S@heN_<-&_6Gyzslcdd45{>a6s<7 zN|5%R{+kEyh#amXa2pK3o_IDAZld8W#sXXy^fhuypQfXWAvL-HSC5W4$?zOTaZlpF zjYr3kQwK2(Huh;T7T_9?E~lK*X`{9nQlkrSccD{GGCW_RK1SPOEWph~I$t@p9aE2D zNR2MQH6dMTIHglT7o%-47T^{jT_Za6E~ZY!kQ!Zpd&Egq_UL}DWV9{D0^E~1!o5-q zrP+mGt8#>U&TLzZjbJb52=_!Wlx7!#t;rGYVY6*|8=*R)x6N=D@ZF!D((C|SXY_#? z?i{{ZX6y7e;JTqrX1LS%rlzMfI{?=ceQt)+#dd?)I=v0JKIkhmoNklGrKdDI09T8$ zjCQr%55Mxq2(xv18*qcrfwsgMe*cMWho+}AI{-Hf3DT*3mfqrq4;n|C7 z(o>opfE$bcKu&3#vzOUAy$!g@=r1Q3o-L?bdP=hcaE(Z##!h{Rsk7NSy$!f&$Q?gf zk5{ABF$=gkNY{u?y&f}FnTkXYB3<1(^{Bz`5qzPii*EpMml;me#X};$=lTKYu434Ow`=5Z0|C@ffm5r(1``;GZbm;E$$kqR ztQ_tZf@ydzYuyz0Chp(eKAayn8b{!);VH(#A!ve&2d3Zk89M+q0J-O`pYaaM*fRa*K-C}(Z#$)z?a1_$ z89M;g3+-?c;n4@otr=UU-yA4S_ijc`=~QrAddiF)fXXvLe+K{E8C#~`94HM5yoH?7 zi1O_8ltu@@Ry&FCXe4=_(K5XSuouiwvc>%J5MWQ|2(>)@ZZ|p*=+PXZV%|IwXg<>L zv{SDd`!T(RB$^v@*A~BlH{J?WpzcLF=Q#BqrjS?aw*%JVB*ODCiZ|K>)C6<_IrSMP zecLHk0acHVIf?LSv01!tS^za19YRihhpB(8!vqabgU|sd5uP7Vyy0n}G%VeWoQgT2 zK$70bok-9W(3prXzwUr-Lr!VZZc@Zhx>4NVB*LR<*2ajTwD$fTGgRD(aRRL|L&aUn zKp=O0hOX`xg?sr42(V|&BPCnRonacV23cuUKH8jW;u>Xg0=&^z2GAW(Hkw-HWhHBH}$ zp@sl<&`E?xGm#;uNoxVqt+`X0GmiNcDZup6?3AWSV}7X(uqjR=JTa$9%Wra>KxY_l z_!c}fOQlk?;Vs0XU|Gi;&fu9%s9l8+noSh!Xa?_jww+6;PcnEavnlVD`PcX!yTEo2 zREE;%3akcYu4VXavGMOKYay5xJbsVbt5ZDqP-O{obO&B*-=9KXAkCC$xOyELmE+%5 a%z6?0(E|2_u(%}v0000(*Y+R42zQT)1$fr=EIh$(n1f*_oP}%7M&|di?RnJ5N6O z>*uHF8H57B^%;{Wn%{5c=z_8_(TUz>Z2=2P;u8?WoAM*2(m%Jno zB*dA#1v_x!m9Kndpn${>6Wc)EbI&~?L6yJ1{N*p5b=O@tHwk&o0fLPAktnta8-xJx z!fw(Ef0jLOt+m$LNQ7W}bML+Pdhft)YYCkfzxc(;W)5M<#1cwd)xgFF9(bUeZ1vSw z4<+vgL=J0~fsiOTc&9eoY_nw`^akpF^PAuJpdR;w4?fuAmxu68H{Dd;r2V27y{Iod z$b@7;b(TlKHrs5|heQEr*0tAOTi&Go%x6BcPe!JUa?5*pi%=@hW`)Vl;)3F_Atukf z-~}(}iJk`+s1C`+Lk~UF128I&@&*4KRe|hLW$N+XfB*emRRA%82pnaJ_~(EAXOA!G ze(6hJnhaMU`a}6)_i%!~pvZjXD__vwkU zEd&IA{_~$Zzy0lRaduW+b=6>(`6FZh>&k>r3@6}7p7B)x2cGt{r{#fn<0z!(1QBzd zc;bm3ssNy;%QGSX#Z|TnJU-6_+%(aH?RTQ&LN=pl2uzvhKmYmNQFbamD-3SMTmY8Q z%#;l@{-VsiO|@u5oQ1e-c$NYqKPo<`OfrN@Zva@PnHC)KhS#HP?DbFKnScFhk5wnhr4-q9X{jv^XJz}2?eA2u>bU@ zKdt?TKm4I*R+S_|1Z}+W#s^u`I`J9Lc!q-dY@dNLk_|A5&05FCcieHuEq#es1oRML zbB1kgx^{UMa9!bAmk_=#5tCXVfsjDNYhLr3WwhHWhH9XXf%P<5tLw~Wn}zqj%U}Ky z{N2?W;m@*r2D*}JZx6aa0uguLeK%Hjk{lBeBJHndWF>trdl&+g0XB;y!Wr8v()7&0 zpj5x2RT^gQ=m37l9CM7%GwDt(8$pnnB~zPkzImTOFk#Iy5ScZ@DjH?6q8AU8z}Lr# ztjrajMF8<|CC?xu;xzUOPV^Iz$A!2QsSG#SWRp~IH_XpDL{KG8SYOgbmgTtQl1s9p zLin$K^{XCkKuBn!N<~1Px%uXs^P)?~sTxoPxO?UuMe7P>=N3iOFy>_Drb72rM^R$p z8SW2jqzscXQ3g5l5t`yhKl;(IWXxhoQPYg^GIbOI*i-ATzkXK`%5+XKLiv63EFy}* zu(l{jU%5Jzski;ie6`h9^HE8+4Icw15K1`F6-=>*`l@O)GbdfvOv~d0UMqNn&k;2c z!Akrv#zyOtiwN00 zf=M8fTVzATm!jzW(*EcgLAzUbMBKjIp&!;|ZWsOcG&Jv@Xj$ z65QvXe|{)=)zYU3pz7H@W`U${=SLaC>axP7G%5SJ&wXwfeaCTd#D)%Y0w6BRv$DBo;4FENv25ICmd#<2!q-vkmSU+&2z`nalFwKK$OiA6|NYQs zp>nef=`<^2WjBS#hZ#)RQ0waG#w?Op{darRtkTvMp1Vk5%4#jsYQL^4vlx$!-n!gZ zTwj19ylqvr)`A5KMn;&=t4=pEY>P8%+cc$TWhj+LCL^}qdh5zd7O4!H6o$sQ`s%Bb zW$p{qq7khbj+V74Ft9R8Th=eQL2Tt!#m-zcvtH~qwoq{OFoa~KWybXAqmPEe7G+0E zFqMJLdh4y%F_oU#i>mNhdFO@O+Q-(`dtL)fkO&(Wyl9{vT)P0%c_GRueLXqBPeQ}VrD-~YH6yzVqF0-qUg`b*N?fde1cb5^KI{@GxcH7G@ zX=V{wHoVNy?>t;I?^GGZjPCL&NW_3{q>U1XHN&=V<)3# zgZ>DN5Cc5z!}Jy&PZf8H4$>cS#1U1{WWv&m!HhT`{5=xkF-(FHS=;=loN|gMZ76rl z1R~pe(aYrm`dz8aA0ApYT`>J)02Lj?1f3(-s1~hq=*-G`e^4u^XCE32RyAqMrt)MIF ztQiQlh2gMo7&8F|kXM~dKtXDciGpX9v**YNL`oWPWAHP~X4{VG>Y(Pl^UmwoVZOfP z+itsU=eFB!3*mJ#0ED&%+hOdW;kD1)mlOAtowZ-a$)2)?F~3JrCf$V>Uf6m0%U>Qq z_uFs3&czpBTqfC2FwB$6>bS5tY?^c_QfB8jW0yNZAWLaD78bZ*_<7CPUU--iAu}A2yYG9n` z?G6-d701F?Mu4=cUum$>{w#w#^YVq3IG!+@;C0L2br2yFU!s5+ zA_kb0pYS4>ym-8@Wj~i{kHZib&Vm#oVorbf!bHJ*jd<8mxnVRvnwK@LgKfxur49NrFRSFy zF(@ORW}~)!4DsLD7-R=lv$Wvhnc>9|B8vQZgvN2;Vs^~%*~S4J!#>V-x6d&9&oOL~ zzZ4T}1Lz_v=#FGOT@00B47&Iizxc)CBARoVz}*^Y>>@->j%RGaU7ai%lM(hf$s!v| zT$+_=x`x|0VS9Tm=CYXnJ|=9m(MA{A_9+jfW?_^2d$I@>_4V(8{=~O~t>z9MWLrAf3H}RDEFX5R`F3JbEVX zS_!AS8`osbE*7#&6*PU92|NP@A)_!1k6B=$OQVL$7?jyUJNg6sAd{w|Jix0PmZ3S= zG<$y&k^M*rBRrvH{T>cCV+RV(>J_U%KE8-R;-P`1I!@d1W0|fhj-q@F-_170_(iCe zDsOQWA!fNw%W6figT(VPg;iKjMGb<7G%z|`bHxLPhcTq5=1uF?LR=m#NC!WfN_;>q zmXtDn@|tUhG(Tu<_Dy*i7sauS&d)caqBO(CtC>`Jvm}+LN$&5bY?1Uy)7EoU07*qz zKX*k1o62MyVK%m5{!lq9=r*PM)EryX2+EPdiveIO^0Umwp^!;409t8==%T8IGTOv% zZuh{43SGt~Lmk+xn(?UMIljnDwha9qhVD1)R#hR4jD|Tcsk|Tr#m3m7F2gI5DCjB% zI=WkSo;z7?xTZG+s$?Ws@EQDM7|JL~L;vY5)@4t|4(v~bI&duDK!Rfbe}_tt-z zw#}CNpi^rOa#^1&T666>HgGv4ilJN-T*muV=I$x46o-5mif~W{9CXk@r5OORNQhRY zMSNA8hw(6;0kL1@3y)+5X!qy2rQp0bD+QCXnJA?WZKPo1Fvb9+AJlBH!3JSDzbJiI z542%sMkU<>`0M9UoNJ!7vAxjDf?+%vmU_5Y@ z10Esqi2gqQ@sAIM`OZ7<>`Cv-O2m{sF|)E0?EzhWhhorf5mZ?xT%&9Xy^JjLo;fH) zU;uefU}QFjFs2^zu=p@d$rns#BYap@w?>hq^U{tx*+l|KqG8SA#fyhUQCoVp{xNC_ z9&x55c%VVud8gk8#W`p?<|?rS$ls?Jl?jRJFinyMl}FMbJ2VG*#2M_m4u{`#(@mYr zF6-O*5C3F0llAsw@9aQeM*Iu1{_F*SK+vL5}mYu3v49Xr8Ga^$Gs-Z82 z<|Q{qe!Tj2u^srNxm|F<1;J1E#evYQC+F&9P|N`QJqN-iGQ~w29D-puCttmh)Wu8a zg5f!|I*b_Lagleoiv%DAoVH2 zR3)pd*j>daC8$XJxD{R(F)2JOv8T+iYm6Qzx+N}){5{P<3?MP?VVAW$5qa)gZ@slI zT8F~>A_fRRAE>}SIc4P6Z4L_Xwx*vxVcqW3Xz-11d}Gg3tHb8W#*Z&o?CwfJDkFe3 z-cH328}_3g{iu5!Sh%=YcEb%f$Xko8XNxIM%1jxT(lINbc@d|sWin5IeYdX@_Xs!M zcw;9uR`BVny6F|NhU3E3CkZjP=q2iu25`aDm;oo8a6;`2ppaZxl~FU0Uv{5PAVR=m zNS5{%lCt*O-uAX|k}Zbkq{)#-9vKG@?MJbr5LF%_lwWq}BBeQ1Xn>U%Hw!H633{#) zUeiGrl~e@nxPzfG<3LOe$=7Ott?k259?z6byhubb;U5 zj?3fyea(T$)DOfc$*RU@#u+E>IU}Z{oS?Bsfz+nTkqVnKam?)<;zF|uRP^l#pN33f z9@llpVL0vL8DA#PDdSotCV-R~W@?aACc{y}(9Q>uuw)nMIVtfG@%T}4!)}WSUtKn{ zO&H*52X~Pl#&Lx2Nfp#5P?(5}{q*%*-)(|nhUm4wXjOUg{I*s2`C)uX2axKw>>7fV)n^$dEQW$XNvngz_E5H3BNj@P_htnLxp9Bxm_9R}T`E zs($d0M(Mqu86>sIStdqw%pC{=mbnSi!?YKsmCYCYsk{isWYJ>1Tes{zOUkC{S2c0l zc6svp{~?yb)2qM$3XFvCQ+Qpw;d#_sUdLGe$t!^&ohh9QjTwvckfh=UsSS@uHBT70 zs`#snK}aIu28JUTL$NvxTEY=E-L2cx-xQ5CalDecCBg~sqZpI z9c1?;USYqG4@C28O)&=~RI+W3v&?=!w~GF{UBCL8VfbA!mTC|~3xmBmvA?aeeA9Z? zuv%9w`xbgw4j?Sn^Z&(8LLFci3r-&f-$24(=god?2Wi%7Tlp}oA5B_>!^YnC+MeFp zRdXmU40aHaH%E?W1)wU6CkKyU*na9U_MG|$%TQ4$4Dri55(f2U_~ji9kz6NEe1S;F9@HHp|V##Bi!oIahx;#MQPalGJIz+(xRwJR3z*d1lxngu?L z(gjcS=W#P#C9QYMkL~l3dzg6R$^G_J-;2TFO`kCE zu{xO8bOYnG*3TtvDti)is{(nyfU}4k10<~JhDO1M`8=IH9utJeP4b>D>B}nAsN+3> za??WD59N&)-zpW~G#h4fNQHAA2&#A{I_1yevEW8!lfTjUCliS7ozSi@*g)|TTO`_k zRGC-B3zN9U&1v9CF{~=hdGH7ao9k?`vK`}vLGHZtql&XdtV`|nrX9c^gux{EId<;# z_Ye$WlVU!3qv~n>lTi7iVt5KKFW7M11+6g&qk4wV_MXynZPW6xAPjb4@p|ijUztY~ z0wM(1u^BX;bZ7uREjH5yAm*9;lpn3Z0M{Gw)Q5TZF!4UEX{w*u#rIc*T7A{4UN!bF zo-+pE&82Z)Me@vSnj6i`O=5VGYH*{XmqvK~_1A}^O{*X!GG1bQ815|1p!8+pnE}uZ zD2?)HZTpI>RSK^!!kYyP7KEc65(?R#Po9TW<4LPDEAXr`*G>=ZZ)$2^pUEiP%=?)F z>e9|A@|Y<&sU+4$&=AZ@pvu!K=Y`)Wm3OAL!o={YIYeco1qD^!NOeRfg2EnJ0X@W(w(T(oFW=d82N>Z5lQ z0nCC-qt<#0yegf1Yz|F<$U_&7K4ZaY zth{ZAqJ zmz#5%lQzt>Sofi#RoSr{8soUGFvP&}$2R>E+pA462n3rqU;7$&Q73OEIgV24(VCiB z5EfT@T&Iffb`wG*K>1@E=2w}1#_31lr|=*C@P~tz`1ZHIJ&G(!;~ezEbfq&W3CPN* zuS-?9PwvBT_h<$H1%RFUF>pibnrPU#Iqa~*!Vz^&A%F6dpRCk{oOt4i;lVog9(cj; z)1UryrDD=Z#_`}x8KQK5BUOi_Pu263E#8DVC6T_8W4{PsO36&Z!z!-nHf54lgMR(8 z=%)YIcP+DEeE5I;*MD^mIpmN=@P>xLxFN2mxL&=#`&>MQBEp;4pMvr5O?ShXDrYy? zfU076)Hr5-mGpJO(siclk38aV`9n96M+ATZ#^yYp{CVkSLfpwY6`;PBD3{Auk2-w!HdO@de z07?Fm8f^U(PJvl;n(2o73uOi210VQ6qXdCEqp_;)uvLFqZsL2UmP)LI*fK&wCXBXc zvSHDt?1vQDx<2KUQyRq%#tZRjbk!e(rrd<}3?R#vNORbk*i|swxY)j%SZ1JUZybcr z3zmT`%iB8Ocu6-Fh8V9jhY#=33_ilUy(AINAd)_ErWpj`^wUr8Y`Nu@g+)Un?6AWQ zrG%ysS&abHmDU*Y(8hHNY-!C9C)RzyI6RMlCdV-rVn)E53PtAd!w>K9?M&2h(+tyL zZ5LFnn;;BQ8QxYQL73_e2Eh;40uBvx-+;PWn6yBG+FyR;h80(<1 z^41k%AxV`bx%r+F5MMSQ4^jp!++FaWLi6xVano{GNJ5=8B#?acDs3Dm7oO$M%oyCh6mnlZrXgd4svqQhzWFeq1 z2m%A%K^kGIo~PDXXPutqXe1`3LdtNGv<$|o?DUnvTLp$wPkagUhd=yb=}!xO=R4mC zx3!yI`7s~zjvp4)V;mp+wuW8%yN`4k9P$|F)Qhe4Dwlaa`q7VeKL7d8PxM+`T)Aca zoYkOf9<@4*|;#F1l)bj>4F|I-V6ojrI&m4X9(Vb6y z>Qg~LRlez_3E(vwP zp(V6qi12;(v!Cr8cieH|)R8}++O%b3@u`fBHn2AvyMo};3{pRF8suQgRQlWOzT`I* ziNwh5Gn6Ey;(*JGCk;X|6BejEPsZU!fYGuDdlv7-|0?mmo^jh=#sM5=T*VfS{wze; zs@S>*K(BEZc96R2($ zNqGHjoP*4|%QFgmXaRUaA3nDO~K9%eSV z;W-OO2m$LN2*RihT3SZ+uQTt@F=Bo{4nYtBu}$6@Y{qdj(NB396jJdT{7#~rG)(KZ zpKEzPrajoljHvGCOubOxmS1l9AzoqLJ!t$x4?Psl2S6Z#G1D{#d|}LlMr2?}H{i8^ z=NtUQ_%QEY9y@qExcIH8_s75|%@A-~KmNEmRvxPjp_BhZeR8RVuEndj$y1h30kqQk z86!32eriPVpX>>u{_jl)$XX-AI$12N74N)6}H zT$Gn^quSZ=1V4KqthAC(jC)c%C@P2It?}Guv$~hbFFPp=M4E)Z&Zaq+i4jULN_#{t zppWD-Wr{1f4@pe{ahYR(oXs%tq_w-Ci)_35Cox|9nZh7oQ^yzDKyI=8VkC$$aVr=$ zUirj!oKM~H9^bHKsFL27%ey^2at{-4-PT2RGHoZ}O4)_NphUJFaI}qr+b`aVA=AV* zAvngmvwFUGn<}#%V!7GI6dMy4ODld%Rn1Wso{+iyRiUFPdDlgU;aOq>>rKRqvUX|B zkcH637K?1^bg@-_y-(9;W!Q%Ialk77DI3V{Xk&rP`XVa?3@r>9d97+fvae~6!%avw zHG37oWl2BrXcNU_%f#XG*A*{3u}wZ0Pm71CBVM>wCU5(^YzDv{(tn$MtW`SC)71W! z(x`;NmqYHkHttwxpG#x85;npR5#w!1r z5Z;>6ae#(pLh(oICO&N6^*FYUoQ4&IRqXA8OHBZ_X)C{u>Zpzbp)i5C%09Bj=c;?Z zj9LNRz=B``@B zEW*L|`rg;8CRFY<_@09c ziHznW1gRI)!^y=R&N9LmHimU{&-QH-pMekzO~T7%bSIEIg4=UMnOXzIE_EgqOOf^ z-x9tajbN{rEmL6y5Zj*NaUA|(>oAGl*4_)goD3&ns8Hpt%9S5_xM#rCIc`Las>Rn;Zs?}_Sh#RuxD$cE zri?Fh9G~KWhp8jp9zfa7Zn0kh-mW0nKElIBeD0!yCuAIM7>e3O^>e$Z=>m|&6B~R7 zfuI#O$=G?vM{GZ0b!gHUVai6w^CzilsdO*p9AD$rSh@fNV7dwcOtw*aDBFe`ZrB~j z5al2 z2ICx+SG>)lYZURSN7J}>nzmg&SlDc{&F(Tmcu5u^;|ix6xZ{pHrrmU`Du3uA7A#m0 z8kZ`hDvn{{5km4dfxO$kaj|ZgXITrJxDc=iWT$Ipybw@(JXQAy zLU+KZNZDCZS7$r|z*+#BU^+ zJ=6vE;Fk*N33Q%e;$Z*-sp+;d=ZZhH6aF!FU>Tc+pn4!&Mq%<}*BNh%i099-HS}## z87b4eIA8{eCk+K(vSf*}nbkIx%3IiIMyr&-3wWeoiaCnIPMI?Cqyx^@XtpsSobwhT z%0j9Hf=k(XX?=R&SRG_MFx$F<6yJOpkACo=DYK?=8f0LO_0j9bm55(I5frPULE=fn zn1Jq}6#{X#*JgTYH2XmxRLOa&K=B}_5j2Hcz4e|_jCu43a`WV^<;uDHIK>> zBX9%YffPpOs>mwwb}cT<4lJ`e=pP7&cK=@c+ShjW-+%v(-O=dSjjgbl!*(&<)lYx= z)6TcQ{q4?GS6vm#uhIKJ8P=ExL1n`YK6;a?i>mReM{rHqAyxC|w{o9B6*sG9>={f- z2w0z>^1t}SFLvl}%NklC9~=L{4}Q@1VU)5s>V~s}Bmt!apicaKf`CBOl@WM2JAnEf zw?V_P(^usiQ7Ib1^Y*vDy>s4q=Y@f83T9kk)XmFY_Og+@@=jgN@!Eg@{Q9Yo^2c^w zy!v3ljLSv~eD$ke?Obui6{SBEmPH$y?9@|F4Idz_tAS+YRTNJCc4H}YXE7}Gl4nx! zaa~T?ffNhNN0gUIDvtgPqQ}iVgpYiA_jYxR2lsA<}+1aS7!}P53fP7G+XY&V5KS(;d1g40SGC%prPsT3z zDk}oWYHeL>G~KQts0Txi!L6V7hsZ=c#IPNR~7;cn) zZdPd-eb9V{?ivuDN$e^ju=J6WHcXc%J&UMA2zvx!5T@$j5>c$sfCt>#6Z@)=oo6M7ouY8PbQU)R945;dYBb}<&z3W5Y}67y;Ri1!VWp)kcoB=oPZu?tk5%k^iq=L7N-#aZt6_RppBYj_)z+= zBlls-Lw&FZfuZi=`jcOA-cOpK5fm6BQ6e9%ut^OPp#{U6NKG?L<0ff%HVADgqq_2b zxv^F6*aLM9B%H+Nk_theIH^IZXh_+1+A9@2wlLm~8nk=pb`4M~2@&Pq@7=_Ydvi%N zVRN3)o_+B_jc{`;Zjy%X!Jm5eb>`jB=>536U4tU9_0vjY9LIL=B#xkYCZBcIS>D?S zH%rdq)uagGn^3AhXh^vU^L2|mw`<5M6fJTRvjxxGOE10DdmG_qjF82%aS_Pup^Wi# z;_eXyADM*=82X|~8>X&h3q3AcnK_i<;V9{0aj9sWkfO0WMj#Ru;f+t=-MnoyX~P=- zKmF4`O`43J{I$B*6F6oMbqH@TzRu*9?a3mnJ4R4K0`>D@a?>qv4xkB!6UI$4<2Wi; zR9*yu@tZ0Fe!_Zo9|^z+P`1MG^J|hI&>z}E;(_i-|1ouI z0&fsV8m#Iou0Qcf^^4u35tJZhD{)iC2ck!`Zoc{EK4>Ct4(~QW5Ljj|y2R^+0A}?F zf+DlHNPJV&UrZw#VD?ecIC!jnmc5%G2o$=kAc#Rdf}lVu+zW+wH&G*qZkD|{B*NA9 zVT^t5CVZTuDh_UbH$f1f!7upv`lC$vfx%W>-xxs=N+7@NNp7{4sTj6mciCl^j(u{V zV=s!9NfKZVw^~R z*=l9Wlh53LDz?gTIJyxX6>9=lR9~`Vn&R+2L5LH?{@Ef3j2Y~m>bUrs{%?Nsn|<9& zCh!;{;)*WHvS;@(PMq>QQy+-6Dvvpb-Q_ zga8#5`)7+FR1pGr#7k^VG0?-g1l67B!tafbuhccrN@j~7R9UkA(T{%Ah(V$%nR+U^ zf)@)#k0AKSEO$K3Qsy(w-h1!8OBd-ApZG+j8A)lx0|HVQg4 zpP0VKhbzrYvT04c&|1d8i>95ZW(un@g6b-^DVq;VjuAWq1gwPYHTW@;%ev}tD0*X^e4oq=WQPgJ?`rwR!SYwBDs$%9L!ZF(4kzOp-rFL}vJ z8hIm|=lt0-O7k->Bte&vOKH&^qZ6gjikpOe7>yCkTQTEWCwbNHV%G@fZMD3}vn@3k2ZYbI&cr zhq~n@_9m~WGFw0p1~uJT0|<}|ZwF7}PjIN!QGPKck#%iBJl|VJ2*{9+YBgC15LCYh zr22`OrSRAWu6uYjj+CF)F1JVQ!ysfj9buzlFTeb9Uz|)g4|@*N(lQa(7(o}U$IX1b zC<`Cv-Neh^GgwqYZwt_ec{d-9U@AEs3}s=|UsebfEm|~@&kt1LC5YWC}qXhQ{E#&k)pPLpS!p4}P$7=9y=fB9lkIZ@J}`Qm~T*;tl9JUa;wQ4SvAq z1;U4`z;Qf;aObcNf|N&{HtPfzTyR0>)vtbaAzI4DS7Yn?L{4FbLjchDXoLv4>O@_6 zTyLp(g+W4BBPdX|=))iX6o*Y5nX>=TG_3%G=;PTJDI)|NKxI*8ItT&0hgMA)@nckf zS#{>)m#0|%-xUNOIEWkOl|9un2>vQ*C@hCF_!{hYzx&-%Nx%H%FL&%iXN{g6_=3>r zC}-UAJxmpM&)r8!OCIv9%t@nt@G1n<4a+p@^Pm5G=b(cQDuo(`GAQJxQqzu{8TJI9z_pD>txHCRqcoEGjc^gPdpP#yN1LRkIIJ z_N?KZ_93#Jciy?nOizE)-ISFsxbC%$9zmcI>u4Da9O)*&Hx5I7WnNa}jU(Pk;6vY} znU02Men;_EQ{P}w>cUr|5A$v@(ud(@x`x!^9*1EHm1p=+CNHP2zyA82B}rqB6 zn!I5oy7O$x z$L{ASA2OS=R@>FzNK;np$|E!{4t)GZ`RN_j4EQ`Smr=Q-tCo{T*K~=aPM9h__~3)x zx+$usLE@)u@bMR`sBkR?1hFA16)w0k@eItk2;whhDt&8ba{#{6y-EmHR8wYs3=zL< zj;Wm|$uO(3v%*DwnRo_|40J@O(zbR!2bdv92!PD1r(xoefjL$=w~L&jN)_B7HeCb# zb}J0U+@l_tb$KBuPBj$7?P!FXKtbldl49wLg=CO;))qMMI^73vL$SOdF?>Z6Fwpj6 z9q~WryUSaZ7mxYx@>#OgM%O6)}l(0LN5Zs{gq+|V@{Q|lQkB_*SY#0=B zdJ4@rZX-Uc?j;Bx8#f_weylaHwMsuZlMNNXsc!^-661lGwfdqjYOAlG( z>P=xX1=bTi9C8uiO`)#}9nj98nDJ1PjPdwkqiGFj3S9#ZTlw1^yD0|daUho0KR7Cn zP)wpP9flv2fq^h>ltd2dxJ6hZ2(~)T5b;~cb)NNaIp}@ z`2vK2{dqJ5gG|p{(Kb#S9x;~To&g6-nF?x6pr~Bqq*Hl8lksssT?2A^|zw;S-H!v6<=H1Iop_AsB3S z@uO=IPSOC65K++c>nWKS2Y5X&FiqmGaB8`LjG7p12>v8lU^Mfl?UhxJ<{_>&1i^2m38X;WI1${xWtcwUI((Yw2g&oO>^24op0jh|?9t$MBQz7tvT}d=aiHACg`-}<2Grg8jJYf*sWK%?A z-SI{E@_1!w|7a_nAGSS~WAot3#*L(AY$NEkCKP{XLa~eeUJw%l17xHgW&3d49#(PK z5~@1lm3M3_zc^g}VdKGrNtHoyiZ_@CYykK@tNi0^ui(m%u*ScU2to#ZT&7uQ8#i;U zKnM!!_b0NZPoYgb8LpF7~$j-eTd-vUUGbemv(j}afQkZA&-|cO~{|}lH*oL_z^QqRf9GJ}U8QpT@h(qy@&OksI3^>Vlu$?dV=20)`)#YB&hve}wTv zq4NXID|h@VGk9_PJjjQwW&a}#IDW$C^YHWvw-3v6dwRS(FO84$X}nu7sW8RK_AuV9 z_#)e<@$RB@iuY-}Tk&OV>e${sf5)$X{p*v7m8b=-r|-6{ff{=>?-kNW-LJZ5yil%p|V@(%@-;GUThY3LA$ld5}$>qTRNo z!xtfWKNYviBHAgJ==QV@%fl+^$u|X`3d^D~1)B<+M0)7pXA6*@w_S?&dm2*iBBk)O zjW*ioJexMW!S^UBL~U4g4$z2bJX{^drlHsha(KJmhJC>gR#j^C9GaJcGD~?d;y_vO zuCCs`MagkxSjvvFx27Hrppb1E@uORAx#cZ}@y}UU^Ei$|_=#26t6PPT#lCXkY6LWX ze)##u5kDHgddu0~0HiPwUX%r|qoXiTn2eH8nwZ(nr*cx4hFYN*erk&0bq0}C44Fz{ zlT9}Hv7J5G0gbInkZ`B`J}!2r;2}ANBMjI$d{XH>JymER9n5FAOgcVYWZOjHA#ln@ zTx-g6KuVLx*li2E`}IH+h3~LZvO_Kk&#FUUVwv;lygLiWbV*NHkUtxdUb1A#lGo#p zO;Rb?8p5~i!)*I{hQ|q8|4I%Z5DbM8T86&%N^Tehpio-{u#!)8x{ysq5PU$84*&$Pa;evP8S$*5q81{?H)~6H}E?juHY2(jJ^Ti2T|H_>KhPVhPO2GDngS%A% zlaUbW0p8pBnV=+avlvTwt0dBO0$*$d`@TEwxTEJ`#~!6%8h0c6(D8Mqb;B2 zaTqVtv0rfkaK)cwFSb1lZpCMXD_(XMTvoW!$do@w{Ae=F~SlsSwPcp+)Q zf(19(F!=?3Va6lC9TK?d1PqN~^1_;y9(qs&2!d(JFz;kI)tcGI0j)vU1Hz$$;N#>n zQY4b~>D(45liH}<*mefwfjjTKb8}vFnoEE!F79QT;y@Lau$gRV__lTub_`GkoFnkc za3+_%EnAucG!$fjT_o0ySV!Va1P7+14ALp5U#OIvr`+1av+Z|-wS^nQ^uZ3!PicptB4y^+nwA5e1IPr^3!7($k)+)W?k-NI8kA2v9o(tTpE9EdjQ($+ z6y{n%7YWd7MekN&eOOgDII5=c@Pnr3P!V{RE?wH4Gq%b=HQL%)96(0c%DnZ~Tf>wB z8RQ8$LMgEB!1RK32el2!yyPnm7k-7u{&A&` z>4Of@gdRX2OxcmfPQ2^Wr`8gxm+#n&Evp&>#f%_a%dif)hM#I z^Ms9pwwPys+t>vK{;r4OfT_ruR4C%O!Z_iG37Z7K&GJux|sebT+ zsT4e73l`&N9MvW2>Bt=@04uKIO-7zFZDTxsR1HVdl!$vov2%}q+ zc9ekp4v+p1{*U(Loa;K8MnF zc=Mkqj!Vv+T_X-%cjC3xgmEWeEff}^sEk09x>sI$c0(NtRf$|YcSI@xe!zli5U3SPqCuS8tKloZBQ&F_}eO zUyfhz%m@D&wQ+!FlxR)C_AXf-aF*Ukd?`j}D-N(;j$XCTehI!YgCI)UEq{^dpIb&%7P zu8e!Im#oA;pq+7VB4O2$SbXkI5$Rc^t!d6({i92`9%42M&G#IV3}twrVmXap%;@XJ z5i*%MVsV7+ln#zB4?M0n|o^;oq8p+f~&dS~~PmwJtdBL?6Rw+`}{ziXM%r70kY$&(SNVNkmNf~-(W9*(E zFk4q_la3-2Ynq(`luX4%ct6{ydb2S5gZ}i z^v(rxv{FDx=a4%c&cN%x zBTI0`(KAFHK3_8&9RSwmlNVD2MX-~GN}6+Z5pAa4kObr}c7L4iz$a__z=1ytQB!*I zB05Z2(qp_)iM8a9$p&oY+=+`CA{Cu2X_H}!XCY>}9RE7DqsZx?4Ki@66)&?LCa|v{ zl}(CjxR&H|t_dNi4;%2#)>ht`BkJPHy z?Do?H5&ULy;(Q3Kb%sj(;{J-QOoHy+{(r|h`4VM2^O6BmIg8Pa4=AX>KxG*9qkZr7 z$|FziKn=1)s95^J7E+%;{4Uh(@GqtI|$VBq#96T>sCNx6i!x&!BGnQ(y6wu6O zcPp|{{!urX+f7)kEo>r6rzsiyCitKeLcSvP_@U+U7`gks&(C|@KfR>+epdT6W;=>| zZNxSVB#IO`iXvhbWG{#1P*oWqHWR-H)bZvJeGzLrO!C;tI~zvkW{KCuUF>&udW3Kx zEYlWa1N^{zVU$IlZduSL1SuTZS_qzud}2_l{KhzDWvVK<3*tT{7OVVf0m-%M_CfFt zR_5%FY1px8$gAHro_eKqbzC?yCDe|wWrF*V`UgzA(sxD%UYJ{A|DWOe=9qB$!#Ub6w~ELY>_%n7$j6xyWl%_ygRp5 znr&WPM}v!psIZ!D2R7VaL&h(~4(__|Bc0EU3C^o01KkEk`&@`Fl?AGpMuTF@1va}F zE!`&h^m{)!QV|!uTnsE8b(T>r`Li1jz5E32?uQJ1=l{Kk~7FEiL>!OJJhOpD{L4cJFPGlr=+A1j*{ zSJ15!-}$1)vi@^er{=83Q3)a$%uWz5$p=)Bg7bj%^FB6@+)usWmS>5yxY!q&OE2xC zlP2||J))wW>f2%9StGU)j3Mj^rlcxNKc9YiHj!1)qJY0Kfs}xKVLlU_(2UF zR=ZzSn|r75j9=4t_oubyXy%@{lf!*BZBF7&Oxy0le|1kkte#mv`h47*lrD``LDRM^ zkK9pd$hWA?CGxp{fPOGM$6c9a_f6DmYV*miC_@Ixz83+V21xuCq0MKme&~?0FIWtW zN0JB1zYaH=MNWRx;zNC#^~BzhU%J}!t0ifLCpMw@<5Z9K74CfQH7`=n?Y-tA=dccrpG_@pCQwZnpcOtOylw1P7Lqg zqQ<795CVA0sz9Kh$MQyIJvVnZ{CTb^-diGm^$@HyRGTtS@mF*{>7w`W8xD|FQ zw4k1BE$3dx#hwA8ylMQ)*E=SxINHlMbB-WOP+x37qyADY56ieQ!Tmyg;m$_IXNg3e z9fezxh=pFTa-l>p{O`{qESbZuT^H(Y$c`O*2OE?ME6w~OJ#;^4i4E>PUb=UlGPv|_ zcL_NxSA<@u?m`4`EAV3tUg0<6eP}UhD}_kZ_|9wW)s<^SGw=Lx6JRsQ;lHk9%Xlhe z0)asd_uq{Th1?qaylF}baX6c9?5KYQu!+c6hl;bdp>=$}GEZS<9&x`*DvsW6%&%9K zR{av((djN)t5EO>+H2nOJzJ$!aO48zOcjw+CuB;!yc|(;S(lR5KuEcz5h4O1tJOTt zOZX;QXMnqW4>O=8F+(?4tJA;(!ReB^xV`GF7Ga_+0 z^8$Bm_=+HOs_cAl;_Q4Q3#JQk18e3Lec1v+5mIf<;sXPG=-248l}22#M-;HJ3p7^V zD={_$k$HvOBjKUHx28ic#s<4Fna<+h@e=~P6oMG%zbyd~i_Ls4u8En043yh+u8+?!6 zeOGp%I$&#d?X3CXYR5rQ%l)&GH2dm`S5TOs`gnFEhXsEj#rgWJO73yiMS5l_$auwPqO>*5X5Q1MxDgKP#avVg%WTIL`Kf%Ek@1L)S^b5t zH7A}2dSvp!sfBs~kL%P2ez`(TcJ9nnQY$+=1N!Pq?v4(8?E_9JX#3m_{%} zP%*zOcJVA) z@Nt{&FV~rD$sQs6MHw^ZAS~+e-N8UA*x_%#(myYG_W>KhOQ#5$67$!J-HkHyi}~pe z<04vw=RM?6m#X|q2j0VDm~Q8YVM7d8(=-B3X7CHY*+ylYsY3NZA{f|LDg7jWVdUu! zyM#Kz3IQdeyks6u8ESt{@pg^kH;Vu{zjDP{0=8|bHJz7113X^smHa$2fOrWvx=9c@ z&`NdvxANM8t#E)mKj-==vvXcBn)X@AXjPsv+fiTRgMCIFK^?Ce#l(3eqI`8P2C@ivVN;sJZ(GNg$Js-%!f1fPBK3iM$sAoBZxE(rR;`ibOKH zCuKr7-_fEONf|V~6x{OI%si{hdTh0x-y&U{PDB#%M-x%O3SMC-_`Xg1H~;L}>y_y^ zOu~64qw%BN+Lnc*KU=BuYE=BXhSkBSDGg_#Iu@3Co_g8ykYJWZeWq4mnn+3d>Sz^x5_Cfe zE7H-(a!P0gligKC;!9D!7F+i?&L1^DulY==Q_3ndTJvSVM}(l@YTzG<_RpBeVPB(Or-|0hMT*5)``-zhKO512c5n9wxsgG>{CV@Rt7G|_$*8pzN}%RKl=xp6HTq87yB6In-|6Q@cdOjq zbcnySzzmeSmX$TmA@jLh=lQ4y?i1#&F>>b* zJ2egib&snH*tVl3dEE5XQ4hcbC6;~Z6sB4R@MTLeZ?o#+3x)mute6$7VkUuj5#XVV zHZ4a&9R~D`MNe*kXG7M&&hYaRSX6GMppBV~+r6>D&P3+!yg~|0pAzuf?Q;=6D8+ju zsv(hS@(dZ7da?qj9oU^)BUKceb@3|CJ|iU6t;qv{7?Cd|^lZhGAkNT?9a(83sq2qr zTbvM#l4E`eOF6Eewh$T!ZJSbN>}cnI95a}_QiDlf#Fko@?j&Chm0D7=aw`_FmQmAr zcMm0FYcIW;^vC}bDs9>W6bgu38oEA6R=M5t*1PAqe(k@Xqr%Q&!^kb$+YO>FW^`ej zAM7IEtE|*{Kq$wCVLaaYe2<(SDIWcCCp_cs^aSbog7>bPYH^ZYA=(jLyv$TGhj+Az zJ07%y3p69df_IK@I7c_ElKQZz!y%!{oy+0Q%g1LO_e;Sv4b$KH2^ks8)vTp{NKKiQ zg!8J27pQNSJGL5pB))rpj~Wbo>6;GPkFiuB9{2eV2XOX7P3bEsg0o#TNseVq*Rx$G z0PsrxwNVEIGDlVLGS=60oF z_R{`Jg^=8Nu0=-KjL8{gRyNvFj9ruA-@$w$_Gbkx06a1fBsCPw7n4I`8c2f>@OBEf zDnVfP2;-M8|BO?g;w{w;WMVH4x%$6wc!uPP*e*dY3N_i@|EMT@^-EnWaI$7wLg(Qy z96zB(=k%-Wzr=ThMp62qN2&FW-8f34TZz;Toxj(PYJnfnCQ-0}O zZ|f!@-3aL(4J1~4c!8U&nit83bQDoS2ZSz7#gb4?_fH`jHZ>v7cJ#XMA_t4O_(>}2 z0#yzvj93DS<4t*woK_B2yh{%RL>QqB=DbACv<~%k@-KwcUbZ!US7B?H$ z4Dj2q7F{>tY@0^TryrAUNxgjegUq%f>4!eMw^?G~ef* zTnCan(f6vPf^~_yB9`7B)f_ae0Ixys0X-HY%W0|@|F#7_;e4TK6Eq{pnqp#gumef{N4C=V7k4ecDhIe?X0iafV%B|GUK@`>Sm_ z%aLlXQ@YJ@D zo-8Y$jF%1x0fj*OK|Zm^Wu3G%So?~)nwZ)zc3etcy@!>lWdrFdb67L_(3VdjTmZYM{a)4vdC5rw&uJ!@?a(bqg6dPVESn{rbxljO zEmaj=4}U6FbAaMEsbomf(9rocZl6hI!F=U~wftR~Y|@>8B(-cR#y~&u#}{1LX%Gu& zu9vb+RZR5VWyI*t27z}sfA|`nIZp%I<2`xboQjz0fGM+k{hE-?uycNz9zyphRE5B(jfk0?-T(_8uS+uNZ|JYzFZ~HbJfs$r1y$z#R}a@aKN;#Xb=$t)MoG>*PPPBVL3=D{`z$4wofQynqt;~@%zGNDPu)%a*A?$_lKW5v0nG=+Gk()J8pYA=)hQX0>YYCTYkMtq5^gp|+ zUa5>@KvIez4QTh&zX!=g|H=F2865EYGE%lDIy4I;zI}YYR>ge=3#Hv2oEk1q`tZ+M zqP^sBlW`TguuTMElT&n4`?O@a-*lVgfb`)fRl=gC8O7&Q7e{53vf|s!L0xH@fT_xLS*vH7_8kd%`}H1FV{2U?(u?i67m2f%Oj?dQP7aqqc1y1moDeF)wP2yrON6tdCYRO0BXM=`s55!^f`~J1(^= z2ux-Iv6h9Thf^5J^-MsEPvd=Fg`3t_7d?bjd=Vj0aM^Nvqb<*yW(xh&P? zS*!$&*s8L@naO%gSxFNz`6-bD%u~N?SR+RvEgqaty;GBhc(S*T1vrv8*s$L~4v)?q zb5y}j3tU2dYvZ%zD@5w&85x3e?}HMI*Zn91#*@_zNqZji-#jcYDwNj2Agg) zQQ%qh@Qs=|6gTm|R&k?(Y;IkvyW+`?gnvt0t3|nw+~+wt?1srUTV(XDj0fc5%&WWTlFS11 z&@{jT2rNwHNJ`IV6-C6{CY6`Q#FXc!Q8s7@*N{->(Zk>7`!CzgVb`12e2%tC4!t7# z`}{2wp5@K0IeQ2Gtdnc`?#tXzdzAJM{=DGNeC9|&AAd6eOikVGv9$w4 zFVieM$&abTs13L z(Tdj%z=Ik{k`?#3+aK^45nsFg%v2%}w}-zLj1d+1BKyJnth1r&IMGDKXZEX{1=TkU zVOoU985|)mx6f`rTJYx0JARVP?QH45v*_~B&N+|-841_!rgdPhc;ac0pFa0ioDFci zef}Q82W8eT)!$lBq(Jc@4@38Twf^5Va3{*GtHp&(PjzL=wW~$NZG1poj~9^KU*pGu z)DM_)xWOKl2^_Tw93w-1GY5u3B>GFNzSArB8lZ8J{=7QrgEHV)ka# zI;k>8Scl|(9Xj#y9tMUkorc(SOJ5K$JSl#euQ39Q!8^iemt%u^O6-LGc}S@DFfWAe zA~RO>`V_c<@!5_ktYNiET$=l=NS8Xf(K}>FgM>P!i{?7XNB~dYi)K!6BR&lKa^O+# z()Y~Rk=o$5i!3w&7S0XjIY_IId8I>h8HOen&3Smpho)b};1t8veV^=e+KuF)?@x!T zlz)8F{Ozw3E13?3g1vWW0}6K8vJjT_hW1SWj=AJ69daqHhu8PfOG_i#)~xq4UqgT6 z#I$PZAAxn7FzYAM=Xdkd^ZdJm8Zp6g`=llsRc9L~(klT{kGjjo zG_sVMj79S+{e;4(e=op8bZWm^U`q}BSax1-!hcXPJh#zacI=fI)swD5(`2cPgIk}p zqK$i4`*uucp01NPdLTgS=Z+q>|C&t*Zwtfcze8Iu%16Eo)%t`arB-DjmiyiKOMgvf z$~Y6B` XlyK#72P5D=69D)}y@wU5){*}M?+_Tu literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_eon.png b/selfdrive/assets/offroad/icon_eon.png new file mode 100644 index 0000000000000000000000000000000000000000..72856c4e685d8a5fd9d7b9f029ccf6ab3772c6a7 GIT binary patch literal 8624 zcmZX4by(D0@GmS2EZrTF(%rqJNK1#nA}ZY}y|gq)Be*N9poB;_OGryeNrQBU(s38x z-@W&_&wZZ#L$R8}pGLI;vM#C}xjyv`uT zX9HW^hMc$Coz8iUEH(!o9<&DfwcBmX%N?G|e7Id$k~`l!`1RQU%X_Zg&DuV9Cih}D!Q_znjlXmSi*Bk0hh)Ug2K3gEmF%u@8DzZ5%Q96u z&DbsUZ-3$HGR*sF`3t{N`Eb|A)RRaawQYcr!zK6UG=`*?W;cbW+FBxQ2tZ-yz5D3R zi0<-lv2^rak!Fet)8UpMhgyosRfs2i-t~7m66iMPRe)(ZE$HR0s5t+(t_2;{d^P3H z)Iu(}*Krdg8FZH$CP0N5GNfDPL*LZ=j>3JSX}&ykBN3rtimWAicci6(Gds9k=w6P9 zPVp)ai%s^fn?mtZk4$gJ%^IFH%zA@WB90HRuV-{zM#H@u+k$ib2 zPRZ6~Qn5o(1B;z1-Rs7()k-fnzZsK(3HH(yX`pwB)0bH)o%89%J30VY^s<0l!UcNY*|7$+mlD z@YSAS5dOp;u~cVK)Qn4G7b(ij*iE|j^@OLMEhI2jb85!c${MAZLe{g$fxDGvXY4bY`#XN5s)Ef{n*V9h)nXZTUUi=0-^)d?@pfR8e;hrXA z{I*VJVM9i75RWEyPGcdWztx|dWUXMKv$6kij^GBa2>M@=FgV__NY-ICc5!VKz|NlZ*BZgv2t`TpM@-Nt zudF$&C61CwkU`v+b)o@GLGeRznLpiZy+WmEiro3tED@cX?Tj_$*7vX>Qx5Y68?@uw zXWJ`Q6m!``;vBZ~x^HZYpDr-mN%{|$okbL1JDt3QOqhf&5zvH(zF@NcbAgVPDQ577 z_*KC&)6SL}fiIKS@0!9S$P;d|8X+>?)2%AtUS^h&UH0~8%o7{m`O>ehv!IgZvo8ue zH>nYrMZ9#gi9ec~UQIFUiq{d^!JTQYYTuRk1+@DNGAbJfe$Eg8U0dPqHJ1&zsGpm8 zzx8U%Yv?0~38K3t8Z3o9N}79)Bfi$@BIkR}%udD>AVR2MLwz8et}p^+Z^2>n1}Aj9 zmVZJoHaVYsNj)ppifmempm^hId$}#-V#RnEw!^*b-;BePtr&*Cve=otwLwU)`-78i z-ELh>j^R0_S_&?q=$D_RFTUP{2PYYMB(%C!el|mYqMhP?$iM>-BNxZaRB`ZU-sBfc z_i0gK(c%yaKa5fMsi}El*;q&40e3SPJ?-sRa>dh=7*<4n(t*NZ_LlJ@_==E9 ze>YD{b*XsEyXS%WkY~Hx!?;^O35hO<;-fu@2t>MRc33Fp$|Lya`Q8(Je|~V^UrpGw zNt;PX`)!i4Tte&Nn=&`t9-9_h=0c>gcP`Kv!o#BXta{uOS{@5l{h?utS;qpP5SxR4 z%O>A_dQ1u_MxIzxPFa5}?k2fuC!KY3A>*oqLC(?6>Qx>1ibAjsB5utT5=(SApc6Zp zW-*q-?sguCHTD$1pavk9%JST^jcd!wys;4nZX z)!+79(P$^Xn?kb%RP@@VeSU)d((wt6$0p0Xb-f+^kVI)iM=-nXM2Y z_b26VBXb8%7pGrYSl?U-avIm|qQ!jw(CpK6x5Z4_kzH>)>ELb5=XnZT{5tZ2h~7CR ztl*!jVq+%=6>E*biRO#bd2Zj(KMMP8d^6JZHR_;j#GpSD=T1ct#5ZHEftwtMtkv6L z5832GL{-gxD3|!CG-4tZ=yP*M;f900rJ<39#UTD?hrH%E_$Q%XPFwbI5o=-4q2k85 z)=GtD}7aC`&pz=8L!kh5v zYXczvk2~s`bCVq(Px3zwGsGh`EqOQ%fZUHqT>|txrX8(-SFB*fk1N(G>-aD1017hL z_<@PXBNSbO9gJwLo}iq}1{rFFX~+x}KjUFc%5}p)H=7lIzaE|VEVIsrqlTa>72(ol z<~l>&Y;OKMDBJC;O7}_zfh}w$fd+k1knFi!Sa=0^@v#-|X|KvU0pfa{oC?Yf@~*C# zx4O+U%U5y>T#U&xGTCMkBu3|4ayHkIZf9mIPZX|mQ^4;1el(Bq!L@)#h9*(orz;_1 zJdJhuO5HVk<uNZBJ2?Ad zY&*8RtA%u-^b(qO*p?@{f9lU4+9(RdlUgj+D+$L&{byKt)GIdGE(#2;msKztZIUx8km+oZen;!gAn9%Co^EY<-f% zYr@VZQc8oL@BqN5L_Ji3;6+j8jXrW=uG-HqMBv8pqM*XgmU~nkAV*Pn56F6nUfNw` z=VM&#T`5a@(ozP~x?Y|Oi71T_zX-BCaatb_WEksVXdU2G$OH3aP!5PwsWbNVjLXHe z8+_|LyMBDkXa7R&+$ud!6;_$i=V(7Pekokr#z20?ZFpc}^UJNBM>Ke_EY4O3O~a2m zXe|!^`{Z#_``{eb&Mmw&uRdwOht$3lv41`+USVf(K5~(>nWkmcTkkgb7VH72^yNtG zT!rf%d}M4~)h~@^9W~aJ`Jw=G<-d-VL6@fF7&S)t3>dsOl@gn$DDX6QGUF+fe^c1m zn!HQhK3V9`bc#9Mp7b53#>nAa@muKL+3E~d1^ikJ3p_Km-Qk5H$Wyp;B~0t!MCVdl z(|@@!S4gvgu_x8AZbx$#kG{kssLuG+r$3@^nQU=z z8#x$FdV&w4e`l?Hcw*J(FcL|eafYxI*-C-i?ye{hDc}`|gki6W(`?8}dYmQCOnU76 zEjg_yQaMK&JPu67;h7->9CQwSsfxj4kOfBnc~LWHeZ>V@ima&@q37Zw<$n=b5!P9C zQE(HRPZt)yJHrU*e|0PzgKyb_*7Sy9wuRu%rNTu*?!xqa<?7Mm-nEF z9OUMUm5=de?-_5*-oxhBcYWNbGNZ zizg)1l+eSRq=IUbZvPL8t1uY0Q25g$5|58_%d2Qba_`9v!N4yZ5FalSCx?YZTpggf znG{J02J~G5v5Xl)n~SS#JAxM!f9-VfdnL51p^TTSk01wJBTsiOwZL7T&#iK)r?+U+ zbxrFAU83(TlnstW6644^UFBBB(Y9F7$4RFL|4r1xjSJIVo_uVRS6ed$%oE0qL-ygw zzGhSB+ShrktVmKq1}#n$w0P-2K!E9_xtyU^Rc`FC5Kz`{q6c(TghZsWAZpGY<#Lhn z1@a-&s2<6_BZEF8uADPPY}7Dl;HkD!73|ixw94Po*D_<#qlMSj?#FVo0lL^B8NL7^%kj^)Bp~9- zOy6^GTbc^Y7g$tNE5lA&LWN#hQyNHN+y;%LG4C~1|I6_Oz?RvcC3X;IX5{N8kx zc)CuVRmNy%hNREXoP4xSJt-}zmIWn5f^Td*$HFd3UP6a5@0IB8q%}jtxX;1Kk2;q9 z%UzbZU1}&uMTFj3_OkN2+FKOa|0LW%b(R!Rk<|+_!&y^emw3@4k&mtcr2ZZ0*_9g2 z-(T8Wu;D4MJR_U=0TTS-8vk;Mi8P}_RB?`l#vC^(0U7^kbHYjOgD4Gd95^2&>lm41 zQ;e-|uB_H!PU7E~`WR7Tp&cF0qQ?QKP89sS4Nad)c~)5m{Pb%Z-S0A!3@S}pDS(^f znBnWlfXL8dK?9T$L`~4q?Vn_E6~aIX?~$UciaUI3GCBB|sxTcOpL7;OH~pjtW{_ zKx;;f#`U1&iew(V5;T#4mT|`M%{^wqNWFj372r>8^GGvH<2pDGhGM25v2AnejwKmR zqxeSGI0<@NNkXOh^|r#A@bHZEY)JZamqk3r2H$v_bToul3fv^GSYv#cHmeQ}T-4y6 zmIN3ReW9ke=G8eD3ULnr`*p6_42)G~$9!LrjVV4M*U#x8E72l?C7<{Hsk5admg^uk zGgmoyvT>N&pXYL@?2kE4xdwJ=x6$-WH%Wa>((sruX);1z4aBfUF-!32TOFyy3d(py??D^-}YlfYdclA4!HLZOgg><+Y#*uCsHK*8ZIDUV> z6yLlig((qAR*9A9-ZtXgNpFo;W7HMzXtSa*G^fUizx0bAA-P==eo0gJu|4_P69rcm zCIEso3@+u`*Ym^o+{9H-UG~Roe5o=E=lQpz9`-=odjh)Lmpdii06}}~!e@TL{k5U! zfchr&r@bcdd^alR-C)l9=5U_?3hP)v)|;q?_S>(mqN=K3pbCs0AXsw>sP3&#{~6Fk z@yE*__Em4(FSWs`$yZ9Krde{7S;7*9OgO3ffef|d*Bxg=puPpNS7|2LTJs%Vb2gJwVaI^5g!`VA1+=RZQ(<)pxT3LA*K!r;!s0b#FFn=3*J~UWQOOSmPBX2afks zBkfuh%g$Hh;*ffvzEMImP!D`kiAgga=GX{L3%Z)ZR4#;)tiyWKhMMK-DIAKZn=IR`m*m7t0>6+Sf1X# z^s~j+eG=;30dQ`bnmStDZzb>hev-H&`l}69{R8%q>()k*X}9IiJcBmxG=Aljrob`D zU6=jkZvvN^Q9Acbk5fyGPV4PmxpY!QZ#=&^J<40Q4qw8**FAz?GofM`*d;~Li4S8$<`y0OE?AhRhMW)_m}RT9Sp73IH4d}4!bw>ewTNF z7x!T+`&WN#Kf$A*w^+22B8ByIsUcD~1Y2Qh)dDf{I?CUjuD_INpejI{)tz>)zkWxY zbB61V>;~`R)lsic>Y-Cgr~_wv*XYMFDb5Dm#rwQV%_2Vf?#e3wOyKU--=)-gpu?W^ zLv|X0I>^zx?{tg(l>!PU| z@T8E1DpAviCc17yej*zbi<}`g1xRT#P5~z5F^ht4=?mh%&woJY%ds?h=)73r8gBYCqIsCLl>mBJh zbXv6_2`PPRLK4J1T9Qc!&_h)Y0V~o%@#}HVpBk!1#ao|=eZ^!2O2#}$2aj9xQ~Nqj zbYhl(ZVOTT?O#}>E$n3yx}Mi(kfD><3ql`<@2|fA_rf89i~FI`u#Dy-iCXsj1P@-<#J6Z!k-vLb zgigY#hHSU|E6B^Sx5^*Quu_}RggrEfr#3bN?OR^N(uIiMxL2l-{%a|4AOu6VbF__- zdXbr|ugJq2YdYgiA7&H7v-9|)ROLqOl~DBi6wR(b$D;9Y44 zfz5w_l}3=W?0&O1YA=qHu-+1Bbg`51L;wd_gLuQ79#o zt;3&RY3)eT28VaA`srgptQW_%$ZE|c=h8&^#VYd-$}c8B4&BQipWwB+;Znvyrp!M( zQan4dM9iCUC@)lC+rYB{>Sdrncq@6|dm8m!^>C6~PSWkh z#_;Cd<)=lPP1#dpFwzH6NDz*D=p3vNPGHHEN5Q+mE+k$dTxm(orHN8A1{8mp;7XT8 zD2^$7+v|a$ih{#KY9OE?K^wYx4dv@_?YCV)lM(Mhv0nHq{VWcPvyhQ)MVCk0Xi8E`{p$gOC3Uy?pMb2cczlJroYrlTaK#f=3Af<%v- zlZ7lH&iMqxD+#{s$nAC38U{kKH!FK-lD0Gl`TLiYSm~Fz10SfS8_8YVyJ)2T<%1UL zVutY%PEbBpF~vJ zS0?SJ57}k{1QWyH!Mu99q1PA>9RWqTMNtSA(wLOzh_ok39=t(Ar#1f<9AYRgj(uXC zQiG%UgF1Dvi1{}30UxN>rf6fTF7D{E4ODr~YX6(fmSfPiqM-8~SmUiH1Q8Q>&@NgN z08tG1XPSa^G~xg1`nRMA?_pPZ%qWAF_@%^^x&IJFJNuC?G(Pt~AflsGM2X+=kJiP- zp@10%3PZVSjp7&l$CpR(Js-3%0VqhR?Gq`#e$ByY#}AQeIn3^9$)Ond`srT>IRjpq z7e*b+;)d|4owM8^js%b&@IqN`UR<0mTQ0_PUW?wy7WKbVoKRaqhzkc4I#-y z7w`J8E_}m!BHt~{i`OnJfAyXGA9f!T_nA}XYbeX`33ir4YdCR4#s6KDAHb1YY#gnd*W2qwCMHxopw2L zO8IJ%DI+P3+H(yQnVX=fgX)+HDLJolFjP6-K}@HaRRsRkt_vHo|8?Jw<#F_Bo#1mG z1x1gCdLxEb02v4R67l)$YTJHe^8OFbZh&X~oYMIsvnlW&E!3G~DQW+bwhvUY7*6XK zr8N&&Iu6hLKfMV)9scc1rLS+p&6xc`5DcV;E<8udsGW~RXW}TGPX+i;P@s&VlL!K< zTn}dlXk50K0sG8OTU?wEX^;X94RD^4672VYH-@32>2vC$V)I`F4uFDQ>#Pk5M;Z%*4I(x5Z*ts_uFspk4@P_} zdDzDvrlZFK3RUI9qj#f&@1YmX|8ubh1BF2l&nxklmwBPqBde+K@99}G{tKPJ-|{w{ z|3DN5^5$5c8_K9GPqnP28wkR6xtXZxT95F0c4VzRD;Qp1xMcIEQ2xOy7&)NQthf-a za6)@+LFK23Z2-}`$9`+=PIG)LEb9Ix%lNfneQL&21DCf*f3lfC`tLD`vN)dBzx(ef zW+q-fof@`xa8^jt2!waid_vvsd$=|zj;LT-Td9@?EqX_v!Q1TWznwhSP_}Y4!~DcA zd$zYdX!x~O4g0RxFYo}u_jG$}QsVhhGW4`7qBAj&!G+kq^&<)V7ye^Ji93@=|BAX2 zc(yhxZ5#GO8uMff$@rdmQ$JzFDa2}Yw2GK^t*Z0;(crSkAoGayaL}XZb_IF)B-T*G z#m63kqmeGR@XfMpH;)F;-QWL|fdSY^y-OlJf((4;rGu>_YSe?$67K!$3s*Xqv4dmt zsmqjn-C5s;7A(;(Aar|jDWi?1{lSmjo(ha$FO$w>a_>fEeJ2!rXn_9cAy#Tu`R^RG z+A;6BsHdKsg3S9yUyFe-ZgAI*rK~HO>2X7eZ|EPyg07*naRCodHod>)vHMPd2Ne2;-4woW!QHliw1hH38QBf2@d?Fx1z*0@9_Id$05+O%N&G_y6|UnUl#*GRe&Ba?aiP{nkmc@~v;JWM)sv zWad2WX$fi0oH@@&?nl0r0Iv<1CuWKBIidD>NTIgY^$JAEM~qsdq%_;tURO82&rn{Z zSMN>P#+gy^wMl2Uo3d>mD$naS7zZM;%c?60Z}b#9Bjj>)FM+fjb9)Hv;9eHONpG-j*|q8UMaWQ_!{n}kshf7?MrY?{liE6i z^|cAtv(Na9ZJo-H?rQ5qu4L=vSjpC@Y;ZI^=C<|JI}BYCm3sgvx|mbd=3=^SCz-Zx zy~N|w3GYqDfiddlJJ@v@cIyY&B{#L~6PMo9-5?9S8-TBF+uHU<@A~y|baqZ-Yz)YYo!Dz+DP`j( z(=5Fy+j-|iX&T*Vja~+Jnd%E{l33a1bT|sLl3o=h(>hU``0MEQv2mu&mm3bZ&FBpe zdFNM2ezS}1)Qy3!(UADsY+V(Hk7r(#_xTLX@Y)VC%l@8vNPPYaShsPDLSYruW>tel zV0VYG(klgx?S=`cADl`O;z0kKP@DJHWCAmeTi9eBO2em$;k0#~O9(Y6nIOoQcMZC| z*++WHmnlz3PlEkV*S51+96z0)I?l`f%f}KC*v<@L&HT@X%h=m>Q|{yduJD1RD*>sX z>TGlADW55fllJPi_1OCK##U|7)CGRQ1xfGf>^jY>`Y_Td+1Oxt0$K+9jJvqKLqs7S zo6CnO@!4S0fbIrYUqzIP2lteVHGYfSbw>RVk4~zk3ZrfzfGcepVO%?J-6gX@rmdUr zq1Da&3ZmLq^`Y>=cl)ZZ+<9jV!E+ogm1ne>E;qRlUPL>7Y}U zjjK02(wlNh?wu?O8M-Gqa2tfM(tGeRcv>4BJQYd4a!X^)K;irVB$zU&nnA4yR`D^J zc3)eoIvnYOsMzt0V=I5U9GbfA+}2S(A1TdH*x0192n|qWC97`kBrcL}qIFL3Bk0yU z_-^?QW1F2r@ZTb_9C>FU983|c?a*Khm)(|B7J*U~!31i~N2+k9-Qs*CDG-mLx5qwQ zH#j@n#C1yJF(xRt&D5h4j0WV(bwGo>GXdZ^xSeGpvuu~3{4T3rT{O{q$U4ThzFXeR zu-a|Xx%Cjv=zDUTz?8`^LJl@{8Bx}Kde5fpVs0_S-Fkte{yXG9roA#3fdNr`LUofY zy;N(Py2;V`u9f-;2Il4^o#rOrd@f&w$tQb zw?=tjp)r9n;^cEyoJl@!uTu8gzwG8h=20*@w${yntjLw&1vYqUl^j%?% z&SzIN0{V*qbPet@hHh?fv0OH$o#I<84)2NBV2gl^!Wg=B^siBy(Z_Nh4&9~FD;e8~ z+GO46J2{Q-vcYyE`cpz}HcsUb4*hYVwqjHOe5XrtMhJ{v2fw0MZUA;YhO^sLHfes( zdF2vFUu_dx<$qb_R*D|~WnL3$S=$-Mu5tn~XC)U? zWmn(wF}h7{OhI53eC^UH8Q4T^vTpR9+y>eWKBEv;b|Jja#;3D=i>!1a z^EvQ2G$ghI%I3kAJtCdydxMYWHkl1H0ho4E4`7Zq?c^)k7?n+%s}I&g21cKd|J)`A zpFSeCp~`Y*bavV3x|o${yIt+1)9f~1c>*@c>%&BK5F8?KUcHJiRm8DZM!I*NYqpW-F%4-j6!ckbI)Ib{J==r(oePUXs zvBOa&2n@o>zL>!-8^9mp!%s<_+d;Pzw13^fTP_5l(wu> zq(iunQ;$~dj?;;I1x8maQB=pAbPn}(qNLqMaAv*#xn@w%J#6!(@FZh=#Fp+u$wZSK zFy==ZTcgO$jlC~-xR&!_8tHJbfaPQtky-WPCzayFXXn!yF53R#wo~8K)>-A>Yb%`mOl8Cv@o5baboL@&X>nl&ueyQ}AHC&wL`ByBXdPCP@#;iw%+TBqI-~E=Q^zxX#R$!Mh2P9jGNXZyX)XIOm!E^?#+%o5U zW7j0NIlI2rw{=e0te!5^S-uM^tKbq?O+CeKfIWH?GmO&Zt6MjG%0nD9xleCwv#;28 zc7rL~?UiL?Wb%+fxBW|Mr@U7cKExB!8$RVBjI9UOvq#zO(K5ytBAQB;{J{mID;B3v z?kxIuF}^xjtv~A|Uwa)LWRG?!lLp54FgD7K&g7_cm@xgnt)oZrBg9Rmg$*wq^j2Fkr4j}qt)jGd>smdfxcPbC0qUqdC^ zb@(wpNzP1iof^H9FX`g!I@om$-qtrM8$RV#JT}%Um(~)YU)5^URrBPsc&ni(x=xFR ziNbH4x~aYF`bIgV zou8IVVw|~pQ>VQ&v1IUp{JF+Xc>v>6`_CdanN^0M*vOW;ouV6E4lB0%yY?CNM^k;l z+4JZn)wU51$7i_&b_da)^Mzy`?{wFn1IxXAO`;B{eX7j96?qTDCs}o{@F(5iFqz;Iv z%&N`nW4u$cjj?#Q2E>y(OG4aEf%~}!TRPCXHdCrj=MHx}nA!pCdTs|&ZATVIr#5v4 zr1ZiMZ3`jp%-mbu4mli^dyIw8`Kh{Y`%|}qD|H0@c6M8!T)LM5ll;iS=CgZd^tP_e za`9n^5UB#N+KQEuj^2Xw6gv~nW;Fr%GPW({h0s0LV^vlZk2S!TrYg#?0oBw2lZ;DK zxAOf=o5^Wg#A@#pO`CGN&DNVT?SC~Gqf>5l%5D9?%Dw>5ec7iE1qD_Yb44;Z6xSQ2 z(Yd*=-RP9tc%!#RAeaS6Hoi{(IZ(!*@ zlH=5}E4Hvtm&0kWZSfesV2-0_7-t4#>dK8SHTT*2bg6tc&f>YtqfdMGV;ROS^WSFS z+9=-OA^D@xSshbR?=FAcw58^p#fp`gBI(-2`sk&O8B9LC_nKxaXL&42*DzMQUZ=5_ zp{kE}TJ5ExPWMViX$^=`wUa}vtJF?1jHa&K=u&f^t*y%}2lrxl_OrQC<4eX_Z|WRfn>*eN%*mhL`Fx22`8DsE!z?A#dHI+fAu;|V>l6uP)*-Hr0m zvFv_ea7Jh9c5d3bdFPQT=kPJG7J&S@_mkO^zI)hc%#b}~a?>nQhpH`Bts!NC?^lC<<+Gk7-# zbEAcuSOIB)tTt1;-D)n1rm>srAl@uNG}9v8QEb#Z-$t|arl>vZ6UakGVdWQ^NGx6D zR;$9&{&5>ax${n>@zssD1F?0D%eGUS%+^QQm0O+3O5pWMP5mz;cUYo-*2Q=5UdD-cKCs1s)oJTEG5si} z4x~_`HF_ZHhIkcu)Ik^5&jFDO`*Q!=U7tnP?T@LKCYzi#Jy9rj5Mxl8GqT0=8Uxm7 z+sWva+xl+#!*+Xa8IGkqoL-g9Z3Aq5D`l6Q`c<~BTkh;-9(~VGvrbU(7H2;LM!v+O=-V=R49EUsv6V5GcYq%GF8P^__LTh^dhK4w{E6-!sTQuw~0 zE`2D?A8M%3_q<$Hflp~JJvWXSunQbvwd)q8NE{C8^{LpeCJHANj1>jTZdL^}x!K}8 zE7i!dN!q(|e?E#sk1al*8c-LvS|&aPetrr_1CoO4!CoH^L^y#zHjsud2~X&Dhjym zJLH(Fhixt!XzR1ekeCD1O|GHkpyzq5uvYspirzDv6-duCYq#wlx1U8Fz|9sxr&u(0 z3wFEP=GMWMRutK`EtSu4eY$nqkEgBr@u^K<$}W-WrcJr8-PO5x>Mup~J*i^O*Tz_7 zElNHL+0t-YZO<^eP!6{Ap&1uPyZb?O(HG0zJ9rdkp=3)e9`pkfV83|HA!c%x7S22!k(qa1xw7vswGX-`M?EcS`{iMA2M+9nVei2kdl zO}X3d)^o6~t*Kia4;Y;<2UnVNb}_W;iNI;DzOrrw&?)*1987d;*jOJ|l@5FT`=?Hd zVF6SfM|SSgnC$QvU(sgJR{qtZ(J5FM6|Zobiz;mwSlH~fEtYL`ue5QLy$|0UjH*5J zDMjF>07##OS31+^V)+EL`0ITrFZ%*PA;#yn0pHxRJ;-fWo%WS2jEX1wa7IVFZh%cX z+UT=$!{9SCZ6>e6_}W7{!>QbdL2ZBQTd-?Aq6hG!-RJTCE_5D7(pw1%f6obIBbK9&q4WrbjpG`VF#-%m`RBmH!y;Yva#@J;G zqhj?j#5Q)z5Nu}?y6wI?_?Ou>R{2xHTXhwSt5uiF!7WTZcthygx^--y>+mh$VzTO8 zvWILVbmr=}v;`fEZ-KEBTc=vAbCErolYAhb&i0p5HXK#h;4T+3gjoOBWNFi0wb%u` z?zY!3_%`wcpJrpt0XuK5&nyEvxD5`H2SmXT)SBH+Wcl)RWNYy#dD=oMUCiAdYHUT1 z1AG0)+BPX|on-5(${4&4xp2a=_gwvP%}DST2v|R*ItTaCPcXop5Y-fdu%{Fc`KM6W{R@== z*$^pC-})(KCQV0tuzwMbnav3F?O1CZ*f|?jhZHS=UBlM*p{%*26*>Ie-3RWuma^|V z3pdYpb}%?E@SEw$&Ho+iT8#{SF8J_Um%KaISA728b`W$V*q?ZSYT94hF5X z0KghVQw*N+095T@hQrOZEM=wGpwb?D^3wCxON`5IgSS{yWCvwqd}Xkuscs);TI(19 z_xm^Y_<85n0oV^!ZG4mRe}@J-LR#xuCcxLTqDW;;_KL9qV=! z+!6t-PyJ(*Z$@5>yb}2saxRjRyzc^HC_Z26S$ONlZr35$!$*Q{EgNUb0qoqhvoHwy zZwtP(l^H0L1NyfQ*wuOeWtOoG<=Czi;Z)OmTw8Q{!PJ+|bg`j2#v6GEyw@z?ig|3u zCVE!~R_l*-3SBA`$CT023Gbm5eb1=?T`29^R)=x$WWdSQt`BgfmrpFaXS>*@b&K0B z9v0#SbcGGb-W*-D z6slP0;&Rib^%yP#Q5pPj|u2U30daOk`jaF-V0kdsGI?C zZJX5b>s_7da)LX~7h?^bW}<(HRKD2e#$ea6*Xs&1ksWNkDWks;38j(USzhgn*mTO| zJ`B3WOnbj_e9ZRv?)lyZnCm>awpD+Fu<1?|x`Q*Z1}8lGHO5)ICQ2vY-X?L{OtrNB z-Nv_7HjbQJtEfxKX*X3Z_}v82wa*bo*>dhZa+HFzD)=tewK#EXY{5piNYDp3fp@BQ z#3f&v5O2NK(Q^}B8dB4{Yx!o_sWRy*|r9vfG+zin4l#yGeGcZp|IarC{NK!O{~b?%Oar+zxR z%0#Wh=!-tJQC0WDUPt$ z^BwPF0`yvN^iyQ{M6S?N>DejvIT&Kn(oSD`Fo(y+Lgsx0&~@@v8yhP70`lnkc6Sr}K#4;9W{v@q~Og<%id|hQ_#ieN+CCus6N& zff#<3P2@2Ma7%rn2i{*5PS=P8l>I6NTz`u2sp-XS^eEzE>o)jvIEdw9UpzS+F)Z9? z`}ooIJpZcT(X@x}Ihvu5-~NO8jzL!B-dj{VIPC4O=*8%2e~k*#(0bUIzhSlg)E=KE zWje5DpcB#WQpzWGmj!HH^{0|z#On91rBja{Wx(n?w!Rcw7Vyoa;JP3m`4rV@CEeaR zeHRv+T?73+E5?OQ?ABbAzlhl~Qd->?>l@g4kr~LVk?jy2h4sckY%w~`wUclT*{Kb?9g%ga zaD8nL1iz#06wLfcY^u9wq6qw|0q&C8_A|_KDX7WH9Ta^JGA9x7(&28Ofa^=+J;}wj zR>zapOg!H8ct80;NcM-^u$k56C}j#1MeKIEgtsbJcWo_IwD|ef2BjepQ6BD#G(-z_ zMdUo6O+>ePWPF|s`3mXrqshg?kcYZHA2rx{x{fv_Khr29`FVVe;8me^$e&J|zIae4 z=~+rAo;t?HW|Y42!+7ZR*h@`pCeMixjwP|vz^KJJ&dlW_N~GWNGv_Ku@j2`M?dp88@Vq%d19369IGphi}1ZR z;K!)vYwQGqdD|fAa%>ym`nS%}r0Bd%z&56So~NW|3z*$6mM1X2#)qK~3;Fad=zJ^c!vAip1&1{$d@)U4EY>9TnMHP(<$ZXgW4j+2 z+xFeIM|5OKUAA|sArIufuL87vG_hU#o*?)AH4{64#PYo!T|fj3s&R>AP@igqA^OeifZ@e!?bi1_S7oL=NwVz7y1=qWgv|DU|ntZEDQO6h` zTSefs|0Sg(J`6mII9#2o4?9eqFGh6Uw;fXA#MU=i8F154zaz#AqU!xCkz8MJP)V6$ zm(gQ|QJ^4DgLGto)~gQq(etU1NW`~-FUHj1u+`^ckN0t;>Z*LfW4=mNMY%@71@bo@ zw2n6WBWZ^x*ub9b;pv=D(XZlbtI*A)eUl#L74xXK)&Edl|!>RDA}7a%2s1dL4T{UK@?ez1+Kwm#v#etn!1s9+w)Y1Qopd*6THpEiaJPAbK3y`I~W>C>{ zxV7lomwINCE2vs)CK&HgwJitm`z}H?1|P}s0seX!Mbh?3d=O~$dn>c9@N69j$oG&f zDLxw%;0~VWZQFj71M&Q(4POCnsbAR=zfSpEw82%Ig8+1E7D|mS4k3L`fcR^*1FmUE z9H;qWsYzFu!TAjzuXF`ylnTV9mEWOBoapSX=?C_YAingt!PLni^v+S#;i_vx3@i9L zhVJbRI2Q_VO6^-KQ*srsJ+lOAvl4LVs!vSyiQ!tVu~ok+mB+sP(xbg~j$ zSzi^$B!##1j0F48&g&BT)*@BW_qM|tdwcMRUW;@M+}_#VZclDWXPQ7_7y5rj(Jw>g z`tjkrG52IXY)l71Y`n#PXw2T%hK*K3ns>s)(UW|31Je=BOH-YJy}c*;vcmV6-%F3# zo6Dv}?O3lt3(CTSQ^=vl^n;GMTfI1kFNTG9ZA4$u(wmIi#;|>B!|}t2o4gBhd_iD% zm22$OZ}r)^I&Ab`&wQ!XbtLlZbJEpS&Y*&OX2jk!9q#teR|oujW6;gd@!^K9Be>XO z?&O`tbOgR_oR0gdn$Zp3MbY*~pOJLNPm>%P{W`rV#*4vLUZY;69wj8FUh_gzxl$n6 zNfRL9tXG8OFJw>cyYWDKji0(ldoP;OIuYvg_n;;fJGj15>re!L94-ggw@FZS(S%sI}q@vBRT2cfOSgpegn5l^uM-`P#NrE zU3@6}Bn|%?YK-Xj4Ee01$IrqMU#-5cR42Y98#)lW8n1On1>f>WXwD`wUX@KcLj4Iz z{W?-5p##t-#O6;LGzaAHRL*OG*K5Zny~v>(y(*Dva6&116w2)lPQD&;G$j3l_ z32j*rs}`tBDRF05l)gr}BC-Oab*y(FGm#UJ6FJ=9Mm|n+(+IGGRK3&& zB%1U|ipA%qF`KLU%EsL?y7}uj?mbrxO6gx0%7_c6DLc(-8I)saKS!WqFVSOvO}zCr;iKyG)W-Wv`s}E^ zT;lk?c51qjGkCsdE2ul^?5h5P+8p`w1l;>q?*ZvcQcEUqebdX(RaV(owL@d?D8|){ zD!XwzBfx0=(TtcU-#;`+V3$Ph@YtlNz8~V19)e9GB#mC{4Dg;-5s!B%Ma*W}wJ~rT z1O`v)eS958ufw>#j#k*ZDfm_&gfEGZ)|&B!FSK5EJ6~U=!^S=m^(?3g*-blrWMllF zue0Fa7qO|^q*I`G-Uxl{MSJgZOkdna2j3Y;PcrRp4$${D=JhUa+SeI~U-XRHgyLVm z&eL>q0N<9{`#Da??X@SiuUmX^#&j5a*VTq>Y-d*ai4cC;>aEU~ioOm5xTFLMSM;9o zCyzv=aoKvz+M?xR+`GDIY zu%XoWt^nfL#d6QveBeVf%-?Y14%OjsKN9G@SOxcY#FyS0;XcVRNcuEdh;JnHbjW+# z>jnqz7^m|^)y3AWL-@Law71ana1zLUy)gf4Aa!Gs9X`C*STW8)#1-@3mo{Ig(4Fo& z3*e+~^(ioX2M2sz>WRsFRCIAo>%^l^ak!~xjEoC~5y0|v$0iSodKEU}NG(PF# z22~Hlt<{24I|Vv+zTGP@p}2o>o*YZvM$c5@9eV~ zy3PvFF22SNjD{QS#%}rVHl|-?k6)>JK7|p$)lvTyqjxp!4;=b|{nf{VUQ0S+Df{WU z&reL(Ghr12SG2jWY50yJZThPSr>EH$PYRC~FL&6Y^1aXF0?Z zpnDn$t&;1xcJOdDQF*^F=OO%>M|UB*9T5HZ(a#`{AZ?`$A=1-oJzUJazVMxbo?=H? ztgYbs#zSXcjQCRN7vKY+)9b8#O97uZx()+4?~ezp?_xbbk*vPRjVV@#)m|2nwAdV* zI}yDR5q!!W^VwP(0r=7}wgVqPIvdkw8S3{0e3k|ajJw33V-|}A!21K-MyR|B8k}5rK3NHSGmqj>&AB;71o%^~L7<-e z-_Ed){i{3C2S3jmi?!7@f(T7PmkxR0R#e21^uaoT!FOGR^Kq9GtX?PSNiHs>4#^@t zM3airU7?Q;=&u=EO_t*gV@UAJo!UhCqARwt?(?8vP0tL>oBf6;0S6*a#RO&Dqi z)x*4K@{t4#zURZH=->-&qiVsBf&|0{k7@z$zb6WjoMz0-N6ou2ggbp)q)_ zFB#66^BDDCA)iD(jA%zY7fDS$r#1}ru&*b%G3M5L2qzUer;&e6nt4mxRK?}7+O5iF zDD4EQSxH~o&kYFBem-D}x}K#2a4!+y|Ee2bZXI6lsSW*KbGX2tfyB}-ReTsYpVE#GU37a> zioJ`0=y_hUNoD0}#&BYC`J`E}w6VbtEGLxE^nP%%$_@_uXCU84^Z?A4&PQ2!v1d5J zKHwukw}`>CmBaaHz*o-;`YAr)($^z`DUoA#kYKW*G|iF1+Zu)#o|ufIRGQVAlLR6> zZ&&g@S?QVnPoS%WK)>#!i&E*ZO5*?kmRFaU%9YBAwldsXyFTE0Fls^yeK|nUwsxHm z>kWRgF1TY{Ic@5oFXeE!Sol8Y(!o}quEsiu@5clF zpBJ-h+J?_d1Add|TzoOWsnc&LE$p)~I*jZk6aO^&k;+3oL*Li8{^0*>1A5ZFeHDp`@-gH&G`(e9e?YH`U>CZQ$I}aR|@#Rf; zU0e9C_xV6~s*CMs9e<$>`usNh!he6DpI0{Fhts~^N;?u_L#q!TOSJ!BC`McF za`n9QB(Mwe)p=*7$JWKAa$)xt=uU9$Q|cK$Qt0}MNg1=$03!Wf96!-pMV7BwpbbW(~VC)J?kX_$*TSgNp?HkwDw!0ewe}&!mOvfIl1K zDcT@h6^Sm$DZqgO_P!K-s1=~{sv-ZO&%qScT|nHWb<5sPJIYXB9av8_WY^Ve2}9}* zRp!P}Uj%S3f=(}^$~Ev>;pR)aIEy{+NImDi)JHx|bT`wFb;={^uYub;(C1(IEheBOMLtdx$T1D@#niv3?ph z+FrqgnU*pZ4TOR^$}TDT?M+)C-`ZnyR{(3PpXJ&OqfS8U z*g;ukP1;>;)pLrv{V&Z%Q(r1TQ0ry2fsR!m@Uu)1w7({R@u`bn2aU)20ItsX8HL=9 zty?dS5Y%-I_hrPrChS6knZArrEZ_>E`ZfkQG)Dvlu2tgiuH!5a_^RTfO}C7>>6sW* z9fb}kNyau zyecJJVLuAT!c{zh_FK`f9B4~bKTM2S&qq>;>)-<8dOI<$l*$K(-Vpe9D&E2U2Vc>} zW`P(Tny1ZyXI|e7t_v*c5Wlym_zQJ*l;a6RX%#4guZ=kFZgJ|SdVwj7NbY+W*O@*@ zjgN8p9}N!p&!yT}xajs}d+ujpD~pEgJC(=@K$|Zl-3R4-jKf=vZ_3M>awONc)H>Hd z9?YoiESGy?tfivQ-$Jz0WPM(&!r6lr?WVbWoyA_Jg~8Etm$CHa*lvuZrZ@OFj4nn} zfq9#0ABCKLc$auKjSb%C#Ky>J+dSsa!MauL58K7;J8gjU-@*QjXoYy_uwU?i`7TnG zo+=C?1xP}lvnbBL0Y|MYFp7kh)kKVXSlE-YNFrc}AMYXWRaBm8FwuKj;yM%ADB`l6 zCY)S_#L`_ko*-J-BGV4rxfnMbR-0Wc<{k`gm^p#H#}3Yv+l&cL@4xUfzR2}>W3-YL zoUhpCwN9twJ}09!BAvU;mk%ONe8i40!RJc3<7F;zbM3P5T$g1}4rMtQUGVHdgvR(j zJ>sWyM2_Gpn+CD7tX>(#^ab2Az^;9!-@ZC~9fz@R;%HmM-3#^Tes}iVW2yqt;nstB z65GCfFvjN(UvB)KkOr$7WSl-<>TSxnVEYH4>v={;lcgKM@q}h?AC;4ebfkx*qzc$; z2kcAo`Rj|LhNOdx6JJ->@#nMg=oaWq^?Mq6R8?cvV}PQ{rb+vt{nd@t7bm*;>+;3y z;N8{dufpa#J{ynjzCm2G#A2OW+xoJzFqpGz3~164PI#A0-C2?*)7(JWI~R6!<9g>B zB5AF0jj^gTDVchyaDYxj%Xtntwkqj9-8Qhwd)4T0l8NP`C?**W7*qsj75WtdF7CG6 z6vZlk0IN<#H;SXRy9Y()3o7MG+-Fy%^ZDzSuc}yL?SqWd=S#7*H7=>Aq1bpt+vvc1 zqJVK@D$I3oGUESIK=<>B~Zp7HT zH?=O1bGyUfw02s}^&P+`uZRoSSE}i=wqa~lKx<#TYIA2fH`X)l<+1jb+E!_ar!AVM z%S5AbFr<1WRP{qVHA<4vSh=$hkk++SF4o4U_rI;$vB0BLdhf+wW0mdhAh#-fDAs^nPqGx!{EQ`a!aah5+}$6=nl% zCdQL}an=n2F7NsnpAVyp`2zD?gR96pD-_LXDD_eL_A%!*+AbnU?b)FP*fGkPp2pfc zpNFdr)k{1icX)JB72~rSqEpUaqQKt9s<$OR*=yp}OfKvukfh|Lv6PUcd=@O^OE0o* zV9`a3V0|xPCCxTRiCb(8bhPps!i0dmt`~im1Oe(E_0ERNmxE3{qjYXg%#kH!;^s`B zLr1r_Q#aLTm_j61EEjgW`y2AA+u*-?xTs zPG)X@?9&?^?e|l@!PF!9tWp~Rx_hvG>H2VA^tFu=2^H|Z^h)7qNWL($NWMq8Sk-U* zq1(d36h+fM3V9J!x$r7CHk$Q8<0-**KrTva*`z!u^n_r5M-{ER{#=uBtFr%hjz&^23~bgbRK0KuPa%t)3A z{L{YR-C)5y8*z_jKGR&?3a+nV)CoHEP9vv(r@4K>c)b8Y=V%CXVm z`6y&d*RF-S&byZ)7j@-2@>#@l8+mf-#<&^=5-l{+-J5RLUx2io9)a-9#CTSWn3y_u zDh}pU?1KL{(!sV{C7weRl$Dl_c>wn+3u_lO$dw6$mmxRXhI2_-r{&!%2dE1G>zh8% zP%RYWpk3c&F-bnZAH!F+L7;P?K1bzERRmt6Idk-D$x86(e+8Zz;F}I=t#123)}VC3 zq0U!vh3wEjf~-+xU$g^WFhW)|6$XIEs?XzlvAqq7}4&7ES}Wi z00{d-5MSCcVA4@zpn06C&y(Ut*hKo0MD`wBIQFpZ3__W%RTyR6@!0w zz~~xn7$w>@d#sD*y%AkNUxWB|V${h=el-*O6GTtCHPN=fgvXB0JE^;=sn3Fs@$=1I ztNo(|C|-CV-rQ-e-Ve0bMUp1mvObs-;z|fM3DR%=q#ztnAf}%?uv%5Pmk;n~?Tm2j zfJEoHDg%VT_j%1fRT>5W@a={8(g^{REH%XE`pC0LS_BhI=$ha~ZMgCEwX55qEDg)~SfEf05;^buA+XQ%}{=JPGxiSH|PfJtQMCdUQ!94U8ns#kFD;28ec2geoAG?Q$AZ-_4Vxz zCtRIXV4hA$wR*{MMkT=4XhUVVH+}Pk@!MP;gNN*3A7NMb1%nIa5nDCsXw&XjE+G7a zn5$AKV4ohY`y+hOhm<}(>EH|P(6x_PAzwZ{{zDr!`cTiuB^`WwBcXIt$j;Vd>^;&s zq?g+^jmi$OuUhL{BR(Qaw|t$TEql9|vc9;EyONFV&@Puii52X>Vsp6VL>ldInk`RB zNk35EbiW(Rldhs$*S-BBOmWxxhSAvf-mjr zQ^s^~9ZLIN5lqT9>zK1`^c+roKPbYdrp+tb)0^plom#s zNjW^ZSWny?RSh03n2x2`53JH1#3%U3D-HVzAfU=SBjX=z)mqi#3^pbA4Tf|nwskO2 zZz_IIIzERFdo5jvr6qItVpyCUgXk0YN!LCxuG(!lx4*Yfbx!E1aLEU_H3g0&-|3~q zVJdKZB*61KgK0Al_)6Y6v9J2E$VJkvE;vmgL|-v(v+uRJ2r|^^87ZXLuYy#iq;qS8 zq}6K|{CNNC2l}M>9dJiQVl_=k8y~PH-AwW>UP{>xea8^tyG@jy{Ku&QV4HIFUb)x_ zo^3pFNOgN^EGf8vkIJJ8cCqI?hBkC#(Gwa5Z!ktqo^+SfL)b3`!G)&UP2AZ5W2m*D zRq5NYK1Gb*6thchgFp28O7t2FyXzvcnWn6l=P^3P7<%$or1q(=I06ej3o$Y4m5^Eq zg2N3-MgAe518icawa#0CKD!hh+&>M)6tV~Ze<2%3|LG7%NRRzy4u@OaIb=I9y&I8J zuRL8;1qxs2R@iaXseakzL+gD9SZEiUTE{eY%H7oF0jmqnKO?DW5!*hej04@>#L^pb z_*%zCB0IlLXZX1~;>&H)Kd>&|AaEP4`oD8y#CB`T-Yx#k@X_!_B={PQYe@Z%#3Jvm*Vxz;(u}m2K+imZaNu*bt{aLe$8;i9)QY)E;4Ud zAtUL!C+Th{b*$jKIpjZ;qi;9@voA)2i@Cx1?of)aE2IVp&*wvf(LjG>$UmH$G~kVy z)_TJM!pi^O1jhHKV)SdGq5cnCPw>wVjauDc;H$a|3%RV)YXSI)$U{}Yn(awTIoxr< z*A0%p*z+SjMBK%~|HI`Q$vOcqY6aa>Y#KC#p^32`Uqe*r`sD?6`-*Mob6(rk(smU%$|u=)=#oy1*bU=Nk~P$NTU;?67sjsi*5bDHIpL@zEtT zI7aUoq$f<9oA-=-SK;DJoo0PH)K0}(7lX;oA#+#ZdB4#H&b}SCW7yv36Tosd$drB9 zxmL%Z*q_#loqm=!1L)-5oePW>A@!u#Km&ffYY?03=;1`s^O-JmcE49p@g4)Pb01bZ8)M2otZ8%ddji<(QwzMdO{4X~zL@3;owIR@ zYN+!Cz$y6fKtgM7dN!6rS5yPMKPdp^!dX82Sl7}Bl*hWLT@#`&5aoh*?JbaZmSIJ$ z=h+l3?qiG&I5UnZcY4tSwJDu=c=o)^4xEvR_rY^HeAhoW_=rbYH`R8Q&p3nmE2mym z`KgDVMY$Y>O-8}X5%S3nt*6;@EPj3J{5e*ATpZ>Iu;EVYoEw}!p_qUrpN7QY(3zoG}3yF6YsImj|z|E(ibsE%`}AK~!x2x;@QVDj%26XBO!gJfsoe=l(78 zlP9mdptP_>F&4Tw3n0E?*m2u58v!=_gVx4ZarQLp;6ysqInNPU9G+?+8qrTOodETeF#dj4U&K zHM+1wAeCRp{F&vjk7o*(hUl%t8* zG`6cET9;*HeabIE`Z4ZWuf8X-Wqs2Tn{gVCz<2~S0{mz{f!GTJs5VNvZ4#%R3Jomb zPoGoX0?|8*RsTE&NOC$IC z$oa@jLBPvC@xIuleZF z?~;flhQ-m=JTNS&nlidv6ivD59A{sGKykVlcWlRlzx0`gvD;q(#d zMPk1dqBSmc(uaB(2cscaeOfv-1>Z9rOtfP!(`E$Nm1w{at8r>{fmu#5cee^ zhq|v-eTLzu$ZEOq3yx^7Pb8>r{DNk8_79q0v~9)7H_Z0>65UsL2{og=`(2kdQ{)j1$^y` zq$V8#-#dX^yzlG@ZmgJoBfy4!7NRpuPSOu>v6RsOr++?wU=I0+U{5BF+#lDM zYQ(-n$~ZQ~5SOkRQq#;Fe~{)}>3Y9Wnd5Ja9q|!hhtQ|~%q45;PWRE2Zb7yTazQHT z2;*iETk^M|!0JGKS7v{_->*s;=M)UFtdSYd9x1%Sbh&f(Ax-R$({vqy?hf%}#t!#S zuv*O;O<)#8PS4;CK{eSb9{rP~8BwR6Mraho>&5ADry-M55OVon0 zI|gJ)DeH;?#+*rP9e}+5F{FiVjwyyc0&LtB5%2e7(fiWXC@Uu$!Dt0--K2@dpCfv# z+?NFRlE^oZCI^}WQiH>f4vIPH-KpF;I0E=%Mi8f@a>J=f=$y1~D)$&S1xJ8AK?jP| zbQQqpnj6{|LT*SUba01LZ}j-L&L+U8mh|hXRGst?Mk}TG1-E6UgQ_(qDQn>80HfVHCh4vRBDI4DQS$8#WOQR5`A;?eKfhLyU z6=s}lf$Q6ee1i3LGIuhn`XypaeafW$BkAhSjs}~JkkozaV%v6H9`FdTq5g!VrVq!$ zgJd-%XYyAI;RgB!b1eQ)8!_rd#GG42;B#IZ;HN8FN z5|X`AiNM`}MCWN@zJ}RG+$Uu8Q!gl1Ciu=utQoJs`lz`}5f7U)CH z+MI7!brZftGRAMqD!%E`&X}Y=t<=G1>zsar*FR>hI%ug~p9-1sDY`bK&E7F!+Ch&= zwYf4|z(_bwNd=!~KG$xk*I{N!utL`nrc_|J0{%%#e0Dxpp z7ijYTP}d{e2N8XP#^m=?z7@HPIE0xpi80ad;c+B3&g%c0=v&fve&Adi{FO+~r#xN- z|9RL<*%TYVwmY?A2H_nQ*wriAP4oS1pecP&QAg;5ZiV#Y-pF(;lBbT%ZE&OsFGOLt*OUS2rP7Ar~U&BNx$69XyAY@UMXN!m3VO??BuW?=|RN3a;`W$-%K8*jtd~ zS1`bu6dX7M81;OR2bLu>2194SSW4Yk_ryr1SX*je^r(6XcK)g{d~%5W*F?I`W07;G=`7t_&m>)2D%40pVvW{MAnM<1ZN3IT-7J@-h7Xxwi8WG1Mm&2bHeRaP;B| z?41?urg?c&m;)Zo#7&ZC=Zs?QK`>JD2uHjM2y@GUyk2B9L}g=zl~az6btNvoIj z1W}XU{Z6@$iytST=kdE(7Wr4dgPYd;Y~UTt7Ej236&eg|^|t8)2^*>I% zrW1+zs#Sf0=jKGN=v5LNdTjkJN63Kp>+j)33as1sxejiLf zx?dt%Dc$cRUq3^Z%I#+r9?s1XT`fI?JdWIrXc1iMLx-RXIJ7u4^nR53w0F>WIycbq z*CVM(t80UkjI^DXN(4^d%}AX99r`99Rz3E-5lKzjd83#7wCi7+q$bT{)J`~A7tsN| zPWqJX7=o3NJ&~O8$n|?72CLbAN2yF~&quTmr=*#q6#KwpVPt-lGCEz1mOgvu7tm|D zd+K0|PU}Ico;VF`972wWaalwMik!4gh);TmR!5#pB-|y&mD7eleP>2*mFFg%m9-Yc zn`qO-{I1AMr0t~t7BLc&{=~5jlDggOaahYcaMM{y@8?JK$S^gX8X6A>mPh`TO4P-j zMIJr7hy3+hPh3CC?2F*hg>$qojp*|MDJeL&)uit@{&b3S2czw}W~yJXuR~6AIGR@f z0Kqd-V`vM9PrXm1TbnxRk+$NPay*RIN{Fr?QqvKkPC}q7m)tYF{O*f*uZBXt`lTn1 z4lT8893dm75VT1BH*tR}j2j@NwV$wsA z)+eHyjQLP)8H{Z+2lMz?z;J1DxXBS;2bnjJ!MH4<&K{WZDl5{p+ zCQ8_HBmUl$5}1S8qm3}&)Roiskf$8}+^XjHHftj$almy(ZUErVY0Lk#<6&@g8<3MO z0~}r4NBfU+2qV~k(5A`ecO%JXbg+8#s;4mji{#8F0S_kq3ysRTAut;T8G0N3jcTP~ z>{R&Gla8F*VMYJhHe-cvY2^Pz+#qQTi+7&t#s`N^1}O(SojCueuAjNej)D3pl9Tk& zs3l^9M7t)54?(7SI)e^G`)bAkT+SjyU8$^KY=@EKUz6`zj-QkIGS@)>FG6n03Bsd3y$JJ0vIRO!3^5j)VIMlDh-v#L_laJL%Vv=#`n> zcd$Rq2to(u`Hr0qBiAMt1nk*+kGB)x_)GKr3S1<^LQ4_JCwpgF$W z*AYghU&(>c$<2`5^x;$o5HE^o@-X)aOm0kd@kd~oH8BWYuQ*(q;ZRRzDsQP$$FvO` z@ytL{ZUam=bqlpz8@^*4_|RNX-4l{de4EDj`_+bDouuzYQqxuaie+SY8Hwj0x%b|O zIo5qV@olxpr+3Lwp^2EFw zC${fJ>LeXVZbACCR?Cfbr0WdCTWXA=)}X91(jChPj=ubN<`|p@zV^EUk{)r6{HGyO$D6)fmeKi3QhED{Bi=7%#B89N5PoJq z;~H}(i~t+qU1p19=G!OG4;@0E^eFt4%)b2v{CqOBQ)?1yqNfU#?j|dHW`w*L+I_dFW zPO5w{aoGK;>z_e5AY&kOD=;#j4Iq{yGh#Q;*VP@Xw(JOGapdcWmR;!gemD~SL`Sx7 z2!D;FBux?>g!KJ!tLX&3UXc=50P{h^Gb%Z8{x%S6NUb@ip}a&ms4=5|OCnE(2Ee2L zuR+C@;)nQh--A<^2G$3B%|LVj)VpI!!Vk?Q3<7pGF{m zMcPVQCD_W<3_P!EE2u8d7i$kvLqq%@({f*?6P?bGw<4EjcB=6rw1%6t$DH_=K_1NP zM=PI4z^ATCa<2NS!aTO8gO(!Yie(1)n~=8FLp;QhuF=yOdaVBwbQ02b(i!$;#CLt$ z#6CXyp*M6-Lzk3g<$tz|=up4nVeI%`` z%C;5}J^|O_#3W8{sywh5D+WaORl6fipE^82K(#wa9M2(!YmnsF!RDspFxawRJ0X40 z zh~q27QU4aGDp&&D4*46ROV!jQ?8mCOL+#jV5>HFiQ&cNWrR$^*gkq_yCx{Q$ z31nu&3q9lVPmIiEEEK4-lcXRHm|+_g2jZMqP7bBs6C*6LZGAU4L4 zj%FJn_T{}UKYxjA&(UrUd3J(ZvFa$lW}@-?@bz1R#a?mMnMcv(^vmJ;yWy&n<6p1M z{}oxSj{N{^GzqI)L0#VJQa2`i+8Q=U+|4Wx|AReL4LzN(dY_? zeL@rI+OKqbl#;YfR>Q9*zOz&JH*`FPZ$#{Eqiy~t|T@33XjAzXe|Xu(A?f*d`mHOXi!*F4#YbPRqB3Hb9#97V z%}8p}kvEzk(zi_?NF{V|yGO~bM(j31w8Xw?(v{#ibw_}~+_LF__Ss%iF_95q!1V&&KNAOD8`OJdLq9*VBXTp+G-*}rCZVutTMW6psgth#KSF-y zRz2gQRiUX#a|Ok1IpyV%ZIFYJI;*xZ%T9{nP-KnJHlyt~nXI~+n|g^(&WEgztb+{g zmI>bnBB^ONd!#X18PS=eU+M12-|2 zFXsici)4?@GRW_cK_-3W?#;;KeQ^2?cU;Ex&UW4>W32aSGG_RBHu4SR_6(n?P<@52 z^YoGYL#akx+&i1}%e945pJmnif5#!Zve$xE{mxU;X*OT!N(5^y#a_q;)GXhR-E){^ zx~Han$BcMRq@Wq>l%z@7SET@_7-osw3Bf7Wzgpq4Z@dA+)J2jPFov(FM64G^KlC6&lgDlR?(ZU=a_l&0dx^Y`bjx{rlc2;_ zw_$@!iuYJVw|>t+u15NiE`n6|+$rhmgrS-%Aq<|*uBk~^lBJVq+k*zb)}`odeqmC0tzl$&h)Ftkn12?a5P_{?S+ZBxemtmxruIsL+H*r`xIrY#~fqSBtJxv4eqDbmly&{aB z=3k-7dJz)*-aRaNivKb_$1LYcY$szk&U;6IvHU~EW@vRjqBokbh8Q*3`B_AB7X3&| zhrNee2t=#W+qhy8$B)CFoEE@(toMH85abF(Z)R2nqV`5-TI_d5+DykomUS?3hC-9V z3m~}%-Jg4Sw#w+(hOYg%J~;x6qn6yKrY}!g4zEP83n2%k2AznjeP;l_4tjb@Rh9IV zOyB;|*A5Oq-hnJQypgQonSeDb-84M}fo?lmO>pX9tH+VCbQq1r+6g-V^t;6jowl4e zU~M;ZMVYbss54%%>c~B|Cs@sE=DhnB>fcdw#RhNENk(oSq{$_t7Ck+$NerpB_<1dI zG@=PvEx6JgN;HA_4w8}{j}na=brt#gl!5GGQlB6Vd}N95<;XuX`r<@aXF+D9&uHLxP^K#+I=VFxH#fs_-Z(F>uNc8mWB>ggVd(&&x6E_XK(5kL zgBryHi{5I@N&B-wwm|0O7!47dI_8fIF~%w3nr;3lfj*TOtUlu~@`*m(Ly$VS+?E;a z=v}dJU8P5$b>H^YWtpA?>4`}j&%|>MEXT7UKAE`zh7C_Wu;@oKPSqojy7ubn)l{Q_ zV4v3f+RKrglVzjTzxwTVf5TNzeSrm&jv?!76z8RIH2Foyl2X)6I-tBB(Icrkw=%Zd zoHNT*JE*9isRx$v6^p%Bgv(lZn3D8%dmAUd6km-o99(q8@{9{WuAJ)GFAImYfu^( zrH-du^m}=IgKl_DbM}EI2bQM4SvUB5^?r=rX=v*?xZaicqU$BIo_Ypao=dI`Gr30r zp87*rWE6s(0x_hn{(PK$^T{dDA3Mai+m(v)0~PJT=I(FyyFox+!+koYbXJE_SVp$| zP`4tJq`t8A7}#?Wee3f^@;1^f86;XV-*iqV!(A)T)TbEZ154U)ryf{RPgrSQ`;6kZ z_!?Z~OjF$5BqV;npT_>v_+5*9dqgkbrd}~=&DAk*978^uiH_}sKho( z%(NR8{LVzjBegCeG3J57*yfsW)RTym^p6zKurc&W-&eT~>D)~u#&ZK#3vGSgBhh6X zHi`$9I#(c_c_KE-KJo63L~H7SWz~_0cC>@gD(2LE_|{SG3j6MYh@Ju+S0he+S7@YC z>P8t@&>VU7{Ql;e4){(SL|}u^b8{QQS-4WYQ^atY*5Y_k6#A8EMhPHbr3x_Q=tg@Mp_M)eJhBamwmz3Oc*0oKY}eXB&b zCQZ^|O^hvDZ7_X;LEpT1zoj2$G3UUt<}d@D0={z&yd$xglKpUdM2jEwqTv=TjIkDq zUekn!c%F}3hS6MknzVso3mHt+zakV6LR5O=^LbuC*TN+Kp5Ozw}w)}-mHO*)0+Tbek>R-ceP z1quJ2XgmRFGd1~S-rj8n65!IoQ@2Y^uduSVE&ftJ>T^;S@mvOG9CemWNqTe}-tk)= zH+-#%{2H;Z0I2pQtx`99qWN*l5fzKADwFuUjUfsP(t@YTbahPtyHPpNj(vz&nsO2mfbuy7sp?vHchE>=)>OPpwDI zvwRI1x&^>)hiLxDB>fNOU6D4|$y}Kj)3W#-KX&#H);g%|{nwA0&|Vm8%xPnLEQRcX z6#EGFT6wxXqW!0C(u(Y_BDZA_?2&=(f$|&s0?M;`8tNT@uUZqM<>i?Kwzl()V)4$r%9# z@6^-*1Q(o#pzT@6w#aXg`;dMoJ*C_WDJ_GbzIujZO_)Bz8IrzM@wYMZP2?;@QwKWX z>#5Nth^A4dULx>wk<|3cP!Azk8POUSP38?cX+xZYd=1$gc>qaCQ|jfp(Ac-BXV9LG zJe4wdU~WV7-xR)%Xg^B50tVVzItiu?Vq-vi>O{1H+B?QIZc7{i267FJW@6GUP||1m z!0G=qYfX;M0Hd5XP8_Pa0>*}V^9XM&9q^7rHc8zWV1JU)pIKo0Jt>?TdJs4A0h-7e z%pEEJ)YL2TKQl44Q3a-_86Ud5)FbjwAS?9%Mnj>+Rr*AQCJc?-K>6>;o%H)j@+p}Z z|Ah&BMPxPP*^aD9eH6c2dlPYKzT+UqKKtwX^jY&ihao9RlcTHSXLbsBn3%pCSQxA~ z(5d$zFF@`=e$8O~hP+XN_YerSOC*uc>`6P98=ucYw=JSc)aSYFQ@pN&kbVq$?5JGt zt2}``-py4uBAu3>>&b^L`mx(}T`lSWElIj^1UFUExdf_x@JRNp#=(xO9&ngnbA{g9)q^>LZ3jV&F<)i_a_;fk1`|H2+V@=XUI9og>3)F$cLWT{@V7JA)Pf>2?1$8e>U;!mb6yF=i(UZ zRyXPQp5R0)e%~I$RXQT5;~{u+j3l$|8w9myrcDo=xSoyjS|oJ?9fjYmdx(atpdU9A z!s>}(oC)qoWDP_%MwX&HoszC7ZbxQ2vIF&(At~t%Z0|p&00)I(TW^l9(=z<2|BVhR z#uvVip}eK3w~&8_@!ccDGf$|&=n3dz%IlhX&0LpK7a`i%_t)g;F(bBBQC^QM*wg4& zs4p)k2JN^bk?6y&1oDH7V3s5PyEE_w6kqdE(b-Frsy@+Vp2ku*9k7+#Vh-Y($hAdh zQ&ZQK!9$klO!*Ko*FNK7udCGOlU=29Lb?Wj!jDWM{{JGF12O`d1$OPG<7WFK2Az;} zuwBd6*DU{z*xpsswzEMOC7_%IWtx!E(%|nS+KKy`@UaY{6@aNptBF_ZYfu^F#IgXQ z)tIU2M;Y|f2FlA8auc!}QhD{0V&or4)6W z7kt0S9`!Wy?DFgEHj6q4AgK@mHS0z^c^ZD~LVm8pN+KXZ?WMUN8 zLrz09*P%--y{Dr&nZ1x!E@9z$C6fF8&nehwqH<^n|1*))^tYh}Iv~dkgx);P*^X}* zP-tE^#JY9r#L{e}uJR zJhYzHFQkvi)I-u+?Ki3EuwnI(09Qb6O%2q-{h4y@TXAgXL2j`4+@gMS7a?m8YiwHc zODD8+SRb#+Inw|yrJdUf2-clS%xRT-feqzxC4PUH7Gi-~v#qfjB_4YB*`kNl1)cR% z7fZI*O?=La9911&4?@f4w`dXw_WJ0(cyf~P$0Ji?-4lT>i0J)-Hj+BOLX$yvZQ)xK zxw1xZH(|4)%h%63{?8f^zitk$88l576Esf+JIo%GLx^7+i_WU01Hz9Rm)#c>Cj`H|=A(E30 z8J#_%StN9NNksE+scE3=dI)Nd)W95^mTEM5-^U$U_)c_uG^zf<B!WiD}cW4NAPRDFlWWD8~g824D?B3H|8VAbLTjp7<8=3 zJ1T)~i`;~0qbtyVAlfh^J1b3WYan+Zb<;O6tUa?|HMnq}kr~)at2jrooj#tG(N8_? z=-WrP;C=h)|7qmS%aOyJr>W+uBKN_QT+K!{2e8ih`rJ_-Ib=&d4sRs~xzpY8qc3P(G z*v5P*17t$bFCZl8v~8OY28zcI+MG(NMfxZu)GuXi_c(nf9h?-vi9QNMJB zo0D4o^aYMTf;^HFfCqavx;D4B9*A6mnA;hhEFMO7?ANxK_Ph+<#>l^soV0t}1A}ut zoj5fo2oF{}#Ltk%a{+M7kKBmlqz|?|E^YDAiPe$ZA9O2oNci0bxeIBU_Jg4Dqhota z;Y&HtUI#AqQz16}+*f9xK85IqSSRh-&k-Y_FVzXkV{zOkBf!A?9I1Oi(V$=A za`vl^FRd@RR!&<;n%MpflD%RS8%>DkB;7_mt6$@i%1aCjAvyn;OMTSAAp2m9&8rYC znQtqd0#U0AH{EfA|JOBxeGTC-}1X^cdnI=P%Cg{QGKyn3CXbsd0t-igS`ZtkV zkbb3`A>Ojdw(o~6F)fE^F=m}K@=pc(F=ic3Mr(Z}w)5$LvPYc&u+s#g7U_kO&Pg18LN?iZpa-6yY_c`(tk>e4a?P@*7!)`MqcCezklr|j17Qo~3$PW;mkw-b{O6GJ# z>pNBsjSX$jM>P4Iv%>=)TAGFD4j5j_7}vK;Jrqc$P(UiT`jUwsBLv5zr6s1Z1<;H(UiF zK2J{wS@C_Tf-2gKz1CUni=2j>jO-LO7&qpP00XMa#F_*|cKTdTRPzCI4F+Lrj=D|1WeYG$q!?xgnx= zSZ+n;_M|J)!x7EpjLefkvmX)DyOBCcYjvj8cW(!Bzi9@(&72MK0DMc<;MBh~U5o$X zHm8Q|$e7Uo=Mv0oy7FrB#;*;)F$ziBuE9pTC(}-kbajb+7@|jbPe&d_^uKVoAJv_J zn3pC#E$-4+%alvjL=^upk`5TN5&gey$={HRkgG;@42i9FV*G!D@%w5L{Dd*txu)&d ztjP$l;ci4ylIAOFKhwwd&I%`IHtENx+R|su`8)$z1z8JO6ImV6+uy4q`p(A^$do)e z#l~HILJmOgL$qW;w_tjWV$qnLuMHcm9!|%G8C&gK zkNAi^x>{>(1~5cp7nvi#wmrqOeQnh(nUuQX)f1ctY?6fXrn!E`_z@ogHu?gH)&r!b z&yRSQ#^EK502_Pf#0{}>Ae8D(P zgArhh?on*j>Vi%@wOZx<*XsOyv}IgV_QV` z?0T*L5abPYc*Zu9BfuDH4UooCW2&*OHAjKnHArgG)kpTc%VgB!(zG7|b`aeMYr#@# z`g6{pK&r{k*t<*edl!;@iJcS2bi!(^kgCs@YRt11&VkSQn3hgNdIC32;}Pf`0d@|3 zSv@uVsh1(Ff%FB4?wwQ8ykm{_dvb!^_%6oK`j?2gn5RpOZs zIRw$uJpCXgDj$U8#+o`-8vCp-4YG~(MDbLOZ$i@V==cQO7&14G06X?+NG$D@J1&sr zu4C9U#|Qi=U+=#yhtr3}&nk$Ptk-^X7Tc=Z79ex(^!fMcztPfQ25=4(=t z7Eq4Ucm%>Dz+SW!awejK!imUwVRX0!y91G&bWWJ9w*}(!GRV*DWr%Cw{(A-g1#yPS zR(Pro+P16nCN1M7jLxzR6UxCa(}g_2xmN|RUOyP8@d)&P1lSQbMN;QgwBO#J8x=OX zjYv&L=I}#Wwcf(`y)T6q@R7zKAcT|D;+1~Z9w|7%ha{u7g)m}0l>_VwQ zjB)iwV0>VyH*P6by4?Ox1yFDNewZJ|K^3@CGiT?OP)JhKfvLbg<8u1BQn#N;Au)zO z2lxdi}F@>fJ}$m&)=U#+_qsr~Olu{{DwP1zq-hPd@x zAv5xDYe89RI>OlH)lGO009>W1^@s7@YFCu00001b5ch_0Itp) z=>Pyg07*naRCodGod>uyMbWl@vLaa|BOqBp$(WD~3W_KyCgEPgVEKPUz{G^Z))| z2Q+8SoG*6((;R}p-;oz(k4*iEF&YN{EX>LxwrSl4aUr1=37l){s?KkLgU-qdKdE{c zv94CzI@`METxEm)kMQd~|D+s;UrQlyQPL``*`Ib;GbhYt%A><7GB@r*^ ze>-K;|2No68tS1$bh+x3_XSz45{E~^eSkFoCK>c3{fU9BjQZ)G9^Fc@ZlI0PuLTG_ zGFD1xWpP_NE3@_B7i6Ifa<|0r9BWMd-|$c1zM-`?0ZcMzFSRM}fd6H6sd|w0l|m6& zAw$-)|U2zww1zRW> zhtfLPy7aVn4|cXhzH^~>6G~v+R$`$1u?$2(XzM9(^bZBwR2lmR8_A(>N9{6hkoT4H zumYOvMeRO)qf5VsY_FX!C~YZ&`Jf=9`EQzwg|^CIL#a)& z7Ob7{SJ+(=bhKr6GqT56St0L>A(@Q7EJIOGFeNMNg-u`EljZz@Up(kz|6cGApYn-t zc|9Vf=NRO%O_0ZdQtemp7V}v3=b3{1>zewr#ne7;IHP8MV7; zt{{+sL=n6&Mwd}Rz0*NTAIm};zpFxBrEo%7VD{|>g|6I9)Rxl`y~ZKD|S+Z`8Y+c5* ze~@xQ{)kwP?2SPd;{^FYiQ#i%`iQdMs00WbLLT^{({J zDvbMoYEB>+$O>t`uqWg~JJ!jr(De%IXLYf>vJKi-Q^Bkw z`rUd_`~M8w4_TbTbY+Xvs2*Z9ax%t+|Gh@kz8d!|AR#{`)I*uE?c3bJzI92U-r-&V z3Mw-7-X%bg1-Z()H1LbbIdW2eZ05{fx{}aVYSghUow}+J{K&4bYU89f0kXxd+=59S zlhqGZFMw|ri0T2%)(hQL$dWgCv2DOmS-H>1SyVV(M!Br&c7L$-!tMfOz1gdxT^6!6 zc%?jB!J(Y7YT|5dRfqOhpsDJd-eqpleor<5t1O(uh*(uw4>oZr17rgSIoSngTMx2< z&4kgGQYMDJ=OYkN0q{B51uA5{NlEH`S9FE$%%ZGUOob|gl}?5HM?pY);64Z0OJpaT zPzL*0meO0>vK||%Eh-JD#O{~d@S1Cb3d zB`NV4N*wQ)X_seL1(LB1Sje`EWraLt+b4_hX!phM!$tX9 zD~O$opnF@JPdL)O~7}2${Ozo6y zA^)y)fvhjG=i0VF4hjP5uMBmS0U%M{i%bteG?)B`gg%JMQAF_gfKB~#pgcvrJ=g|$?GncggRwwDy-hi+e;HFiA_=BybL*v%sbKR2W81sX z5B|n%_^JgBb;@#nhWdYu{Nhj_K5_*@2t-*XBbOkraGwmdk}c@3HlrY3#QL$c zN#Gep5~-6xPh}Gc2}d%m;3_Y{tWI@wdIBmsFxFMI@%gqKMOC()>WQ~@FY45veJwbm z@)U06P3i$V(o6EqwpJ$TVJ=1b2yHy>lztF2uAr>iPbjhfoiZHP$UGwHie0-H^A1$ z)W09Y1zjw!-3DNp020cSGrHb^k+NJ+lCuvOh0T7Uoht)gQC9wZJS_a*Bn(gAnY>7J zAW)s)b!mWc)s2}9j0Wh3(RDfyJgoNrlOA#>*_(d)^B z=(?$5>aWG9tXs!WkDZYBy>}x$veSZnRK7L#5A9$V+I33Lr;w*6=AJH{#iqGqER$Zc zn5{=UN;3`;?;3daJbm4a7oWi`1&IZ3~0soGQ8vrME#-^#bEp zDV--Pe6rYu&9hP%=-%UDATOt2J)0C}pUgT^e{5(wyiIdx>#=8s2{4bvG%H0*-I~q{erKjEA)H! zoTvU|Z)f`Ov0uMWP&5Kqtdl&J**5Cr6{xkbb?o0z12Y*@eo*Sl_yOcv!`zH|aM7O> z0w!TXt2`S7x0HR56*hI&1%T~e;-zFEw)F{ilmmOewQpSqIIQTqD+JDgg@kf8 zL08x&&xCQTfJ?b_@DF97OTLp9Y;0NUnU6sGoLJ6h+o6t`<~(i>?Y>oiK}Z?!JiRgP z*?M*XC)j&-(l@aUc-ay_UHJ4UYZxhUun*z-23Dp5j9dnqnDowMR)MVdX0!Z7R%h!| z+CjZ1x4y0GfZr1WsH_WQeOlH}ZxHKt8>6mYYdeCKgJMCDKPn_*<>ROmcQ-FKa=mDI z%pg-a1a!Bqu$YAHpw7U8RS$oNffADAA=xVCrP(juvZz3t!&2E=~UVI(3xCE(WPF?3a;~Z zN#}bPhx2wXGrddg89}Bp+xAi|9CA`4 zP>|(HYH%D(1r2g5>!M!ZzT9FVyRVS1W#yrcZjC~J zVUVdr*1OrYvd-#&-%teY6>WfVe7?n~s>d-3`|{g=v0iO#^cm2;jaSGe{+;TblaMXd z34ndy0v_Z4ztpwpc~y8_cpvz$a7h*);RaGznO83WmbLmqR?FY|CF_7aI#z@LlxxSj z&_=hQu~YRF=_oH(BiMPRY(!R1^UJZ!>TO+i&_@!oK1{0*^}d(BgV2^jR-58JCY#F( ztK7tMVP6JM*sf_~G_3!#q5U5l+SfDJz*wsC!nQmHdA0%1(+7F5qb%>Mq$}jTFU;eT@D1)4`T;n4h?QkJCkVEhZ7>&yUpl>VXKx{x;Px+uOq{YPXI%TsO4mX&QF z$3~BB!Uf-LDI3YKIYl_0K9+lrS_c3UXO`X;6QI>8xNXM)QEN}sH+GV-6ZT~;b$wzC zwUw93x)^=GPdSR@EShTd{;p%{y=p2DvfspZiFPt(!p@3%2Ym1wEl~>q`1QWq5cMgj zyDJIw8Mxe%0a-FpXs604i@c5XE9}o|>X*RC=4I{s>IB{o&aKKU?TaMOF9k)VkT*Ie z#TaqB!0dIZsJ|<=$+htbFIp_%*qr7v{7-8Q9{tgvwp&at13 zXX~+@*UtF_T_`Pv`+JwMHH_-djM`@eTS7kN5d`WHJtW}}J&K@WGTq^q4 zXREDgPt^mr^#T+1drh?vALHq)eI1+F-ukF6vNm3Q%Ch|X5^IO_#!{2{LV)#g>jltJ zDT5FsrL!{G*>+VO^WMFewJTzM+{)rQHoXf;%HE8ld}5nU+TgAu@Phsjg9b$`kK3|~ zWw|!yN5?*Diz@u4jLhGh{eTX?^3wwaM)K*M!H=u|MG%hsRmt|g>^6`@MgaEy3K*M6 z2Avnn)keNzPdoR|&PDaLu|4wL=bH6u%k^v`VQ4-r0U+I-K~CLUGXHmU<-AR>SBZRc zc%YNkCaz-a63M*62-P7P>AAy^CE=o7%jJ zAeUO1>d4<9T`c$71A9iw5WLSJe{=3$LqT(T;bNj?>TAi4`Xj09O*efeK?|0bg71N^ zF8Fscqb@%eTRPbknAcEURdvZ?%HhPey*3Vu2TmEFyH%hmU657jWrxi_>(~X%Q09El z{Ze`;9B_9JesL+ISQgr-dSejUy{#b!OQo`?1YIn*ZQ0m%s*Xu-DQrrYlT~3$AE*ik zyQ!B!3q#sZ3cjZNvU^LA3owMvy^$LNQ?9*ZoA(onu$Pb8i$-lV7w!EP8L4uyAmGWn zW?AO~YqWEE`D3Cx?LhlBk{eJM zL6u&n*xXph&cODnRX*q!uCgiOXZv8|*8M4c#X5O)l1pCL8T;1Xe=!)T>Xs?tFtT!B z=+wR%bx{n+uJ!3y=Cn6;|duwlUcGz55g)6o$R?ektv3f^8^~_3p?+yH1JE=Y^fJMSPHS8G3^J(0^Mt zDGX1R+&jRyo{<|ko&<0Wa14m$vY0IipVM|l3rc_?? z^72OhPkiDFzWzWM^|p*a0`*(;0-P^hELR(G@*s&^??!$Sz8xNhbf>O&od!O!Qh*-e zU*{DNxIM}_kfQs%tQ|Kh5jwBP69fxHzfnr5vE31euez_97bVN zPLbwp4d&lGJMgX%W=dbgO6pSfjbwmtA3Gphvk2OEwOA*SIyN?5VZWc1*}8|9k*`+h z7O^jAhZ2Nn?_zh62FNOO}|X7#E|FN)<}yUMl)HfPRp)*spD3i-NLu6iLai&&p+ zmtJ!#Tc;d?+Ug{;?YN%uiEV7V4qjv*mhUI04#3+YCJqk8niP5(T)6(CwZ7sI}Y&`{t{>8FM>0%jXugKX- zCz2mUc&IjjjV}3YDvsBxtpo}hxautu3;Hjpk_%F$55Cy-KCBhmaVZ=~7pA?vkh1R? zQ?Qp&pdjm{44_5%Tn{v|>zj18K80Q18O`cLJ>Z45Ez$MfDF`-{->`aHH#VV~yneGj zmGyuW$|?u!ULR~Jw@TR;`s9_hwJ+?F>upSo?A{shu>W^cpWvG;4cM(o14n55RDG8< z3py)H)eE~P1s(0)eNXVG{Bh9P68XBpCX)ZQkZby6cmizTnRO~~DpIgBWw}SC?5(Wu zNj>*D-P*-<6HC>B1yHelXYDBPN_Bwod2{5~raAEKDKB;e{yWdEGkFv+JC&IW3eFEB ztW@)$97fRL*!%2LXou1Q2HD6;FIbR|EN})m#HPG0HY;@998+TOxJ|IfTN&-;iv(2k z>8#zT>LzxrGt{W^7{K)sGjdH;c0yqGo@P=$U;$06fg4_HH`cmIYS$1L*&~en6eHhA z^3cwenEe9oyWWv+AnO}sDy@84>mezdM3BXarsT-}Qpm4!FuoS#*zIF54heFV$e(W8 z!_<@aJ;MM7UnL*v#S~(%Y2^1HUsOUP>swLLR374WQ4W94P@To9!Gw;k7V4DSntIdf zjfKO>O&urFo`Km)dx6L%I3=0-TSsnf=9xO(ADC-J_Mc*K2Br;=my4R_nL(I@jxex` z!r_w$2j_CaE^HvGJsQ|hIsaMR3?BhD`8$gZ-&dr%g+V!8+-E$ZUotU18pWyG{4<7A zuREkVGArvJ0S3!n-i1N_SijX&3#FC}rD)&S9;1=&FyQx=cczjlWPhSO6n+)_TzG%@ zWAKG=6={XjETu+(k?Xx*m>9w2IXz+56UEpFJKtfz)J_o7X>shPZ2%X7wK6M3u?zV*gp=8&~f`pcUA)DF&$RIMWR2=)G}g)t>Zzkm7MB z@3X7&#dalQ-?Un5X9VAo>~<_{ zFQHsF;Mx+o{behDD*`jM(KpS2J;Uh2sn&>ERj)8!E1G&-eJ~bGYnu({QkRJlMBi9X z(fjJgvCegUJUg&{Z1Ggj*xCzY*Us}#$)nir>@Ifp(L(QS=@i~rWl{12&9=z^l>D3) z^1n32#OFgMv7sllzoO@ias`#6K~zu(kb{X(rj^&OhzhI?4V;%k{_kzs*b8u{9 z+nAN#YM?&!kHlhkS|_>p%h&FX^V^Izkqs%|0UU&(=W@vNQ2wen%=V4i1ji@JM@ z8)9MC_vTCCcNgUzaPRa&sTV`u1*hodfaR4q9cUdryOGIla8uWn`trjDHF%-Ac)&!k zZ4jyq@+Kv2I}VGHiU+1PaEd;hvX5mr_LexO01`4yXlib#lCbN2iOOIsRO!^UfeD_g zZq+0%K(|C-i^cwtK6fV)yOwP*{$Oy9DHR=53~pRqvjg~65K$uAv;yhMiDaG=CDhlf z69>ty`z=N@N7dYM^g5CRCT@j-y-mZZ?ypB)G2Aubs*jJ`(hLM52qQNhZD9G$}Qz;)Nmgh^X-sjVbJpSR?rR4bR z4aaw*=dMzmKWda z7xwY%G!~+)d;SA*JPs?poXUVxLV)Yjt$V^GDZ;1k!a8YGQ)uH;AIY7IjS;7X?)02K zwr|n~_iq+E)T=OpU8XEw!mYw`^?)A)Uk4xI8W{z4dO%o`QB_uPy0df~@=D*}jN})t z&e#~#2c{N~9cOJS2cU)lcvl(B3#gxH+Np=5eW=)e3BChCPaWAZ3Tm*SpFE9D9L#f#M;1l*On1g;XA$$_S!21z!leE63^t#9w=S70Kr5 zF&?tTtz)cj+U^p|i%kr@a2Cj2zJS5d)AeAamavA{eWjOg9XUXHneIJFTNHooi=hn)=tZC&tbuPWDMOc72aJXeU2FpNfsG zox@T{edq5{)|U3=QWRAAz!AIKgK?((myMyrS>I$+#A}^$@b4plS}XUhPcB(chyOPXhJKB@cz!di3+}E-zgX?yn)A`xUma=n z1o~`Pueqvy1AGrWYU(|iPmN0yxO_01vXu;bJNtaJXII!hHNroW_Wp3K2c0?WN*zJ$ z?Qrr_^Hm^V*v|GHZfp21jlX_1?}dL3+jXxr$3|LwzG#hn*NHOvQtV^(vCeDbvsxQJ z4{v00l04lc`r0;ujQ_x)y(u18*BHDPHuY~}Z{jq{8@~mtFZHVwmvVJ0Z<0&lU%EH- zt+WTZYUZ!jlE^Z{smdyqffEK6BcX020?S^|?cB(@q4BVJTmPt@eL2oc(_(lwR*wB& ztWTo;AKA~3;x5Xn^VLS!ecA@7s`s1_P=0Rb*Ss+MEgqb@Rxe{gubL&8^5%s5~4IMyTAxB!MfYv4a~p>yDmx- zr*+?z$0%^XtXvg|P1Q|BZ}zx%JIY=>^!rKipp(G*;9eBV$K2LoG+caE9Yx2S+W5k; z9sXGr4Vzk*5MA#m_TAx;USw7cK%wuQcZ+)1aca7b-;5tw<$TQev+9r7^$znv1Anlo zH>s8{TXisi*P6h&w*!sYv{s*NqPIS^F>a4HIGt9@9flyuN9D*%s*22E?QCO{x`;Ds zw|b`0JjK-8RPD9bs%-%3_%J}Vr}r!Ho^SN0nR?Ue3C7{=ran+DH?Ci~-a7Sm7}+9R z-zrjd%a`;_9jB*to=WB z0%oIf7faOE`=HaWTy<+orxINKc7LrYCImE`3xtegPfFN4gP z^C{{&0_b0-z7|$adWbm;X)Lt>Yn@!KQGlg#wjx3NP(XY zw}EsHT>^dq{5AM$cwV5J=)||-J>W;c?}G!~8VyNh6UToCXUfm#9MIojY(rJcVk>Vl z2JU2V`Z2-m)w&mZelDo`FNPvZuyj%VkP$x$pV~WH;ddTBRnyicM1NJIVI<3gr46N5 zavuXP1MB>(M+l1)tUDgnH6^dpnD|~(*T%d_3|4Ppk&S_DU`(;CB#VLZPQaX4=~Nit zt9;ZS(HZzYb*h^F8^uZ+{lEWr7C4)G%2F<{3c9#7u2BJNkqEEWjH30a5ymyKIMfex z4Tn(J7;RzNV&G?wEPt&VAHUp1ZZDm>Sh`c$57v|3|AmKs^B)YI(=ENEDjAG-F%G*_ z*?W30E;Kl&dv?Rf4Zb~^)rQ3X9R{PxMmKKh|0i2F34nBWdK9cxf$yyAH&Qziu{7|{ zE92nSIM&r|gJIu%Y_&mivB1{_cA#(NY&~6YF3QSDKz4X@J)Gwvp z>UyhAOa)!W1aqskzy>?vUI?2&;d_h1&Zpeag(_Ku2&@jJw#>Qq+tsoSf>TxqU?L%Wpu4( zYw`b%!FaGmib)qRmp8a)CXF&e)=b(nnm(1+BFIulfm%C? z#VhK)d7>tHjn$SU?@lBwQKNq}h5bt$oSwK%ry{&g&es;RX-?Lc`jeuzn*VNs>0nsc zaw$s_+>zMYtWx!1f`WH>0#mcmjR=gZ4bE|moE>9>R~{i8(>^hNXIkH=KGdlmEIoJf z=(@f{rla9yhP?G-ey<;3UYUre0jfOhVbk|3_F~kPgZD<0%Ll9cu>G8|kE>f(`CC2C zyTaL1Gy1FGm~ON<(^ikNI=?Cr>~&WqdJukWm3>N&-~Iw{=tksQ#D0(^{B?9zjqO1A~5J-?wyy)BhoOPAhwP~cX^}SvHXYNtvF1+b$p4TX^kY+ z@gK%!ne;g9#`5bS?xMug!lT7uO%m!&zq^R9B@H8| z#8@px?7LHevDGPUU``49k#EyfKAp+55i}4Hxt+r9w#Zh^?K?|oLV@Vx7KwgKEwQYHG-gkthm9or-t%0E6}Plsw4L?~ojQ7KjHMTVi`p%HG<9 zddd!2lbzt6fEAYxw)>-q{b$=PM}UDpFERM;ta8FuqOZo`kuC1nCKp8sBV`}shBmf+ z|C1p22K{U~;t^oL-w%HrP96ai9-SWD4^S#Kj2i7Q1^xgwf_J9ygADyM;4i=%2ia^n zK_kG1iLW)>4TWur+=XEnZyY&XK0#fdO=TP-zz*?FE7IUBwJ zUT+3>Wj6ITBfv&~7cA0**|Hu6x(#F$(T<+|!%^-|&Cd&i!G`}O{fJ+FOTOBR?LV-M zKN|QDk7Q~siyUUWh^=+JdQ!hOtXFjOA#1H!xdv7rjw6pdC}(L@BM==WLi1axctIJL zDcfOX#Ml&0O$o%|Q|*zw;yY}gCeokL)0YkYV@7dFFHvJ-tM{kut%0qlY}?AfJ=9_k zS=Z|}BR}fdzRtMQkOtUxKy~l&J*Ib}9(VwmvQOdWu%)X@VDEwLk23apA@6wj3|OB- z)iQ;ZU_FX>Hk^C+N*{WjeN4b04Ujf!f?hvhhyXiHgbk2mJ76b4%C?CNh+C4tQ~%Sb z_Ky{e1>s{HEQu?>Mc5?odBWBktW@W))t8=9v{r1NGLkH|tJ}tPIR|sAx)`1vxcfTT z1CKR4jE9AsLAuEqsN|vAvHf5?SlDT9C8kz)Ab_kH1JV9e9CO$7&ham3VCJ*>Yk)VBJLu?jF*tuV+jQv9!jK?N$+>7ww*R~|qdWm=^w#Azf zestKbqProNbYgINqLdGcT_XE?Q+7dytrmkH5ZX;j{N{^dwLXnCjH~OJm_FVFW5(Fh z%V)*t;7BTm56ISHYWjm|e)h*Nbu`b%EIgqYON^vPu*G8DUG`J~Ov} zb8BAmSPcAv<>lFrLr(a^l!GC68O5mbA-3kA`e;@41oxk#&7%j2#_(AnIhVS=9lITD^r>h1*0= z4!<|K_kE+r!@+(#<5Q=qC8JAwcvg4X|_&ah5Z_7kBe;rQA@eRx|cIpj-88B@x3Qe;uC+0z8JXGQi8 z(yqJ^#zuE@@o9Sh+!$aV-vn%yv!4hZNqe+&DnX2|jU0ZRvYQl{%{7-3c57Q(>XrXL zF~-B^$_PUb99@cR&vgxJDk{&fHE~=s5`GA!_v=}QC#ILh&iGu6Y+d*d=!brm664!8 zvGi1W16VJvJr34O^pAvfD}GDCw-)93#Ck@l^m?T@yyv{+xM1c&URvSB)v84(kK!om?o%_OBCEhhEupZJ+Qwq(E8lSPz08J z^YZ;UFcVi*H^&^t*mWfO`Y3VR+@`C90R5x|u2KIBHXnm`gP#ho13wzpk!W-H`S6?J zV`00IXwIcv{&TH*wd{py4kze9+0SAId8)K_)SsWSnMfJQemzP)G__EDF%3I>E3zDe6FZ!C1%N z+JN)&2+KCL^XQ0BUPxM{#c5gx$9{0R2b;s_Dz1%D7t`8NKh$E3y-ot(jS_P22tsn$ zYZckSaP}(-!9FhWdmHT02V;A+G46ZiG-Xp)2G$;N@SLx;&Dk~4)y1@S)Ej;Lx=B8@ zY@=jCQwx+kC&0Z2jyf%@mkWsgBOy7;8*{c*I{X(hSfQ%h?<56-qAZVeN#hzqa2{nb zb1v47`c669k?IJ(a+Hj1eyGdf0AFOmi~60EwXOlMyTtf^Vc6UZR;V84VFrVue5Ges zR}Rh*1~YpaH+FsVJauDrYG;#4)PFu~Ffg}G;7Zi!qBz3Xx`VtT$T@d=m>6n)rzFp= zuDk@As_f?Zq3&C*;Mt8$PC{>ul8>8TY?}-~zl*`tZi8oW+W5yl;Mobe9(-(L+crM+ z?X0dz9p8N|R?ZhY`w(*I`JG&>+B%Zz^uK_Br)vWDR=9Rz#t^)cjJS0buwRsbb1Tbu zfS8;+*R1sp-*>G7Uh-Akkb{j!{WC#6?Ip=<8YNdYnG_)}hs z*ToBVVCXhI&>cZOObOV)##4YCChARO6H(=iF7}^|eAHaJB9>;HOUl_!n~v;s3JEiu zXVpyvpLdo$o2v9SD%JI@ye^)#!(WSw0{ztLhN%a@sLZ}2gzZ+5eP|v{MNhspC$tE> z3;ZWIMNh5DJ96s$1-EQ`g6pmQKtISDH&g=pr2t%%mjnpf_S)dDLEfYU!(RU!(8M=q z8|56Dr{#R4!*Ii3+@h?UDgbjMi(8dXr+NaPVuPFd;ll<3>kS4^)srk{q-(XdCBkqg z&urW}^$53Y*721M4kwjP)s^fQF>OqsZZU8}O+Z@QT6GiHtG=%mP-FzyP7&a7k%?<4>r=` z=SYadeAbD2d5vOCk^jxuwOWgd|H1~N)4>BbzSgp#v@~<)>Mdf7UPOQ`fEn<3k4L+MI1u9k}tl(mp0ur$@0mx!Ks%KT^kMY&Ik`KdkGD zRq6!AZd=&W3Z5TE`WG)Hd3IHD0PNd;->I^1sxK3yB4694eq>X;w)Vv8TLI7(XJY)K zf&6MNF>H@A_J7RT=5%1(Yj9qlvu&d@*kNZmGM2T$ZR$hJJ51bPH1(e-dpdHO>CF9A z$r)Q!8{LXp>k)qMrLRaf^3wtFG~-)Roa4yaMAV(inXnc(x86uLL2$HM z-cscQG;3_Jn$|52^~TSYs^UfX8_6EoZ>_uvV^}@0E;sQmZ-a;bjPKJ9seI*Wt zDf%PA>@$xXFur!W{ivL6(Agw{tWDV!ju+eFQ-5)=i{zc3{!E;B8sZT_S5=bZBjLUs zJLFyEt6#*+f^nv7v~UNUzQxUzNnn7_Q*8V?KAufiI2rt#OpFf&J7jj@(a7$Mh@-PW zpx(pRkb_rZyk&66ly8dt=Z^%H52>)%o~SQB*QFmB!(B~1SAD5bUSR5zSUuk)wZ5ru zVe0w;>}%T{*0(fRr<;1RN*>B_V75GAyjVikFUss`R&{H?SGtA64%R7cH7LdBcH{T9 zL5q44F!VlCN%g#%Spja>n)FS?q0`%rB{f5?wgz}$g0#vDpNq?c@|Ehh5b$3bz9)|} z=kHZXNgrYCSjQ*f_vpHQu^sXImIB23F51M{$Mo}o7}MxfeQm67+XhQ>Tq*i!4iksI z9XJ7?@4zgT!$|6I`dk7`qRJK8XBxO}9p7#Mn5OFS@=9$VT89 zV{k9Cacw>0rXTPM*4EU&k@Ksq18^l+UjooA+B$U{v9lL`rTC8MaXBa)mxC{WHTN~}e++WIBhisWNlgOa z)a9Mf*UKd4%&`~RO;W0~H8GNRJ?MW>Wm6f%7=U%H!Ry@s(7w^gt~2JHRpYy%PJl`J zbq44bQ?FCCuUOW4IGF)m$>@f~GEmK`e4S}e>%sVZ#kQN&@qHxrs~Df~Zn=Hyq4sxk z4bJpb%^q&6nwUGVDkE&{;_7c#+2{0NonsPcbSli@#yS%td1R42Hiy=+i?QQ2820pT zA>(?J>5Vu{zD*=ukiHvUJ8xO7jk9*zA4NVe?H}2?pWdp@qPKzc$Rd!PyQ$+|+a?51 znRBvs)PI|^P3iDiGQ!9;uS{Xokpa3IthX(mF<_6-&H~ab>3(WQ!cC@-_ba`prupsp z)u{TaXVZGB66=$)USuHI27(A{+Xk+UOl_Q;BX)aPTk4H21F*k4^0&=z&^X8na=8Q@ z_L__O8thG%TpnzDr45j&*P186Utcx|^pOw2k#wTTtQ$xdcP zw%62+hhMyAS+C~o68lH^*_{#FCr0*ObCF&gw5k79lXQv`OSL1%g&Z3l;vR}@bIl*3 z>>YVhc%Cc*te(F1fGXrsoYivX*!E2n(stjEwm4CYa8YYbdiBWetpf%|fUSMN8@cv1 z=iXlTi8Boo$E{j-*T^Wae-^BJ{-&gPpVz~4J7REEwSbYT)259>eQOI&Th|#nHJ=Kn z=ss(os^erI#tzI9TOVwHZGv28b#dL;WvhLDSUxsuJ*DhFcl9AmH88WCsvLv_MBfIk zk&|blrIhcp%2cebWW=!-(l%_}x<0<_QUtQ1Yls5doveL@ZQty&^)vO}8l5B#M!G9H z48FrS{3B@`39L7-kk;QEnuC7MnSs1x*FEh`9-jfaDRdIjeYTz@NMwO z$r~I3f7}GW$+NR^W1qb{lMlA`vB7_6e--X~Vs5cJs}sbY12<~}3`R+wKL*c+wPQY5 z8c%*jJKuZYb=5D*z9;gu2iA`icBo29UIWJCR9aJsbraL>BFSMe@O=WjFZ^Y=Z}AcB zaglCepHOF`V5g~xl42herxt@ur4HTkN7s)my*}NC`$rQ7n0#Zdmr@QDV3QDe(Ikv z1D%BL_G+M0KK}^{AGa_{t2e| ztd6kl#eALBhP|-lp+#QWu;ECw9qmUTzZaQZVD|2YdHx#vu(NE?(APCDcNUUNt$e?q z#O*-1KpiPoHaORt`lMIw7}efc)G5Yy1I9iaO(nXS=AM)~vh)a>kB55A@^8j&LsQRI ziL1%Cg<~V)-zAw=TkQ!e**g<_uXIr5v^zFBoDWM=Glf$qBU!98Y=Vxz-C4?w?AWHn zhZ~_L4}WRe>zjJrs-5PjoVnKa)kX$fN3?PnBvFt9sIqa%yb=a-wj6GC+(x{F(MQP)s`>Rjv8*}lhQpB;o~HA{OMv*+8I?me@4 zVP~;N$0mJ$R&30UV%Ouu>RfvyN98Ve7CT6f$n_+no2fgC{q?pwsw~nf5M%3WK&gORY(#ToTiy>nd-1Oa7}d_NC7DeanLE(Vru!&v5~x zt7iKPQLgu(x92~}JhD4Wd6(rGJMyju-GLvO*yi2p$WmlxuXpTtHch41^OKH7bt;pqXvP5E$RA}e%8%SP}yrBYcq-UavXXpkmQdszD;ZsQ|8&8JQCh+e|=ed=zs4D4-S>KspuG>Iuff4|fRyrKj%l>dVb4mR?u`MI11`Z*a=R zOUU%$o;Sdk8hxE=>wjYdxNdmf1vh>R)C^0#YSfc=(!M^D<(jt`*@m1 zcBfajaR!tL0romtJP$q+)}rmEq!-@~h@mY=tee<2Nv~cvaqM*Z`!;M}P@~z1v?HAa z9}MpX_pWs)E!l@_osOLiB4FBD)A}6v!|(}kn;inTlJv!deR4^oe|2fiKex!)w$;V! zSCTj+p(nsc!K=Z$a*KRv($EN%xM^;UPu~&7=mx5h?|{A|!Oh@Y4{QDD{qTK7sk&Hq z0FQ$8+{f|?w3miQNgoINP{yqGlz%j4&%yT>UV_-F4=2J}Z1pN^%WEXhr&126{UEUN z3G~=1XAJEHTchO*A&5%Fq1YJK1()u$9)jlu(zL?6;SGyEmVK%k+gOj|vZXVXSZ~{? z7qhme{&j1Yst+7laMrIz&v#K49};^w;E$RwXr>g;u$GjA$yQ= z4e}khWggfNHt7uDt$;0?(f3qfT|y;XE8K$5W2$_lw;jS~Ajdiw1f$1nvN%&}9A&@pk zD+1t!0YqghkP0VY_cAelSz(@3*bV$=FEs!oM>(CF3(cY%swEEYk4lV5M&U|JIf4Mx*`2EP#vsJeA z${4I-jC4BA65HfT3^vIcO)1Nxm22zlYJWr?&WWyXN`c>^5$5J8yI5v?vgi8P&$hwP zRCY;L*HsKviCm+wmw#hcmIE~5JF)kkwRN3bAHfYYSt*#6FHW=22`a9a@KaqZP$bOtqeO)P+DEfnCR8Y91%DE(U z0iY;#*U>3i{5HV&Ki6Q?nvcT1Z$`LH+-dP4aqR@U(5fWt`W}Pl9E1r6`a;e&rwaf@ z`NEuS8=b{(>Hiyp@%1VUY~Nw*Rn;^=masX-_`E4=+_jRxx+T{6&C*qM;#ddj*XDeT zt>!sek-<>)^Q}NKP8L67=Blhe^(VQ8D9|qz+1J^*{x9+g&AoE5I?)kH7eF3W9$|3Y zGIDk|ptWn8JQ!Lt6X>kAIG$esrmQpVFaTrxD=)yUE%mzwz!HMUC)M08;WnIzC|Vv+ zMeEmz0?5xJpr@z&u+fv`Ky#P&rHmaJ&R-7zDjl;{V&GOa*e5jw!FNUDpUn+B%@&tb zHx>?Omri~~b1&TxF^=}*lp0Nk*CxE~FFmI!11t0p?_z8Ysts-o@qeYk$ZinhR;voG zoxS~NEhl4y|F=wTzcH%5DmH&JcB-z|XHe0=-p=wyP-XKm6)^SGC7fS*Up=ILs|1{$ z)%20Exw}tMvw{EP4Mx{H%NGpxb8Dtlni*eJw<#5-f;?Uy{c@wOT?J=p_-@#v)oO#~ z3_(A|iO~8kMe)GY1Yk^ktK+RQmt#)X1x5-V+;a`~;whV)%=jjEV)SQN8|t6R;nmTB zu^Ma_#nYT~TOHrpHUMh1Rv`QArZz^(5Wx6xfMPr$*iyH@Ec^YEU{YBM(2)J&L8Wib zz+fgfc7^Z8Ie&Dv-!lDW4zH;WyvM*Fg?DP|JFWI4yb>JKvy~LWU5(=KHi;U4RiD`g zBjsapQ~I0?-xH00-@`-X_C0f%)p~G?-DNT^C_Cwy%WZ5r5?vAwtJ(fpH!wbWs1?)C zR{JiqZ(pcoFE&f1kaw@ zde)ThRcWRMT_W2byhZJ@LMOBQ6)zg!026{7B;0`n< z;aSNEvYKbaLhp- zHa_tyCdYWT^OD@|C8oYqu8-IqU~ETz3e4rwiH^>kZaSo@yMPJZQju-1*-0W34wC9O zvVTu_+TEu|r!|SD7q92bp=)s90m}KzD>^!T;6TTx1dSe2&MV`Q?FZxH-8H$7|MAg; zm|md&P!@cemE@<>@hPxw=^y8%gDyo6diD=nIinP>IPVRdHy|i=M`CFrZyQN)1)F41 zPfpUI+cRM+QKM%_-k8l3at($vNXe(e*xFTUrRyXP2FYDeCTJ>NuExYxKjYbtQ$8s( zes4~7nonB&FeOKJq9ad=8TFIQ$Y)_e!291`jE9|Eg9B$@j!KR?!qi|PUeK{0Si*?i`3c+G9o&~BY$aOI zvHyl+-|B;fsTi}e#0WTp{<1PuJ9geqm^uv!!d=wl;Gdhyds1bSa)CSS z_@pihg_)cJ=fe4+VFG6SlktjJshHiqkUmVO=0#tAq45jj*L(eRe$C#|B5B?QwlDxs zJ<1q3!g=v#$YbtEYP_mS*WT^g{^6~5oA1woYFFbRf4(B>J zlXa<$iEOV_pB&rV&azj^CxtyLn*k%h##}Snpm%y{WA~59R?X~l8T9cBV{3Z&v+@}- z0&G-09#|xoF8U4Nn6jri;o+e9nay(8v$}b31lZ^+!)L>Ko-@`ZpYz~w&UR^%M}Qq% zuc>r$hXszFfXAmsFbg{nrc%wpg7?U@{S zq1(95&|y2H4=&`d*>!z8=MH$%=}HoG*F)9WUb8k2;}Kxz`E|`b{2uJwPvoVB5c@yW z#Fm-+7O};~ZpIy4$XQQqehW7xy|4H!_*L+_b{v}2@zp}g4dFMz$HHw6Y`U`fEbP8p z&?Ki>+lRpju(KqWO(9QFqyOp%z$;TAj!aK}Dlf;enGpvU^3?5)evEZVpS{+t=tAS% z?TEJ|{08`HxGvp|;XdQcb2iot907Kc=hfY#3cJtO?I!m6f!*H#{{>apVClBvp$3?1 zS7COkCofIJYSOfdF2&$^UB>PLi=6b%(%ay>;5wuU=SH{8UF127F+)axoukPaRy$nf zK_GM;+au*rlWM(q57tL&;(b5lG3t_ho&euak(UlAPabtHUE-6k-g!%YuPEy4pJ^}F zW$an3X&3=E;#1(iL>u>4v{!AL4!(bi@N&%uQD)!p4S8Uvg>$#%zzW@sl(o-**e(x$ zukekF|3fgAb?d~@|6+}|MV!ya5X|UzDT{s{7k4bt*294r-Pf@1KCDVMnl4$Z?v0OY zGbrFL3I7MKOTTFn2hbhi3lrdyZQTTGQf$fl;6#6d=)Y9>4C9*gp+Gt9{e6|C4-_bI{rN~IG>x>$ArG?3Di$A zV<6S3@WfulR6aeJ*Egc=9~(-a5UcyYANBo}P54BI`_8n*4s~K|Prd4@2T^tb1m{GGA_4|YCMSlIIy1uYodAu!%I=W8`ie@JA4VOr+defkNfI0 z`k{z?RtMl5*juKcu~?TJZlau}Nge?<=FxCn(o>68FACzPc^$2ZxE0oAuFlj)!L8?Y zCV5=zN3-xWr8>`qWelH|7~3FvMHd|fOmk|V44`8ub>ir3ZUij7#*m|ldKF`yye(q% z^*z$%;hVW!yuZzk3C8E~tNZOQT_&$VtVXv;ZStBIeHd$PtLx#^Rp1L5*B=ejZ}9c8 zonOLrUnJCa)Gd$R$4F`ol5*=6@Bw>jEa`5E> zsvv#r={X6A+9Le5SW@qZRZ-nJJvTN1QvdEC#J$LMoK-X%0Y+3`7`-WsY(=Si)0Z}h zfc-%gm{JS3^&8Gj@|o9c88^LTm?B+iv?c(n76R&)WyjV5GLGPG1K$jLq*c{hWgse5 z_~%Z1wH8ZO26?y}Fvy#DTQDQn((BsarNnjz*jr|=opkkw`*vv4f5uIZTlLOUOqv+= zo{m(8!dD9(JDSDzEe{x!Hg04J_gnq^^Nf1@XukbeEkSaCf-LThnoWZb9&4_ziGx?FHqraEgu}dnb#4BvbWvv-16EoBZ(e z&fwRz!5ftid1@tgiVkWM6QFfcV1=v|W}7@xKB@ONQg$PkF&MfhwU6&~YojI4t#4IW zO!N@^T$0y(%12=>GK%R`1e;>FNvs$}oBrq%2|5V$=0=F2ob-dzqO2-98-usQtCFv! zWohgIe+kxF3wICv7L7A0oP=P?yO zgy+Lmq&bGIXKL5UeS7$#s!kgHf2scx-mXob@!Q*A#nrYuahp{7d`M*dIGIFSeQ!Lu zj?cFeSQ4Gom&7zT$mcdE&o{M64Xj-pJc;*igE>$5(0NV5X=kcSx|(_2q<5Yi7lJis zQs)a}nDzeY@cSv3?V@ksc#mU$+XenG801!G73<5J#sK#vut%*wzTGsBoIT0qR@SbQ z^YwIK=9Xcs;`z<x~TNBCx(> zm!fGuFq2fBiFVzpHYTvINp%|8v_CB(2hFWr@8ox6`!&DVjD1ai*RgHR}QTo5X7U_?@nv+K!3KPD_@)rVDgTQ6y^c=e=hulftPOEql*ys> zjy!B$u|GL(naR_t?xC?*>|dvipXQ#bp3ohKO{eo-;H?K=0_W%?l#QQ=g?{7viVXNy zgWYUdF#-(Y;_z=WgLwzKO)Fp;tHFF3oICsJ7ViCU?+i%kO(veuICx73a?ra)DLS_$ zN z<-C3uF(wj&j_U{SEfPZ2BRwYlCcN4tb%J~j>1F5tISbXm0TS85u=hCq6XWV5IjjwP z^qg_!Q8x~WzRgS4k*{4BJ7)*>qu?*WZ4VSqdIMrj9=|%5OH&$;oTe zOui}AbqE*iI$tn1gTDuBerFic6~+7DrMk{hc;N1tNp37pB1h4$T9|ZPkH*>@T;eg) zPV|ggL5DCR#+I;m#i5)u>6ZQXr|2I8dwqV(5a~5`C6E7sQ}oBiU}JJ1+1&W2`tpBc zN=-lJh2V8y?I%0I&xN;#H;2c%UWj-b!XD|pw0WQC{c7-)-Y7JbUpk5rBL_{0{XLV* zdFX0gMPc_12S@klW4mh6I1x_=A~DHx2!lCXCW{_{-f zN2hr*Alt!bz{60h7x%o5kjT3;$>?*BwP*6N)#S2w)$$%Mhf&DMV@=qjokkI}3rrH$ zguh3*edje@#GiBw21XAUyvN!)iI4RJHj(314AP4!FNNz;XP3YP)a{EV*gR_dMk+ub za=>)&?#|JSVgnKHRZcFNOPZEfBkJ^%+_rG?mUvhA+>Cx=51MuQUdM*MpX~Hs^LZ0D zk5;EoBe!8-7J=Uc$7@4$CGcZ-jjoaa>;14tr=e*4XFNMk?HH62rOKQS?m5*;fn%H?7Gpi*={!pAm^IqCNF$$LFQ z2h_ebR+HYBc`iRTfc_JJe&{LEJ?x^xbQ=H5QozVQH4JVWUt(&)&!ausV2;y=#6RsM ze?!OveeO+aUHJ^GKMKAxt)wsSa>hgAk-XwE)5d7p@?`^f^AFlM?;SQVFmi9*c6K{g zH&60;nmXoC?Fs6-@w&Dn@0UBdOI*GWMg1umyW7z%(RFU)#-k7WXZrZUapyDgcyv}P zP>;`aS}*l|27bcGlc@+m4&Th=+3M@+aY*og>cluDwjD>CT=sMF`Oi4w4;zErb5|uh zSbS`^ar!FpKj7@TB#Sj^b#m7O50CaAb-n~%13m=yZn2fyNpLrxtN>_bSogI}NtdeM zg|~w{eg7vl$ch1bPZo4m>*QZ(fTMXF-S?*Gm8slDEhCXHq>@2)#;9X=flroz$*$LkRC&cEOfrk>J$1=eq)DQR16JoFdufCmSl(r;=6A;W_&ID`;_7UYq8an*J;`5?>HxAYhkn`;`Ewn6i7$s| z%mId6cTv&~b@sw3_%DOKgSZpk6@S5Qk5+Y{*LLCCDSA%;S|#H+k;WNLDrY(_t;NJS z)roafYtSJb$;bQF%5vYTe%Zg+s31( zwE~?6CpzFgA^Arx9sIP=&Z8?)wEiGdE^Ze(a(j`NcqG4%_KL&A#Q*9Dvu*PR97ppt z1Av!;wZ`Mma2x9E3{P-xlKIqOHiYL(Jbe%-Mb~;hqn4A5=CnL&^#!+4=bXZ)1G#yW z#Zx{(hHq{Rw9aYbCV9zeZ@3Bl3**-Pz*lc;x1o!1dM7+Ri}nbtr%8LjdI{}8I7M2` z`n<413|oTbeb?eDbn_33pYjLSo7d^=zBm;(CnG1Va!!%=U;T1$)25>XE2TP7$TqA> z47(?1{I$Y&>HXI#Eg|Uh9i^H`Q4lWx)*sT z|5Pka9$dYfZBibG%YgfT_6R#M~mB-op<)Q_sxo9}-xw<1C5VI{V zL8y0)QVR$liToP&jZQw7IS@P}Am-aqAMTjE2>JQg=-~4!_+HxkIkpn($=b-*j%DJ{ zdnyL>!*CnY)x{rSJ&|a&W8tU!_7uH;I!Bs>E=whaY{oo>4&z78Uvc{KlVDS~1ZN5O zW(QCE!{&9dhP5M>_aMMYua@}J!{#-1f4a3StclqaX;StNuvUb=65a%E{JDZQog&Vv z@F+<4;y-{jk(HbgN4^p4(No&=rz;*U0rwL%a*r&&A-jf7Wtw<|lKLI}v9{WTg zG1r4V8hbu9H>YbxM{2*lkqlk9UD|eH*ll&)#uo+O)y{u@mFxZSdp+-g5B1@XuiH)&kW~bU)q~!2bik z6W$r_>_-olw|ML!be$a7+m3G=KXP6H_UK7XF#*z5%Np?R@CRUT4hGen&eke{r3VWs z`hL?s$Q~fw-rbb~M0Ru=%mVkR4rW{NJvc65^C@>i6j~#42He%X+(yjapJ#(Lt&`K^ z@VUbA+XVbp_u~#;PfSeBz3c$*2y0HI)g&-}P3b`#u7NLy)n{?2UrAs4o`8_&OVNK9 zj_G=ASBZr)p-rFkq$Kq;@U6%%fz_`RXIJs!Q-_XW++JMAFl9sT3nBj-ocjG70rqQC zesyGEe*n8f61H=YEd%!L30+nMrq=!30(bGmSU685kIQV(^57DL1eHubti9lkVSQGw z$;9nL*l$gs(Tfn*}7HgcAgJ)^_MnDHs9RMzZH-fz<92cY8(EGul>m#LyTov?Lq*Aihty^Cx(U`9eU{QAa1-Jy;j0X*t&`C; zY!~e#Sz_#u#o#%Pkxr0ngLA8+?}@?CesKnz`W@|#|Ic&&O?1T4kN-r+XL(|2OeTs_ zgEA2bGMERF$YF_O&SW5;l8}!?L>|`z9Iu4^FF7nQl7KZq$xCP8^%CYfAm0uz2`^z- za{|*zx^&i$RX>889o9#PR)AxADdYXUSU7B(G5jnTZ*g#R#@4*yg(*G0nl?B(q0@m) zSGBs5?~I72D+=Ax>Vy>2zQj8+7S6Vv5nwRAwJjfWTsjw%gBBB|=-SSMH3TH7D^rOf zYdtC1Fon*|$^9ayPp|GgSOG}9*E=zT`1x^c6bA=oRO+eDim`oHZLsxpGeuwODn^$$ zIvP$YJ>E&|_l|rN;#C|_UCm54rOsf=>AvYsY>44fw}6oR_R)ksJ&xQI zgQWDnk4Fm)n+L$(_rM#~LoX_;n$gtnaCd z*_GYH>B?nfw?%eiuy6f~_VTbM%j=LPn%`c>up^smGB}#RZ%xJT_QkCM`W^NAJyr*o zu75yX;CTlZ@3OVOYu&ZF=u3Cm^do88rAX^JW-58x*XwKN{p4WrAguYmUuD4cBi67q`a#DH9Y1!`@dUoO+?X_U)Y7u(Ngyo(OA_~nI*8qpRCX`)&IV(< zOwV-5%dOm|8Q)1&c?ZU^U%3>XUZA7~n7vZND}J0~$+C3siL({<&twzIh| z=Qs0TM>lQai9EOzqj8BdDw=E?7wIUTq7_rZG0VJz%S^s<@p7MzE0<+5+jF|ET-I@N z@_s9h`FO;Wd~i9-8G}?i~CW14?`2c8^BtZav^*)Kgg~=h2Ra?D#U*h zaWpeM4${?2>NZF+z1=%q# zeG7kec4v}0g|ao_e;ZiG1MtiQ$g`1+>)`SaVtEIb^Aov^OXU6FydUVe@@f@_ZLJB^ z#T@79xN`9x99-$-IBN0UPJkcqTlue}%ZeFuy-)QAcp1+Sn^>iT%_Xo7K0k+lO8or6 z7LZ57SHoS=CIlXeNMvs(nd^oEZs1J(Bb^-H+5o0=(@b8U={(pN0O`+?&NxfF%NSDV z3qef%kFFHy2Q^kAiB(gH6tW%LB!jO$QvW~(w~0#s(`aC_**lp~{$0feg2{a?GTk{ zRf*TaVBpTB%E{3$jr_0tCi|{Ddj}VU+OS=&-8i34f6qyzwz#<5`?TZmMn~SY_+_nBkxqK-z5Be_-g=r`}!x_2IaSP zI=;uY^-uWeK=rtUy!Se{{C+tW7KQacfU4+T41NcH5Z(&zl1L_l92_WoO(zR_?h`~_J5D|%zNlOJ$4DU`%{ zJ3K7u`zODK4}!Oa^@OVyVe5TBOS9|KLge&9I7JsvOF}~ir6Vs%bq1N9){T{j`57md zd+H{FzrGFgO!#0}`(4xT#Nd*pm)FgusU1=6|BC)J?cc&){`z0hy2YBgLcM@|1B zfDWMAxn2aXt`Va=0Z!3trfWn=X6sZ!$h_O7=}NU$T=IUi)1UKd0d#0Y9w$4w^sWlg ztq$)Ae-=I+z6Tx!dAMhF*xivqbv2O&TR5)Iz;2GCYa`Y&hm+yoirHpYQ}&23+7C}HnsK4u!o<_i_iW?rAp`z? z;(aI)QyY9OHqMm^U7rXHty$R$-m+jl6&U9|z1D1mgV1HvuY#{G_&WOV5cNu;AIoCo zE#g}Roa-w=Cdh#Pe4TV&ok;0x^kx5qJShU_Q7Bf1wFqu?I2JAA zA7C9s^bgGbOPMA5pj-AEVf7`ZvHe59IB?VUj5@fea}50ND7IETBK=79k>oj%ym6Bl zdg7w_lyCsjnM`N4Ng(x4JFU)o8#)QS3;6}G4rF(l@=nHQ)K^r5OB3U|2%5!U{diQ` z`g>__3df`$nO?zI37)nI^e8DEAasR#4*Zv*JcqHpo%+zkIO%}&0@9*#> znUqI1PhI@l7Q0>1)IT`i@465YxOycGO8_)l;f`fe8)5qRfJ z@WZ-@5n~WfPnc5l%-A+= z;M`i8-e$u_kA+j@&40w3yLFqO`WGf1wO+IdpvIsLU4+v+;4as|%^e?rmxs0bt_#wJ zf5cq$_BC+!$|Ur`_Q<{`@lsbPog6UzsB<;M*P5R-VXfoQ)2x$VkFG?aN9g~CHSUu} zy2`x+z5%{EliZ?nM_{xya+nXk+sWlkql`|>cRO(<-fo!K_+OvFZlV&-y2IpB`U13e zlgKq}e_n!jP$AwvnV1K35TXx)SgBj1`;fQ3T2#1DDt7-s{-S&41OEcjzbRwQMKT#D|+|P2_*nXPPb_urJgJ$ zQ0j>Y;@uj(xE?~cR^+p_*Ky=~bsKGTXykgJ(~l!Y7j+Ps9FB1E&;;v9h_phc>~QPFoWGT1Yx7_Z??m#7^DzDy6rKA`fuA`5ndFdlWH+3HIjjSK!;>Hsq}X zYL+sQH5qw)CIii4Yenl5njv>_je_yiC#0#-2>efFyr< zssqT@ZwcAhjab__IXr}1kIXwG@aBg#;q1|~Itx}4h(uP04}q`tl0tqCTsbLTGvv%N zqvIRE-lgBI=!Ty476zQ6L#AW2NaW;HGRQ8Uj(pn0B-hjvGp)}V8o)UUm*i2Rqs34R^PXQOQ^C^eEZ3RPDDw=d| zO6TG5oTmMn2zwIO!l*Nv_BgWF+smC0xVftsg>7^O!G1wl6L2vd+eyL=KuEy51^j0N zn6aCZw|;=B_tErH;8=+G-sdlla&_8rFfs zqX$sz+61$WEiv?@^nI{*n~bU!d7tuVlh*J)q`VrO`k__zMrVnS!AlRHMKc6qezGFD zGtp-k4Wa*%gVEV7T~)7$zqpfw#9y!SpDsPQ{oKiWqfzHX+}Ap>HTha=E(E(J;XgY# zLHzbn_r=2}ffe8{z_|(KkY^}Q@$jZqPIjBXnh490?y|Ke3Zyt4S#MA?ZTN1G)I;1K-Ho8Liy^J&T z9dw=E)>q|Kr6-?t;UB=M31H1VwSIb96}vM%NowQiQeBt5ABFdUy>Fy;7IzpR^3yGj z7Bb~Xt9%DG0J6_GPCE^gQxjj}zu(D0;)$DgAt!IX<@-(g-Nu&KZ`YtCNGHYxJWOO!}s=|S(gN%0- zfT~BjQqhmOcV?p0ZHexyW4gL3URQboZypCX?KgH6rz;$C`;f`cR`=~HMhb^OOThQr zfTsQ$$LBTJq_(edo%2f?T^&?504sL~paa~rzRQ;yrx_<>5LbdPfIYew#dckH3{2fF z>GrLPF2-Oz*jweBZ*AxLLXv++3nw>YD!lf%n1d2BzbxJ_}% z@x@M_hd0G)Vo%H~oVdCLNlh-t=DLE`zbY9Sfv@?>8{)tX+CRazlTXQxtdrveW-v5y zb$EjTj7@cGw8WTmej_oPJmP!dsPoep!~?pPP2sU1PyV*@p) z>!8!wirTt)6Z69ja!i@FUSV7}$BDONR9=`GnFg{>zckl$z{pcS=pWY1_dM)Ix|j-l z@3H#jP5U+~dvd%ZFum1A<__-iuuect=xZ3)TJK_GbzLWim%(kW5cb(6S z!K3qf%2IWIt3gW9dnT=;B)J;=vsAK<>{rM;T`&gT-cBrur+wumIc)Fb*V(dj@U>c8 z3nc&T#PY=7MX~&(?N`c&ytaV7&v1JEnYbkgV;fsWWJ$Qm!9{1cXOAtxAp()-BVk?I zHaTPJ35w<;8o#9-QpH!Fvq-%Rh`8CZ_JG-CNe*9BA_>~FO&oAEN3j!p9Q+X6gmmzE z2i*CR2K5EpC%`|4W4aN+ZY}$}BEILwfQj~jZSdzQ9|mRj#K6R&zav}kPfEbhIfSB#a(eO*m}2VoqYT#j@P73ZmG#ionR_&L9o&C z06oyuNR z*fY+C0eK~SB^*d=HgsuQxzl-_#aA0ym%2H+3gvPh#wg^((~sok@I`PN(vEuwyeT~J zh#A@QVUN}rMW5n z=i=J*W7fwR0XEhL8*bo{F5Ys|EXCydY*;T!4okW^${kSOS_U0+g}grDbWT66uIRS_ zb-t*w$xso0^Ol{_x~`Ev>Tc4HVQoh;J3nkv!}zmto`?Vc!nJQBig-KDH{X1}876j@ zzVt(D6?9+za(HLB>r34^VEz;Sd&Jk%zPsT6P>R(KrS_Re!CLAr4t16K7aTfB>!sAd zy8Rr*mEnEhYUS}!@UPi+4^U1FvHdg-e}pSP-H}N8LS$Rfr`r>{S<$#hfQ`8UoO>Sw zwM(BIcfM`o(F67KDz$`vVR0$oFrr@?}=%s*IaIQ?!E6h_kCa8ciwaAbniU(od0v4|MT4IeLnrFL*VeL>D)f_1NyRR zT;LqTe+c!;V)Fd%b*h7XM}J(VKP;aia-Ne+{lwozr9Jidk)Qa|M{F57h5tK`e;sTo z!+hdUm!%h7H+|Lpa#ZD7I(_Zo>Jf4J1yz0Mnsm9QxKH#goYkuPLTobxj(SOaj*5${ zDE>W^qf!?d?Cba+&4L#EJxM+r3!X)CI~ky&22igY@y0|3+t8w)wwle*OByl@7@#iK zpz4Y>lFExX0q#M^8f0*D7SP$*MWBMNHmIcJ@s%ni#o4kaMYA0%tKf%Ey%?Y#wTRIw z=UWjynXO0rQ62E@orq{f2!T<=02QLG^5@X(c_#W*vA4*tQ98aCP^)N`Dx||1pt9$n zYByG?^p94D(-h%1!vHPoinVoN_qv(9!na-wP@mdD;rYM}*Q*2(O>G&VVGW~JQ6qE> zC}XdkuG-3KV`!ABWjgvULpW~Vgx_!#SZ%}VSom7 z+SrJ+;L9c89x`GlW@oJ#;4pxe?Go1R>H#ZWJMD-=ACj+Vk!VnUn(3O?$$zd^0?14C^HGzqp7R$%PTSU|C}PQl-{;3YQTo^{0P9UoZ;cF`bt zUbY&D|8K`IBpk#w7-$&-G~kiEmR*vz-I_TV+QjIQO^vVt(=@E-L^tidF$uVvJi%hS z*#taoguP~rJaWr}AGX0jtr(!C=N(2}^a8j}YzO3G5l~LLw*NO2{1)Z-mL+X%2%0hg z$U0l5JTInPO}F@*lA}?+nLxuR7^ouyG;(WWAMwTycG)`c?f$qdAP>c3 zl}i6zDd20-@tjOFn5(X8-i~JrMPU;R%x(sFIV>A0lXq*>$_5T?{kSL&@)%75Gh8e0 zKDL%Q?1F({Aj1GJre$&0d+c6$=LhIL~*9ONh*iR(~fg@n+Z33gMnb66%6ol p??<)fCQp8n7=xj$AbJ*K{068GS>67Gs9FF3002ovPDHLkV1mH;!3HEtW=#4Cq!^2X+?^QKos)UVz`$hc>Eakt z!T9#JuNSkUK-}xN zy3$3a*2|)|88P+VipiRrX)xc6<96RxzpWB&nN#kbx$`EMZSjKD$?n_zqh^;itetfr zWN!IeF3D`eo~+^-=G!ED-f~r5ICt-lfwd{CT&{wA6>E&5>G2IOY;*5l5pTb-S}TFM za^)|sjC-OL+Zykb^lyj{eK4(mZ|L9Zv-|D8y}JEyHJ^VKf8p}B14q&>?pt}=L2t{O zY@6svMq~5eH(f9OUg;v=cw1hazvNKZ&Ffps?%w+%RmR0S5*~Ld1{x zO!a@Sb57j$=d;SCY4y0Lw)n9(n<#KBhXDzot z=I5_I>)n><-o3DyX`-3GZ+n!>Eg6BmUO`u}u7n-=O=-S1(9a~(3 zr&><*h?ac*L(k>bqqSahJeRC(`P3lia*HkDsohkM=)8xGUpu$(vYalpnz$`y6Z7kT cQklP*^0qEYQEN`^2c{+lPgg&ebxsLQ050{ZK=1wOcnI=%}#*3H>8KM9*aqPX6E7L%J(3DqqxjDyIh)1I!r>2##ok=v}7l#CGTHA-AUZ2t<1v z8rO-v+}4c7JQbN~gol|VNIuw=b1D}-e@RQ>oMbS%(EV#bM`g&M^W|~xEWB>awgN$* ztrp7~An&HTW|%tue;G;XGlyPG7+a2Fq9p1ZZ`EN7Iuq9~k*}WcjsyKn*Hv1-N-}KP z{&!0~GNY%V{O+yHz;S1G2IRvTodg-8}DbRFmoQV>giHK9#iD+hgcta5KLZ#g+h%zO_g`pNx9 qf}XB{F7tQEnNsbyzzpm?xcma8+;JeBVG$bu0000yP$Ou!_AX?FxFZ7cI1)RWAis3cd9o zuol<$)`AuEsG!H5>|GQTv=@a|(1KnRe^F>xt1DHPwN)$I=Lvbo$z+mmCdqtB`sIb$ z%#U~8_n9Y?$z(G5c4){VGcz-15iVJZhGyxRP@2)x5}yT;_^?E>lv&O)$Xv#wnoKd# zOXx{?=%vhZ*j>v%Y@oBego+C^>$kPI9$hL4uQs64xK{<$Xhy_k&hbd146UA<)AGX! zWj%pPYqg5I^)hQ5%Bv8bAbe^nDBQGY7D`&$=gdyT3=EElg}fv5rf223H!FK}H1-)? zY<=cMfANL!y>2=$?nRydNzq;FZICmkms{hgG{TAwve#+=nF_Wj(3r#v9M=H-MX9HZ zmozH&qNC8`e0CDG9TIXOta8xxRv{C-aGs#%9J97G&CIu@VdG`wKQ+sEp?zj%GEL8} z0`-((+6c;d(B7iPpP1t{Y)%Pzq@OE=+%yQjr;+!HnQu$$25sfJd2sYK!YzbJgdY&t zJ8~rt^+VLu@7h*FS%?+aQVVFdBXC^lX_R%S3wb2<<(NPWg+EcSND6(AI(mf|MlX~x zN)UuDV3c8Gj7nyiBW#~${fG+PQyHUDmy`rC3CB37&dEU~_i@v9PI@W&+nucPOwa&ZYI>CA&@+Dpz+X4( zq^?4Ml?h_u`JCybMEV-LnOQ%yyeXj0^ENDuf)j;Y|K52Z#j09+A06162<}=katG%10LB8C|0ng{G#74 zM7Y8Wx1@|00g}29ix>fL-k`Q2Y(aP*;Y|cy%zUW$1K|Y1F)(-;$NB_7`PSNb-eQ~) z&fohdaK6_7P$tQlUAP+?jE|K;*P|}GQMCexk9s(*s(8B#^4tp%NS45e>x#FFKNp>g zxL|YND`tWQV6G~0b*T=y3*d{h99uyH@N!hRmQ|@w`I*2|paGaWr2g&`uwHJgUBz}A zZwg>GXcQ!-F3tqgP~h9ijlG)R?{f6-1WuIzVBU5)mu{lm25wFbBGExlBgbi1L0q@r zheZH>k4~dL4VL*rR6wt6IN%5#dPFok!Ax##Bh%-6nEnUc@ug(t0=r*$oR_zJn9hBR>fzL? zic!qEq0^%L)Q9O$EC#B~O6@?+Fh1qOG;MJA==}_1WwL$N4li4GL*;lU8$J$lOcgHr z)u($D_EK@hW9%MHpOTtwoYf7mkF8`V#fR3$LGPXS^~=g-ZLM4d^v~1 zz`|wb>II6g`~IM%ax&wp@hU=}YfWw~o_6TdEmH z12~uGJHrhK8xcN0sA`@3F>IYh;Fgb{5H8>XZ__j!kP8S%je09((wD5N>_y))g5aHZyE#j#J3zzPyg) z7X*=u+c7sUax-GNJsL(h4)YRe$FwJ-k$uSK=aHj%<9B9{2FYWn%vnT7a_=)mjyOvp zXI8NijS2^#ebic`%gkfoD7fQml$4~1hT>jmeVNkiGF%zh6?2%-PmIw}7)Pmk+m+Dl z621)V!I-^IDk-8ta;vrxN&^~xTnDnF_sS8`AeqaR{8@?D8xFi}@a_ZfVvzk@#%R6+ z??|rxG?LS3e*rhr@GHCr2vse(R}Z({7Wo2VA$v4Gb?itEcQVQCHWIxxoR7|O%)k~B z{a!~$a0W)bel!K+xvT694n2?qG;qwdksf-Jycs?LX4n1TuFV_4l%`ETX`Lh6#_bjKhJtmfAWmtp!;5c8c;GH{9<%c4@Zau=>sL@RjFq7oQC4?l;( z`5IWuhhlD%yZ$j=UjZd62bPv<8-5iezbhuy!ap-WG&!6v;G`AetFa;4i2wLEwg&PW%`kXG>xZ6E#yrvlNQ_ z?u@^+!`HfCW$nRz#lMNgFt74CTuf5 zkmVKvXOc;hSC2MXMGxofVs7Uw3&2MZ_@mCw|7HWa{Ssm#wvk$UW+>-q z7=QYk|2?ee&wrz;x6l`Ta!I)FQtD<{HCm9sm$_W=;tHaKWr%Z;i@WM2AR65dIF2%K n5r-e|T-CxAjIGa*ZiM^?DE2tKw$>7|00000NkvXXu0mjfk@?0^ literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_monitoring.png b/selfdrive/assets/offroad/icon_monitoring.png new file mode 100644 index 0000000000000000000000000000000000000000..05f78811e274a59ea8cd114eeafb16a7294878da GIT binary patch literal 58679 zcmV)9K*hg_P)UY)i%PV_YTq#M2d={pdekbqgYS`1yNDJu0JY>f@1mX z`uU+)K(L_LP(ct2T>(Ks5m1DCsZykK>2Uvd?K_#1omolN%4EtuXYxEbldQb!T_v+~ zW>4D-EYO28Z{EBIdf>(ak89Hj1U--JJr2d#HL`$wVZa|T_$IdtHbqWBqFlxCLw+JB z_sDLxFu{q}?WbfnTsg8ncF^v3AnO#C9OGdjhu*9LRdW6tYLbN`2!JqyCr> ziR}=KZ|xF8ws7H;FA?t}j!*&T9G92+#7o6DX35`VwMEV7o?#4=<1Qn{7KiwLTW;{S zjM|*OiwX6myas36D`fXTwoJ%Ibc~2h34wvx!Qiaz?IE3%F^juw`gj0XzXYM-!-?hK z*g8gNkDGSLfWgGJN{)41yu+WgB)FWTzD2yG4Y1^+rafl2U7WK23!BTd!SRU0bB#6j zH8W;p$y*Rrz8ONcolR(rnXNr$+N5K~1KX1^c2Zz`G-Np4t)q928Hapt)3&#euVwdx zZHN5L9N59IpGOx{^ta*oI2rJ_G92{px>6k6tO@`E2eUSZsmL6qQP&1Ru%nH!$4ndJ z``Z|_S1@DREp#8VxqSK|j6FteABR_N6WAc1T#K>su{Lb35wnZ&WqlY+UO7aF+4hcG zq~7cTbBcvq*-NGzusB1uZI~AqHBBrb5Qaxbmd2V7YsP8o!=%bB?zuh=3lp^O`d9w% zH3JsWdl+L68JT^AXJjpJm+;xMeKT7) z;es>c>Ph-iZXeE;7wuPg?E=7_Ub9KO%Ef>N8{=}vHQXH5lKs%-7O$*CVwCOO(8%nq z25aj{+8S;RmTZ@6M#vG6mS4DHi3ss@Fm{W^=4j8bGf2vA!1lO1#u?M%IS!vp%k9J4 zaU$uWc#GZ`1r7$J!;#d_Lwb? zwJp6ZV_509#X06B9vJwB}mYiuQB@jR{>lEu{g!P_;euutZS4#94C;yOA%qAI2-cy zT@tQu>5Or4Sg9<9lhd(f#x}((`Is0yZP&9qZMG4>e=U2>ee__6PUqRiEW6{U*vAGU z9hw1CBGBM4IBqmNv<-rtK}+ws&d{if@kcqiR|bU@45=5y3_#~hqgQPAW?(^)qo0}x zmEM>`a9}p-*zt$$)EGF@f!-0eF52u2aWsyeIv`u$@I&?-)RRo#yS0_6Z3FEwTOMme z?{-_4+A$p(2dr|Zk3`R4p#KuGRg|Y%aw8jUjeKl7hA28?0Ca4OJLc(5D*w$9Ev9{c_?eS3?15fh~7HBh0+X{gtz%YI187nkACP2qhDVq?lXX7|MjQ^@s zU>X?zqs77gV=&{kdh~GI22-0zjLdT^VutPQ#lViP>f8D@z}Gf5LV5;cIBcvtW-#0~ znhYYg32j3hAt$r-Xj`z}xal#=2l^s9n!G~)zvz1}cX|)HNSTW3yzQW6)NUSI zV1924?RGKlJxr%@Dz=W@F2=_G+ZE$>BIwAs+>49xmF7n^?^v5J*e(>x4F@g)E7ZF9J7TNmw}oc^e5>p<{tr(der@}xGHM#uQJGGrT+7Us=+ ztuyw3HO4i?k3De8j%@7TuRZ4YL__Rdf;KLx?K5hV*_c3kGh2t+z`h}XH$ykMdZupx zv^BEEwpwF0K0~{5qplk$Z0u>-^Z$geBL z7PsZCw0%xBZ5(!QGPawxCFbWGg6#L4TukZ!!L<#?XJoW>RNC*thc%5uwsj+;EhFb{ ztF&R|@reD-lXEh%W8^V?sZSEz*nb3xf&^m)u(JpMe;#>7 zjHHy;H4LxWR=_m{jqDjdpER@0VST*QMvkDbpukb~oHjwF20}?d-8fZ$;`9*grKqD~ zJI~2z+$Xnnd*4P7b0`qoQ4^R?o{F{g>a-jA4+4kQA*Y<6_pjrqtqWf9SASbC)NbUz zhn)cX-=2|6W#qWQ8eLl!3QRjzdygOosn~{%^R~>_CM*?a{50w_atD@gEpZ*F7>Wt( zB-oA{xh;!vg~ok+K6!|X8>_uXfb7AlbnX(Ke)H<4ik*PZo#V*M?tF$ShilKaQ;coFVD>JFLk(lpY<*ZW zUThEJa1LhF<#0ZkRNuvMe88A1WO6@Z#LoD69>ZfW4kML~5uwBBg)r_I^*Ih!2JEX0 zfekP+v$e-e+l-m5k=NN8F53EdYz*4vafU7T>53LhTbW2r-~Id!EY}vi zCrY>thPJM4dyE?||IOJzo5Ux#G1LaGyk*fHtJ?>6d9z!Li}Tl(nYQ7ntPupDLHF}- z-3;q z#s>dKSI`mGqod%Q_{i51+ylq6x`0^i^&$Eim<5q7`fo8-0v_!g7&Akcnnqu@W5J>` z@)O%z*nuJndrT4-@J}&161)Zj-lH_!!0y1|jm+Abapj5maOC%TNDk@-r7cKp|Qt&ZA&NkAI7KelUuyye*z!Y$fY_>FP2U7n|Nz) zX|Z&RWI?QLxF*5%HTB0n@|1vzU?jAx*jci~!Dfn1kgymuyb`Rz7#-SLvh8d+wds(R zUMIP*0bx4}OF?-v7lF)J!Wtp|EE^l4t?@~VMW`{;ik%dSePR|f zd!jI#)vwPsAfY{$2pFKnb4-@N*@jB+MW`_c5aU`dhA!%keU1u%=y<^;v-Y?Iqw^@Rjh<#{_~(DG_L3a4!R}<*~NWp=}H+8BgJZ&Xq>b zwqaz}_Q#{~La>Pqw%eA%UA8>bwsc0#5H>dEaQ!`oH{-URk=a{}??M=oi9P}bJW{}Z zWRr#3ww_kk@Ydn5b>06GhTm-2h0!K3z?7|PT+8d?UA~Y{&^^bD+j=f%i7^cT=&Aj& z+4d3Ga-;9ta)u@PuAW54_QBRSy0)yqmhbYi_XuwiYy+A$V|b+QlN)YsoRb;6y9L&M zZ4>hU7NRv^hD)Ver=WO;&r<iA#qg-r9#~_Bl85`?LFk=cuN2vD>gQKm(^AUS2)E@gdxIiK$nfZ)S+sLSm z@)Oiojar^Rwk|;&eUH|-O{pH)viWV>B)9us!}b7l9wkLnoU!eVoZA|#J!WL~)*g4- zV-M>a9fNWEM(%D6j<%sO8#mT=m8d@k5E9!wuD-SpuKNuir)$Qn?VDYkH8yIx<80q3 zv4e%sV9eIVLT(;ytR&LK#`?wvZ8@wx?!%BC#?~&d4{|&r8E2p%EjKPvIWTYD=iD(( z-{QH})w9M%O*4+pC}`8qvbBx5g!UM+0LOzP7DT z7`t!Ut}f)q8=1k-*2t2#1=;Uyf{+1wjBDFGp*E-M%3OVW+>Al?2+2)9+txPbGXQyc zLx+pE`X{(fVQeAPJ1h*_boET%1sl0!8$7af31Dbh$nG?9$&ng4XYh5mT6+?_@yY)7 zX=L6lh|4onwh?P4=AZJi7zjrNB9$#eF<*QBUn4VHW7qU)TiCKiqPA*}@G)Amz9<}_ z3r4LJ%WiT4jH5}jWRz*^I8!Epn=M;U+xGDNSdiKkakJbxY z#yRHUEY})apTlyTG1=HTg&3F{x1F-a%Lm{r8QTm6LSr8Ok}Eb|0wayuAB_lqIgFT& zC_4!aJ791L;Oe?0b>5=### zSAMkH$8Fo0q;_jZ6Lph<$$JG&pi{ip=3INE=gJcLl^p^cmG`<5FU&pW_?p9hg3Ef9 ziPsxeB|nHrg*fRX2u=xSu@J=XA`Nz4hRp zYh%!6pH_mLyLEf)WVYdV_)IsrsuiHwhGRx=k&K;9)~xM@zNA-(4|-sma;z2Lv0zQ;ZC&l5cRK70l{_UadHz~Ebq;mjr4PwS73=bW&|?KZIG~tVs1hI*)c7*(EBY&=a_G^|4s?(>5r^0biz$ld$ z!Esn41AdK>mh}f?ecB<&)yfO!jQ`Rt!W;b{5Qm?iQ9h>}zB3tuV86=Q4gs^GHJ78N zJ??9}I>LVWG8!Lm4mo_eRp^fmi+&Jnu+=W_+i-mcW<^)lS>JNFZ02yLB#Sp5&0#Mm z2V6GSUE)HqUU8M%oaPgh=;n(7fZ$`9r%qas5Y=dVyIeu_OZ)gnI(+us%*$>GC0LMi}p+nDLHK8eFvF@aj~`@wL`itHpb=R8|?1}zfY9#!{?U+_wxYu25_zEj=QmH z^5k;W>XRc*`En|u!{c@@l=4Eca+L3qIsH#cxm_H1mPL*IMCh0~mm}04Q>=E9&WV8L zL6<7zgK7-KH@oC+Uqa~WIQ_3kI0ys1vFG(1o>5oIRTl?i^eW9@(bxzP#dx6mnvgz? z#W>XC;M_Q5G(;HCn;X(|#{xY019pu^`ta?Q0so?RblLO)9&el}I=0O$Z8%|GnfQDk zAu#2SiMmevbbNAG-}HU>uH^9R7~`9})%XP6@>MEQ9^g(urGKmTySOxFo4pZ)0`Yir z3l5G}^^CD%A6I7wS*({+LijuOq}0^N0!zT>`>lSo*>>!e)7)_2dUC=oQO_L!={urP zmnIQKwL@?`BqJiMxgrLbfQ!iLna;I^~e7%YM>;-V(s`U9jB`?Y%b6 zw0(Fp9@@emI+a~n)#`AD?ByJz%)5Mb{01FeeXTsl#&L4C9beS{${hXCSHWE>LQ4QA zZX`$CVnLFcE}!Wqk+rO3e6_cAU9h?AwvQK>;QNGJJ$9vVLDD`s$Y8g|Ui>FUE*5!s zdwon{g5!MWKGg;<-EzF7n}fStl3}F$O=vQR@;0f1gd+tGUw4P#I0u=3@-YqNoQCoQ z+z~WqRylYKZw&;SV@g&BN=tK!7Nk}a+=n;GU(30GGJJkolYVpDB;#E2VIBEsMKAw- z_{eMnzNN{h>%-fe(l%!!C%@DW4UY4f^mF>n+2Hs&oEwYLE0-D)#EMH2>JwLJJjWOU zZRPH&9KKo{zqQ(pG`SrhHn&;l3l3~VPPip^v@XBt=eCoR&-iF>bMg}xxW8`mn|2*L zwLi_|1m{53J+Cmp*=oWL7mrrP`AQs3_{-U=OSMVpki@bLSLwrpjvvsDI; zS`@K)rg6IQb7NS!EN02K=Mf2~>%((csjN*~QlES{&etY#LiRPbIIJ7P#Q*!CfSO9S zn=DPAOMX*+=C)OS`_KgJU{yECIJ!ByH{~FiR1WMAwLjQy>^XLd z@CnJve#Kk;Lm5Wk^lh{hdCG5mCOr7nefU(l#}0c;lWHTE9_MQ=Zkva*1KBTa47EKt zBfi+h#}tgBH~A&NX;ci=6o7sa$Asx7-R)e{9k04^%H4VuY7DqGsL#=HI7ar3QWt~l z<7bu<`x>8;01XRUHtq3TZIIto8gLr9Y^3tQo$os?mEBa%kX}jdG<-UMRbI|!tNQek zuVgfQ~DiXjM^uvLqba}qN8F}g+yxG(qE zG~#zQVz?kRMts{2Z2zH2nwCCl3C=k1+#BR5X9sZjTrx5cDXhP#_9M0$|Frt- zyYT?`ArE#v7aQz*NGf6<34rXYcp%@zr&C8>aV#LHV~2D>y;*>MY^bg+pZ=H;tHa@~ z;ZW25)k%(qKVY;Od986N@N;b)tNpHVWLgh=msy-{^FCML^pnnOI2@X8whx2PXe^69 zJtL3lm*Y^VJndW#3L4P=hcW7G#m5-XJI~RLbw6WV1Mnp=aE9^n>GA}wos6%Nt&d-# z%VEH`3MX$|2E!Xlf&u10A5J0<1tQT;!T4-~D|7-dYRct>!vFb{Tx_R(t&=`{M)~ov zguvD%8SGWg6uNdjHm>lU+p8;;-=qjK@-{OBexc<-Tk2N{2 zknJ($20QSJ-Va)NEHLC7bm-rycpf5LwdP2b8aO`sT_Tzcx2T8!cJ=MPl*`t!+J{Q@ zo5ESX*v+>{?Lo==ggy}}cowxCu-j6O)^Tw1FxyeLEpf=zp}s_~DGbd2EY&CI`M#}< zD4X)R6<$Q}UNoI}4qEER2x&YI6aZUG)U1z%wXV<~7T~5!)pzs4$X}<6zgX?q~a4=~(5AoS! zCTLq`x6OEyTiElx&gfglE-*XVeg)d^Hae1RfF~*M5}RTStd+S;d&>7pP>nUy2N2Fc!g|ji46%xVbce# z{2S!#`jkn|;d9Ew-;Yy`hJpxv=MLEeC;2TtT^{0UVeAsbxp|5m#JL*u{^QYo6ugy} zmw2!$agG~zRR#%6I|CJ05lI;P_u`J5K2%4)_&p*i{$OlrGv49$T-&Fj?cE{h17iy3 zGxTpF4vca4$1cR_Oe-0ZGsh&z-sTDtoYI%3+veT&?;uEi6`>uAOI-99u`x5cjfAjY zX?;ln{%k9$z5B$#w+~wWJtGi@1uL7iu1@=GO_Us|P`yE}Ox<{6_r3%@?$%V#=id}! zs^!DZDEU-6MlJ6Fq=PHFT(ZhRtHI%n46yA?o7-Z%@)Z#>)>q4<-TVN@OEMdTw(51w zKF%2-N3z)KCBERDM31^0R*EBCDHgaVNU@wxgG`tKB>C}7qS*s81~(FMrZ_BzBN>N< z?D-rX^2+lm9Bz=clmTw?e5RGyi#2$k%|YH_1~7s28sayETu7N@=p2Ju-k%xbAI2s$ z1DIfXsOXFdb$@VMngL9*`6;OXW`( zJUI5&Lk>I00vSNE%^g?4*Dt!0QuHf7Rs;D$4EB1?1sBI*Nao_G&tW;74{P)>en_FW zl#$KoEt28BYhpQHLW;yyHXI(Hu}APYj8^6tW}jzqFs6I5&lUjgs)yhujH_k zAmet3N$|UIACZ{vQF7c8G7Rj41^(?JTvuc8%{-<5i;xd)%+wFzXVe&%9LRe07Tw$v z;)!|Y>=Z~q@W)Rueh`O^W;9okmL)3sC+f_5v3%_#}$&p&MefuP`Psy zt{dNgVBHX3${09Ta1BvE#O2~c*j|shftWt$G{&B9#?6+)X=LCr=RXW(&MkX?sMJ5# zk&vE?E&6p&+lNdxH|7auB<8GQ;89CQ{hTCp*SGZBY|iH53CZBx*DVLV?-#W&Zu6%h z{yJlgo~J+*+rqiCJPy)xlC^&m1UBeo&;1@7U5M#<(&ywbjM(UloN@?=kOrz&1 z;5fbA*7xJAt0Cx5RH79MpgX#=8t^{t5aj(f@XeIu4;={J11@%lfP4;WVo|l};)f@Nsc+RG@Yt?6B{;;B?7vPF~1@|CR!J<&ebT63jIs z4vOC31`fK=^EZy)lHHE{vUfXKm`W4eJ3;vS%0Rl{-|%BYtvdXmTt_E9wi8A29sDH) zsn4}nibxRA_fa9p&%)W@4na0h#5)8yx25D!0e8+Fg7Uh-eCE;LyGS4@@PG71KVaE= zMGZ&cv*~KK^r5N!A=em;ViC;!R&_8cE{D_2+e?D2vAx;lEKXmkV z<8ZCX;LHIMW59hpgv0o+oxsMrAzgQDOfju<71T~fJ*lXtrO}LOy}Mn68MVzC>|g{(lwrs^Eo9m0HzC z=)k>-b|g|CR5;ieUA}f~neI(KG6UeYJ{?XD{d+l%LbfNT)21xoo9Y-Wg(swgv7a=a z2hIVXQD9f%@P$l#LW=kUJnQ)Ew=EC&*yxS{yYFCZU)FZ~G)eR%l=l|_$sxv3Bl?}j zVWY%szpLSC1Ize05@~JwcpyL0$5rSwc2lp!jO7*EBgFY^?Gc5w)EBjmrQ6le3i&J6$VTBL^49!O7SQVugx_sIQJ_us4U=Mv2MpyKM}w;vV?u zgT+1Ayr4U|z!EO{LFDGeT`A1%T)BV8D*NR1eTN84`ZEJ#!6C%#TgfX2^}xpF@G@?P zAP3kdyNz+|ZEFK_jpOMfPQUDWJ{h#5tx$r7M%Niw2=h_diEO7TD}_A>BdM$Sh+cv8eR2JE7a{-|qX>a?5WuH#osm-CxsF+It69d778 z0rdu(qhiw@^t4Z}C|LrJPL|-w499Po?`@Ow8#3?BNSZ*v^Cphp#{q2cu5scry3%8c z9iWr#pwt+zvxPs;tE1ncZk7jkaIpGqE(YYK@>CvV?+2DW{lIZZcM8%~-3tKx2Asi+ zvi&o1wMo_V4KUn^LV7e)SFk6Yff_42`B*tcA2vnK@slitt4$rw@0|8Iel9PNUFySH z@@KQY0kEqD8f&r&5CYWrE0o6^u{u7V`XaYnEt@%g11bA}5@(}yV7ze;x=-iuwPfQq zrh2tV9c8e7cZzwc<-mH?g_k={c{ODYwsD{_EP%9B68C^&t&7hDDGM$1pt{uj~+Q`G_4w_2`7_S5rI1 zmt8|m^b!0Io8WDb^QZ>7ZR&mPj<(&%zmK}h7Z(J#OcJgMTbzBZjPth%UpYH<^FlX- zu1>_EqD@Fc_`f#9o1GT9Tt7Q$Cc@A>(-@hde;+r->;Zdh4Aa8+t6H#;%S3BWy=xpc zlOEC`jPx~y-esCI)WkALfwXBWl(^U!=O^hjkr$0EAJ&aWdZ76(S8?c1+YHRV$Q9dz zLVGx;8^YH~Wt+Bg`$>FFt5cmZ=bAVzmc5+4joa)DNYwV+OnLyr!w(7 zyBqTVFLii>I|U|U57d;4TU*p|iqpjbQrC&*-15nu;2UT|j$E-Vxu`oGlkeeGX^IwyNk@gP|t-e+mlAaY_{< z83ddi$Uc#QIxB_8Pwz9hsm5W4UM*cIE?)(}3(C99ga1Apa{8f`O2Jaq^*g5yt~k}9 z0QvU4&vTUq+@jYF5L=G-l-0(b{EV)E!oE#qSrvzc0fQd?$%UK zpsI#Uv5&QOaEUOw#2CWU8PoG%Y;kZ!v4M7b%t)q=&F{2-naM;ljpL8qy*HWEqX=^L zrS%>-9aC&#JH)iBPoo3$*8-@1MgV$mV2orxu%dur=MS8%LUx-kDNV}*J~fpG_LbP0 zIN|g0h2P)O=!vnOr0gOlPyju)O0j~fHWWrbpBw}B zfdZfB>nq6Ub-k713$6kz1U`HYIZXW4XV=Jc*fAX7q#tSvmDLTli7gC&)MLDIXTAq_ zjoL2|t?MBx#XeF1o>hXz8$0=Q>dME>czfBtm3S>!19f8x>04&TnywB8y{~RIims07 zbLSssn?dasXE)FD=;Zzt;gJ~%&STFN(@!mI?FzMhg*`2`2oL+u_5eTT$}tz!^9~M3 z6c0dOCt$2N++$tn(htLMCF^Pd1KyXybH+(F=BTm*b@seK6SjP=X>IxNj=XZL;jR?1 z$M6oo9$5L`We0)b_3ggZ&azq{pd~3N@ZMr^+f6s7a;(rR`_cyVP6pN&_stv+*+QAi zjit!I^&XGjtsc3#QTY45agt-cDi3Z~@S{-1|EN#VLY=*w4*8iCgF*px|7YASws#TH zVT69KBviyFltLslR@jTdXnbj5s4UE9fCYPm90vzw_kJkTt9l>h6r?h8fWv~9wdrD^ zz71sOxbjfn=JweS>1)S~J=mgGIbEsH{|9t8lj6Zo#|K>AE(Fgrr91`)zD1$;py|6? zcBzFztsSB;a+qt3`k~3f*nu=o1<>Rjg6tp$E{QahrP%yv{~M&5C+*F79}}zBCjjWh zW^635tKK2V5cIq|gx8T=1EYxfKVuhQc!*r;^A`;3%UM)N-?xC#POoAb2Y=L!Wqf$7 z=R0}!F6VK47eXyhqvbCgij;E!E0*1E81#GaOq!_SW8hw}kM_BX%e z>mcm1#2GX)7^d6zPceOKyDXNa%FQkmv4yGIq*n%24%lEf8b=O4Vs>ETMevWlsWe(R zKVbWI7+u~q%wb)O+h>m{ToCnPbiE?6+zvsIYv_+#Qk-%)Rw0g}EaQxcyQB|rC20}@ zV_bk`cL<|j`0zymPY6OEO0KZ6(VS7?6l%%l(?!yD zA*;Q!&pt50JLoNrvKipIu>|=WulMPz<$fFG$WvmZK<-we`Nokk4jPB*Bb>TKw`oir zzc^i27V{tYKe{?@KgJ;*cZse3yTv2`T6$dbLJ1cXm*$iux=mu>)4Fy2;`EJ7<2!V2 zHhS(>!xO}U_ze#Ew}T3SL5Iifj*hwm>Z2i7iTW{}rpGy-G=BN?3whGlPw0-Vs!ivh z7JnoG(RXHg^yBC7Yk3`3_V^?^o$k>!;;)1)PrxW5F?;7tA$Lv0zHLPJQ=DE%r^zw+ zvU!R>(0MYaXUW*Jy4Lu=nv5$8x8`?Am29Rlt(9ez#HOB9rO4S{FeruIX=BY zemUn4r^Dgu$i(L65wy_#pxQEUyc1x z8a35+mI}>)$w@|RL@zdt(3Vz=2#@(RoDb-;hzr|0J*MxV;gG#tW3W%ZF2I$~yTVv} z1-|l|OGzb@VY}Ua0RAcKe{jj?A&2& zIor|uG9Z)Q(>d2?2^{Z2rMuWFKNA7j{-|v6@wFo7JPH|R@W=Y_z)F+K(9Re6xa-Qn z&VB{;I^rMjF7=GcjjrFoti#}rcX8Uj*C{CxIc2b+|7SMN;AtDtA^)Pcs@r^SJH+o| zC4IzE+b7t01b+FBM@DXV@^u{a_ICZWu{q-PF5#|WU!R;X#fPz-_F*_Vc;^u}#y-rA zOJu3GIc{)KzH0BJ2r0NjaJCB>U2b@;J5D(=#U1NqA3=nEId>zC)8M)mwQji!1av@K z`B7Kb7hvdKO7ji}G;0;rsvNOYxzWh=y|;Y?_Ju%jqXV)O=fO$8#Xcz|c{L6Nn36ZC zj%x3fk{TQZW!ld6ax8c3cWnn3?1KKu0Q@Zo>S&Ob^BkrFIs5@k_+GkJ%XIQyT*K<4 zz8!)RV3lvgY=GzQsG|bxA7c0x#_2v)<4@3>73Zkw0~48NZ0wGB4< z+!rKZe+6!H3D(ANZE&d{B;t4kGCIewG-4WyQJ`ne(Av=8*-U93ZNiCfQ_yb76%=^s zof4i1!#(CiTVHI;~tcu!*N(xvg4UFg%|7GFkOoau9TjE%j-jl*bV#$K^K zgwuC0rt5pb%II5&0hukwJELSs#M4YNXd4RN##wDTfi+ezM(?<)lrfOi0dOr;@9lF0 zt&l-rQIt&%N3s&&G%&P_t>X;O>@E_sbtnTEXWvf4=>RMG9SqX7CxqG@ABQXSD({O5 zU}HPomOk5q+>-%!@`^rt#nOZQw@dB8o#5iA@4=p>zGHWHmCNNwO5n;UM$v6uWbHUq}p=-mNi|+!?SF?c)Y!^h!k= zOKlGCVv0VyQ;CJ9K#mXVIQ`DLLVr8+&u6#~C$D_I zCCM=n+{vE}lE|t`y*#a6b#sug8Nky0epL3`fl;uQcf0vDGtO-RTpslwsFm|09DWjI zl~c@<7(^YPX>YLgCw0lUV;I^)25MyhpNZA!gW)Naw;k3pHYg7n7&6d&2Jm5K&-51` z@-wv_K=1FK1;Q2YsO2U+NS1Mloc>NJyo1h=fguB)3^*S!Z`Y&FioGP&0q^NNmKZ`% zysb*ZN-pwo4DulZGa>`{SS*H0?_KyA>PJwc&na?=f!;Q#((*EngOf=KflFB^#PpnR z5*Z9^fl9w`_I=bHBsv3T$Utv0fSquiY39g}jqdV#)bp#Tqi*PDl5^O8F{ zQd!r-V~cZL(vYTd+T&*Y8SdOOjJ=g^nW(&ph_Ul9&Ze_>@-bNYfSeDx=x#mfS$g_p zakd!Q?ciLIk+UMuUW$QD*+EAr^_A4Xy8<@SMQawgbNu3&cdJ(x!CE6p6= z=*iY29a*R=KB1`O4cSZ`6D<-TXYZ~J7?my(^unxRkq9Jm80tX=@IloS@hxH+Qb`&V zd>2dj2m{VN6ugxeclqpqbL^?Eh>cJCcm{b|28JVww7kW%G_Mkv6C<<654YMmnv$qf@QVetO0>;xKE6pq8NbYGnd-VX-ohM^$?=^4Pz$Ub2R`8!isq4!}_ zago{p;pqZW>4&N`3(n&#-iOeBM>(i$KsWfx@WPJh3J|cW-xyZ9TEbz+cf_(+2^tzR zI|Idz8`?aOk|7Y@79w@VUZk-BU3y#Ar%^9LJr#8)jeZ+g__Pq}Cs2)#&(qq4uBM1j z4jVr}PVX6rm2(V!*v`-lU=MkFY%eLswI|+285MF%uRhGUSwj9U73S~&ZF0c-6e0I8 zKicF@N4#`rAzVuQPz(LUbf>?eni5ajI>=w_XV90^`UK9MQKjXxTK)k)O*0_fV+c1* zQ!rz~!W8bQnD3)zOk##WWf@THJi}rkOKI;=nB(^<<~jFOrrzaa#yEsYr;~d3cqV@x zZ6Z88ocJm&_kiy{1KdP&c?;lsX(zRzT}mqZiW0ss>by5t?2pCejuFT06p^O!ki z=1OEoeb|WS0$Rxd{G;b8=pB@;*vr1B^p}vH)?E?P_+T3@Vjk(9jXM%-&4Z7veZ@-f zFQ_u@c3Mm%-9f2|>m!)Jj|a1qFbF^B!LU0MRGUya1Egmc^&G@|e-0yvaY^uOXVu`Z zd*!exTD5wGX}^zx3kVrpn@}F~XsP7^kk)@_|EgFHq<2*U)^I*XAIIM}nRO zz@LJk@xin@kjZVUCgqUuq;o6K-#awKJpf5pPG;{C^VlGn7 zKd9Y640K|f-mNMw@U64YDmmHNSy;q`yEY5~seql4jB>NjJ%a5(aKMuaT=98nV^Y7@Viavj3bbhy)(8y<1c9 zg?M52iwXYvRBD~iFn)skWj+HEx#5}dTO?~uNy0psEQw1j-bHBZ%96c{nu=}O@3;Ty8`tV4q%^9JWkkmcuBnI|=n_$ybd0`zNV!AN) zLD%3k?0+PdhdSfPSM23Cl9ZmK^#P=}N{B7Y-?cVoG#-h&!AhRDnVKXJKHw#l4V;^5 zJEjNo|0{E0TBE)d%Tww&vUY0C%-yK5Ewpu*hO=#Kr)N?n!6M0@0PbK0yA@7osh`&X zpZHg-7@H(o7Ix`Y?5qWT(Zg!F&*W$Iu|qOC3||y^r@L;m736$rkky&X>)_Mc5{F>x zJHT-dgKY?o-o3Iw5>qV<5^^OfSAJNFxTZ23`YPv?P}a!R3D`bEXg>$+e2^T7s(!zu zFZJMB9+h5Bd;w}(Mg7mg=f5q7^Vie};3%7`tv3AK2-RGzaoyjxEk9It;HCDY%^@lS ziD39ecl@Q66B5k^)l!{_=v|2M-rdd(pPq(Fi&XX!OmgBNoIJCJqoSjWMAzt7*p@=Q zL*rknt;X~;&U>)C=5!7==$?So^4^@j7_L-j7`=&qh5#|0#Ke^<%KjA^j{G3i8R%v6 z2V8%v;RmViX!gHeY~j%3YX(%R*9{0nsrL~4ysm9dAO2il2A9^D_GiM87CIuTQ^Y@D z%*~Nc28Vv0=+uvVoH043Y};HL{?IR1(H)s7l?5`(;*5BZkdm_W8P@^-HPr-HyIy5)We zmC}5$`qpsRs(UN>*N}q)5`67W1u<_+fh)_qv>t;$Y30}2k>cUc4$7DfJo|zr^|^02 zBxD_v6y^4nO~e8pQoqisen3bWE5XlhBHm6p5fq(y_m&jryky~lS~qHi{Dj$E!lv2L z=Y%+C@))wU6`QfJu*vz|FKn70)yyFnj^J5F(i`!Yj#gVM*}rB@)cnb`1Ejyw~u4J zc`8tw9L&*Mp>vN??{%1@#ukaf7tJDZBmB|q_{wmn7aXag{q=f9RE?bAH1>mg>dP<)NenvB%bjXUJ z<^~dRF2?9q*j5T``R+vXxj4HO$6&%`af0mJy3QonZ1o-l__v+H$1m2+$4u8pt`Ak@`xR~G z3x2&+;Tu8eB(1tAZG_-!s*T$UU{1Ym%sG{Mo>LxJ_aSSWTP4KD*&g#;y8_{>^TP0)>Owx5<1bJ12*BxF4 zF5lq_Tj;+`Y6JfLNs1kCdU3rA2W%25^@e7=}~Y^*+nvkAPk+P?e=! z%QOW~W_IBulDQ%5iWjgxED~MhX|OqY8Nj}(dG*5T_$+jG&dtrPccFljbYH+Wu0jia z&DrdATkvNvF=QZT1~l)oZ1h{Bwp<5=!%)48j?@8gd_-Y< zj+D0z9Q?jl>U$gh%mf?Kd=suu`G7n3DSUrzitpfG1NCUs2Nkvq^a!s_An2*K9OVyQ zBas1(@d#Dx!|?qCh5u`{?%*^th+HqG$oCn23t!>8YLV0MMzHU(6M_#4C4p2S=uja+9^yjR!TcP-|27ESlmAFbDdK!Alc_Ne6avsd*u-Y2IvK|^a1=}j3hP=8to#ndW_Q=zrbowYLi|- zJd}DFkS-GRA?w{DQG_mjGy;pj5`uK)c-_Mji*-O?E&zeU&pG8dZg#8@s*+`g8;(D&Tl3!$ZH|M=w^= z{8JX$YYoH%5)$0i;s%BhLHxIce41!Y}DEj?Ta9BQ2Vj z(Vm6FqV2m(Sj;v}a|~m~vmD|XvKh3UPB}&_b1-%52&Yf|8zDm8D6Bk35k)o!(7aUS z!_B#ojrk@i6Lyl}y%f@96*%OK?%b7@2c^Icafc{uKTCnl3hl!Y#Y2clbZK@H{sUu2 zUIX!5FP)`Hh)Eht8#v@w^Ss0s$nRg;@T-mu#3Vfm{UhS(;%?~$#*Qf9@88L3Ww{CX zIwu%Ki$tA?Xj2yxc|)7_W}q$c3G+!k32>`fcG>FcL4i7dMD=PV11H0 zI*$TYan;uua?V3l5o@_C1T6{_aovZw>Ku`^7*)5Xkkf16!P*iprs=*Sy77wggIv*L z0@q4%CBe{FkDDbxA?6VwZh%c?Kyo9^6nbX2M2p1CPEi^C?PV)NgD$u103Pj6^RcGE zHLcD!ut5&OAp;YT0elwc!p*%ix%$MhuL(F@*%8E_LfuekfDUaw1E-RIaY%89E14)5ZBn{(Jps_!S;{=K?WWbV5T!feBwWM68f-Ed_x)(R^HZs0Zi&! z4cx^wbZ46CnbLrvo)c2xZiW(~CrUViqbjMQoyU=m{4)kaG_ipj@Acx|g(G!z)3=HfSl_9CC zP>j9*_EcbAgPL}r0LA4{bCiXoK@koH_fr@>M8n+`RuNBUC#bs0O{(4LmQ%#@6-7+j z#_|R(`e$CZ+!?e3c6w`7u5y0R7&E9b%&7NHgm^wY-D2u8$(mdOdsLUcN^NUml5lGH z1lVO*n*v1*gl_Cm6_9IQhqt|oyd$tCVTA3-&EA`xj(J2(uT{i#rDT%8cd>#q2Ia5D zLF>0MP2qUb&!B;OmXLo0lO(Qd3>>A0?zH8cuKn(deI$;)OKZzSJUgQdN_=A^cn?)_ z``{aU_XB9`?9+1OkD&j3)aQE15(XR_vF@7^Oth|oAQp}V;u$}$b!U5G5cx>`r?qTP zLI}En_&(~Hb530A>J12K-vEC=fWL@6L;wIl07*naRR7xt^-PZ3BdaV-6+tkjy(1=Z3^$q`J1FS94YLy4#ganua-|Ve&mEL5}NmT9$kDU5>qqH)#yKq zqU<|q=|F5(DB|Ow`%PNRuD=M1uH)A!;`frew!7*h*mr9J?#j=Jv5RD`s!1rYy*e_I zCK`U9t&G!!zej4TFE|9Sw;P1A|JT06qVWSUE}@KbaSea(u?U{d?0+|sgqLdr0pIZv z&aq)Ff1mIOx;W<#kBf+Rn z2Er-2^!a<#%_ZaxW;VWWt?$T!T}na_;0#XEcU9v$LZs&x9y0wp+rGxHoku1IFG6gm zF!G5IY2%m7qn6W3)KTDno7ERJqlfHp$UfP08(32o335jLUr&-SJIWf#vuRpu!{3cy zEXyK6PE-6S$F&wf#1MS>0yz|cNrrz-ToPd4FxvPf`#d;Ts}bj0$tP2!Ji#LhkUaxL zf0mL(aKAtjQoe$akK#+F!p4*4Om8#|)Nb+T-EIHO)9C^+a*vb7JHsU|3t#GGUF0YbgDm}Jc& zp}C}HTz(jKZZe&=wy=3MY^fG@g>UBQmTvf4RiW29w3uU!-PmVwjH~!??>i<;?7-I* zW2!;t;LM&e0%rWzkS$7qSmjOzCl-N+c0AR48xkf;?2i-(AGSxOoqANDM{%qr)h}>M zA%1#W(*a67f}0bFe@f6*sUX17kIg_y`xWzk+D}x*=KtfMU#PRoJCz)b!O1Bl`7ESB zt3&@pkD=U|0-KwmYVR$gbBA? z6XU2GFinapi}WAGA=a!2hOQhu9hfsvHSfKQ(MrZCo>k%Fts?Ned34^UlarMa{{ooR z5u@nb3FhKI;Hh(lKj4OU=q`-x3Lnq%BAfyE`7lJ$ealt@|3rQES~(=M6Xdp$SQ$I#v+qonr#r z1RQJQcwsMG-4l6OLgKb<5BU43+A_3fqpGe3O6>YDjUN6WkS$>NLZ9(~ z{1hbgMS=0LA=sffnz|%6W=qid4ltjC|NkH?d=q~~f=-tCfXOvsdN!)&KOMQ7qg)4) z4G~JpCEYRmh=YFC?!{w5PsijAIx7M4K2*92BKlBzD07R&kBcJ)@jhcYc`9;{^v}lP z@HVsTm^M3Nq*azCt4>M1Ig3{LRq7ZP=+gJmw_s9^6<}$h*bTU!Nw8*TmteIR_(5~M zJL*oT8>6m_n(`m%4(QRjgL6=S1)u+kZ6gIfOFu9_haazyI04F+0QV!*wic1Q;M;N% z-wZ|(w^8A?uZ3NTvtI?leVPKyP!6vX8SF2T!3RS@m)B|^(i<|t_UbyZPbXdE>Tp56 zMv%I3gM{{(^QHC_xW!X_Q`iVXQ|&jV7xXqhxJPcsVDfKqvn=BB27LJ+))Ftwew3Fx zo;LXS)UeVUn(zmf-o{#!3FqYU3Fhc_fPcx%vZ!rx`I3bPE-uZw$qPT3#b|^Crc>^@ zFdm;5p;rwXQo(k{{~!=@bdn%XBZz7egkTV#A+^uo8eQmNZ+XWXd9ZdAZ|{rkmvsHW+-f!sr{Oyq{Su31 zUS!8fI?My7d&CnlQyKnDYThbL0YR#bN!3Ft?g*sA9imI`$pvHwxrEBT_*@ovw~ugZ zetbDO=4q#hq{d#YSLVG=@E{pI@mP|jHP+Dh022o&%+$UYLE~GOSmcCWP9rTzPs4(I zMX7-R?vI*0fk*Q~-OV-JGZu@a{wFX&zM z)mK7IKEO@4?z?w2LZmL=(%3avSh-zoY2Lh6PWBrgCEKJ!cL}iuLy6SjZ7gmo$rc0L z$o2k8x=VCfxOT7YtKEhzx^YW-=j2>)(e3Kft{@M;LQr%Ql&DDN8=Q3i0zKR%TDT*I z7lX~@BRlv)=e0D?B-!p<0oxnfg09-FKI`EIi6qWOO!^kL4jNPw&SN(WB*89q&Z-BjK&+6m_WNnRv~ z6cqOn4Vu@xMg;vQ75k6&c_sn%gg}shCl^W3ZZ>H%L^!vY)q45oMcug8 z=++G?)_0u&e#@9n!g#H#TCR^=A3l9E!LQVRrko3tB}1~bZ>v&2mjD~(e;Hhl zcw}RfN=C*7NjE!zB6eA|w33=o5bRNsbl2$D?YV(uB1KDdm!^v4HwRn|4po@^0@0nl zP><#%=+I0XM8ft&{Rt{vfk--c0zJ)b@S{eAX$!D>pSMD{w zNRY>{^AOoY^O*?|JciwNxC1jGaY-sjw)T7k{a05N*myCjTi&H25rAQU9*6&gYiQ_~ z8K9p^$a?e(KKEw$9b&vPLWaqy)R(%z$7{M9&ALWJ56Di>B~ubl?L$*{Hg` zS>Sh{AwPg~jph~nqn~sPB;icW9NAcKie4~d>kRD{Gk^)&pPBd*Qd|I!d96P~IVS4# zWxnu)jzT_w`p+@1`rWx2?!5rDldrt6D}9lX=w1ll{slX4M0LxlKKvxevmVY(Lck#( zF|(Tc@_&Y}sjm$2^<@lk(L67Yx-RNdP`5>WG3u(QDdjdO(K8xnq5chZ4(jd5N7gG0 z;LKj=(<>ys3Gu8h#162Tk^$^LtI$p)EGhTxk5UPK`Z}@9Ov!8RIFUO#Dp)O*7rL5T z^6yEtGw4mj3}ENk5LH_Ku1$e}xbjlEXJ?`~#Qf@d0|ucPKMG1K4S1 zMRr1a_z&8A*~*djw0w+Qn=coSoIMc9n;HJTs~hVZMZs45Gl(&p!}x?|06WP(f*pk* z$7@3r@*3FI8h$A4hf3GvO`+eV==Ap~UH{?F`;2qN_OIBge(S=~k9D8y`Vi~K2+eqm zXBeLW88ACTVEZL)8o>370G~T_tCSy#_qxhVe*-CB6FB(uFyoUe61|WGN{hORp?*p{ zA--ZP`603te+Hc%X8=0{_vrB5DK3NS*@B&~gh*{b;pkE+(vWfz4phE(hpK-z09>Ds zxK<8JeT2e0N+m%<%4_35%l)LoEjDIo4;jds0l~g(L&TS;ZKYUS5)e2(9^)y-#V>RL z{y9QUg1u4VCt-lSPQgo;ZHF>spuZWw&a8Qn>+7VEfcFWC56U4DUIm}(WS)XodQZbB z91Sn9!^vUEPB37)$pCiH3xqqg>M|=hZxHf|KYUU?;OGV`aRL4mDYuxk05-*|^<$>t zJGqs1Iwu)-^KFUvVh{a%3OMZ<`o|0N=6&NCxm>pxdXD3-q5a{Z9(q7E(hBPSp_w*;jCjkAS$iU}rh1+}I!+GBD#ZApPKJ z5+mgVE@h$EO343pjn4yi$iR?+NCxo1J0kGm+b*JB84hr{L)TT5g#r-W=#mxvN3k8g zA_((1z=jNTmH~WF_wsy*U9sf6Kxc6bhKCFc8E7E`SQXq`t!bg4+ru|(!Texi$iR?+ zNyq>e1o~}>@1fp-dJXEqli>H@iYUpPJ;u_ zi9Rk@ZgezTa9r&26#W}CJOfsqf#Iu%JXazlcG#x^cuoNPH(=HcjB`WBa6(Q7?miq< zXpShjFuXFvcQXbl$6R?l#^-VagREW#hJ~VD{y6Q6IiVw)?et?^@j?M2@$2PcM*B97 zMSy-ie3gh_beHLF5zH{G%)qcvC=-?oj-7dBDHpzb|3iueZju&?3lwn?^lTyiSRrnJ z2{SM(6v9MFVEFKFAi))w-z%^hXs4GPi~sske>F!+#3}uy^QEN@3^-W^hJ`|wClLz& z`Ts2f&If5vYCfjm?h>jwqB&0LC>Egqm12RrN`W1qf(#4`g&;{yL9p|S-@*+aekAn+ zyj{-g-cmoYu-+%d0{3J zNQ9>x#=^H&*%36b0G%X&4Ui!N-DUtgwx&Ez>aBwG$QUQM#J}hrwMtbk*CiznLTI5-)Iq(7@C{s#cg&|RP3;`|87z;}H#;Q4@s zLOf;+Q2Nz&aWQ(@EetG=YQG5hJz9`FKKd5Wmwy{$NON7@I*Ezz(vQXD2b@ z=wUpUE-0UB2n5?X90w-@*NOqY-*7r@%i!NC0Uv*_@h8Aj8Pf0?EJ)}FghJ&qgB`Xr zI0M*2&I#=$#n@Wf6hUuM0dEOO;C~*JX)(G8^%JO~LwT*8I(Ya*Z{;#Rej07@S0b_t z{0mW~<<=BmLH4HT0qzZj{5xy8 zryE|i!cVv074guk=+rwR_}?kCF}xCvNffTkoW_V*5wL$_2g1UChKI}1jmy^1n3)+6 z{zn$@Iu&{D$7kP^G1b8{$&j9(20S0QQ)pq~fsO-%Mw^WI|zSQ>Rl z)U|m;TsrJT@f=Mu0`vP)#T*}0Csx>@OX@qIKA{fJpqnWJn22|va^*y=36LDX5pgmt z_kiy{1DHqg=fQXr$z=aA!|k^ z#SBZ{xlnonrB@oo(6&_QNdvyplcn3Eo`BkiavYqXMWi=(|H2p15k<vvG9+M5}u6u7m2Su!kh(PHp-n3DIaW09x{8rl+VU# za%}4j?S?a;nV14Aexnlb8$|eD)Nptedib+3>h%%7CT;kiaCrSnunh_#2~vMmC0D^2 zx^uK*vcd2MYBvMO{=JnMhzrDTat77AJak`oeQBZ(+jP`$kjIDVD&C*sZX%zC6Z~{F zf-6ZcDFV@@99c+ad>OVaWB?QKhR|dL#&(pt2M+q)|6|m$)S=9q z_W>lKu|)&i2clkqdI{>QrTc`9gC4yHL|tr-NohAW5p5&@GxP}TERATTvrha%QT%sVH6>Np z*?y6tm!bn(2h-jS-P2R_2c1d=&ZB&yyty*cpaAx6NTlBl`|5uabvsv^$ipBmYnZ^N zLH-wREF^34P!K**evd_ceaMGlEK3GHhq?TJS(rQ|n9r3kl=2eaAH%oZJ+y%}pMkeV z1~8HIT6l4(VTx6S;rEG+=LJ3nI{LtF&pOt!5Ps0l38Z|mpq8b)DtE~6>K3hMxqTS; zGG+jid9rXqKbFfZ>}@2pnG1Fsh~A5ua(Osc*kT^|xd`e9QR$wPHp`k~CnG>OeUZ}f ziI|&6*!>#D1ki7P=A6{aBa?c6jtszt?@qsn`J~}vptW2Mzq{r@9P|*?_fgv@bfu*B z`8aUALg8%EEB?X1R@ZaWOZ!L+J*w=M**TmA>6cyNqJLH<{$o7+ImMsI;cK5ckSw}g z{qs4K=HaTHOAoIrR=xBF%Jff?D;xBA-dghwnTdTxsQq7nf`J|STCgW-mTT|eSqZht zLjP$e{?c{Ij)b`BE6RyYCKudEKfqk2>NfS4Gd1fTmq&JOgeCRb6$yqg$ATzvF zp8|nXXB)>dZ|??Q(&1{K@{`jSf%ZD+uVB96Cqj7S#z667wJC;GZZ|A^`ox}BW%o2JU* zeOx3c*yR7lO=XIBF&R(B=5GQU&qiYDJFlvMpU!Kjev_0jum)_?TePzl_(nVQ&8V}o z5>FP{V{rHJ$S>s~Ybo+eU)}1IW#HRA5(3z}0Jvwyu;A zmN2RU-ld^%w@PUoJQsEwc~A|$T?SLbgJDzoz6!Z+;eguN3i zu)q^2FDM@x7uWA$9_cH@i8Yw+fnU;Jj-%fJ;r8Q;;YaTm3Cd9;M-)gPU6Oh!>Ri+x zAQ{Q$5};3CMOMOQU(^RtzXm?_xdm|0qWCCkYI!N_o|LNW(}Q2vVJzF5y?k~8a#}dA zKs85i+zw4YhwvoS?29BgrKOQe&&dB<;lS6WPB6Gx*e^u;6>O~!{XJ0WpWso@<8sZI z2#df=Z=ioR>TGbH5=Qr66b^5T$`v|EwNY0t!Ztm}P^WB`+jls#MjeNgy7vM94b)xUo3l^N&1!Um4TwY#a{n-(^+Hs@6=j> zy}FA;_FIwR(`)RcG|)a9oG)rE$(AA5eIaU7?~X93+RrkXr3vB{4SC8oixWZ;_~(1Y zqwP9fG3#HkJruO>0H&40Sb;AgNcP)~VT>NmYNC7;q@Da{3+;{Y>Ch&E1?R^?c2mZ{ zNzaO;7P?Z?Xn|vgD4jc`QHQkTaDHuN00w?78jW2B1h=^Z(AX1iwKqp8xh$43hnCkryqNDwV&RgXu$L9_hPSyDdhL7a(2Y&2YH$l04$;MMR zphEvOIUEAl=BfVVua*haYt=gNiS8N&SOAu^Y!ER68Rle~HFHq5nXD|R%-4`T|9B>#-8o&Vfs*IDVU^OzhL#_nhuGsX)`wHPPgsY?`2fn1E<6*(ati+Q%^j7R%=U&R|Px;o+IU- z2{@!B=?Jl@+`ymIA5|8g3xth#Pwfuk*0xQ>+$t}^r4RCD!m!_=bq>5Km)d4)?MU(P z=jFm!ZP@iv{+WbBg67ys61LymRE}W(3ZV}+Om&oKD@NL{YAVi7c@Z@I0PT%|;E&Kc z2(H%!_`E|}I~u&#sDD8HkekMzNyj2>bnCyWG#RtXkty(28lR@r*w%p>u8GAWbb532 zPf_W_3zZX6f`MM@SB`~J>`8RsllsJ$gmX zz8c$?&-DEuDSjl*EHp(fMVrl&j0u(C0X@f}DcOH)M(FB9!I01$HAw}QUP;hc0snzY ze+Yg{V-5|(dwQi8r=0H*ylI~X{vrd&_6Z3Sv{KUv zgirJ)X=zcN32)l>N#RFwHP1lY-*jB?XL;#_Te!oU_G`xTBiRdD370mHYa?+|X9^s> zzHBJU3?O%^w^1qSli={_d&;>dxa!1al4ETvQBbJ%%_iSLe^%RmkUiK{KW*5SpYTmw z+VW{S+7TytJ}}$!OrcyVeIj^kud9Qt4N?D0Mo}I`{ctFjq%n}vtIa~?O-aNFN^oL{ zkRzV4w%(-mT#tQDT<1Ztgv?DZ6(lrtFOHk^6c%aEu>W*P-4cpQ8Z}C5|w)3so z7mB&0A18i5Gq12g559d-t=eI*(FlD)LNQ3{OVu&9ZC z?jX2OfP^L^*VC5TBLlh)Oy^KEXN7Nv&wal&dU%2`w)e`$|0RQUgTj7zJuGXEDxO&E z?`=9PK8gu06yz}iz66y%us^98L5lt_ls4B>;=6$NdI#?!A&EAxkm}(B*wy7|?GJN* zQW(?kg*YGVJ@lDINqSSbk916qq|@Wwx1*}c7>Tf>GB9u6Tp?|C82r>c81&QZ4$MG8 z#&~k*akGkWY{#G8j zSB#*v4^8FzisbbvFhD=@BQ2t{%u=!$jML;%Ge5agy0eB5`+f9%75M1g3C?o`ymU*# z^XapSvLkBB)s>MM^+I7g2g4sjr3GU-)C=q}tGz8CzA+0{Y5t`m2?${0%D`~bLz+j} zH9L6Ieor#LCXbyh6xc6MS0?#d2_C%90q$52_J1)>h3;QE&4W>iYb_MU5}dgUbt_a_ zG&Vq`2XW{p-l&{oaMCSSRpQZ<*K5EHU^P3UW(RM;)oDYi$)jc=Zz4gOr!~bV81dQK zhdy9%m==v!qb@;x6wxKmCIW4h6AQ&5sN&M9bBr-Ks`(M(w=)!jNSOiT{MF(eWZt}e zmGs%+3SSAjdv*tE5@tD~sObZzegr4<$j8 z!A8u^=;2;{kYY1|{q#REj5B_K)9Y;f=l(Nx`HMStvB~(^wktkL^(nIX-{e zY49mn*myeXi&5q8&jk2ssJ?O^29842K5H-b-)Gn(KTJ&AFcAJN?(vZm|FU6sW&}MF z`)w|{9$C((pljt9{vGY{krO{u%b2AMa(a~gm8d6kh6-8yy)gi85FiK*{R)FyTRtT> zLq^=OWFrkJy8Z?Fsyj{_a(Cisk>67TId+FM=QA434IERwNj}vX*m(=;U))4U`kc-3 z%rOyg0Htgd99|_I=D|F@*oN+57ZunkeHSS-3{vFpKDfSQ!|qIbdgOZ!f?P)u=mhU8 z6yCz{UwpD0d7&Hn{#TNh0Ok*{Irfao=o|&ebDfF51zf2g;7`SbX+g0c_nxg3RsY+8lkTVPFpo{J|cY`XkD!?e9#=x zJOwuXuC>u5UgJM}PhCu#3}K?UCpq8n{Uu2DucQf=?k}30#B94Z%~g*FVv36K##ed- z(W^y5k(&WJWPn}um05R$oqo6tc2!ajxufA<;~05`(Lh z*k_-eGG9IDdlOxPp|1dUNt_B`_6>~rhQxP(!q0PjBpu7oQrK_&jyr`flL*!1@9aJX zi2e9`3cp@1#A+Wrb7@b8UyHgz>X!=zb!f3bT@IDL6VcslhoN4BDlJz+^%yC5n&C7% zq;%q^S&FiSqsgCUUa~pZ1ra`b+7p`R!p}FO(kt_*(AAjw1&1>9E7Ekw*B_a~n*CEO zfQN1^l@>ae(#wJXG;yfz`R`@G9Xf?v-znW;fLpplSA(V%F=%cbpx?uB?^>ldfuDf- z!k|Na9)$C2qDsq;dmf844%Ni>Ip!{W6DJwKF8q_)gnJh%Vp&Sc+XQaxt49+C1f0(m zU<~AkrZH@X3`~Ozd|wfRGKVi{(NP;uzh>%&NzFU0b5MLe1Xa;EGK(KwOcJrz0rQDH|HoEdzaDBqk}}oh}quO*KadmrYV)CB7p5)g`zA zGd}~!*K~ZB$Gwv*&aMpzaj;*J3ZfOPn zJ_WXG=mk;-u()n4#m;0L^0bm7esTU4oJ~PB3x)WIBD1sW z8}VTJk*=Z$>1GACYv^JM2jV{>T#(_P_E!|VA?Q8ex_m+Wxe}~IHpuR!N;eQyP>t#qbB0}f;I9WtL zDR?C6OHd_eS7`@73w0mpr=CBUt_y|cdiR~k;ZWik&>Veg@*lU{EP{TVTUt~L1wNPb zZdQ7i>mJx1gi0^WmJ~X8_z?6@H{f!`fsoD@>|azf-t<;8`E=6n?@c?DiC=Sq@|H|C zr#p@2>x3r%UFS`6OTn!v&f>FuJoKn07dl7LWf|S|C3HZ0=~YPE2uyQ=l2-kp#517D zljaIZ+;X#sH5K%o9esAaP~5Ia(z*(4*HFzJr<#*=UB}g>eNCRG>q3$G6~Fepb-hq% z0-vNK3eApsX6;#=83c4bOj;)CtH);2pn%gHRVirW&`uYM;$%zQ%lU{cq`)5F#5*c- zpt+RVgV4Hh0eR9~9n#!$(M>>8R-ZD}47ZR2&3#8z&#Kr4)j|LFT3F3g}&C~pr zW{;w5*A?XR`HGy@daj|Z$Q1F2E}?>NR}H6yeHd-|yK@0P%~DQn{#%=9jUg>}7kI?8 zk0PeoUHCX@Hj&SZ6ghpvB*dqPN4ijGD1F!$aJei0`$LOXl=pKWtxS6p5qT`Nq2-qH z=ENZ!dLM%L{Rxv0Q_lRPaB21t@Gp*>svgNs@u`ju;-NQNJt*af?IYl$yMZ+iS%yq6 z4|`(|pxGxgvn&!J>w&S;17l-DNXSda1U>8^$*Pl?h^g+2gL;^Sd@dnBFW0d3eUT_) zd7C1pqXpPH7ZhB2e!;;+Y=)YxxK?9*7~Wc8{EsodK8z!t`xP;XkEr?(TiZTp@(65a z4^CLJ!aw$ISgegP$o_Eo=vs7Xtl2nZ1P%X2GI zoi1>imwO z9u!sVqlKc-&>a4AM&1lZpTrFaW$zT?2&O$8RZwSzZl1t)U-2PHP@Ntsh<_nOBED*5 zMZJ;L?sM}~3g>oJV9n9?Ng5pn8~%Ea3Az_mQZ57N{ixaAb_}k?B!&%!39gqS`1>#8 zvvRvaF9T}WDdcErWu6Q?>BX}Rhr`kvhlSf(U$bH3si|oykZZ3nVbUQ${y>PlY^e8OTL!sC=V*p94h@tH%Pd$D4=+{41k= z0QCyX)@^97--NyFoN)93%kfzAnCuQTM2JA%9t$Qg{<((S>J=^GKQxeo*wCkY6->Yx z1ae|57;F5d0M*PLLV~ujk`!%DQl=0Lt=OsM+)0X6>noB{=h1f6pFi3M@f5mBA}ZZ*Vxv&2@PFo>Iekb7yVPko!)I;(mmW+dbDsCId81tb&f zCWDPo>nO0jfnrCv3(nNaKN6jC_hM%`fWLHwqRt|*@FXr0MZ(341n@f)I?)YsYQIfw zF8Z&IDs=&XV>_bKZO6Wn^a2qdnMeMWE@IDR6EV>Qr%!Yw;?@&5e!nIC7akWxe)_9rLMj!A9P4mX?P$qi$ z9tJqPf5>UcSRdvo)d$4)dP$5HX33Z>U}JCEw&=#1^t?xN@16nq568@0+9fIF@= zFwv7~uzMT8 zuQ3WWw&FMXST^2lwWCe=`iv;3Ux3_a@2~DxcnjouR^fkp7MI8!?2kK%fK#B|r<%dm zQo&K#;PLP;&vQf|N7EH{|NC+eAI}WY1^x{eg{E@!0z;Zp<{Do}) z?++>%4Kpb99ICS!^;D7QDeTx0#TTW{$8fl;^{W`hGyYePoDPP{$f^kKSHVi;aKZc1{HEiaMNW*s;wo#!+Y;@~!Q~&*M zK}@SwjP_7~JZL{V3nDhL4(K05*rKC>SbAVL`gv(%g+2v-BrOsYV39o4+l!FIUS0u# zUwfg_&Y)Q<3(LmUHBYdf+=yRf%13^cV!kngL&29>Wj8c0oY__wE$;@VbYDhOlK$sHsAf6*1kXZRH@eT>ln3y=&LzUNpnrxoehXjciPfnfA}!dXuRLv+ zUM?63Nl5;O4O`oyhHiL_x%0Eg)W(Nl;s3>~IOFtd=dX-2>k;5p{h$u;N9nEP)qoE_ zMXghAG#=F)fS*&6<>4Bb!E&?i;;F&)h<(oN>#Tgq7I8IUXmcHKuPB(BWL zWn6O2_LwZj0wjodB91EHC%yOa7Rd|=Fy(hgVAmGlLlDi$vcOD?55eG%LPjHF<%zTi zPCEQ3fU5fg#-pj%gKavQt}WT$MGFV$X2r_|j^usx0S3=zjQ$6*R$q?}d)G03ghb_k z6xLNqcb& zjlUiN{_NxNNpGR7JI;!@wP=oh%X*6>QUo>#9UILL-Xx&1XFNm7YVu=*y^GWdvj3Li$um8 zwM#XcX5F7ZYdr)#y`%DvIx|_&(T8?mg??vcQp?eyxj;}$q0&k5Hp>MtmVCk&y60=1 z4dq}M%aj33%8RuV1N^fk=7BpVfjfuFwOIIjOvG(Qsy~Rd~}oFrtq1z-jd=UINANsYorGQO@7aghKD56?~N`N1@Zv39&C+G zI{HsXr4w8CqIR`NP;{@RKiY!*?eWkd-}_!3gs&-!#10(>MqfqfGB;g4*`D(Q@|3rW zEzWU;WU#YrXuOTF))xu{y*TQvsB}a?CsxdjR99;P#*Rm4$h8le(Rqi@pgys%e-Sw9 zyfR+natJGZytu-FJkX6s*H#AlBe(`Wsu%Ub{p7r444?k{n>%C6TeGqM(3P*%ly>L@ z<^vKP@b6ChC>7x8g)^ocB+<`}Y3&dQQPPbi|3+Om6a*5f@`837m zL6Ydcj^BzEng#v~^!uUGjWo0fzgTJxc~ZsA@xtVVh23v(<1NV!Bp*;}EfPv!zc}CI zDCcxkb(T`UY52MDFSQCUaG(N!P1^#{t=nqOX;KToK?>xXJDXK2K3a?S{dAW=XOP(&pt1`q`me^C%YB}tBwL2`7-Ip?rTX33cq7X06{&g{-N--PP! zx*cZjeV#L+yXuBh)!o(ARnPUh>Kh(t$UqcHYCD(oQ6fW0R%cP6+ksf}g9!foBGj3zwt6XlC}*U5B5T~} zuowmUc3Qvi=hq41@09fSX?-xsho|#&@-}eaZLypSwAU`#D0a*h(U+;(8EUb;+as}9 zZk1XOyiC%9n|7Pjc^pMBFf)j9p~>nHek|24;3V6#`Vlohj<1r$`KGi_@jvJuGt_DH zP1s~3$=_7B7@d4eU_8x8zfPtrxevbn7|NMNfY_cGBwhQY(Pj08L=lv3*Qhw@??wB&7$X9)vENmfF-HH)pP=7pm@8wv07`=}UkV&jx9cDn7>tZ0{_8K9I} z%^OKI-T++_bu0BQ`(Mk#M;F}#c4x6u)w}};=>8}3BXvxS=x(NCir|Hg(QMd#El3M}cSR8NaA@>l{xUr!TXRrA10qDPWh!&FKjemVK&BcTg>H@W&njysEg%ezSy?O8a8mtMP7fy!hVnwXL(;}d-Y+Mx z(=O@kq4rU5d^;r#+wTh1S5&&p&9~T&L!NqULuY|L$D`%>)A)cLH5)%lleZzyzp=k& z!~d>7RXMsQ8kb-;^!LSR%_O|QNve8_jekLH@ERfGiebR7=`jE9fGr*VB#7%Z^tPQY z-@!yKyHYiwtvrKNHRnQ45^`g{w7yU%8u*ps_JxOkv9!VQtmGZ&g*msZy z_#HI8zflkR#|NX?mh~htS(1}PqYnYU^}f*H>F5Faq9!TLi2{+I?5fpU z3Msrr0gu0hiBu;E^6eFiMG8e@{4dL>PnA>C)Q{|vs#$`=+6;!LJ#y-mTa*v`kM zbY1_p(^KW`1pP$Uz#9^DiX0us#Zy8AdQ^CR}|&b5M^qO$GnNP0Uuy-S|DAg`wJ!Bna{sR$fW`3`rX+ zcJ$nWy;VYN2By)g77~?9h+h0uKU3P}@fO3U$3yH`r75zHBF#zSMF=xLNr-G!7N7(3 z@<`;bpo0U^39>E&P8{`(?Y_zTX1je=+D;s2CG>aDybg3+1$02iI!XLn<&8u?NhntI zzQdRLu+qpbX)^Uh9u;yz(Ul{yU}F(*4N%kcPOw2zCFGHg*m5ljHBl|;P~yFl`d_B> z#5-?NA{+fD@4u4f4@j>^^N9qV8r^#VcoRGXb_!KM+N5QENlfVCR{#J&07*naRH*Kr zO9xqFUR2C?h#a4W02Fsxf-ccprO~B>I%HURNIZ>c(%f4|U8*k)w`ub<1|IlZD`XD^ zddX01QF$i5og+^tU*-+r1|5wr9_|)bl#bO9ze<+|W;W}_PHq2p(>NcZJEh(vD**36 z5Wg^mxREMN8sCe~L!g}|`L*IfS6+*gvuy2}h7apH@ynlZ}QoE~6sz+4l)9T*Al7)GUWLg<1*va+@pUdKZUU_l zHu3bd?sn-5G8LXAoY4Y9&5=mNHjrlNmdm^K86F=JM zOWA%C>Yw6q)IAv5W2lz!l(kN%DEx1Pnm#IUunlFwrq7hO@4omDu-& z423>pZ$}LN>EvIu3>xg#&fjj^2_((3c^&8dbhGLEBQih%{xoH6{820TNkCK zH3qaGNm6;AK`>^I8SzU4${Gh(CG{_6dNsYT0@r~@iF;&L<-|7=Iu-|OgAKv*pbWA; z@m*`>2yy=&-3O%5e;F>DgHngyyA8uP3cekV)lieB3^1rZS|j`iUada9av1_qeHCy5inlhC=T#A6B6_ zZ_7I-%JW%l&X>Y&A^xWDb3m5d510YgGyI{T{y=uEUX)ZOq+)%ZG*hhf_^ru7Z-L5k zAB&5OdS;{?3!VEyS!%6`&;^LbhKt{oEBo=sdSAUCX-*PDi#$n)V(h;I#Jg^N{5iQu z2^ZbMX-PUsp(hEsj1O87Emf;l`Ku&VK2ap)c?k+O(KKJK7%ziHc_*pScIoj&{UkdA zU0vn^g|%|p`B;+eIuPd*Psmmv^VEL|wE6wGDr0quCl>tai({zDK_;0fwgm;6Xke0R z4z*^srkbN=>7rjj@J-X_H3eDak*dNr`PmD9w-6sX5W(P1zjXCTBxuouudb3vX@tZ$G!-braOkewBuH>H zX{U}rPml_1ogLuYeL>1vBtrLMUG!hsBAai@g8>R=GVo|q0crN={AuiyFLXrVq-pfW z%7dQ^fd2zkl0V>V^X*(LO1kR7_NYLzQjf7gzb-V7H`&p2`LA?!&=XXH0SYt8ipkOD z5X52!|24Vpm*7KCr09S=1gMj?G=e{&%MXkwjngG@q;k)5EqS9Ny@vjoLu}B&RvGSy zORqef9V`sAPUm`HHIP)xf7%v zkd(?g3vk{CuoC_U?$oK9>Tx6o{%9<{9B6Gi?93RL)|2%E15}7PL8v^FloJ$xsg3fV zC)L%D>ETY(yIZYQnRsP(^dwm~q*BWb_G8`1HD)SLr`5XIJwOt*2FSU~fZT)s+?8vv z6*C51Qw*kT;FhEzk^7N>8an=4AgO*&--8TLMHcN?O$P3~GbsfFv$y@1rDHLvOO;9w zV<7|1Zb}+d+maZ(BlD2)q`rCj5;8!&2wsdgsr%?YeQ>>Nxy75fEy#tbuC0kWn=P_; z+(f<`>v;pd)d}j-&kO`ql6sQMlJZo~81kJ|cR!?uw{1eWtEEXiPa}cu&HI7xPBA9B z-|nQS*Z0w5zFCqOsf3FqNuMMwx-~GY@jhE4|MpL!!#XYgs5S5yXq0^u+6{d|A+>)? zs9VX;4a}o8L|porfyP?g;rEG2IYL+PEe&Ze4b@NDA9nCF`pni)zZ%ow->*CPnCPCr zgPvBqCTjE}jcl9m-2kE&;G_nlOyr|(e)s34u@0IZiZZ1nxOU8QTaJyd@e zKO0qRxOO5TvnDgG0JLCnY9W8fQwoy(ch(Riq+3RbLnTCKa~gDa@_E_j^!~q(8KAPX zdJEK7(@+vxscY$iJK+-OJu=j9bk5aAujaiZmNvRtZ9X|vd8^DFwyhGXw=o_1TD{tG z^~N;*+ZhQR_vMB#5k^rBO-c9al3jcGb68@Mz07Kv=< z4$Ru|pBB7LEofdDc;{tm20ddC15~n`I#%O>J4Xa5B@x-Wjqq&L95jHdF++#nuY~%j zbRF~z+7+sojEUaR6{^?MIRk|;Fz9ILykVYDM^Q7Zv#N1>Lv)gQ)p0pG{|eDpPlKkX zJ8K)ax1J~Dn_Qjx5ymO~->*YMbb6X_27DYvI9FX$Qb&WHUepyaHe*Encffa0DS>{AN$2%C0a+nQozM`L0@F~LUk^;Gm&XJ@?FiLbOLuj`^ih)&SCXeC!6%BE zlTQRX`&eK)PZr34pC|%}N|5aRfV9H{(u_?)6MciRf4cujaz*d1%{E2QSc(Q0mTUOk z>F2tgcKW{L4ETv6IcFVna7CS_V*+-PX1;D|n)WBT@}Ad}w}`(VS{Q}5kI~!hmQ8OA zf7QZ%KkM`pg+b|4QMDFnt5(AkwS7sgZXKEd{fXvMgz8P0?$prqw3em_O{;Xor(3qK zx5@KO_HW;2pKo>s%F6%;!cdUtX-IQ4ril4o4&Ju=n|35w)VL|@m=?xMgEsnx z=nVL+M|4U}6do6-b~Yy2UExi;C<5FQ5vU*3|Sz+ zmtO>=@gyZ+z)ut(XHmXJ2Lrz$&F?zw_g&6_ zGmw@6?){ep7X!VR`DBo4rX%@+S07L7Yds&fz6mr}RgIs1`VQ0rs#{$ybL7LoePOv#45NDm< z%ERsfqB02?Gi+BmT(dLa3^)VMfHTmI0WMa{g7*hp!jk{Fnk;4w3v>q$$xYz;-@9=W zYrnVw;wX!#jQkaFu?ofYI0MdrGvExwV}J|PURkbiO?ltr{|xcG8>b1qiQbFbA61wFN02^x~s=hiC%Uyz?lDW2AlzBz!_-G04LWCL6Xt@Bp)jp zfY)h(-_}MGZpFrRV=cz}@q9uzx+cf9gX6h3R+IUAYq0eESZncqT-TMbj0tdcDezWG zmp>riMj2i3?9M}I; z_`P<5^gWrh#(~A-AB!>@TL$=j4uACGzUjwqO!hjE?46Wm@wcC3KLpgX$%H9AA1iB^{W>9b_P+OUMsWcs_}Vmlx`havFbsp*8xWM!__$hEgA3zMN3+IV@VkJ%*c-; zI5As|>_5rC=LyjHO#{7EQK{I)L2R)ot0B}aEtvI}*v{7UnJsu`Qem$ZDYHDfs+G zREJ%eGZ2vhZ%{-e(^Z);urpfKu!t?wqVQj_mDcoG4D?%xi`62L{2d)hPoo->-lSU0 zD>WL5^xLA0N z2dB^8HmB9aD%LoHf4B8K{SFJA@+MZy&5=bfBkIzD7+JsBP^ABBaV%(zj*Bx;S_Zs9 zQQD$$$Lb7lBGn^=-Ru7&fB%XL!8$Q@;_sX2v*`VpHHM$~cMEzBjiIZi;}yOw9!p4l zl$dLN*1s;Rl~MhF=5OlInkb3MX`@fy#@{C!H~4R7z!`7`D#rjP%IUz0U}a$PvZ_#0 zuzxDBkWWymMDX6Y@fjwe#CbYrz!?~#5$dahZp&JeWXvnNV^8VqSOnM{4?HX5 z269(N<0*FH<98$axn~L&g0kSF7SGZk)lkvW(7DYz!PcIkjs>LqZV)L65@GX>0J~|D zJe9zWC`oa0GoY1ayNS*bt4A^FN}K^_ptl&{)@ z*mOkfIB;ra@K^@t9w+b6*nV}=hdnji)W}!?sDZf%DD=G&*dGeSMOslA%-kvNH2ctb zcv^?LpY!PdG!$8u89Ipa&YIO#^50cW863~)mDPSUeTi}Xk46)Cp2X<aV^eGctr2~-5kiUf2+L82_KKl;AcIn z&p^qmz}${AP*w&w8|aQdmYk4RoH%@RET^0FY?D_EZl~G|P;b7`RCi+i&9iZSLM*4z zGe@;c)V+5GoPkUXa1z)h;t55ntQMjg6eqUskLXMd64;d^x(YJj4T=gDnw86(bY@4lPI$53!l{#uPC7dIxHtpOK#mM>Tj9eF<3qn37iFd3KS~htG4OUmQeryDZjs<-0OMy>te+KWvy}(|2l?aiFz#;rVMoq=OVio3IWgc3ikygUHp78(AlnXY-k#$ByX0Ao14pwdqD$?>B;AWfQmzY&8WetE zNkAy&pkq~o>+~3EF0cex5iAdMR~GZafx1FP4HCWm^*(SfcnqlP{$1*g5A21AZc?i+ zYEY>07(*UM$rA9N%Z&j3FNM9^K-QPi-H6X?#~{FUbZ5XD6x}(Bo`QqrcPRZ?WW_q* zSLNW*^UbJIJ2~Br(&Zv3J_jFTuh194tzuNb?F3lXKv*@{RtH}L-fasB2}Kv5OTaBa zul;^IuZthHN-5N>vvF+O2+pZdw*q{c-vr>Z8phWF9SgDKVSHBu#l@HbZ%`N$+^n7h zM%~DogI@1SZcdW*|G!YM1qaaQSrs+s$M+lAwr2D81pi+m?K~E~CGa7)r0}KVOOFv2 z0ULmCgZY3=E&f{O>neUhWx=<@pms09}}D* zS;GB@yqU(q1bHsbBNn&e4CKxL2f+;q4umX8wIuG=76GDH z7tn6Y3~S`I?m8+j#G!`6{NR`1L*UXs4Cp--KLm4v$~H9ceJ`M6vXkhT-Z+l~7CSno zF6rb<#C=vhA9+w!85@;7I4Z+%3r9If^qf##u5-88ZLvx7#n+(A?*R+ty`+<}(J?VI z*cluIvJMJEg-eez@G5Z~2rdNg_44DB*yYD@rm-Do$JX0MpC13}QL7%gx)?Ix4GKeY zyQ$`&+K)7U?3OO#el=oN;lO$$qRz^yf`5%;Ssd&SzFFBo-0`w8a4Zh#dHplq$QW2O z9CNd<+Q{G-Jel}+0eQ*4F|;0h=eBM}UV)X> zjyEVuQZgKDn*DJTh%q%YB&sh+q~3}eZXxa7!y)zrltL+A}tRQ?aa@i<7wo1}iOsDEplE)rU2LjzZvzt!V56sVkLsD0Oe&&2;} zflFrwH1+%U9G|-5uAFd;{s^blLzsu$j}a~Gr~2zs5Ce@Thk{&ivz-{=p!^~Gb>Xy< zA8-&JZKXVxUU<+2OXDAY5ld&q^yoSKbKvo2P<~n{t*3VF!rLL&4 zQ97Yq-oPm}46Q_sEA@i7l!O6qP?V$~Lfqg0)m{1x;L9QDyQCSx{-rn|Kj@M!x8202 z=f{5sz4opT&8E2>Tmh~G50&*IfNwn~)GIxjSrKehgBl;bcJ9-7AuTUmnl68MKM9|9 z1+hgvA1e~;JFykJK4%~b162OG!0*80Kr2kvMXMreWy_s_7Nja%@MA`B7f2(DXYIm+ zzybWwN_k6zS3obw(*$uCSPt~s1*;5ICb|!l)A(Qwa5Q)s^n%<=5OYQ+E1^Psma{c#Y%Bpz03$%7yv3i3!A8K3Z_`q!pmHk3q~JP`L^LXUpR$CDFN=e}f_7`+ z%iqhv7NGEhKt2F1+dT?YRi4N3--4yfQV-mZ_zY0KD}rM{yJL%8rI&Z{aCK0~u`j#e zW{_1*k6*&$G~(QX;K_te>gG(3*j)OZ0V;yl=Fcjpqo5SM7G*9^IMPXFXHZ4C9jA8( zdK}}@=L}E}W&l3`4}hx4$2hzO$h~oa%~?U3hQ-=Z9SR z!>8~M$WnV+E8DWDgY>2bn+;3Tjq(6|>fLI3{X3lK|QK#{NOWL9D&RZO8z1!7jD z#tQi=f0ij}=;m$_yBZOz0G+JLF8{$nJttkzoESIIcMMRkRst7-#_?GEEv0A-)4aW2 zNW`cy9cLPrz|VS}LyxbC0V>m4h83!=S{JKtG@0(%zr;Enc&HwHNxyXmbTF8{XA8mu zD=h=myIH{D;3H6GxfbU%o2+Mqc+`V*PY$GC)H9@cAYlwpspia~Vl|qm+$xkIOcLM( z;7^T#mh88li~a^o8xoJFaR%~afOkL7z+ z^;EX9WFedi_7C!ZD~pa4d9?4d6Mx|R!4ZjML z+Hv(q9N3^RC)yiU*=gMem1XG#F1N)=oeT0DD5?59D;%lr_pS70gF>ZErBnCR76p|2 zhcx= zJOCbSz+;qg-@JmlcD(II{D**Oa_A0#3BxR$ois zHYil;RKOMZx)BtywDaLqz@NyEvI_jng>MgmX-eed<@mBE-04oYCk5W;A+XgNut-k^ znk}d&$$m4qMc>qi=d!6QZ*J;?8jD&9Q%j1MMV`Wu72v(_CF0>njcYAgKUD$b9192E zEx>LmP4;zzqFy4k3V9X(^Il!<5Gv!rbwA4T4IgXa%ME4m2R|+Z--D}>CGshgD{!nw z4I6@xZfyAud z8kYtJyg|`G29r?iQ@6A^?LP-Qd&7;M!&g?| zRbvv=XxI^K4Dx)gi#eAD21fH+Hx6fjOQ>6;8unH0Cv{7WP#v#&JW>YH7!W;z{BK^) zz`>>1+AJq~8YA=#;?p(4r3C}tplCq~l~iK}{tmv=Vt4FK8mM`GY^9<4h;@9@o(6UZ z&10DERCMnHAMY62FjEbeYAkFA_5(|r8FIz38PK?_Rr}3I~NhiyiD*=PhtJFDZTmz72{Phtt_X-4De3}Tc-iKnVbC}M{o8fa6a%dyY6N z*D#=q@I2s&2mxxaSZ<984!oh@L;QXX6xEnG8ru^S_srlXewSL{YeKL$cpK=s@FTz* z6QwRSGv{;b$nk%Ce0p-4fRvT$Hb&euP|Ci zO?Ui0(B1iTz`QY`0}R}X&5uFejS02x4-hxV!l2ZR33!?wTmp3WrpA{yCLqBjn1QuP z`Jn0#avhi@IA;L~IUb(?i(*>67Mhunx6Fyb58&xh5T%!gct!&a1l9TYOW^7bL8(Er zH<*;=KM!82;bqF}BYsB}_?;4kbJQ?9-}8V4 zz=E~!p?vqUsBxJESE0(`v~n_IzCyBo3sT*}8JylXbt_rMOI z-Q%Ep*mp8Gp$c^gKg%Z&{Y{Ye#W|zN`wuX8`69FNh*dJr|SpHo8W#{YPLDvp{lCjQ_KNFF@Y%Hw;!{ z{0)BoDsOU9*i)TX@6tj!RGXeP0e|y@gTYgv>~a(imi}%WA14Rb7C@$ER#mPMjn9(+ zU0Y(`6r*yGJlC@abBw^CYn4Hi<+I^w%&42S^ar?j#?SFV5qA%J#VBWM9W{P*XJ1B9 zck<34%3w5WE~~B|o+kp^gL^?49_U@pug5l?vz=wH|(#6IF?4P&MH~(F31}LvNz?ogjHILmIaJOc; z*&62^zUt9uo-!O`n)O$RV7sV6@9jALeIZ0t%_!^@HOR1C!D)pzEo7CuU{_sg8q|}g zT!*pBj4#30i}NI>$<|x^-wRZFhDGibyQBswN8N#c8)%$WQSxsLS7nUSWcZr*3svdQIb-;EUEul(-Zd$V04c0Ka8!)%!I+$#X#P@HY$$y z!8TdT*YlU30m^wZFlOm>zVnpNFt$?p8Ty}x_^JW1c??9Xmw}GKTyFBPb6MSJ!QZ+T zexoXNqSSsu6+({PzM)F+%1s29JmVP zCD+7_ptUxFnH1z%fwybzNqM)z&pCM&I(A+IOP7}o_bhJ)s1F*{`69?muFX5fto9%# z&l@7murPb%i0*6hDroHJnzme4{yl$21}KD$z`eji-b3m18C~p}9UEV>aK4SsYuRpg z5OxhVMFRX)&&`8v;)%WaDHP70!cEW8Ck#+OW(Im6MIJH&Bc-2S+F11R7u=8sIW-%4 zr&4r5_w+#501MGIYs2VHyTW)3P(TxaoxyOBRkR+zsoj|fa=rlI$U2muU7$IhTqH*;2X zqmp_lJdH&D2?!lDbQfti%OhCqObfmMdB`90h{?hR;H?mGK}0qW--In+@N zoHn^&T9*=jpPd6gGVv}j>&-#82I}e>5hA+g=-M-xHNUREU|(glaJ1URH?#Dy(%QxDw0Yw<|OF zInVN-ZqWUkc0TxaXQ1*7P|-EMBacN=-onnTRVEDoX91Q|(0*QJe%$wRGeF%v09eW* zcM!8Y(CVPpaw`TZ`Ix9PgTA+~8K6?@mB4w(`Mp3iM4e?w)=zqYBafln3{Zdf zHLSzAOl7xb7=A7?+eGbsLUGaoQG`D3-m&i?q00q=w9H+W2goL zRN|woDl&REs0It2y(Esj#*@v`*%RMeN(QJP>e`$t6 z+zhc?VMN%I=FYnTXP}7z>hdE-_4&>wQVnvs<*l? zPA>q4fe?9>ME?gW{R}XqY>9EN5JEDhIWEMPs-%Gny~D&xavS+w6~5h1dj_b?i&|A^ z^!C(wlz8$Ou-+>@JDOFr3kbdTen8rNKsjfl;MlT2PG*%4QE)O?-Tv^-#{#h&4ya}jZEac%{WE7%S0@jQE9aKi{hw?4tW# z_Ulo?6eX<;)+@qk;hgF{7Yi&bVvEt^g_;5Ka-exn<_wrIK#kNpVk~45Gp7qw3{f+J zcPt2N(D{o3LmYx1tAjIuZW4=-ON)$ujBTPmvxvys*u0YMr5KQiAF3FZa&_T_Z|DHT z>AeURa<-w{uG$$0Vt|VMSBuJx&aVVHP{BmRrUCws8u3vz^@kbI$u5ERNw}hQ>8XU|&Q1V^m{f8Sp88G?2ddM-7n!&eEVbF|sc) z)P0A-x;TcSq&l#BIC*wSnlC~6KXFj)lpuXolUj{ff2^v6xZgd+z#~S{ENrB=G-^5j zt${O^1FJP=VK=LQ(Y+SB?+0aDVC!PIeK$tjsT&kHa1Rdb6T^wfIyR@^a(Po|-EZve z&hP!}{|&x>3g4Fc4O~vG((1(cL~4&bqcaeX0jqjw)ew&tc?3LVm*_Y^#R2fvee6!r@+MI5wM>j=8VnyuN716bW~t zZ#J^boiLkq@+07KexOG%Q6y7?LLT7E17Lc7&I|sjZ6%Or^YDR6vLtq{Hneph+#Y7A zzl^FaPK-~&;u8v(u{FC}cB0sIhH4MM7$ZvGyQ`F}KTjQyX=HVrx- zimkUn-@(N3+lK!={}WCpA;_r>0)4?ir>k@Z(lRhSZN@J7`sx)2oFDb5+43>M$jFVf z1G|)8?A`C9P!knaf~&gB%8yfH8!AMfE*M~2a1Hnz#Fl4JIJtFj*cczY8{7E?eSfu% zp^W;8fA$6rV*V`Gig0Bl-+juB0V=iz|5-@S&h+S1I1qW61(`LS5AdxUbt=`CbWZ7bMfBKgJ z>bccLW$k`t6;AKBIw7O?keIxpZ(49)27i_J`#?htTtXOttoqWU!};Ax9%iFnax!U% zzF29nr>Ut{qM0*&E0DUD5wV4?gx9wP>VdapfI4n<4$%yVz7#l}7-$)3D=}%T;p|ty zCE$}5j%(ZHU~4dOUlwdH2Th^Q1+3&P6zAGFDqC3*zoz_J$oI<@tNYWx3{b&!fv}Ko z^)IVKw1oA{;8P1?YdS5)clA_}jo(wz7zRUy5?2p-;e6dmkTc9%CO!i(-NB%Lfgd7_j%axgreC`WH5_69|7 zma9jV4+DLF{BRz<2CA)QQ!IvV%`96{UFTQ^ z`u;>amI?pi4D>hyoKH2~{!*hbkL7wWr;+Z;tMvv&mm;h^>bSj2vb4LOqw?>aHggZ= zv%2t4(1TogNY!P)>bz@p{8W+YZE@P_1(vt?qmR~A!m47owpPupKgDgU73empCM9NG zzh|U*sF7Y*>kOn}z^XoKAtM(U;6_cWQd-S=nG4-tbD{?`;0=nwoQ&NI7aPYTeZmF`!k1EyU{hvGCPgC+Ana7U38pL+5jSuo_cm zh%v+=M~Gho<`@K>+(!seQ*Fc2Rs22dtxU>Trm zmcE6UYi68+zTJpZZ*5K{IH;wt?*>K5OBmiAOqk5`c&V{14qgKma#TD|druRDziL4G z3%$pbM^se?sNeS()bY{ijNK5gD#e5Rh8wL$X(3k*GG?#=$Cm__?=0!Yje0Ux?H1ag z3P`3K$+Tv-j5+OBkH*ThjNZ=4-WW4*px&A54Qzgd&gqFK+WY4Xd@NL@Vf~u|-ajrh zI5+MLzyNjpL%ybnOva=|`%J`2ITY822yaR0Q0Zu~w7y@y!nPN{P#Vtu$> z-tilE;JhxRYc_5x`1iut*BFhR^YQ~*YGhe;j~zr|cw?e-VOlNlrMl$e3>3-$=a)Hf zAa-LyG5G-R4kgQZ_ceC^xkHjHyUxgxxm8~3$&}z__LZqIAy*G=q7_cbcDzxA?_k=DPh8WfAPHs@QNfm|6_)X19Eabx6eA!>h# z)zJo)SFAM@W2(LbWwXUp7)e*hHbQfQ;;u+WE!6zjLTL+~C$`uYW7AJ#DCq+oRwu?4 z`+z$SvHT2J)kCY}ru>WsddLmk2PFMnVDhBN)L4lkG)^`~kp^0pQ98B}1~e!jT(d8Z zFJlz=G?TSo6y!YESlYnO>u`Ijf!_Vp!^wAQa1|(nynqvf8b7H5Ym*866Bz~iDS9VuW7apf zU;w`UW>glw7DWrbeN#RRP^XtMs@E6f6G3lSp$z6XDu<8JJ80%)8rIPB6C)p!s(qIX z!RO7k7in4|?}H722+~S}dxFcsTOd!l31f5Ph88@sl$DK?pNQ}3Dsl;D;O6k8iBfKu zD77bc2I4YcRsXDxm$=cFL>uShXK_W>ve=>?(D`C0#Ya7w**b=<1Ufz=?SnwJzl;x( zX+i!yCbVLv18aeO!D--O@EJ%eHGY6G!T^=_jFo!#7ZIdIgJKKxKHLuk zdW@xFU`r!!bey;(WPt0CmXbb;Y~M2O=PKqZR4C~uvo~I7E1d}=Q&34e#c0!t91riF<@2S z&TeJQw}mmlMgKpf)XOkq%ObVLN^HHQ*XIq2Aw#TMlGl{J^vmzy@kTE0zyUwGk#1M( z42)%fdZr%G-NtT+`{RVT>iSZf)p>f3eq_@d6hnrrW>oN+rQni*0q!6)D&AtgxJGze z-8E*2*t7N^1KShR)CO_g!|`#yf!=;odACu(n#I_6;th%+L$)#~bv@gB)y^ryQNiYb>r8U12g-2P-d+=(qcg7bu=i}EA1gvF~=yU*Km1e z1Gl%LoUCS(7`W>ytHc2Hb`AW!$-w7N(K!`$SKlrf8K9iBguy}?)ih`C%R%`a*P(!D zjW1Bw&FmoNGiNRF`6_rC+{S@naZyKgSFu>sL`EO$YS|McVc;(${%w*Bfob<3oi``~ z$?{~08Q48>j<5`W^~OXPQGuy611ENaVpgu7i~)QVOsN{=6`W;@7E5}BUF z&*RrBNiwBOJ4?!Z-LiRuq8mfW_n)6UOHhvWgHm}SXCN5^R`u$gn2c=4$D0&Z7?V4D|I-oYh@oG?PlANbpa_Diy^2U~| zo}Yhg?04U(uMKXpm@~cr2dP=tWZxB(2Rx*9(ziHwJ;`zKo>Ls10ljt9LZ&oOs(NMh zs6MN^o2Wry)jG@SobrDVLrDi676mSI-k|6}dWKzhWysqp>%yIO`aWkMAp`T0KIRDf zx_Lb>cZttHl^PV**TgLBzOM$waalAN<{d_BTrY>R6st!bqb!~7W8EW+Vz*f1!pK!u zTLA{F#%7JEKadOJZUqi8oA=A!S;t z)}B>EC1sdBlTCw%EyU^qVBxFlEI$KQ4OA`g<`SO)tM!OJiSOzdjk-4K8d)Z}Ky3;2 zPz>S6*ZJBO{8#@AmVe;SEWoNT8pHdj@lV9x-k^v`W`ioL^0GRiG`Q|R`-lOn`efBL z-$zB$GE}SbGP#E7+Nf(Jk^G}&H2H2+n_*l0Q5$01d*In{E>HtQqm%P~R;N49ov<&l zdNUs;28mS<#T0`q`Gyz_OdUf>3mrb@r3ERzDK!Ho7ZSX&s{g42?U9U=8O1TmNbeZ6 zx>o9f$)BBoRqt)P5Y$Fk0rPswac(`)pl3Ynyoa4D)f4pix78i*G(FB+QQ^&OWcW=Z zy{@)D8PI}57GhQZEqtw#PAyYyA-PO=;F_&P|AfM2%p;G&y(rFs*NjYSl($QK24;(| za*W22MtWUse==ZoUa_kG{aH%mqPALTvhQwG`n^H%#<)5a_18R6wYjo71Jl)iME;&J zvOZVW-war-6W|RBn|fu{ps;$RZo@(Zt^MAhuUpFWya7}r+&7g!br$o*{mrlu%gI%Z zWx#5Dmaj!Imf|Qs)`+5Iu#!gyZ|eOm-k=yVXk+dkLmSPZ;wS!@(qm78{NWW&u{AclXPuh=I;$kdTJ`{>IQoIRi)LOZht1-uQkdx z?&*!xTdl%r{x4-G%PV%TE5gHQ48_sV4x{{jYT-{UxV&p>a#s@%>f@L{p_ay?ueTm`-W z?L_;Y0q23AgN=d3%(%AU>BS<61t;eslSapC{%-wy?!=0^XLy1nYj6-*jF=v4op{te zY4O-&B);pda4r!Tpqw;-cGU=~npG@8IrZfrs%9eme|83_r<#gran8Dldb(D24_yOg zG&wBj?X9V!KqbeAsdgg;=i&mK;it(qJYqOS{A=NuQSld0QKo0qk8&>MmzpHJp+`_ zw~WeYpY&dh%ZYDOfY*(D3{`t22^SpaRmxu|nF!nn$|P&23@0cXfquy-*b9Oj@I+l1 zpnO&|DkG^~w5tQ2z!~Vm0QG2o!#etEiUw&eh?=SVjPO^{=SF^L{d)IqGsI)s+v{2 zz=ruLr@kDW-Aso6PsafDQ|C^LMeUxTZhE6PU9k+vMHzjW4R;LK80U`$%+5$TWqRC! zf4a_H5yz#dT8<*NA9d0=e&bF8(O3d4MP0VWgxoY8i%_csKb9c_Ilw??zp6aMC~%Dn zx}RfUz%gND%hmQ61FARRVZyR#Oo*+6dW^Cn!`a)&_#Rms6E(j~uXPz>{~>jJmrnTy z+>MiXTN0n$DMNw#4yUkwVrifFtp-zlir>@V|0qlU`$ae9bTzTAZxrvF=v|1iddEn= ztL-rcsE?Bo(j#C#qtNc9J}z&hyRXzzR(fOcYeqp&OgUv9+>eiQ;@=BKK4w*WJ2AF> z{Ly?jHfdICM)^me_h&}B$Et-Wy>|Gru^Zz3(6Z6{#Z%Y!nzn%ftI^0ap!;nO>K*%@ zWhbC31JslCNc0h~YE0;jm0Nao#1n)vaA;`4gy{~A(U_1;^t{NIRd0F1um&X$ZzFJU zOb0#(Ws<9Lrn%uWD9TtHur;qy@E@Xgl30HByB@gQ)To>q)jr1`H85P9fdLFqFQx?d zHC7g*-`^Zy*#D$vfbyBssEnjmz1vX*otuMB>rTjS-g01~An|USygh7V@84{nK9Td0 z5@YwSHa=zDe0U@mT@4IS7`tUHkih(E)OuskYn|$xrqZ7kSZ}f>^Klaq>l}q~O4b5t zlmE1cZVpm~&F_KHZEWYc`IbS>g>1mXMZvo{dHN!DE(N~=D}mg4BieC+4@&?mnWLRu z-=3TS3TYp!f@+~x4T~v~d+9l<&H&{;F*v71ov_;U`>JzRCjTiUt7QRH{?U6U+Hr@i zS%Ge({sGiO_8*Xk9M;aK;O%(16nHX)w;z*7^L&p5T1NZJKm(U5Blv68OJTLlcV)PZ z?I>ln1;|q#$Jhd~<8XcDV}Np=4dn4?qp|*euY62Y+at)myOH3CzmF>$GsHF?m=A0P z4h8=LFN36_#>y{}#5Z7;N4Jb9pPe-GgP}m9;YZX4knpp&q!#N-Mp11FZeCKbIuV2qLd))&*1`D-_37^Hs$4^z0m^bW zexFePANjk|YYf4SdR!LGnJ?K3?RJ8KC?o1SbWQwM7!GjOg_zewk|Uta{8X#B>>h$W*wxq8XqDPHs^P zYdViFI=)`D55Mbyq6RTNjctD%QlZL4dCdVH1VxE@LtG3Ppg=V~&q8#5DSW)20cEbz zk^w5sb{4ga@*DR0|T|nX;e4=JFFi# zEILLCPm9_Nw<^Q{y;`8gNADL{5#WD&P}HL^RgqV~LIqOLH>TnFVG(X5K6SirYLZc) zRLt)fRZgk>wUOJdwuu3_)}2e<(*RY*jk0f(TmILO0f<-Ew|a_-l4meHpJ9lux`6?> zKF+Y9t==Kj5J7c+CYm-{RG3r_4RX`8z^Q>=1O6n_T3+BgH^B#S^$1wZ$mmyz$>KdC zM($QyE#;}{rKf?d3W`LpINp&mKdT`7J#UsW-k2aS0Y!~dxB=T+QpWH1JlQ1)kTTx| zS57u^=W@z&Qw!brtzHjZTjm9NPthCT9_;DGk}hc&fK)y2-T{vzaNGmj0YXKi>Q_r+ zFKHg^Ocv@?igfA{*L+}?oEd<3b%kpXWf7u5fy?F`a!;Fs&jrC7MHD7B_1u21o+h}Y z!NI%bYM81{ddXuHL6@epCYhrACh7kSmX6{;uPK2TJ<~o2JO^Tk4&*Oe^Ms9MVmRAI z$9rs_(mDp$KbQe{UlJ7gd|d;7{Y7Mhizavr{7nUldYtt?B70yuh>@){JROKNh*zzB+~dSXmxH(f2{L z$2P5aiE<~5lS`pot@N2%87W}ffedE(t)*RJRu|J-U|J(P*Ac^dM!H=s3{Zwg@nznl zm4R%%n`C9`!6zAX^ki1bP8aX%z#1hAQ0IdMD6e-* zok{R>Y81SeNlDzyzbCGr#Z@_ENT%m5kTe0%N$){Wmd1oQ`dA;9LSg7dDwd1WtP8gn zSjN!Ly5aU;#9!vdgo7h7?V9M5*P^)qk$jPNK zp~A%02)UMk;RIM?g=yj}V;MrgFr{9FQ4<=?kN~l6(LdA1E zKJTUyD=dK(78Kbx9E4t8ty}L_NSTa6yEhg&p?a{X zyQZ~6)2B$M#~(gWGX-(*HYrf|o*J3Lj49NVDa+o(q5;q5Q>4ofG;uBlv@q1K%HU5z zA5Oq`$-jUWEpo}g032#C{DY{lTz5z}q>pBBvtw3t%lBP6Cdz;3PnO--zKY4UK=9Lids6T?nq7bT;JsUZ5T;4QM=LNc8_LXKdko?V|}IQJNccb>|z~TkbWYb0=#SxxmFGQ z87SKrjZj{;H{hgErPe9X41m58V%Fn}UBLsO46;je0pOInWv?yBx#zL_)n=cn@E^a| z0Z-=4n-&4uw9XH|wH&hL0!g9aX~kUKJXK}9NS(sy-*B)z(D}|%wu$a|B!vX62DZl0 zT?(`sbZq%%Bv;3%iP9n_!i~_TQKD(?lGMd?5;&J`mk;^w34s%Jb82d$rECjl=UN&l zLO0w^h}|`S9wBW3ET`w9K9#Hi_ru!dBnFM<)~N0xmeA2ob7lBLh`*ps1 zS}2R12=FxHAUA-^Ym99~R}VKUqx4%qjiEG;1pi6C?TGygzN1N$21VVQ+QFzhBn7FK ze`BCJp=pHc1>i~o8O?W33w*3bfWwS~JOM6uH?|Q~J-keh!gYZzC~JZFKvhI1_C?`b z7o?6toU@SNAyD;!pdI6^;LbfLzvDakP1)(ft;TFsL<3i^2Umiti0{R!INr)n_}9#X zJzDLHxNSvvx;vu2LRG<;dbHFCTN|tZG}fvvckx3v{bvyKtM!eszoRxNVmsFh`Y2@G z>D+G|%TwrIii$GeZp+waNA<)#4++#@*Z^qplxaZK;;IQjFN?}bJRS?5 zsTvWj$brWr*uGDzeZI|v0d;AwMj2-Ay`$_jW$_s4Gx4-MO7%Eey&0#2%iwO5wQF#D zAT|y)w(}ACrzajgwsbLIz#9|>q_$JZK_kBPOnr%VX(Dac^Zlhca8eC&#n17{uQ4#{ z?$zMPev$hL^tE6Vjnc?~N8MoE2dp1)=-5^dZk~gYG1*_zF9$*?O0`y*b(hm|Kv)E4b)nLF2tk9& zNH;q;47?3=!0C?s63|bL3Bn!I?Q7bYkP+&^n_zx^s*Cq+ZF7mnz$a*06Mm-wCXESs zitZ2i`UB{vbLb+(dmN~**P-v@K&r+7`8GnAdJR(LCts-OeCv&gP_{Cp>!*W3udAK} z>;SZIPUHF+nvXsLoC~%BdOTqwoQVDl_CWbsCI$v7y@*(bfdP*v_`f31y9UMxSzZD^ z1=9`8-gp0UosUjEcmxcEWp$zJ5sOQD2Gk?5K739N{+(V;qMW(bmqecBlXz0h><*r& zpG)|@2W$rhoO2r8VV~A&xr%L9G;TNgt<^6zt0!vD1pZG9bgj@eL)Q*nL+YYyi>@)c z)=Xj)S1Hx@^dk=nQw@XNfS%9InxX`bCC}beMmLm@u5;(nV9yi^UnS3Pz=`f49*2H{fy;YT0PdS#I$|| z=cAxk12+Rzo-e?8AZBAiz8sBuo#3O3Dic@%#XCk<-g^o)-ry9l8BllYdLXu>x%-Ii zgPzeJ3Dm=;2E|W-#s>7W3@7-n!ii*BP*`K4RtS1*8Cx{iQ5W3Bfi5-=#x_u}zC0Qe z-+{vALCnU4&iyeP6DkH>qjasRKPu5Rtn#ym@+e@D7fm2t1)=FhUjupi|0Y**XYgQcKCja?~VdzN;7@OM9FvRS^StT+T>Yna}civa~=RR zeb;&lvTZP(wW}`t4V+3@l&*`Ia(E5jX6_t9;=LOa>y@2yVOQPmS}boBpa%6?pqJ|b z;RT5Xk`IMH^{tA2t=x(hj zd7i?Z$J#jYs!WatyII>RK)==kxDi|v9eOZf{k0;B*A~=Pr=M&#-+0_!Tj}QJ^2yHBBM@7?eqN%9Bk3U$9KUC-h}B>8}Id z0j3u>^v?k-WZpc>+ig{c0V>-q1{E%Lqj&(J_^UTVYu3T#;4{!GvebY;4gNsXP9-Dj z#|B~crb-HKHt=rA3Q*7Na~C+!^r{O=#znI`AF|rRqnr64$f9_tgk4H#t%6JGLF|9EjAY@LdMnfukf(f( zu@gb*Tf+EwrvWkEOHsyyp&*~AUlzR+sd=Y9~l!O}56-T7Y1`qM4jf~5<#g+l}}DY&9r zFb4azP+{c+9(3cUYniS&R`QF=5mSW2u&;~d=m@2tXMleJvFD2yLCYYU#5EbX3*;@2 zV6b$LLGWpPBO-F0;WMb9eM6xPP^Tsb9~;!I(+dqOz&J6_0Q7#2yhXi1m0x(VPBF2} z40J7uF)l^dMokHJNx}f6X%)<;L8xf7^toW+BzCHvmUx!|nr)G{Xk@q+*(r_S&&38L zsLQpGQTU}HwvQd5>@^TMwrGI!bY-O#-xdUV=~dpM3+`%VCHVE`5)ThG@^kz~?ysMxm8K80=35pQ4wtod;U(6Gci2Yw11^?|t zj(FlqGe8}h27F>rm!2&fF~s;2pjll-$SD{t^qf()@^F9poB@bI>#6Gs;kx+=mDZP$|CzhJz%c*7yVw%m=B!mIiMA zJBfpl(`x*|H-nswm0t&a<6|r;4>}8f%z+PDKj8zT_(Ig`W+VET zBy?^7-V1S{mPS1?x(W2&ksdylOCK5)aC?w-wY1&y3>1Hd0?p1SQm(}K40*+ktzQ}i zdtF{JxSjkNpw8@URBxWjKbrqpB%W!(MMiOjs(p@xbHwHVozsD=ONU>Dj{4Yz*e<$0 zXJ8-$RJQTJA3#j``9Lf7|8Ra9P-Hi!_|u(%##)&7)L`RYU?Hd2mzG<|n*l1yx)znC zrgO18RjM z+UrSdde@Ks3zImMAgvyq_*xHnRoY&+LuJw+OSM+5WxFD|B)IXxan?Zw>enE+C1dk} z&Xoe~r%84|Y=2!}{tQs?^8l+m`M+96gzs9{AnzryG1*eiVQVhqjIi@&OAq30RB!6u z*5&8=dz1kx&sreKz@DsCcg?a;Ng$d!Ru*{>N20w)16|)Y4D6t?l%e~PoB`^^0zeB* zS;!s9JqpW#v+7Z~)57VLI{!qzTn9K}PwyGZOHRU2W#0P~R*O892?JCVU2xPI%~S3& z2_~ab2$&i?o+lAqY{{3eWDHA>ua4|uC(G_bvij%w^JjnpUldp!_b;P6>a49&l`y2a8nK*cydd;LnKVK})aD>Fg(r$JqZfij8K z_}B@gx)UPbnTElfS?2O|-v%;3J=oB&F1(NKC{rWRvkiFO(APAo|4OD(tmS|oKT8up zggk06E;z7O`MC8Fd==IkTTjgpe)lS(Q%S`dL((L2fAR#ctIj+qKS?-EzMmz!LPZ2F7QRjWf=8i zzI3%BCxwi2xh8?@X!=~e+ZSUD0wuO8V%pK+B}-NSdS5PV4l9+If|L0<8>osuv>?N~KQ z4atyJt5T-!_ACiqL2eMI##($g16O%vy&gjY8h8A^(AfAzK_q%2QwAvGt&Ge0L-fzo zE(rGNk>RDrKEzP3nO>>JC$)>c=bnsqVybLk$$j;4); z-enIb?bg;7APV`ExyEYR`LP1Ha;5KI!wA9Q^Us29mf{vOL$*Ha+|s7C>sVs8)D~1AO9bZ0qVwVpbSe-m#v!KjYB5y)M!_F*o*nvf+x`ztr3JSjj6c< zWR=k6Wqybql-hqD+jC3cT6h({`~0MS;glrC^GNF!&F z$)}9Qt2WiwM1`0I=s9|)74u$W|K1?C0ZZ7L89WOt<-j6Kkiawz^>E7oORoDV{PQWM z87mf8}C61VE34pfabh_cFHME9&!J&1vID2unO4fT?K z>daxp^V436DMc(Fljj@Ya_Y~2Q{*?vLfJfy;zdl9k5j66cOdSw$8GXoMKRzFilUfr zW0!;QD0byFpLqnf7T{p~yp21BZiWjz?>z&oU#KJb8h;madxA?Smr?neu7)-0g+~5s zne(lx;jxLAx1x0$>c}f5+9N2XoHV{nHwSsh2N+osKJLrInA>R0fHx>w^OE~k4!&J5 zdUB42@5k0k9DtwZXfw4b_)%S54(LLXcqPKrhRc;v4ZkPAL*SW4P>!$jzbAyU9!ek! z0KF$c-@@WGOvHCT%JT%R!MwLo)}`r%=vEMvCJ@fnzwl?B`yRlS6ByL1zkM^!lVtqo3~BJJ}vYlsC??*YApC5Hc03q>Z#fp{EK7ti!NzP zy}Nd-o{f{+UhvNqCfdP)k_4)c2$YWg0{&4>%C*GEUyzY=~qo|N}4kAs5w4O@! zGB)Po0Mg(jv&ICmXbp)Sfff@Q4&DJ;CReND?F&jZ^%E{W1!sWi!5D!jja~UV&>%+_ zXCNyBFQ7m@VpG=Z7~fNY6F}jO364pOIrr? zK8$rh9(UNOj~)C|eLfb1%I75fQEG!JGGb3}EIvKd!4&C!nZhm4l8^y^!n8Riu&a@bR298OxA|_%*9xCGdT)RT+G8A97*f z3atDY+)DlZI2VhNj8JDcLY4eaBZ_qyVtzVJ<}`WmcM9^|2v$gwzfGPe*}f=o^wn6E zHe8r)_6CJ1z3r8A;LO6_hrtZ(Qw8lgmILLxK`ApN!e7mxxIBZ3dR8sQb6)*VFMPv| zx{1};+8pcwW(O|SVnEYrj|Uno`4Dw@D?jL$+Qycu(RjntqwKQIgo0GT{5X zeBB0gp3EZW;`_E)6nI`|pfU{TzyS|{B%&9Z{WPy2v889LvE=!@{4RqXNK;p?UWT?l zI1zjXT=Hi?Z-i8r`o>@e(DOG_#P|$|C0iG9JmLHt;P!+;=#9+BfV4fSMTFWDHhcb{ zs#+;=5Uh^Rnx{P-yU={rZgWz7^`!^aLOKy)fT`*OQARmAID2zNUbxM^G_- z0bT_X^ZR-i`5 zlHe;qqu8eaRTr(&c{9+I=Ldmi->5;Y2Iyzh9e)lE5g|f-(K6J!F^MTXyEtA4(pOE&F<~FD4d-pqvwgkK&@e-aUU9Fs%~L5QUv|hj0HizCuspK zWvq+-sM@#w*P&hkLE{hfT~9mO8v?MAvrx`o#pERhW`9O`{@y^Zt8@mOfnH;P6VY#g zg=ldf7iYj3$cX_C;{7ZRWON>yQwVOx8E^)w$^a*dBaKc#yXVCT{;v&=2hRb`sjtfi z{J0wI1N2@27iSk3Hn(AC#R2PQ>)y;LH8*ZZzTYCTtIkJsO-|P%H1O3hb zXPgr(&N}Ga!J1oad=qH)OHvs|1`Y0VaRyQ|pgIK7EQF>yyK8F0ff=!}Be0O;16}ZB z&VVz}FAQ*|Im_Z~gU-z@IYj@mU{nO(PqFmVb@wg<)V-4;)IZhXZw8!J$R-Ciu5r z1RqEz4B8E^*rjsZ?Anh_C8w5;?()+A!X>Jg24Jhc8o zbV2W?;6)HB&ysMn=#EreA)IUu-Uua;bT0!F9??4q_!wBo5!OY8(+h#o5uIP#+Gp4A z3^)TNXMhvR%@Iy28dNr?b*R{|8dxR@wu~jIvj3zpADW{xsD$tLzy&ZXAmF zo}1?Qz82fxW_=i(3&a@Itkq3joB?N`-x=V9GAVczq?MP*s4izy!Nx4W>g8I|=hWlt zr687EU`lR@l|!J`bBHCE#SRt6{u0Z%COzss&?6mF!G@;1swXF{=-i=4H7?G8GvEyT zj{!~!JAfo>IcTAtALhj$wjKu-a(C<)aPnIQj+(xP8Gly+r-G3!d{;y6-{1#eveVy))np^brG` zB&Gy9xeN!*@(LRc1m-;wjg({Wgl0z~{Wlp^k8c(in4=mwiSZjh*8y*(75{E zg8mq5JT!;*Kx~IGpu7ASj}DrB)&GCQ_P3Kh>xaJGtq9mcMgl$=oKdh0eOEn6cM& zs*Ivf6Rs)WnC}njh9Z71$1yQ?M18Kx8Hmb&Hz=ag>B=HA@LFVjb#?2pTHvVqpUB@9 zZ;pH&f3Jw_XJyn8`;|C5(!gPhvKoTFTKRMX1Ao6T;=#aGSJ{sYc!Q!JOT8j7b7KAk zR}YBn?)T9feVV9z;0!ne{loxwlA4)tG)NdeFgfvU2{r=DfmwhC wnd-${!+~a3T*N@e$N6?~2AlzBU;qRE4}t+Jib~eb+5i9m07*qoM6N<$g3lrPHUIzs literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_network.png b/selfdrive/assets/offroad/icon_network.png new file mode 100644 index 0000000000000000000000000000000000000000..3236924f4dd90b40018cad92538b397e246994c2 GIT binary patch literal 39872 zcmV)hK%>8jP)BYqPU&cJ?HhvL=~*PUd-Xb~3Z(Ti<+BGD#*m zGtJ}>o`3%NwH(Y_Gll0o>dpbphtt&^C;;XO%DxTci)@TcU@s!r z&V{?N1-JlUyR_J6p@{-#zU0^BudI?x_9FsdG!iFH%0NlFEl z+b`W6=>lbdCIMV*OBpyOxcIcO9ja|I%wpo>Qh4%DF<~gieaD1lDy)gODeoXoKn&ro zfkA%xj#2;StS7w{p4RrxA&Jwa;lZqxgu{YUfINHB1989(u*FhIB z8JS3z*=2zFJlMWc?E7Kad|KT;dA^oqG})T`iJjyz*%#wR>@sKh-(n^?&ZlSlC3dT1 z>DjNzt}HIgll_|PNLwdM&;OR#=1qG0VmD|3rcA{+$yJQ2IR0-jjqHaO<4ngUKc+ZZ z!PO=C?={7j#sR*UI4FdtiWv&&y~Co79GmPU&SYB_=YnCfE#jJNhrN#biU=@i~*;Zi$^!?Pr*_SS5D9&2X|` zlU?sLC<&QS_FEifZEPg3tzFT!=r7}8i)UkJvT+&&Gg4*0CI{GFQ?wU53HkUJVus`L z>G}O)-h7(tzG@3F5i8cL$)-r!CXbd)SqnJ1NNS=U&rFSc!ce%w4ROIyHnlHKZ0$S< zja*1c3wU!8h~{-uF>Zn!|EyRJ5#YLFBsDNcF>Zn!uQpN+3Olbfxk4DZn^H*c9TvfS zZ4CM5%wrqUht42kYiaXv(XQ+)@C@BxwjzoAvFvM&#IbN~_?4XnW-XHPJx1{(@_CD- z@@cYPOegGScjdWQCYCu_8f}oxyfx>~1XPwZ*fsGuf22fFcj$F@XCR z6AF_aVr*WtB$eXrUd7! z#e62aqKzDv+L7>gL*m6n5QEK#0A-FOZxOHR*yO7W!(>~;HrWvOkAa=ZV363~G1*95 z(N2y_Y^~N6koO)_eg{7zoNDoE4f@_4>`p7%nhH=BSIo=t$c$C;8tg_2Z)Il!lDHy4 zTf4r~zvk?x7qP02bNOWVM3Zg7W^h=v9V8TX#IAQ5%rZ!Nwx9jVD4p$Rza~3LGudW& zw0~VVm~1nywWmQc4?X;>DhRf}u1eQR!_T$0Sf;|4=EeAJlA#z(8HzU9vB_354nK2c zzKXvlKSi7V@qC$WQ1ceB3@HDbHLrY}*1n5R8(UKsIKYAIybiX}OdSOuy3#a~66H+6 zWQ^TOd0Uf>c3j>c`v;ov3pRtpqU}f*$P6S$wx9oXR6C!wv3(crrY=xPv<$p5Q-g^W z{O&f5Zprg3ty39Rinc$J1cQW!s*2Z}PHpWF?-n`11m^WagjN`&HQt{njYX?DrD=J#ouiPl;S^My;9RrG> zeL=3*qpgEf!qYgJ%X_R80MN4c0+P4}$QPt+pE4X>mL~C)UBIMjFB5&B3bd^>AHJmp z@d0bA;Ca8Uyp3JJ6(mm}f&GyOyTYlgOh&$9YzX(6j0<)jG1+Lw;qT78PZM@NJ-=_V z9q9s+!Dwjc_a@uer$}3$COautk>5}kAk!itg*WAGA`ae97X1_pnx$hqROX=rjPA({ zt9}8Qy(+zhG#5TY4^4{#jBqbeazt^-SYkVZ84^+EgGw3cx@ER`{{sO`02n@+HTnU1s!Ts|rbII=?O!0X~Wu#5{BrYUx9#j10vGQrM-#ZIn zAnSofmd6)KmjM;+1lVM2vJ=~4u+3|-6Re`261$nP8;ppxg)frKj*HGDzQkdc#p~CE zY4TkHewZPC#@ZtRFNR_U(!W@=kz<415+*y7Z82|l?2^C4cBE^Y?8INz1x5-|RM%91 zqKyEW?0SwcmS5Xoi-Voq?Y*;zTjXZK6Pv+Vpa|e|jFb17@)gOLY>IKVd9WLKud#?# zbu5deYiqv>ppf?M!m%9w+Yl!$Wk>Pd55F+knBv6V6mJo?XVC_zpZ1z;pTywDV0iK% zamLQ>2D=%l{k@`%9FG{yh#0wxJ0oevUJ;X&yJw^h_D0@Q9HiuSjOWN=^Ar1`)1pmQ zusS;vRz6P=*JNL`3GuBq2G|fa+2jjfQjqNoHY3a4i#E2$YAwK2xMEG2Y)nLL@@d(q zwE$B=#v!f~AoW_J+pK5c_%}nGSCr-$umB7mEV8iatNA=O_C*`XZyH~Ub|xF!E^v9C zWZ&Vd@^LsTdx(-Zll`|9BXY+VldWc4(O-6K@{y$#eur+A4Rrwl5n~fr zzS(5yCR>wTX0P#U>(gW>{)_xfU0^N~Q2_r{j4y%})0;Rpae(VBCf_F8krp5sZPhb5 zNg>XKzfpj37Qv8TH!OHqw)m&!)zmup)=>H{KD~Gwl}xN z2j`~nj@Af`v15cZ-C}%3vq)A$fQ>_`^*Xy$hmJblO{XK}-1vN~&aZ}^!41Hs;`0U3 zAf3mXi2IJ3PDfMk|EW_t4XhIul5cb*I&vLa=VKD5@8nSSxuqTmUY*%1lX!C=*fZ^V zzN=!Rvu_&&SDl?20QD{-#ag1Q%Qvfoyy?X%nNIE|^l*D*Y-?0WOZj38A*~!JO)X z+hk?6?MrkaY+lDhgvRFdI=d`gK(qbgZ|Mk7m1zXz1wzH>kz*Ike&(q_uQ~!WW)U9c zuI#m0@xfhz{hPAmy5D}o88S0A0DvFH%IZ~76X=kK{(-9qwzwu=sm8_708Fd9hJ8)0 zN7vQ!`iz_c0F-rfYLyS(<}L-7ikFZlS+x)Lf@}w}3Gc=N{+4I^fQ!R^xvX#UfL}Uv zXMVwyPZV#G9oPJ>2INSc59JZ3Heo1J$pJX|*8yu`OJGK#0eVjj*qS4m6e93>X_a3W z7gadLG#gy>S>Z8pIEVf11)crigbB~TziR^%Rll@JaTD6yAB-Zgro7> z7DIrR2l)Lxrd!#V_j`J+sY6+8=LEL(H^8eN4oZqpSNZ*HmDl$gMCHQs zJU%#;rzo&&9}(Mq1t9OdWM7_9zqBN+7`;a^BI5A}ZLksSU1fHZOHLtbp{5a3j*K}H z*3a~Fd3<-}YM?gA2vGT~I*0J9-2OQ1TFoEEp&*_dkG07sUyG3&HgealGSJ&SA`+|6>-)8?wYzX$p}z7jOH^#Y^D7180K&r>UlQ^@*u_=cGp3P%!o647ZUwzOEZ3!qB<~s1?a-}lZa?3z$IA*r4zcIMDVAhol zti37IcWufgSiKQIjO&0iKpV2QSYWOW-a#35*{=g$4?;K+YVU27`7_0Xx1NBS(#qm& zcmsJ=S^i?Y4IX){D_`&j4WQ_(>KM{LsY>ssZEayACi2<8U)I_73%_igT`s+H!j-eL z-Tj)ap>UN@XHU81zZ9)oXD8{Fcuoz}=oeB}!I-%a3DB8VV11)P_R>SlZ>+(Ma?icS zrzF=l`Zl}d@r=Wi80L+t_AQ5|6~VZ%3a6N6gImm#`mu|y z{j&7_)mL4)TyTrJ8s`8-qbdS6&cVCM1ylS9F5z8OzQ-kvavUv%ap5a^5o+_e;0j=o z!$?HlAQU{0mF>G=W_e7+v$WKIJ<9te<(<=}TrSvU8X8A{%z0U+EIt1#WC$nb<4pU4 zDZ!LB+2dYNroQsg`Ts<0TfKty7H2NOmKd154^7oz%WciE4V3LSHRY4!wQUP%fi+}e zi(6|qglczS{pm8`<~KkdSxah+3@G1uhBD4?TLkhhY{*{~^&eYoYdgH{Rprr?W)0pM zmMUPQ}=3*o*S7x=wH;5b>NfCC^9#@P6v!JK-8%eDQ2>B_kIG%t` z(Q=isC>BJ|msVR0V?jPal0_Z+$MYsgwfFGm=@P=d=p;!eOsYyt(wx3d7QL7d`ezN{ zUUGCI6U2dyme{26?juAFu_Wwz^Js!pr+YDM^~A3B<63pzgRTM~Adf8{uXB>6cUJWYW;GJpoD4~+5nt-btu_#*(O$si~uer3ena3MvyB>mjZRRZVH6dg;xXcaTwA{ z-Q<`M)=RpUf;zdvHILXkHvk;@e4j@3B@Lf~j#C~w%boE3g(K&eP&dx?={yJU=>4lu zAeSeHj^&=X=4ky0rE|LR<2uqhwHS}eKcTC9{|1V7^SS2ss3SWU03R&i4&hll$+U*ZCbv&ya0@hcee3fGPi(J0E^nlV$9ZDcnu@0ysY z%@$DXT+TyP*e*CO{F=6{C}ZuXUNWv=tjzw@?AYS>LG-JABI`5OGbbpREm>#?1Gu)v&GKrQ~UKO z^AnW0_A960%7-J)w=Hj(j-?}jEiiUg!x4nP>44cYEhFuU)26*g8RkT*+R+!>3pC1Q z?71$j*0z8ym{KrXTn!OoV^H=r@$nxQKQ`qDS4Ik}4k*4&n4u$p)pvPZD<7_v-@%o_ zj8i~(`E2{iE}YTqzB+qwtyg1}VU08Z93N3;T#SdnQpLF9F?fp><7$r21lMIoTmzRz zGG*Gsk;y`q_SX7R7Y7tEM@|74RbDpa0Vvc+{(QRZyWokv4W`&-0sQx||1kM}l*Kji zi{IVwGY!9gcJUWO4;Rc@eFe-W*c2L^H``!kHa3`Pc&vMk6g|MQ*6p1UP!UUakbO(3(i?}Sow4to_YJ4 z{U4X&)nv>k*ZwyOjMvR)sM{|kRY<7A>8JmokS+Mo(y#Rz2ur-4nGJbgyrFZrfY>;z zJ&yolizWVS@Wd_#rr_EH2j9P?Jg-#7tknp9QkPZ_*z$T0t^xpftqti2Hh0-z!q53e zk_~PIn^(Zq>8YIt2P)O7^NKI{ZIt;Oi~vO10&I@6%Q67dFHlbrZ}r+zzBQV#vN#8R zy)3r48GhYwEdLI;M^UCvRPl7c8jL8;4ZucN2O@Waw|G^dB+UUYgE|ge)i-E8I1EJ2 zNSS_JaO<=O%lcKl46D@!kdZJ6lf_Y}_p|@4?AYel2G<6sXyZ~@{k*Cld$uW;EyoP2 zHwPfo8pXnv9RIH*eh>|o)kI{Fp?)Wc$`_iMX!Vo_7OGmH?a>3|z#Xu9r|4`FX!UPP z5MXHwzk^Yw#ngH4e+y<5ugs?FD8hM658UKR6jeA}#{xqo@+-8T;lNPjkBU&~B*x1+F;QVE^ zMwSL(xvZOizNyL=`uN(!vKWn z@8Hw+R3}$44_M&-%fd#mY)=<9a89Ry|048iRj8t9ReF{NPOW&hSYX!vZ{N(X1LljN z`1dSd*{=hh)dbQOuTDP~oS8A+vaEoG_>UKkqaDJ@`gL-|cxN3E@NQzWYMgznzuDN= zRYV=H6w+nr{Im@b3j2RHc1kujL#CChenqZeWn3__X#|BVrH5dBxHM5e;d3^SaN6=k zwuQ85?Uq>gfmL~FWQkKdtb+4Xgs6RTStHg1@GZUc!^i&Q|5^=3FS$-b#d6!O6+A($ z0YF|>$edvz#JdpUlqx$#AzX(2Qc4Y0oLs}NT1up!P{&8iEH!-AY4%)0Z10-%UUFUK z+hEw(SPEbRWh6Hm%kIT^3s)-1UO0OK8MS-)U#c9|WO^|7+F zfcTRt@>;*5Re|A>w6%+Im2HX*V1p{cxwM;e`^DWDw`!{}rxgj9j%k=$FLljS)jrvjybeQrg)7~p6dS;$mPIU`bRzU;Eiqio zK3ZY?hKjTpNw;f(YTgI1y5^>Gw4MW0-cVw=wc=wdWEF2)UsV_x4@<1mz>IG6MG?n%m%fj2-aI=EaJO$X^#8A72ttz2SZ>!2*NL#6J z9P4mD8(_-za~nGw8?{q_II|pfrcr za9nm+dtGf&fo0gWBTQ*VLjpWpzKmu-aEdz0()wF6?93%Yk430mH(-I$GqE9Oi-q03 zmUx#tU|KDz1n)juOiPYdaCKN#AQ%mBoHGn^4)56FU{|}m+yQGwL5ArVkHGy(1@@iB zOeK*OI3r0V5QAtkd~_s}IpXR;rji|Vw$a!@_R%DB%pgO_4!I68=NyeKffz)S<2|Ff zN@J?-(hV>*cS@NU5^Ve$vXw>EUb&TJEXE73-c1=vupw!4K5YZ5R}jeAltIIWGA;(r zUA9=M>L$EuTa#@eBiUJh1-w^>V!f`_x z4F?t&0~15`k*I;O<<1Cza)c#~ftii_fpPuLZFP9{5CeK_}_VTnKRrt!19?Arz#TwAQXovlW>Jo~|=_A=WR*QQ*qSn8($NZybWpmG)MgN?p%xuJqGg=t{9e;U;9BwSHCXy&LaTeb5XD-s+`!iLcsuQz@ZEiJXx0Q zB$N$qnLks!OPM6Ut$zpH+K*{~buO-7XX0Os%lPF-fGdhdCC9ZBvkbf>|4=lfYhPjj z?|w4X`W*sp_uv8>_mo|hfm;PMsQr=(KvtEH-Cr}OL%q+oHQH3LEtU|m!4ta}n1X8) zV))j^w8hKoogV>gbm-aOXiW>_Lo94EJgZm1^2BYio3^v%Xj@r*{>#;s1H3=h*_hJ3 zMgRe_DX2>!ZSb-J)Zw~dWtcXgu<4oj z7NCe9p$vH!v*i!+`;LCCD<2=bZ+i;rABt6dvxE1ai5e8<$JfI z7R%TazyWhG`_FKP<^Wlw0A~9&zyD)Mv3j&ygEN#|J4_8(kI#XFuDwFp=-`5B!V7Hx zR+B*~jSEq+H<6Y2aSgG`?}BU6bZ8Qo6W99nV+h#3(CB)8w;hFYwA0*msib}hF0mVfEs-)3wtmLV4qcp{ zVoLdJHL}&bui1KD+KCf~u%e9<@ZRo#DW*5u;HGHfSWYpwswnI>cER@61}BHda0KS` z7`WaAjg--)jMz@IrQwLXpe?S^&e56G%^`8*fcrrsu`!6Gj8!X;ha|8q&QKYaN0`OEF)MeP>!2y%VMKlZ37TzHigKO zvT>Z*S7E#0WO%9lQa-s)|4bP#moipqWx}_?uDS{sVA=o;jM;G^+Q)t_pI`P}eHQbl za!fg%Eh)>>CGke;E}9B}Ew)ty=rfX4Io1Kfx7r#*b`~L=54L&7#V%jA{{HN?+|lwu zTid?fI~?up%%v4N2AMx}AwU82-osJz+Idx;j@29>pFzmvkL&iOwb$8n>1G9xdR9`N zHm90nUG;W31!Nwt$#!ghT^o!I<|MLls(f_W-c=i~-sw}Rt}WBGAQR2rL*wVr*m`A9 zrk7U(kjx$gt!Jhgxykz5q_#e%fUI6h*T-cB-ET7rgp97<4FIQdbK~%4ir9InP(WT) zZ!a)hJs?AtO=yqhczL$bvTt)zXvw_i0C~qkCVyPEA2L*xVNS$&OFiX(C3=tGnQp-V z0%TLMHZ~cl?sukT>om})eDR^u00gL}g1ZT$h-4YiQl6%6T4r9Oby>FN;u*qjkYSAQ z_U61!OiyTdU{A^CpRfHo*o0Jo!q3BYWnTo-&zTdl;9a4TSAfR20NWj=M%j;ZzB8MA zp_?LzfR9!PTb6WrQ~WwVlUISV##a-+>*Q6;q2!2oZ;g;P$yST29cXo?odWXo>oS|h zS7W38`LYR7HHdabjc~5X>r4n?xqYyl&O32 zcgsSA>+&|LfOO^<4%=>{vfi+@5KGk73e-976mV3a-v|E5K(L`>Ruyx#=YTG3DD;I5 zbpGz9i%X?+wrwh~f%FH0&8JsYc{X|pKmlbzKokF<@Y9T_pH)?=1Do^;NDpm51g~}d zzPuWn0ifNVAQ`>$%QY3D>-@egqRUsRfHW);_bWBfNtjs%8o~}baMdV{%mAb`)ihL6 z7odI~Rzd1OIt6MJph;hciS=hRYv9U~<&zRo@6$z{0U*-;4RropWMn3EoxiLZb@A#7 z(B4*;Mh9@rliMuPe+bbY8Ah7{K>BgSnNwZ)8GzSICCoVN_BsXHQJ~*J?~3gGLfZSQ zw0%Sw0A$G0CYs0VkG%OP^?i!41)v+TO=J5lKBx2Bg)vfqI+Xuku`b)9Z0A#lcgLiU zzjMKVT}&TMw0&>>2(SuU%^0=eCMEs!NhfRrP?=@6#EB9(f}HzS*si>q#aS}xTypRajQZ> z${?m_mjg#3XNxkPM``oy@ah#PtBk<-SJ!)Xvw+WCft;$c2b~~;ZUVwe{^#)=ZgSXJ zYv1gE>rQz7shxLcE0qs)IeVSt8KhUlk|09+dp%r#7KyL-y9D0r0MK6kWkHP2e^mtW zrJ=;?{8Fb!%bzYx90g=>A*i((+O#|&h|ym}ba|KHN+0#TW&k*okJiZ}7VU5lLVZyS z6rS?`<-VbXSAsJg&hwO{b0&>)6rjFJ8MCANOcy5{FUAyZ%1AzRWL5>&%&5R*sYJ6{MumseK->U}{FRoYM$vwr8TGOB1N& zKzq0qn#)9_`cm41%BSq$8f7K`zuNv?YajwbFh=KJ3VwHJR1oxJ1|c6Ci4mTF=Ug#> zJIuHW&@QA+sLU=)n0}nLq4ER>u2CMT!>_WB*WLt#Sd6pYo8hI^`DJj5)%iDqXOzy5 zu775$3Rc%}B@HvFXbSlvwrN#`CG92Jq^Y~7*`x!goT&}`j)M1DhIr>FXhwN+7JkP& zlgToWc}X_yaAJlZ`m0SWj~B|#lpp*<^FAE*qrPEg;;Iox`KCIQF>k8=vJ2o#yuACl7Zmoj#ah_qMQ#o5l;FcBjQaEmv9ccW*^^M@19f}37%K8e$ z*UC?MUjf#Ip?ERM8?oJ-2H&@bmKlDFgK=jlPBDL(mZg^f5cyUSB=i^(TAe@EyZO7p zQLXc%;hg;j7u@+p`#x4^HAKx1$5n6;-1&v1l$TI@C)=e!{f=<6OCC$x-QoHnOWRU2 z_}xXK|FpdX8E&65C6%60M0rz&fVlN3+*JYjds(4%F*`30#WCbxqA$K7$vq05^6?4z z5QTPl4?KUM4XTAlxt|5A^u!Y2XIIMolYsm~S>Y-7Sl%%dsdKP4JcA#X!%w^a8UKa1 zv7+!D+))c!UX3WhnDCORbd1hF8~kMC4GwTzoJ}e(M&}oPv1UKPWseN-e|=q5+)&@| z1n46wV8bB)9zOItf?w&$*$=TdqZ*l+8J%bfEo8L{qs^-?q~=1Ti@@Bbj~nGjOUo$a z0Huyr_-g$MeiSJ;KNt0jnyxy;CDhOKe+7`ic!oD zuXFNoFUlXte!n3XqrHzQ#E1`9FgP7T9+d?bIp1%A+8McH?_F)p3`DkqYm_h67<{Qk zp-Zg$0U5{J(Pf$JAmkUWa^hPq1jCSbR``hq-T_`R15h2H;56uyLo)!Jebbw%IpcfG z(ay2jo&Wb}Fb^i^HFuZ3G^3JtwpJ8d*>?8K(<(AM~zC6`C0M)Y>DVU(p^pXJko~(;6_mW(G^0Jq^8zOwez3 z;{L(5Rx!=-_?__kp<|v(bGRLZ!RITDJQ6i@gqys3p*5qBQUt$I3MX05|FD25g{RPJ zj@}Fa@cc|b1OMBhAaHthC`KXwWrbtk!=yVux*f>Y3l#84w$RQmI-QbX@~cvQ8s8Vd z{kVW@2Ke0&iU+r!hhh}+2fyhDCzYF>IbL#d7%bV8Pkm{IPbz?^te?;E*ebX0wM*kV z%qwGcCarrCPfI7om2|9_VGZ%q4-17jqEXA!os&Z_40%_A+pLCo*Qmo?GgR5bY2T`J z%d|gO+F6;wX`bFC06UM9BY2d`yi&1)ON%Vd^%qVP{*nYuK7~|Ax@wcRN2bR(o;x4c z^nPf4Yu7d9zYR{yhU%cq>sdGj4NUOajxwDeTCQCF{j#aQTIbJ!d+$9 znRkIoGKO@1_^iw(gJi3nUy3F?2;QsKLI)6oyef->47edtvxH=pyy&EQBM`_vvjHHK zTR#64`2){=jZ28U>jU!#p8LP_%vYAp`_3?(Z4W@FmI1dEFaMc0WO0?&J(^ze;qrb3 z9ZplgNEu>7`Bc*aFqDrHYK21?sg4N&gVP=4Um^q}pI74y1E(Y|NuVLiRd3FhFR}gi zqqo;hU}cSiKiv)=ne}N7O!B>nvqI`iS)<-fz+FQK8S-?^c8?wJJz)#AZ zUy5~HK-o02&Kn9wXT3ZWqmX~=!m-cc?|d?q<&jH(^~w@G<8SlKmuxmh-EEc09qxk% zj~DyoYdQ}+wKM?^2q?Ojwzvw8&Y7(&{6oo-JTG=#T%Y^o6P2W$9sNF zlFUScA4hBQQNp@j38x1m1AyiYKuvBbVaak@&ER`Uak?gnh*&@L#9qlWpD`P=QPmr_ zMkj8O&$yWztrs`OdPd3s5Oi0v=$BDf`x$=GMH|QGC_DAK@k)dKg))yQaPXAZSAD{k zKAFZS&s7RsU!j08fRF(|?VlR-QI{E@`|l)mAAtt_w0}{IIrlck+C}6<@9gH6#vLK_-7sDRGsQlkxLDb6WM{&Ts~B&uWyl0 z<4oe?zAn#`@Y}7<$dryA+K&&9HTiLjd$Xf`oq5PYsSI27sa@|T3F2#BE6FFo*Ui}a z{6c3n@@d}f{3e|C^Wl=^fs?E(lg_6Vg4Tw^N8VU_tri&toV(E2d;JFG(QJb%U!sQ6 zljx#$;}v~^Z%V4`Bo(g?nqol{;xIW=7p?E zobCc`v0ySY09G9|JPNGYu;t7U{CzfMPAVM@PM<)(BWGx+v!~HO@=V}4C&xFkEt!uG z*ncG)e;bg0C@cJA(a%Fekva$RZ{C8Qx5I5#sHi^q(WqZ|Y4*`xe^49Y3U#-6;n??3 zMm)8EekX*2QIWpu+$&v2s9gCD-BQx<@&OW?uzi(H7B}S^)B_y^solQvWzlGBf)|0~XW{ngJXfE6 zZC;sP#Y+H{Q8X(cq=Ro*Kvb?}HN!0MlI!@O0I#P2ST+cxJoAE5;e@!;zHQAu_6=PG&=vZ3Ku>}(sp}c=nRbjYZI#~f=1=Q>o@RvI0yovp58hD!9vJ{2e(rE}h94pF z@u4X2x)Y2OLvf1vH9J+mQGUJXL-QEEAJxRu#)4n)l(&Y{y67Cd(ocNARocHS_|XpQ zD*>u6^Dg%9kpZAjd}E~oWH5Unwk)m)3XtCu0C_5)8sMgOjRnUKv8hZ=OA5I`Nqj2N zFN;Lv8PS!Xa*v8Cp9`KbI{(>lyed=!_?;ArVaUIIF|M?sLO@nR1$WxKL#e&|vF|?I z)H-Z|L+~oHJRUUn<@mUKoWlMr$oQNBP80~r{2G9Np$xt%WuB^q2}e1>{Y48ehjSl1 z7s(xa?ZQtU0pIVHxjd8cAC#8O0OSVQY~@&fDHQBBznsIl;HEN=45RjrDI2H}vOt(T||n`A>jUjLt7*5AOVZ!L&QSaFZF2 zTc9(1j!iop<;J4iTANr7@1Nyf{ZqidHRr==*WYV9IVs%CP6Zq`zB~qNTs$@GM(;?A zZzPVN^ya50(Gb$M-h>JnhftLd3a-=+p}D;!)laKAZ4rpFo@ZI!&0^5R_xzUrz09;Y z~A9)av;>!0EV+@2!Qg$$T1!xZo za{NF(PI>f*u_pq}IjR?N=-C7PR7=a-YK_EQrP@Gv-5c78E(3JCikTZ}M| z6OjsI$n6q?U;*>X6%@LpmK30leo?5W7>6rp6%TUT#2^UfxwagwE&=jjLO6e{xW5S_ z)?c;oBJ#{rTn^5+<|DfO<`tl>Wr54DV|%8qo%>4}Cpf={wC|Ut2gKh3&E;+LTU`R= z!8Aq4A(|DS`sjt-N=zT?FU>B=zdu zM+P9d9XQLY<0|(LaIH8V{N`#ye2YE z%=U+F@_oTQHT8?g_c6H6>%%p;lSM3)lt=9`VJ1!_zIRdq>aQzjoV#DM0+H%c?b&|D z8lH=?e|L7Q{2TNinVjzd6v;83zv9g<%b;;07&UR4l5|Lan{ zumT9%UsW+yNZUCEad>^$k(ss(=CRt--X2_BvZQ;tNhx0LQW78A zn2j7hi?Cf$;Pn8ScHV>;-tI|a%VppCCgn%W0T zO8o3b8$YWgEhswb03gf|Xg7Z3PH5DCK+($*wE!LX*eM|A_t>Okx9i3_O%q~K8IK~E z{LASsbP7aMfVTV?;B!ZF@B;89wB@ZM`_TLU=XFH;BiU!_>;lv0m4SvZ^7Yd|+%9{k zfXrqOmd1q?u{-~)O?3X&s#HX5AVhh#+nQ*d<5m@*z5bwqHhXc?g>38+pja@(+>E%( zit(Dq{aJ@5WQR3L6_Cy!v*>NL)!?PTzM@dz%ln1?lP^Y>uTx+GDDe8WI=^T)Yuf@+ zc=;rfTwiIAu&1|Ow$A^AQb7Kt_Uwu!x|z1Wf+C(5RBM+2Cbow6f0vtVEaU!; zxG%P}?aVp_tQ62XNzpcw>36MN0+m#6#UtZquTjGG;duJc=p)tT8V&~KYN+UFRt zoV$-PlF&tzD8Q)u8yR_P!l@%&fZxi%>5e*}ojcP7cpGx~&)xmu<(^OUhs&@WpYIVSq zQUUt@XO#=S3YZrvV|u~0J^&y@luvAfo5Tp~RV!Vl)D+kw0-;yXMn4t-*9o%K0RRF1 z4BI)J7~31G{ew|^m!0JVRbZJ&TzTI$ZYfm>M-_yp_YGEBkd(tSdj9( zhI0HemV;ni2+qkCGdvVbvIGFqv$9RAATR%fr2EK7iGHa>Q%7&Fs6$DL_MQmX@}-}s zAr+mCJSh1SF-vcBst^h1A2{%ys^GGNP*#BYo5P_F#dK+93OzV*zvjrp)m)xFq!%c~ zF0LhUw2yL=1rAp^^5~hTR|Aum5f!qzPaTryr7=_k_aRR{w%ODcBB?zE5auz&>|=g| zYoGnK@u4gqC6SMl_=IQRG@DPxE{~o9)S-N?E98^iTT+ke_jn@r2etn%pz;)e!k(p9 zr6Wj>M(X_M;>ox33rV?W@VgPVT}0Cggmix4dMWi7V|KYlL?Pt=3#fddNM!~9nP_K! zI=>3Xd}ToQXpRrb#|7*!48i<^~o{PZq zo>)~A+V(W2up$Q z#UTjZ0|1Vf!tsJ3&MWe&+~COL!}q!TvF1M5vI?vV%_lg{2E)e(Si%q5_8?k8*dUn3U${j?cb zMywfD&;%=BdB1z()hQ5X0SG);Afa_Q8y)HyEikz53)XR3cqSb9dg*Aw>f-DapkCz# zoSW^e{j9X>70%bdB-Z0WueSw#X8^Iz{>LkK{`nC+YUc+(+6^ARW;;1@(N1oOT~a#i z)0#fuEH5U-3Rn05I}ZSeGCPjcmLld!BhY*E#|rz=ULMMETR*qo?KZ2x*^%AJVz2X* zeSBCMFN518+j04Ip1LB)4LDfI#fhcuP7DCDI!`6Q^D2PWRRJppxgX98mnU~Au@#`6 zqb)+qabJsimg&1nh{*W@cy8}P(q{mOA-L-ER|J-qJpSY&gpVy^JL~7;r^{2W0CoLx zQZFvI&`Hs(YdFVP!_X_JD^I6O0EnNgBj*T;_FC-dou3lO0*@}VtN;!E5-6M+n+9$F zIxQb?{s&l5{#OP(Kjp&H=?n&VjI;kk2%@&00E%*RNP9pjYPvC;qkj^*=(Ia7SAcqN z;*xJ$>iu`+EbLR@E0>P4NJu@v(Yjw-&j29&Ms=ny04}YC3&%~tirx9&)pdTY8q>p} zPSykMemz7Z(nZEtk4X65N4DENvessyA8cJ~)HkpmDFBUe_P+%ombWEaXBUZM-tBSl z{XjmV+fPdY+Q73gvOckSu>U=6;N>3qMzX+l4kDizNeGX43XXzZ8>|KZh|UMn!?kGc z26IC6N%w4{IpBCEvGS&0tRNo;T{#wbhpVRmZ6U_VDo=1R+JegZ52y-``u!yMS@mt( zky8G@pLUQ(Xj+|L-b#$w`Q<+lb)8?k1;oQ!A|7-P`EEu0RTQxXPz)@m4Gt=HYzKhN zDlmMLR`tzj$aj|^PA!VgZ>y7<&ko360qRTI!<+pP>T}Y;R9;wvt1MP~tlp!u#oKIh z)HZAix|I!(qs@~PT;+xh{A3`R-_gH|`35e=ooyNl(7xo7&}(_DWeI+4X=h`$nvIdG z4Si#yx;(Yl34lBRh}vViJ|VToXz+`9y>|u;NoAxjs|e`7j5K-kOkOFLm0VYr*-nIb z%DV;SkY%gW*e;{IQD<+F+sF6ezc=Lw4v~0-a+~PWYa!O6bruE#4Lyc~K4GhsXWAyjExWco3;v=4v;= zskN6!IV#q>uzJveS)@@ z!*jM?Z0%eGsj|i28*F`g*uB5Xw{MyU56Kc`$*6A`Z1cf;HP7;X-`0nV9bE4BTr;VB5FrA$tT+$DQ9gL08sICRB&*cB!r@rG zbx2u57r1MR9XooJo3>CfuVNkln0KqAA0}feU$fz2;BCHfGLogmo92w!^+BvmfL0f z*1u$OxmLxzK3F@iF|7CGZSln#*Urf>xyPGLA)~YN7BWD2j{@zG!(FtC0GX#l2vy|$ zyareB-(2CtH|e%AZlz}>@l=+{GyY4=L=N=KJIDsDg*cEGDbz#NRLRE~T>nVE&3*Eg z3Ky0N~5SXMdt;t}4YwmT~`fC`fk!_?Ey`ZqO4Ih6w+ zF4N?@TBOSA*jGk>3&+(}Bg(++ruI2AMo^66690i0ox&@B9~FIE5V8(?rM4tCcc0F3p*x_H2ri~Q-9IH> z+PjR<;JQV7%RM19{cHt@*`xNm-!2tk3J{3c9IPDZ*&Iw^F%z{TO#voRTVG zU#}6|y25dedAtgO)w227+V)ygQ^0f^8;z0zU?_qPDqggHiM3h8~E2-Ib%tVICEI-UMuMxQE6 z8@TMt=$M-xa1{j-w!0~Qoqau{$-_AyIOsn)-8J#Toh23k7~WBPT35*$gOT(4-Iz>T zZUrYlA#L04#%4XNYby~xA|^cxrI0)CjJQ6Vz4f>nJ-hf!)gsQ~!q4T*Y$%x{ZNg|A zq(0qtPgjVnjI6u15#;pU1F~OkW}&>OQ?Z`frZ)NqxGfQ@Nw|o3!ON74Z6(h!P3xM! z@{NHQPvVY_qP&BAe3t_Wj+|@$ITQq3kAicU_WrP^#IHQH84-CU_# zt4~k?1&Ha2jefE0_hV3)%!J~2&REg%IT5amxdsxvNBfek=o>snj-juw(0yjImRb!8 zAnDkidmhu}0dy$AarGCl+pZ~iYlWBJ`u@O)7x>^~-6^rLE46>$#XQ>Ui8ow>5bh_d zWr6l{JM^cqf7O>XHdd`Zu(8La2W&tfS>j^qT^ddnIzaCyvu?be%B)E4X-lD(TgXGW z3DNZ^o<42Q#aBBQ&|+pVKEFL8=*L|&ity0fP>bI+cj}@1NWi^XkDxpZHRhEr|1cuJ zTWU4T2f@Tox<(88uBP(yQD(OBC*H+5;dIrVD>*;wFX?KFxDFSr+xBGRTepD=gC5~} z%UK$_)~+jt9e3wHsebAMe6=Kuzxt36^#L}Q24vA;rDKZmmvW>NJD)jcP*OBXWGe@yWBT3Qa{P?rrGe$&i*+tl zD3-Q^X7%bdY%y=|3z#=hv@2ulxhUvGXF;!#tkfv21um_X29uLBjYxms_ndJ?*ITE{mkHJgE(d#1nHVVbIJ3V6(L z@m|dR0N2x5Sj4X8fETSge9=jd!s1A8OzVo=f}8v)g&aGs9CwkC(AJ(9K)3gN$Y01M zHNMdRCbc+n7?x{nl*pAHdp`%*c~jS;&7)dvvKf3s3@U-O#P(Ly;MA`Ml>O195I#h5 znhCJ`C~D5dbk}lfRi!aTtf`qUbvc#kqUU2f7%N{Ik@lsO7oZ|~1_Y3JW-cz`j9ic8fYz7{V_ve?t1>d5 z$D2;+D``w44V{Gwxh947ff)z=@nli}fx706uz3g1wx<28x5DOFbe`Ivkrs@yZ&m{= ztw!WPayydf)gKtq=6K*|?MvXX%J~~gP2SUoEm?%#CZr%Fd_H%q-SVJ8^VQj(0|(^s z9;+Co<-!0VoRP?v6)IW?PI!nCSbS!!&)#e}S9Q2WYXW2JJ z45zHsK}o28B`UC{4|@IK&hXL@}#+blU9^0fEK3%}RX_O{FLKYKVZ@LOF8SXiht zF2CxH724B)dh2W2mzy|w(5(ePA80KkHwHzSX85s;!iAr6uKQL!Pnn%w11w@~=hxs0 zgR&`s433gP6yfW$_*MVg&tTV7A;h`2VbQ4CtGF`u_2Mz%+vz={G>BCXxZq$F!c9(L zoBD|^d=R#UI}JrC4Q9(|q<}0Z3^w)vO*@lV@yLoKgInq}NG6LGg1G63oC;|#WbWn3 zdzv<+c1^0jKy9ao>k(lj1*LHj*KGP-q+7Z-ID%4oF4{iGed2Z8EY%O6#k&Nl^$bhA zumo^BPkXITsW5|$NiRmVmy$UG!ZJI z3)Tzzkh2IbXYp9juKWlm`_Ew9763gwwor_U7D0=H$?i}UDNaX0l6_Lw8rS%f4cp7`&Xe5KNbW7L(!Y5XEDKi8dOunHjzv8ABi9cyHL@;!(#BCD`G>Rc%j`61 zsohkW){3XdmHu>sTpv-VfZDc>+p%N)LpeSohLC5fI}Sm2@S;ba8{#t6C5iFkDKp?b z!q$#4#ndT6z1BcWphkA?AdRuSV7gthe@oeldZCkcscU-l*&;UQLWAV-b@1*7VmjR5 z+9Uee3rS2Sk;;u8X6EaC9 zPVKL&{gfBgdzWl%! zu`OZlZP%Uh+3XS<524#y48Uq8ECZd8&OUEFmK2?!Td-D=Gyz~D6&>)~cAY8b4^8er z6T9!enPG~hC~^PN<=`eI8MV&BaY<`UQf!UWvc7i9Xd%;WBTrKOY*6IcS`H?xX5=yJ?=)UdUI&_VM`b@&~_s3uqs=fjic;hoq z(p_xKG$d?fAYCYfWm%$ttTDAP7Iv8M084j||63QOl#m3k9pa#^@ju()q!u(b}QbR#(d zw2iL%IS&Nl`vQA1cd%qjtv0f;Ca-0f9&31-2oU9c2X;h>`7ll_u=vXat!Ni}rZ+C< zW*EiweDNH5(RQgWSKthR@~$LY964hHS8h>rs3iDstXV7I43)VMMAlDmEx^YtiMS=U zDbCB(_IpzbDz2>#IwR?F%zbLV2kJ{9fP>M^e#(AKkF8Uqw-X9rdWbV3>NP+m8#BbF z`nRrXwjPF~rq|$~vEjC;c6s8w=wq?^oBV=t^@^MB&#<+JkSj9hPqc}*sj!GkW8Ax<- z`(3B+gKtR208fL28RplqB4eCJr*=PQ@2wK7o~Sxfr3&u5MD4zF`tjw11I8v;$rLJY z95b&pU*?~D8f^~C{j}24ljMBAWZTfYA0z?_;WT7B0r%=isA*+A1~|b+*e=U*I4HE@ ze%VwIsV!bldJ#Ubd4Y$QMBd^s-q((Obn%Cq**Gj_d&9o3G1wi{?Ucd2?uLEMXN}KuPwf66uJ(`8(uAM)NoAZ?s_iVB+bkM00 zS6gd0kesxeBV5I?#z%JXC1b|BECyU*#s2KT?DLe1Q>+AA6+kxycn2|7PKlp3_)&k) zyv-{!8&4ogdv7z)OHN&1TqYB~BldE^J&sXoSOOn)WvoPBdj5w$zG&=V1TS*&D=h(o~Li*sPhTf`xpk(?X2)MZHemsF{S3M7T&U19J zFiwJrH)>>SWLG_VF~=B13`!Z{@ET-2$#SIsxU(UGSLj*LkjhmIH~D3$TTt*kAQYbu zSCJJ(>KKk~i*>*ucIY=FFWz=bil&Y$pUB7=rbnE*5%RFX0uqv@fFMN)PB%U(LW^gR zvmAZ=r}yT|l;d{Ypvn<9ZfPry4fu`(A5{apug$}8BBra8)@O}O`Er44KvQAN7n2TC z4vICi`4bg-{7>S$P=*NOsj1Vy$_65;bc*}WIh0J-T#H47b>miA<7 zNQ8|PNrNzp>ox(-}asH^9`;!A<3+|fJ(2BrhSRvItulh&^1{L(Mh&KEOHQ19+;}qgF$3*Iv8aUyLhL8xllwn~$OCXE5H;G? z{#2)Hwu=!8?F;HmpE?giQ{;NidGI*kTOcOIQJO`M;Ki8+wX_R3^^$O+G$%>y6@zc; z-$ansrf;(=En9sc3xAeBK! zzEn<54Urr9Y0gWcZrz!_vvlN_n!5v}EOctDYlN>*qZfj~Z<|{wWd?dWPzveuNpn#)M?i~>GZB(=Jr;L#O zW#hhK(5Gf7XKGUb#Pg@A%=@NymbbZT0e1}fItj!Ji;NmH$<0jqag&HQ zVIfQUq?G~8O$j1|o=WDu5>8lGAz~vi-?~n9F*Zy8s!_VMCkCd}Kr7!Jwoh-t+mmf+ zt#((E!`(jyVRtlClo<1-|9zJ19s{PB=XqBYG&0)@HcH|ZOw29T<3*Q24$6HFBP!>? z%^rXw!l#t5K3h^2S=#Xmn7@>FNKPi`-^87@TD!i6+D2eQ5A#p{dFgN$0U;`tRTsz@ zPV3A>e?MFbxZXP1o#B1rjIfHezJJGZIUbW9X1%qbeV_eAMBwfFt~%dW!)YxGv(n4c z+C^XHyHe%eU9pQ@VWh*_-jWL=!~dqCMU-$`iY2YsbpD*>-odf{3;*mlY*W5N*fps^ z<0*SakM(@5ELRGW%;LE{k>PlqM_BX$9EElbBCPe^Ya*@6sU!XtWaF!zp%=RP`mNw3 zJ9ImhjuqA&+x*x=Z2Dma#HAc`h=19PVRQn!#|5AiWuBQS^l<-VXpW}rO{>w^pm0tQ z)_B*Pj#3bVrWGXch(xb+w$%UcwW(tF%QbOh55&n-+-pzbGS&C{Lhlo~XgD$iv+jNT zRQrbTdctqyrC*(#ebA3<$+a5XR>f@4p#yWG%|hnLS$;BLv&i0Inwyi8ug0H{6N&wz zQ`_)cjIg==@iH|G%Qpiu6CH8m*jy(-YKh?BGO?Za{YdcXd^y5(%8-RTUR5x;7RZko zZfL2GdPQp$C>i&}mN+7!F-*Dr>&c2G%nr`uU?o6*Sbjs+6 z1$hvzkdGFk75Xnwenzgi6A>U5L*I2$oIb4Y+vfo%svIu$KJ^Cb*)GM-{at-G$=9dj zpeZo=KbsBNo@?qq*J%?e2ZXz2CmdtLqXZGORq~D;OQ`$2OD?8nZq!c7N4xQt{7@m%8k)$(IEyH22SV`g-R;F0AbtuddWbz7}xG4!qx3rEA-)QyF2G*`Qg zx)S>hFr>}uZgrVmM>JR5Q2>fpgPDKlOuY;-9mCyYZt5&BKkkJS?M|#ecR+oC!*ltx zJpExV2KA5#F4ck`D3Gp(6f-|aF8Pi?HQyW6)cHlCUg84A>@8!$gX%@8Fj?exT#Oe9 zMUh`OPc6ozPOwC->j%rkz+?Pfcxd`HaS!m`6luM|9L4gI1a|63?M902{}Y3l^l5aB z{rjjiV(R{U#vqE|^NyQLRJBbFtj_$-^m&6Z13*m7;0&VJ%}`ZNa~#B8aUt6e>E!*^ zmA`)xunKkR)FHd;s&$@UthZoN>2sunsr!RTzpytO16VU5;iR*_k6*Rhj*H2$zPZ(T z_a3vK5>C(^=geUO~-*X?vAQ#H7n9hlCRy{96)2{z`-;f68z07ROn2u+OI~9M(R= zu`tXXD|V^NC1FE)m4_Df9&wnJPG&_-gAPqM`E0F=+La7|i|4gr`4)yaS^~ zy+;p5pxbTizqmu&fud>ljRNqOFto=5Usxj<>-9T+0Y-^BrG9Y103X5mWSR21`S(M+ zBH_|uqA9Tqi+9i|-^|54a-##yDF#TrKoe%AZOp59BeOV8`d_)K1)zu|$MNv+uz`Yo zxI0gnfhquLok8U{z+Rcfz1Sn*lJGMv8wN_`oFtzyY10v(5-Eb!oRL+*_jh`b$#fY3 zv9o0IVfFQkkcSs_V|@Og$IP}T>Qvcg6e>_!bBBMWanR*X?&mZM3`Z@ViNLdJ{`!M| zuEc;{GUO~k5W$3A^yBJ>wWVC6U%b~zSx1~fRXA8m!auQZuR=al9%$Va7jbv}*^`CB ze7uCCSO3nIpYb~zPW@<#LkFl4!N)$;h|&@5aO>8LIX(#1<6HfDH59*D|HD9AYy^vk zIy3B|%Xsn`p?m#%xo9G6Qw44);FM$3{e8isOh7X(p8;E~tC9Tu+=3Tv%K8(ToN{pZ z#9QNx-M$2OTv(YUph0+RDE0gyF0IaWjsfczAUAMV6gm5Jm3ti$_H7p~h_AGO_3%)3 zIRXDy)4Iub&(;*BU@N2Ub0&uThv?V0*!me=V!#g+1kLw8<-#Afgz@eDN-#zUdy3uK z-%0$xPik+uw?e^J{wC~5Fgk%#VM;LQ2qvAU)V!~nbCgFh(G@`)ej$+d>_Y^`z-6vg`-D zYLsPuO|2j)h+JGa%3#vT9vu!P?5m*4(WD~Hmp=_9#elQxi5?KKKa9SB4Fa3ko^_u1 zyFib9M)Uu?YkxM+{syyoE4TLp0v1GEy0BY_+OuVm0ZSQXW&d-${SDLAl7g|Bq~W-@ z6=dUi1Xnw}#tH=r>GO^Fy6T6KO^aJ1Vwj5M?99_9_V^(i9{Zk)2SNdFaD->22(z-K zYe!fQj*{sswzI4opCw^H8d`63L8?DdsJOkWTh6st2hA@<7kB$%igl$j$E2D$gTsVO zPRMnrBnbr&1Q6)*VPmtd|9ZHB43oGtoN-JC`|B-QFM1b zZTv0(OGheXj9l3=MONZ}Z$sZNfsJ)`Z6F)*5Ye-0g$;_MD^W2hocR`n*uuVQQ24op z?!84epIQ+?KrmOl_!$@qG9dn_5;WMvuxgqYr^>XdijLRpI?XTzm4YGw z+-9^LrVV;f9-nU|UKw1LAL`Urx>-B8aeH8Rp;Lwj^7Fgaj#6;FdQh+9I}uy~@Bnu& z1#`-?w?OoPKvWEmBu2HqAbrWRCxJa8#{wa3cwxz~f5 z^nH*gU(zl3eQZ98ZB~IRvZc5mb4U^mQd{rJp5pJL@aVxM_}{n$!^Re0XS$5CGn}Br z7W&4aELw2^@8E+F+wn%;(yAYO^Q=OcV7h+}`gY-HBF+BK09Yje(_=fp@cOLtpGsy5 zi`B6D+nj>F1m^?i-^?0W)^+7DUV^Kwxi4QMEccZEuZK9Q#+qKSs}M<+pveRMOA(Mc z&UC#h$*$)2-W`?cTJx0EBS$nuTgSet_jKPg?XF|0-XGUY-H?9rsAQT=YMYLydig-Cz7v=9lh&m?{|uHdm{H zDG=|Dj--fYFq2rCy=tVv4T|`9z1Vh)cLbF>&7k`G79vO6+)oA)ZKF@gQNjyKM<`GT z4g#avOb}NI8ZFBLw(*!6HWe>jD3D&jyuE>dO$_`}}R}T&wprg!vE$G8x9? zbD%7+`Xd{lqB>f?9&tjUr0Xr{a{Y7U-?7TS2JqQCG<5tYG_`=;c|A%9BPi-}a0YMW z69x8@_;sHkPL2vLfKjGP+?{h(JYJy0>g|ib^q5_PRXucG{U@fS0Mo@VyGF4mLDR1t zIj6xnrsozZ7efk>Y@ZeYDxa<~4n>v;@&L^)?BuR{DVBQyAg>IF~{?E(q#a_IjB z9m6N>vJDTle{nQh4UwXKZz}q~#&DHj25r651Bh35a0{HS z1wcZ1{!aR%9H0b%l?vt`ZDpl{~c})@FFztK_bu=qon8Cro zy7AD>;-B}`rx)!xjT8T&4>DfJ06*4}lHWPxjXfntZ zc2)9`)b&JT@haOG6-t*iegJ0-_?l*) z(+@L&kRMC@YukINBskudD7!KM-Z0!=w_kiT7u&l8nwOzN)CGGRb+<%r)5A&Z`zxs)o_?@5^ojt8m0t& z`ri`>*$ukvSE+9Nc_>iZH{-zozT-}5D|OlDy*O|B&L0Y#_+#=zgHDeb6o1azvb`^o z0rI{kT;A_qH$cx1Yy<~11he0xfbKrEN;l9{M%hOVwls_z*e@v9;CKSCcDeB$2*>es z=10F2R7-?*=;3q25|IQVFV#u~Ed;$FlLUN)`_+GhM}&lMl#t!4-esF?!bhkkI19{I zOwu1jK_|2{I@gWe6$$o*-KZ?Qs@Cydd9;7U0Hi%SpbEzW-zikRW9n)BucbE$8^QR2 zzkz|)4@Lxe4YN?g$`T;@X+?=!WR!KJ z`7@6K2zw_gP1T#(CGaTOKFi~inrAO?m{G{f{^DRUl-k%_hLeK9~s7n zrtjPSaCku30Jx&TdxU5oxdITJl{vdkO=aY%qOW!XK&6y7jWoz@Nsss|UGvbIx$e8T z090?9rj!7XS>l~B$wGYiqgm0^o!hYf0FNU_$y(&g(0E7VIUbQ7f||jLCH0Xfk*$N7 z-qc_#`p3Z&-mQmS`$vph2(_EPI%T-}z0@Xbfs-0TzN^VnO}&1SgHmX+<*_Ux*E*I7 zN5NPUjhL@m(G4GF>^x&bDEx_537aKg@6T$C_Df79O zo`v@2ccNceKGaC!4Tm_u)107w{{0vs_h;OTN0mMd>2Ya>)3-8*o3KIu)Fqh z%jv6~cKf&Vqj(dh0PFhCT17otQRMqal5vk{uiq+1-XDUHDnmeU_d*VyVzxS+tN%G> z1>jXj*n%2ZK0p@)2rT}GDoJk!jMsubm`^6*S$bOb8X_>7R!H1 zZ>Dqn0>7Q{3q<_TFO|J5xY3bYoKevdtPPgfzOVvGJ?X^vQ4~=LMb&l)f@@W;ZI~fW`wUI&4Msp56XF zSkJA-1b8AxFZWm9)##Nb2*}q-I!`MRh6yTJds<$IQM}2zFa6}#>D@9!&0u~2O1Q`G@np1SQ#>z zJ#|$O?RH2rzdDkbLOkz0!Mp-a+>>UWx||<&HWW<$<&~z4Ju0_l#iXU7?Li4$uap3G zL)PTp$yViuB0Z8$Fo_8_bYktEiR|~CMO{3DncS91$TSwBe<=d6R0)0=7>Nm#mP}G^ zZ8Kowu$V4k#o&zSMmwL#e0^JYE*G7FF1qaCdqwKNxxvmKGB~AZc%#I$Ad;`ZK}i(| z;+WczS0KGn8VX5eBF(UL1w8b~qKV*?{W7r-jDD6Mz7-gb(Y z>4wT?I4trlWx#Hi$RYfeB$iOQM3P)_zj1K)T4qb+sKw(~fUYf|3oXf+50W2i#gO+B z7!t7Sa~(+Wvu0u;_eH|jG^1O+2RbgJ&%d#}`8qg<{s?svUM1DR`2!oRmxjQ?8{Tlt@bkDk?#L(qc$-zPw9;a+mka)bZbx zc9t7dTNb|&m;IE=8af`~X5Doqt%^98ttJ$o9NliV&a>)!UM}aBO>svodH{Px2%wx2=2LjxWBu8I z8@dT~5oN8guZ;9~qGmt*)htwS zv9vV3m4hza#Iurv3Ia+UHm5nVSk+q^w3&~CG-E_BbwOb%bOLfp=kUXXDk;cE^p3i* z{kszpTMX}gZ`Op{en5aoA6UYi?2_igo_7wj14+h(NfV=HuIq^wom-%({PAcexHeRbmv}R95=6V&3eO*0 zExFnD8Ncu7QNHyw6Ez=|eByn4!5cP+XjN?M1r>*Z2JE_QZY2rU4=Y@K*uKrf`&++9 z+0wITux@5_A)($jk|fAjshwUS%cJqyHq0UfBK$fG9nReW8==y=zX16R zC(}=>J)Y`gMFdf{*-_B?ZWy_8X%V`PfViEDr9A^7{ZRxwaJc0tfVOyJJ)cCu@!aBH zb={@naZ(+e`th=12?zd9r{#-43<~>6diC4G3S3TC0{5bJGYjfdBO%1+`#yVtX6@x zJ}()_f302)F)Ehl(o2BX!Q)}s<~;KBiZ+{e!SIp=uF-rAz|Yy+R1EB->Xc_x4H7WQ zE3u{pS4fQ-aJHfQDn`RkyXkm=SMb_=*)g`6tRP9>B8xURw;R4Q`pJ0>!@dqoReLlX zx*&;Kh%n^8e2vN7S4IsE=lCcTkPS;Hk8x4nTLKM!=;n#5PP-o0gvaJPYX~9;ow1?eMOS=V%xSG?kXQN?=(~v?8Y%1MS2*8OP?f^?J1TpSZVS{ zfjZ%wXpEs6nX@mIFDD~&CBjj1umIm5reu-@A;sH_b~9c>ki9_m6%XKhonh9V0mCSj zV(+=;NoedOE#?q zkhF+qh*-CpvMd$F>RgBz5>ekW>HP#goV98tTuW%#%5MOxC#E>MjcOPZ!r~QtkqJx= z;GWo~TIpkgX7QB?%<}AIvwi=Q?RKljE&&fF{@my&Nd-=IEEqrnD?sQc{uY2!U=Gr9w?J0rgxJ^oHSfeE(Qs%13 z_SUNp^|bDzxjav7Yg*q^Qof#ir?_1eMo2!Qt9>jJhDi*|d)7ME@J0gE69OBBo|XBl zB+Q{lB_T(&XtW|}uo)y6n-Y!wHg+V6QtdiUUbL$#aRLjT9xN;8C77$9W~2f_Pz99% zw4jo>7xq$@g6g&J#1VoSn0>C!w@jVC?d7z%QtD4m%3i#m+K{T{fVu9TfcqP_m2W(d z_tT1;7p>x{U8n1Aym2)_$mp50&MEf<@cntan+`fGfj=U#r#uLqc#S_o?>ZS#SoZg> z;u%BBW~VgiHrsj57W?yK@kK6&%kvP%_tvQM2bB4l<@8pIV~vl=035PE*ZTAem|bD7 zD%DXIfjy>lw@;ixJhH*^2uN+&jif)p47nWWtT)dW4`Y0>Iv~yu~XM$V$ zTM)n@p$PRUk}$dby?5azIcTP-ow19yV90$j$8VV1Zq0k?4$Et-a|Z@8)`No%t`n5^ zsPiGYd4sqCR!iMQH-0AlzVg#$J~_ zzmd$+Qf8*q-tS0}W_!jXn#r2|ViFfy#{D{8AAb@2kRuSIe$98>*TK&+?J2dLV6uk) z2y^z<9`yP>_t)takAFnML2kbsEzbOo_>nR_>lCL4H3#KQ6eL(7mlNxDrHAVKF3&ws zswGbY<&+mv5UhQ8M5^-Jp=#!W^4qH}-;d2XEji#j?ewV)$XO5~f_6wYrAC*( z4yIsNL!KK@x6|u4HwXEuZS4(jV-2qLlif&iN{<3zHrao|ec56y&Q^HSML(h?3@Qi7 z6>UJst++YF*p&c1E0yH68ZnMdC!H6hVu#;(voNvJtf+v$ThdFo$>S_sw{MN?sy+3G z`tp^e^V7~2;~@e!;dliO4rVF%lhV9JAhw4ymy9bbVHGM8L)qI6`iy=bgvxMRD1SD0 zfl#W=W}2WVF-Fzvg|+M(GpTccO5_=v%-tUAT1uvMVaf+)3OsR?2qU%a|K>EwYvQJ} z07NBty_vIO%k40o|`OeNIf~EA{k$SV1SZ@zohw*#Dx5(7XMCZqTT5CmVptHko z`rBdC+$0o0mb3%zHvlM!2AG5wlJjDz7%YPj;mFZ;Z;DG~rl?%JD(h-2c?8@b!Tf@Lw(*Hx926|#kLf&7VwCdzx%t1Hs1 zI#;YILC(mg4;>W#Mj>@BY0m_pGV)E?)#TNG<#n&op!63oer|eDrJtubfn=P-61Ksl zd@%irKLR;Jt>+V(uB?a^cR@-OOky*jBHVV$x;j?h8J4m(x|AbjgwLY;dZ5|+)4LbJ z^a5+z3zDDXa(W5q4^51n#S^9){w*?3CWX9ig@b>5us}vN)VPQAFI1s_@+My z7!`Np9n4I{vvD}=uEOcB_Gm*4WQKraJf*i$O1TkWpbomP0xJGc!KccIq5ZvX#4{#v ziikkXU%Ht7y%I*PjcY#I0T>GeuiTz{(r^2!{k+R&pA0#I1=8O>X^DCQC4T1&_tE%w z3bnQ2x%m<~8re(~XOwq#xExyw$Wy4{UvU$!7{iK6r{S*3>4=AP6Vmp{Iy9D%b}3or z<{|gaA;l_`X%%Pb&pz= zhPbH7e>siusH72BqswE6_%dyCRO2CUHslB!qyjDC!mQU)p#a#hk#D6HY=gD^GKI|> z`nRSUw*pwl3WSHm+Tp;g8&1*z>D$(y{?N#TrDWnp?$T%c$Zs4c!ypb9%@u(U=}2bu z{HBI!q!3K`bNxetQE5-HP_!fg+^d385bKgwAFa7{0De|G*UU}a>DN%;Yd8{nJ*iFLRbMo+iSDK@&Or$8T z(yAL@wfI!=EO;f-O146mL9!`WIA6xiqexpGKxk~0=Br*r^zt%+l_3W$x8K^3NSuKp z%Bb~TVU$$ra@Q?v{|~>S=^lq%%LSINm8QDhN?^x!X|JuRszGV{-dx>05G9_x@KnTn zGy$4UE+B>I!%Hp-#Y(R^{&TF^4lK7%w2=(m|MEuQw;ukCR2JLQM|Q?bBk70ud()-c z$e6>{DgK7N^Uh5|?uNtNR{dH$FU^137PjONyv4d?QB5V#JL^&8H(Bu2R%<6`ZZ8h{ zgU_0q>?!)RuzV3k?MjU)S@N?cvO!DOAhl3SSo=!No%iJA$FgGeJizc-pm)u(O~DP= zetlh!R`o*PFr}kxgE=07%}rku$1I0;8vJKroBF(ycjFvQOgIG=?A0uu(M0 zv`P?lwJ*R|@=^vyEKKh4^G@@N ztP}9BBX$o1(vEQ*E9~anf z2XK_&yV}}m;7Nu zEyWri32F2D9yrN!vPT*|{IQ!)ZR8M%9V(j6ADO|8%!p~m3+X^lw9!rmHEDYwQ9^yF zIf|YhZB-3@QmpE3P%1RJS8%^Yc8}uOul86@lCX{1g;vjT-+uOOXevKe{#~l&?&sb_ zlwuc}lUs`L7r(R9B%oBf$PhrIPd^1joj|pUQIXR=; zKv#P2zh(HxlCEo`xBh&E^q&}nyKMWy3r*xaZ)P)Y#Bh)op229IP0hd2FlllW^4_qN zf66b3DAQcEbOiN1ECe$B%x&&DV&Hf52(jbL*yOwcj<3&)uO7)GTi+J!R$HG$h&Wi8 zsOJW>7}S-~#w-n@OzXc||G1h8E2QZpmS) zG}3>{`2E8LxM_#lFG$|9O}DP#EsL)ae12?l=TF1%&aSQxCxg3_+luWMJRli}3#-Q# zI448vfPaWhe*9LXcVT&3s)tP-)*f%}-XN|c-haiA(>)U1@kCqQ=E9r^m z_yELhl9&!kZBQa?DVPT8Uh-ob1Vr7>@4>&E{{5=Yiygp$BEwykh+Mx11Td^A{r=6Q zlR4|5-C+;Q{igoNkpWGL72C@eF2ya${NKSL!(UdJFX690qy6!){w<`xKEf2-V9Yf? zr3g5&wFvV`kz#hR{u`5@vOyL!@N&(Q&J-4(`A6znH47wxYP9)#W=rIKb0e!~ojWHm zC;3M~dVv`Br@5JudX3kl@W|5Ui&D7?tNDeeDa~7T`7|4*ZyMEwpp^&zm}nJ2+GdTA zB}N*PD7&{!qYhq&jfXtf$+m}_EX(uU!yE4n*Uc>co0kJ#SBrx&j~OBP%a3Z}IcKD$ z|ISJUh6jFE*}!X)!u-m|CXlL2QJFXgXp_S{#%_3>0%*)P3C{@x01MKxbb(?SDMsln z5(1wJjHzu2NR2v=m^}eLi*Ogi@9NSXB)P@ zw!<`tdejymtN~{WIsNzbgINKkwjr3o5306+=s-i&9#PIdzuC|?Jd^W!aT73k)ILT~ zn&r5Axq$DvKlzL}lJRs$0a0 zv8}tSC%@8`=+OOjrmIhZ25OxlLqJz29j6?}I4|;PtqDK^=f^Ts>DA)o9-1~iA_Om5 zlpO2_{101oYe{%t{0&?r_ls4Fk@Q#WzU$>Dfzb3z6EZN)td4g_4B)}*H-&iVu8c?Ip@=85WsqVx&1 zR#eINYzjRQH}hH;!HfPOT=X@q+t0T6WZ!$QbdLXX*UW2L)LFjB_a@`(m{^B9Dr#FQ z7AAz>nmCAR&N_S%n|I>Xy80z;XL$!Y;S`e@;WaJv)aN{rH}H?`E6xHBgL(U80L?u1 zMIh(FXT*)}M7i8GvZ;-7OZ7-!RdqmeeZG;xTk{Nz*Ak6jeyG~+h5tN9S~Fk6Eeyb-v(;GqDgT9yGpu|eJcU{)d9+@|629ZZ6&Mpg;4H~PR=1L8X zu+eWf0P_WWop=${n>ZfzWZO=cUOAwi@$;sEEn)CfAjlz&&@MY%1f?rrPvFcA!*lT9 zspjmUu6!LU;}F@%LgkR`m^8{e{MvN8fQHFl3&-7606=h%nk=gOY1#*=XNd7Z*W1JS zv$TZ6Kh@+7hc{P*QGN&!G8gVP4)pY7gfWP;8~Cfa?PbBQhRGi3kr7N9*?x|Qob z!U+I;G?JAR`v$#VwvZ0HAVquWh*wRsWO8kr;Fn>0_xldENo&6rI!W_+ZzC)}s$KQcJ~+;SYEYq%Zpa zz#f*3?H(R%_uXmOLFjQ;YUqdVBeSRWK{uDCRKn>A?ad9W4}&&{=x-aN$YtFj64Z3* z=B$iw7tip+t`B^FD2Xucqxy@_p6l1)FybG=f;kG(R!Eu~SOV(+SY7GxL+J!{G{#=3 z*L(ia=y`}ilYN9AajkwH(t00N*Ha~E1`u_e*n`_u>ZIUy{4Ye4VNOMRZvupXLgVm7 zcdCGTKAf(Od`=i6%Yy$GGaAh0^MdCW0@VgGiZm`lk_VyFJf~NOHK|dvERz9umJxtn zJIxt5xFSOs7eNNOFw%sLhjeds2f)g_Nv$*uprT&7mWKzo8$8&|WAaCN0+$%}IO3jE zV*Eu!t@8hG%GM%9MAmE^G=?Xm>Ii7)(93XmvuUVv{|NlMk;HGK-dAap?jQq~heJp@T!C++<(vB$@EqKjt@2fiicUwS}g2BWn0QfFX!DzwjKnox`Dy$rxPRsw+y@*DS6XE2Rp3dZu$D&vW`R$ma9@l7K%5Q(dQ*-@ z#Y6`Hp0t(Adm&57qZKKDd#Ct2^Mb2$F!q!)gN+;N&8=hMZT`liDE?0Pn}wc&_8@k3 z*1w02FWyq&G3xE&>)@6QKus+&CZC6c?}WlrT~35QDJR;7Vzu63vhs3f{q6q&p2^uS z71bjEDiM}P0e0lU)$phVIoAS+6b!#k@pJ99n`?s&+Uvu8>IA5O6S7E9X6>1c$fviFj}+krxxG z-fAx@CaR`mvEBht2Yt45?f{r5Y!z^wu9~OarIVYlfAwZ-SytwO)!U+Xp#pmz5SBV5 zX`HNr=X-FsLRugTe(*XCy%=2=oh{(f^SlB2JM^FECumWkhF%MWk3+wS&evg9-xC>% zTHhfv5BYjp2YxQ*MeApNYzXCV4PmJT3e7b+@HUn+@2S(*c<4jT-RU zlBC5sojV2%*eKd6}NYRuQ7m7;}nXhQPZ1k z%L;kYjl^jioK(;JB+@*SYfA~~RN7Sj^cEY6Xotl87Qn*aHsH9y0+tjEYr)sEDgI8p z;Ob}$S)N|f(EoyPHA{rd)zIUpH-_uwVN`}f@N!15S)m+Xp4zv~XA>VT%Ps#;rUnCtAS^hd&3)N>=bB;L!F`?*dn<->gp`UQkWcTvGt@ zAQAI((KJ90{cljl^MLfRfD5iR0mmo{SW+`Ig}W1Q-?f%sKyEvObr#(26Ae{i-DIIJu}Ork_D@=L;5&CX_OMaxZ-xcRiCn2orfLPqqmfCau@ z1;?Qlu++hz4$4#TW~wrUzbC+@ImmHn$g(xuJ`!>QEMbSsCBQQQHC0|4;OI!oxW&f* zAkq>-avTiZ);#ntgr%~o=HvYP=?wcwPUkIZB*OJH`>k#408_w>**kES{ z8#km5-tus#AyrcXha&;>15=>#gSirJL!a8npX!3|pe&3d$`uQa)@5`$V)>ht1#?q` zaI2}SD_xS&ge`q>^2R3aFYH!$+lR<5C@jKqBGTJ`FE~>@UsF;?0CY#k&DKW&b|6Ex zshL7Qj@x7QV?U;ISykum6}Vd@*If<*Q||V`%y%4^D$~R+aBJd}vN97{X58>MocKd- z{GS2;LX>BVjsI?73#IWt6%MU5{#qD+7HVBabhO`zIO~o8=uRF&H53!kx*Z0E_ayIN zS6{zVugAM|RQw_Ar4?6NRl5@0B@Pw&A`~8VB=x`0{=P6YX;&53&zg**ZEq+4pC<8N z50rqz$a|A7Pw=`IoSNDeoRY^+!sEacf2Uq>_YVwOAKBBWlivPSw0{QRY@HDx!9ahw`Ws z{niRF-EV_=S<0=|#(!V%h0^$Iwg2W;$^d0@8?ab!{6&{uJW?Bf11V5+FaMulkBb^#;%$OSfOp7`*cL2zQ&xrJ= zjp1>6*Og?HRt=jFc+*hZQzpRF2cZJ~ANbp{eo*%z;BqRuK9)B@t?UD?N5n<-0!05* z2JT7qwd465P!^_qni+-cObyTVg}5Ep+1>E}`@`pbhVWeu7Bg*23NPX4Qd4NkUn}QT=nZRra9MBszYWfbXh@C!Xm~Z# z_`{v#_RlZo|7!h7=Eh&C$vpy4p@2r=1%CId{BQKCMMQld#mw+Ky!8julW4=-d*E7~ zmJQ(XQ4h9rnS@{M8NVN0A=iz?1Xg+52A-@1h)HOT{}XU)YSauK#bF4IzlyB;^&Jp&A{v6I(KRKI z_BC{72;_Cbs3`$ez(ELDd!iS0N<&fqzCc9l1wllMf`tEJ=(M6Tv??Bb+3~25Xanyc zG{idP8E~5#5e3h-XejbaZ{-w*R0)P4*Lx!=!7!xtLuZ6QUJZ<)^o-}QPZ}0L4@6(8 zk)AA0lL#~dU1?6F@rM}($d{q$(`cje3ODXw&5T6nU@2Qr z@bpF10SrNI&X%g$p_=Y>!I0)!UqMY}V(sM4qqC7UglIe3$QkU-XL$9M_$zx67 z1SzCX>#(#oCzw&WDx&X%dov5Qg$q6x3=>IA5g3Q_ieQyr2KB{C2haKr%h#`&1q*O9rR&5WeZFohjHyOT)0 z%r0AWVoQo|030?oyTO-BX_Wq{|bKdL&zR0EnLktZ5#{Pi;Y1R6@?e^9fHzw)b)4uB#8%#XOd zsNVsI=5Y_PgcJTgL)Qh<)s}GOz_JEmKZMuga@-SxMg}4S85!W&nh(8$;9BLc?_z`~ z2T;!)Z4mgqU{W0xf?NiNXBGiey`I8^!l~ZVcvRc(LXbls^3T?Q!lPCnpJWYJ4m{c_ zH3)9CMj%RLATrP-1Jnt_h~lg!qw#tB42-WsozT>fbr}hOTOIUcYAr%aI@P}Rg~vj+ zkr&zl5NOEUn9Ke89f(-%1ZYp}gJ@x+G#>IpLuy(i_>l+O(PU&Gcm}9XS0ND(qe}#w z7%jG3oqE8^Nse=RTBk-v+WR8b;^- z#=k?d`y&-Iq!TW6@Xi$(f?5xvxxmfg`9AAFBfiLhO9ptxwJ`ZKmo`hXHHCQl^Nf!x zDgK6|g=39+>su^3jy)79ZJTwe9RRTl;aaiUKNP0Hsc+41Vi7M~E(R_wqS2PY&_!Dw z^&NH1Yek6+v@HWX*DH~D9p)4AP=6)=G~{pftzX-eUqX9Vzy@$F_1v1m*8tQYR9`3> zSHs<^)5biIFQeV90p!7&gsuRtR(MNLx%e2KwN4;PWS}h>p#1-Vg#Q<9g~oq3!;Qao zsJ(-R)cF4aK1)5cuJjQA2-hfp_Nbz)11Kb06;yCx_IF&D*czh=UzocmK2W@ zLP*Fb09Xw*w-Pjo7~B^{-=y&9a2|64r%$5lScP%~a~g-Yz;my(0MRcp&`JzY-VY-^ ztp?|*lC9}8>|>A zGEg`J+It>y&^6O zZ;h^)oVrcnO&>_ow2)JA-T_eRNT@PMTiM>%{{e{>F}_PDU{kA@;r0zwoq#>8Vobm_ z3-{*|{GxMYpp_WVbX`cIwOji1thVh=vkIJgc{i}Vg)U|lV*;*U!Ryfpex*8l=>RB2 zBv^|^)Cn-T%3c^#%fKg!9Awf|h11-$}<$MeYd^34pgMoVtWY0c2{_exp~<0e`#WEtz0bLlaT@x47VYPYgeL52YomI`CRe~#(gnxr zXg!2#FRVq;IoHd>~CD9Nt9bJ|G@2$86bk%~!Nfbg2J((5weGS#Lz$U20llO*#FE;*WOHc$> zGy|0PCx~#$PWy--2JSjXxONZUdCTG@&6q7ytdz z!Wj0u2W&&gRAsJdf#+cW)FC9kMV*l~;OrIOK%)J~fDZ;D_vpw>wRj&)8vGMnq3DLA)1}Oi}qdh=zjwd8~Vfg_V7D7X4{5J-#MkYdR{MFH0 z5}r*o{$Q~wG@?7BAk-_T{^m9O#ScV=nxifYTIPTbN#PVaW;>!dI4mM<|WIGB=nJ0D-Lt z1?3igZ&mp}(CZuE-hjgLTA=tN?8rc5ATrQ21Jvg_pzKbxd()Bmi$GJM8uAZni(fD! z0M+>l$y@XP531b){Hr!@I{*R>*%xtH27OQe2P~Qv(5m_415QJP9vO%XLVoY6C{Ymq7TSxSp)U?pa)$Fz%tAvS*-%=dL4G97>l_Y}12_`O}_|G=->L%KGFO}))1k%7oS zWFRO8sE;+oKN?*kDB!ihYJuNC>SHb7ZV3r`3ZPaFkU83aIS6fqz4lt;prboasg>5~ z78!^PLGCmkKn(_{pH{{BMYI(f|CW5~ug4QE&ar(QdTFLcg@UX!#C6CGlkD;r!Ou=_XX%0=*97LHkCa z*dy%7KxCkG8917x>ElEp%Mr8{EjQPnlp$@?0T2OX?AxfmX18Y&A%VDW6bQ};Gcphv zXdecK1e{cjT=bxQ_+!9n$PK-%Isg@R$mB~=EfT!6;uhF-mB8>uxRHU#Ks}Gn2Y5%w47RYsUAUGq;$UtPEeHi#xU`aiaHsH(X zGlAhQ3~pO@0K_7h|36ec*Uixxax*TUfKOjTj1n1$3`7PjF>r$=Fez9b#BTxW{kA_} zrR_Tal|n*cxC`yZ|HCV8Mz6bqQ{T*v5*dgLLDnG7uSv4ESMydTdX0s*6e! z8`q&d{iHNnZ3_k{VBOK<(V`3WN5r{DTaXwN85xKSv=sx?ZA+ndqeaUUB0R9I$c%}# z!vKYEJM<=WI+{mj68KtlEjy`+NFoD~fyh9)3{dCIj~;-&jOG=+C|!xJTQ17hk3G&U zmzc*C(C$Rv2h}Hh-$N&{{bVNBD3O84Kx7~?P=f*LO?^ygi4J|2I&)%;V9}`n2L2x* W=2VBOcQpY30000m07wjFy^8JdU zU@ssFSV5^GpaLo&0-{u^AubM>F;Xu{jHSUR=uzpa}bThE=PCPK0o0 z8J$H^hOKipt5Qn3Ik!@PJ5y}XrgPGurXD6Lomv>W)3%4cEzO=Z&&fPYk_M(#PL}D@ zdKy79$Ve;HcOuH-A0q=I#@74P(nVO)2uU`4()byt%QPWHinI1hd5v^bmOR(n#{!~& zCKWUx191x=@BXCB2J4T5C)t3N#O2vIZzL(NP*kSuKeFUujX-DUdQyb5Nh4**b_-ZQ zl{^tKX2Tp!Gd+2%Q2NTI>6`Og@8GOT$?X6;VMIc5m-qFmq~KBKCP78mr(y;xk5FKq zc%d?GNIlhmEMBkc<&wBlV`Fq&j}cMEpb?uv5h2{drBqFAwoc^ zmTwAvZrJ}oQz1jCFVEN`WMkU&4s~yJdYp1^e{EyL;<(`r8>0w_X8>4nuMy8!{L{w2d2m9xr zzSET@EDfB>wggamuFt}jwY?5z>O7Qtm}ChRh`fDSAZu=4zGA)CWtA_&JVi!Yp|ou& zO7>0J*6Aj2|0EAUo?X*D&lI;`oQikl3D&-pdPP+-_a}i?m7T1gr6@)2Td4bkyu;+q zEMf8OWdX$NWGtT--wxngNxF+)43 zbPsg3{dHVp0zJu0Z_iNquG3ld|&aq>-JhKZ6VjEK{+n;;4KCAWcV9rp$jN zr%c&2U1{}G$&iAw0Jq7i0cW24e_S}l>%&VK+R~R#r6|^n@Y1?DlPR1>tKPr10|4YX9)m)PQHu--Dg!1>VN2WQqcJozt5PZqpjpyJ0ZG>tK_%fLRVG44)b@-x10i^c7>Hx4 zvs~LV;>rX>DZZ`6<;`5__F_OAp5lstc%wP-jJQB83uu&*`x>r4$CKQKuxeJvYc7)K zlu0#J^sgFZEJi+pd>Q#p^2y{E_s^0Fh%vBfI=+IsT19;Y&ZmH;_8s;jOB64P%2eI& zRG^x@Du5>CT@vDih_(qxlIMbuMyF8-cxfFH1UxTc=*N=A=B*2ZQeGKv`{t-F_4_#& zAWCVPQ>gN5A;MSd(2%|&PvQ4GY?}KErrK13Ni=JS3M5P0BTZ3 zWMtJZ!kQZ+kozJ8r;=49I17-^?ITQArs>EdDXsk2HdRhbV}$}-0rMBraBEv-xXuJs z*6gMN`2U(_LzeVZx0isl3Lzd2X*i>8RqV)(5s^Us_l<-+%xMJ8AR?_0LeH1rKBig? z2nn-9L^Ab}fH-FCNu6dhUS=#th=BM`E!Sc+DI|dPBHLOc0wA};#}ZXJaoG@gWK56Q z%qvtCd{jP7X0)&De_V!3Qj+>-1j}TBI_mOaKPDiIK{6J-1-L?T)}G!g_n z#-XBayWZEDet|7{_^|&h_CGsO*ZHc5I320abuPK4z!V}{=~T^);@m#HfF%<)9$eGT zR;nfOM(cUX^J2tl5|CDz&3mP7cd%{j@*i(a)t{#)3$yCv>^osf5ejFxUrwcI9BK8Y zch*=)>Z~e1Sw9T|G7n<=_>1;Y#WaP{zBFOcHtIQ@xIC^C*=nT6B3)(v5daoX^>}9VBPfyNL0TD2?~O7J0ekO|K*;C2t+caNlV+7 ztXF0|DW^=GWSOLltaa+WI9ZqVO``JCF+v;Ip||FeBUd$3z%@~YyniXm+aK*qdV#i= ztsBW0{l5TNCndI}uBOS4;}|1C5{fFMYKd)3s~_7v<6K@;K3+Gu95*DnFTS3k<3-dz zAu5-4Y<(fx8U1Gnigu6vmjQ>o^CeShta62wGI}Hq70aiIjgz4LGdw~YGXOqH<*Wxn zsy3D~WQ>)myHb_}$xp+PRzJ-nX1MPNu&xx>FAF|RS=qWd0h0w%+p7?u@>zPbR>HqwS?887%@+cYhYPk-Q~=UpT!&DIz2=j|_I}P2S9a#=gr(pep~#Na;?isC{YM zqitFBqW$szR0Z(@$>k#DDjx?>rhHOI+Im7}>I8-Hdhzn{?ODr(F(O%Uq~N>B?eTRP zAEo&ACd-jL{Uc|_ERAv5RY_3Y${rC{I06;l)b;W+AmNfaAS!!AT*-)ez2(z+5*AV| z5(K`HN5rkiJ7%-KN_<-z%d*~u9w$QLKp@2HOaUWZl?R%}F{UjyIyBM*(m*$=m6X_j zNLrb?+vZ4}`gM-GE~Z-b@RpSoU`wX2)>2}X#uFU?%Mqef40~85BD+Wbr*v&yXC5j7JQ}|t2j4$E%AXdE8Jc(S=;;lP z7eb37j?J6%)MRutxcK|JbAXNoV&t_h3?0e1$}zl5ao!^Z25pY^GcysC+c7nUxm?k( zOR0gIBJ>?Sy!9!t{m~HtwH!i*$5L{bQ&V0$s~@vT2V~{xB?Mf&j?x!>7~(uq2y9)T zBCKxRA=GQY-M^u39akJUixeZzt?UqqBgd6py_6Gi0r=97?nj2MJ>vgYK^P90)Vb0k zC&~E#X%OIh03w6GqRnHkC$ws25wev1i?<4JK+53q`zd_pZfe#1TqNl`yYt*unend- zdJjscICHE2C#;#O(|7FSpQg#w0NszIQ=Y!n3rnc_T)MjStzJNw&>0M*v!A|oM&%|O z(p98yZKB8O)?{ams zIm>TCSSw=|;uyep9C<9UKNN=$)U-=QUsL+TsTo_QZ8R%ZnS=YGv5KtBh!kQwStw=w zPL$Sq!j~c|cT-6`xiSLW>HI~FEE~)6M|)2D!dRrJAi$eLfZ;CTh*FlZJ>Nd{GHzre z|9AVcC*Ih3I>7LeX#cc#uyG+a-W%=6`Y)>_tA27jdUs%3=i?HSxH?|n0G=;!g#nHi zK~|yTMQs~*iZZ8-u@{Exf(B$MU3KLTtzOhvP3$Vk`R~xR)7a^wNNF8#fLTC*;;Bea z%lkixz75IqlXoTmfgDtdbEoAx;7YdL3nY6gQdCg%cj|nJdI$8wku#b$8(VN zCs*=9lrw0jXc8HU8VlzrdvmBrRB-$Cb)PkZL*)RFPlpgZV6)AKTVW}AdQ(xn3 zCL)~LiWI*E&Q9S#a)ZR8MSULS6wju*z9TcZ)TUz$=@g>R-28QL-Y_yq4Moy@1xpne zsC1jVg4~db{%MYHlkyI^D?4?-myw?=GhGqmKEclYk_FP%r8sSSm2GX1Sp`p8*&;jJu%QS; z8t&w_vN$7MV~ty;a#S&?xXyYReRbrzs8eKT3)p9aVKo=FfOT=?6rK$to5!v`qK$b# zT#`{nUmg};`-*V6vRTX2(8d61OUfCoe$+9isasD1iS=?#%kM$|y zgrpUY?;kDCTUL2W-PBDZy~n5SbhJ@AqLd~Qo2Dm4P22Bs+XzQyJJiutwoRlvO@8Xe zc)_L$;(lXcLg_dlIBPEto=U0=$1YGPaC)v}yrIfMWdI)w_ARYcL1 zQFg8BxJ(uF&rq9Xd=r^7lvLc1g{h*LvEtZM`tuh>`b#;5v{xaqNa>h06;`TXs35kr zq9O2721Ds^ITCh%83xsOB`!grOf&|<-|4NwOXcI)}k_GRl<#Zo#_!~s-Pa=)C2v_M>ji)C=!Ei6%T zA+w2$2#5Zg$jPb;hrbb#>@VvOXV<|}%P9mpA|T6vlQXtmbRD+93 zisT4NRNAd<#StbAwXB?+cr?jX^elc zT<1mO2QkLk>7~z3(E$76aOk9eRr~Z2IYRs&P?{J`j#hP^#`#4?l;Se0E=xw$I!()? zQg7ndPLbU;vCkvUNlqL>MmUWWNmekj)a*FPdWrQzG58IMZ8KJD5;{XplMQN_GWEf# zN7)+VP&<{?RYyT7BkBlF)^XTqk05&q@;yl%0j_Iq2n|&{#}T$xK6KlfQ^ZMe=pb>i zgI)F+71BuS#3|xH%t7L8OfNfsls+xF#Ddd~W(j>Wis&ea5qciZsG-6n#hyXz4_Mkh9O1I)l)(Ow9YXM*A7SPHCu#PCx-Ixf0io+a-ld@uSOZrOpOebN9c-k) z84l2qHZX@!TST9e+99uDy4)9Bq`(i3fskFhB&B8Ducz9=2?lVC&fBEZJ_Qb;K0_N0p}UjoitxIL`nvn+{i{LZ zgf!!`kmw$E!st)Sa!={VHrd05zj(4kVwY*tmPl9Yp-PrU${qe|@akg@<<$~}X-iU3 zABS<7G;2`Wj6*JUjLB;4^Z{WjyL5=eX`pk55UXIiJ;KH6>SIjTU(s_M9|uw<DAg^XfSl zilLeE4(0p0WowVx)FQb2C_b`r;bA$?9!MtlKZx8#7E`+SY2oG#*YBi zNKWSV_GVPag5mRBH8`#8Olf8|K79yyn&7-`79H}~d14>bDgtZL*Gj1=zm1&29HLTN z)h=9v=SFj;*X~o)02;(tf!Zz8VZ|CpzUEASXRDA=_#-(*mDDQ0fhw!Qx60O~q1Nf6 zs=^wcUe}(%*K33O%1+S+sKK{vLj!%cL8U&0Z!itHnwaWUBQNcyp@gMV=}3X#N_Q-) z0xyl&3QjRVdsLcvuu6MWi4;}tShhNRY!dy1M!pZbzgyP!s!_gBE&^|t(2}XvgPlSU zRv?vul5G+do0Tdgv9Z+YLlP79GFPjFsZ1fZqY?wI+o$mK;aXuOYprl82C5v0wC8(^ zgyu#H1juR1-g{pYa90#5wEcbBy zr3%IiQK?jl*9mbMBNii{Qp%X(Lf;S3#w4aPxoejF0-wh!inf@)ld|aADlDMh5oIA)>|+eo~|FhUGO#gMBkz zTO5lNLS069Tb>V`7l7x)GMIW+rnOH!lxfpsdj{zg7@}VBUwYQib>MoR%e#zI2zcBv z>YP3ntYdwdIvB9%$cRaB2vKr@>?LWyjIUHV(oRPTfL#u%HHwhMJ*uc|mHlF-O8Fs{ z?ULKL?s%jqbO;{}A!ktXA-iuf=P=O?7wA4N;w$bH(YCyQXEVzH;#!fAr)*O9i5Jp2 z4(QkWj zMk?tWTDd8H-pMVPvJ)LUv-$XxUACzl122XD-;^slvy{AR=GO5oQTs-xk3xqSuU>u) zEGLZsh3F9f#FFQeW&hL3?<0qrqHm&o&KE%1>Hnr>tILtfDieP%{mx2Fpr5E&FZ6039%`g$<)bh|jTVE96hw)(Mrge*^uxXmzClI`^_A+7 zQK!xjqs1U2MV-dAI!`cQPVod6b(eOjTQSsncKUG8GDACsSfp^^6hjkXPBF9=bzsjR zoq}*a;{_K7TuqFKK{^Gk_rS!opa(;T>J)m9asdx~O@zq7It8tF|3tK)2P22<6lLGK z_CRZ|MgD$}_bHN1;`_Gu!0uD*u1N8NB#A>?SEG?mEo&ELf1wIx%MYm>2hgt-DOSR$ zYldW430n@P%zGhVY6d_!cmwN)q}3}EWrpNHvUef|?xr<%*=-R=dF6-Z6oc+)<~5|N zeKABUT`jMV#@2k>SQRPTj)&DBGs>*g*zR1ot>?p#JXD|4k%znM% zSt>=k>hvk<)JcN6KDi;l^=rDu6g5&^9Mr#sx|db0UpZ1V1sVZt<0y-C)%h>7vjzN* zgTciCSoU`RZ_xKraTQm(eI4=|)T#8X%m#XTS=E(8lr=tb2$i3X6j~|c{Zt;Sqk45y z8GUtSH>p=-V+*(s0mGY`*buK<25;Qvc%+ESX=OPMq!on@ltA!v9Eiyk;n*RL%~dvM z=h$^6$ES^^Me_uf-;R>g1Aa{mC;#AVEw|2 zVO!>Bvf9Aul3VaT4Js}vq9dtu%tMMQNBdExIW1hK!U*M3S%$117C6Ks8TFiPPBxAM z!G#Wijv2QH(jvtY6ui9%kZS|lI0|!Y`YrZoO2^a$wu{-J+4Fp+-Zx?L|js zTR6b`Zm=9w7I&F)WwB>*kQFJUyRC^o#_Y@jI##IJ%AQ3!%97d)#+=$79OBrLxZapm zE;CZ7LRoT(NX}B8x4o?HJQ<07=Yn(7#I~_jbpDeKnvArS)Fp3uy7MB1h$;2mY{)#! z1B0`B&#z~9WGBCAZAS+n^T^qyQscTSnl=b@n9yg7Bf z?aISccOPJPFAKOxNABrEl~HsSf6p!wr2RS^%ap592K}=sU+dOy79M13EaP{p;BZ(r z_pWJOJ#vVWb)O0^H|CWs)rb`o-i*R!^Ay(Ehko6J(ao5uX?l`&WNb*~^Q#JQT;9vq z1uL{qsROsHQ&b`JDLBSWj>%NSx*C})yO!Icyuu^24i=DkS+}U8IaMBE z|43HMSJooa?T45p%L4q9D;Hel%=Osq=akY=UX}f-hE|o|u>ALZ;;YDOna@v-nOiHgRRmS4$2*3q!U|Y)wd1^FTLHpYQJ>Br zMQw0jDN;n%S2etj2e0#AV)S$`AD4r*|t!TZ4M$?ndHdE?A6&C>D>Qy!Px}u3g2zR4M5gA?sxT?M#@ZXMP zxcUc+K1N&l{mHuevB3$4N&VPyAKMm8ZZBGQfybFaH66qGl?gaX4LmL)x9olwjgZvU zHJ6P}A8}*qk|P30^TuU0T>etS`khsWhc}9hIsoeOpQg)Mq=KQf`} z|Bq>q*H^8SEZ+pTONS6HXOSW@vH`%UiC!V+C6TPE|I~HvGVnrZ&9~^`d_@uu`<1 z_fN6S%a+ZP(_~*+{ghjDRJMsje9xCdh=a;UV^!iHz{v>dG$%v0#u7Lmr%=_#MEP~V z`tQUxJ+sgNp{tYIYpkz`{2A|m){v7~#apC^G-AL8EH@r8rK4+<-o*b$w2a))971OQ zYlQRr{LfE5OzUiK><~IINM0R626&GYQWB*RInk>9muKKnoWbQ~d#+~hks_{LZqE9Q z&>Ame%QF~Qp-qR7_EsZB++2$qaW>MIM+Z^*PLEq#jTCV^Mh5>mzRi}W8Cbk4hY*6! zBE_`%ELhZ-X5$2$;YHJH9W4am6p`%{>>Q8b43&o=M7+8F56UTI9F8G!yw5M?n#j8H zx;#x}VeYI?kp&2nbon)vvdRo#`?Vq47@SkY8$3qbmGSL8UVhccrp7n(d~y)n=_Air zPAwXVq!CGdN{R|WJ3*4npd&>REacuFiyj(b6>2&!!r3>65TU(tins?r_MI`}74hB{ z-{11`L+H~m|0r$JvVK!nmH|#TAJb*7<8&kPGN(!^i!J1Gz3NkhOk|hXa8k`_y6q@$ z$A4>cccCjSX|A->$$udKk*t@(OO1`8tfc@Mus{)DqePGh0Q$7Z2gxsvwhi=O_bLw} ze~Ew+;t-jE(q7&y3l!zKa$b@^ph*-CAnU8Jma-X8Ao(Og-S8W;ceP$fx?0FkuprSzL)6o$ zCqp;ThVk@{dZH$;mh~ud+8mG4eT6-8irB7UG4N7)9KRWsNp7sMKoR4Sz_1gmzm09O z#mQyhZcJZ>!13VZQt*W36CWrD4i`bkGoGMi&`X+D^eXZ-iF_UFx&f$xQt^LXnrc?- zWL}+Z>yp+m!kDp?|nF51Wo z(M}3}mio#7PIoyu!za(XdbHNVlo=$N+w|8{)efjd>J)^)ipoj!%GJyX*6<9a43@zBHn1c%xG|(&>r_J&8_Yxe`Yq4Yuq%wd{w*3y!>Goun7{Ogo_ce&EFOD%_wxArKv zwM!4k+k~vk44*+_7UU^ekf`l{Rd{A%GvL9S1UaV47v@} zn%vY^TAapdjWl0InA~A9fd6acr$&JKN=xJaI>x*uuRRI~T9m9_gs&j60|Y5qknrXr zCb%gB_~%RHq{z9psjQ6pw{n>MC1anH&E9$x0RIUHU*iPjOd-d>yUz$cQ=@G$1{^Uk zI(a&hHZEoqkj6JUSo0DnAVM#1d6Dgl2nSr62xFi$0~{k8Q~2D{6{;0njpJl?wJQ0g zonCri{5+#*=_5#NVL>9lF>P;u7{Hg$8~L-I0=iCDaU34vQmC^78ekg&?0lEtMzZdQ z(1kq6HIc?Z5DakaEDn%6Jb<~AV`m8$a-H-jF!WP^@ew4pw;4B+EBpmoxA zeN%pMj!ivGXq+1ND8TVIP;A;5NkYJgxWralH3o*w0LRnTSa_OiE1MoqjRFNm{TqYU za%|Mu81-z&GEJN@&?^Qwww&|?;zlN{N; z-z50d3KS^R7<0`4PXtIofJ~P1apc|3DbZJA~U{U$f14U;5d<&Q0N72)z zNRu^UfcDb!`fbS@jq-Z@S8jLeB$M9$)i{9jM*pYLj{4ZKCC3cVhPxp0SeIhG9&-Tx z9@%MfY5XL}g8V0u_a^_-X+yLl>|xY=m%RQYw3SO6;cOk(O;iP6=`#x;^&!?DR}o%N z_Hm+GtxKN*xxL>F*E;(jNPcebjj3jUM)ZD>{7HPn`OUm)P{J#XUn~VG%?9TxJqFM7 zlo3`cPykS00eAW8wgm|Yh1X~DcRbnk{T@UPE@`CUUXva`@EO;$)1LsRFDmkuvVp>B zbO%@|y+z>rw4VlkBX|$)6XqUZ{TCRw!=3)q1FX&<;!CR|>&#>RQDuLQM3<0g*v0Mef@{C6~KNWS$C~1wadVfxY*0vRoT8ad~8>=9^*=L(Q%o3 zj{q?H0K|esL2JO%&gAJtaozp5AW^`Zr`<1`ZiqPx_w%=^CtaP1<-pcckRP}LAgc0Y z<(}P(D(4AK*|#3XU6iuDcbnj42SA_FJKzR5Vn74?1~Fy_U%UmQbl<{7`U1RsJWWt$ zpl}={dOgt$T&x0lSCVskU}*%~w%{3f6ohMWfLs+k(hPtuk5za`jR~n6QLK;io{)j7 z^5!h%l?Am_0s9pY6c`jBEKL>z7vZlOl-8Sszb*jS`yBy(82j~E&#{zshIAGr(6->1 z#z0pf`xE4;1Vo)>EJy^}R-R$48~MTL{~ez7H5Si-t)UA)Z!Bnzfcda{#yeaydK47; zI^|t`li&{+q3ikJ5_T>ND81O`>}G9nMj9a34BU;tWk(05YuSzEDX=vbG7^A|W3eHv zN8u_+%oSRYfX8D*rV@PIM7AK|%Cjaz&Z3y9rzlZ!_SC@y>yT<;24G6q6mU{{WVr=Oyo-E#CGd7&vy!K_7qoeAZV^lySOByXroQ zt8{53Xu3y%0hh6H&1gr%|IGpX*CsN+qd_DeAnS5SkAEyxV?bwur_c_1g5x#OR&PeZ z_q{3^ws5tPPIBL)y{>I)D(&$+Wa!K4jT3mLVnjSpIJ;xo7@Y~I%RuL20B}cdyo^|J)YQ#P8h3*rAQ_0d3_MMdpVaw4Auv2bo?BorX7{=VS-oHw_=S)} zPdz>t3@igug@NblfF$X4>);Z&el2hS>pXx3M^1kLO${NK>K@Xgu*;7AG@Ov$%kj5J zzaUTDfY#{2SM&|H;hk%i1&aQ8!A}ViukIi0IfywY$>$#HEB*<^{aFhX{c8CW2@)^t z7vyxb){9N&CD5%`X-4N=0C#Ml01Z}*0fNL-V2^F;^`Zrf{xqL%X71J>xD$200-4IVIpgc%4Q&MOrd`P3KT2)S7RECfpi84fH$&7qk=63 z%z*Au=miqJNMb2q28P~ExBC?VJ0H;0qZrf;vasnkbU6&DXJIK&1{5f)fdXxuI4sV% z>&DjyxcvM9+B6uGEKu~PDKG2~)appNw7Q^rEvwNM0}2$^wWZATG-H5X#h;r=u-e8z zJq8pgG?|H|elV~V!QvnNfNCg*#DJc9EQLY04#}tquqE}|3w^g6U$mDK18qdj8{mD~ zxtQg!iRaGgQJM0DFkl&qJ~4n3P5V$2+~$8x*z;QVahiDUs7K*d zlL!m#&DBjj7oN?v%u=+0Yd^%$lCCYtbyt=Km#6aV3P>gU6 z`N^B6{oA|9hqa$_%acDteuNxE0@hCiWUSlRQTI<{IP{?!XXIdq9N1o;R}1@1@1)(n z*+d0x^%Cm;x`~Vc>o)!XR@^2ydJ*fbewuKk{}$SJ87(IR#kp+TcvQ&e-!uT9N+9@a z$bXMd9g{2@CmQpgI$Y33L%BEhD0JxKM_vOQ`7gWTRy`Fo5<{_?m}>Jf1A4T>3PuStQVe!9h;`x zCVr11D*Irx;P78Vj+I&u60!lk3-h;~LwhD(6r45<61w)CcEp|%dYzn_)M}6rSLjp^ zM*QvUiMz4(O$!vR&%FPOJ+nL+Q(7z-P8|_jx{ejhWI)~D+KIE_K2&~9Z2@6ad=37z zQrA$x@LL~#jm$sAZJQA&D4_13vuhya1@)C{AEd?!oq*;2;js4H5d?|1!_ilI&eIBT zaCl%gtmzQXi~yK=^92$%qCtmplW7Kj3Kp1mH#>UwS-u&@w7Wsy68&IZm2kd4b$dMm zQ@&Hze$Vwbb0q&ROuQ~BYetVER-m>+#AM8cb6gT%4`mrL76r>`q2TEOj<3Pl?sakE z2RBpKf<#>cbLzpZg4a)Tij>|(8!w(#I5SXCLDAnudK!j&-i097GO%%5WPZrC+yTnl z0IuFw*Dl&$z0)Vxtsg=?><_gkA$oMXz(sm*mXJc@M~$3SzsmMa;QG8O71}C`jq9W9 zpKa;ulb$9A2)up(Tff{VdsDF92nWG_q{!j%nL7?7vqupl%+=lLb1`a#nA~6%afAz+ z91y`6;ugprO*k1jaNmQ(rveWW54mb`>`c918Obl~QK%q|uAaa%qe>0`7X_5w(&pf z-f?iTYhakh;J~*=fi5t%vHnWw`!AIOh445I7Ms#A=hnB=e@*PY4J}Lh*VL+pJK??2 z8OgC9v}$~YvIXG8$Lk9j>Z)&c%z5t3%Otu|mmY~qE+2E9gYlnA$Pa22=TTSM<)v3w z_T7bI&AP5sD@f2*`^s6Bx-!Cp-v7>_WTJwEZYSj4yiD?3xkn)Z_{rM*{VOS~!TRL@ zU#mg=R;psR%Ns~-VEzTXzOsoTYLHfVwXbbi(#80Pv#$fZPSXj&FhkTjr;}+Htui za{5qL(V-7GX_FgWw?`A(8^Ex8Z5CRl)mD@}gbf z?ntM4T3#o5ab*|n}0(14DI9oe1~)A&w*QlRg3_?U%`phy1s=D>se zuX0fIZZaHvL2rG|=YfyXL$a&t_7*52Adqqs%gaXVj{o)HAj$7lf|GXv_`qI)4hO7m zp1Ym^x)tka_e)Xat4Hj0z8CL-LM;G6oAUQJEqhAy;5?6clI>M2+-M53PCjGc)iC$M zm!gd|GPZY#Hr52wZ}tToUc4X2&YpVYk$@fNjEwR1i0V-qL&-;XF3+^a`{3n&#ElZd zKG#^_a0KYGRUg)gQtyHU{`fOFC3g4<68aQ|_aGscYDI|@MG4-X!SY4Xx~Koe;ZH9? z^)|uNcL2Y4Zw;sqT*1NVu;uzt>eZy}PNe1w>eVh)>k&9=^`zK(ponOI%>S_blxW@4 z|0^N%7oKFdA{L%p55Q>!cMT=KqOJC*Q7@P(G?m8C_`ZL#20UHaw$YshipbEG4urEH zcZ*18-~L7_VTpSzZ|j z`!?6XHcHDokk__|x3sOWO?`a~68O?7@+Wxm9V8ymF+%DrNXQpD?@`1Z65hYU`abb( z9+!JD2Zrp27auR)d8D?QXdMOBYIIYYc5popOOYX(XefwF&(3=kai$>U{UfLOV|=@( z<*7L^Xndt_dD7uZtnVI|E1ZLqgKy|PnyII180T`braZ1R3|%RRAR(YZM{*kI0x+(Z z$Eb&WU!s9N>_KjAk?;_V!_+n+zhY2Nsi0dYP(3wUI3Kq2z02Wy|8*|afxw`86iIs^ zZGEzW+3%A3Jg$F82j(dK)T5qKqQP-Qse=73)cI`Z@VqcN>Nz|LooxmQP3)@_WRQ?+ z1>K`a`aTW$4Ys`_xxJ-z4HjF5#`N+cPnr$bt9L{6j>x2>R%gP7-w#0Sm%AcYk)bQy zRrU4;XxuOwcpcU+jc@B<`2^beMLzUmpU$xQuE-=NZ|`!z>v9l!HF^FHiM5*j-ME{FCl_=BIJ03gZc=7bjEWAbA5waxt!AKb8CpAcjss$q+_-}Nti29Os zeIyUrnuoHhAfXQ}DfKQ$s8M>^qY&_9!Wr~fRgYIgNtXje_gEfC0s`ySY}1pSUIyx< zJuR(^$93TInk;?rx()kI&D!6=_WQuw=DiMYCJrW0#2Lb2ChgijZoVyd&%llZh~IY) z!ySS_p3!Ke`N;}`E4ZV|BpCy_3>+e#8>K-730XbJ9z|Mn(#z1tRDPYd&$bx@H5vFP zfnmd%b$eB9Vgg0HRR|isC(?p zJ|6W&A&1^=VPUw1%FMTH083V^mH`ttodHJ&-QGs6TQB)wSY*Bh1oxW^T7Uw|A z=@IxI1OoLMEIDGp0)-BL?i!qY-`O zE9202l6NN0NJ!a(d_#F@6H`)89X>(UlyJ$kA{#77OpGg-p@j_48`*(;B>6G&kkYvr z^SVL;tU%`s*riA3P2e5?2j6N)-JZM^S#x(hjl2}uN75I)E+cDxkkiShai%|?e@g>m zzyig98Z*z7QSexsGRg`bE0Px>FFN|ya;D?Ef`TTR)x01YoMdU> z3|OETKm!v5o{1UTj`DW=>)`J)U4e4Vw=tCoCjaRYjOlL9fCY-?9JVHbfS{hhp5#}P z*Jw?#TSccL?lAIC2_W~m6>ZXdF<^nh7qboJ5)>9dga&hIOvaNNiVMB^*#OjM5{?WV z=%nJaKoLmG6Bw2N%2&v53ItM@Ff`No7YH0*?h=IQeu4oD6i;x``Vzt6wJ7~6dFVZc zrre%}0KMw{kEVjGemw>(P}JkCRxJX<+*JHJ`JJ@{SS2x_L0EeeG!8a8+GD^1g=ek_ z4&wL#vhFuna?5}wQGOFa;|RB6OSLSaQICu9+=0WPkv109j6XCE0>R zLp~i;*GqPKFXmzLiyX+CcoEj4sObVY;Jj4TH*fy zAzGj)XaWL+Ubs51pqTCMF9UjkZ5;xJO`Vt1h88F?$RR*HgIyPrjiU^X2DbSEg2e^{ zv&oq`b`T_}BtR_5rklw2<*)=d6SDdj0>*PD#MaVg+T+m}RRoEPSiOyGK_bS>ge`7` zA1Hlz!tBm9*LoDtgH!1Ji+ATTWjiO8f%WNO=n{0I(?kaf0>oCd{+}nr12jpDKACq- zO4e)Ly8Hid;(syLmrmqmSznK=&nzm>Pab-@9Rr_Cz|a(d6PYG9P!J^aU5Moe)atrq zI%brQ$EiDc><6z)f#G@N9my{suS6b7+7DhoH56m2*fDW|0!Mx;1bw>-NdcBU4ou&} zX^#yMTPh@Y*LPcAPJSJE=hQ;|*r=iUi^IJp9-f#qF@XX{okgpvarNJ)bPHfVOa2DV zIjEPMXcJx5e2A=9@cVWNqd7lc4Q@+AVE~7GFS#%2L4Z!=jaBSkhJ09G8ft`7_i-%s zodFv2)*d+CKft(o-??^;A5LCJR^SXhecH9{p~)NUr3ap+1Mkex2#?{pfaMp{eVrZK zW{VjN(4Mbn*Z0Yxj&Zq*wp=^|e(yIAa=;Z%r2r9PkkI{x&2cED4al>5??EjY09S{S zXOVSs+pi_HRn#mt>h^3|rBYwY4ys2%L&+XZz8YEp{0jd4fxb9JUvSdi%YgM%vfj%H zDgB)GepN_-nqnDDpulO?hYZaV5lYe%md$V&eWTNoX9j5hFQDS1p4C(le+O-^_l5?M zLOb);A{8e&h>D>E3Eg{87kM!Y61AGMRwcOp7+EL2U1|w%Uug;aQb`|n>V4{ckAjBK zo1Pk0+;utvKi#uy5T<_)1Ng=2EU7oADGR$!ufjKe-Zh9O`gDyY%@B@fqDq>s{*IJqj9pGg$62NNBFbxh+Wa%hzeI*<|_qOFKlq9{#JF+`UV^ z3KWq1UKl>RBbIfUvpmkWGI>z%Ty(@|Cu(WC-;mX-_);eT=9+5}{8*{Wo=r!lx1bhc zr#`YXMREH-_VP~)ZQO+lTqq7%L4O)MOaj&dnV8c4Sy{2qv_e534 zzq%ZQvj`oWdqXEY_)8BO@eh#LMUYsX2JGdHr_h})G<>wPX5iLI^Cul(y9Xa%x&ytH zR0iFnfWY&yX2VJrH7|S$KBF0$EKMK-qk~rObp>XPfggT#RpMqF77Dz%&D+19$fH zhISS-iSMoLs4A}|xE=+Kb0YBD3=*%mAW`07CaENTaWz>d(>5R^HJPGndi$YqzA! z)C`0Hd~|tCxxOuP@X=t7&mejfG=Ls|wiP5aiHrq_w!D2ndhnYYMhCAZNAjLHE`k{W z+yd#jiKBYv7NnQ02h8CfKO-v^q28t zeJrVy)LEc_V7-m$TmNm48~pItPFmiSI%5D|UJGIWb|x@e&P~kXHGY2scj8QvF_6swKD{V=@5(OWY|p~@^?lByl@!$aJqif@AlQ5diN9Eo zDCq%K%n1Yd+uaCi<9NE)3E+xCTJ2E~BvuCB)fF*TEpAiPRb|Y|J7oYr_kHi}dIHmm zPC*w4Ya;^2A@~jwheP0t;tFlq7-*XTe9-p^cm-lnt21=@HfXwyFzg{#e9nY?4DGYq zv_e}j20CV-g`UOJ@cC9gz2SpJ002M$NklXYsoB1@oWk6Kl^Ek}1u+-As zASvA-B_RUR(%lWxUAuI5cSv_gH%JK5-KBJgH2?j4f6w#ozPRU}sWUTY>Vk0sny98P zRg8};IUq`pqS!6GpwXw@(Kcip=DsanZY|fAZL$?p?*C!86$^Maq@?m*${8e1g4FHzfeQi+>*K{E4X$R7Cw^eZlORN?1Z1{4jj}Yp!IDF9=+{@dwrzb zvuSOqy@9azB_6XXQ?2exYy0iojkb*D8i9}r7))L@MN~N08TQ$I5>NLn=pnVBI*{gr zOy=h|CdxpC63!_Qkc=|($VgSGy;Cnx;3KzWzXsM8v&@OTcz=>l#?k^&Z)hL=1g8`YIB=-KaQ(w zej-_X?CrbUxmj{|KZH&z4H>a7>chZqO&mSR1U%~)g08uU(T9s>A2_q6$RUTsHI2Qv zwu9)@H+l7Lx;!AzPq^U;JFw2rAeAxaleH6xnj|2p9pD<|=#rsnHJ6R{9l}Ec>upk!jamF%sxdmspg3^!DM)+2Ds<;x%@VKrXNB zd7OUHU(c5m+l=D90#CkWx0RM;XJ#`nI2*8tl)A@TP^IC4kb_n@ciVz^@?JVAwW&SG z1Y&yfo@npn@^5(d?m_*DPFPtxR3b=#2WQsYnNMJljxos`?D`X~Z%4wl_V{bSx(|NJ zxeA;?9IHN3#5E_ZNQEoydnSu%z8pw^K6?|mcmJYKp2dWOnk+!6h)z9O1>86y0^;`e zGLWs_KMP(l8G2(SkgVg$0v?>;e-eIeUM&d)PpQehGeNp)93f4>kJrBiu}dzr75QTP zm*}hU1Ja;_4JmxlUNJ|r^TU5g+4}=u|D?1f zkoruMxx~gy%7c1ZDfYGqdS{__>%I2A;e(>kWL+=c9v9r(aZ-So|Dcm@6ZP3S<8qYV zejO*&yd5EpfuG(OHr)>o|I3~p={v|wg14lTvkZ_&li zFYb7O*OqdOXyBXt1d>&LQE~T6t*Vt*_$o+hx~b5zWXQjPV{Ce1DG9uKA;Vf_~wK9H_D<^x9^CQx!$ z`5u?d0ka`4DXrCk$f#;9&g>Ea?Juv+=W{$y)khky#7#DX4l?sUU;50;ok&8U@ZwKt zs@m;yXmV*}GU6Zj9>5J}*H+GnUsZgm{&w)0>LP3~v%y>mR$*7KY%>SAqA`c)GtHsD z5@G7L$=GVm^2;@f+FsOYL4q-XLJ4{!E+g(Ya9Q4ES-ZNJH*mJ5;rA&UZ&N;0H8V4g zrDGlA$*VLPu{s|0>jnaVnNVfJnm&9<5jP`6s zD;4CmXJWTUn~vgFPLA|A{oSy}{5Nq;g?Nu>i#tZ;GZq;tTP*#LB!AT!*oIkTTCXPV z{+yKY(ULEB+q95;sH1d#kFCh}D>03Pv8)a@t3hy;^FY__DC8@WCn)E{lIiO zbbY?$J0)-GTr~vqgIb=~LxT4QI4_3$wfWvMArw3|Lo=rlxo$?!r8Jzp33hWIr2gL0 zi`lP1aT1N1(-Zjg0{_d!>N5>NPN)1Tm?c-@gI;Q-C*xM8%mo8YjR>D_@3)ly!1WuR z8~xk)AXRaq1Ae--PpID$QO@U4A0~Z-o+8$%HJYr^s!iItKV@TF zurpzsX{moYl@;g4FiGwXlQ5JcsA}`a{Bmn!H-(aQn>ekoClv^?*;=vKBES>Hr}Y1B z|5N>Td%%GG`Oz?4;>G zWAYi3X1j1JI-vul1;>faHyOF&+!sjCvMv%;;{dk-IM$r$F1(&)%WYyC~GN9Z^e(k*aAa$=ZYDGh{Nbgc_;mrq8p! zo_=zLwVphPw;nLP2-D3p)8C0;aTlxD@LMMz%VFi3=H#6FXH>gxHgnA!g@!-8pe_qgF|YYGq}44O^Y#cjc{eoSEtNs+YI%#k@aTr;i`1;i8e9)sHrfRwK3yxOvCPoq1|o%yx5AMXZk6VBL(W49)o$#zhj8rd{@AYU;mUj$c44H#?` zBi_%vN%o9sr?vA~?zrtLspdqKNf%h%?nPJ@_aF#^ZoI5jE&pX?DvQ@CJ50~_=Fuxx zeUk(wLf;`H*;>th*XT(dQd{J1{nR@}qqRQ#UxN4Va1RCQorOh!mp%T&d;tih9c!(Stz$ljeF#q6#4fU7sb-6?uSUA06ofekH(?|Om7t+vy$yl} zJps5$>H17MPP&>I)IdC=QK1^PCvC;O#9LHZBvga~;}V|tYXo?LMRoc3$bo=|9Qcs+ z7>vRXsNx7hbro1%UjWw~cwhV1c{b-_A{{S@8;F3JMiw%Mbdp>aTg_GGB9XaGb>0CY zP#uzzTc$6n^KN}$ zktZ5T{TRzgsXVZ+Jh5E;YUXVN3%?Z-*q>^yRQRQwTJOD%)t_2(EASH4iKzrNu~h`$ zJEgOEa^$RYT!f3<9)#Zi()nY<2}snp)rv6qiPdw)muFijpUVwmn}<~DV)5UQ znokg+$xN+9_mPZ)kM6g>I{Mg(J(DCe5NWB2M2_WZwG>luUdY7Nr9#`yG9)xg{6GTK z>qTP5leMe+8zGpBZUNIObfB*UWNA{~D z^!IWzsTcbd*XRrJ@ub)S9q|*BJs)M&C(W!7kCK=GQp8A?=}xDt6@^7Aq9qgt8{s$v zaTDND-SCZZ`(R+xC2+cUSZQF;stn$8OI-SXigwr@AF!4?umK~Tz+5B z!p{V@Z#MKIkT=!hr6J?0PD1Z)gGD^g>D8tH>W|em zV5D1vaCC+*6RwiL6RiagC#ueh@Gii0R|Tv}+;o`WM2N<=$KGQY?v(HJqg(Nefus*l z0De=IL0VjsxAKi|35*6kxyc`f)v{ zrSDndilM~&Oqq2#O}pvmYP>yBHLmK>bYq6d_{V81$5lkn58b7$qVD=c0L44TyEu2x z`$gp`ji6vVvHjv_^20s~+~sI!JOyx}`Fj)w%14J;t#<)}GV+JBO3C40yT8GI z3*0GRRHxCme>2SrR4ZyUT1^Ko{3BnvwpX~ArjYbpsTUAln-2~var3(j*Eb#hr4<+G zhsleW`}GZTDK9O#qaVEmwtz+siKbn-iL(3%;xgiMx(5l>11G<*0#&XJ-_~f z@zZ*TllKQ&aVFmnfEf7x^95Byg&eQ=F(K)Y7M=pQ(r-ME%@Nn!=r#S{UyR z$gXKaP4H1C6bWkTVeTDHV1MD=+O|9#Y3%^UeMI)c^IMLyr@DYH^`gE&$TH5*oV> z%hA!3FHVr!FLZ8`qzp0>bF*5Wl7OWLPf2Xa+8TbR{aRbv8w&Y#ei&>rU94MMRbq9~ zeUQz!;ZV#N`>M7?kLu3maxGB^$vyIACS(M6IN@sVr> z))2yPI@fT_{4EB3N^QTvVuWjNe~xdZ19*lJNXVx@esO$Z`DB;N!As0skUOXxIQVj3 zj4^10+g-kE;Uo>GG_5#PjjRAE0)Kl|JwCqiaLA=xO;A~EXQP-lmAQ#3!KvC=s^fh~SEWZ$8*lZnNf8^d z4c&@^Ez^cprE_|Uo`JzrgJZK~UnazI=y*^2N)9P90TN(_Qc?e6$a~bJFEv>amhS#j z)QA&|d_u3nPlrBu74TXj^_~|I zM=@!8b;G==J1TH|0hE^xcV&eN)BlR(B@=lIYc&GnxXW9;s((RYPhW<`2`zd%#(aX? z$1BWSiYX8qCW<|+(^EGnE_=5PG06IumWD39+sR&z+WGrxi6xi9R<%@8zoqw_OJUFW&80lR z8Udonys_m&4!?hrxYO@GtXvQ8--D zv2*HtrDF;~VDgH`wmy_GF=!o0`7{5ugn~m7O}q^f%F4E^naCZPP5e|$=T^|*NMAMx z#q3Od(a9DuGJ$Jxmnyc#_EXlaV*~4SX(gb2HhQGD^>2bVRhywT!LhtJ$K{n5_u36BGPMl*)gJIL%m?jPuz7--8#?;7E3g2LjudLu z)}}4q{?tw*uO#y^ifn%RvRz7wD=Ev~4m zsz#9(Yn!E!h+d)QCT<@k1|;-fdujjX<@U`C4Oe#Ptk6wB)Pnx2WJB#)rd+yd!M~K%ktfTLtfv)=I^y#v#4+Pw#qqadp}4qImZGY>DfoxnxN@Fgh%g~2n=qxG7Oj+ z)p7t`fR&C7V*45=91^uZG$LSzMqlJuGw)*+8NilQbfaY(_QCX9W_$o_A``pDwmASo zv4U1-44p$tej=iE{d$2pf-&nfqo=2?2mMz8|K@`uqsWj_|-_6`v=6x zJ1Z&ew`3N%)s3}}ORDD%2cJ%^MSsybUPtq_UTze{V-wLdG|xAb-h9DmHiRXd^jV%e z;ps@`ALBjDUsNunJXMZt1uetA{#0>t#prIPD!8N%^40!3h4W(63sjdBuLO4^Ta->s zry{@pv6003dT4j8DyxcLPzEtIL^bP%bNwSov26{|^?hy%hQ)*BZ;G`@YVi3?Yo~n(y5Q&>phq*V@MUxnClYcu^WM%YU6`zwl&E3jJoQ zFZl(l@roT8Q}w`b+=UAqWaAn8lbiLqv8IKB)=ZTF3UBHl)&lb#8|?i9L%uR}(F3e9 zw+=^2xV*o<`H1vopyE=l#*q(~oVm7Q2UtB@hqgNkqTs*;7BlR~gnKg0d&>XW=)j@g4V` zawnQtO(Yd=6=g%q=7cW+c9toi?79~v9PwUoyyfd9WFQ3qT56+A@3TR+IlBlP_E0{ z9iO}cVq>@^s7kNp;sj8N7|A#HTpqM}`Zs-<9O*jD4fOihm@Q%UWTGLYgGE{>JL)w? zx8ISY^JG4;MuJ!ThS7v^wbR&z5B=>a{TnRH_m#L;DU}TIxH)jJRuUEG9bK6i-~)+J zz6Zt1m(?+VjQx?_SabKmGLKpQeJF)r^M|5GN&yUaOxSo&_>d7OEqb!elh>u6z~Hc? zZ8l2Z^@;N7AcL#y+)&YEc%aM08+l<${A*CVG&V!%=c`-ez3JAM?&wmA+fXcQgW84klg^R$avb>oh9oJ3_37 z%te3G%u#P!qZi+=Ra{7POujp=o@@>p%(#Ezt}wFiu&aYgd=krT_qP|WRJ`iu$0)+< z51%mV_$xbeR5Nhh?RMN=ffQOxEhk=h+FM+kWqn5C3p2h|zK5TbYN3T0E zRIfZD$yFm4c7y0eb6ksH@2~$>;(nX{?32D8wS6r9kFjtUo{KleKvPR|I3u~6 zV%vI`($5=@A6s0)*W`TJ{(|ICERT(Q&h(T?=43UEih4pYVn@Yv{-MW=*{IG{%@D&q+~iMu@6UM2P0NbA zJ<=$gn601uwBBH&N2SNw$#e)A%I0VLVqePNUSsRRDl|;B34&DD^D0udZgbRx%QVbe zQqG2B*>X2NG!~|bM2>imyfKa0em*9DJ$61oB~vZG84>*DZ-8HBD{f-3YpwM%Fm)Z3 z(Q(zHyl+cmAc>4aLNk3#McwQJbDTQRVhgzAK=L7p8<9cZC$JqS+p)e!pyBM8zk}5rhvj<|cu3t$gwvT)#Q=Wy zc98)J?}QkvC1AtAc7RfIMhMYz+6D|dEdi!*pj<^ryrH~r=7?Nelg2Q$>-z>4?M;Gu zo@H<+Zh&$F73UQY4X+*uKiry8ML5Ru+CQ_$d7&zWG{es@dE*;(Iztmi$tLY?`7hyv zl-(i+(GZvV-3mfLRuHl(e+MLBWWpg} zSL~fSJ|T?PjB;rClTS3IT6KzyRf-f+VQF+iAr%A~csQf0Rn+Kx(E_Sy%!>dsO^p0A zEhrigBSN2HJ5xhPk8ZelI;QhRZ5jS8w|jtiyq)>sgZ@r5?ZpF*RRm~N3mw14{L~7o zqN*ab$aLRGGz4K_ZPNPj4+I7y)xa7hp>sS5H#`QDcjrm_a;pxjOx*bnecf@r`La>0 zUKYLHc)2LCgS%7z)xzOt|D#emvINq6sd#0k@`Vbw2+($=*@+i2Me&a5#ud^#)l^K+ zYLRI_#!qMIjgrNatskq133!O{-Ok{l;X!#xp{62Ke(BGdz4<=?`|`;rN=5<|=;kFw z!Z2$5a+#Nvg&%&$=ui3Jw#O?3*p@y7hKnRu^*Xju;?vLL!`{*3Ty7wPA7Lv~t2O0s z==LLV7DRNEjt@{&Ze=&i4`t1Pm4_a7-ncUZ%nW)R6gFZz0ovDgRZ@5J3;fhiu+n2` zffQeozAcPbR`hUy;RH8TKsvLYrET70jwQ(hT_ei|yN-7(% z|3n?QE{#bg9b;N}0e}kyj8r4;n0Wv}uy>F*?v-NEv)${hJ)zu?7zJ>#{`%9E!)WQ$ zaw~If-6=OHbOPeW7`oAKv55yPQVcp{>x{389pE1Q`xb9BiUuU$U+7hJ>fv22cV-+rg|6=-l@bYSa9ZozD1!!b+FE1&sq{zvVu@@Z1Ih71J zR^~CEI`Zi6E!(a8@N3>ld4V}OH5%H@m2drcd+>=oX7|8q32wT(c@JT?8RI7czrUe; z>2>}k*jw$=;wow+GkG|XlLH0(j7Ae6CYr1`^gGF@Zh6TNR3$kLt1X~)7Q}qyc$OPE z5$2k3E25D3ta-?Y$z@0?fi|yJ;(km zrU0@~J%_vMbLBcKe?L$`42&VFgWCuft<(zv2x3O5zOwFlBxzQBUHnA?V>um&qVNWL zuXd`hweG6|vmJQOtXB|^H=@zzCwK}v<%{tYZ}_>{i#+muBhC;+2{a*n|7zw}e2$$L zDSv17A0J2UJlHj0P=NdLsBPhjVa>%v$XNhCi2cW_xT+v*cgb7C95=?tnXiDI@4x~~ z-BY;*sxQ}cGIeI)n{=pLUpM;$p(}@7pxW<;YgzmpBpfcNn%1@4t;DBI#S;$iuzr{T;3>N92^)a4p(6IWEBmu|Es;;%53< zopzQv;J*^XM3jj&sUtygaJKH1c`t_{4Y6^Jhy$jTr_!`GmG*b|5&zizL*Rsc62<0( zM^)N`dSj^DZ&a>0rQUuB!f6EFXv)OBahZ~`L$dF<%Ycr<#){Va(zc&`t+8t z`Gt>ChUWdaeH`Gp$Lx2kr=JFW*=Aq20j;l!OA?EmfyK=m-m9jPSxWsJC1?V4WN=^b zJ77AG&n0k9kzUaXY={iiHC%rNJrr*jxto|8}co0I@6g0kHx4vn~(0+rvzdePIxxZh}1+^NgNc=K}JoCcSiR;sEP+B1u&f zfma_8)Z8do+(zJr2Xx97>+_$HJDc%t0qcHW`kaN64AS zMZ1m-udENoVupUg_Q^_r-rfa%?`pxs_ERJix(+f-Y81(<8eQh2){PEEz&zA2>yFy} zTS{S;H4;ly7gS8MqhCRXb>uV@H!|t+-lN~#x~d;#Z+CjKJj)`Vjt(|oI|nHhy$3CS9X>0$DK!Ll`0FMdWccj(^_wv2n?bb>7mX) zOs#@tC~<&fQ6xO=q_B*?+mU4g>%6I$DeGKYx_)i@{88e69~kwQT1Q}0;JJ-ZX|61? zc|PoV$V-T$($ZI}u1MhnRlp`Yv?KiBVSTY3SxsWykdO%ZF5Tj=@7Yx;LC(BF4g9+W zOLS`RLan8L9ck|-jV)wcI0p>Ao+re;BRb@sfSq_MqAjh31pPFP^`lfKcWb?$2^)g1jZKIffUWt1Tm#`_NlXIS8@4(Wan8y7dd7k zeD#W--CguYYSNsm40H7d?_7Vvv{<`|s3beoT*>_qp-uU7g6xJbaL9IT!~=z~E2Gmo zk#yXyb{Nh{Z20YX^qjg@Rq0p0?O}DrWc)`tmZ^qfxc{^>T#VR-7J#US)&UzXJDw^V zKK%uSs0R%t*_ad5ZUhl1(Cph(T967GQq|5JfShR@)P$TFXdV3@3q%1Xm~+SVp}&v# z7xmhI-6KA5BY=L_SdPMuk24XKf7QfUT#})5GsX~Eji|!&{YkdelYJHp?WS=7aWSOV zmQjaq+HT=Tv4CXw-UsSHZuudxJR+**D%6d*giW#B8z-Xnjt6Ixv7BdJn~49`ed0lS zVk(lr({)7e%yoOKf<{xT`lw?bf(c|9$Q<5n(n6 zg0|Vt)idD}ZRPvFe=w*Rr&rRklyDD-?8HK9nrR$e$bewU4M7}00t+|j8TKRXj&tNu z9tjMm11@8x*It8L(j#wU4RmqfC2~}yy`9cH@g~KRq*TS9M(ZJU%z?7DUX3mMV5~e1 z#FNF*q5ShSIP z&-C4W!)T|(Tvu+Kgl+woLo9lh23w)2Wevg68NeqRN8~Y!uypkE)3NegeoBx$(xUZV z!K9G~C7*xzGb;vHRt&~F7Ghx1FF2=j^`%#ZtEqE6y^t6otm_+xa(I{>E)yd_n%lv9 z1A6VE&Od70P{W0!c1s!fg*F^iMB1iRjroGm@=N!U55F z-Rw5~sV!Pah3CJm?qi^@++xw|0OlL1ZR#$%!j2^&Y*SvXfSuVv4@O7l+rr6rwR}_# z0=T;F!=v`DR}hkUc}`GhFC3?)LnxWzh8yx-v|ak|o^JJ`*U zcLg2Ib3EI?itf^7qI^q_x1$c~&`p^9MFTj+q8C^O8REk@yz)gg>)vzf;F>9X%1oE0 z5U2nF^*^8aSnlZAd2%VXXS&hT?-23Q#6V$AVY)l67cO{Vm0J2{%`wN8ZFh~E(_tR{ z6$3G*JmIIexpQu=Q0Zsv*;ySG%}~C5)3e$JmvwVLmen$~kgW z5^G}?k+@FxlAqh>Q@g|>D|HV$0}jlRRxtR;ImJ2`)nx2vp%(c?e2CD{aW4H3=AUsPyeSEufj z=-DBwllH8upgwX7gJ1qoNqbR%gLA7R z-pO?UZH5EUVkv+R;y$0quS4^rb#l}Z16Wa0dVZX069uI4d{$10bLxM9-b4c?2ptfw zT6{pdj=U&EXBumZ3@2Sj%3EaY!FnPL$GYuUy}DauBs@0%aRIhZJ{?HF;XtwT@3oh# z9Fuv`U+TM8$!ei=e77WCn;_=fh6Q6j5Rvuwy`}7z6|HKiR0mky7r0Gc(QKB>C zZv0fI%hPe~mHp)HqA7GQgcn~v-LapPM_|`j3KT+S@b`FRTebO5xFDQUh`?;sjqr`2 zj;VFA{fKNO*D%ooJlC+m(8XR7KXTXZd~Gr$57x@b@0Skbn|8MULyHJV&C%OtP9UJj zaIDbR{rwI8<}h0~Fvo;yNt%M^-iPX(a!=HaenZZ*)-ETan=CJM_CFa*0GQlJ?)|R! z^KmxpuB>O#a`>~xIG*~83(k0x`rrE((z>XWACtfSr!$Sf!2@uYPnv#$+mPF!?Ye&m ziCYw2VsqBL$Fo&wKGUZ?n_+!J&^K8+E&idr`K-x}BuERJ3;nH-du>ZJxu&puDo{rvrqK;Cdp zJf58|Sk7o|>^Twav*FCzmhbTR`N;l~+)qFHVg_<(2Y#oK_&4PTD4QPnpfqWTmeYhLF z&aJen#eXs*77uo0n<|~ogBS3#V%hsnin#Amv)*bSU+vDwaq&WQAJZIDRd8-ZCS4mW zs#a8^{(t9(h=>uGO=u8neSQq}+IOB2lpL&!OL~fTMf#ZtJJ$ab$oNq>hQ`w; zM+sn236TTc53W%7Af7DE0~+(&wZjiLqLWr3UaBVlpYYm(1X`>y=oCg;mA68Lvs_k} zyE(njmBsGQh_D~IOFMd7`GPn1vK*5fz)hoY!+D?mZLyY6HSzH4$t)aFL#=cuJwn?ilm*uqEMN{Xl_3XoftvZeZa*0$-cpx5aU5+H zJ=flU94;56hk4jrFc14hB)=IGV+j}Hy4_hgso2$mfw)%#yq6oaDNmQ0IZy1(xLU{;IrmfQ1sQOhUPs*z@%0x%Y^JMPc{W9hkP=br({Mi55e5{8G6PM=3@4vggIVc?4uy6*6 zS<|jIFwG@D4kM)dcLAnBb2T3#Sx#+J-c|3rHT_V(WIlu4E zFH0=R6Heq+e7uYep{OLEk3 zRWZ>u6sC_7{^(BaD@`!$w~E@w>h>8wno3x6G_D$N+02oBdBt|xuW(n(OvNImIy=Fv z`4<+BE>Du(hALWNj2e@agn<}*7=xj3hHW!*tt@ig%tH;{N;)<<(jBR#3lq+@l+YO* z4~BM(eq^AO5N<%Zp&y|Om)`7K>jLs>lN)qBTzabd#=xYD7Y*xZ{lM=5Yc>Syhktl4 zIEfT=(f1?%M)8VtB(rHWk#mX=8#8b~PIWuz&?(Jiu#_W#>sfQYSM; z%5p$s$h{j*i7>me%SKEO`5c075llP}D(bKy^jm008)L62R3ip2OjJyJ>-XstrPj0! z-goV!7NbPzpFpqBX{5wBsuB^72n2AS#ZJZsMMrk0PX3)R?weo_Tk{Hx(AwC=i}AK& zWoYeYT?$lxI}^>TwWz>bnv+Psq(@c};YW>NW`@g=F#o3SCotTFKLmM-qZsB=&SsgB z(AODxM<})!gnq2nCxm*-xg~83WBlN*PjjO`;Cq4Z?A%8g^k^s>~B!#KdV96wlCLf-xV| zyF{wFRf-SSlYcU#QU}C5Q)%NC>4`N@1e1CzL~?FL0e-%|Q5#n5rruyZ=Oz2|Am z03Yyv{Vk27GgB0YUIAh93xn??NvNoN!;&s}jh`6IswDbme#{A>JedF8k}&V0Uy_Sg zX$}Jk%ANng_XZvH_Yv{VD4XMBMITL#jquOOig}yj8|$XGW^-QkL*?Mds(p*-`63LL z$A)Tyda{WciksKHFJ1GIHdU=K$^?(~QbO;2B~JLccB%~MJxw7Rox$!O+rc$o z$x*@ju+CIAnz|sa4wDln@&od!FDpJDqMuk`1-!yRymMe~m?;$m3(L^y8~MjB`B;(z zG%V?XgX<5=6=-`>mS?A~W9m)UN9I_`c!%hE&6<{=)m5HUcuH+u3j z(y^I49JNd2@?g9ht6D$B_)xX}jd>X)a2RM7v(gn+)qzEr0Apg}N9O;`aWT=9zQX!? zw8cfXLaP^V+r`e0qL%75QmSWoR|htc#bwyq&^+&rPmA9}30# zf&))0E{H(Ob0{(g2SE4~{|-KtD!6dx4Pq4kOKPN0laU)u*bm-96IX}TEP0XLcz2Ne)qVeh`iFiK} zVYs<13rHS318#8)GU+!E>HtJEt9mp?bm{?p+UuL<)WuK>N9rPHaMYcd#<40P^=KgD z?1e&ddu%`S2#`*Yh`-)`upE=Soos@`{G6}-{vTiyE)R}?+Xyr+rcK;RIH0uk93Z8Q zyhV~P{V4!rd?S<+!*)*6Ny`YNHus@xWE7!~8z&pI0e1wQ@)_L+GT^2lU(^zF0L{&f z?7?qA6EW+~ls!*@50PJx7lqJG{5UwCKKFU8FY5T*D%TY)bfJcVEQ05>aRT$ulxtJf z1NYrN9E=&U*Exi3# zbx=OxepO>SRFQa!>b-&(KenE0AP=k?}NLNc>6cpss zoh(%>yCA+g%`2%&7wo=U?qFrD@rUBj%}LVB+_U5M1bd?2GdT}0R*=#L-jHNJe<)?{Eylg$P0XQ4mkr=4eRWm>xeos{ z2hb5mJ_YivD47&#x`Cz7O=bJ!$IPd{jvR(Jpk>Gsv9eGH<(g(l!0aneGb`?4H^HH4 zOl8m%eMTo5o5itxl>#G%*r5xT@voG00QVFn@W|_)Kp-r%GPqE!f7BHXEDE%;3;hXB zhh7kACAiEsMe6(z!Op9-`yaR4I4^{33?QNHSOOi zDk9L$SMj);8)Zj+j^G~-H+GkSFe%aI%HIh0YjqF3oA62{yU``wf3NW7BP>8Nw}Ex* z)9JwhTd4xNL6#YSZ~xvd{!L%|&=4k@T&7#^ZFF)!mv105;J!>@NH;>dd8!6Ygf84a zhIux^K77boha>AhS;|p?8(BS5IZKxX;8q@h7ywCshB#?oc>d;lTSWj~xT8;rUEM1I|~SL9#KjxdZeA|dUEy|#K?&N^xU(= zn&3dTD5-mgA7^f_|Di|@IxAlCYP)}N5d4|eq2}3zX~nYS^v9xqAqy%`oGwz3Zxfd{ zk{qC^Apzn+85a~Y4FBOh zm9{9Q+m6aGLjQ$w>Vuq<`FHoX7&5quk?v+>pbM9}bwCg=0y^93>6KUkClYDML%eVb zsIW*G7aIqIi(Ph16&X$33*0ahprtBb49A*acGgPm$+GoGo0}Vp4#+H65I*CeA!r1O z-DcC;Wnh7FO`THu_1!#(sW<6ZP<;lq<3yU9%&iG#LE(r!bED?jfpcR_^Bj=84a*dY z0ImN34TY*46-*siM!^ut;dZp%mud~JBBCmv(xnVDSI;}<1R`1*Au`}0{;T^vmJEHL zvGDhopatan&M+R=kKI5$2yC5Xjl<`)<*1xl^R7aeJu_X{j6wdA67NG{#oEgjO`DIwjk zv?z^qEGZ=+ARx8yS-M+7zy+j1B&3Az`upvF_j&fY^WK^B-kJNJGiQMD6Qf<_yz((J zf89|?fe8XHS@a?w>I4aW#q%#1`Ic2bW$ny6O)nD17z+(=Y_^3*!4OvA_Vdp`uKw&A)=f2lwN6+~Ay(2Wo%!~zz zi2+_>r8pzhMl2z~=R?uwv*vo9fOSPZ&!@G!Ys#SSxXSlCw=V^CQ=ysrmAPFTz()KM zbh^;)xa>%L>sRhBz-W6|U4jC^h#jgu0Z?@g^1VZn54$-3RxBeM($ZrA)RDmG_Q&*A zm+}U$hwMJKw(#mO2O4?VmGCdyVcF0Ix}=Y8%Xg8eJeP3VQpia1m*g45+Ubu1CrOzE z7BvgbEGqJI2XNN+QQ~AlyIyiUygimHnolsxm;UyzQFl;xg?yei#EfY&v;b;E(UDYv z)c8cR74GZ2^gKo8D{a-wun-=^dR~-B9nrAK0Ml<^i5CYll0rt zlc-rd6Fpq&xX+>~#q}bHKAQj#^SNfIEf+e#_lvF*k@>+2SN0n6-rD0OCMYbY0_nKb zE;rzp-A6@TWnFLB0g_@~%Dv(D-Y+et+wT!kP`x}ztG~8CTnkguo9{@*Avv0 z0{$GTuueC4S&U&$K8jCZ&tc@w!mT@1tDIS2D>y6E1U)WYqY72kkrA=0$zOIT`5TU5~ALC3pIn!wE(X zm^RG7^{DCI)mu3#8;g!a0fP^~E=as;EZtZ9xrb*1M3xMFS4WV~UCJ=uk)QlHXCZTbS4-kcTQVptv^;Wep!+8 zQ!Q0xoiF!}vrjJFH(&B@xp{N$Olq$A+-#;xXrtk|y`zM100QTWqZ8k(u4BHGsi{^X zU*PFU38TwZqLD88l8i|7#FPbGqnXDPpC@qT7_!3u64fQ2eb9Ab+F>s@{~9t(%Ec)+ zjlQRl5kl!h{=kRB(u@6wJ#ihx5x85ALgahsysL9UfRWOk>ip1U{P?(y&0b|^EE%P4 z>aV=5F2rOV`_jDMEFxuUv@5#2-%N|%q>wfTL4LS$l&(U~ZfWw4=kWSYoPv-&qcRFr zU3E~{DIZ_k;^T{oBnPy+^bCT?qR_AI;ut={Vo_+6(z8y`Fzq4UgG0Bd8BqVOEgQ$) z5@-^cne1%%n1H6$r|Z{Am+7p*>fl{Yhu0%f`KQ_c1!o3iTpFVgoigM}M&bo$_Hk5(^Rp?bjMRC`IV|&&Swk%HkCZh5v(~{8jLKH!aD!wg2a>nXZDnfg}lrj z?cX_jH8DpG<8XAu5E`++z>D!F`PAuz&mGJiI!AbnIyT0Q4hmluPfBNiRO>Gzgw#cx z@)CcHk>YdSxZ1uiz%$~gPZz0w3393Ui?iz3V7c5{P%vxX!bn2h$=%1u+Dp+%5MHY@ zQ8R1}Q0rUROZnj?MPcpQA;*h~wX{cU3pXO7ZWm{FdS8l2giInY&ALg?I>bD0@ceGm z4v5-;YJwC#b3g`(`3R7xz^X;V4DHHhMq{gohD>cxQUiT&$wa+{0P1Tx;p5V@N(Y1T z+fKvr^pU<<-|)g~73MqETBks-!M|i*{mQVq_yp5Hfay7r9QCT|YxUA(NV@J>EK4Mi z6-;#hvr$Ecium35tCo-)VR{uVA2OMHc_v5dYu$Y`!mQ><4?l04qbu#>F<91UY#8+9 z@RLdWU_7ORjZBNguAR-9)Z{K^gY(MrE~+H1O@C_oaMc}6csGYrU(g%dZ>Ldfn1J_0o+Tnd}6mB;-EY>1s`plWx8O5Uc=;b zbz-nC=K8M!_a6w#M3R zJyAZi1Tt-o*F3`N2E7igmh55j@|v1u_C)rUdj@hdnJj!*CCS9{%RE zBWju3yv@K#L`}wqbJPY1S8L&-QM}-;ko)VjDxKkTTBA0aIplJorceO(Iz&tr?R%c- zgd82HTcNW2qT0mYCu6C?kO-X(%*ZTz%d%HK3m;Vi(8H5?R!e1oa}{>stYCq^13@kXn2Ts4JbD!jKPbe1@YS~q*- z(wyBkz&S^`z_KIaz|@cCT7T!%SmT?Ow`+wQdst+F*9<`IiN?EqH>34<)&!wC-FaLr z`BIYNPJ&uDo0(aHrBHub;IAKIMg=Vr>p_NPAV}WKAA(Cf-=7Ks%^V+UjTZrYg3f&( z6|S_|OS|ixlgaaKw_=?F#=J{5fBZ*X@TsvzK5sE@)W=g%?5;$`WZGi`{0 z*bsfc&dV4f=hA5(inDgg9T+Q?tXupSSGc`i{?0^~u!G#_0kBox-`|-7aZb#!u>E0I z@YA;si>Pli_r6iRadp`zaNl_II1@ufL03)dZt}fe&+^YNAQ+<~ci=S#ci%HW^&Jn5 zpiTq_!dNgOjN}tJIv&b2(Ip2xyu@BQO;w z%LFX8wSIDcleyUXwP5x9^b=jhUrBzu=>QJRbBgaCo4Izkaa{ReIEW8#`(dOyjZS+J zLa?yJ)wZe8mMszI%UBH7w9OpGSp31ZZOBFn2z9n_)~mhej0X`-P)wd(T1ZN?73u1h z4(VySe4HaorJPjznL#$r`+D}qmuslV(gfgPG6%9yn3%w))BL*iI98tQH7cX-MAniW zM)@s=LX6e=8M3}e?2$Xakv#YM)i39@W$2e7T>~&0`|?E}RnSWTT>YVh3SF+RThnj$ z5A}XGi*bcYZ#V3xjuM zwHU5uf6;p^6+4X;N#Xqa;^tECr3u=)d5C~!6h+7L2}O&-LSfq0AIZ?4!Z&(L{$0Ia zL4}GmVHo@AnU%`G#9grXPTF&#al1cf$azkQPu1J83V5(Y9x3Y+gFLbnSvu^)si8SW zz>VK?lZ5{+RZ=SpK^8G9hw0yd)sjMjrQdl7imMc)krY{`gALWZKp71hnuTS;jip?4 zWH5$#s#~|Jr+LFb<1mX}=&(Jc_Cr(?{%vH*p+A(19@BOYvrNO!ZOfP-qJXprY1Cl} zd_+JG9~XRoYsQ&SYsMXttU%_IEKRLJ-J?T>Z?Rc|vPCEu8vOqYH~QBXiB;9sRGYme zO3G?%WE@^pH$kLhEEYqUFY#Rk8e%6k+Qq04d~P@7Ge@1-b^^a7C+=uYnCCZe^wh$* z5z~e?ihsRuwlGEIM2{==eLYo|GI2$j6tAlxC&r8srqm=>2rHJq zGYK-PH}lOg5y#g%l#Ac56Tc>is^!9J`i3M1P+MUb{U%T}%~e3YfCl}vJc0n|D?nn@ z6!sy=gkCJqWu6!Dg^n^IS963>dO)2kPZ#?3TDMvbm$_jgRR!ate(&MFoKW@1G`b`M z@l(prUj_Z^v}D_g7mi!DwND@q`4b`E7x6}AbA3^}f{p9Xu7~0H$1tMqo`ubnjSZC8 zDU8(ok9)UjgL%qO-=>aPj8Z6sW2|&vk<07Vt!&dK;LT+v^nmPx#7!Uv-ZXxefeF%9 zPCAh-s`FQ=%vM&gfc)ATHmVvlMWW5h@Pbb~ro#jzmbVY*M|9B9$LDK~48LUqmvJuA zVZQuJ>aS^}j6T+uM&&jKX0W_692o9u9-OCN{>YZq7DCu7dfsrZm50wSkfuJ3wJm^( zR%9IBbzD769qDzAc4l0Hj{FP!^1h}|_)pu@yVO7G8t)9ic|C>t3 zky#mZu#^@2B-j3_fUmOLQeOvBL5m*BCrchs;TnQ{bdQz_CSLn!tSqiRG@XBH(fD+5 z+rbhJyga=Tw;}1sImRqj>swuMhn-AdYh$&1D|0@J$P$xOe)0GRJ8P~$I+9SYGuMyt zR5q?R-_k^y?8TTbq>ZrG2qUl7AwzcrK z@ZYnT0vjqjuC`1Bh+XEsJh7T9KUK~e{X}QOU=a?{df-c2xvhvK=urg#{m7-0a#ye_ zBA~7?MO!2A)3EIXJwRkX*v}l@dU`}*cwty~feH$ka{k`ib_BS43QTK+#%E(vz&FWt zCps{bINV97UIv41v^L1m!owbAaL_pifA$pHyq#g9XkJ{_xbbPMAb2j0Sk+iHI1 z{B;frQVzws)%rC2Z%cHoYtoaR(5dRhEuTzKE})UTD!75sl@gpaWU5EZFypVR&cTc> z2(I4wW$9@QYSGo?3^+*$XQfQ zQ{%vbEuXKF$RNC6G0FCb>eOmSw8$rHuF1O|_x9T-@r9Ex2@{GGW~Tm5hD@F@v&Xl$ z{aY_#{bO?{bXyK(+0|l?#vl&`t^#{rhP_EmkEj9%-^# zlW5p@+ArgboT3 zY-5I_MbK;VFGqde_}ic&b)e1o3L2OkLqXI_m_6F+W1Niz=&Q=$B{rw?&LduHrR=$@ z|8mzHo1|HnYyRuL%JtcXW@jfG>Rix-8tknBC$g#F63aK=&U}|jbr-ioh35+7^H>K% zlElnJ@Kp!SR2Irb`2w&2pR4EncLw0e3ty$*?5a}Z>B*6d@xrZPHzzRq`7jx=t8I zzl0#rQm7}VKXrbdwb*TMLY?oKb9+(qbK#vY??WF({?oJAht~q^KGqBoq;25Gh3s|= zi5f`o%mYU@QV^C$Dauy79-0qpbkzxYcc9Xw7Cl&HxR8GHw9|^`Rk?0MipQP|_Fujx z#_^9Pu3^^;EIS1XfnhB2z(nX3`>8~eT=ZbP$pR9Qy20vZy5%BHIJd>eLMZVAYcXYZ zI70@IZ*B9+Zom1mj>DLsweh6sMx9u(Yc-FegOQ8~OO;}Z219&at}M`-og@Oh>zS{nxl**LS>hL)zn7fnLu99Rzg)vDQc>19OucC}EQa z=`c^HFE79B7^uG@y3I#GL#m_Gw@C5$W9+Y3qg48iJca#k(XiV4o0k(BT;AW2;8Vl? zl*psbyXU7YhyV^narZmPjkXSg7VPDuNz|F?KDEytN!UkSOe|%=_7D?6tsi@(QB8_xo`#L zxTNrn%D>5P>EM!|At&TqK$W6&mER=aln@l)rr^`KsaLHnRLBgu{pw=P;kj{8l#FS~_zLDyJ)F zqHh<~aU-RygK<%15cf_P;41KoHSTOOm~p4ksLC~x)zP54 zHfBIx_IEW4v3|Sl_jb2s?1w(O!oYcncAFuM64@O;Ki#WwV zt;3S6_Gr542ahHbb2HvvynUA%1IfVc)<1cORC4-gAz2KN$`mYNXja{x1h_Ldc#WgECcts z)_(J=-KUokC8|0E^}$l4;pIk|6tli_7f{yd&$-ZUijLeQqKfZ*={XpVwK)NOpzFh* z9yKG!OC4SQiJ9$;^IaO>tLcIlNI?fBPTx_5R_wo;kWxr!mHX)^7N0dj3&;aRlM)S5 zjSZ2zc(5~9NX-VIo2*fINy-^$RS^;X*5os@w?KNjqL}j(E~|bK&|)Z8^Pw<^61_}^ zb?3LjrS3>t60rrWmCvu+f2_a*l@_AzX8^9zB&w#qPdvOL;XX@g$bWNz z$ETwdLatzFx2Fy>Zp(UIw|sP`K;gucVY9`GXKL6CE z->M;|!eF|ivFj!sba<48Bp5m+@Flb&ieV#ziJ2XfF5<8=1EU+!P+%epK~)dh>zweD z27XoGY5D1Qm&kmZkqj`PwJ*5luH9z1(BNg6nKYGoj!6jX+W`fxa&Kv}Mds}e(Wp~_ zKebl$E5E<&--{3&M!<%}vuP+8Qi`!lFx3Zy`{F9Uf%a7#h)=DkQA?T8<-!Y3z;X@PP1el~+2fS5C> zT`*V9?x38(f)V?oBYpy>EU8??DIe&+x_eUe^pms{P6gYdb#OQ_tKtg z^(WEu(@@B3WttBGXyFGTkXl8u;XWcEw@6diyEn&W%Z^VfiXSvFPuoV|<%pSi13~_n zS_@?f(0U9}k!HnzC$B4gw5iav(GQbnZlW2P!TAS1%62Y75D$SDsyPy+#OS2aTkNo9 zj6kfzJFe*CRFbnf&l2orBBkVhdh%gdg@64xT<5UiY79ZKMbj!06pbM)gZzcSn`&oZ zQ4aM!nbFLd|82wE+=(Hv95gf6Wns{4Ufe**|HExJ+sd-5uH>z zx9?{cN-Vn^**V0wQ*O!c&8Z`8=(Yp`=Lr4wUaLi+uMR|zm3Nv6-SoKlkO0H`_a^T= z{T1{|a*Er82np67q;CwS$LzTGZ%cp`e@jiA9Nh`td}b7Wlw32jG*qj%_S zQ0DVEa(kZuGyNQ`!|;$3TBFl)F=H;GDh%nl4qP(+ycud=#SY*xYK`|46sRyOt7;ia ztmze#|=_8fc<%C?{D{-|IpU!ft~<$Mmm7~(XmmM;UC+PVXj<_c#B@||`h}1TEnOe`iD}eHXpD1I2xC>W01B(JDqgqm{RL*N)(z-)W6SbU z8%uD9C~e4-X3Sso?Zc{b2^ZaMH?i~OG|HUos1o#o`ltTm(;tluy-nIaDa|dbuv~E z9M9FXi2081b85LhimBgWA(vg-3=T@9Qq8ti&Ay{m@NYnpNw ziFQ5lifEaZ3-D^@m;rg&Of1BVvR(^&risR+FvIRlo25kiHZmf&g|4!G16O&R?Jm&Ry%H{+G3NIw>vvBoYxj> zvk-r!e1maLa?aaSy(}YmF{o-7S~GwmYVpA0Pd;T7v3PsX>D_wu>c!1uJGPijpSc;P z#4nh|SCh&A^^^B^dptwNOvrfwFRS2KTWg5DmLAde_V}PhgPToE3Er&pX5~mk(I8<$ ze`km|x40mRLUzVps4LDK$*%9iBE%IAyf_o(0DbYC{HoDfXGAS=0||Q@J;*_eq9gqgd(* zIev=VB+AeXB`HggZ<0qGI0@&khEFM_I2&|M8%$HWR{!}QQOy4f(iL9JjQsL5;Ez=) z-&Qb0;amwnWM+m3o9YMmlPf$Mo4E~M5{NoZgFy^vrNWf_F0CG|P!n^n?D3fok@6Fb zax-?%^B6q?UvnjXbRDt^Gc{E6a}HaUcu&v8Vlc}#2K|m97>GV-&nMy7z`V7EAU9yq9E6o?3xg}Sd=n2v2SJ&qf|Mx&ipl+2F z)o9;!a602SI@w7qBO04SCB|qR>(DG&Psm^Ov+jTT4?ch^A8fRzR|VruFjZXF1Rtfh z0!fv%{&LceLho|WJ1~@OM!o2bu?-M!8ZO)P3oRqj9N(*kpne>Mk*}>;UM#pn>L!2f zo5FAF+XqqVmDc{KD(dCeZER^unqJ#M^!j}Nf}AK-%T@F#Wv?SbABJLOLgpP&q`WQ; z@bT@lyMUp^xTYZ$<}uVAl@7R^Y?&$C?N@4S#_h~p>QEuNz@vV4+_K+@s3GbIuFu^B zX9lCdc-RW#pfsD~5%~~b1pT^Oo;1A;FdD^o%Ub|1DHMB1o(s+h0kk3cRb!G%_E9?u zE&hk|V{B1+@P7gW3(y0Je<~ZaLzJiOlZOikrI(mwNjHlaOwqLx|z!*9S4Jtb?oc_ zna-Sr^Wc1~=w^zmBkqit{(;~_qRX<*Uzx?O>ra zLtkFYq8(!jm4Eyv(dwlP%A4%NkYx(aUHa3o;f50Tpb&9K(-n^@iH_>N_9PgJv5XpW zLg~^>DT9FjvBg|G?3dNQAnyH+!uX$b;d;9$C42nG#jGFd0`UeOzso2gcmN{%#3AX2 z=$#*NWfYE*Nzb=R_hp8yO|ZiQ9l( zl!HCD&|JbyEQ)#pGMlVAZLy>*JP;ZmcpUrLWk0!SX~hvfSKA||BkKy zr;U9RF{(&D4BL``Rs4|1h+o!xi^3^AN`Hc6;^}q(=G#TZ+T#YSlf9n%TZid@)`S?3 z3L*3SG+@aLIvaFP5f%lk{Cm@cPFdRHQZO7)yw9tH3P+I={%s&!Uqi>G97S!#w2H%a z|AjL;Q2*Y~Ti6LEgu(zMxz59-8k81RP3v|&vrA>ezLXRGK7o!`YBrgzF1u?fouPX` z;-6wf{9kvd{0b6!6hmIBL#pDS;Eqg9M-KE4j r`I1!`bN{JlA_*$G`j^RgaQG7dE8=}p@tS!J8tSK}tgY0bU=#g6+Bz_& literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_openpilot_mirrored.png b/selfdrive/assets/offroad/icon_openpilot_mirrored.png new file mode 100644 index 0000000000000000000000000000000000000000..23a7d5a5528b7811887b68448dad93be1705e48d GIT binary patch literal 18150 zcmW(+1zgi_6Cd3@y1PdA=k@iC{mJ2OGrrb?*D#1 ztLORMbI(0@Pu+cQNhU_xB!mov004kQS4ZOs0DuYn?~RX*uGxJV=868oc2PA{1ppc{ zi0)uG=rWt5&J#lbAeaXLh>QgQZqQYcy8yr|Q2<~c3IKo$003I=k`9Oh`T?eczP1M7 zF(G537hNLo*0Fwx{zg*)>;dmvT+h%y@ceWQHSvC7;~x zxe2|q2_|=DJZ1Ys?_+P_LQHp%(q%+9RWX8M4^MeQdT#-!EQ-PeE{o!fRPa1UznDbh zlXZOj+K4^Wz^Dd_+6IN&0gu;HQ4Wk!$usIPj=rfC7U_yW+PrhxJjccGd1X`wU#UOA}oiLkD&!|2CSy zft02=4CR|+1*yVU0HwiQT160DlH08R}+yDHlxh>P5BTp&Smilup7VLvu}KuSO-;DQ=0l_ znHH3QJQye*_I8m&NMlSZO^qpU0B1MyQr5^ucYPsYj4mEl;Mw@LnoIsUF#5#LPbH)| z`Hn8uQrZDK9@b_pBE%I0sUnZ0o}u|O%VJ)g8%yZG6A$C#dH&cR@r^Guj@pO5V?Feb zdLWefrizv4z1>w3L!2=}L0FTvnY!#5GxdC>a?dcfx*Pjg6hqw0Kx|=ETH8cQlpe<@ z!@0Jy!IMt!G=?~JD+bysB5-+5^XtSW2Kz1dyGs8JQYk|16Q-5;aT6^YZOR5Z)~bA? z@4hh%ajycoJT)x8WzA>hI5~(a^_$pv!WpFqQ)bpNSK{@vcL0_PMIME#hVcG4Ti7kmyRK;8tB|JW~g z9<_@5GBf9qn@6Gbjc+sl#R>V6eys`RFOkqxnMq$adYF0|2dNdY-3d8^-hqiiBN^67 zMB8*{Rh)&{?Xu8oG3NmU{S&46JbrPSM3eDn0lHIrs;6fl*v zO8kQ4gA<@p&U}TeBl#O?iE2%3W~pSga^&~jC{r|TIy-J{mpq)L`p8p-I&U9U#Lfpxq||1;v= zG?69;fQo0Z zj=66WHJ>ozn0k}F(S4mv8G^t#Xi(beU2dT2B)!d#GJDHG&7W}B3;Mcq1|j%vVgm-1 z6=W<=V!Khi=4yZ-l$5k2+^EwRlB?xd4;m+thSazgDlH1E=00W`UM@-hP74-!gw&I{ zqzLo+wgN#!FWoQuOfPB9!1ymQZm{3)1rk=DU5P0U{OD> zsGG#_n#6buOk=IMM@084#nN*v9OJxB$(k%|VjsCmAqdd3!JifBx5fq|9uvb%AmTYK z83h`{8M-ueFZ!pabV@p{e~1R|;&lQ3gCXofO6s7#>4HcCcvdrTy5jIlsszN^MnBr1 z@5Q!^8%6kQ4J{<+DbJ@Y3ksPKQNdQ9roo6wYTvir<5!w7!LqdVvkcmL?nx=_ZBrAuG#g~PFd!)5aWmMBTC53! zQxwQKf$PTpFc9n-lQIjIWMn@?ItEJ64-3BT;|t^oPH-@u2`fm2(Z#!sd2dkTj#n}Z z4{OTm+2|Ui4jRrzkW%_oK?UCQWk;2jchhp7Na5m~QPcnpR3&UvjbsgNbhAAA|G*=g z@xN#+@mW!I&pxrytT-IfIUfk<2r)+@z~C*L=FE8rcG;#P8GE%8lY*eHzQ^M=(PRT$k`Lzf>sClsdbnb!mUn>j^mWe64=!#p@qUf~J*dWJ|; z4cE#pnK^NT>)O+|UzG-kS$`eG!L?YgvgHihf7uZ8Lw84G3`fvA^IR$`1#FA2R@-};FUUS^$t&s4_^aSM>ZKT%81>7gSPg?Oo80Xn@q&vR8?PptEP zD^=kp}t3heN8whFZHWJus~ zB>B9fH+$g1T&(B9PO$!G0;n*?ctzGdO)L)@;?-pRc)ae6l1r47427JWA8q$ukV*)g zScP-Qjytd(=TE6P!NkIaU8&agW}Lr4IcLplrgcVGbqj_u9BTYd_`I36+~f+wq~rvReCT;o1nPM&sFr&N zb6X=4PIuW!Hfm^Ji*%iMig$gRpL#YcorR z-$ZMtr(Ab~A5o_Q8!a;2Ruf-95!OMxULA=CC&?oFa!7e zsvvVcCA{FPWmu<8(}E^=6@WZz|4}no)0F1dtar6>vGRM4y0h3tUz?FUP(bE3=R8OO z0=D61K=51M`h9=bl$p^u^)=>aBhB)RViR8mHd!>1ygu z1a|M=z5UV&6lzwFXX#23DG(#0JMvM3f}v+K+dMRXFk<(rQG|bWiWHS4FdO&px_N71 z8I`5SedTYD>U{Pk)_kRZJS-R&We0we^sCh|p6r8N|I&Z73H1d>1K&%A(otDAr3=}i zA6_Zg)shQ5^nrU6x|jR2-*R3^e5elN?^jl1O%QlMI)=7?+~JwU&A;nUh`pS@U`p=2 zYPL34-jlu8+ffeHfg9UZ)?Sf~pSiGpI!dVCI_J!Fxj}r|vTGsG#I=|HHkEpp%+2z9 zfcRRby2|V|ecmtV&W|hH`ONe=XF^lC;UGf$-1H~9{#Gjq^doZ|U3eX25@Pl_=@1Cu z-Hj-8O&_dhIo7!nwErdxUDpT`xCQsF9%rSaG&lFXi?^B;*_o>)FK?iXzx>hQNq5dCHl451*QwCXnF^IF#23(e4-f z>~;3OADatzMsB(Z#363yWyV0jz$Uq+{YEw^RZ|+t+bz?a!1c8frTbe0aF50uY650H zVbGeNZVcIs`^n6J6V&1tn)LQ<^Bl?MaSpnc61n$n;Gz!1Y=1}K(=PVa9W~3Z=P)B{ zhw-=FFZA?X6@^48_trALf|SK;8WvXoqBo#o)J&%W-amuC}GwN$yom)l3Ae$j>j?fy!cAPy0Bp zTfq?A(Xama4YGa^RO086?7-OSE&X0D_XBE{n(6X7J$mX_5UPPcnP_2hHYEO#hxw^0 zdyQOib189%kbrJ-Q@>HMwI;ar4l8^C(sy6YX$lNLlr$+LRGA)jvQ{>^7Jh?7n2Rgh zVrzVAvj0sfy%Ax+XYb1h1P*c3^_d&3sta1_fm>r#{e3AnE#`C54Ip>XJ8}X!|8o4CZm~d9 zI7XOV7GQDBQ>vcBUt!IhY>e2a;k+Ah^%fbGfw68Sd%wERbN!qER)xh(v8}Pc-=anC zh1nhXI#9dlYUB3&VXFhZ;bhLQ)aeT;r5iHaLm2rydHra&H&@LkKI5HARoiADUDrdZ zW<#;5m;oH(RG1x8m~4;c{$RZ}hQ<7INn7{%Re4N6?k`h~%K&mCD;X_QpuT8sHgi`K z4WXg^uRYQmssq0WUrksTFU||kEQ0N)conwnVaY&ld_+P_zz^Rj-`5HQs%$nvY7hXx z;ALakg5m?7_-HWsQ@@w2nu}ylW!qZp56&pXq+hN3|I;sH&?KO|TR?Umsz#{OIVeWj zTN~UA^66!+XRUbLhqWR{x^)-(qvlFQ!fb%tt|u&b$IT=6*~%*&SK+7{4M;SeDRUjK z-Sq2+L@&5qu!+Tlpk5zTA5Xm~;D+;O_$%c{uzE73_`>+j?F-o5fs(;WqdSz~kW^k+ zRk3LV_Ab{J0TQTE_*&H;6`{>WGW7CZFy6q4gLB88M;yWYw1H%q^e%w&L9!5)#YLpR zKm_Xqk5g|KUxl+jdRJ+giGW2!)=FkKlTyyM87=TNu^ zV)l|0i}<@1xawO)#%@%V*rbhYw0g1lbGSe{FFW%aLcvI@v?PMJsyQQJH5GklCpxWN zBt}p#+9_K$r~$srUVFrdz0ZIQPuTD)6(;ltXSR(p{31G4Ij&YLRSP^ zqF*PnXedJ$=uEfDrcC%A#f^t=P=TqH%7=NmK|=}-E!~O8WY?HhSK2EIe8xJYDDe<#lWFnz& zqa(WER^Z%j>=V<_%~^I4M)5e^i=BY;?gaFZAXsm_NWwUN4W6b1iLhG9_W8bxNWK^q zyP-;P%>B-LUhLC#J-!3NqkFf>WE(Z^Q`h_&&_IfHN;16fbQ&YOYx+&9cM%v^=*$~3 zyoQZOOXK)7yze6XzJZjv_=9%`GQ zU%?0jPO@GR+7}d}#D8t<6}Yt+HxQURTDw!vv0IY}LSLR`{+Ljwc}m1y7gy|E_1pT> ztcy}`)fa1aA$6K?tj^oSXD&UU8_fp#A*#TsN`#^;vaW^Uc_P%!HtOlj(%(|}UzNMW zH+19&j@`RRtpZpJ@^pKp(jGYQTQ7$Dy)$G1Z@7$5J}O4YN1{XJ3-oe|Cp7&H{7o}4 zy)2=>rES@hbG2lv)JhU9YhVi*Z*jH705OIFjm$b69g(0AwQ2;D3# zq@Gm@OM{Qe(5Q+kE6+`X;~Y++PY+;vLSbv;T%Yu zTb;{AU9)Ldw=LLgCn+3R(4DuYyVH;u^h0wc7{TsgVKaGt!DJ$= z$c)L4e={)dv49A&T$E$?p62`OBLxPsb>V|f5x!Nrl>7;NH;PZ|^aY+xa^LvsQq3w9 z38kA|sZ@?#m$2Rc_FAQDf9Js*38I_&(A=)auTnr?@VrUR)@~t#sP_U9vUQsNk0%=U z;PfS^|L2LzvL$zT5mc17sk@n&x67-gMa@fzu=@fLymgu_H}c$S6M^%PWYhuY;=a!lc3tzeX~UY7#ikcRHw6I)C;Ah^zrj2d^fr!|y;VQ&6}Wd(h*Rnb7>8VF zmj5!(JBUmSNa=nV*E(;D&&5lP(DIwzI9GJ56kDk~VWB{RSv6 zp;r1p(&))FI{9CZf1*?Sw+&jKq5CFy*C%%SbS%+;f7e1~Z!cX3%3FE@$vb_B1Of9x9&;HcnDY~yL>CJ>RY z*?1giY@ZEEuvS4|q%7YPCpp`zyIH0FgNm^<+Gtr3$b4vHPPxX`*C$F!f-HD8w1j#p z{XKx7?LiUENcJpNE)dTg9eRt}!dIY8-!N=i-fyn`k3>JJn0E~@g1Ago#r@)B0KZa0@^2;iWly{9D#e2k=m`SGb+=V)6uDCO4+a6qj%fQYny` z&N5a!6MLTsp_z7Mf1F}d()i*AtYPl>`WA*vFR4zO4i zA(J8uNkPs#wlK6;0W1 zK0WCnZyB1ivZ%stw>iF|CaWWnGddho(ryWY#9izP812M>JpQ4&5che`0Fl*1Cw=5! zEjUh|m3tjA!|w-iuZ+r1LtzQAY0>eP4#GF(^B*aby-Fgd#ZvO|YY}e1AT54d`Z#Drbg38>7D#E^JZHf* z@>n*DmSCz8(axMHq9xYv1}2Qn_r~oR+7s8d1ePQr3&xA%K6*VQ_tv$%k~9WiX$n_C zsolA6n(C(HGbo--xLpY!lc!eVn~;@3_8dT6jf zW5serF@96klyvDsDON*2tmk&NmYAwt{ZHmrruF{N$4$ytb3mn5;^dnTQ+ZKhj70yqUDBQv%!@3x^xplozG{vCx_Y9mU^~KgCy| z`nT~_L5!~zaG8wI@7UDbDw!q>&!c7c0Tg2)uW_( z2KUQ`!_OW$(nS6%mbJp5DN<4CN1;&4%BHc!o`ZG%R+-~ z7jL+dbTv3Mxfmq1I%QRuKeq3h2zQNvcPOl2xzAwPUx{r`nXSa;pI@7*p?Al-RDuF0 z1==#$%an+Zw8bUu=6Goi0!3EOyO_5(rw2WituSBBkdw@k*F0rjnwy2KC-L;`u}6 z{h{bj-sB3WPZ^Exleb7i&1Pru+|Ne_;O&nI&Zb>8rfYQwq7(!vV*>^w*3#$8ysBN|r+-7B3hN7G7GVG>x8%X2Yn5pTt%*=@f7!idHBOWb&(RAQYb| zbicw~s0!;;yl8Y08`?M#;)>})2B2mgqn}#w0$x;K@Z~Kerf);C`Gp2RS}E(Efa<{s zb}jVY;d;W!z)-yWJ-E+fBsY-K8hsiX|2iD6)uLc-JYky3uLJq>#c$iUVLz>Y#mDl# zpEI%qY48qKGi8o17ji0dR^Oa>2W3vxc;!Z|*I(kfeRvG{W>SnVCqK(yAdOLgO> z63B`DfO9C5T!gX#8hZ@HX}!OKf(o2n)2Pvpupw26_=mkg+d) zobWb*NJM#y2o6NSfu>60QU{IgsDuD1pm@T*mWzGD+b-_oq}0l2L{D)r4W8GWxF8mG zlGlvO?Rh@Wd9LsRS4TfFJ3-9UCYqAhIgl$86CwLi*BwGxUKV6zqt;c>y^G13-z{h% z%igICu{*$v&D`7Q+LB2*$wBildhW~^w;C9mF}dsEubZNiDN~=9W4V&;2$VwW!RJh; zC&VWfvxzKV_ep~Z1PwHmqz;UrD7&EV%0HuMqm+006V7UCVLKK|3#Y3E`-E| zQ^f1Ln>f5}WYAoogYoF*PYhxm0)%ZupfGKr z7Mo<~9*A?$R={hTuyrFyzcNQR!Qy^m0znTBE9=l00NB>g#)t z(zs#h5u+PNs-iGUDqAE5A{jLC={SY@_-)#hiQj&JV3&qn>Dok_e&g$pyyU~2HfS-4-rePUn}k-vRalR2~nHRfvPS=&43XmZXuPVC}OE(Xw#HN z7`^|C|GGOgL?dgs)#PwJBJZiO|8&1l9Nmp#$Wbd`7wVIH^`A-*GB_b<)y0YG+eAKf zozeMk?9YK1E>UQv-@cDjp~u0o4$7rjFR(x}D3}pTR%x0#%*i=vO+ht zBBs?vTU#xSV+NFkrhfS77X1qQA1-^P!{>(%M9Mh9V^h_2;gWHqBZW!rT@VIkEdDyd`@Q(K$JumvVXv@U$AzOY2`_-Y})UV(!lnr}cJ zx~d(`gw-k>mwA;)+TdjhHR<9yV3S>qElyq{Jr0X@h#P?(rU&K|K=(C1C~GM{`^8Br zS_Jn0exAB%VF1dMyeMj=%E`Pl>hV{@aB>)6&VV zmWuciS#1~V+;p)hlmL*dZd5w?HyTRDl-06{3Sla?HRIWu~o1Razj?;>)0e1^v9wJ$ns_>;N{y-3tYr{G%NjeA=IUjC8 z{R&eWtZ5WdIy~cWd#^kWdGl$dcO;=jXsEE|TvJsAn$~ z@Qy1yr)U}FXsS+QtQ{@Ir~7+nmc9`4A6b*KxqK>F4aLswSS?;4J8*RUbop^zpey5h z$uO^5^(rvsR3LrC_&F7YBMw?XzkO?ugQQRw3CZE6g30R8m>sc=9V(B}od(Q%zkt8^ zjZCtE2Nl>Gd3{ z1T{@-se7dP5ZpWPv^oerM5_usfiP%Sy!CqmWL-=X=W&n7aF8o_L9f@x7ZY6ISY55L zwmM{DEkkAGuw4vda}k|89A-rY=U}?RKa`s7spOdab-#SPT!T$z&sPCeUh4lj%puhv z;C|Wk_yz4<_<2#^E{G>HqoVjKevwxd2-R!zM+P@bxLc&D>Bg#iDx#Nx*^`+mJ#?Cd z-kry)@=!!C0$7uB;${c zD&Z3drIZO#iwR!+KqpWhF5Enuc%9Pu3OAN~(AJ<|FltY&|v-?Jcfv zS}(q7O#SAY!nz~rU$D{5588nPj`pK+?xJ3$`klDsb&hiNq2`!c}9U}CV z{uRX4noOUcJ5WWAiF$2nbfp_0byj9xI}0^8T7gsFvJ*Wb-Bvv?MSBYlAXvsoU$+Wb ztClq$^x17K*i114wDn*pd{~tD+U?L+WOd5Loeqo4$AvTR%K z+aR+JZ4%dyQL7_%mB(A4ytjzWU<9qDEL@zSqU^Y#ZD^Pi#f?(s!l9ZOG-zBbACqL= zbm}4#jL_TK%#SJCmL}|VaY@(0I!jNX{0y(%i{=eY9~LUzz5g)9vB&m0(%8G_dM>;P zp50Dl__Eh047Q0herX>b{`HC|pnxcK;3@W*!V&NUYH2ov^Jdv9SqKHwC<&PPe)#Hp zTVYgQVBZKuTUdebNy>_r7*d9y)+g_J=0bG>uMO8Cxd%I%v0ECN_yMJ=Q6w|jeblM~ z0H~kgF5O7y$u9pYx-1*#n_wvOXD^N09?m}{pCb#nrp#isg>Q_FIPI}t_>ab!s^Vd2R!O*>d zsK3Nx+fs!8WLV28vKNokGx0=?H(n}d?2u2(uwKcjeQ{8A!1yGtG_@+$Iq_|SK>20;qH)C z=wp5N9PRpD@@>m8)0U+QKP+QI{Wtb?%p67AkS`e<=gzBiWgcH(idtXEgQiu!4h(kL zZ;KHQs7H8YX|^p)d9+-K^=dkqoZ$x7=PGG{V@JjMLb+Z-v!evXR;|zC=y6s^Ts~=s za7t)00ia6SBJEXAx3Eioi;*?qSdwaFnYS4pt;1!&u&AnGvO>H4e8`GZ9{9POMF*?} zfyuaX)E=jbV%Nam#BH*E5_wJZ1N_183*OvW_?Agk0U@o#_^QO_zhQWBoJ^sD-EPbF zuqB#0k!(`djQ}2>Jw#|qS_%tJgcSTt04L$lY_Q{145ra1PrsE4d?(uxS?^2t~f5W)Zu z`@~$J#sW0fHrNtj{%t;!Z?I8iTHqvE%O}nIJGG^RV!D8z!s>Q5W=Qcq+$&M(8Kv)~{XjLJu`6LoUiXJ4+ zsXC0$rHx?z8;*PAYLiv){QqeFHT$+&2VBXVi4iv4tZO;Eu|DSDT@`gl-#Brn6~@Hh zgg^eoH-G$FoWzqjopyLZk+Ab`@=j1}sq-3t`@!z>wOQo|^T>L*NUvuetlSTuJ#JO} zm^fry=q&80@R4zGby6Fra}g1<$Q(8DmTYd>LVG$s+{7~eu@FiFtaJTP%6x5EJ+{Wj z11+u|c(cdGO(S}LTGfmWu8lkfeeLu3W6IU%e`ji=hOrR5t1SKax9^$(ttLMGgqB9C zFH}cl_jWg7bq9O@%4U@`SGruI!C!t1(?C=(IDt4B>eOtiKu-sNq8#Sn+Y>OLwiZbx&7!QBea<@r=`D1W0W`(1M1S9by`s0IJa}7!_5{Z zbf3zw^0&=7Jgakv22TsK81+465zmY(F3nL+rFkU$Xb5PVdu<35SAzs*R0>#F7e$w* zZ(+(mBMx`_Gy9s!GML_Viz;g|aF!$mGW}Ed_bQaZ!uq3z*mp_6tAseZC~Nn6&@<<0 zYM||3I!t#5u`~AC;Hy9RqUzvCl`|8Q7nptK^Mv!Eb_--g$6{zJ;h#kEpdAt^^y2yu zJ53ou{6gF(do>(5y1NeS9>)tgu6u~PN6e(8Xm66a|5Fx? zD*jq$DK*U!xt$qp`o4l)A~p*g@jQLOIf^InQFFFwOPJ3~+_c*Mw%y zyU`CH!;xxV$1~1awk~Z=NYRtc2oy@F4oSEkUW#|-$5<5RwkP(%L%X~u2GpVBPY8C_ zMQr2Na|5$~BiEO(BemCMm{fl20`DODfUZL9*-;JgiU8J?o70)h#DMo;``#1(%utV1!p~g+@auM5v zpehBuITQUGoQa+;%<~=`!;sN}qtPJxo(7%+<8Q=Am|}o+Hd|0VlCXCJ)Wp95${Cc| zWn+#e*M}%ahD0$(x>@0hxQF;QF^&`oY4(CzpC+qX(as$>Z0z=t<^D{It(C`4HWiaS zy&s(Lw2fzdt4_X|&bEvlSzNz}Ey_kyoH)y8@NNjhaNQ@bb)o3hgn$BjJ(5yLw8WWe zYJkNyicKWJS5t&)7ipW37n8$kU6T0H15p+R2xOdl%WYLjt<|Vj+3Rt+ zDUc#lx&c*Gm{32B3#m7>1mre+$PS*t(gRc<~0k-MC7*^CNStpIX16MPH3c8Bh{~b!pG@QaoEHqDF4hWr`%oEaGh-ST_e0(JV zm~1csT_{@8&Hv>llXpQ-9965wbGESrv>D5-|b`wYPC?O!uMmIEJ@Ud3NYx@BEFgq zo4SQROBFGB2F5?|7~bPqU)FCFduMaFHYH866%=Hf(mnCFQs7`ncU^mKlEs!W%Hg3s zD6gzBaI@DlTxD)_LR@b2h3XdqfQWTBNxEYw2gX8yfBWDI&-%g8&%XB~J5D4Vg*DH&rb70xrF+U(;T$pk+GTM~gV*{Or zAo9`wGtl=<`d+ZLS_FOoQ~B3Ed?OqR-<08OlQ-tkq9%4G3w|%|K(nQ=l2op21S;xo z8$QgTfpBH4W2e;r8N8jMo;$IuU2RQ~HeDCkPoMaEmQiAysuMa4H+q)7#kR+$fU>(; zN@gFI5?b5srtOVydwfUNKM-zqZ9?e<9!E$`K(X)WL)4mw4Bq^y#%Nmd>wksst9#o| ze;8;oP3mP;0>^Q>21?Ae4L8;%KtD>7;NARlnbN*ImHND;QP=;kkeyiv^KO`2Vb>XN z91?LHoaRYt(aEx~cVCidy}dzIWF5_Y#FOp593$ zF5L;rb?~iNwqt`1)-zh+A-Eg0kt`0?b=Ma>I6P}F`W^enwQe%I2@W?3u@iEm#-(Ro zTRTO}tB#950~+!&{!(RhGE3awX75P6To_f07had#Q*qeD*mLK9=P|!dS_^SOefk5W zS7FG1s^r7Y-!Y7L-850*I_Z{eYylGePA%i@Ajyi8p8tct1Ct zyCsSJoxX3+i?bSG+zt9DnsRFNDTlOLg{Lw0+#G01BhtVW5Z`BpP1E#Xxs?H>9hD~! z(lxp`NTzX!&MnTAT=nc;bBi%=wu~J6{mLRK!YX}bd;eG#vwi-C|4=B**CDm5=)#mv z^72%Xv2}9u4o^l8FFT>s0~B^YSkNf~((cKZa>mqcP|(gMp8lh)e{{OjLE}Wlsvl~f zY1{s>?-6?!xhIACVU%j!`7QXD@9q9y-veZwqw}6A(DBeNtnK}8>k&`sqn*X9;D2{_IlEZe zf1!AZJs+?@yvu=CbLP7@2Yh+{_$uNBUMzQ46w5dwiSc06Tj2n(uo!%}?B+$)j~#Qf z7;F*|Y&W<2^l%;pob zv|IneZGT6>7$38*7UbrJ{H6^;9W~cJe-NqH?tLw7S;oV(P(x~Tn2Ul8F@@=-zY5F6 zOEtK3Oo{bvQPVj+R?xcvC&_8&%O$R<|GBug;`=e?h#)68F0=#exze4N4w4Sq(^Sox z*~A?iAV+rHTZhjCZSj*XiUhqaTt8Ls7vL<{Y;XOAU>)OF8Yb8$DeON33xog>f8M*!x|@4VjO3{eCJzsyo9p0zgbG$5(u7E#RVD4Aev19B2o9>%QWyLR)TBO z*9orZNAzkliCC#lNN|gs|Z@#c7MN*0N@56;QT;#+1tx^Ym zwvE+rdTMBI9luED4OG%vy3G!Y{NM^}^pJwTI*ASFA3|j-`*aY@uDP+qz|dJ9nv_kH ze9C>jQ;#E35S_nazq9~?E4U_VBb1~m>au(T6gjBo%2uUym0-kNg>oy~}wNkf?K znHI25iVTYpD^-9%0XT9zDZ1Unm-<#e2^2O@+UjB<7 zGk;67t|w>bLjwM?@cse!9}fTC<*w)0yTYK2o!~io=|I(2>i?oYI0F;vW1x+NSK(3_ zR)8yo5h=2T_7`;rU3Q;~S8EPpEyM7iFiYOGwym#3o7 z^5!$Sx}vqQn%=SV1d8)iMaRU?`6M^=yl9R=LE#^(?#Bc-Z$&)>ig{^2uhYcB`>kBr zS;RBYG6+C3sfqy|%U=k16$vA&#eU4%MsMuWy(uh`TilHm@ri9t#&5#2o1{f?Y{q<` zi}p7vVsSncsgBHM!GZd3`t#}nga>QWZT#cuV`;27>Ny(ghT36G1c1--jY)QGb7@d* z^Q1}Fwx!=E;j8=aom~ooT$8g<0vuypl489&DT%cHLt*Jf;q$UL*}s0xV*#u%dgTgr zFrC&NB>HnbEk&tCsydsK6Hh6Q#6r-jAd+_|kNKSq5TzEfQ~c)x2Lj}`o@yH&t1wC| zmik(r1fOf@x=~ZGWBp7$d`3-xw4fu9srC%0%(C9q`!YZRnNVq40=5vxBRK& z&aHMCDN|lI*j~|`gnNa|G6ekmxfnagg3~8n5S7g=)x%Ifp_jk^v#;?Az`pn>jvyWs z+9--DByopDHwn1Lq|R|;8Kq&a(_i7d`BEhqi6gu0;a$5%a+v(3tRfBi6OqJrPVxx{RQPI-u3`V^J2 z?p2n@xPCR-LGK8+94q{eBV4OF2(~;#%z4nMpHYhZ0~R73!nCpZB3-1`BzJw1SGoEM z^B;H$g1-Lk(CzOXfu_7l;e0W|mzV^YhkI9>`^J{pop)bnJ}~XbYHvU#4|K|iGF-&d z*5s#V)lp&{`p*cA{7br`{2*8>YoMQ_lj%)B4^&X;x!g%8slIRG7U<%i3`bcR&55i* z!ZPv$vaSE{R7PO=1e;hz-Hlp}cw}<;*lt>A;0fLCd(p{on(`0V`e36Pgp>qR$RE+X zymZvdJUyTCEf7xjzk$1Rft{7yExHlwC6?iqxl`W1;XC=uB6S?h)jOcvP2f%tA%mBW z%g_Fx+OLaKXXi3|eD`{AubmIJ8p{8s{Ijba+r9?9i5{H6Kj+!^sXkL^|KMYf%^|^H z%|KP^wbhBiJZYA+dx%U~4{b1pTBYH_Q=0L;PMAV>-eW(i@~kUlZ$x--uz31!`nCxx z_;L-OI-tp6@qIfDFI11nx(#j9D5hRGFn`KJ5U4J^xh)AmiSIpM2J|+X<#v|1@Z+bx zo@(BaxBxVjxVYgJ>y7YdEqV6XMo;UG?1|~KUcKgao64SQs(I;j)j=k=G%{YznX7ja z5!#L)5*O6N<9<7H_8Q*dm#0`-L3wzfpI0eQ)iesM@s1SXXBpE&H3W~MyzPCtbY=FK zLS*I5<;L=vxAaSC|&%OmW^6J>M0CtbLCx5ah2eK zzT4Yd;q>-p$dSqW)b4RIzu-V{NV9#@-%Ww0``o`@q3ELWlB*RfE4H8g>XDsh9-5r8 zm`JMgZ$qW}l-i!aagwl!zNuPDmfJ5R0TZB);9Wf%;+e0gYBt2~;{!C|=R?1UBn0CR z?0uT}EFb=wW<7`8D8tydfK6xkt@M~NOsSG{2t~b;)(L{v?Py4b(=_2 zwT5X%(TzeRLXiN(HO%*=gjxPp40J`gaM6V~82?LkGlSXh(K!1nUy{ zibo&3zk>Z<8w0>Y6)|AKN*2fsKV#Z^pTd>gDZ|8d!gzP`Wa9KYPk7&2j5Ae~1YzId z&~Lh}EsR=6P#MuxI@>HdNdJb73tRuxj@Ykl>~bS@$ehO%e56iL0s+8fgpt_xFHf+; zHwjQav}(<1m2a9OqhVME19m+uzT(1S4+hGqDF6oaF|*EbB|rHV2mTkn*GBZVqZv?x z?T5*fa_VCc*L(44r#xm+m^mmM8-=zZ39ZAY&k3LeW7*d&Z#k#)P4ZvyQ$}pd4ihjs zGCagl_OSS2EaALzRfHNV`VLfylGfaW&M*gJdf~XUCH+QVuoto90i-4b+z8rX{O5f! zJ)alusc8$8s~trW(cm(muTI;2%~CE086lc=QSCUb-kG?JP5z!^)FW*%a4?{_AnIj| zJ5`i4VV_4|P{FTTSg|8G1lu(^fY%LUsvTm}7jBh)> zugf=6$et+pNnyOt>GQSP=)&((Ff;({!~Z&TC2V1nDv*{&%f$v|s{BI>aj2plD&oB! zT+kFu}2MERnL4K{@!IF`S64WuEa8E z60ZV}fGLX+9YjuT!rFvdD}t#~w(5W~8ifx}uQPi~HS*Sh$iRCSvgs44Ug|3z3GA&f z?T=)+*e6P}VNEoRRT&LDBk<^U>wzMr-_mgb-Z9X(*5|e7j*b0OE9}8yWX{a?n_aq+ zdi*qV2`z6u#tSPUN88`SZPj&2i%-aA=Sq+nRs%k%^{=1%ambAC`bqIW^(pa=-BTF< z^S$a?Xk);cP{2TO7nj?MXs$1f-Bn%Eo6x=Ww!t!%510UGJHX>-XN*Yu!d-z~ zAwP4GsC8&s-j5f5ftQYXe$bMMz8`1FbRe2UWRFnjSI_n!C3fZ~Dh2xP#gC0NAvpb^ zc#X}E$3UD=ErLYdvR5{xI zal*Pf5j}L}s^UOE8FD2c$Wt;$b!C6_nly^5-Pi$K_?k$12fSCymOv6JFe{X~SkmM8GJUrYPaFA3(z7 z1iV3CoFE=spJHMgIK`>U?dOZ%PFmsT|lg$2zUZt}S#wNZv4`BamJd zZpwrvCO!NAe&3cMsg{7&7B5>~13Zwp@m~LAc3C5e16k=PWrm=2nM@ zS`xAo_0FX7V({a?b9tj*bw_N3k|IKUr-K_4>_>OcYUVA@+v#f}SG{f$?qA*!(vaAW zfl1lPoLskA@&?JPcztxa(xNG1ZGpB=R&$K$Ef1^qfwP6pJ8)`$ z(YyEz+JYgBRQe3875UNXVbx$P20G{Fv_Q#g!Gc#&CAxQB=b~R=VP{akO1{^i9;Mz; zZu1}()eTIf+fcRA@ye@)aAq%O)H|AW$I%_9{#Ja2A`*T^ywdH;X#nu2q?l`q5Km&o zJ)ni_hTN20@-UdkEzNvPy`6p^bwN5lCi6e6Bgz0{#IFnHn#PJXSn+zllX_^WVahSi zU|?|k;hj*V=tZ7Q--v)U@VLtw7NBDnWq9Gj&vxGZGq9?;s?t~)3z{&gFMAxnxDrFZ z82Q(BC_u*F-tWyC)t-07qbxChARdHjz4CQCxd?me^*GZ}Q_i07PROhrb05s{`57mo zaH?sc-Hb2iA`x2bsx-KUq;PmQ zq({|mL1&{rtDkbskFJdQ{4U{pPBXKtLL-D7`;+X0SzUCmEJ@kbsZ>ydo|{*w&AH~S z{?Q`F_BQqHiQq#WtQA}wCWp_Mp(a-t>L6oT2sS#ItN@r9EI{QOH0j2Z4c%IsGH$~| z9b_xtoU;tgf#iyG;cr|=7bp2?JDY42TlJEQY8@wel?NvJ1i;cDsex;3Tb0VTEpUy^ zr7Rq5u{%DHM_DE>)zo*L#8@p7kS@(1W{DlZ7;)%{>EY$5);zuBr~_|sP4z}>XMI%b z)e>Ir%eL*&ir|~ys8}nbpXhg#KXgmUdKRX z&i1$#h~xTxP6ep;zZ_lvkjk)HImiL~ot6^QS<%3!UM_ zKjMvpCR_meHdMbJLY<61m|Q!pP?(*-!)*vhJYzNirvp+2P+Rl8E}nd4(nGtcQD-0+ z_;Rf)LtT!BBGa<8!Kr9)A!;Y@SyIiQ|0>%6J^Ba*}ZXZI>;i7 z!ujj=d~iC-$P^WfQ$B3G^me$-G^8MHZUb#S(Ya{EZ2ZUaL`eZ`dRaOSye}RcD2bDi z#>ot#_A^x~JvMJ=+(f|bcNy_Siz(!$D~W51S3Os5erA__rR zX@)8aHtOG2A_=rqdXxL-b=Ib9rsuYwpYCAt1>4UXFecXxMtN3!IJR=0ZX<5LfP4!-o^%^ouz2M>&svC*$t9TW&)ywSO9 zefXXmC>d7)*cOOU^Ii`h0N?2@1^?HoL`KQqAX$bixfp_kvqDOtJ{Ps&>Bo7&h|sDNABFSdO7cqla+rm)M7V{Zp-5Ex9!s z^S^(!Fry#v@zB(lZs@<7l9J*TYb~(uGMGym$JH0sAnHKCiAY#dRia*@v4nJWuy!lK zp~!R(>%jDL?PF^4#GQnfcik45FbZLR{BbUx|51x^VgLjTa^-k$&xEln-&r>;prN1| z2-taJvZlzK#W!pW&7XS*nDTv{Dh5PZv8{Sz&}kvh`s;{8+?+AgB!fS8Oo?K9V+HN; z+-<~VtP}WO1+9xxl9#n+l@bd2^L4feNfea#;zqA321P9Q)?x>Z=2M8100YRI87>JU zB69eBTt4d~;n#+{3Bft}QL61=NATc4&3XPB9*db2 z_;r`vDvRht5x=T@iWe3)WOP`;r~P&?{jz@;VC zbaJj~IRpLArwK!~#C7ND`8%@+?l2aj4wX|xPL;=2*TsC618 zPxm_Xf4`Mv^?9_z4cKrV2HeIFjVtb~iGkF)Fe06+54$0>cMZ)C#~&QddL1p+ygC3V zI~tiO>pDbO5kxJL+)Z`(Z7JN|n==ywf|s?_{7d$KhZ)X#galA14y}!jCgW9^nwa#Rn;_8=3PfOD=L;<|t4zKem@;{_t+>cplQ&_D$Y@9&N}gkT55QuK%`27zIe{pCI-%MIZ{X{ z;(}!rb#cBy(!BfEAikVz`-@jRCr*NdF=T=1X5Gm;180v!X3(;aw2tDdW?JBl%&;^+ zgr$pGQ>h=KA{6nA;IS8q5Kp~(T);}puY)((0NVx{xu%b)`^%51ewwB6q8tb|Mn`KB z0grGl3pLpJ`Fc*ElA*8@uX3I6JkHpyCH7z86NtP=xT462S+}K4PE4>Ztjw@Iup8>% z_D4c=4>XBPM24>L8y#V;>jZRC5&n!!%A`*Y>Q}Y&rNW%VR%1*^Jd+&~%a;a=w8yj-SNcEnEHzoTdJAtYlw{Vz zD#DEDZd7{GJpDq&dX+^pCw$@U$kSo&j@i${_w)TFrw<~PqBKxh_h!X3ezi-f$7kE` zX|(C4=F>AGeqcz-0d$#5-r>)x42}iPDl1UTKfv1uyX#Q9^<{wc<6-qUS%GKt)qbrZ zQcCcCf|WGq1zGljkoMEF`%PaBAE$QRp&jN~#V_WDd4AoJDiKzV(ClWX7v&Ti8+%LB z^&4r{*=|ZTKy+9QTqoIGHr;3E{EB@l#l^6a%&@t~MxM5@vEeug9PXYhlxD{*_Kr$o z0iQaiuR$mTH=eEwpKoFdwbt_#->nUg@oJ0~$hN|AgQuPTz4&;+iy7Y?YxT7}5H!(G z>^)gg!20~}L3WQf+KS2SBkyS(Btb~j`k;YPNE-bf+Y9t5B1`u1DG2MN7V-?N>R%!ag5^ zHn%baLyuK+gEx-87f}S#rG1iG)e;4RICk5m40_$B6}}j=t*g!Ub+^m(>G{a(ut9#XwiitG^v+(ku-F69CVI*Y&B z^%ly0CcomWs?xin#g2MgA#~FU^q)d3CV!hRHe|$2^OZX+C1c5NQ0qU^(55cF5Nu-zfENuL1mbc?ejBG+K;UeX@?!3MnpDXOd>fFxu`yn0EZ8Re?dUzqA&_=$x#GeCoRgKHZcVZ?lDVmA~Ej$LS zV5wbT!;=ZYCb_`#VG5J0_(ZcS5$e*z5q98sIL+k0@&rpc-xlv|2 z{d&MIvDQkE?4aI8HQu0s zE3(|AfIoSNNWp{g#_)-h>6!rl_*O4gXu@$~e$?Dg@virl-15=%2aS9>i86-_FxPA% zNT?9mjja)8336@b2?vudHoX?$E5Lm zByC^>C1*@!pkQVVW7x&Wx1<+R#fEj&l$H!*`R5n>k1_E3x-^b zI0Q=y0jx|}fZe1BI$T=uQU#d||JVDy z$J!(2?g9dspu0baaI``8qqDbm-t=KWY++6#Lo@PfXeb=!SQI+#h7~RalANmQ1gphF zM(MxbaZ-Lvj~{iuOvMGTOD485$-HqoB&(U`hhRUQwO3E;yyr{+H!JIf4TTLdTi2nO z1_`v)EqxW|+h3o}N`tP4W2tGterEUonw>olCIM5td4Lm82p`so2-WCRrR&*bo$aKt z+6xF}j{R2|7W5$^*XN2G_b9N^zDAVlR3U){@wv@}DZc?fL8$yyiO%ON;bo4iUW{c< zn0{8KEk&B*y#tb)SjReNHoZYofz$=% z)|Z9;Nu!9#iE{tX-NYb}Jf+z&39ii}PDD=$eBq(v#2!DwrY=k{;e03#|GaS*QsDD> zKf+gMsA$IF)3NJ?g67K>*m*SAs-d;v0gbPGDH#`@19-22;X*%56HigTRP=&-U-s@Rxy~;j^PC|NBQb?mfys=5S&0ceobEYNqtuHEs*T zQcp!E_v_8Bc@lTNJP_$+r?C#eJ;@r+`%Qo6UPIVun`7%C2IJL+>vZf0k}978&f;R` z*Eb~H?pYNLUFM!Wvw|ViFv$zwm-}~DM34E}XobEIcgK`!uFtgXz4#JN0(Dj=fX-)_ zXlN^3d$RjpVL?pRsPOA~if*tb^qBpME<|-d)pT;8qIY;!j!b)c;mehZ z{Fx!C7thj#sy>fvEsh5ZCd)n2e;e}XTP-ySPNsAQ33Gyj-LO6z?#1*qb2TvE%G}>H zhD&tFDOu{LDs?BhD)|rH$_0Vuem!-6txA5L2%G0^R;`jIOg07I^vlFq2r_0W3cwjt40R!EBvKw$I${% zLSSLvi)~@r3p3QfI~3#n9M4sm+z%NMBd#ashaWx;ljQyo!B-_=z zdg{*(UqqZ39VoA{(k8Y^{Fq8hVCUl;+5QxUu)PLq`g>qaO088?qWsSoyCB*S+M!!S zyj!bQ-XbOY@HPD=fbt99sDVVaAN3yL%?8~Nby;11!G-E()jiPP=1+x z!WcVTOE%IdW(Mu_H5(pEU9)kqhDLRmyv=+Qz(a<$76Yb?#+t=wGQG=XQu<+qp(Ux| z|Ccn(tXUJf(t$<8Me;Pq8bUV>!M_{yt(TCO_IF zrX4!qL8Tm064gQU;xOqums9IHBtA zJZ-rOxk#D(d=NNC3_Npu8dD&k=le|}^84UGl zSEzz@G|xGoe)SIspaZROi-1XB{Vj6KSI^*9dS#Cs=5xoSQ@CkUzi0W+ZfbMK&Yk?8 zqL@DkJnS@*SSbIEa)VLcrBt!p>xDxiurM-%#Heq5*!;YAByF~ zJcEpMxeJ-Vq7uZo(n5idEBgq*oe(Y?9Z+>;yu+@4<})s17|&O{ddV*_S#P zoMa2$;|x&Q$6u|*$(~qVtrp|@=Dzi?Pz!TM^3mWrI>$bx#11r6Gs=gN%@<5^<9*;^ zUvJxA-q#cDV$Mw41_qOCpifEIN8+pu{!S<3#jd&7gh2@N`8@YMm63j79C4aqC=M@7 zc%GH3?&BW8Of-bZzuBx&XD!)H6x0FTukDCGa9EJ$?hD$wb&vXy1lhVjE*(kFEb;kV zdO%7aW`{QsngrqJv)S2QHwxh8-0s77pMw+UZZ096y2SG02;I9fC?U|*43%;hOAH7e z?rFfzuvvhFP81Y-a|p$zJ20j7Zs$vr7RSVNX+;mU$VtOOhusQy?i#w0P4?@sle^Rj zH>Cv#c%Z3#>~STx<*-~M@5TSLI2C{XB3ZY{>!hDK{;7vzpgy@&;oVfxI|34ZI`bAJ zHF)Bc3ROjc%yhWMHDu^AO3qPD^LfKX0ri_uf&W3Rw-t%;HzBCQZsK22>qMRqGo~7S z1c?n_Yp9$p%|XnfPH_W`q4x6fpFNUmvU7UTrg(1hSsdtidr?-um+0fTk1`@!ZvMK! z7n(hn-Pu$yLQxZx?R={~2kd?0zo=}C*KUUi9ZRg`&G3TW^L-NZ=dq_x)q?;HF+;P% zRSLiMOHeF%M;Px+iJWje0h1W?IwARl(U}8ZH|cv(j3LNijj=&x>x*pq>npJ9Km+(f zHms~1*8(=|=Ty8;ZNX7%6#;p5N6!AWb1+C1oEY54Q=;?Z^pU=Y_A!)#w{d5%oG|?% zt5rQeA*1Iw_3)q+NK)%6{f{Fs_4JA`sPoZgj^KW>^Y1xf~3WiXo$*{pP85Y2${iBCplglrPcy)!oRgRK#w zt#GJ*^SGD)$M!tN_SEg&{mKtowgfmqI zs4VTKQjd?=phD?tgKM1!dnQI#NS+Y7rMC<}el=LtTgpTP_L4bbhJq=llK!G0&HZ;; zk_$<`*v_@$jn=te^Ub{6A3s!aW44F}ejE@@^uB3p3NV#mvZp{DUD381jZuW!fs5Y% z!?hslNKUkl*QXZzc*C(?qT&X-MdJULAbxOnIKGcKU{>QdfFh}t%BWzP3i9-~jKJgH ztR!V&+zs#XC-)`)T9JzyU4xH`eu|*@{pEcji^A#?yA863&4S`c< zDaxd6Kc5*6S0qN%*lB$ijpw`ZH24*D4nLO5-BDYUshmW~Iq670?U^0wgP2D;;_C#3 zs7EJ{VV_XUTQWXY0!)ddT^jxS_0*P|eQO2AlqK=enURfwYxA}tFGkbP zB^WzKu23ZBOXzg-(1kp;fv<^eb>v8VrbF;q?AT>LFkKcH@(V`7qk4IIjPL|B=KHb` zr5<1o=(#gWZ*F_Qki5+OKVK|yj~)nMZOGKVCn0noNhrI!IyvnW6+DaWi{6pnTsI}2 z+A0OSvCQJ*_Or%3eV+xju5mGKeaPWc>gDs@ZN*AxsLa-;qr_j7n zI{7j0D=bjrx z1~4B_qrVLAd1|?AT0i(Vuh_g=wp&Q+^5=EE*^#ifX~S(^-e9q?G*ZMSc(%Hbn@Ad) z`v%W4mv*ndR(yp>^vcgEB!&Mi8G4$*8F}rycSwh~=nW9tZxn_yzg?;@o?$?OJV5I| zofO2cF=hjtd&V%hFWGRWk$2f0_lIKZjX&zQ{okyWydN*D%km`>Y+7#S6$Jsy1I{>< zO0ychMF%kjbdIn8PJiQ_2!8yV=g66VJ_mL?KoPrhNsm5^gs8Oi!0w54eN$FuL6d;m ztxg}G4w6;SrfY@!F~fGxotBiOJ5^9cMHd-GG?jg9ZuI0kXDZ$B-iWV5PBU(S0RhLy zPrc8Z2Rv%F!K7KwvV+Gyx2&+C z%x0#~lL`mG2Ve`jKa`yJ5QiQ@Bv%3@;|bF8o%1MJkhLk#m5&`sw^*T)5yh_HTkB-Z zUEdEktut`p^?Xsdl*)Xw>5Ot>d_tIb{H(g~c#YC_uhP+-Xq}(nt^>8fnh_nw#pb_~ z1S~vy1t)(gbWY4E1hCV>O|hQeD{^GPwc)z%T~C(j>q;zV2?+|h-{c(rkU_0SWP1NS zX_V*n!Zz1=D7{TM(M5rqQ!*5IlLKf?JW?f$c$&k8@}KY-V#7}*^evGOhhHde#YC#* zD{a&yxa%ps6Lz;T+<3ERt7b98-S=T)jK83H9ydWLl*V9m;L)PWD)v0O3G$q10iZ%F zf^f@%Tts0X(xI!_XzlJJ_IiHu=sbQI7gc4T%^Gn~xKBt=r`V=XrZxOE9Lob@7R@k0 zm%9SUOQ6496`m8Kc)~rl+waAdP(o4o3+tVC9teh5BZGmnU27^iesRt^$g4L)<(|z4 zs8eDV4WgCPPf7S9lgs9s&B_lLDzE<*YJP9R?wBf@PX3z?_*4ykT==VEtzx9GUa7hY z%4muXsi$!S4EU(fWOdkx(gFv-po65Mo?y@ypi_Q!r1Dep{)+XzPfLt#iLk17C03?p zAZJOQy{Y(|68ymT6F=BOamRm--v=*%R#Zp(TwKFA^ z&D@~>&^zxVUc3G?wfbf6nOa2xwzKsYg*jRGNV^X)s@L&9>$>Zd*u!r?=N{wBJ8OoEKDHYP-Y!U)|5aj?swRQtWjR$ObU}W<$rF!8XLq*RBe*m{0 zaOzzsSErq{@yn^Q_`L3VV<5?KQ5buJmZPK!upp%Qtig|peNRty4V^@PO&}KCxKKx3 z`mAAzN~WTAGCrLvLSaqHDmFemet~yo#rcz>Sm}gD31#}$A7Rj?N+JLH1*m4rZO5?9 zpr0e^l%jCRq)GpLX7Mmg0&bOgg~KLQ?L=kP^|e*X7fMmehQP5sFjr5eKcz+i_Oc%x3;D%oYo?}{Ay%8S;b1-J|*X3&lo@m`Y zI1ZbSAko~EZ@$0#y6%Qz+N3;qvSk~U40mC&4K*J&=ky6@`$Cx31ojGD_zY0p`>+2k zmUqZHIF~Bgyey2_YQ|#*r6s7DY!cmtMFqQNCw|{b^OSXFB53Uf93&`C_Qu9-qz!qV z)a}4r#y%kH>8g4oLtG|YM?<7~dK$@u*wY4OCar;n{bT#yW2;98p9k_C||v`gw(>Jj;KfwAbGfk?;?Z!_l=7Ttc>vGGe}D$ z?$U%?5;3_DxJZ%&WRZvB*a63zYr14gxk#X^7lpGmvq zJ$12KPwFkK`ln$+>J3AfV-m}A7~fM%*R&xl0?fOK&u?u#FBY0!GMCe(UO;fhjSAu6 zR;KVjn`miNb;jm*iom%UzK!QE=Z2!c9PS_PXWxupKNJ#Z-7R_vob7_LPwu=Mqg_e~ zI#SPVUi}stzG{lK0e=FwxmfRKW#+!AsU5Jjgz)=4X$E@KmKsHK{#4RlLy+=W98F|C zD&0P92RIsy%=8E)401=r1PSB2PV+xu<(P*)sDkb7e-JQ*S&jFuwFjv$P(i8MLV_>% z@MRin-S@a<&_hKR8sM$N)cK3^?b1MGCC0la5#By#$ z$hf|thV@_bhB7DY?S3R=Q2b;5b{2vB6-4wpk3UsrM(% zF=dQS{3{p~V#C8OWQfc;X=0c$ZPr(QG($O?U~FxlRtk9%+uRsODpQ|AQINfdE~fl| zRlrGj2s4@2l~?KBO^Q=L1XdM8p0gf99cq2CBf;AT$7$h&VJNHa_dVuoj)Kq?WF;IP@YnnV59_gl*$ z^_KZ{z7_E^Q7anB8%cDAclZp$(S&Sf$q~8ZVM#ZQO9aiB5@E~n?~^q6A=17Gycz@~ zNg7otlW#Q%o>FzQ%b^UdU}594S4+{uD`VGl9|Nwnatfe%xQOj7mbUZ4XNM=O<$9vy zy9l}`WnUW#^02Nu>65|tm+qiMQq4A_C4!TfJ_Qt@ctzD z0V2SWka6aK9&{t~D7N|l)p<6t(>83nLv#qjfFe>hx&z->o|JR6=wAx8hDPOV~*2)=9ftWT)4 zT2(&-p)@_+^%k`3yPWk}d=JQrT#qJdpKMh8AYzons0|!lFKUM+23nEGV#s(pFutFk zECs;3SeHc6=FANPFw?*w0*{t-W7uN_7;TOI82UY^t6&z?(E*!x8y7o%U_49(q>Yx#|F! zu}3gtI(q8nW%#TKpJuwmUx-qM0AM~-m_#Dy}Jky71l;+1rQb)xi+AMYrF#(@o+8lp4 z$UXV;rU*R?kOZEMcH`(dty`>n_3d(KkF<@i)Z+1ZIc_#?;=&VeVnyH=XdrD8nD#^! z+Z*Fk8X=9<;%4W>-^=piI~EJ{@9F0{`+-TBL2nhp#PhUC^DJ{@l$5$-X~5*sk55X$ z4gs|#dR_I371_pHg+DwnZvVh7<1bI+)XuO4d|NjBo;E!sc~kFAs^cuHZCI zY5EcCYv3CY^ubU_3N3I84qBbwjqE4PZYN5B@6d|b_lDeg{JwCOb(-&I;_TLW7*d@QsMj@gpY6IZ7FikR+X}SjyVXTzRa8IJ^B90heRsKVy&Sk%)_UUop;`!nyF2Wl1vGjIJNM ztBE_iG%gH9Jq`rxsD@(gJtQl6cZ&DgZo1^Yv=FW&$Gd!HmJMG4t5w>#1r>gQ$XHBq zgxR8>u`191A0L#-Y3QmgpOL7=P%-43kFV_Lwt2GNtV1Z<6iup%Q-Za%dD<;mWaHpi z)P?J?sg8{BvMm`Uqpl2R%E-yn@W@U{*jR_OVBH)J1ma2}sicg*zyK7Y5_RTy(U=`J zkGNd|rJ&Qs6ihak6Ww>c2B7LzgPGe>S=;{hNs&5}HJn zaEa#DYD-Dtt=vJT2dO;CaJeH0B6Frw%&IL4+F&YcJh*O}$3+telFUmhW3;8BWef96d3lS!(ZR+(Je>`%vtNI)&StPTuK8;Zpp|Bg0Ua;oYz zxMqU6>Nu!jAu=nOV?Dp$PgkXq5D2@sj>|H%7Ro@Armt@h9Y_!>vfM7HDJv)Hcix~a z7fL6aZSifD>>GEwju5UW&EQNtUtuKBj>&EqC2n7wc z{NLAOF|J6vswDwouDUT^FSLssDmnb&tA;?G04(PBXq^Da7`eL=E ziXw6k5L6uukCBtpzs2BkDty~=+&&t(kS>?AQdPN25f0zhoe!Goe$s=r#^v2OWAn9y zJ*W*5^2p@9z7c$Xlc2H4Wu%K#rC$EXXIT+tSTe*CRDVAxZ>}`@;qzZPzriSU18xG> z!xfwP;#kb#AH$#*o)QCt-Yw_V?FWWmubOHsRa5;VQfj_5C}i?Rn>IhV0$=$URc5eZ zw+4w^$lR8cCRSO(1sPf$GoviBZ!jBc<1Z+i5jR z!pL9{I1qhYmb|I73)LIH;P{nje@g>;HQ+)@g}nnf(sk@q&+*!e%osFsTEdClffT9} z67kq{U)G)?)mW{c7Fb8c>m(r75a7%SS=m$~q7++pwwRm&5tY z)1NR4ymp^tUnY}}koFb)&(ke#>6O4!hkV-d0j5&F-Y1qivq}Ul%hv=j%-lfTRtn`$ zpHrHk(8Wc62QIbo=Cz`tZL5L>Y;cU2p62Zz6q!R$za$j_Gg-+7b zfh72AQGa52S!y=Dvv4|gSVq(-Z4|T>=L<^CmM7(&47Nc=^qh|_J;oHS z8;8^TzgkI9nyaC!wA2-uU`l^GxIptVoZOEWbWj&Df|W0*Qskzg1aXmJP%eap5rn=< zO0p#@>8U#)aw-xQ!)H5@HJOSf7fjIIMZMhg+>Z64Tyr3+-3bGG>yZu_;x;;6XO%-a z7ky|(xz79zo&wP>mI$5>9(*|~f*RncBSb>Ezm{^~<1E5=R$8#fo~VT5ENY6qVD65; zAEAiqg9`1?(9+|D`ZJxX?ew;fPWIQ(_D$omLH&NZjZpRuH^_ab^JFMHQ(r3R{>b24 zz_u)7r<#*}_%d1~^|{+H)=%jL>q;(+2Ajn(mo$He4BB8CvZ$t)-?}ovQ>*&cHh;`+ zK!m2O>S zOTD#9$XlicCZ>!-1^g(l52my&cvN_Nl`jm!Rf5XQDjj-;57W{af?;{FjT1dXKVQlrJnB$b zOnJOQ5ip5unQiRIynys)Ai+H;IS*evovLobzIhWv3awG$A)P^=X0y$`zKKlQ30*5^ zndBz8<8jTFG=k(lAsLY*O2@#Dyvx6@_%!upKzllepR~@oOgdi*@wqTrp-xr~l`oZ5 z!fXi4(T^;#q(IMIH_(O0#rBoA#oZZ|qL+A=+&Id-e3Cv{E~AMxQc*$eHZYkUm=6sa z6{faSc}nK52kL5FxxpVvmJ2|QF%=6Mh<9d4usyzO=gG5xAx$6B6G-ntDQ%R`JLU$b z$>%4*N`*pE`dBr0t^L<}j?4WR&8?DRYW8!b13uW?*&-~3jv*=bOP@@;ik0lxWTHX- zwmePf*N-Hky_3J>X#lRQ&Mv7f0uDt25KAu8-X(IfEO~UQlAmBDqSE(ReQRXW;+Urxb&0rC~a5HIg}t>-6*HmL}$+1Y9G7W2E7b{Yxe zd7Tmv2G>1E350Fk{*R`22cy3mRdP2R%Z08c$X6<%n$f+z9+qVhrLJ55TKz2t;iRS@ zGp!u+_>SW{L{@!nIcy%p04^B=kO-vmN<(mI&~TkL?mgwey;Q=J>C(?&2l&s6GeTVC zSbnnkUx1D~|Ez5LZ-Kan?3BnaNYZ|aq(kqaOCty4Z5!+pmuy@vn*i<}uMabJ;R=~b zC>Rz6w(-n zDVu4>s>wjJ2U`yg=B74-3J$Gl%yYj5igmVn*Vc)4rFRzWD{z%%nZHyz!- z`5x!F)L1z@8~i40pHp_fr_q*&n&sG0A-xOaWzm`g0N8-%_tgZ*iqW2Qt@}srWUzUg_#6>};R-eZ*Pyj$IOF**+Me16Ka|WH$;%vU4!+DLpcRjWp z*j-@*W!1KQd_DcgFXuH13JrT;?;p2Dq@lx<8tV#Sd0Uwy;Nt*GveUfKtvpf0DadUH zvu%DU055^!9}Ir03F!z75tXEAgrXhwmt;aGgIZEE4xF+XwURgsw< zkgN?`?QHRxdK82qnZ?1)yEyU2g-7gPShzNTy58e0gEp+TYIj;}8ayZ@Pt34?J`f~)rBokvK)=IxxaSD-l$00>J z&D8A{sx>nRk2$|lr1k0S zWzOZ!n>x75xLElrA={+(z}T{N!7dHRIhByE=|^eG@p+K4{rO8x|1Vv1yTic>)xTo~ z4sHgAw1ntFp+ z4V8e{Y~ohrF@aJ0LQpmHJqUfi(;klzc~$)|J^1*6#OQ%$vq?wiezBm_f!eO0Z<5?h z_oySx$+Q&11V|&j^>hKOWAUvxJMB(jVJzk@88no!nu?Wd4tfc!bNmiLeySS8YL6COeNiRXN375gXEf-2;aX_Z-)`B4WSw7KVmcEWR7I^tY0wrcMa-2x z{kaBQid%Z@dIE-m>QO>;qNRdZL?DIU$mvxHs~WF+YAr`9)95fY+1sBcMd+c}Ht=BC zKdi!&^1(5!cu`rLIm_Gn*;`Vkf`09`G}o%-T+yYs+U3~sOygN@T|Ab(R2~YkR&GKa zML%BucI54{-LkzeZFO4yDK|eM!9FMweo01+(F0wjk!>uA3NK2g^aJUmH{jw#`9Y266zD^{aNJ#r) z6~V|yT)t_aS2u-1|)=Ie}m5J zrH#`)grk%dI4e@7HFurDlJ~FGyObNph@bBqh-1Wp&SjuhvSC(=s#|GW%dK1hjOg!LYLSj$L~?Uh5Umy7V~ zh!)Ve6gKDfvrnDAeLt0!xtXjnA G*Z%=Krk5uG literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_plus.png b/selfdrive/assets/offroad/icon_plus.png new file mode 100644 index 0000000000000000000000000000000000000000..92b448b0bdcfcb2b1f1abede5f5b751b314353d1 GIT binary patch literal 2833 zcmV+s3-0uZP)WN8vmn!XzrJg`6*c(%5Ay&O9c%;y) z_8(A-iN%{1Vxe9t=wzTMcEYNVPpYHB6@e%5`)+1c6M*|*>B zo}35f%-b{1eCNBfv$Hd^zq4&yM6O-Cc1rFak*sao{X{8U^WzrYF0t?q3sfnSPoCr^ z!dU@gL;`s)h<{4l)evMxqq2K&hyI+3=Ef6W{hHEud3ipJe|hQqES$BzrVUOpFL0z) z0qD&d?elC^%MYzT@8xA&-vqP@d9I-BM^xaTSLks+FB+EeopM*@ei16T{(;3X)8f{? zI(AGq^D|~-aIKK4h*|Q}rFUg}ta_AV>8&~%ea08R&sf-9sAzR{FrM;F*M(bA*Z!jT zRr{31`1W;OScTRom>|bop&;O3TRO%p+`&H}^k=M`Gv3pv*~@&Rr*5n(6d;lpvd&Y= zw*&*qFn6aV4(U??J@%@M?hFlE)57#vTsCf0`hUYbX!&KBNSvBO$~J&nxV1R?=fa%iH!A=!>HCD=@om{K*pz_)3v*li^Edn6eIeXh_Y!qO`Av>9M$P zFqU7Nriz}Bdq?h~+@Iy>9ko)2`eT*!pW0DFRfrweR!V3dl4D$HG)ftCC6}zc`31yM zVE(YjGTZt-dWTp>Pxmnj2%sAnXIKgAme|La?UyK@QQ_BAWz?FPs_P@Jve`Oam7j|~ zr(>4dAg25%h(|RXrNWvWqa>CVyP)C3DJz#N7M^{o?Av52kMY@;-G0QvQN)(%`__sW zI$zJiqh7qbt(GDE(eJ#6o6w5ekL3z`Lf)?0b)1#^iTc+P3@Nb4?N_U~a+61xl zd@ih{NBj-CRam|NTKPOT{}L*7h(F43f^;ZbDgtoHEtcVoDlutJZw2doAFS*qz2Mc^ z^YXqa+aG02%kVSGXfrT-c2*kvH??I<3v{X9^no%W)4)2(GRN=w0Gy!gPnl`FBbO?V zi~&-W-zvvEEJ*;(n|YFq0oZH`z~LkiQsQ;u1-V~Y;W{6qb@`Sza-ZJDt4efb%m8%p zM+W`L4ps2EfL-hYZlW@~vT<6#OFIS=0cxuDsIY$F9^?KcZ7SK6uP%41rxSgJ_VQDM zylMOqW%n4jlB$r^G54Ie^ojl31^6w);Fz`qW%4+0Tnsk-k^Q&n0TKt8`bwZll+pz> z6}*G^1Y%&n8>>4C+7yNRO~4~cd)d-Q^yvmj6l|}0)$e!9os;V;N4fwh-H2U`2ssa^ z2j%XUyGxG6IBsU<(*Kk@A$MF1o|QkH2q?SO$@7-rk}!W?ov89-0f0VHW_IH}*kpX8 z54wi3;hJv$tDp)mHB>rO_CqOXYi~p$*()Q374H3ttuT(e7APb6R6$ckIp9o9c9Y)Vn`|n7 zkL-ScUdFWS@=BC+41z)viCd?(?(w&YfV8RBEsz@M@3kpCm9Bb3HaldohFzvthXgWG zpUxm+8>as-B;ZxpO5VY517=L7h2sa-r`uqfTK9n^GW|*$rau$KY)UqYe<>Q3r6B#^ z_+=Wx-)X~i?JjCVMUB}S#jZ+eXQQG{EVg0#=LrV;sH6bK{^d4IQ-I@>9}=h&UGeM? z5;|hAFxjan*JkbTZ1gl#g<+CmqfG^rX{%3}I{AB>?onrGm3hbM9)nFu4LKu*g=K%J zsi~RV3Ddu~*b;p4@i|O$Ug&>A0v?g+i?Y4O?$#GW0v_4ceb~1f@#x5v4Pssdzve(I zlI~0wZy)@z_KjN4gPLlTY341eLHSE zB~ca4VGYm6NBFV`buYCfIHrjxlh^d;3C~4Bz~Cw{Z9v61n~nP|KA|6-4i}g3_NU{!j9+~abvl_DIc?|ni&I!>pM= zZ4ou%7C8pU)LT@llL;8XI{v_0%UWWlfb!UUNp9&v8+fr8Oll`fDYXa?Kilyf%u1hA z3yif(7ut}0s*<;j0}j2U^TSX8xZ*F$?eB$PIfZ$x_*vH(b8DhSFb9NqiWlCEm%~?Y zq`ZLME5a+^sbV!G6D@){GWLqx_0of5eEDhg@Owmf^sU=hB)lU`h{YMFl+L-lEt0WrT5<5E7FC5qdAwZtQ$I%G59e;SIYna z^Rzp8V3=`a1#x8MhhHV*E8#@azbcT<<2I&ABa} z`qvEPoS2#A_xJ+5wDsuM1^N5d(`@Ll_>UBr%Z8_6TA~k!aOtE#w5|Zlr5rI}X>Uuq zF#vb`L>^o^DG*Jn6!-;|y>c9wnT=>z`*jE=f0LWjHWr-i%{eTdN&=Hb|VL5)l@PHhZU2j60 z`9PK<1j!^rQmY;vvZ@}=?BoTx%|4_sMBFEGlg>hiJP~izqeBB!EXNh*g7MH~XJWGm zZQ&t@RDR|?X=ByX*PZA`Tz# jyzaSk8e2I(Jq!6i3v!liw|v~500000NkvXXu0mjfpO=4A literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_road.png b/selfdrive/assets/offroad/icon_road.png new file mode 100644 index 0000000000000000000000000000000000000000..5868ed1ccc3f733b4c42838cbeea9354d97c2120 GIT binary patch literal 6674 zcmV+t8tvtYP)Py3%t=H+RCodHU2BXLMVn@TbA}lihx;J+VLiuhrviNXg=kl{_%&|Uwd;Ce{8-@%$o0qW@Fq$68#e8^1%!PI9$#?Ptos5 zoj#YooIZW}Qg2eH`*c@TS3U1jZ@*n#UDYrk{?dRdFi`aUJ4fpGo3k#>t-kM6BE1g! zzEiqdpSRaT>Qw9N)+GPIHOV!+OobQ&aY=?j2t3Ap3irbnAqcm(5N=yRj#ny=ULV#) z>LvA%ZKXVdJSXI49qjetb>w`I*ED%KAV3n37#W17ufP6!VJ?@u9i`CU-~V4I+g%7* z1ZkAmEhz={xp?v7i&3fz%R-D%@+JggPVB>Oh`3}hB9<|j+``X=<>y_iapugKyRoGr zA`@=jyh)2V1c7CALlnkg18KZ+u|}bE*NtV4oy67R6Ks~9)^W(9MT@pa5qXRF zw2n^xy%b-FpTXUN=^`ih-+%w3D3llXEpl~Wf#OPhDSPJLd+!}OX3UtiQA8I$K6^um zF$wL)GD^IGw{G2vq;A^U+PaB3>LczBcH<|J1lIvZl7r=@wa*?uethHL!Gl{I($wWN zh<_6o7BYJ&Lj!tI+%yy~c?J@fSOfD7$c*j|bs!Bpko?2SB=*FgJ9qBZu)y+qo!hr> zllYWG^>+jFM^Gn2e5Km(e)1N7`}XZ)MvWTP8Q!J6UCAPTqDW5!h&i#xuCe&uDB(M{ zxDCq9*|%@sBMl7=k$ebb4K<7JyTVaSNX&^n$|hD{^b*D5mMl};T%EkNM{OEAIyxfj z<`8W>pwiW$#h1Xti4b7F1r^a>W>Gh>kvI`wtO~mZGY1YF=)en=xlu+ssTQA@6Z`%9 z_fMrR5Tv^{Hsp^J@rgHqCCJ&GJ9qw(2cj&R#gB3^{g$l(I{14e)`{;ouh7%QiTFZ# z0-c>SY0}2f(eijf^k#B&CM9tXxUAIV$&;xAx;wEWe_V)P;O3k7aj!>2eD zl($coQ}yP2^wCG_GMUUU{Exg~kQ#mb#F1SG9=aG#o#2@G`P3D47HNqK@d+efS~cEx z-+i%gbEtLA;`47}1v=sT6mfTA;pfMN_{!RMcXy8%J$m$txG+ew_=&dq(8)^ZW+e0? zR^M3sDoHBVLp{{K@x~il2M!#_?z32kH9C`J^+E)xb1dq}LQ*FO4;~b&PhCa64pF!G z1dwG^V{+tp&ir} zPS9XcccRClxb;2|RpJvDmQ6j>u358&U-lb`0RqsKeF#G&OC43>i?tto_uY3788>d+ z`beT@3RQ#vboDTFM)#CPORRoTym}vqBJt(+$ljdnr=Nbhy0NiwRK0;R*LQ~ib#>;< znTM!51nN-q=`MqiVnvnsESGX~7A{;En;{Az=`8Y>!K71mcZcMUlth*Is_(wDvvU|G zi+V6ph?&ATB0!x{cZe9-KK-Z>Uv7(v_(zT$*@XUV`in+lgaCC$-J!@j@grsRqey&l za~fyOnic6;6k^21(2EM)MS2#7s1iT3XV0GT!-o%F9JKrw7>eLSTAJ;90F#Lca415Q33E?UNC)kR_ z5C&S;D2P}C^-z2C=+SveAUzsy&+65y4}bH`H@^X7D&1+&78^e?;4qEVPd@qNKVUz$ zLLI*Q?z?lJd+xdaMkQD;)}OjAIZzMBLzAdje3pZaP>sa=@y8$Ez!Y`6@juq`)mLBr zD_-HBL?vkLI9gGkQc$m(=s`7noM^&${FY0XF1?2rLc9aUR-ns2O`ksfRa8JmYzhW- zty7dNzH)V-=pp!Oe?whS3FzYZ^pK+z8K`uU-)Xd>dcHxtq1UfpzkyXz`r=Of2@@u4 zKphUDF04Ow90`lhg4A0G1cS167^1Ke){b8;#a=MR{t7BV|Mnunc`cm7zCG|fk6l2J z#zN~DYk@AuQm3dyr26!uVDU+MW$m$TT)K2AdjgUoeW(a6T`vL~K|cch+fqKRG=AO{ zh({9|PV9+~dJI^yWC@3z{09QvJ=U)r1~?UtM8V>-rnL5h@%2v2*s)_*hg0?1Uj?oX zKgQsipAtxX?sIDo5=XZEAU+=kV=vI@8tN7mp`oR&>n`;szF2#Lkv(?o*ap1rj@3uj zl{5(A%jb6_FuU=%trQq1A1^7y$GTZV-+%x8hfy~fu}R)h_jQw~5MMpi;hWk-4N<@Y z9j&*xHL`V5w!{PPli}*H!m#*scOo+jLu81*YuB!}kt0WTI7=kfANh%aPzTYMEi zDHflVrf#WY?9#}k+T!z8$DpkJ-o1Ob;jJe36C)P!eb)zXdn56d({}~5gw!o{j6-7e zMgLl?@OJBI@mXGHf@xizO;7LcmMk9 zuTRIAjyVEQQnnbYBE)BvbW*#jV$z6@Z*k{P*Qk8m`}FHYd@7#TR=qhpcI@~g4Viy?4h6i<+FT7xBf-Vav}>oH%h~O=?%?OflAm z7N6pl@Os=FW>rg+tHa7+?Xo{$L*i5St@>9+wZ~zMBO})L^*r*tPtO8_2?QU($yglTsMol$F8_LJRGWoO?>g~ zRd3Gm^n#zsVDj);_Kd6I zCz<%v{r>&?`LiG5X*{dUOeiMxsIYDlqk}`y$=I&0di7%vA zy*ZzJ^2utvt{#zSEn1bcEWTIL7sLnelm2k4&;ln$f*TK6#3xtC%bJou4C1o_%FS7@ zU_oL>Vxo=(62Qal01!VFt`32-);g0ueR3xD#8=iHe%$c3wzjSUb|mF=MoDDe@0^*C0@4LQu36>g*kBP*F zy!qyve4DQmzh+jy*2HK2s_%a0%$a;Wof`4!BU|J(h%- zFk-}r`&qfPNPmBSH5Q-l5qYhuJ zk1qg$D>77>+#!c*;_lRf_`0>vU_Gn3SPN;IR4gr9?cvs|rO(Gto2x@^kSkm_3%fOa z$gKtOS$?th*^L`F(#=VoR6B1b0ZXIBXT3LV+QbRQ#NDY0M{AL3-p#?3aZOkQDUp*! zQ9+digRh!!Ua*iY@pcnbd@Q3A>xJJc;Zx}xIm5Nk5T|DDPSC`s!Wh__ll}PPk5{1r zqp_blS-g1h+AIVW=PjFCPl0I{En2iTb-(4*`d<+AS5tzHksl=CgfeqTL1@URwnqjTR{TYHca-2BGh(W*;0_e)^ zTL!`6*ndSrE}+L@-hmN6NLPoANGyK#op;{ZXh;u4jQB!;+yRHU-Z2d+y$EtEFhgAn z;`4zdi#3lDJ&OYBXr#snfI~H#g`pP2&+Oj4dmPq0T2^CRO!f&!fE*&1P|d)HFa$+> z-hvot?K96l`|Kll{mk2w5rcql1jr$B2^o<1(B^3d1X*M}UZXu9k!ndlb90c)M0OrF& zWw&kHmdN$2SV<%GK>(cMuot~|r|NYrbaw)K z$gP(6a@$dE&dHM}J2Ae5PvJ%k0)Zg_PL2Qk^UphxVPNh~5X5I5s_(wDvy*EZ88HY1 zj==Ke%k>Xb$T=Ea-$KGxD~kAY=gw`x+D7ZD%`7SD@yh+?x8HvI7mU~GMYmjz!KrRo z?5zRg(VH#v897eByGy#Uw$1Qxpi#3cmcN`vBS;94LSfBW|B zV=#>N0TjXr5V(5v>P2j*91f`^`8neP735^`h4}2c z&%BHP0esJp0oUYXblw?-ho15AYw>wOHX4$>5f2@Ft!%_Xz#=Oj!mc3nBGBTyadi+) z`LDEQlt!x&-T7yJxo#GT{}BSYM;FrRPKqeSQjNt|zUYAi2RhIT@pr{pr}qeYbVziP z*S_U3r@%B4`q7B!%Nnr|AlI;3Vh8@}efpm9@k4yMy(r@E*s+8Ct2}1JLIA`kS!v-V z&??Ekr>!ey45O$O73q-H%U)Yp?}#P^i0MC2TZ&%1{a8vjl!L3*3I%td}ZysySqnXTuxVEG0ZXbO^>JUj!$ssRe@$XQBvG$CY`QU>O=3}Lgjx>VnrOuZxUlvyK*Mu_j*;)|Q39%?aJ)PtBQZB+3k%@I2SSjNWg>e!>W`L7xcmQyko-vwIa zCOL|zt{!qLS^T`UXJ$*5EHQoe0K$!&J$qJ&?ERbwl)TGw=dY_@Jxvb%__vTJr_nItfIwSY z+Zu8e(dh1wyJe*u@x|IJH|OoQ-{yK&^q-74AOMo;{yk$0ksVSNoGwU%udvK`odS4D z{~<>YA3n_IP;qz2?~=a06Y<${8fVR#WkzC_#=7XJMN$&CfV@Q!-5pT*pfMTZyTfb1 z?Af#Fl1rbyZ{lb6?AbFOuZ5Soyl(2FX~ZWM)sSD(=B!T{Q;)410LWEx7IF1H{i39$ zEWY&S(AsC8e)?&yXH_a*QD)`UcyCoSlgdnb}CDkJu!)^I|7HPw<$s_FK1ZHA58gP`TT&O)cUs zQTbTL)hUln#WNOn#oa05x&1)i&Ea}h6DLkI>seKVxA-K8FWs4P(vQ{G(-?~{NP5^} z-K;;5!$?xn-O-6(;O3k@efj~cJv7$CwMk&b6_tdFV z%aN?4yJIIl|FeZOE?v6RtY_sBY)02y9saGB{LDl0RQu+~Jp#*?Ewhi<%=`H|@tLC{ z{+u~;TE>kVx7Ph7OiV#Qb9I6sy|VgNo^lDZb%_Ah&05Q~*$`daoqS3me%`mone2P- zy|*5(f6aPUd6?YqXvBA)sB%pD_{P<#j8Vz6T$AnS(W4LJr2dertbR%2qm`JEm?fcf zK4?w(m-o+|Q`bb?mNiFg$ zeWm0b<=Sjm!(j|+Chkt&;&X>Vy|lvgAzSd;mywM4Kma7=SbSg0)0DUzt^RE*&l0E2 zAtwaL<(FQ1iK7n+dUxy=f6(;l)6IHTPH0v*Z>@jDRZoQcB(GNyH-~xLG7G?Yg|9IF zv}x1m?$EH4@5^sfSi8uxn1nnj4(}j50!<(D;Z>E@7WKku`^Ji7(HHR1iOS;4+mI zCKA7h{|(SYp;!bv0h-_vJ2nQMWAG}HP8t*&0^J_2c`G_G`Y4a8T_@x;xlN8MY)O0p zS%{BADv|-1NVpT_iz6z@&p?oc_}KL&)C=>Fu|Le0`VwCiyGAM?Amk^8)Q3)dWyNVZ zBnYUo6{{lK3fD>PDFRF(`K1BKKF@LAkH~|VxINrTV17m?l~E=3g1@+%d5bULackd~ z|CO^hXLSSwY}xW0_x*_AFS?PfpS;qXMsy*1Q2zy7J22&r+vA!4#Rv$%#b>HJVsug+ ceg%5@f74bt1<-Lrz5oCK07*qoM6N<$g1SsEG5`Po literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_settings.png b/selfdrive/assets/offroad/icon_settings.png new file mode 100644 index 0000000000000000000000000000000000000000..d0c90a620d780d68bc33098bfa3897bf1066da0c GIT binary patch literal 13369 zcmXAwV_+m*w}q2TY}=XGwr$(V#5N|jZQC|FnAo;4NhY>+`~B{Z?)p=8dRLt~`|Q1* z)sadHk_fQ4upl5H2+~qwD!^ke@Y4nj3H-L8e2056fn3!w_d&fw@f`rh;g@n}9#FQVpjFxOri#3z}8P+q8L{nKGV4{nY zD;HNZ0>(jmDV{9|8w`*KZ*_GSk*z8@O;=XuSi9=>e(p1T;ma3MimbIbN zX{nffy4=j?^Ss#`Ad`$k$LDpgx%oF=-2M1n&g*f7|9)DY|FrC-ytoTEg=Jwc$uKl3uC)4 zNmi)pbUj^&cE4D=H8D2c_aK$ebl&R^d~LRv6_8zB1d)Ow9my6m=k-doSc$=5ok^f~ znPAhRtgywSCNnFY>Jng0K-3!AbT`|VB}Im&kbl%P^lhyL>>rX2ttdsH`NUm;g|F6V zyL7`QlMUbF1|Fyjj7byzO})Qt-`%0XLxkAGnD|c7HuE>x>Tsf@rN06*U^g&3iq?e2 zK8==YHXaP)70>D^Oel$QiHrL1s3i8B^Gw>6f6F5M%xyZi#A!?Q(!#z#!~9lkgW@z` zx+f1saZJwB{Y}4pWk{QhVw^*Kho8gacIG96cZV!E%5z)}Un0H1eGRx*@V|o}9AZ(V zr=s%gF`v%rlp%__m^n%|G%BgeC@&Fl;dI#H>ypD1a~#;|`Q4}V=Cxo;O(1y}o0@=W zwU9qXRu3&lcb`PB+Xg6j2p+G`_mO4?-^yz`e!uP$)N1uFk%JWT9B8px{E`P*PD8yL znmE_Rk!t4f60|5 z@Mdcd{(7Vunp)8TdN(&YDK0%X?5*HvO+Ld^00P)SW*abjWyMO`DX~$L73$S1l?Lcd zexGkxQ`wvj5qG2#ZH|`RKOx`c6yL>;!79-laM|_{y39Gz9=jyc=4iWW*839` zG-43hod1+M%k;igy#`AcrBx_oSQJWdjfURVakrG%SAKz*p3%0AFJzg9DLIG$JE)YA zItV0nxY%=Kh1chK+ry>Sq-VoAX)TakHf^iw!_GFR0iye+;0n?x$?Q#JCKv_12-J77762O}DXsu8* zT*GqX5560zriqk-fI=y)rGehN3wRbh7uhZ#CC`^*Z9ZqG6A4#_|6J%;y zi6`|2Jv{e{KGYC_AQBSZgY_x2D$hz?-XCbzCDO?hIGLH50=J4nN2A}+#XLrjhh(SE zvR$b83f)%2;e_55s-dtL*ar`#=-?rV!Kn&?SYd`bhyf+Mx73EEi;99hlGKlvM9w70 z{jik#6n*D04{P$82dca&wa&RbZdI+;%Vz@*6?HG^U^V^l7bRAc@nYyx_Jx1#tow$G z%%!7UZ*|m1;)(o)foEoT9LPdL2Vi8Js%0C1rZvKP)a2Ff&|hkm5{baX=O2iNX=pjO z_-Gf&oo88V=+}PG_x+G|ILb3w<^YU~qcl+vGPG&we>kXzCb@Tjh zkSEV5@FOaahR%k2`2GGGo^~yITyJ_YZ)X`Z%d;h9bSGT!I+^AR_*Mx#Z@K6{X7ol9 zF0KL>D^c6g$w~d?eDSCz52YtQw;sq;@(rofQxpd6SF?V%y9eaOEvGSYgY(fuxdQi5 z%BbtO!KrX1f=gId)NMpKs@L|JX0Um6$PEaEi}vZK{t zB&?V_ThilrW>8KUjt!IRc$j5VH@?WW*@vOIci^{pF|?hf(Dc-E6W=#yZcS=3f_-Q7fO4dTLI^>g>!Hc>KI;nAA)= zgW3URk-`ug`$0!^Nl}lD!_0MF*L`JOsbsG01VMMsS^MxFYv0cKc(xpU+6Z`oNA?6G zZ0JZufuL72Mg4xK?goQEYo= z`+9f8S&gVE85GOajDAH$5AfF;LsB*+U%9*O#W~6KFp&3(=3H*%Bg=w!g`%3XbF3=6 zWzgyK`%G%JSv{t;-KafnR#)JET7hcTOYx(#QkUUoMeb8|DjT*{%B~Ac)Wg4Dc!PO^?m&iigg=n{RHDTksxNxo)b{pV z+Au5bJ10YS0pH6YOhQp-3WD|^i@Pr-5r8;+o8a8>G*$gx7TCKX&x7t~o<6jy;){7f zvA{yOr5~v;DZM7;=_fIP&sXs(Nw@WYHf^*2I98Q)o>Ys0*reNLtF1XJ zdd6n6B1d93D8VyAr%tqbnCf$ptSGQvyCQ*6vZXw$!{DVtM5{-$Hyrx$fh zVYjepFnKbQ+pV&@rSmz>xqH(PYTUk;I-X&3;0Gp6P@q;uO^Dz_+iJB)adK8&Z@&$! z@7%p*cPsjR9c4ib?BYA#6ovz%(RlZ`Qm=ebI?Vu9I6J+WOKi5Je6np>(@o} z*=@GfX7P6@G0slqGn-2EHW-m&)Ss@W$uPH;$4dAR(4cbO#y%{`o3R%V=n$GEKb^?3 z&hS5Pg#mLD?>TVeyfOf;{5Nsxlwbm`G7}!3Ma(O4IuOE2C1H5_<%E^R!D`iA&%;T0Lwy`Z61Di98lNWe$Qcxr3+`|Ej8ZHAsDbCV8se_aKJijat15ow;J zcbi}x_q6pqBKzY))CV`<@Ua!b0)3!3B!dm4Ez=^;%Y26{p3gaPpfFFpN^ReBBhuXJ ztA66O0~Yd$x8#BL5033%nq`Co#*dew*GJcLyN_i}!`KDag*0Q`q!O$>D}j%j!F6vE z@2DM`4GLCm9=tgc-uL6%=}BF)HTw0-{n(qf<)b(){s#6|&)q8!3BUWVr(>KK);9ef z-}fiCNAXnIS?-gZ-mZIReVvFmMH^oCix=I{v~RV*o2RQ6LZ3m*AAA>ZZlJ3NnHA6m z2veym*9)bxla;FFh^rAp(r<#L;$+ObA6FiIc;)G(n$^S!xhN2A$UA@@6hfrb(kxShcdcox zG(Yp5i#)`i`(6&B5B=}6cc;>B1LXL|F+*=Gnf9j#@fz1RdfmxT2Q#AA%TWscAb{Kz zBNLS}H0ArfoeH#XIZv{yS8J3Sm*iMRy`Ol8x-AKkv-oAFAcuGDF-+#No5X;!;x6@gWq$=7f6-xNJ37VN<0x3_%0^49w{aFd$2 zIAPbs>;BF?nmrz^)O%1Oc zhs$n#F;^(MyYMg83tOlh&1|S0CEI9$vPy2x#-zhEJC)&3?`PTe&Vq9JH|kPm;g>sosr z$G!eHU>oL9t=Gxo@vj7pyWoUUF%KXYmRZiZpi6)~nl$2WUpVvu66H}(X-9v_aO69l znn=fhK5N5fSSG~CxkdTTkouGcY}gZ4QWvCu$>lV5#nrZg#! z$Wk{?;fv4}O$(;ubnUJrb-ZHc(*vos$QEF(6vC6+olj+pj zOZ*|=N@>Xxz~YSD`_ZNgD^cjU5=L3C4&&$a^JKYG+Pz2 zLOP{h7*V+}bEQcI0H)|QDxmJaQX-p_B_?Dtp@KlQ(8Ci~`zlec=E2zjzM9lIe++=3 zoA|ZImX4`k063a#=jM*%RdzT5@1w-_lh)e=@WNsGEuql2nV& zf#bZq1(hse_%kK5iI*z?X6iKaQ@~ zBv}TWT0rNr>i+R*>_fs2dCkVV&T%A2qee8_ek$cqEKclp%AbP*Tt7VKI;8j_jhidlEZ|_k-O{IpJUBtE--D&+6fQ%Vm0fTgGy{i#u94~G^OFSI zx(RtmA>A3GMCx}3#I7`2xc+gO2gE;*#u0R@;T-PM0Z7uoE$>4%=&?+WN-vCzjAt2` zz^cUxkoO?lv=3vdaSV`mVU>i5oGeYgJzJN<;bB`QHf<(mr5uVmCA{bj7R%7V!ED(+GG)K>r6RN!hFv51?z$Bo}Ws;?vJOd zQ=f+y7E9?%J5|cAM~(_37UbCruA9bKcQjW<(|Cb?&pb{FP#rXU@HDeV&7wSfTy~U0_%+U&vCi zm7!)ba{vtM8ybOY7;%8W_tbGZnStggf3cS=Y3g0gG(NpRlD1dE`wj!j421Ekz4k25 z{1wGzbN4PIPjOls#uf5naXod`{;{yuBXM~8Hh?wvfWo()=SI+Omn-IfY5Lwaq&c%6 zP}Vj(qvb`4vp+PsKnd(0w2l%BPIK>)gG655>dBXKtK2_rJeFdE6JucqVr001iZ;lJ z5k&DC@_oG==Kg}pBT^vuIUxSYS@Z+5oit{k<7`0(sJXnw_D1O^K=+TS+B5*jc)ev6 z(@7BztS>QvY5pwY!{pnx?aZT!j2~r|f@f2!WeS zGD^am&vlf*IwY^6W~eTVln`a_c_6EO=8{o7=ujsYW83}UH7vF$gJagUiC?(c+Y3u#?x z8`;Vsr7K&WX)F>D4I@Z*BTvkXupnQsS?Z8%NA$W0^RkhC{cgDaQ+Ep5S@{vRF__B^e8U?(eM^o>(N=lF(kWdA?X8id?nRS0+DAk_trVyG=+En}&uST$qg9MAD&!B;lOMZcTf$n0?Xhf$a^g)yZeApF7WS%0~dBe9!)p^hg^WK zvRP%RF`_m9n4iqA<`$s|F&T%M)qA%4J+tT*v9!+gIHAT|*hR^tgXBIU4|LMw@iYpbOJZIly2 zk!G(FuqcjyVoN6Qj?Yzgnq%`qxeV@5qDko0VSN6%%G;+FtVd&y=Yu1m zR&*?W3o*`8VZ?_w!(Fwk7B5WMl&Wzj4QUM`#i_v>W&bP-H4o$Zpx0Yj zmy-+Lblk$(FI2*OxG!!_i`vm(oP&t3DDIZ-D~++#PE<9cbBW#htBCWSJf(F1WTed< zV3(As)x@o1Zl28b!KAmMjZ9=ecw2(vlQGl%`)aH6{P)8@r|XGSTCDT$6lD4G zI+t1g=a!U4f!pHxM$&^|>NSb{5>D#=_2wC#a|5m#{LEIk@@>LzY;fkn0?G(Jzy1F% zs3ZijUBaS0v!Nf}f=xnGkZJO78CxFd`+BU;pQMA8u?P#hl=XyG8g&dV-`7?Yc>Rl9 zt2M_8_zB?8hN^$lxN2{DG>a9INA_r+00Vq7RQ^_Grd)DLUW+_(MZHhcP6~WR_o51E zO0aZ)zS_Qjuo{b-&gQJIPhDgw)sFf+V+WQKod#fy)IWIGotl7p=xdWz1zo}1*CbV< zI)onaFINK*<&K*!gDnBtrV^9isS;L*=gp0H=o9Et+S+#CZ;$8g*6gij(U|l>7YX=` zNc+l!V;k1%;>A4n2hH&+Mp9Ev@aQ>^{m#x8o3QHm?OItcjH>zJ*N)Tds}I(zb^4=X zI~YqhaII7O++aZ%SRjErd=O9MuHZLMT>Tfoey7drvUOEJEmvh11_b~V?k3Y?i3Goj zu?#$oLjl}k6b9u6>vwtVk9sXbolhiuaq(+AJA-Xs7x5DO!~(ShpF58)~gc2YeJzxNfL-%2h z01{N3uz@=Ov$NxdUtozZhdJr}v~Kaf<2*^fN)3LXqi8mp$8T6I$Rd<^C$H=M5O6r; zzVW8Q1BQ956yNH8z4Mv(CT}O(_wz}Tz3+JLepXOW!N%CHV(E5ksTe`FE0XBqar#}i zm}vkjk9Ddt0v0ds)o?Y7wGd(A-2>I~c2J zmch0`7~q2bo|@d$@1+9FHzo`R6a;E{219xL_ILxS2{lyQ5R3BoM{`NrBS+-dElJCH zL85T4a(91UPVIm3M}P)Z@mTg0S}Ow1T)uy9l820u{=LUyu0Z&^@Ix9%+uNBx%Zzt28PzFCT^$%)u3VycUY5ON9VU_SQJ?Z=&UlGl6Y})$?d~ z{$=627$00m>(t!b&$`|}kG}mJ7muaCz^BId_gEfr@>FMeuK`d1{EE5iSV{ERZ{;6o zh7)0zDt!C~d2uwxalh|cVQq!HUcbN=QHRL^(Sc7jVRWEB$!NIJmFD+IYT$~afK^P<>6 z_#oSfM!re(p{yL}*?miUO&W(~nI0ixMfm5qG+$TKOwjsMz2TN_@2HHxIE>WZXZ^oi z{2T6@>RL$eHMojCe#<&#I6@&Bqvgo(3`~}xf&TzaG**Onpt+>uS2WnYXSAtkoYve4 z_%{j+3LF@eL~Q?*>_YPDf4oxJ>p6V@1K9oSA?pqFX2?vTrMO|5qWmUELd~B4v0Lov zU)q)z1sKcpF7ilaX+1$oS$}@}u7Y^Z?V`~NT<=5t-P|rxl(Po|Yk^(p^cJ}>P?;ga z7ZD$b9c9Axw_Md(D0d6Yjz4`Sm-l%6YIKISwS`_}i4$OA;;1D*+tc9vEO#~M0W zp$0*A00+Mup~jN44VCf0v@{kB=e70WKv<{w1SkZZQ`vtevrrhcC?qL<91c;YfFxT3 z%m0mMy%s(a(>w9mz!rxYR))5r?3Wc2>Y>CmdR`?zc57zw@JKt*{t8K9 zjgh0~J%g7BK)?=l@|9Dxn=gXc>Yp6MIFy&WcceTPAJ!#_v$Cc|B1Wai65{l^`#WAf z33AT1|2SEE((cR~j0~Ixm}+dZ8k}CYR_X&8QoBg;9X2{Xy7pO)H=alIdP%sT`$e5o zya$uv%BJwjm7xzcKQB^2AT>|nhobBMiA`Dm{r$A*u$#tjSKpA1iot5`!EZ@RgZ?@g zrL!8GFP1da)(b>?%$7hoem-3+m+lwf@$k%Wefmg=Wl>q7n?Qt&9O&!td2HM58*d9+ zqYUMx)+T~vArb!%aLLouHAH^MBUualTdgOG9|q;gu>Mq+TVCd}=d zJ@F=lv{gn9$28Df1X2Q<{wi@yWY~6KS;TYQ8#ZMsFyJ?N&)GXi;n{j0wOUMPx#gO_ zlAA@S;_o#*Hl$Tx7k1Lfg_gp5=A?9OPZ*qmW;gcmn9Wy#BdN3whDs@c}Ai-;X*4my7!8Mp00wWCvuw`{x1?8|%g-kU|>$a_I zLh{&4m@rnLIz8)0;HqWSG`PQ21MT?9yF9;9`KWU>zi19XY}dnkly18jy&0V}HFdKc zai369c~v>`=qOJ4%#af5)-`GJaEc zwaKV8q&qeUt+=xmK+oQQfTvzpY@9|i9^1m9Tmj2Vc6M>$ z_cxP&rPO-}n#S_(w%y2Lw<$C9eO!)y{P)=q)8uv3W;Rh9`8$7i>#<+J8lkM{xJomV z$yfx-H?^csBcfXh&OCQS{7C)*r5yr@@d%5YuhZ@{@~3x^@L)Oj_6_8Q_ad8cIqmg4 zfM7$GMx#cGjB2&WxP#vsI^U{oA1kV}Z%LC|V@$Muu_cxtY~(l_D?CxuGgtHQ<9^m* zzCbuwwZ+v?vKGlTD`H1}%~_LrmDJXM4)8gnQ|OQ#utv!ag~q`!k4)q+d&#L=jn)o~ zUGpR)_cwQ!P->g(VDx6IS%gzxip+Z?rfn5zErZGGLi*sjr7YA8u;rd(dF*MizM~=7 zp*>O;2l%atd|+2{5z1g`u56t8nWYAjhCE5@LrRh0+pjf{1jAzPN?vrpXcnQc)N%Q~ zx$Y!94@(kXK~LpyyQH%;ekl&Uif@^uka@s)uX?`oAyoFHXJ(GunD)Lv4?%#^3jlyn z^X!E7wpIlfWHPZKN^%XgcC>wFV;=bA7~pw5zQKqBnUIl3G5@(9>fMZKVN(OvQ zV!!cUY-P|spO35eE#MP9GOp3C-6{KWx=!-l`_gQMi1ahJPa7;XEr$7DIJGb;@T{)~ zWXP=GdrS5HpXZG-2^oZSojrbHuY0Y2pV(yx%K4Mx1WC2Sm@)E{_*msCfFpIK%V)axznLBDRAcY6~SDw(NC0S%75`#rS)`$B2d+ zgv@+2`}9FYFMgjk$z|8a$H!$>Mu+BNXuRctUYWpM?qZdCHHAEo=GL8X%VoyNu$x57Qc zLZejp(8|Bprnp-SM(XWxYA^Ix?gVNHt=GUFuKD3llR*{u&fGJ(1oYUt?eePavB2BE z;``o@J6S-T8^iRW&YEtgPOCLe)pMLC5G1YZ*z`ruAY_|{hK7c>l%0%~=Xpn2i0;b9 zehfWHi~6jqpx-e8q-`j7!av*``aYlXm zRoDmC&a?xvZLx9XIz)H*;TNOqVNWn)%0GX@BC);ipQ2&#UaE@6Fw8YTmf<4uS4dxr zzaO-m!M^LXtc^?}rbEIbFqw-QJu!UO@B8yvu$Y_@>(plePs+iGA3uU-X#O!SWE=N# zpn(2VYoEF$`=eDC$UK#Z;CcbTJ^d5??H8oJ?gL|cE08lE<{Ez8r7yB4qZFJD6@b_i z?ncz-=RjHnu##uBG%I^m*s%9JlU}}~l7M9?@XP00eLCpRNWne^ji0&eUV4nJzHieX(+ z6kgg%7-)ovdqW8m^4IdX|F(kZ1h;=b4xi0+~o7jVxjV6Sxzgu`}}pVzV(&^5r>vwDBJBvSW9 z-as}L^^0)uFpyH@*V0#dUi$I3{Hqd)F$b}sdsWA=e;@_)0YWN#>?f+& z_Sqn?4W6E`y11tZwz(QhYh!5r(nSA&FNuU#ZVo*{ZUKM0CeKcW}yuo?9S z(6(O7MnL})okUv}_ZBbrXJn7RMs(`$E9q+J_H$el{ZxIf$bLC~uvA0d*8g@-r)0FT z+=w+Gmg5U?1qCThK;EwXFel6xQTF@+(uBAFI<3=%XZz_B)NxNn#0O8Jv0bO%o%b+K znGYzL3*Ysn{s9`w5#Hr??%pi1wDNDsPDKQfkJ(K`U(46>SyF^QLuY#thiF>wu_tfbfOh42(v1o}HD6RRaXukDjU()A7~8 zmQVs7*MI6dU|)@g&=rO)N+q+a{+RZAfqzoE8sFyZ8%;(@`j%l}nO&D%T1;TKFT#pJHA}mAWX77IMyP2qJtutVRK1r7~&pMy4SJ4L)CF4Y2q7@~ht`Kam2{b)j;%}CyClXv67Tyz@7xvFrX$@^)e;~2ta9!zp&^>9 z42t??dC1@f;l(Ns>$+FWC-zz%#YJzg;{-<-Bef9i0feYx&{G8;i#55$U)k1Qej>bW zq`!gAEgvS$Vv2l)T%J@XXFggL<$F!sZJ@bgo2|5~92ZnE2aVLo6{u3M&6lv4e7X|6 zNI|z5n8}phrX*CtO}D(QM6j$D#4W;P&2&qmH5e>fj?bD+wl0t?$d>;2F(J^WKgrGG zfxkL5p2Lz1LA$;n2kUN>k%mA_4_7)-v^cXJ(<$8fM!3|hV+KrNziHk)*G+m7ZkzJ( z4}~+sgEmA-@JN6C!w6z7hxuK7?$+(?UB0*b*wPvO^{mDw>TC_9PvJls^v{UV^upa^ z!QNY{EAC8*m(5yAU3=1w^8||V2576buj zjzGxw;-7*e7WPt+m>X%xhtNt5I+GIB?|@&->{zGYu5Tr;l-2y0O-Wjl0hPb9LrA=s z`I4}6tMLYYiVKV9FkkgUm!a?DEdL>frX_b^8p>-)ZlO~vNW0PToEL?4d-4T39UVrRpB@~os}?Bbgm2fb zjAic&-a6G9?;ElmBiN)Sr8N!nGRr=VlZU1)MOM%l^;*Qx)MHM1ec{PPVLDF^C}gA# z1BuN_S9UJ(Y)~!z1Xjh5aK8N}UYQI`LueW`T8%=d2h`nC*)q3tfAQeTP0Wbp7bxQ4 z9uh-BNwPGLt#qL7X=`n#U88zcfPx59v^q{o3ZnsOKYbQu0w17?-i{=c>+><;n5HN0 zrHLo{)r_S$1x@Tt@qD?OQ_Siqp)FA-Jk7@xg;WdY-@g^Ozw@H3JoQUKiutJ~I+@{A z@3M?N4^0gnDyL8BLGp0aTJx3i?~OjG%ytm*(m7e=p(*sGYL14drBx4w|9R;SU5=+R zr!U4?)={|vA<}`Imqoc5r(TKYM2c4mPdYN%^pbk|Jek8QVU=4a#6Ci#X1wW0slr|L zKRW_-_d=%{EGAGRS#kVBhv`8_o}8mX!aW_8sh)x~{6jU<(;pY~r%3aUZ;L4CWxv~K z!xr_L_eBQ%F4u(y178AO;S9+>$Nhm<9niNP99Hw1RpA5g#h#7!m%KGD4KmU-2L$Z* z#_lxqSv}ckvs_o8v}Wiyf@6_WY4!@OtbnY+V*v2HRjHMJJN>W3QrF=e{cOR`2D-BC zwm;F{Bvxj*NP1jfp_CT&W4I&;C1i+^_k*dwi?C5 z5Vis(hZTu=EOU|UNB%r5t`m*?X$YF*)PYSZsTMMBnJO`-&3OGa$>LJbf{R5*>f}epn>A1Sivjy)eoxt8rcG*7 zo!{Q6vnWC|NG8Tm7&bq{(ABy^h2zRszuVXkM0x5?bY?gY=0KGE$ms8r($f8+GPSbS z0y6lKF&*p>ur_N|&jg_GwkO=yY|q-Z?-uqSFlbr zWfGp8POe<`CT-cWdR^YGxtw3+UV@$Q(hSR?)DCHA|4 z49&&`xj^Z$*d}hw~JkL4L*`Bj}N0ga~?lE>jb_NE9WBPhp zw-^|Xkbpl0R%QkU#yQu$QQ!gC^_uZD28Qx@4$5671_l^|zScF1AV&NoTdn8q+XDEI z#q{#T|1u(2V?~|A!@%74%(yJTOrL4|ZCcM2R3wkzG`j&Jxg8a>IF+C$5ObD?`PH?{ zM%T4q>Dq$sW^dl1BfKNtv5^1T)tF9xFfS+ySSivdsoJ*d`{ZM}VjFUdP-Bg#Dq8xX z;os#_0eX?4gZ$l<$fA{QedX0g&}&eqh-N6MyEwR7k;J_j(tfQB{y1m<4{ICS$IHEj zfjZOiDVHv5Oj0P37L4GXGcVwlpMLSe(iMkZnsEv&3*Ko+NlXyvFOanyNDv& zGhFWE_O<>mR_cwrtAz_&=jVMw#u_Cg8csx}Y50%V=Fc53Kvl2&z%$KNcdC65LVG#a zKJMiwd4oo@Wyd?5il=?XZTOE^cKV^coGOfoefCq0P5Eq|y{ea_ylVJqbA*R1u*WXafFdEvWYmVx#(r~Qcks!BSqViHC* z8Ni1Vz-d9mEQb9|hVUMWoI|5N<775CoC#a(t;SfNbcz(7C3hbsSP#j`fH)G<3E&0E zhxR`dgNWt@Sq%2iymwS}*qR}ZJ1viIesTL82=eD{o?H^RLNW=Pd|ILsoC?&tibHD)%1i} zf#+~#qtM04u|CRi5N@m>QX=!bS7Sx?t{3yI>yCcQ&efj@(nRyGTjQBFx0&J7HEb?> z&J`TZEj668)w=ii0CQ7{85d4925hK-Vb#y##Akkz{q@@Y@>~`Gn{(=eZk!;1bS1Pw z7-|b3)wDeJ^-raJ9_-lvdWLAfb$9NXGViImp2E+rNb7}hr~K`q{4*!Qp`k8iaiMp+ zB3OKZ$kE0eXzAoMx}-g(b>!zmv_V1Mf!N?P`?@~^y9Q{Um((8T#1-fyme>B z>=UYMnxLihs)g|E$NKcyr}9ME-1@s~_;7imkd9xp(``C$k#5m9m^qN+uxeSH)Auoc z;Rkp?kFh}_;e^~?CFch>13oI}Fdw5zGLGgMadaWH_ew(GH^y%8Aej*t-!QcsnFqqy2)% zM6)jw7n4NMAJ~m=zb@Rh z>!I|96t&(2)>%+}g?xl5N~SV%$Gw6}YhsO;r%mH4r?`FiDAleuO`*Fno*8MLe3Z+- zy#%{o6n)6{6pH4hq@(mlR1F$1JN5Y@S&gdrJwyFCb}5wA?RO-sc;EO;pI07}X)m(_im7)(?m#Xy&H( zP%Ji)$Np&CiE6=rsdK&rjqS#liPsIL7wT=RH3fThPLJBL13??Y2>~&tG{N z1vkzs!woHzOD*Lka)Z(xzUlGl<99f~m`& zmR|K9mFy>TUSU~Ij|k>pz$-twFMl?eP|mEnH`U&I3EtnSCKQM$ttJ>}zy4C2*iys0 zTuaKP4HG)N)i%mbAA?V<*;v%%!_<%5IsKxVDvT|C>eJzKGXFH^xFl00@)tkpv{>zp zpW|)$kBNZ`m>ZWMZhRE4-Vfh9>_P%QC&vPKD^ClS+xCejdq5c}4VxlCkN@*Dx z(krIQo`+y;td)xk6Sg9(`efX6%|KC!r>n?fwQtm)E|;4~`1tEYFL1;826=`_i@N65 zmdpKPNU6`kSUC~lO?T9Z>BmP#^S;;5X;jy>IDYnl{7`aH7AZ=K28A=B%4go~nS@FH zHz@*K2II_r<8uM7={m>4!6<$MAPNO9#|ul72oAW|t$0<&;XTj21xJy^0B%@!%U^{W z-_sBND(?h`^LQ~=UwfP^uV_PTcvEE(w%R-P`6;Fz4_=T1V&P>sAb8n7D``+==4^)K zG)%A94xIxcAzrZBJ5EFvh=kstT0_}fAhLZlTnK;$Yyy!m0EjkM?r{T=uzF^ErPh-k z31xw>mt{$hgwGxx#3YF0o@2F!V)u056Hp~n`mJ5haNJL}>F}JN1&@Y56PCa>8WeYE z5`rGSvvRb-IP*ZL6l@y^SV$1&L60iQ9^70kpRmdQbnQW}67Wsa27CFm7gg5vBqa`n zX;um_pq>#Zdojj@{n8?`Cx5SFuBYKo2@qYrWM3Eq!>3;y3wddV9i`v|@{fRA9 zb@vu#&}9MQ+dmz6rN!&MLFN7>^xnjO=<&*tSAFliPHfE`bvGLaYYHo0_I&VYyt~@j zXr=1pe9k45UCfy8_}fax^r|b*m#;m=F;T10@)sj#9uJ)%Yv>UJg}YKfSl6w$_B~2h zkqMdD?(c-N#D+>Nn-iytNxU!0DI<71=5fMw!L`c8AD;d8VB~nUD?(r{IMuhtw|Cne z#UIul_W1UQ)1(AWobs`+zEvvatjAdse$JXxBcs-_?jJLuICPgGN@RziQbTxjk?7GkN!YqyNsDls77F&t)Ba=6++^G< zB0-Y9!|QdvUy>BAxl(iL#jFMgE3&WUs(&HEU@5f>uT-wMmE|wioC3*FIc<@J2XjIA9U6^wDuiL^vdMsjaa!iuQ=2<-5 z=}WsL82UG_{nANFHQIF2XaA{>?{^0VxtB)+QK>Bj4y&gqV`f?4OHtIaz+>c+7gV{6x2SHBDoZ5lPLaA*eev3`F_YiI9pV$I-~P~g+pe&mu(R!)^^`i*bj zEuSu6yvk_6>G6o>iZ+$lVS=ta1c^UamES;{im7u^Du>t-c$exgFl)woZ$I_H>80{b zShr*)ftx={XB&oNbY36VORe3l_s8X{pb1#Tr!UItislV5+tz&EzeE;iHE;f52OV1TVRJ*rb1hXDJ`w-c9R>dp%wcsV>_bofT#;3H+j7aGlj_PP3Z&hpS`;@|I z!2w!dyfU*aMD$}ZEI8Tcwy%E$u8l3w>zm=Ibe6)OBkq#U1? z<}>ngpIQ5{zopQiizdDKaD7lTuW;kIgvSY|s=p75q$U}g|e`d)cew3PkZm?Ti zS#vg_Hk={G^&(9fZkT!GN}-E}N$%ITe^*x98irM=pPsmuQ}(F7CY6u5u37ao_SIt}aV3u(5PDQ@9>x(C#g_v8~8f+HIYhudxD zjVDz_!w{H^+;bM*!lj-j?V8JLCw5|=pz!%!Y0e|t0U$)ym!B?_CsUUP23?T2w3;T6 zfH{1817vAR8H1H&QnMNEpZ>sRDOi#wTMemFN^|6 zJRb@q6&9nQ9Mw``>Ccwmv!;B-U0lQ~1LsDV#H3CoHg5%iJNOqa5=^Bi8O3Mh3e6GzUTn8Ibgh8*y zAT7tmd>4KI-;STn{sIXr!Ce!TvUnZ^H~m;v=z30Pum<)DTZ~iw<+OkG-gwYY-w7w| zgw#iamNvM=r_a<=k`xDJT5$NP^!4equvBvAIVEhOWN5u7Qmae?d!=GuBgE_4pPy`9 zB-!h42JS(BEpNVaie8m50I;J_F-}{@Ajqm%-EX`KYa?wv&*1+KA~ADmCN*c&@>N(A zl-~q`JpQGp2sj^W85?}-s`o=fu%yPCF-gMpnSC->+V3{y87W_Hq2GdNedACFvL}7| zKYhB8O%bj0N>tGO(Wte_!fy73`CX_o63KRRP!}Z3kwy{@FN*uWLpGJx=8U73n#KCdo0eE( zB>TtP;<+{4D{s1|F`%nJO^D1?+n&XZ{wns<;tB6zi6Zmb1!WoU3%t3z9CFI^G0ao* zhWi#YrbQ8c5cn5cTOKVsK(|t6a@lbIwsqrgjDD?T{{^mO>d?(4nKy>saHoVQ>_`*G zEZcPOc;L@O@Dl&R#-II02b}!Y{5bjL<-*#~9*Ri~8&~c64$shUfp2GBDDk?^1)M*p zL)Bh0YzTUr-gNBxs!7ODq`F~GW;1I9u06->cGcSF!!ikdZ`9^lx{1+gx~P(~kMFIa zzpv7E7W&kjLVWJ;4+?`eKqHZAfpII@%jPEZ(~LtX270+q9I77r&SP?RTreisPzh35o~2lx=rA0{DIL>KxIkm zr;hH_@9uj;L=#@MoV4!!vG4OsetAacBx(%pjera3xe|BroLAjsj&Xs3xP`R@xT309QgCh7ME!MIU>uNII*kamIu41##&Q(jn2;- z;0SIN9#aOpCesme&gGdQmo#7Z=M3m8AYGKI{JXi3;gs9t{tgIK8jEGa{^&OWIde>W zSeck`o7K&?ZtHTmw7pOXkbQu@ygRpE`BUOUaGo!aQ`HyM+JRYlMTs*ud$>@0=!i*Z zGEz9Jll7kLLti86D@=81=zE_*S7D1Rv3~J~2H$6DK1f&k&vr7xZ6Am2153poj-+)j zc0xJt9B=#)|1|LBtwnw>dsePOn5e_LNZLG0KwI0+eFvt`N?<_U(a9*BAtD)>{ml!s z#o9JO-QFF*catQk>apYCC7!fCa;IXmKHNGXHlhW%sMj!QD{8OTj43ChJV0CQ-z%sC zF(S#-*sbF~yI8qwcvar4x$J45*kSu2lTbk|zk+P~a#;}sKEd?i#2D2#T5VDamg9}i zMRj4;xMI|jR1VDQDaxh4-gfNe%ALHOD3K%jI9tCnFvmw| zk+H^w0Es>1d)itW$<=e@iY|BB2N+IdZR^dNF?lh&R;T$>OGw~{yT(jS_bF+lT+|ic zo>2`gQ4h4{CnV-1j`ksA%RT>*`H2PDx$bRq&C-}A4)m={NPcH)7W8=z$}Me^nC zr9ApLnEZ{5_^_rXP%RDk;*FLz!VSwTup+<0+9l3}Rqp@qAdVFfX!8-o{%Esi^&Oh- zkmf9q_UJOjVP4)aBED#|f!BLBu8mSw&1X$tJ|bg`=lA|9p-sR=wB^RMAFdHUpjAKD zLqJ~bDTEuMy*R|}_r*#@$oC@mQ<*H5^)U}2L3fZgA@p=?=4jh{WB76PEDY zuo#@4e+f(^S<_N(Lqsef*B@Qvu+;f!?yClixG{BSYa(KaZBx$dXB%f}bO^ti|ANxR z-O^o_uwg9}sLGf^&D$QqyU>uFJM0jJwHnT}uh^z6G2IgiYk?eLU$GgOTwNf!34Ecv z8>npYr3JWWl&9U-cgQ%wz#-!*uG(9G9#)NNy^N@Vf!0}XSU05{X9GP#LXxp|W>s5a zX5($NWMrD{&j;%@v$ukdq6LBE<|q8mieUUs8+6(3t<;<04W6{`ZKn8i6Kdd}#|8^MykN;IYv!;^ znH1Od)XPTH^WUpuI#lYSeAZq4w->*;fs!*xk~FvZjEGCzY4|qf-Ah-GJa*zjrq zqf#E3fU7dN|PCX)~TEk?u4#mzdd$!-clGJq63ch3K%uZ>Z z0oV<9%%BL17CD&#pT$<2zS6$N6`3DHI{>+6T#&PD0Mg=d`2Ptx9%M{D&SiPA5RjHw zjXqW^=Zh{kV2h4@Zi7(27k5?spMo?yaf%Bkjmew1r@Kc{-70^PHkq!?#Tdf`zc-tA z*WcZ_vzdE}@g&xzL@{Ht0?|!+Wp$^cPt-{g!F;X%xe2(juI5axKK4wClQxj^3qAXq zhhxxBd<#f9;$iycG1zH2z`)@UrDWu>xEC)0udsgBmj`Eb4&-`D<-?1?!Up=Z^3}ElHdJI}4vV|s|hDC{pO76Gbp7GuSby`DPBN#jKOrfcd z_amIbHSqE)%(>bAHP5pqfHyKKh;#2_4ZP1jO$-+gi zVkDa$Ww*QnC8q?ENSd#B(ZwvVnN9pRBuVIBeSm4GWcl;GW0lSNWMncAoSY4ZG?;hS}#iA7~m@D)K^ zp7LVglOlbHoZQG{eq3gJso$(_3ss?CYVXQ~f5+d@LB1a~9PCRT#UHG8Z$S$nsD;#+ ztFcW#)6;xs{&Q9_9k5m}?j|9w^{_Y(jXP&6WNhE8yN^~WpjOve+?FWnCe;~HE=nTg zoaKS!WO)4IY%Y#ruhNWVbwm%K`%P&!Fk~Oo`oZ}IB8-e}zJ0pGIzOUBQR3CS!oL60{ ze?YI41G)T@n~!K&9+h^SC3JZW5?B|AH|aIns4-cXcuKVhFggiTL^2g^cf9>BgqQe% zdg5B&!$A>YZ8(9!=bFXbnVOhdjK*dQ`K7xh1j>{zUwFIaQP$>-7{q;r_T}=~sgYfL zJ~H}KP|38(01CswSEooIW~S-nL%X)?6lFmA>XGWeX;_*fA5E?M^Fus75b0U7V1Q z?oAnr;{3t2C%IZAMfD_xpw(RhP(52m%*SdQy^Yh~o_<+QaS=50C;xb>su}7klAJl~ zw>*<^y1BgwzQo!0UK=#Y9`qhpTJVe2$kvfZeoIRDZn)G(Ex;R|I`N}_0Z#o(%rg}H z8t^Q@P0pG%ghjzap2fzu@BqP$?WH~V0dRSH#D84lwmAz#zH8;tuod8fS>aaF1Q`Ol z0Ae3^p?ynRnMP}ebqOrgltyY+^_ks~D0TofaHzZPNWUJLF57tBFlq>->&;X}`C}zD zF(O&ig#|xVSXj#~^pqm0YsRO{FXV6 z9NMwuh%XXN_yjA%633U@`fgj|Sbs}%v29#I?39jNp_Xh6lP|H2fZs4h1m&yib;P4H zr_}FAuyP4F4NCpFCW)-v@I4~|b8LbckzGsV2PSjFfg0fPh#@uonFnZ($!QQSwH+Ej zo1(5BQ(YTUFrreQzW=KTzzYZscP`!|ya;}e@-(_pdN=OM0y8>>$w_nKV!iT0p6RJ@ zS4y409kmMD{NL3EeaBm%i;I2Hj2NYkoX$*=d!w$?Iw!Tr`KX&0Pa40#-Yddr^6CP_ zRJ8HY>2@zr6?+~VMh?gt@ljAAn(&9;DrBGFz@g``DfL8Ce5F8h=(HQqn7Yd}sJo;~bI@!$ zda~NRlv`BcHSEn!UCCOfV!s^vJzHiLvw8+8KK<81Y-$TH)7decV(i|isq>RMX!}r0 zT7hJO!{367eTvBX{l(3A4o1*V_B$R*70xH2D+yb!7e284kW%R0cE7iA5;}=`Lhb|# zlX~!9DTLrya||Y+i>&|oIm{ju3xOUR`CTTnpmWI!-L8+hd;)NWXM@(qfokF09Y>&o zyP-m4Ta#md?ZWs?#k5MM z{Rf8!DrLGA7uUU!as19+k*IX-Z42VeI|FqSIzwRA7`cbO7q-iqi}+=%Nr`xjAdCKX z@o)U$$|r1@Nw3Mp^_7=rbaye)N3tuIMEBSZ<*d$RC9!|RXHoaFR0kJQtncmu-vJ|{ zAER1kQ+Kxk*={2*`arZ@4%w%I;4kw~-%2u~eHQngOr*zn9H_&ry5(zm0&RDUE3TC2 zJiq5WU+T(PD|sl8Z~SRZRVaXXg{jQGd@A&U*r6Q3C%|$sd8j44?EWYI)BdT4A}G8e zihvUOJ)dLO3EN8o9#Xj^w;$`6S<68};H?Y;Ivb8s=%7HdQ0`NBlCL3__)) z_hosrhv3{~P)hvEHfn3Ep^P3~IAg3@4h>KI|2CCpWf~VKE_AI8yb$Tl5pfQjK_*Vq z{O~4j7&_$u{>b?a)JxmA{j0W(40=B9DCz2y4apFF8A^QH0@m*-$T~iGc9tz}JOPlM zf;;;C-=@v{rc08%yCJ$s7<=(OHl`^v`XflB_`{(T)>&%a)Viq*<$UN}!n4SgKc5^M z4h6CSN@Ry}@A#--%c{q#q$qP@1A7ScuU^|ZzyM*UphOZ>1Sq)*mUK&%n)2auf8rKb z-qh-CU(p#!1CHOH4Er7H@$UD4`Btu#on0%U0lGrJ6sohBU;#S42t*lx3r(=xxJ)Y39Wp`b9C**)@I|(~jWO zU@G1klY5%(5kN`2JvB?ndAC+{PGbgh*9AKDHP;1DyODm*W**$H6?K0a6>1=rQO*PC zwPgWR5IYqvt7e9GCFNrWeXQ+8S5^5y4^7x@O z2(zY;B%04cntvi#T#JF)8_=@{T8|_W8IBEJX4g^q*w#mcUwN7=d0@INjV-zJgp`L3 zZG6<4PIj89Varclx-Ax3=Tz2g8Qz(}R!t3c0=*Wx*Fiz;r9=c0*B6yzMMrXza(s^K zHFQ5PUYH{Tng=&15~d9~aMBz(MmFq+Ai-k?o?s&_IwS8=o_t`PKO{tFM)*u~4+LIC~P^lL+$Qa|f{`Ctpj_hHYlDeWc)`{>QbFsA~efmx2Wc=ig3cbeIaE-W8B74FN)L z!GmXu@{SvlB(y#B;d7yT$)o%I5}aF2%dZnDeX9-JTM$v0s5Nkg`7To5qvOIalP@56 zH~wV5S1zSiaVPKj*xFnL82fQnbY|z&*Y{GC7}JkCI-cIRM{ENy;~G(Iun7 z5oCyUowhHMUs-v3taGW9dh9=5F_@?idN4b;lz2%4GpiMB{my>8%Fc??z^8Pm)6>f@%sh82VyS--)+Ze3-~`}K;Hta zBu0#1=GW$@dU%#Ef9JxRHfTh>5*yb!hZZ|B(=&xBB~{J(C$|~xg>$2)mPBsYXMkBx zt-o$g&Uu8kS%jY+pD83=%CdGqKDVO$>Fj3(vO!o2JBs1=hm3P8mM$Z6K81ZRv5Z|` zz^wjaX1^Yl_YoVS_HwH5rQ4>bDhK=oKh4TZSp^$}0i!VV1F0f@7O zvk|b)(KU)@A1lE}cQz&v50dHH9c6G7Dyw&(v)2G+3*nE#CK>?#WN;#ZXc*@Z-E2sS zwc$aDB?5++azS(^^;DBAS#C}Ft^Pl1Z-Kp?eyA>dYQsgITT|va4{WRtY^*=9^j{gU zu&52Emj{@D1gjoNLd!i&6JV3(0Lb0WiRg z9>9$sPXh7LOPvTrB1tIx>^~~U0V>CDp3C6`j+G#OC=LO0SgVLRwxt?4e$GD@6(Yi( zK_h~hya3AAQbM%3dy*SXW-{o;Sdq3c$+>a;FR_WVilD)ud(P(p9g2Pg&P;D-C_@rR zBdSfJN!0jK*_mqqas0Vy*?nO~;pVKc8ggp=q_~3s!gEm!2xSRbFn6CtL(*8*^`WJN zHY{{1k%-WBfkuUZEBMaI&V(33$IaaZg*U8dRFzIhm)JJJHy+@45^%-9xx&|R;1UvN zmWcdQljTVBD`3{mb7sHT;jM(VduChPAafJS)G&_P=qrvs!(?Dcni>>Y$M;(aF~S`@ za`P_$DiH+7`2u#*iRi?)*fN$Hgw@E7EWM{@khsJ!= z=kgG5K)t2^*v>W>T1eBv%J-%M=>}9Ae?1Jw2+EfT^;zV9cb%QV%4KO=ehh>fEKpAJ57IvyL7kK?a zN_2+P)!x#Oj%aX**g^!%iTGE$<{W^C`G*(-AjZ4GExPH5`u`9~03zvPS3L^=BiF({ss*lM z-T9|lSnByRCdm)r0y=n_iVn?wnMvIs#~PjN{L+5VgM-P!!Is)+%lNKdMT$#mG-TUE z5gM*Guh@{zgQ)+$I^r+vi)wekOYFS?+5NR?PU&s0C7rgpwgxG={*({095C>6hj(!D zbHi7os}snRO7Tx0xBSx+x!>2( zBEBb`Ye&erHCPtt|0n)CZpKycOPcce_x6eIJIsV(-Xw~8kyP)KV>KL*AnWfVYA1&0 zOY7}^sc*feTHQVUI|p?-@6~sqblbP4Gm%n>*go|O^}3E(EyBYZ3*~Fz#(Zct!n|AA zTiR@6?)*T3VUP2jOV#=%alX;H_nfC4Y`DeY*@D(}H_XZ)Ub2 z(JXlEvcqxE)L`EkcCy))=`_1M8nBcnPn~;_T|CI`Ger&I5af9CYK!3H4<@Sr62sLv zoE`b9&Yy3ZO&Yilz{@p0lVw*zyMO6w=!rf;r{Vf~8>5r)+0gE86@32w*G|b4tIdpa z!u#)5QF@nV(|AJOT}G$O>3Xj36Bt-GI7(F zAh@mFxo{R^@@hC&IrQR#ro6p3KlO4T=$iIMtcTPUKC37`=;~aS#igL+D+vCNtfqC*Pv94Il?u&Iu)t-+kq><{P zobhm~+?IrWeW{gKH~8t36MItfArqRQ8*HbtHvjIMO=MNg$?o@_>wJH1>Q?>zN=hB0 z9nJIm#`5ve?03VgS`_)17iCTFB44ojOAtwEdy80nz!-%1y4n1$89FTt6Th+`A!vfx za_GOoLftQkt$mFTVVJ7^7TNjuetDGY=_)UcII)jf(@o_B(%3HFNYXw}UQ)pAnN;3V zS+Zam46AuO#MX0XY?@f3o$lJ!MuiKdSmtq|Raly@){_%PPoEk$W?!uK-j+{jW+lHH zbvQ8|?KFjYOOsrF@Lwfg^E3F!uIoXjuaE$9XTzm#Gpk;_eB+?N>flWvcK#Rva$(?( z7tjOp23Ffkz(*iCFanYTBZL=_o&)(P8pub{IamH)EjlMR(2IX)Z&Mzomxd%X zp5`F8W;En_z=35>+cN?UB(jw<0KAX~W^HTe!QFgw-Iw;n1Y|<9cXsb5162h*)M~Y2 z6?7i0BnO8ti+lg&NeSPUD5s;*zar>ZJ~CFz2CR+>?rv{+)0l8)YZuV?E^Ul^F=;G z<&7{0mo#oZ!?>+->(hEP1mC{_=z&@D0$)cPZ=VlsZ_bAXuI@i>n--b}nvw?#Rr$_o zj7h}^@*o8};W`RaY2LN;8jk_}0erS*0vmA;qy8Ys5Cy+8w}L?BVolqG>HLi9i1O?| z@ttrVKb0|ev8sd^KlaYr$@j^2xiFAE(3hV8CEoDP;?X~K%ecbyOPTj`EZ2}v91{(G z0srW*H*tz9@)XJm-}t-b$SZsy9U*lj&)VJh38@tscvzL*M0atI=trGhwaCB^!OUA} z*XwWY{?R_4=KI9s&)jA816IsL{aWJ-+PK=G4Kru7`3>1h_0|V$_K|ok{gkQ=P<+c77`Lzq&#mx?U2ZVZSTQ-^wpajbN{)YW^9F zFV?=b7b=(awNPXcsuM)R^UX|b@y~82I~n4B`yX@w62Y@iNQvbLg=$3VLNC8_GM=;J z&x?4fp0S$-^mNFN&z&oW6*1U=KeBz_5^Ip^aQ2m^=>A~?3VfWkQGIa##$VcTnl&eH zdH8{jxz5>&O6*+@LtxcJqA4;bcK9?5vJMvvov3{xPT`b#y30rXZ?uj;t&EMK*L%QA z8?r>*Pxml7-?jBBlL7yTzvNYsPuh?D8-f&_DPR#>#0Xkr(&ZNpT~XBR zS&McezUR$y^!}+Hc_glwW5n|B z#ea{@(45+Dac-z<+;|OrAb%(+1t}uXZ;j7xz%BMTK&Vcpb4)Gpw&p$A z)xd*38mp1Tv}WROIJ9k4EyNI&+}n|}irv|68z@%!i}mu$R6LMb4hS9JDbSnQ7w#L9 za1VoLHYP=Xeu<{GwYChY9e3^6e%W4ecs}%Xa5L9_XsZ)4de5~jpx4G(kF9#tFjVW| z&;mu)*$@i~DjhX>+4KCsKKvyfic6F4cw*vZOZ%Z*`fC5Daj^cDGW*UBwc1cV-s}^* zBILXmF*=Ai6tY4dj0~y6Mz7HFWUclVyBDB&;lErTXgiMaY4G+|DOZQRIRe^>;P1xsm`vXM0yR|Mmb`U?=`Dz2jsmhyUJH=a;PsGVmZLg94=~WOoZa2|YV;0@AEarlg zte#r;lb4|^5T(w7luIPoI}TSf^OFABtOQcSHM4-jZMuTHI+?Wwcn^+Vcysz#;wEA8 zPm5~EvS`x&&|BvuMC!mze)>}*%V~#1>$1qwPwJCj*`cbN^^tl7Wm@k9@6H{zML9qP z9S>-&&k?1B)l7hEnt5gL{pHufKq#cI_mqCvtw(nCu?@Oimo+6Fc@K5dLV8R-xr$zW z0*wzT;^(e9T&3Y-yE0<#%;tDY0e-O7`Jeq;fpAEj?!!QF&g;rMSWPd$eIUtqLERQuTwU3p&%8UF{=oc9zA@M2!kb( zY^r>u(D7eNNJD7Sepc>!O^p}uvfiPA^P>%COZStNOY3^r;T1RwOM1@@xE8T3`sD(s zfpM_{D(P!L>xx4Ua>)s2k+J&(a<@R^KS{R=&gbeO9O+?L|D`jKN+|Gg_$vS zb$83Y*OHWTluO0OKOQ*sUhn(na!7a63e4Ak^92_Ud`KtNrZv811J#W8UDWueRH=u3b>lDMn(_(V z!5bHVS0m|nsx)|&+h-YjHCC&&>})pkp-sPLr`!;yjOXdb9f+w@UiQA!;U;DkE# zGJ*`5G*8J;GDJjt=5Zd2UjmfaD2BXxsJXQ25%6CZW0s&yx&{B@(8?y)t1Mj$85bTO zQP>shH3GdjvK}}`zL-4k#vJ6p`@}$e8}&f02u$Z~^E_AGa!Mf$+Oa)Up7q1k?#d70 zy5)xkB+Sdtcgi9dw-h31yjrG<|2bIFLk8>xD6zZwQqf-cD8&iSGjh9iXLlc&8Q4DA z0Pg*>7uawx9gtwvTBnsR%+DDtEQcW)zu@i2N2=4k%;nX{>(oP)QU{dch}(;o zDDRu|F&&8DOpbYFMWCk#oV=Ywt6oit*>`A`rDBp{O5rCT)kpg+_RT%) z8fO7>4HycP$nk-@ssK8d@$HYTxju;yIgM<$c>5spz#%ViJ()?oxy05ZQGCvq!plP? zXqypkY1bZoN>__2UnC`gdY=Xlv~_>?>Ss0)CHr*IHT;ssu75P}{3@$fHfemJv(#_F z5Q8Y(H4KrD6V+@qRewykH{iD>Yue2Xoo-Wi`XaaE^M?7TLK1uX=zxQmHO!$k6=ayA zhy4owli$Hdxtub-_eZ1b{0yy(wO==tbI9Q!QuNzSmkjIP z3x!?rSqzbZ&V4c(0f?Cu!Wye+pBKoo>?_n}?~#gD>`L>^y2Hvul`FFSx2#&BWVG}H zJ<_}mYzp)IoykFTi3LG#eaQiGZD5K-f)||;=s3{l6ZST{J>7Nu*xx2;#B+?*PSXD0 zHLE1LFsmV?ftBOk^M!-fB&(g>OvB*ofKL`N8NmOfHn!3#ejYfHz0)81o#%#T8 zN@;9G1&LGm`DMxuf}mL@>}xT_34#<4f&OPVVKH!*eqvcJHd=+i=QWAAw?Aq&ah7MR zH4mh}28uuT7@Yrsh&_LTgtC;bM;?IdK>5w3@O!O00mwRtb{}v>nAOAH1MeQ!Y#Ku0 zn+JjI8(+|qD0}&fGuS*WH^f0Y{s5ePXI9U^h(zTrYrABOp|6XAg_clOd0yO_btR3k z;^kjQmiE#0XZ8XXg_+||B_i&Y#eH?+1z_iH1BDoT){ZQJ5j%__k6A-2D(~u%^0kdn z^m|H_1s(slKS~LaKpdA-599jZ{{nD3e^8)-Kk$-l+_`v=?%YFgx;ne)4dkor@YOox z&%@|u4DOxGGc$29u$zHrL$aIcYHGR1^s-wwUxM;A`!@4o>*V(t!fdCm`u)x;T+%7eIz7(stVSTte3|d8I=K5SE;v4i`#uz_ z!--eVw*}yNzU<%f6p34rEpNJ1ZF(w%_)SP8zF4Z`Fc~ids`;{WY3}C|OE^2Xzoj(H ztwKAu_uWy^hPJyj9aSV@ee^`9^g+#>&aOvFXMX2ZbM`8RYrJ!|R>mpBaeQthg_hOS zMuU%}tkG*|)_ZcIGp?s|jO+Q?cJptp4vzMY=22d|Af4pbP?N7a)ne#wqr*$gZ{l7H z^it&^zQ5V&8cxZ|V1dm#f9 z&e+lC?eFAYYEC}%EdbsD0lX3zWMZtUP)Z-PvsSukU zN$6rM{2b4cwT?W}nUYyw2pp4S4R$z7nYayPT)fs4;$xL=I;e(70)C?IHmc{4x7MF%mgAngoR zu4*+g5BKIfBf!>z1K>qdmED3vK7U3YCT@B}zP$)Ia3ye5chc+%h0tB;F&YxUs~B&-R=jQE$y8j_pVi|Ds{H_+++Be%UR zBf7Y=TpR%Kaf&N}$e9p>71P9Gzml33npl#Mgf>CCqgn#}ddm}6CxabLvKGtb&o36h zc@FFEY+##gbWI5r?)BtO)Qc>Bee5tnCPjb~h)g-R7}=nGEmPK|BDY_jI5R6|;dK7Hvw}WVuV9 zbD9I=iH#Ui@j8Ckkq*oq229l)h#8k+HfO%PphK6YooL(Ii$b!A_1?%fFR zp3FI5P7;Z|JLKwVG@wBz$kSX;Ct9VTqJ1dv)zS)Yx=;lf zvChcC6<>(7{G#c((FkD169UXFn#SC8wFYTDZj`IJk40$_68jYAycYm#;s9%4tkhuESrv(=!F_$|OB z-T)@?=53wA34Ijf?`eB|T27P(nAHM!v%*?%bnK(}etO$C4}FwGEDMk}0=g(W|3;?c z>|$A1-GiDu)T`&f4}Jb2x8Kz#N1tU`H6$NSf+PWnzH?KG(H`_+Q1#dQM~^;oza>`V zf(4HIKd~49eObepUvY@nn?j8L#Bh#2_m*`M-m)I_d6u$yFv86d2e!;}dpu#SkLA8B zvA?YR8aM(YhzS@)F@fLr$pHtg#{kH&z`Qqy0YDBD-I~$aG7?l{5qSB;ESDGSVLj;t>ii$Lm zB3-(4M0yDkJ5@zM0YOkedhd{+(xpg|DnW|$4hf{*4FvV~e?Q%G?x%a+Z#hr)*_oZT zvoo{vY%wt+7+5V;(Gzn|fIRSQg9aAI?dgTz{t>HuJ4L59Q|UCVllj>+K^A^N+tb`#6#%9YEKwG4K(_DM4=DgdS&U?VdW&5G%vY&56zAJTuA!EWt{aJx zzJz`R9HX9u*aM!#q?ccZcc7ZgYqO+uXG>xMgR1}*Rk`V>7_Z`I+Jf}QQQrO_HwbvF z1R!jtej`?+6OD>y=0S|(ez$Q6*b&n#o{N-9eItn@>9`aE^B0V?PT{q%MX z@{(+qpg#_?THCCpg3ANg@?my;aCnF5v(*(Tp(OwqstC#ulpfq_u?EBMrGnvh8;7t| z$Y4W8@u?IQvI5BF=bWcZlz{PTe*s{!eX#2Xi0-Z=vbNE&D}jCKCZNqtZR0F}3CU=w zn9MSd85IPRmji2FQE;o13rwzDD6vp6v5yK8XoJ$%TiqVu>G6_S!HV%+)Te;xO1pG^ zQlEM_g&hRuIR)@AJNrW7kx?m>ThpGrJ zzn*od8s+k#t9nMB4&n_s?p<$lqUzPG1c%*DP$UgB86oP`Vj?EoCsdGI4!iOTEYcVZ zGY(GAc^znp3ZLo0{d9W*cpv~aLILyi^mw=^LFp^oEAqF1^RtJUaX+bGZ2(xC$Rl=# za!c|NHnA3VvV5k!6^Yp62SDBIC@}b=eHz79&ZDw>NzBpnMbuD$0C*~JKHd5xU1LC* zcILcL5s}T8%Dhm(ywGF=P;)Q~Y7PXyY}FjR22Wpq@cF@X6`SF0?w(LxIY~VknE*>- z;;r)zDoQAts5#m5U+Ef$yd>R=uBuWocc&!Vt9ns`D>S&j69X*~?Ur}ip3#=z43^+r z*qN=L?;Jv@vT#RuZZ1CO7}>gd>#2P zC@byMr`GT=+y^4yxkqt)T9i;XnQBQ%IG{>B$|D7VZVPIr>VLGv@VGZtZzwe|Ybs<5g@Z^7ZUiHH{=-pyX6j z|BG3^od5}H5fGYYR0_rVuccixj|xn)!=fbdzQardVHWX{l# zsRN2u|57&7xUu@U*-QV;&5>sHt`5AIZF`=2X286ln*c4C%;2LQFM!$@V!7R_i7m(-_;mE|4pYtjF543 z@ZeT`M+a3hwk08PYoDJFy$tA`PNR1b(6QH-Z-FOiv?p>*{HCLcDT?BN*vqd}v99WV z_Gx~e4lH4FT~|ctQ^XhLj}J%JV)>r12$2W7cEO6441VdcyMo~nudZQTWr(^CDzfjF zZSu}3o^GsO+W*E9Sy7voAUJT@H}xC6t3U4A^&4jG)bh44MjzchqsE+jKIVwrN|+tx zKXa&9_N#{|t56U32cHb?Qm2r`mZ`JPn@^?-&3)Y^`HNd{F(&dQ3D2V&KYNHQ@fEuv zysqz{XR7f_3z7v5INO?af1^=X<#1dU*ux!d-zsr&Xyu!>-SW*xc zu&<9N-=#FL$x3>f^HaJ%9{gf+=p2hSThjw@0a?B6!P1tXUj~lYfDDNzON_S3P9R-s~N>%g*M;sXZ zB`z$+q2!t1b!^6$TWG!@5(ZUc6XWPXEo)2Q7_kjoJ+0^H3b-b~IgG|6X zew^&LSI17tpOleQR8%y5g^nNDnBcd+ZZPW&wH!G@AH zbNW)01Z(iiiO8OrsWp92qxyTO)tEPN`j!7zva?>;&`#(w`#PCgYSs*t$Lh$N*5}B$l;7TlihhP>fC6svU66+C-Nt0}S8&JW!MC|=Y$ILk zwVZll75dzO(8yB}pfw^z110YD*eAFAzly#jnLvd!-9`6iUq^bq#~0}A%Y1qM8i*B~ z5N|E9>MzPGmwRI=lt<~Y5V4O&he0$3mb{+ez_|tYw8Emh?dQ_^+kFW)@-fT?c+*8A zst*EcjWLI9QeSTz50+9$jhgLD>!duKyZ~C?cs-f^b=kuY5+AiF!8-Qf$(dS9Q_Q<-&EJXMGV27b7?P9VrbCmw7|mL+R`swLf= zdIO@bNG6ejMn;AAK}Uy!fI?@#tjc+N*hiSCDfCGU7wpoa9v@#(kB@scrZx|n;J%2& z@JS!NA7F2K1-62fJ%qL8S>2qfm$NxzRp)b>j!3}G@_`k2_Z}uoJ;6#fl8^L%swJnt zsJI*m&jJ7BR2u3jf0XcV44~Y-H&3pZ2f30h&!|4z-rKE*)7l`x5^?O`0W5DoOX5hea4`Y7N*3`l7Dv-mV9#nGJOQFHRdCPU863i#oqKRE7UnCEY}3)R z@)r@E*0qrbBNE`1s%z6kpN}fQmbT%}rp+PZUe3zHddPFXFTVycXtXtuNNe?==;wNk zLOhk<$p<254STQ5wmE4TX+abi&&s5>PBsUC?GB~lgnO4@_@sC;+!94^z`tBMx6f@q zatS(8JG~InQyvuymLUF~O(?u^Ws)s+A?a>ofNJei63)>(?F&PQ*kZkfT;|UfFsLQ2 z?&zA0#p&vc120MYynLTjJK&CV!OeJ(UN7)Z?-+D66$7M-@9h-eel>Z1r(Czy$(R1S z-?9-FCKC_nu<~3O=6-B@iLV0aWyQu`_tlG!?b3ogL<##?C(^x!2OZ@ZEf2HGs#Dye z1Uf(YgQ=9m&MthlybdeDra7VnfBp*0v))wH-GG64xlc&AGelxdx8S)F*ff;J zfxqE3g3|5^_<-W_$iAJAdE??u&qk=IJETw_;9Wl#{{a1Egjji>X=m1*5cYucS|QI~ z+gFMb-nAu%SYTEfbQ1E=vi05@FGC2a_RNra*+EZv1d<~uINGYKMJV_h1#@y*qs6#U z8Y^eWH{gSWg?LjsXM(*>fd~Pt?OQybyADaqJ9t!fET>g;k(l6cs;^rc!IEsDAmWbM8VPDHrgD>u*!q0`P?790iX82|g_LdwL! zzI{ETOqb3EDAkJkXmuhAPsybJh-Ms=RWB$kbvbNAJ?aO3A{^&!8}J>WGzva;3+VE` z-i3G~IIU~78^RWAs3JEtT88t`j6cHg4J!Eho!-cDbb&y2GjRT!!!XrD^Y9D~Iwv>hz0GoZs*E<|!KW^-Kciz|M}ce9tmHqg2_Q6}Lb+al*P0 zyToWCXWgAek=l~V&gq{=TwJ{OvI}bl!OuP+*YniNMxEl4BEC%OzGEsz*mqn9R2(58 zKqVj#J_J((nQ${bplW*O>$k$@|Ns39lvqn}nx$_pS`&qqQ{^+i%ZNHZe&(*J@Ks7lL7Kk4?YH~n+_`{Pb`sm!Rg4FtvF!P>^RKh6&Dh=fnd*}6f6#0E_z=*?+twI;HCgcU;IjM8;AV&Zci`vU+G`EF; z0@Cztg>hHQK}?6nXXSd?>9d`;0pwdEn$rUtAoIf+;A2SP)rmW|l@Y$oaA~M4fK9;o zd!xDD`rWg-8&XMj;D`y1J~ANJw2<7PeN-0^jxnNUgNSOFGPs_490z~yzbjc30a^ij{w0v;(=FLA_ zX@F(YnMs2zmT$zsw?iGUD*`p;BfSFhR5c4kKZd-34Y6I$P{rO|*AXZ3==n^HygUWp zD!a*j25z$HT`p5{yjlG9M3Fdge=x@(uY|+LCGjAFO$YhHbg6osWV=N7rC8CyUMJu& z3hs5y@7coGBmem==}d;an57(X8Z7Y$J1k1Py(c{Q>p}tP&ErknuA;i|d1hxUnD)z| zKB9O~vMOfI)uo-ARaZdd#)1lmt4>`}er72&O8gwj9-x>E+fNr@QvM4Zz3CvG`=6eT zP|na;Sbuj+1lguGB~98WHR1A9$8u55J{tg30}1YzqydXa&uqkp-B;F!K4mT1K&Etz zeS#@vz@BdEi3!rH8sX(I)w7ZkGplU|qh_~9Zj%D_=TO$PtO~fWH@2>A0R@#trTHrP zZVL$4bSdKHGQCv20N0IowYvwY#U{vQ=*R}~cb+l-ISo|(i8adv$T}Az?6{G;_njuZ ztM{}{1voivD%;40FZKuNNm5%t(0DqUln}W{S$ZP@n1qh z1mXoFZ`W=Ms(BMWCcF6k>biV9#uZ$3Ej%e$c{aN>R(5#1E-?#&q7TE%LpSnRR(Vs zar?YF(s$0$s+*SCo?22O+^hOU01guB&NR^X2L=6bJimYRwZQARyMYV72q zgCEFwQU?GNY^e-SW9j zbp;6&@x`}Su`IToJ{b=aj)Z+kAg94d$EbJyH+fKr-VFkZ<&Fh>sE@FWGY2+q4JzAv zVB~0j$DnOWu38a%f_Y%iXYlirhy|n`b&oF{>0%n57 z!S*ur#*0~vfsa4p*#qp(yd+P#t}PiW{?gxs3^)6TRyx#&XlYWB_cO~VS)G^(Q;*}u zX}tS8!85dK`BhN9sg$!g@q{CTv@%NG`x{rLwn=9O2eC!;Rcy}Cbc5LLxysK8IVTl8 zzLZi5H~hD%nn0gbX!g^Nde1kr+B5Oli#A`Ly(Wi_V9N>!+fp71HQ|0nuI78~a67FN z&~8KPlZ>* znkBGvbL;A|&Qr287L_fCg>IMiyEL$O(Lp(j z(TD5PDVRF)#8^jym4D$@y`O`~V)>chH7~|sCAA>2e`1{paeHCs2+pFyz+sBMfx~=7 z3}vMWS}lNmj}cT$s=s@4&%kJ&Z(y=f`Mp)%XH(89{f$&^QH;<)vbm}$-fhbSDKHwb z#(Up!XbbyFo{v*3?v2g_HLf-j3-!TB`#O?gZB)RR#LsG7huSa+{QRcmZ7>?K8()`N z4F;EaMc2Z|dTLvIM9(|@?z;P_id(8D_Zc?4gzR0qc+#*B(tbJ5Q5;LF68q=u4NM+{F-&r@2J>?U9! z_;~KCu-;|8ys8t9dFwEVY-3#p{o#e0uNRa_Y8cPjD6%hVbvNa|_<}|hOdnuuUj7bk z!E?2FiyDZFu#IL>?mXXwCfM;LN<(i)ICk3}Q#B7TU;{D*vr$6@5@NN9g$Q8q!s)8!9_C!J(HA*;Rq(Je(?t-#FUyc{VpNy0c{Jyy{GT^2K=8#bZ=Se?N=mk z4=aD)aO*U<@2uuyG#}K6Rvl6Fe?)m{bSYndxc)PFb%(c(gXcH;E3p3=xeKxo za)Kq~5!stBa;~T$4b0n%QMiI@>g|vn0ewTZk){3sx0yR+7Z9pPS24$b?6|V=qDsFP z;p;GEzsEVeWh5YT(w^4Ff%aB8`&IjalGGw6gB1^*yRkmINKn`=Z^GmtpM_G9n#61B zIpiO5KVtMdjVJ6~dPeqrJdG2kVqyy0wVKlFB-e#5+^R_XgZ&BCb@=M9cX{oUTNwYT zH7R^vE=;6&6|?&TNG~<=VB2KwTgEIb8T5;yh z^FIsQ`~fFHZ0cDTI%-olln~S@ou9XU(3q2+pMfof(CTQniOhM`erok@fPvw{{l2?M zA%XQiTT+qI8oK5$+|4=B_P8IthN=!EPLl1q)%WS35~n`o|BgvQH;>NXS#A%OHIjZ% zIgr54iIOdjb?gY-s@?y~F}M`cEos%!;yuDOHrYUW(ZUrGly+9`{@UqK$*r2TziTRF zUpJ4ezI}8VRyL)@Crce`cMJcbw}axgK-$39c-U%FEfNmNA^a#4nd`u!ZM z>_KPznkCoO-R4UEj?#i#{V)EK0uR`<%rcwxU9ULL11Y3Zb*wnY$h#2KC(vlV^#dsa z#N;d(WuhyyI2w2dG>${7i_TY71A(7y3%(ToXhG1txJzCj&>4kE`2iOm%Izg zeEu#0U(Yx{Vy#t>E~G!Mo>y?E@Td3LQ{FO;+9kJmu5$q z_zjzdfC*5pLODg2n&m|jpjTK+&-4@h91;v&{ihiGJ4CmEqEFFx_)HzhGnOj0mnl;x zgax-e0(A>Lp&CmtU!sYupn`{Up=lNxR^MP!Qc@+I-4@2N5bV0`4pRATfLv#lt5R?o z?RDZ9kpJqD&^ymH@GP$k6eA65Y5j8krd)$i9o#6-Hq^veLWd3<^1tJd^R%{t^61Wq zJMx;_G(s9fN7MpejjsFFVJWrP++OuifXZnIMgE7mCyZZ02XAl86i0@uAYsqv z9=R@m&=>{Hq5cqPQeXIoZO^kKLI(`-DQo@~v6Q*O(wPfppU_1e5K7Hbdvlbs!$cST z5bF-q{@@K*g5tv^nm-H}#iK3!!!h+T0d`N!Y0v(gT)D<(xeyzy!Om1bAo4HJW8|c=M>Z6Iq5}b zInWI@V2t}QI=tTFg3rsR&0oxYDPuZ2{$k%?By3Uw4CO+dhk?W08bn2}NvwB?dyXm6 z@b)l{InH8kAyoaR^f|__<6XT0(#6egvuVnk=eI3p=DvYfrXWlmaN*L@*c`!uPIJPt zwThI^Gjvu5W;lU6=o+H!*UcO>{qaJfr)A_0pC`7K|H$W2rmsE=<#`Kz;8Z!~`N?p& za+Q%>G%Yx4sS>UH8gb8|zVkDa^`DB3y=1P8Gkp zKAEFza@Y)M+WN-DQ1>+yu+rkY1T<3cFh|G~hLET>FN$K)rCZ0$lP3rf; zP$AjVV%zEnFp*>YdJsn1fx&$BAiS;98Pz`u3QDIjS8(%FGwa^FuPyu)_#5Yixj?C! zE4guhoxwDZ^x{hBV37G8ip_?HM%&+E;JX3vqs!sp$5F?Nb7K2@Re5qK;<6}7fARAB z<+c6+$nS^#;;GI3)V*mu@8>!GcgpU;{PhbQ#LA?XLyQ%kH+U#(#wM=c`Th< ziL0svL|*Q|Pd0kL2e5qch0ImS`2=me?yk8ksGz}7xUutHngr|MTR+u%C`o(@4EhND74A86YNh} zq)_{RZlw3Nwxk)pnte`BF1Au*3eJlu&lZalDY z@=QzqhfbjO7Cm&3!u36)?RR&<)M_1OIGke!7XFGdPnNkVjouxe;-<5F7E!pzEc^;*)c`1HO+0=(~WHe1BXx&|oe(X}tN0z5j!~hQln} ztHH^iQup-4Mg6-F(4EJxbYsJo^l5a>%tx9!ZpHK|2l3^vx1H?&2pjYYx0lcAaME|* z<1hB<53_JgYFs{vI&nkWfEFy;oD?nySrVBT|Ncs1;(ILK_YM+vBP4-S0{i05+YY9G zXUk__kDpXCn5E%q%hSCR6T+d0U+ft-W zD6Iy6mkAd(r4#bm$I8b{B)^DnAo1BFx78Fl$d&XaZ#{9-lkwEoi38-=cF4bYEOS0} zmNVt4BGmi&>Z`OJT_l8$*5jQoF#pTK1`~9D+5{`Gt$X;pm7WpgfBZYg26J32g1dSC zJ%F&}#*TB&r2j|mm$?^z*|Z(cM=x-%zg#zb6-;ovF!%4|k{5t=09sp zi}h@?=p-F8k=jb~-#3Ica|7uEYHB*&|NHnDM=qM$mj90cZ2q8U*8jf~Z%NDlC!{zN z;PC}SsjQf(_ZUKWYI^Fi-FZLnIaS;l92&cKXTPFSG0VIog{Q~)oZq@j`SxXKDno_c z05`ww{NM}yO>fSI2r8v4_L3>R^K1jZddtg=B#x9f4|!y^+OG7@Rq-tZ&rn_$>k~m4 z=Xu;ez8#MWT5q-9wdV-(3Q}J`foA|$k0tkpnT#Z^SP)uz=XnjIg9&L)qs@-VV~A&S zv$s(r_{!dZ)5Y5I*_Y4%BQc7cx#)#RZ7Zk;$5Z;{o#uomy&d(xqrYO~dY!5avx4~j z4GNbFdzD||1*0|Uura-7>-T)lVf#D7lYQPxb4P`b<-?CY5E2@w&HH$nlwn@c-C#VO zv@xS1hTQz83o=@8ctXypnsg6nzH;8ll_` z&djM7|1o5sY@HcYCh)77Wx24i4G8M_nDI1&o1WBCP=g>qBA;4o6v; zJ4Y>iwfPtGd%xv`j$=71)dp3W{Szh^EL{H{4bVPx%n{ViKDl}DqgNLM9(7WT5#gaM zH(lb{f2T!}Ej?n;@{Zs|MQ9vyKK!1*Vk0!L*2 zj=W44{Ngejjc;d&42$)NXP6qu>&a$SVUPpvzlipIG_8I{^%;`CBJif4E!>LYn_w6 zQ}ZzgfcYhEHhZlaY8_%@27phz1n#EF1~Z}9^+GWKuYaiR)it`Hp^0%nJu(ix6BN{lq& zhP`)h+f54MFo^#6hl}@Rgoi!JJ93F1p@L;yRX@u-knF2D4H74ZqD3ZqhNRd2I1#gl zg@+fejqQUvajp|e$iJfxGcw?{r&Efy=ThWiT~uk(m@n-+z@hPwZwZ zl`QbHig)Q6Vz_lUtLSkdonGiH`=k74el%BmOV{aee>Se+! zmt$NwUej(Bv&JL^2EuBy4LV~Wvb=8h+~mcElL=}?s(CccM@}&_tamQtaqg3h@LYmL zOqrYg;@rcGVkv zY6f7H)WW6k0X|eqG5_uRBf{;i{Y}UN@`wJr;PY#nL`Ql+p+pa#j~&mU?90vdtFmcn zq93~?geQA?I5@W%CoU~KtWjRYC7%MnKn^}hk*YiUxJ*Jscv2%NlxypjH8o)hN9Uka zj%4Z!i%@po9Fmff(Ym|Fz<^&{y&$#??HUuq`YVTw%URlBP?^FI%3$KSK*n9V^QbB8 z;jJbh)D(DNAax->A^RS^lR%H-z{_J4nl4!SwX$+)q=xoUX#jp8;_-2n>j*vmShOrm3$7+2jU3U<%J zZ~6ZEy|3p4NPBCPwr);>Gv*NpgnUc!u7D1s=olrS&h_v#F`Y^K1~X*nyYqWhyX~mb zElJ^Fz25y|YARq&srhe5Pnsyj>)dX93$08>iQ7Ke-Uz@&9dyEViL7J;XM4){h>L?+={)-BdjE9cSfdaU^!D ziU5=c<^~30Tvj57QUVh()|eyd2JJa%yw|ruc8LlP_jK(ox-TX?>DfJhoJ(pl{Jq^) z<5Cd0{{nR2ON%!C6ckFjyXqR0!MZB{bfJBlS#N=8ye)qpl}!&NWe>oF z+g2Y)V5#@@1OOV=Ql0Ip^MHIHPvAMtTh@F9n5Zq^b-_#>-k$JfaV7u&A*JBj~PN5Si|$nk6?MhAKlj_PC$t9!Z#&}IpQ8v+s- zl5R>PlL30kSB>)G&=>FFq}Z3~N#lcq+ho>^2a7RQ-G9jp0n~>)IP0Dfn23;iWV-EG zI|89{#Hw{eJvdocJwLjBF$d$!)#tamApzx32g;Ex#&qyl2%uJoMSTGSUO*nxv9(;} zX?iH}G$F+f!pzKoXVxwoZ3VBl%4BZ`&~Hfqf#_kUXX8Z}AUaytxd+t2q zxj?b_mQhSp05mO&Ivj(}1>kev3ABn&diLH|r5ypL_p>g}%m$}3WE#WUO_esf_DN1^ zWF`Ng1@2D)9OZjX&~xzU0UUcug8Jx5``$V{qv042aE$lY;zWi59QmBj&(JgAvph9P zw7=cJ-)_>{$B=7G4EUL~cf;SIB*xR-FKJdv5fDg`kaPret75=+7kwyt044oUOxe2l z4*!d|H4xPnyvFe412XijE#v>fo(6wU8{YCoJ_wi-xJk>Mx5oh;GHTv`1GEM{kID`> zr5~DzG3$(^S@$lmY4!AR>#*4ZL3YlzD&jmk+4F-9d=P8X7PkOFZ7I4@1D)n#U7eZN z*xAj9-+SuX|FP`f0Q7Ie(kZa)*!jRwT7=-w+x_gUs{_+|kGh%goTo2e`(MNx!Lnc3 zPnC0vPUaX6F43s+8z|^+gA_A}BcQ1xF6Y5CJ&EaUB9z8Xb->Qn>a^$RF#x-<#A}wG z32(t1OUs*p<)FcGn8c4s1DP-&4WjL!q`iqsv=A+DjRQ?V)5*)=hSYgfMHEZba8@E^ z{*X#ooZ{-(@9o@Gp|J39NxPUF`{Y%4`$AgZ=+U+JZ?H`d{mvu!O$%s_5GUBxIOSFD zLVW;@eCNr+_T1n$>M6!8Eo^@Y=zp`M>w4lv0O?B#OT`#~lv0_2_?)X98@g>zq5(d7 zuv-@c(K0|fWsYT=+!}sXHoC^RfhwKcH@_VdwN(Sl%CeXiYcB(aWn-t=+BjwAA+gP7 z(0A?Ax9#mSO%*6ahETc)-0VD9{dq~xfosEIWy=!3Smtndb` z*x)h%YgqxvS3bsY?>{4rBV4*b=6+0mv15mr|Fui!Z_RO4qAIpcSUOO*42R$(;3et+ zebdRUAT304qF^GF^?6+vQ98t{y|Rh&$X;MOU{FG`k1(x-kR0^WYA%D!d&Q6*gcEkyUFz z3GLk)5D2#i8fq_~4T|)FfGG|-rtbanqP9s~5e?r?fNpA^UdBNhMbpUh*tQj!fDQSL z)7w*=1XG;Mx+zHqu>e|bF@0JI=P7Sk_L*h{Wq^{)3^;uURo>!&lH#4?YZLBecEL3J z^Olo!G1f62j0O#R+l91C-joTw4xdVBzfr_QGnD1rtcw*0h8@E2VSTXDy!+*)b56#Y z9S3O;t^tScm2L86P_-w{LpDmWLCZ4< zmi!MpLebn6w?93i$#e^l>6Vgq2#DVs!gGZTOQ$zr+V1Ypw-w_XunTTH0RS=Z8P^A- zAh(Sy-l4pNCsPwRjo%5@L`PV2(M_6kxC7}}+XoVw$QpVmq2`)l{34>*ptPKZwKAZK zGQp`E&_y`Hj1pl)irTZ#yD;4OO9vA0M6JYfbDH*iphov_UFw10630-U&_h?dSCvXa zZHO;jTvp&hF4bP43&B)(aXr%vtY;nvnj!Y^%L`oD)`>rw12?mxs|m3B{7GZ+aiuQ> zd`-FoPqR2vU{#$npMYnW8yskcVh+ieps$W(rZ|w9P}@OI12)!0!>LH%aP^jeG0x?J zod!yNbybKn6`QxCo_~O_@f~xKILBIg;+HfuoP@q>wxMm39S&|XP z=fSp~{m_>pJtT7`nDu{ulWk=#r+3l@-zfr2M9)LSdToqe_*Tk~ z4$tH6GXoDH;BXCj{xeBSCYyGGJ;1fNkLp1wg3ElB78v`9-M4WQC!4>p&%%y3IEZhH z)Gg6r0pjzw@ApHXVba3_1PemxS`1_y(+?A?A-8@e9giQ}{F(uj;nY#Ei4LCq$T4|Y zxP~mE{2ZfNqH=p8n0-3DZM{m%T7Ek_oybln^gZVTTN4mcY&r3ASXwG3g_~PLM|E&1CDKa(HZ*&hw zZtW%D5;{8P6Q7+(dugB<#%rg%X|)+@LokhY{QpBV&0wIo7jHHjp4j)}<}1aw?5wk~ zcG2cEtuz3tWT2ER1KG>KfZcoQ(>yypp`4JcNJHT`AWq)n!_nXt+yno;#j-d3`gz^i(%|sioJ2;)Xh7kgu&q8ZbdXRW?4fcu%Ah|)gnM%?dUw|AX;BCwfeBnMYc}9ZnwjT!$AM!trjkAOALUPSw-j-6k70 z|9v?Eyv%Be>SVx@utQD%`*H>o12%)n1BEifkS^}ndRMp|oc1smqPwn|B>>hd|C%iZ z3hjJteXGL_`1k`ji#sP?yDplW35-u>48fU$b+!aqN>eb_KfrSn!T-XM6?5Xky$j-_ zK3jYXgzp5K)K0aV2a#1k@~R#VRzCsbc1Of+n-XcThe+SQ77F!XW1aOxx~?SwJd$qy zbwK_gU<}ABGqU^={QuHyeme&62Z3V%v2*)%_p{FGK?{|(O`|oCo8R+kq39d%T%4x9 z7ChIKt$lvmK5+rUa+QCma{^}5$q?4{nV#@ol<%#?L}*3IU=VK!=CrzqO zbD~9VpzihVef*{7F;gv|SGprunxlXg3ld1I;4UdZUMa|rQr}i)vBZSeOY41JmH|Ej zEDu6=AjhHil>6>J;d2|WI5DKi7d<8mX)ho5U(%ZQYUJDMf`h*fnnL|VxenE`OHn_3WI};__LK z(wFTGf1rf@;7v}5U#bpapM<^98p^{hjMYDuhtWYUGDN!RDA@St$9>6v?bg?K@rJ`b z2virSpx#P>Jkp&@vW)xQu1rWB&q&N22-RPMs3_kzx7#$x-|lLq`(H_PTymJ5V#tGZ*Pob zYFI*m=U|vOBS25sHIOhtJj}arbxP0XY&LC*i(nnUy2l6gTVGt%a8iaq$>5kkQDR21 z@!T-O?k1|9xC5r?+#TC{sR~F@sE1-3$y8&?wAJfYvZ^MvWVUX<%w!L3yZvm5?;GnG$GV!FaJ2a7QL3e(N?9Qn%7hv%?*JoM4KE}Dv>EjAg~MPg2M=A*T_Mn6?FN+>X$M~ zMpR$De+3t?$L(amKl%*%yCV7pHh1KV*Z9Nh49?vtI+2c8lEIMg^s8+nK~osac? zlPeF<5MW3kSEUEV+6eV2t@6d183%w-YEMJ+*-Z3bY1TW9YyroW*fr19EA-Z~XSq)s zROk0dfGwcSXZ6syHzJ3BEa^MT*bXY9F5hS4RKfR4#DK<#)eOeNOh`vC~GXiNpiQ*@5a;3Ftf09Z)@%@h~V)NvuYAnasH zE|)#n;NgcLHs4ySLL)P7K-_`FbYDHs8OkvB==Zls1M*x|D7q4u{+#1^m=(YRfgxt` z;-k&LU4k=1WMkrk4AXQ%q3OW4%dibPcz}I<>am^9^g3AndYv5quLVkFb}jTrQHdItRQ+A%nK} z{2y=9wGpoKB_9P%JJ?-h=F@+2RXhi@eE!bgm!s6znR(u;>VbcK3#NFrv)I_<1$Ddo zAv{ zu~r$>qvI=p=DS-;($+WVFiEhK?6Oqx#V6W^n)Ne>YpNZdD4xz;t%VNd_Wm5)EP}kU z-$h1{t*5IKgx*rSH8ObhhQm)(A)dgpmwF3?s>OaVV=a_4tjT9hWLnLukG-M44XzVI z`#IJ>&l(Myj2{utr31RUb8=r_3f#n~iMx_me>!8Kdiu+hY2Q9~SvoTqB&WAc9ZPkp zk>{atK_G%~O%?*e?K4(+eEJjajQb^=hfDVU$F8U@3iG|3XWm(7ET~7oxg>yc^-b~5xxLntEIW|Gf|{s4~tHC41M0?KucVgBYCboA{uCOp|Wt zX<)XTcl;C?;EH)vhqCqMe3eCZ!D|;^d}aLpk>e%d@K4L!zR^x&!}~y@1*uFg6CdwO zFsjnw=uHIzp>d|dU3PJdVf}NJkKnE+D^CLR1=3SRU*FIi7P3+6QFAelqIN>-hc=ZJ z$GJH|8IFPgl`P}$dFXTagR#_=Q8wP{FG+z8PD(~M{fjTgO4YpZWosDCBq|Y~SPc#~ zzs;hyFyRA+viC_#YZ>2}%8Tr_hCsk75b2mixQW+L^p}K!8g?J$)nDt;bDC`oKdJ+e zXMZclBuAkJ!PX5ZcLow36K`Mt=4U2U9AtkqDr=(Tv*9LzGOcXYGGFRF>OT&>1z(+L z_OP8{f-zci(bej^enfTFdoiC4U z1yi&N?TCVfz)d2mBVB#02`pc}*+#uV|0<1|V`YOBF^;)<8(-Ogwl&*js8J8ZwpWL( z#*GYGKke<#yam1;$*|sCeC3Wb(^&14%1sI2m&TWIDUHQ*ZwS{5q@{FFggLfF| z%E`;l+3jDJjtsnSc|F_!)#YxmSl4UXsc^FD-dZ0usD*4~tjv!)R6uGP)3rViJpzh8l6DTgDta}V*hHBN`Mt+(9GzK6*uKjIr;@BO;X!xmG}`vU$5;(Y@qZ}qxIAJeRL z2N8KG5ZzDTRJM4!z-_djWj+w<1Jv1fy12;chOn%yywzEyqkYtbQHq08$sh#K4>-f?e=KW|UCnk@-GK8wEERCi~a9ek%0i#Smt4ydsz|F}Ky*%A2voJ(x%(hKy?lYz-FVo)hZV zt2`Ulf9g)_Qm>g}MKoJoJtZe9LnzhZq`3=$XeJQBV)F73%Y6ABSjWB9BDW(<>Yn^?>3z?#G<9P=h_^o4-O|^m zjv{~;{(a~eCvutC;B|#Mam-R>2UHpeNAQG?8zStom{iP)|hqw zdi+m@G5Y0DUX}()#H1|c=a7b_U-5;&ve4e%G1+BHqYlA4JQKhM5Y_!D#uy`ar<)z?g~~ zI^;xW@M%;Cq(C#^TGY+Qz#C|#w?;(BE}*@+vsdaLj8kJ%;5&ijy#cVQVp`aZcHEBv zDKyxx-v$SORBgp3s6SQ@0oSwBUTQl7vlX;p1VKLzr|gg0G1|@XU|z`oo%a7F5yA&% zc8;n$Q=4XP$NU&h9TFA_9XvvZFdF6v2dTPLSC%{f9U$U@6Hj+2y-J55{{Cq}ym;o{ z$~kB{cSPtFrx$^+6D}z@VL?nU+uymV>FLu4%2Xia2K1YuATK`)6(AB+CyP2JF@Ubm zc1)0Q{m@Puyjwl&;h{fBQU5hT`pNh4ewttPk&3%w1tG8d6R~Gw6v7v_!&RH}bV)5n z`l!aLTRoUquR1ICWW9KaWt0}r+5(gYw8HeFJ(MUXJi#jXZN}9DLLI6D z8~EaJ*TpDFVRk8|j{;HEf-rfO`Q?@u+p+jfgjNqOI{V(X-8-{?v1fpuWq!>^>0d42 zV{hP#V`+Y$Q2qXkr?);GqRLU0Vl~8)g^LK=E;67J5#;Pdas1JT$iIBTr)_sb5YR9E z^nyOaXe2J1l(ug>^0GNpjzQGATKtLk^nrcjtZtB@nuIU9FhU z-OhY(5-x*LG@3s_i_BaZeBvRY`;5wfAzCQZBjOp0WfZJ|W6GGfI?$Q*=Bs~{1{{R* z8#?b%_)fGMSi^9}DB#%!tdRJZ_zF6Uyv<3A0UpKMx%^GuL~&jvpNUzjnZ?1Pe)f>$ z4-I36o$LHxCl5u&CqyA)Ddjrid7B*~wxM{iUrj?ff=02AJ!d^3>FbJgsFB~ZTK&;( zgfd2a^t>xfemf;W6%{iLB$Tl1JcCdgRl-&lDBU_ddg^LYmu3xX73S`_+QQ=iUGpD?#G56xfra4{e_o>YKWIpxG^4T*ck5bi z|1!0SlW%!#(0yY#DiEO%CIg*M&>`P_H)usD2yvb_@8;SLt^!+l2uW0+6!XHOwa8^o z8zpPwzUBMwUus{uDJ#1$j7YOVs`ro^G70hC9no2SA(ThF68G)y^!>GRZ@C&0#)aaR zeuOM95oE21_v;$fWUns~*w!@}!EwVzgK*7vS=~iE+i1f{!Q(droVggl;dPKfgm$RWuHZgFD z|MR{aqiDgovunglb)6@|GCrLyx+S*QZb+8CB6v*iV`jxIoww$8TXVck zEsxT-bI^cCQjkU~u}YY7GEqZcqh(PIcRp8I)I}%1uO=&y@_cr=@{xy|1Vo8BQg*TQ z%qVb=tcZ67&E&^Y|IV=ksepuT_>PSz@Y>k;fqTa%9H6>v>p6|47!>ECQ0$xQ#|qeZ zR1^JzZ8lPcg@#U(Pq2JlzAXHY>26^XEsS<>Zwtx6oNoO#PO$7{2s!NHaj(0!1WLRY zc~%(qRtP7s^7JrB?&2&x`->cNkB$_?h#EE?Ymq#l#ZpjSbI5)m}<$ zh*Fm+>i=o$N`soZqA&zT3beyWMl-20P?x$;K|{sSKwjx+si6Wxtr!D>B@|^fffx!T zF?7(eAg&M)Sz5*w8!1o-o9~UShy)T!krWb=v|&>M2`*X8^7<%*hSc}#{W$l|S-yME zx$ir3pPTi=_o9Ff6&1c+RqPNaC9|o0lY*Ne0+R91*S{g_%4Rf`WUkrT^JU$G0=H@^+Y5|QPkD}@ zw9E_k0jlCyEz8P7WYRV0Y|BTr>Lbt&C)Thpx+4f+<%zMXKf)!IrmAq@Eb(h?H4dON$%UyNea?!_O%)M-j!*0c6njswPeGQbU?Ufur zZ6wQ2fPXz$nNE5;)N%_kup-``@hX_zsZY>!@J2$5^fuWxPce%>e{^yt(o4jU8fq4kX`72!UmW z&b(B(>8ELv9Rks-^x%E2| zr}7HBIhw`yC#><%lMlFcJ;hFry_my-7pWV5wXHFc1)S`;ne+=~NJ%`ijnrKFcc5jZ zIU!_BX&hgpi>sXbGhtLTe=@a+XFP?2G^;W;_H#43?$he_C`5%DRn-*&%r{cHC1r4C%5Aq4IBYRhmGn_lwoRk=} zUfDZ3J830T7sej0gN&I?@*e*75Q{P;nC9ey)^LwU<-_M%jkP#oPj*&U3q|^YUA*hu zV=A}E%IAuU!f<{EE`kIA>2iBV@9wiLmuuPw1viSE0%j|y)x)9}xviGLqAN%mwF!S& z14JiDzrt4c@bdx*fkp$zSx4(!Zq2-S{80t$==+|dM^f)2R|n+Tzb||*@6-7Fe*iDP B>JR_` literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_speed_limit.png b/selfdrive/assets/offroad/icon_speed_limit.png new file mode 100644 index 0000000000000000000000000000000000000000..0aa7038f909985af264c1c4451bf9c143d724c03 GIT binary patch literal 3321 zcmV8>qID=q<{c#LCjVw zv6$=?^hc7id64oo&?T;rofZmQ35mPRPTQy`avZW0caX%SVs)#c-A%Sh0v&flawU1# zJBK!&SAoXi@!wFqBTHT1`rCe(_^#E8sK+RGEadjPIr10yfBV6QQJ14CkRNN!@u;BRPtsRehx zuu(n~$3YMlr#%pTYw&M~iXARJaC9s*#2-K;bqu}U0EK`*z#b%4odg~n$lhf!{Q7!g zG1so=?CRsa7Curn*-DH6Sq@{ufb-#8x3Wn^to*Jpv>S zd0ic6p_N4GG>E^WViBm|q_uWVe#YYg<-X0v%{wB)sXn47GTVT(rzj@ha@G>srH*5q zA}7c>4s<=SIhL^2@@g%nwu;jpS33?#>;&`$<$`=wt%KBN6px%5QujPZAu!M9aKyeA z#pNImIiA`izNpGBUVL30bVkT6uGTw>E1v@)7AD0D(Aegn#*=-o*z&sWBta-Alrp{Bbz^X#)ujticx&{wuz;}h?Uf^t* zI)2Lnpj!5aqL*_>a=J;bnad3tgU8mkq07a4WjV;&Vne{}Qd5QG{7i0$uVvOHsEHOa zAJ2A@34)zug`xGU)bR=r$Z#}5;QdPKY5cv>si?oL*4NMmfeTRcL)7F&m#Svt7|W=Q zk{JicCmr6;q=mHzs86a4MI&T|YSXEk>d_AP7aw=_QNcc)b~6_@^RHZhpD?G?x_-(N z0;pQ<7`Q~{AZ7#QtCdkO_eMTT++0J7vlm zA&Opih3Dr0J2-&M^s8^wj3Pik{@U02^&XxKu(}lyn;YVrPGmrE+#7hRhkxw<2ES@L zxk0Vs3!FXvAlk{$4uCIrc55ZmUm*FG4Xl4vKP0?b{hQRwx4N3l)~MEDZ#=PK)1GUi z!@gE=^Osx87*5tef}Be`-yGU$%WYuRF@uQigM$tZ`~m1s(3??RbQhpEq9>u-SU*Fz zklcr+Qk*$}7o^}0Uk{cu1|A?q^9#g{!GXKAfE^@!M6W@@xK|5nJvcCjw&0X{7}Zy6 zay7>5=44teXq%T0KWYFgWD2X0;c)(5z(l)UVAeI9)v6`7G5TlACGGYeJCF_0qY0VZ zqjMz0tKD+}3VE%TZ&yB%y>s~17zB4FB#T-LNP<5RZGA`~ukGnnw(a7s^Hk<8FSpfz z2^es%nvP6 zctcx0{s3%|fVW8dB0mK^A&n2~!?n=&S>yrqoCC&>XQ9gFM|BLY>^Nm^mmOdN+8_r4 zQ-8(S)c|StME`@DT#Avt56aP1F|ZF=q3i~b;6V=1diH?x1N3F7eRiXxOn{>4zOVry z`A-MgYk#)}fpLe#I)g}=(^< ztu9NpqpA0q4IzKD!+Z0xQ9dxQ(&%|?Y<*(Shxi(qyh6Jc;;qMA=VicsOub{C;rz-} zrx><)xTr9QIt*6FtjT$GLWV^{yI+*dIN<&furG!B-S8hkuL}O=A+Kg~h9U|%tju_| zOu(<*E{rM*jw94fyndL${`^d{3gC8W8YsWjl$GvwOmV- zltZR^eO@EF*7%NrnqRp(nXjQAc92#R>^v0($!?OT$K6P7?5(2;NgGvYXJ%_i9-IIh zZ;!Ku6A04ZmA=nbDi6fAMWHRNpKUGfNWy1ZYqpy4XSBL*zYha=w@^-g?d;BnoVM}7 zv%2H**R?9#R$J#l=AKonS*$@r8gQqp85?hQ{g~~B3Y~GaWI;m)A>F+u9yg93n933S zY~bRK0>^!E779Rn|Ia(%_p?BPV00baAJrMXatZgQh%*5nKy%`EVReGd&w#dkQ%q9Z zhh$Q6J0qGazi>|HZdx1Xn=02bf$5~lA9~`b)lQL4`Sa0#qZ1We{GR0XJn?mTvHF=#N6lSKGM5m$kPiU~~mj>7-)hlU@pMd(?3DqOn4QRA}!tavb z0?;G>z!JSWfn;MC;vZJ$DWBrE7!O;DI^A8bL8FPZeA3>Fe=>S89Iqw0$c0xAt?4hX zrc-xg1k5dD8Lv>UvrW9;{k@7y!(+2uG4 z!rjq9t|fXR-C&?jmI9bDXe;0vbPzdqBtxOc(^`7ftLQyYJtgOUVsqd~1~CK)q4-v&WRTelBox&UTsa;kW#*=%$V?(}vpm9)jq*Z3x zGy9TJtEZBM8IINo1h1{@9Z{{<)<>fyRNwyl;^5bjS(5Me;-Oj#(9(@yZZDDq1YhYI zs0rK;?fNw;kXr7*YMgdSmjkTYGG`g27)cl}XS4DJT9csmGpMv_*1QxpN3||gn zBrg`lgO+xM=GkY+wiIfu_A;82+1a82gAh+aOLsIKf!SpYaXo6yMsw1AMD!RZ#E0j| zL#%$K*PsHR)21ZvX%q|?fOtK0QK^HL`2FN|x9+fioWbs5`C(f)*Ua!*=qu3@BI%^` z`!Kz(nGVDBfY*;r?&LY|%A~%_Jp+J$&weW$x&i1N`h2wXXtf!+Yr)+PemnFSZ0*0z zLQS;&KhTi}hc*v1;r_**-n~vmQz^|&wGKNIvOz=-%Dn|*|6>~UbCQZ_x0TaV4hl6N zP4M}5vxU)7`=_M7%e}hoh7-3dq)S4 zj{K_vW?F*1EAhKr{jTCHG(F;`5L+!%obK2xfiU>PTBd!gCCK3{xVO*nYrClua;KuD zrO+khs#A*g5HyvK8PBjSgt|GtloAL3v?4EnwF^ZGf4NvVKmwk_c5NVBU$| zovHs~S8bm>y!&RjE!2Mf1a*ZWllC!ue-Z67mMjLI$!L1L^WEKpqiuctrd>-EZ6@U8 zQG&S(dA8rKAY3=*Iw5vvSFJA8y33WMe(%~z)B`{#TAN*fmL{e&4ozrwz1O4LECjyK zmO3MTh>AL&`v9H}?)YpEV`DS9m|s@NO(;yi`r+E1=+@{asBUDBpbOBs^!qsN$c27) zg!E=KH#hqC^Zg(3AZvTAci6~Bznlp9oI9f>d7MOPZJ8f21$uVV19eGGOe+DdgzDF< zXQ11q`DN`h2K~@b8?oO&>o;jO4r1wAkWek!Q(VWe1GNuyL=gg z*b>#@+a_;_2}?f#1MV|{T6lM^B~$L+KID49F3Fa?iIy>t0qd#2|7S@4Gn~E5hC{Ch zqq?r?8mNo!()oeQh(8hI)GwRnp?XKGwOeiplI`{XgyZ;oml__l00000NkvXXu0mjf D0wQgt literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_user.png b/selfdrive/assets/offroad/icon_user.png new file mode 100644 index 0000000000000000000000000000000000000000..9b653cc4b3f620c507d041502df189f37896b4ce GIT binary patch literal 15798 zcmX9_WmH>D*A1@0B{-AAcQ5Yl_T_oMAIV+o zX04l;lbF|4FxDb{)Pc#7BR`O&pG z)**TH9Aa@ero6((kiY+y1-v`Yr$cdt*7df5n=o4D`(N-K$TBUs1Emv%UUByN?Ur ztt6Z*H=q5?&R+kmRjGS&b$R)Nk-O5c!)Kb5+tz8U8g`S_zl%t_@P|x8ON&?Ll-BB( zomR8Kgq!7NN29`{vb?-^Q=WRwUtVlq9&e2NZf3QOR-6YZwx@4Z0UP zUMc({?Gij_;M8wFbgEgrS=2el3$y#lBI0NW|BIrveS5v@I-9IAXzM@<5^_JBIbg-P zPTFjqdpo%^!KnG%t@ELVWu@Kw3I%@jX(XN1_w2B|+VFn;?bS0D9fds|liH*3%gP>D z6#hWXP^>oj#hN-Ngia)9oSR#4O4+EA?}EbMc5<#Xgj4#Q27H3a1nyQ-d4oH8a7YFinAGkYBQ zr@F;KszAS~rAE8Ae4L#&d&!>DL!je1YV|n_Nei_o{hU=<*{y2fy+@A-2FV>JmH+i5 zhy=<-GWuhcMAPC)SfGy|B6I$J2#oSo4ilFc$19Rg4tUyj)@jJBUDa+#D`=#}W2T%= zWge`M1cby4qi5^@-qC0fK}04lIk@DcKfQ%w3*D=lm~2i%e&v}1OVFRIP)TT*&52Sd zAPt?Ubz`dOvedXZHxbxWYtON4o%i8VwnAm_QYUGW<`Kt9xyM1BGFa4$SW(Vf1C2~z zaElmCuS@lu8WN{?#1LM_F5oN05IeRgxq_XR<4lPvYv=Rj$odXold5NkVDX(93iWRx znXsCF@F7^HtMrOLxE`Oc#@QB{9F`$(^vNTWX#j}S+z|O9^A6tuE&wGbC#_Dk=y~2K z&_9*FcFj5MTN}0!JnVOQVz()h3(laNeDXqB_+2`C%Dh+DPM)?}ZFR?vbcFwn=RpVO z7WBa!3#I9;Sc&}$w$5g0D>#LFr|i%z#@f=x@JqWJ;?`R93ba&UdmXGsZaA6$ZM)A+N={K1zpK7NAORC{5WZ60|^ zTo5uU-xBxJ-I>wbL2-6xmG{-I)sd@KvXqThAj1@8)ESrAb5?JRW~)*4)6HSdmx;aj zCFf>?_2shJN_*A1dMx3$BqCj`mJc5p>aF(B6ubL}fhu)(THZu)Vzo*2B#H zRH3~83HZ3>tnzfnp|4hsV5uXO?>p5;2P=@Pcv(r7m{PmV&xz@MY9?mL@=W%`bdA`H86YtwaD{LxonNB_ZI7ALz zu^5|D;9fgB;IY&lTDfill-5163Q@MpWf~Fy|5d~)Z-!8UsL0#Nhng691*d7JNM+DF?G**^adcG8CWsw-^Oj1bsL`i29-&*)Md!|MeOBJ)?l#UYk5{ya z$dW`xKL~&&@80TmFm)Y4_T}UD5N#rPZhh_Nfn<)U{T2L3N}v5tx=AfcX*s#W;Ez+R zsOt1`<$AZk#8@1CD9lg6j+=@mrm6~gNkHlMOVK_WxM zJVk%6hTcn5gEku-9<>k!XVjebO@%%VIp^b694B8{TEK6Dhk~8S!`bq#j+fiz;zPuq zdW~ZIv;;NMsz2xK{GncW2#jw3JTh=!$HwdPvkYGN5?-gudH_nghN4&n24Utv_-vsMEoWGB7@=id@*QLR(Bvx zUiwF7bWP46)jAxN7RN&qA?))9(Ly-H#R(Kqts%@snm+u&I1*Q#)((`W{JH~T6Zr*# zrnEHkoRa({-bq{NRagi`?z_#%QBQ%p6<6hQgy?S{wQO4OYF$0)B3Nn3>tp(kNO9nPxJ-xNs85r7m}cs_avE+jsqTFR5<*;cPmmqxcHT_n#Y6} z9K1Y9B^RA`(zMqqTn3pYdns~e^r9z%OthuU^?P;!G{NtaU^5RNO`?EEq{GhqgpR|q z@-IsBLxenGtfl&5M)nwFBcv}RU{vMHxAREh4%Q zGxI)RCJvaA)h?{8wI~yld3q-S9PkEhTDj`;?P?)07A zuB;b$yW%?TLB?Y*GZKshJHc-4mL^=&p%w%?)O7#;{gvCLb1_K?OGeC4LNiFp^-lcT zDm@^cmLPfyJA_W{Hv8d)x8oE|^q881@tTMpq!Q5IiSRXy&4wsH1ZSO}HuRmzo-Bik zA(P%WVDDOrIW=INhGnG#it#nWyzd&f9`h>^<~C|J+1p-Tu>5b~Ib ze~FHM(}_`AEyagOHVuJvXkE<{v6O!DxgQEobI?S^mkJ!k(RP&#$!b3QD#0P_o8_6Y z9rJG#w{!UDbT6d6W8^li$h%r}IRK7VIjo+MjGjOvw#(uq$dC<&C3qid+Boz(WxqIQ zj%S(P`s8EIw@{SMLC1Rsf}nqwVlPSDkh8onEGcmOWUPRrxHQdjx30b74z~uxU%e}J zSf0KtoUxIZyn0A`&asnL^xm@#rp`&$=enRc`g6bLpzs4!uLZDn`S`*_U zB^3YQ`rwF`dom zwZ}2wDl@Us)hYIJIoDji_IKn48@@nq<^e?xg1JZtaW0|b7En>fv| zb*EvXM~D_uwKm+)&^4u;H{meB=0x7)6!)}L3R$l`-FNp67&fie)){1+yg16A5skj^ z(A7^B$?^*})X|I@HBLgS^j|H4;gFfv^GV$`r?$1hj*`4fIPjs<-$y$UI3&?sPVve&14tDqdsc1SFXad1~di<8bC=Xd^F9A1bh2e|ZN)pOlH z%5-ERj2eNl^>)dQp^QbOX9(Zy5QNT}%ABe|8V#4X#yzh;Eo#^BffyuI4hBIVJGb>p z@;zSZu;JetCK_fk5TkdEakFK9#OK%7G+`EJPmm;j?nc+z^8jQ%>pg`)am>PfS9YVh7+eN59W^Q&*%} zSEUFBP!UaU^E)gx1eOV4WMdM(|LgWA}0R??)AAcZ(S!b;Cy`{JdAJGnG17JToIxzb#t)Qsq)1ol^c z%gqlqe7(R1lUnb)CmG(gwKP0h{mT$5e-}TcpVw-^H|o|C{C9$aPXIAXuGuJ(j>`M* zo93suBohX&n+7i+XaIcaUS#hJr0t|a4uv!+!Z7_yBlMF34303swzzcmHAm%k$U7s> zb_8xeeH`Ss(%n*5H?}l$JV85M%s-P+!LWtlcZ>RfE#AEUQBz3%Nsxze`TdHe0dbR@ zpcoyZ{4;9)*iKWRo^HRNK$~O%M2hjGyde^AYbGvDT_~aD$`DEmRWmQK?9sMG{!^ZS@J#WxKoK_ zOPzCheSR1(jhmE10lRD4mTnKkxBg5_x6SXh10)i!Xb{iszUr5W>A@J?TULxzseHqO$#u2KC$G*%iVAweG>?PdFnp`N7k=pwiEu3+nDK;m7vXV zFB9$3_w`|qO7+uR^?u${Ln2Fw!Z(Es)W+Pu4Xe^e0drwJz6;&~u*m!ti{dGW+g_Nd z@axaZJ`n}V3-I7|lHEM0vMg?*U1~+odT)l(#4A>_T#Im@Q1`eTl-FPtNAgHGw>amp zgw`1v5MISfC^m*E?tL(%9%NYkkPi2ccABy!OhJ>%O;Ca#pgfaYI^sV9uh(yB=I47u znj>(^YUq2?xc*Sp4okwC-?dAB;>sx?*6z|xzo6T#hTzCmW08@;uiK2N$xELP5vf^} z^@vu@P2`!m#s8JIChM6sL6xBJ>vcUd?E9Wmcu=A}t>v|Nefr%Wwgq+>9mPt5<+9Sg ziQVNBJbDEhaPyS6 z^D~+B?Oc+A1GNzm1|%vOVD+3zrSWl7IhDqBV8!gb)X%n?Hg~zBG#(}gRVFp21UiE$ zxdGlvTUPJbO&`y}oQ65-u-@y#ro&oUbyA8e(D{!qkdFTieDcL-u~%d956`MEtv%7Q zW<*d39AMgU%A%#x(id1hCR^Cgbke*e@D^k%T}YB^+*FtQHJ1-xPW>Xdyx1|g*}C{u zdB9Lp<;SR+Uz0&!GiJE7iE&>Zu3N%sZE&Ak(sC%{Wy|!qMO%FuFRjTw!RqN>#(ids z6reiKbkwM5%fBo+h0S34;W>|kDT|7jbt4<>LIq|FS-`-@bx2-lf1Y-yI!?y7Y+KgZ ztbetQUx8oD%ix%3>}HG0r(PGr?9H->EzL5F+ZJjr9gECOTEEB_8{|gFrGz;BtEm4= z8p-@YFmwACR8Js}Q?_feniuS#wp7+&Fsxtsg;UJA^Tu{VT?3)o&nk?zSfvB?GElF{ z-i8^CrNOB)xk+!Dldn0+7J(<&;l2W?DHh1AoQG?_blle4Z;Yuhz%^I&QYBV1zbNY- zr6n(FmMUE9YemNwMxrBL?P3sfRT-Jpr+fRao?C&wdXUohxcJ|=lr01e3p4d{Qjljt z#|Eb`?Q!0T0xt3BMoM9Sf409o)r6n} z$)&V(KIvwfk<#$tmcE;Sa|**` zLMc?S;l=j$*C+~?sL3)I_29s3V9OEYI0#u-U682cy^*4O*r9w>q*r+cWa`K^+n~XE z(zBISW2u6muoGzml{C!bWQn5UNlv!m7au`o^Y?t*pmhar%|W`Xh3#r-S@Lt(knp^ zcBW2ghq0)0^DF&^0u>c*-Eb(F1df)}`-0OOP94ZiswLvflwZfrS1?RQ78)R-j`rmK zXMa3(x;J7)KTcK~b>+LC#W&O+D|T#c$Xm#uN{)zNn9!=Wj)8kTC#bFSN)we(B)rnn zml|yP+TjH9j?{qf$40k4)gWDwlGPH%tFfNzU@u;)LLI;5s~5tB@)?tR^I6tcMcja% zZln^0U+-Bgc6~7ZK})b&HylUH-E(V}&0>_1vrOQOP|CVH6R$Q;vQlr?Df2xJGbW7f*U%|aHj4$Nm-atnNZ zW>3ycW7OV6VfZnkk%L_ao4Z+_Yu>6)1!%d}X#08+{dyqJIreQEGi4yH&*pt0%r{`5dnNcID@=$(1M)HM!(5 zHl|&G7Qtvb|Mz4}HEabw{Y|ybJL-qsp%|E9rV*-F$Mxfs1vhkSh=pe7drX01V1$Tx z3CSM45?#16xHoRQxtS6}O0(6pU)v;$`9Tz)%MTRy7*WTAg5v?0y{C#CWO6jiQ~@y# zW?Md{{`&U`SEulyMi`j3x@jB$Mc&U!Ps7 zh=~iYlQAvo3lST%3B;;A~tUv?oujRsXny z-WQ}QZuK(bFjWxU{M!GOPJV5UNwYm1HdEF(F|9dMjp?JQ&*B<%GTk`{qD=p4!_684&8==FwZi&vD;l#HSD!+KQCfHBNm{!^)3HreJsPnd@ zoQZk7R~FcGmyPJN|0)w!-6HFRtR>eqJJfv*oNPmI%M-;K|yM;~v` z)m&KcvxHs}zQ7^(IqtHWzQwOe>glM8rBP>TL@DJd>~fdv5uMQXq_-z)E#GQbeqaxg zni69~keaxdD^pY14sZBmJ_e&{p28u03+F`0n4pCB2bJ|<{+b~T75vb4Q(9z9d#fWD zGk*13tgNv!6~Ep+DENd7%LBa--k8g7uA;3vxTu4Yrc&ktD_sTX(+M)Ry&648c+m~y8##M#1=8k zq9fSp(!cY59cn$pNI$>I_R;eV;W7ydgzAe?&T*E@&%?GHnJ6GSfe81HUY|R(s|^8t z7^P;~_b|GL0L=MM96?GWT)6`iwCpZ24`CCFa-t^%=@h;a#PV_QO~)GKYh1M$YLw42EOU?5#`URVMjOaHYPxF933Fcc^SxF z?1TEu)?DLVL>Sf;PUig*We~8`Gt|JZ_r@sf7F%&YhfA87i1W02-3-<6?oGBoC#tc_ z0qQp;e0lg2iJA8^Qp%I4JYauNAYzz0W;TIWcSfg4a(xJ+-+m2P_>TdDl)bE+bLx-0 z4K(bIV*e{DCMb?6<2=^wb>bU3Qb*-T^t(P7Y(f)1h<=PV)dbdv=1XSze-KSvY$ucJ z7ewv_kaJ(tHF@~Z0Fm(Iet+RR%*hE5weDd&wpA6reis#G32|8BvP=eoROf(rEO1yI z3@ghUGNZe!sd*Jyf)Tg#bwcYHj1dNfar(wy!@PeKtdnIxBRmuVqcIzDvP*$RIr$gz zSNp2F#7>BY;-R!Z<#%DL*Of9z?bQ~14*ojJw$?MPvRkfNQIg1K zvxp%*#m;UjesE4@0eL~ZeXq~XaS%>!48jUgfkLo@axI1wJiKVKgwfgShRvw`u0VP> zx4DwKHf>X}?C;Wt<=HwA_g4wg&a;3Us6iJu^G3c1Qlq;UAY*FkCu5n?qQVyYm2)v8 zzYC-zr#jJ%4_(NZx>Kwe#2+f$48>gmWYuk_t@E48!zX4E6rg=Z>-O!78df%f`iGCm zsW$D2qHsOJ4TN)K>@yFRiM(+w(RF!pTFUL@l?OzMDnewlP}Hocf-A zI^nG{X}4P*x(OE>)%q+TN%eEey|MjkdY`p%(ylVPy9J_FM~EN%iEPTaMkZ)Km@QzyaBPTF#P~Uz0%1aCrFqnf(a%$|RFbfVM zXHv{5oJ=p`wGG^7{l5ao>(Z}#f4!k^tVhAYlE6@ULi6wnOr7rrn+)BCn^zSs`n_Y1 zG254=f6EHUH?sz9LXeMJr|;g~1CYMYqXy+F-pji!4P)R|*!?bh?^vr-ebr%P)KnjO z5doku9NTasvx!+w@>tX1`sxyH#$zOg49m`e*46dAiMc!N?q-b%oT(7vgJFOUh&{wf zE*m58<;ZBA79qcIjPD0bI~s+_MUYm@?jat>O=$ZMLm%~J|0HOK*_E?XOE>kIDSejtJ#o30gF>r{F9Mszy znn6<;-zIVij!l}irI)QW(99;@@)fF1G}O8N0YMy@y#6Q<4rA)14Jy9+!Q}(cp;=8B zMFfkgQd1Hd^oEp-tF}QmCBSq4L`a9@M}8=RVb?|ohGEjgqTW9rj6*7rXcJiChKv6n zNR!k678%~to=FVdH7GrrPeC2tn85iajn`CMD=?Vb_mvv|$nN|6X9nZ;s+z;vl6uw8 zpIdetrj^YRJ=Jycf)hc zv5ryoS1va|C>-Lv-oDu!Za3<&EJIrJr6%lAWbEByDyZ5*=ZO@2JMlyV82v%2rYXO_ z#Z70UUG~^b*z|X^H*haa*O))wU*LbIo!A>nYX1`p^9Vc#YS4&?f-KhHDJyVi9JKH@ zN@$iZcRBudqFg2*(6&SiE>y{~+}il&A_Ga?X2^X1msk-pzH@MhNtVavnmF0LKF)V_ zz7z|;9E_7<>;;k(Ckj1U_XML*%5=diOZE1_?b?$^t2J(!n-EYU7`w&1G4zwMKA5CV zk^)^~LqmtZ(#sieWAgmGpPA=RV{6^dGfQ>UD@2xCvt&-wZXI6vSpU%O9332fDi@lT zpt|4^Dln*J#>6SPn!L_$BZIhbDB72`-CV8McBo6HOw2sOC?wOs-JRU8fAk_ zaAsBMuInYa!tJt4Hf!zPY?vVS4SM(Y8P&$}944vZDvNv>d(cVy;>QfDUyEtqezu?Ppj&S08Hp*Z(O7;T_%zXIw_6;S}CZo z7r^mH^FOZMPZ97cO5yTIZ9{tk@e|pc&f-IfP2sejVF}ASLx@t`Y#oz}2^DLs=5X2& zv4_G=T)`S&3+s=lakE0y0&2-?Hnj`#rBI2jG2bIG)Eyt7(W2Ems+4bIQEeNa^CxqZ z&7LTxw0JAO8D1BR7P=s>?sU>yr4X~3nIUvCS5)3 zWe4t-8;@CBYZ?C8N$ahU<- zv?&2g(NMIL02vPb3M8pstYlEJDUEm>jwSqjj*ym&5odp9_gx>89F@>)#bd!FlDj#u z=%}oaH&yllyr2p38S|)PN7t*&br^UmU5{riR9N`fR28RSxzCxD0T(KUNiO*VZKXi4 zG1hB8l+W{2;Pb=hj}~!{LwxAo-!Gh5Pp6BOpWL+NHkmAtcLu98dJg;jc~TZJa=jG2 z;}HBfLgUSjpxDNLL`7ebG4YvLsf?D2`lf`oVdVzLW;cxRhoqnS0I77OX|S&XhU!{L z;T*qowvXEI>RCaxAhb+p%Jnx*Na^$G#TubmHl+ zNzKMq9h}g%V)US?RgD`Y_PoQmM)gnr%g&fItft9gHxXm=r`jsD2f!Vlr{1MxKNmDU z68j#k!S>HekO^fzB0D$=1v#z~rWV|_jduE!216EMdKT7vVI7PK*cWjoHu7`cgIPLG z4&*HfhxbbI6T~{JqhDGgn-;$4lb_&O|};#=OJ0bf0-5M7hj zYQf)wK5v= zNmQ+x$31N=OMJtobpEd5J!G=RE5&BI=;gC;f6}OH%cJ7E`M5Vkk}cLtsYJ?EF<*A% zhceaCCI@R@hQws>$8Hmf^GapmmxlS2PVNC=sfV_htA4B2D@HhULPP0Ty6Q>Q#D*CX z+W4rK%NXXW{R;GndjM8>@t699ic>&-I_WPnQ>#%QllPX(L{d6~ZKLg_h|+5fDu=mR z0fX7-FXNIXM=y8ZE_U9nlY9982}eoh}u7hdV}C)i8DctWe2doBvolL$xJ#u!x9t zNa|Qn-F^v8{u*6vvD?4UaA_rkNH#bpf6aF7U5rJVtKnxZcci$+95@~%_A|9+@eY)WttK}!ap=zUB;WaKP$L=o>t;zmEWJ9^uGMINWHWq3H{CP zsKBh8EzzNZ0}+*NU;$Qj+%5^uR~hh+>@ddMp_2&tpZ?xU;(TW&4lL3M6`Gy0yUfxLOHRW8_P2;8{(@n)zF^=cgIx=XO7jxwEVk{SjoL zYMDBOgm@z^d*gmhx7yzk{YeWI&u?Z_WWv+8Zryky@$&tT_3NEwzs1+JXz^@F16X>}@)xvBIHjI6SgnQm>S`kY7FHf)i>$VC2zw<0+mlw_hj{gT~AGa>>rrV3Rb2Dm*qw;=nvD7EnE&9(h>!DL_rml?R7En zGGX~N?Yp}L_NI#VRd)2OZ*8I?A5mk8I?AV#U@72Y{R>U$n%%eM$E^hZgjIhYrXZ0i zS!86WzG{`w(Qmjo95%j%ucVtF4Ny3}96oWExwc&@-Az?R20$D!Aw_LT9b>kakDHPmn$z^Z&%Fkl;k(1NTQ z;#C6yi^XXX*ETGkvbL9T+(a&!p>36TA4;>HfeX>ffStCpK z7_j+0VJ5@kf6jE;Vz>hAtb!3)70DO;m#DoS-j|tvBXF6TuWqfiCiWz4-AyUvjH7W00z1QS# zY|TkIo2k@PgK~H=xlk8B?Tf@~=PLg;EnldB?iZ)J73+1eifTDy#%o6TG6DTzW|!i} z3IT7~1?K-eaE8$AXbRoDOZ1F08hwC*d{VX6o*S^abE_@k_p_Xwh*Z1MFRwZ!H)cL`NFK34ab{7`jLF@W@Xk`qmeS6+SXnC`LSGiTxwieZ4jZ?LC^bu z`fo-75A8AOZEa^}`3q&2R5@WMt?^YtMN;fIiE!@g;x^yYWmg*8V(6{{N$zZ*fu0o3 z2uSE9<=>*X<`hoP4#4#4mZ!V{?{k!{>|m~2YAKmMDYKZ(X)n632W-|(jRGajMCd-* z!o5qS+8r`VT_0Qz3kgz`6_t&Mc7~1k5sagtB z4SQZLNVTX}pSiwgA&oSp_x2*>pP~tSnbHhdtvVaHI?Z%mI6_tF!}$4o>a$K2233#f zMFr*#k*hLxxjy7tNqaT4-yef_#J{Y!t&z-JX@^edY13~2w?Q!%pdSNrP=VEkB#*DcKZcrP(Z|~7; zRIw_ag}G@NY{ifYd>DQYF~VFJ2jvI;5$i6g7I--4vABYM4_FYRB`OIW55 zx4go?FsEMd%GtqmQRlKY>mukDirNUg1@FmR3GOn z^}cCQOY4B)?8PEaDE?h>iQO2Au8bf^ zJoc7{F};Enj$QOy{!hfIcW~Z$Pi`S2oJ{s zHe7TIftl(wVaf~CP2b&63)hiT?Wy_# zvc39aHRe(O@VKYWW0P`OJN+Ye$#%s%rwjhiTH3tsb5vQ)EX*6Wls7Kxi(anBl$*K} zJnt-Bidy;^I_Ux{KliAdy5S<1iCyP^BKpa0q-h&^`wS(~G&6Oj$*nVPa<8a@^D+vC zQP{!c#vA^h5yS&S-5>zj!6xjpvIxYc7Je!6A` zMZb%KI40wPQxltQT#g(kHch_UcTDMOKDWWl_p1fWv`C+zveXu6u);U9SKe5Aft2Ul zj9++wHq*nY*?X*b&FPXJ9`}S!@=q??qNIJd28N{yJCs^VXx5ismUm#;tuOHPD*LXV z<^{dC7%1lzlghsWrB&(#rcI0@Nl%by3$zqjjHDlN4RXl5-4S;7XAG@sprH}0!fJ;`zwRt9ecn8Yw&HZ4$4$14C~!BKi+HA{Gc~UKZ7+Tc>j1laxj7#xZ;7U5#369 z5dQOJ_B{&G5cs2GNdxkJ{s|h=|lgNE$x*pj5$Pk+dJTyj$eA%E`Z`(AQGA`!~zCR!in~c8^@s z84X8hSbYVA5FV~_t?KYQvN9CvW1M44Om5F@KJFz>*FD)_(ig$XHSeriZPvX<>wul3Wy=9dy;=~}*Y;;%;|zTWn_ z!|%SogwP0%o@*i-%&lYW0V1EJm$SO%1+S`MsiK zcavH=37(^>bSZ#x^G4;T^z!OXpQ_KUg5kj-H_A451oXQK5zJpAe@-$1x-W5$QhBwc zD^j%73>R|6Bfn^Eu5drm-YbnmJoW*yu=VQ13>+xqk zOLCB9ovh2-1Boc@oQH<%(d?RPQhtlPdB1|iOhQzTV zxt!xai-j}aA%`5L^6W@5Gh95ML-r@v-TX^D?EZw7+8Q*K@86slPEm8;iK=q4G#A#W zGKn$G=^||s_G(4?C9m<0K}SBslX9Eh3P|Io1o17z2Hw_Zulm89z<<-B`^qi;=tt%V z=+pJ(PjRmJ+=(XexrXlrP^DXzA$Vftest~9;-BKA&?^&2Ve}Em8;?hF2i%93WVPS| zBRB*LCJtob;IV@}H=tozzmmX_;eVSAMtsFgFh%X+mu=K$K-PVMTVS-S|fdT_#3L(N@R#@y2IQKh53z_rOWy} zE3{5_AF1%{8nPq*LBa~GALz;{?fF7iH^099lkRA3cw5o`3U z&4vaM0fF^J7T~OPcIfmc&1u;yUS}xAHzTwGVdpW!q5?7itkc=Ep=@@O-Wm?G0rDz? zP={+4>7CRdk7+`I>j`mXBbQ-1*XueJ0R(CQ&im7h0yFLk_bMPx@|k?e-$FGW1cZoD zUyzLbHTsz-BnTvPudh5Pfc5dDVOr|&yxGvCok-EbT<~Dlng2Rs1smo7TidJpz59c= zA7?-r!VaR|7ym5$&KZ?wio$-jO#$j*3^My5vj3Azgyj!9Aa@TC_Ghn^uexNcpV&x1 zAA=xrn;xAGcM{fCr)`(J-cIJ&e$fxx-0Zz!3;-M=CK3@qs5dGg_*+ea`y9NO0HTIY z(B`GtS|8s&&s#7G&8Ulb<%TQFu5g4-{c>$O_QFkE2MalOFGCCKtKG3oE|iM|kEtb1Fd!rjKh0-^p&h=`kC!xeO}QPq7c5F$pjZ2%_7tL;%3cx~1BRWcnHTZ3n=*OSs` z^Lhom{r^muC=PJyd$A>y1up*B;WH@tNgJRDz)3j*HtJW&Kp=}cv{pGZ)C*!23#5pV zYz!QXdI0M1D+}w2 zI?*|&$nu}vPgPf1RF5TYJ8PUbG-#}^$-j*}?;1+RB3dX5_mhWNcDBY1{cmO^VL16s z!itCEk8MQ40gF4nZ%ZSG)q*Y^Z zH?Z)0h;PtxU*B6x_g`R`Y?D0#`+JWP=E_K%YC5n1lv&kULJ0J+rS*ztS5`l#B?!O{ z$NsbYg}#NyW~!ixh^I+~xX=RD!}J68X)TrNAVrn=VP>DR+6v3;FpE?|yCS8poJ0@d zZ)+PQ4T5LY`sysl%tl~?N{U@LYw&r zT`JAIlb~qq^8@i+6-Q=rTg14(sf%b&M<$E#$TF+45vwRNrdlb37cpP3Sy8=APFcU1e7hTf`YOmM3^`1Fo5hkGybPv*L~I1r>ag@S8w-reP6w< zI(5!}{&Tus-@e_|edn2{!ZNP}d+yx13qtR8U3Xp-y&v2LIF-i~z<77=T-6WWra-?i z0aE!xro2#}Kx_uCF`Lam?lZ>tV?Lb$nBIWV`VvElj*gqOIU|x$(Us9%(3Gk1`BX#S z+LU!2)y9l`gW9l}s$^%w!9Ln@l6>tD-BDOz(T!oPh$ijd7s49m*MVhNcX5KQ?8# zz73q@X?Y=M1Obhi@(lA-;Q&*~=zq)T54xO#WDo-jSO=j&V`;G-GH86@2@Re38=m9E z^<)U041f-Xc5aptt2a!qhEdWD(vcW(&TKM;H(51oib}5QdD54dK>zZ=j#41DErF+n zor=1hQna4s>dMrXur+OHwmd>Y@@5W(^c4<~nT+~wB~aTCP{ZZ{qaUYB1TE#PI3C7P ztpCYHoe){6O~~AkVvF^_cdC}*rCo;5dtK?e^eP_%iPJ-fgxHwD1Wy%muE0Wey=FfN z_Hz`LbgO>|No_KRpb*mJNV9tfK^!V}9;!&0O3Mu{45dU{q24Ply;5TunJryFn%9)p7x{@#&I|ca8&aS4BhuNT4AF*mNcL6tY$R zLU0lr06b10REmI%TV(!TBDIIrD#}u7lhISgw9O0%I=XGz-dtdoQPD8uS2#4I!lcPN z?32@Qg_B`aprh=uz1eG~DZlAewkQDOU=1fIcm*xO(UeY8hHcntys}BazzW*nUS-Jw zOF!|-Itv8X_$7GBah!w-FUBEH$BTsvOu8EWs=}KOf^AhN*47CA6{8>OCUZ)V%Xo^q zJe)lh>LIorw+9D4XwXu=GEl0q0WNn~_}ob}a_1^g-V*X_Xs}Hs(sXN6ND;VTZ|!2) zy@R7x1UGRZY=jN@PO-e^=6DD&$kFM+{6gFLFkegW0q^;^kc>`x5&B2c3oy>ma0-7h z)@(UDzgM-(U6BmfmF}7<;Y+O3#nD|gcL{j4^I4V4E0;xXK-bQ

Ze=h#d{4~bitD_2ZtrYQKoAETS=!z*JX^+L7>i0NsJE?2wxvH?YX{}IDiH>q;v-y zSSm|ypF75FL-(ZvKeH(ml2f+R;>?-?h3#jNP3{`|^sVCnI7fk5m5c%C zPf<2%Yp7Ve&`++#lbuybGN2q|TWI%bc1cs>OX=vgO2%ym{}kpR0VtVpZY%ZN9fczH za7+Jp@1$V!!F+?<_A0Pe)eFH(|3F(d=TRfRdv35{fyOPH zb?ZPNVI2?cUj@Qs%rwk%lK}`;(uCQFGN!T)u#VO7s4cT}Yw4JYrY=DHGPk*Z)WA!+ zek;F*fxAZLJ0Aug_CvTefU&CKBzney|By*MmJ@xtWIik0VcSQIWV})dal8Al5s<#t zAbtoDzt9jy$$A(?-iqUwoU71)Y0`#|e9$6(`e|-Llenq*x1C8mjgnSoE^dxh-G@)L zoQfq){s(7=P~H#yA68AO48A@KRL1FS@U(P*{i;;PVFcS_b=>Vd#)SPk_SR9m4h z9lO-Srkt0-6fXx8-x>*|D}76rK%S1-HCDpD64TZtoThN(NM|7Nw?@Vch8r9UgApPb zBF~2llKow{qh+6Tf08E4@~DTPx~_Zw7P!tQmtj9z1qr!}lFgKDie>^B$#ZoKR_y=@k9PI?^)fscC_KP$x8p`F5Dl92nh5Gx?~`VYq6-m&mojf22f zW`cjLYSQpIxN@xdFLX1mYL3zI5$LD1U{&*i=#DIaaG1F~ni808QSY`G!Cj&S~UkRz{mnfqf){f49%B(Qyzyi6O1l4+e7s z=7S7wP894QH3Z-mIZ#}BD2rQ(J&4}NkWC(|FY6GvgO`XfJ_e$)e#jnROAP?EMhxs| z7~n#pEn9ER{Vhw=Dnhlz72C^;ao8c=gr_vkJRN>1)%5N|N_p#UcX z#6vkU-#vUPa&W2BFxDU(eV*Cl!ROdgUYt)u_Hijzh#q|X)bK~$KZRh4ZQ$USjMEpz z03{R|zouyA67V8ZIQ)X?l=>p$qDsK!z5?G=6em=l3sjed;uf`oPxb@6D2`KK4@_&T zwdYRTScCBE{PGjaj|2x?l2_+zxlqkTCH77og=B2Eb{bVM2><6A95USsTzVlh1SUFL zc?~%Q*e@}Gk!elg^y`piSY$ir*WsV@k)<){eTUPv%3$`l15>SGHK=(2lnz2Y5p|uK zU9;}M<4shvJiscOLRg(_T2kNC>-*UZAVq&*@}?ey%qpuM4A>7QHQt6TIO-27+>d@U zU$vQJfXm>;6KD?#qncc-;VwY6W@ZoA+Z$hI1FKmGdfee9n@1>dmsTmXQcn@aij{~+ zN-Te6aKLjN8&|?r*HUaRjd`ey^N6;x51@z+OF+%E*5Pz!UgP*6>Sajoa4+m1p`F@HsQAx16qUW!138uRP#0;2-4J<2 z67QsJ7AW)x;`AX(K|P@$X?qq(GN)SG&Fy+JQlS@Q&w1~X%dSN>_`#71>2@0$iQ|?# zTkarb61?g?8sG8Kpf1ID3C2k1AVHHXNqQ^4gkQNzcjrXTd*TZOOIVj^JfQR_{s zBFrQ_cPOjMcjLGSeqkm7bgZqcz#qMV!Ys#B=FkBg?E}i;BQu1kxev0%@Ih8}(sQ#q z<_B~pNJppE4^1SSUW;L#HT%NF)w^^Eq3LI`Vd7!^z6I?3uiGb+Rs#&(J z%%KO^Btm_UNq2@3%Ty-7M&D)+KHL?>AJvi7%0Dy_93^*>5zKPLY+$2@L>1^jxN`Ob)>X z7FdlsjGf8?A?WUzfyq6eMa zd9~0^sqLd0+BWzwrD0Upw9JyAQ#PHY1=kcycZ?35X`6s)f4z)S$xgHx4s!p?aJd3A zl)h=!Q67olggf-z9RW8k1d`33NyPGEnR%x8%ozRv$}LPfJO(yl#G2vUv5s2?5sNp6 zb3Z2xkgdSjG;;rw;gNj0Z)8q2>a)s$LJpsi?HmZ7GXpmFe#RSficJWZz)2K!-G{}8 zDW)IAi&jkVw7*C+2O&Tp@y`sg=#P3ZJ~&abZagFo&IS&?!Z?W@8|T|9V+fImo?wnz zEPgWLs18%GjDv~J2g>*g{?LT~TNuZ;<20~}=W3doS(`C2UdPC)6(QN|yFse*3V-zW zHfO2OxBAT>-T#SI`D1b6nfsZS%3fjve^=?za&4Aq1R;Da8q;6lLkgU4jW`xGW5J=M z%11gX|20B09@R%&w0P+Es;{=l!@a6qWLr4l0Oy_}*rABi0Nog0+XLK=n;_|%Fvj%s z#?p-3DJqn3IQVx4Z4L-s%E)7iN?(|YK!!VHJ{bYm4uOPoWjVV=oDn$Pk#nre;&^hS z=>D{Jv~Rc>?{M&d=0r8eGD;P7;Osrhp=J9{MXocj@cm)Ve?}=r2Tqo&#gT<9e6x4g zHBMs|)97OOa4(1XNmM5uFfF-U^9GN3v|%`3mLmX}Xce3HLlZ!|gKbU^ zAC!AUi=sSGwI5y@Kg3O!qQ^9mYKlJCbBR>e+V(uHt(u=yjh1X*tdj?lKArKmA|@v% z&!{>R4uJDB+Gz(4Pv_(f%Idm}r-#TLQp4XyjbzV<%9S;BuXVLKBARUfx_Ib*H2-=t zj0+H+)KSv*v%14N+wgCFopqf&bYI}KFO#FZlN9GAX~sh9;4-Y}E{0}ONfQ)b2XJmJjNxoq(4B3_YVZ2;>AN1@=!GFI zTZ?OLuK9~LB%33alhGb=l-lkU=7<>raHPjtxFvR9H&h$zf}isd$Ap+8*~w62>>Z9l zj6O&gb*MBl1Wvz8l4kjnkiyu_mT@KiOe5?&=u{=lwp9t=-KL=A9gMwp%E;B2%9mw3 zaoTE8(8aTAkDx;ik*GcNWLes~4nl&$EQ^vZzGPs~HwGC%f@bJRvb6^W)PT|gHbp~z zPsVV>JIKwKjQrTT`FA!#^CFuzBmc-K=NkD~5|z85&7{iy#gb+^w@{Gv&mv9FtQLXE8Dvz@%FV z^fxRi}-9-pN_g+-GHQJXx1LGOM zg!n>%NklKTTdnTg!RMz?-xBhC4tnpZn`7^z>nz?)Pi7NfT+f}Tue8Ng1bFLd1db7?~8tbo*`U*V-zn~AV>2Yw}))z=ReooU|d;b+@ z06UuAJkGrv+MFZTS4<@;Jjkz$D!H`yYv}d&KB8v7C1BXG|9~nfXS9TJAsPsb-eUi} zAi&3<)4J#63kBONXET5u`mcf=Pb&YCwd__8{OP;JgA|CTyoT{ryA@r}mdyZmVg>e)Pr`k zFB|Ga3`20(d4J>Bf%?!$El5J(AJl_)wC~4Qqd!_R4D+y(7_ejLnMFzYWhDe!4vNIA zjw<AqK6$qPoPW6_eU!;*=Ug zAKD1P)G0X7^PN*smq2aoZX$fsk2&3gDk-g7WY*+9tkpO64*j0fA0>MUI=j?L4$k0{ z)|gA~EItjre{6u?W$-I0oxb^1cV46T!(Le)^+mznnFE~}QJe}v;LrP0P7dBb6uOC` z1|BCnxadRYMRC}J_%nd4&p@S#>npE7p|+*2@HGXM`|(U4Pjmbc2p0BdB8~=pec2>n z>C;WK#!ju`MB8!{Bv^V)xAp}^;6^L;VwH32+!Y|bvyeF5Jge*()H-8soi8NzDB(_^ zUvH`PNCSU#2`+Z2;?)w?{R;B*fV1S2aj5V9S`$>|01|(JaQ0kSB@Y`mxUDDTS43?+ zo4=~$Ah$9qo!UvtHdXN$8C+zUF0K7ul5ObZe=4M=Ou_eJLXJh$maK_>#tjHAib|(= zl5#-CxbMg_fb7yu3A%(PDW8`kSEC7%F}`4`Sm_N|jTMlfm6*3FGM??pjS=mtV-o;jxR=rRi2|5_rxm1v$m!PvEUN(7`K({WHv51cDkBC(Y3OS}F z4w6$qT37!J_TloS97Z;7%>+kc=q}!gg80UuvkVgdv_Q8`74Z)v2}nI4(5X!Yxu!*G zl2gIOq4zlU<)*cf>w+UBdTY`L1}%W5W_S< z91<0}o7kFDM{eGLAFbq^i7F}o&0!3+3|aXrRLN~&N?`3vNkftkp0v(7MtL~Ie-kzc z_6A|VbP2W9|FqHahd}ocCWX|tisrZmAn<*nKx{VE8)~2$%>{xu+ZKo+r(cI#BAVki z0wKU-jG%2@y2-O<8)I;B0_We_0xBT?iOWYD#}J$J&0(}(*J@)7r8yz6p9yy|-SVDN z+F=6#1!8oi;+O`gmv)JOihMGEsI)^NK;`E}2z(Oio#69P0Vle_u^g_u{z;(QMwLe+ zkeU?%qjm`FvoqjSdP+$@Jn*GDNLD(*5d319@x74phlGa9jyN(N=??WO&rh;J!W zx@|8hSGPYRgCU~&h$OO9=WxTkvt7iqMS-|&s&u=%^98}tWz+j?K^pRh&|k0z!=*wv()Je#$Fb4(71 ziSF=~DR;!=(-tfw;`xHAqUglDv7x~vKfxSu@Yf4`mk{c-eObCf!{!R8tQ8TqmN;p-GMqupc_vG4nK)1 zEhokE+Og>li&3RzM+ekM3?Wg|P%m{P>`IKSI}*uo z1c@A6)nKi(E;=G%2Zf0oZHP*zx{@*rN|H;}6I@_$xCA-XxeMEQC#?Gx@-aUu z{glb;sJ`+V6plun+-Ghg1IWiFzQk$c^vY-1uX#Z649(Ejq#Zcax85gG?r$L%G_kMs zCCxE@3C4nNzWEt;O9Q#s(~&D~=>5(JVR0H~<&b^a2{=N7$kD2(k|VYwoyibAlRDf_ zpBI=H$c1#dt;*}>EIdY!QX0Z7y~3*-i`3bO;|h_B`-ORvsQo-HyY8YPSw$9TsobuU zi5Swg)kuMD_&3;$_wIL)Gy3uvv(Vdf`+^K0sY?eWmL76XiaOsrRtXAhXBW^NcGbrt z2iQ;WG@)3W^$eOt7wK()e~LW`g4P1im&B0U>a-%PFUSCP0xbbPE@CoHh=|o`D9lfK zI7S_ai^TGYL>T}dKn*E$opSLa9*12Q`JhXKWy@j1o~I)5A(?vzCUpD^1ID!GHna@Q z6Y)io?$Sjfr=o^jDx^z<{Uui;xyZ?FsG(&(I*BiGLEUsj4~a^i<}qlGMi;rEONVq+ z=dQ5a4f!`vmmiI66ps?QIRrJd%uGDOnpO(F5sCu4M^G0iPQSP4GhojE=F~PN<|LWY z<8k8!o$r(cqxArbD7=2#XP`_5FqgJ1IUmWK9;qBJ=+KX@mc0u{Upnc5(!TT=2+jcJ z(DzWwmWy%(fVgv6)YSgh*!Ih2a~bXht_)z#ybrbPL6)ZAi>UnSLJWMCG$NJjfYZqD zt-BK0kF_fUm?K-Gz7%QB(W=5_oe@IeP^FKl6(#u_80?2y&uaj>IR}P{HTE?$mn{_$u{gloC%_F)=MMqFNaMktj#*^^18J0>sj4fN76I@wfqJJIj zZ>oO3?K9AD2A+WbZ85P2s|Ia+L=#*YW1`by^0QD^Q?h>BXQ0LmoC#kCVq(82^;zhP zAAoN}T^*JFG2VxIrPNWc*JmIg1GGx>Xw)e*=TP=R6;E#RSLg^%2DXBu`_dTOEv+-K z?XQK~lGV$(4A7eTD^Slty&4m_=o)YivzPT5814-G8G`IQ;HEgOj1ggN=cK(LFMx4ai|E4sv&5Sa(k5B?AM?YEKu( zkP61Pv(I+>6^b0^HEt6WN?o{Q%GCOU@d-<(v~Egjce;7wMBmkfr8*O)Bq@reI8IvR za`TK+kdDX34Kobd-tT<3v-bI&>CbJ-_k7>`wfNq?=XdUZ-udqHhdnwG7fNfi`<U$88!CCBewMgttp#B%joT({NAO7nI?C-j|>_yhO zM@ssi4y~{(dzzSbcKd#&r4@V4BhR@^o@cO7R_1X0k&pbYKhuL3PP{N@oza91onBLg z=W)4C{v7{srLDuAi2jXY#}Ca>XW&Rv(8&AsC{C?ZHD{M=WK4m|MK`G+8^Hx;VNZNQ zglf|95(;`y?5(5{ik=Lt2OpXOKqDe zeWzSDC%0|ylm1Bu?w0bNJu1yBu%=A#W~WpC5q7UxyAQGNe7fuT8Kw9=vmL+oukCS4 z{wn4nZGHW^{QmH&DBd@meYcKGNcd86bc4D@maucv#ml0H=RH{A%fspBAI?+VwAjp0 zMZz}L5UTKxmiYg-x0=4PW*5ahKhTgHQIqrDR6w}wqsXUnep7+o>XkcB+Rl;cIH&A; zmv`smxy%;}luY(=eq1duKUaq1;!K5_Os8{GKZ-nm5WlgeRH0ClW7(b)m8Whlm#n#? zmvtiMxy~Q;dnwbh73-&Ge~>>Xs9ZQ-dRN=jt=Tpc+V6HXv+-)beqQ_FfVrB_3-zCC z^S%CDQTOKkoIPWE(zNuaUWUa&mD*{QVe3SU)hAL*=+DYCH5vKc{Sn)ed~c`gKAdsi zea7DM7Pp)f_Gz_!w@S|}*imfvTymAT`t9bgTeIDHw?;ns##_25@rXp-iib;TgWTIK z^OuXI+nXh@zh}F0`_%G4i61)?bBnLFl&;Fnnpw}g`{XR^66t{Ii-FrOxvqJozI^N1 z3MQrBqMt0+tb1(P^?L8|oY^-_SFAr;b#0mUXY+*V75=FcWe)F(>blj#8y{^t@$xl? zNrzhVRIfFg)y~|{zWa`J*Zs$3CN@sFp*DiYbN8-El>fCf!utpz6U&YZa=BkQMP=?Y$W#UnDXUpDU;j06#}m_ zck)H#{fOTAuty@K*0uUg1wedQU`gc6OS%n(P7B1R7@k)0;16hwA1 zsK|E3NQDY?#V}0bbJgqB;&9bt@N8F_?k3uzB;K&Zd7}4XE~kmy4wn|5SQ^N>@C2*E p%YY}BRx|}X84%2Q9AFv7;OXk;vd$@?2>=j_MMnSt literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/illustration_sim_absent.png b/selfdrive/assets/offroad/illustration_sim_absent.png new file mode 100644 index 0000000000000000000000000000000000000000..554097409bc0a54f27a8d4d3a284699abcec2e3d GIT binary patch literal 6608 zcmZvhWmpuzyY_b%78WE{y4j^c8l{$4nx#WZT1n|nVOfw+IuwxZkQ7m1Nu{M*B&1Wi zBs~1j`{h07Iv?h`=XvJ2X0G|o-1B8(bhK263F!y{001#cRZ;I=^Y7a=1P=fJ`Y3#_ zyAOa~dMfgO>S2a$0D$%lN>T2qKX54&XBKyLu8YZVnZ24=&9y9Fat129JJM9Vip zlqy_Y9=b2eYiRO0>gvm$;%Mr3Co0nm#5hj)DZY4_Qc|VW1WDaSmWB7>J9AC~fpTlY z!#X;6cIg4v{|-J)XZW0(1m*fHy#JJ&CS||hdLEc__Hik2xXqI4Tx480S!fp#(9_k` zh0~@cviq%c!rqXuT!%)qC3ZWmI#TDNu(A1dYqG9D$>{Au{cp9xX84-vpxS!Cq{Ixb z`twvg>n%c;bYkRU4VmTL{GO3>1^LV>;DpV`}w&< zDZIq9X)rjgG)PnXtig%Zuu#Y1_lmATHbLR3Vvs?x)gyrmt1d3e0ZM0OyEFrmN#5?} zb#mpgv+m}B>Oqd!W}cx6PG$Rt$CmsWw;4m@>9bk2!gmJLtU;^1N?sDv)arq4#_-o4 z(;9%LT0ysTxAZOx(OfMa*wzF=;rxNL8-FKSgjES&=zaEY7ExW^DCCuQ?6U zSEh}0r%#@r|9CmNhtUnF5z6)>Bl%TnN>jsNj0U?Yoi7FEJ28d#eU2lU#L4mLUqFws zA-3RLei?LKeC&?K3(dQhs`Iq6Mw&@Sr+vHlEZ4tEKoO1!i(b4g zcr^XQk7qUimD2S*>|Fny3&QA6>h|8G$2${RO1~F(0e$W1>tPc_;ZCsjczE#Wlrpg9 zjg>)DL~I`TGDe@Zc^q%du& z;+>S+nUVhN`YS}0vaF^oKiq}=tI>p%RGl|`~7%9oS8`eAn=La`Uqc*984U1A*X8H7$n`eV{u$0h!_So08LaH&ZLi)qPGkh1q@&U7K zn^r^7AO<@l&MGmoS=G*Eyi~Wx?~eG{Pj0?iG*InZR@hf~?z5d#NGdfsY3m%UmgMtD zr&`)ie|TbU8x?3aJplcn<&xWk!T!U|~(R*6f|?DriS|Rj9Ca>zKc5+5h(hG)*S5vX# zH1u?7xJURV#1gWNKz-(Os-b|=?TXNsFE<-RWVEQ-3?#~kH~PjlB&l1fBvd!evYe;n z*4LtTRU7~0dDb8E7;!Q@)v~Z=oukE1OVO`{Ng6jXHJovI%@vAXn|r!z&oDMz83h$) z8su+x@e|j5K3K`4e5;ZVJw@AA@!(b&OA$UIcrN1K5S2|~pj}H_?hQ>7sO4Vc!Xc9U zGG`Ywy*~Rb|NG!G3DRZD&Z{uD*{sz?jnz#n=lG{-W1Y?L>T#zAGltl1KHS$P3#XY1(QoP@hsh`E4;%)gM}7 z=*F#~1n(iCIZSdYnaJMDE9j_%fkn>*!4_Z%^&^TOH2$N~l%8TXVnyoPLgFXA@9sGH z#u@oZbj4R+m~*!;7fvXfUtTG#@3Kq$G-_1o4ao9vQRJ@nsakp+cz8v(esQh;x6nCK zPGeg&rEzq7(4aR|R;gtU)^(UHnj>zhHsXm*X(T%-$=s6d{1k(2YFeOlbplk8^|VCli8l6R|#`=XG9pCM&vT$eFK z=y3@_-tt#e=S>bKpiaA`33kpxHkb!EmH~U=SluZF1WX0OCqS4L+*<|>Ay&B7~|M$N~VFsp|aC8Uh;GEx<n$Ku$~uCp72gZ$_22mw{Omt4un^4M@a0=^W{whX$sVd;i-I=1n5#3PbBzU9bV*p7rjtLq zzy0!#&Q(Je4`25i2wUSxCm8Uk{|!xg_-ls_EUFVrb_IkB;**Y{ubzNYlKR~osZIg| z%=r=X?2_o-zBT+M0Uo}JEXru#$FjdmI`)vi#N4YMxtf zA*ad;&CkCp^riyg0*i%pK7xINxHa-Qn6FDMm;pxhSS)L*_6MN*+qa=sI$6I-Be%x; zurp&&g}dRC;hvUI&=~z(1Lpq&3i`4X%JjS#GIF%2{-3=_wIAchgYT26!?~D z*srznqCSa z9S;v5!`z}l+J*D)5egLk*Li8BcJdVdwl)(dX;ARuf{ix4d!w2iVn}+&_|(4%yBBP|@LqVIIw9kVi>FkQcw~?C zW?gf8RfKD!e%7)65ET74moN3XsjD%wjD47K?I94;9DI9iPJAJY@;VG6wecf+F#y>M zXn*%QVOHkdcua}2^^1Cti$`Iu7Ovi6CCD)ZEQSSipE#kj^$45a}$u}=|u{P#K#U?&> zd{M+TGnBPsk{|L1t$aCc+#=d8l-U}pw07WRp#!SsiaJ> z-=Gzzq*fY`E+83324i}&_YW|(J8cIvUZ%eVtn3PXmWAD==$auiUWk=6b~5qaXkPla zROXU}vFk;5A=H#Ue*)D~jqJTPx$7b^70H>(*f%GAX#J_cr9C5|@0XTUXJfP8{hk|_nyK4ey{)5A#A|q1Sw(UMs zl5&85ANvw3mdTp12u^0m>|BA?p6G{+Yb0~zk(8b~yTmtN$cGr3mTx{7YsWFmpg1#o zl=5IF=Z}7S0`FKm!u;BJ(yQvDb>3ZN;``GZsr9WHx?^PKRVVWN17+)<@tNAPvhnWb zk0TO)Jq06}WoA;z7_TacS@Q`)%@EuS2TzZ|}?pQP)w zHWijKYRdvc9xwzy)AZx`w#sQjb3{~W?WM7&DgPIF@NDh%n z#Ldf>^9}edApqU>%SI0pd(XLukxE#^<;J8-N6AJ0FB5l`T}gHy&ZCQ4%ULY`G1KYA z?Bw~YFI~YI#O)*rc1Q9@oPx z(XBZ4k{S-^Ui^==F%g&1O;R>LF9aCIl}o(=`$FR0oHl&09Gcx<%K$PO*c}ZmGgmM^ z?2c|wegXz0qk_rA>>(1D0N)LGAE3g)s>bL`a+@#m!+76Qj5j{u5hvCHj!OGnBM*}| z`gu=K;rRCzeFA1T2%FCWia=G2D*BSQo){{>W9oH&`xFAu5XBY*LEUY)8K>P9!7lTG=(^?Av4PGAnl<48IJxXw1_FJ!VfVZ-3 z4HsbFEK41nC&Ck?1a#P3G2;Pb>&`tQL?Wm+^?+Nk0~We~pH1TL36b_s&)Y&p*Um7T@7{2DtgK}u$YS2#A<^ar@rtZE_b^TGI_?6;1OOlPf?Xhe<=EmNiQo+E z+t@@xf3wH&$l(Y!#Xr~i7YT_t3a3h?7r4H8_?z%DCI>7hkxU zT_;0auSqI%ybmoUwN^yLMzUQNa1SQ{zbklka&?NyhNTp8nuP0O1bP#PYKDsblWPwf zR~#w8=wfPO;B;E_7XQg*bvP83e!lO`^du5}(KHpL8d;`MU5rSH4{mj6#N}KhT+I!; zF>F-cSUMcsS}}snyujuhyzqO7f8Ay{K%4F9i{}z-@ul$iL()kM_QY*ecaEDG)FYT}3z6k8bS#;t-;)G{|h~fvU0KWW+Q^I5Q>n=IO zkdza&E9B^R&{W=uSMw|29HngM1#4pK8xetGi)qTGiW{9aDw97jtkIKm2G6-Y!#LFf zPr;3nz=Y>*^jG*~8CtH&SH?C?;W}=S?MYbb=e5ZI<#WPlyAi9K)`0;&KCS}o+cgsT zg=szYSB&1D(EsEh;fXPFSNP^YJ^!K*Hb{#w5AAJ-@drN{53g5BJsVjX7d(*P9~XOt zZvPy6+qYj3I=q+nrx;SK-pyj+P$=%gIh(k8lK*>;Q{EWa?th~?7oZSLOwBmku64bm z*FGe9c*4>*IAFbSt62N*0~b_nMhb)o?EeE<4- z!V{o8rj}qp+7TzrpEN>Xzyc=#c>J2<{-|p?f#XFVAm0zUTvnIuL*OE@H> z&TB=3DHoazeB$s0P!m8@)%ufjUuVKQ!Mqp+;%w5+o{_k#)D$;u$B*HS{xV720YBKp z#E(S=5Adzi$Wrb^l})@)pj-M-nS`M(>j1&;rrmVslEzmb{MEmGf?Y>^qdyrwGse_< zDF{nNu|cB5HnMl?aIH5ZZTv}4P!hKvh?!LxM#dADd5J~Q4!1uRZ&(kG5UB_;HLpK9 zxtK#{L8^b5?o#|wd@`5c9-OrkHvw77!Jt=!U3|u-E~?!SrzsKrIWmL?u1&6Be69m0 z3?`QjC`gZHg~`$MYB!KW6JZ(vU5)P#6JfEdoIeR5r`ubX3=Cr>HxpSdho%qau^u8E zRdKpZ^{&hqcWJyW9*CuYMt>4NMpw=G=K~zEZaUh`kj-%DCLXmA7X`{o4Yt1FqV*8< z#gn{`F+x_KQJmjT<$H)PD3ItZy~GKMSX)gU-svMFS`rj(!v?#)ynbFo3!?ev73ZPh z8MjdT{-S$ZF``G5j`+9)h>~VO*R}kjX^$&66La1mm6wde8`5Un`!1E>%kGm7=!JCE zjc;q~HCM(7=Ux_&$176ni9T(7eSZ0_bVTk)p{EQ!7JRH99nwgdl1#_e;YZm<;3>TJ zS-C~Z@2@@NtpJ@Zii0-zr%s_<8NDqDvzAiNW^_QZA7w;>S7v9735xikRqa0duxC*- z(T(MhNim1dhXwNKOpE9OgQksW(jL2i^Tp@*fdpN?SL(a>aJj5UCGVr@C?rE7ES1I~ z8;xtds{kWu@UofH|n;HW3jZ4I^8Ym2KSh2cy(wf=2ltT zkoC}CImhkslkk1YALRV--o*tXa<2>$<(f;-2`h{P5#qH*g3ESw#*?v0Ku;h~8C*%p zj`x!T9fUQSlw9NWuSO$oL~@IMtz;g{cAOGCS-Sc-22*@-08V11q{JjItJAP74mLf0lc(ZJBU1#3uTNYwRf8RR%<47gr3^0fb{gjcgLa-Fsb4bE!HARgtnQRc# z?xo;W$ahYdrPAORg>&R$J|;M&>0!^%axz*a)-A5Eg@X_KO ztqM%05aWS^T_QHA!g$zLFRDT}SmwQ2Am2A(mMUVR<<(hHR%_fjYxngM<5$Ab$TgH3 z6IPJ%EmF$mamF7bj3DD+)8`0eFk$wDST38aRT3;~eiXGR)K>j^J5l%De^;p2QK%v@ zg3zq8;(NoU#}^wDvfUdOqBS{wZ&;09Jzg+bB8&)^^W`=~6W8TjgF`ru6yR6&!%Y{9hC6a@ntPY`^ zwj-4NkwWM_La?necvVboIN?zL={$Q!-71anwh-eG`{mFb0m04N%l$ZY*aK+W?Y5y* z?_XX|6eB0PE{N3(3+>Vr68lCk=!=?;sFhy)Xiq9HZo$^je~_LoFk=ln-dzcPL=mp9 zH;5~!Ow?EiFO{c3OS*K@xJ-+19~)wH5b-^v-%e>0odsscTu@9(%LERg%$;9Y2h?7B zR>~RwPN5);{f~=DHSi)0o9X56w;YkV#m0V5nxd5E0sNk{yry^ZJzCgBZpSet` zZ{eIBml(le?`NjS&RjN5U9vK?WSZc3NZ|7L5 zFHaX0S6-w~ZDt0zNE9O#lD@ literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/illustration_sim_present.png b/selfdrive/assets/offroad/illustration_sim_present.png new file mode 100644 index 0000000000000000000000000000000000000000..0856795f019ffc9bb188ea0899246da6f4c903bc GIT binary patch literal 6331 zcmcI}Wl$T?vu_eCXcH(9tXOGqDGtT0xVu}C;;tn?fItaFiWVtQpg0t#I01?~MM{w( z#jQAn+yC5oAKsfcb3fe=J3BjjerL~|v-{gQv$0wlO2h=z1ONblSox*A&Oe?1Pj11u z007We4paNj0D9{v$pWgzXmdWJKHt|NlLSX=zb6Cvr=K> zGmIn?&!0f1vC88!q#{?DO&WMY9qE%*LLI3aw3q62Ok-6lXRKaEWMKj$6Cbm3O(0sD ziNQmouy|V+ZyU0gwV^fdZXd=o8zh1+vKIEl(%U;(D%)SpZJMs!R6dwpjO;IvDRa}x ze5+jKws^tESKHS(IdOBmQ;?r(#y)Y39YfRvcLcn>O{8^qR%;mku6aNnZ^F+-UEDqx z!sC3Mi}yr>Qorofmks^+tU>W@YIG$fF=b|P`&6&3)bahs@?X3uJ*sxEgCb{727TCk zcSQIUXW@{vF-@wav);*zt&FHa_lmD(v%)H>Xp7+4))~ZeH#@F!y&*jZdEZYQ!~C<< zvx3xV>B5U}Hhta^>Dsn=H-uBI>?C3^D6ixhvD)q*swlS-b!y`BX$K!8`)MyeXO*G0 zTwXy3dy_hMo<7C-vML3y`|1v|w5Cm0PH)F&eQSHh&QEU)r?$}d)Fw6_?f#+H z@$&c{?qEp>jMyt;Y1@diu+(l|S6e8w-LxXaV3yckYk_cU4MrWJh;DIr?^VMymq6$A z>JEMUbdNoy+%4aHcys%LRYK@;wk#0G_JhofALQCJF$w#0UoL` z=9^#_sN4G70q)yxvl%GvR43Cy(zB%eJ;8O6>L|h`{$_^jNqLOxa^B_6NRjJgcP??z zqN&qb4{vg%XNy;FH)}C8lCINw&js_LQt6%I;*R1)eFNWH+?vkrPhx+|pE}uK8c2ka z(Jrq+g?#YY)z$rj-fY(&gKc&8q>kv6%(_K%y{iU$O=zjeLQJo15!q7?p69l&ZzJ#k z<;C{5sv9w#n04^C2dE^=2^vR#xYl25p=@$~OCP%H(Fx40+M4Eak4d+>wd&3Z34Igr)7nOjPWE+Cx~Bg3 zirn=tJDkJc$I|6q?NA9`%8*>NWj!8uv6FI))fKlbqEUu6**i4O`sYhk@}$xzk7_vM z6`h-y*5#{tPEdxh$?QkYF}(TF6d4jcU)Om%lwR3vtH$UER5jHHJJ%Z7rIBK+J))v=Ao_;8@$bb@ zLwOT|s3bg?k6YcC-%cO1fnsmbOUWpaV;8Jptf6bn=&T+nxWfGdS ze-yZ}qdxKgS1x8&Q|6bmcVDym+>VsMr_IbyJEnbYvtXnl*&MZwWW0P z&a}_wudIYnc)F#J%omqIo9|m#2Tzu!f_>Nj@&0o=ZxUWYP;DhdUD*Cm%Jx7GtAm_SGOV&!Qb`ph}R5l5OlHlPVq^!vN-5g8mo?$J^MTnrAN9xs6&YxSl z$F5J<|xr;U! zC7QAF%}OV;Eh43={IpC@qmj@D@NQ@$rL)tRmED{i6(q2f9NB> zC@(=-ZWitsrD|!+u-js^Ng&T*b~6Oh9`9o}WH4EqGNeESaT~ONwBPMTev|ynLp|af z-b}N?QG%zARwU{7qfq=pyOQ6)(=myjy55oyTLMJ3se6Du;Wk$#8CLbh(wjMn=M7YV zJpLU@qA8BMF^IYt)wvi!!SL3LU6+ahIHWR(SO|iORIBjDE)e|EjSKQjjP*^Bu2&SA zM?m}^y;4oU314mt%*o|o`dg;ZTU)JS@j_ExDmvZ;sU;RbxIOE>< zeM{?9;o5Y=d737s!;3@tJJJq{3yBFqKiF#*IKIv*kukJ*& ztRDHTPLG^jKu5JzyaDgUEL%9U(uD~z4Z8nHF6b4p_9~l?lCCWZbi`V}KBa{MRij)y z+8-Bm(IEBH_yO9hsrl^VN0BIU+!9^#`e5u6UgCPzWBfT`$T*wQswL=lhfO0$8|bi< z3ZLmaoVXJI_BB6arRQ7@w%B9zCOq=*itESG;)E{dCY)n`ZVKte1_OrD0Uy@ngZv{0 zkDYYRiYlGL`$BHIhL6NiqzbVH1W2+FlWu|_!qrW4aGCsZjjq+e8r05%#m`th(0+jv zFADYtZtv~wJvg?^FBHjFCN3(PRAKa{K-;`mg-t$tJ%EsvwW}oedc|%$ez}Oh7Z`*4 z%`H-zh#=8|%ealzICwCoSp;IST+1JL5mhcwv}MARW;W-MXe$^3-WJ#lbi}N#aV(%5vC8uZ`Xz4w|M4 zUJ>bp@r&|B-e=IxA>zFt$CiDp7^bo+20-~W5f?c^4ytbmLCl6krxA4JqslnsMG2N@ z1?A{#%VTId1Vp-u26!~8ny*02ny%6`R4yNrU3zjSa6SV5JY8Kdd&~-uzz-0j#0dha zxo@vYMo*HJ^&Xl?ocwYql*rV&ye_~eI|UOYeh010lie?5l$MrmY>@5!J&IBU1i2Ac zI=c}}_|gCNx$Mxl1Bu%b9&d-=9<_;@B05*Dp?FUa;dT-W}QRo z4mrz&c&3+V?37@lyRRfCBADB?UwfIIGAVylU*1?-Q=AJk{B)W8R9kj@_5$OCv5Z^8 z-hZ<8NHxB?>Z9|`N}|!yF|UcMO^KC0jmT?C2%Vd$*i*yeNL-+EY_@o!n92dxK?E)mFV7SK~d<6LpT5lPtBeo?@tO1-5KV4C313|`Z zbJbzN2qX?FWcF49_1cAzK$=t@fRT84sQ6U=zA{T2f)G_hTs<=g^xe5J^V=){&|=Pd zyDLs%>NNc=L#1KGTIA!=45yai!0-AuOb`$_+y!pn+ z|NmRN0#A4JegzlzTlh2=aCK4g%_ZHR1^v*owC2w<0C)}`DN`%K9Tt41YFqOVogp*5 ztVX~QPB+D&7&1fZ^ND;F*fiyDZe&jkI=%;+x@f$WdUlLGA3x8=B&G6HU*X7Z*j%l6 zRY2HO@=%R}CW$)geGZ|tJ)P^d7p`RXm1OGo?)Q&!&oVQVfaAM7gWtw>V}$6CWV7}l zp9MTc-?G>JI3Ks;@uh*kmAmR%ShWB_q{lAY1pjw(7W^MKFSfLqp2+C**u3Bo-!B#_ zoHVeX`hC@Vj%rJ0HK%3R(Q{=iQxRU zQD}!u?6K9>3^(({*E)2VIJAUPw$`T$<-ltmF*j2eEb838WR=7i%ai90^b9tLGtmjj z0=(O)Jr&g@r`l1Jv+G1+q$jhotu#5(kIrMYG2e-`1vc&V_~NdzvgX__X!PQlI^5zu za#;lb$C>6tODt7^VO^&|E4%NpviGsBzuv1y7h8()6?b+I5??+x^V!%_D8vytVS_!u zYh+3VU(;hWZ95vjesHQ{@#*6Gl&^_|C0^1!wr|cT(6rF*tjXZn`-v@*Y1uy$ z+P9>G#yw@)U%rf=l@hz9WwOlS0L5cviYG`h+hU~NO)Hp{Yb$_Rg}eW{Gbt|h_V-P* z?b+SIGhv;JEaQbw5`Y`7U5Wn20)^lw#SgeKJ3K%zkX} z+ard4skr4N^xrn{Kh)ZL@WiWE>oc3QcZ~jE)B~i1P^!FE;rDhD{mTi^8aRJ|O#-kc7$&!^12I;k7%$ZOAG z&68VtXZ0?)e(Dz+k?`NM>i4AZtRiyX{-xR>YK5V;yS4w;B zq1JTozb*|BpP9sSC_=6Madb+yA2V0;zY$R^$$>C-X1sLF2Ef;>!6!o#xjwSUd_1m; zYAZVd+}gOH7<`9OR<#>O9kXvZ9O8mTIN$ZGlEG{Uu#(y*pj_syFp{cH-4>FvUHa_i-M6 zqnmSoZ+?@9Wb;#u)|r$~TsvItd5Lh8hnb6jij^)akU|M+j@*ZgtsuVT;lH7*z0{RT zQ+5;tj?Mau`h$frr}Y$2_HDjI8Yo8l_g3_Zey?tMFycJup1X$HS^G@+NNdn zsB*&u%|QNU^OjxOwAEodOThOzSv=c>Kn+h4Uel!d%&`4?1r7D@j$#~4w4;FsGoR&= zIayVcJ_hn4S!au-+JYBa932HbIHmkhO~noIl?0hTZ;t3(;%!z1+y0_LjDKlDn$~WX z?^evMi}v#8_K=XDfdD@$8w(e_T8(C82w1y^A^ehY&j>>XIorQ~w09|&xEz$inmuL- zuTVf{Ud?@U$0aymLD{@vV-FO&8_xWK%t;M$( zvnV07kNTDvx~7vXVw)x5{pp3iF4jhe8Ae^ZUizpLK@1w!`xn*rsgA@ZTk!?WFd7$X zU3j&3L@OIYcS7b<{K=xH}pw1Z7;}}k1mynnR-44 ze089e{gD%U;ubJ|c~Uuu2{5UcM1gIS4w}uuC+Zk?8`vXzxfW`h4VK(h8F?7(jw2Nk z5;*z6(gHSyfEbSRMBhG!M%#*hNn^m|z_Np`o?cN>K-a#hz^}UAUCS9x!pSevx+F|G;|P9FsRyZw$&7A7hNnn!auTaWT=qa=|{)n za}qCE>azh`hfkXWh?ySsy&zgaw-A1TBM*LBOSFR50;nh84+Bphyyyr{oa8&mbe24&t4LF2SYs;pWYVwazzj10?wme=9Jb*MnyE3>XS_UMWx3} zZ~-CN0N>OdLS<^VgFS5Ha>z<1kE)dasxD?;N!h>*tfhpSNgygd p9w45=Axoy83H0itJ7o`2C$g6?st0_Wf71wnvVw+um8@07e*w=S?uq~a literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/illustration_training_lane_01.png b/selfdrive/assets/offroad/illustration_training_lane_01.png new file mode 100644 index 0000000000000000000000000000000000000000..27d9bcee3e1be0f637f09a27b18e172456c5865f GIT binary patch literal 268080 zcmZsjcUY6#^0u)eBC-YPB`Upxbi|;7hK`8z5|u7Z1cXQeD!nVc1fn2t3r&yaKfFl)>B(JQzpd&|og3p;gMGiAp|5^&7ZuvSoH5In_OG}3{PFm)e#~ZO z`;$wbM5@@+*+CC|BY8%L<$r&WFFhaARzWY^S&RO;=YKxu^Zumg*v$s(ZONbSKbcC< z*(A(GBc2YzS(UA0`x;>$>3Tpe-g+E;7hYM%Ej%+%>MxS0+pzu7oqx}qGjwBU7 znJFtK{PT2u*vZwvGy2qHRGNS8`v2DH)|tc+%B{hd)EUip@nf8@_8}`$+|y3g^xv1N za4f`b*cMX^<@bXLYfY|8Aktg`wj@1~!Nsi&}ioKkrrP3vn7vRcgIVQKKAIrS6{gD>@NHTsG6wcMWxye%zWXMWV z>iC?SVzUi-G;fKnU#z>yrQrH99aXV=bQ^M?5*y5^#Y{|j4Gj%Q)D>AVr++v6#rNoy zd9KH2=F)y`S!D1Ta^|J#&}~+Nr{wN; z;!oevq@pHdm76-t_N5Z@7;w6xPKxAJ7wYOXsar6v_VLx34w(cv`SGbN1vguP8m5EX zf=7ca?ViYUCDTg_)uZ5N8?2%qxZu)W$0NuJuVPCp!>qK%o?MOZM?@Ul_+IJ+4=tS{ z+hNfBaowEB3ST84ji(U1h<2pbawge}Y3yaCTSqL;TeXIa#L=Q; zhMpy_~zXQ zYZ0?vMbzs?gn?Tizo}P{00z?wd!=0NH5W}$f#<(Ng^f|_xWJU%57VM+p6xtdl~+?S zr{;&5{C)+6=SERS_WIN+pDg_R=Y;+@=II-qd>OqHz`a1xbg+pGw((jYFjcJ4&weuG zabxA&S_zEHr&Di$cA zHjqE?$eQ~JeVvl|Ln70F7$?J{{K~{8j;ZvJB8Qus=edBtu$KEB}(|`hS zAa{EaIPltQrHN4&!n(xT0n>K(N7DD+7}D>f&UE?p0Xs6-l9K%Yg|5GEIG#PG`LWbu zgYbx<1G+<0Y#f{)EYG{2MD0ov2c!D^7}^4_9emczX&vWodHy1rpdzR_Y31&08m|N8 z40)sPDM#@CDvSre?e?@(W}0T+&_$+*_N2*$VVd^76?)#J6$_pAJ*pOOP>zlUm6fzD zwlJl@*dyOqb8W5@prZ#9QBsRX7~I-wMe%9Uj@j@;rIgXCOFU6;JS#gqF|Tr>(Vn+k zT+{}o2)anhsFCZgVmW=o-6JL6Nn@iU=*G1^oza8>JoV%45yXfw0;j!M_(g|MElo7x z$0HE*;g9~#Zb;EH%WO#*|C8PRSqC^R$F;s)+H?D|I~xo2xuGvNqi-g<@bP# znK(8j%`}Z!+6iYOd8=w?Rc{#%P+$6$MR@9v60^2L zMEk{FERd6Hx3U9uW1R|V>WFkMz;hfwNUksOxIcm1L{WIX6@Q&@rB049sgu8N{CBql zYp``z`WgRl?x`J1_5;&thvY(N1bD=DUx!?j6{Dy1QJCwpkULUZ zoJKn!@9~iu)mKHs8yAmqv~iselA}hQmTcVPI{f*tUMIoLQ;5<01f?1lSJlM%{uxylA~n_dJ_7{o8#NN_V9XM+F3Vx6tQ6legIHY;FzChl3>G$kLrREM4BX|-Rcju^rj|G99PkI*x}SK;3OD!gT| z%(Gys@u~G;a^O*45k*ZC1s%d$S6}IkC*(*?6 zgx^eP^r~spAgM7NKS0!s$4jT-j;kzP1_^u~e&}VTce&hi@|H=4Z0Y-VHLFs}kQuo+ zl^%Pe=I(bc+>u7y+nkXRo*`*1Y9%hP6I4pInGdd&n!k!cXy)^>7o?iun>sEygYEET zz5ChpGs0ps0!u^8jfCCT{Lr6ev}Jo_>wpxsjqkRormM@N#`)j_;SXwY$Ca4J+d=~= z*1*A6U?vy6@cpG}pC^PL*}wBAf%}~KGfliB{9xUd+!$@QSO(#Ry=_wG$N;2Aq4E-j zqTQQzdq-(I1=4lrfdO4xe94q-S8!)%`@GQ-mp!ykhi#8QaU577o$Tr;+(Tum>HEZzS zTvS8>TEx^7Pkm+O6I*Bzd!e>IoR7v$SFk_NX`p8LBF|6H5|ac+M60GLXYCTU&@wmy zzu`#NJZNeIo0fXLy-Ql2f9^#xMChwwf}DAtVzDQ(SJow{oPx7Ie#N-4D<7}Tv~6Gc zz!3J2EdK940Ce63=YXsF9mlsEAH}VeNx{eI7kGL>+h4*SYEe4w?Nr}NMScwO`;quH z=K`+dBoFftB%0_sg3@e1bTgs`#5%aFvcTJMGb+Vd$f#6QpM-jwhZS zo?ji8y*``CIIPKU7^R&eg!G!*<-C%dw7Qrrj?2aK?JeDKOoF+R9(XEmD__?PoNukz zv8aEtu(T&rktAjcZVhaK3pVBd3|^UgO==;p;NUY{yPCM{rDx9w5=kYFKg#7-1dlK{}@I0m5uz2Woc6IGS)o{AJ%eO@R zE!N=1h<$%P0p=&#BQY8a7RHTrNveK(wovNSYj&NbSJP^<$2;MPu6CAOA#ZF-A65y}E>oJGwEw^& zcCb8Gp3IYcB=S|&RO{w;Pl@(W?;H4&U_U4y3n(>s@P0Pd8<$ToFDq&_PwbUq{;> ztV6D3Wqw%}(b;w<-rz~4%tTJi1ACOAzJD=am5Zc*186|yL3WWCSnP91#?3y=Ug5(o zGl7_3n5BJ5tMZaUBbAszxFmv1$X#nnRZfO?$SlUJhI74$!xDo`cO~~9N7pR22IcrR zuEcm?qIX8)$X%?0Ju9!j@aZDUJri5H@MT|fJ)`xsyLPt3?(>x}qHa`~zOyGIWm^xh>9>#v8?V{X@Ke?1mY~zs>!&SH-w7>Zwr6)rXeKWrL zuA8J{F;u(`$Io?N>Fl6a1)dU*cV#BX*br=h@KV2AzO%Wc7R>1XB(B888FW4}lCqJ` zx*P_gOctmtsT6u!JI3oRs2Ywa#;HyfTAmLhRLvJFMQ%miM(n4tLE)a1Lw)M{{loRY z1jp1u_bJu`B)OBtK#o}+N+yj@(zyNn9bj8!zwCERw1#;e|8qfQgUQ=+{BoeY{kag0 z9a05~DhA#ggFpNxW8l*FW|j{)nxQvH#%C)v?(2TG2N{~SIO>~KLTYnO18F{UuA5vHjQvvl{0+D(DBzb!y-RiTsTxh*9ZN)s8U1a~lJAe-8}9UC1yUMtZ)9e7 zh`rUzm|4<;HG94fu6{oBh4{%N5l@3=#d_bR{d0Fw2h5MEy|V^LYi)CulIkQ`rpJ@u zs&V=0?|HWdn_Yfgz1d$Uw_eOU{IAsboo^_1G+Gq3lVs8tbQ1PzE>DV`3o2bjj1rjG`oV z;cE-n2NOswFMg&ZIgcCys^1u%g6Sifr7yrnw%bzJ6}ukn z#_LrKSmn%5tGmqT@VPzQ5PLJ31pe9`n>4vwT}b;x`)n^#wzz4IW(nLlqf~$gT}tQBmAAP&C_UeDuf*6CqNIPi4>Da zxAbVJOxD~z>8cjJf3hx}>5(l-KQHK#pEjR2?T)3cPOZpFHZ6Q&Tq# zFPfB>(9G(%g6q)oGRXkc;k4Md5^Kvs1<=mI_lgap%N#GH#`!Z?rTi!AHv|qiLzo>t zqt4vgw@?PV`YmC17X9r9%k13-ltuB3e9G8UYNKK1J~&2Ev*(iY&su9IPG`$3>8vV! z`%u9FgyL09s2W#jVK1!GAi9y!` z>|HF%`*rmnt^ws(_Mgfz-6ooN;wU2ppAEhK{adjmm+I}(+L?D5>0%{LH_vyp`$q(x z*kjE8AdQbuDo&dE%KoOJ*Z;~O1Tkv072PvOhOl?ZEtSQY-B%(~K0%TV#%wELHNzM^ zWKI`yfVgn%x^mb;{IGj{%m5J+nu8VzsE8tot%zTh5rD55r{e)6kqKvc@eswKcoEV@ z%|h&KG^CZdM3`26!ZH|YWpy+>6k}GRlS!Ux?vT0Gt`?Y>wA@=Iho3*(LJ7%-oM3Z$o*@LYi#Wq4gY^`J;a9k zwkKaolhzqPkOL6xbM$*>~Cb&NhG|}EqvRh+W zu_9>*+gA#rtl0-OK*|nZ8PW`bP|Sgea-b#i0bqMup>N;3|lj>*28#blFPbVj+A9*q@4KnQOk5L2D^Okc~> zYh)+a!k$;+d5B@r2(S0kzOGUyZp{c6%mh*WM3K@R-3Q-2)5)`}kt_*>+-2-a(D@B{ zAb1=De$>BbwuPMtGP<7iaVqT98W#FuD4c*QnX}y5`?4;vu=$SI@%UF9VQ;4id|&f# zWcv9U<1tN(J>}G0g>8%U#UHihu&wbhF4ae6wd0{&+Ke>Q>S_myYk`oRBYK^Ut_2!A z)7AVj&AWSiZ9GRWeurOrH_gY;lfq&?`b9_P8`6cJP#G~db;*daH~ z0*}*qW8J+KcCApfLF?qnd4HM@ocpjXn8YX5UtIP%O!_1A?w?Ay+xKa-L`S@KGsuAv zf?b?k6cT6N{7_E0wpi*XIbRz}}l|>&6*#;wx5Z-8FedQClTm z)8$ZCkjG~&k#!NV9d z!9x3=Zfz?)v}rlM*(S2$I$=F&I3vSblPr-ygkQbaY;k!ab$%oQS7=#hQBS(+zp;C~ z#DnTDZFL7YL9|*+J9Wt0VFZEphU0se*HS-sl)3q@Bmu?VtHs}WhH~%TCms*VBbV@h zF`lunjx?R`8($cyMvMsdY%YzC!dIf8u4t#)oyB?`EiaqV<$7`;2;tPn{ciG|ofY@6 z9hZ1^G>stc`@ma5okz6Ukb~-a;>}vS3N{-)dxV}}Y_l_ea%sgk&00?Tg@BjBphncq z#~&K9PFxQ7&})*-msamLP+;7BVxEIVXJs;t&e$sE>f*`wGdiAhpJZJ0?SzWj(-DdN zCXVOz`4-+zVv^8SwU0TdxzCW3qsKuwPMN#w@`GMq_xWx;ZNn=7Z)UVj{Z-1cBRBbaXa4W3G3x8E;FD4bv za{fSd`wpEBA65W$5lG7Pbtq}ru$Y3I zp4CE%*+i%ZRI6PH4oQywJRDZ5wo2DCrkonIOT1j!K_!V5sn3%7k@+-EO+?*mJ zR6)LBw^MTaPM?8-=jVOxEvHe%ltzos*$1ggkUr#h1?N}|n5A2Zn1#{}-*3d848nvv z1>2y}F!3-@fX7~-VX9L0CbSaP<55Kbv&hcve2X+1p5s0M^dQ{7J6U2fEO=rlnNKrT zs<|Hq1?0>}x0fLKj-5YQ)8$ zR+nd4vAk2PE31f}egm~Vj=Nbhr=$`u``#eC{qwBZUOYNqC-u*3u|F?(e zsCrB@)q{o(rGD`8lizfbDJTD#3?QN?>N>G-qBZX|tD1y}a+pY?`0g<2r6NBkW?dW9 z5b8_u?k$mHd&ep}8$n37ZEb~#=qKC5(E&gPoAk2}7wu7wjVDGyCbJp16s(@jNk^g{ zP2J0>gnMIcF` zWkS8n5=sQ|Plxn|gWs>Pt*;f!cZ83_S+=#;zB^TO?ZpVUs!rx+0flm--+XDuz5>&5 z)Kbml*%1M$pA`cnacUz|!y3)Wb`p!!mA}GF@xRm5wU8s&kM;jfSva%9bZ$(KN!Ybn zQ!r|yeRk>j!2C!<{omS`UUJN*$!jR+C7eCe82M0FyR@x!$WUvOU~xG{ct%bN79TT_ z;#y~Cy_Jra)HM~K(e`WOq$p~q)AxgqpO4zea^vqBKCS`*pGl0M2Zyler#?h*Qbbn~l8E_0EDSYpDhzSN@s%S#3ZkDVk)^)IKB}wA= z`rXX_x97|GQOu}YPD7);1EpyB#t!j1N9(OOGSs0a+OXMK)|+tV1Z(o3fry|zVNyFE zKk>XMW%N-C0|WSYJV>yXdhuu2t7YPVSVJ)h(0(nAG|=3gUVp^!-&^F7Adt>({X3mK zmyJKdpR6!3))=%8(fH_sZuq7O&{zgu@j;+dC&9o}ddJ!BQnYF9E*srxTm5(z-S+G| zNAZVg-z4*DL%t{}$ zDSy{=9?jj0v5k?g07#?$_xWl&zTqL^GwYGY zE|qp6lSs!3ag*Skt*C7bpJeeIOkt;#+r&ulD{yQdol#^b8~uoX7HFQzYlnV4 zH=CReO|5WS0SHdOY0$_XLy<#l`8IOLDhhkH!P~bt;1dkdeLed3a{R?UMxXz0T|5^3 zfQHUXux4Lo8}g+?OY$yEVO}>C`gA5&K)>qRmZ7)FOJb`z^m5UZR9EPjbAn~-^i})e zK9z|ao6<78a9+c=bHnl}4I^<6d1Q)Rfz#9h`srpwI8{|@Sw;S;2bX$o^ahgZJrG|8;NRbrL?YXZmLM|RjVNM+=E*yoc2NkGLkOcxtRu45JKFocba`0D4$z<8NRy=*;~O>N-GVjgsb`xKUA4>TI+9L! zRtDRq;KK{Y#V%TUvS9}&UaC0>u0lG?elfm5JtJ5kyFa( z+{eE|XnNH%lD|b^8Jo?*<$9E>g^ckcYZmk%VgF0+qa9v8JeBli_mLgejk|E{^;@nbmJMcqi7}n*kdG<5PddG0hXN+Ev;!Ofr5Si? z0FS=xSuzE~l!Uy#F;F|vFYJxETkYF0?Lq^p*Y`R+bTvu^kU-EpBaPg$G41_(YKV|I-8 zKc~N6=?;0M78Q8qN~*5$1g3BneyU)&^ipueN-@i zU4{P)+Wr2EbkNr}K}4c+fKUNG@Yn!}4dk(|%roIr1_Ttr9;n9X!kp!&h-w`scSI>+a#x#0shFt1@fw zm={d;+D=JK$$dSZLl-{<=)AKI2ph{W7&J1WaJiLPe;rtsvB{!0nm|`F5Gp>@SzR{C z#NSq|%eI$kKe_3SA8Uyl@G}!Yw|p5n&(|SY9Coj6m!T- zp7*C8!AjTtTczl8oqVY=k#wqv^35x*f#AxGxGn-bzXGOU_DV0&k1~3&iF!vgOwh* z)I&9Vy#b9_aJh1OMh#mMk~EzZ7L2M`EKptSnuomE#LiSrUpNL(Iv-fS8a~xfl zz}SQmsxkcwofe11(8u?98mQeLlx^OLW18E$G-p>i)_hj34Oh9j+)f*`^8M+<5MN}N zOXW-5b@3J~eqi)Mw7ZVUQb4!0L)mRwX9=&p6(1dNDa(aAfkAgVvfWbXHI3!)Q72|@ z^~y^Wqi(y62!2je%HuUAmJY!g3bNAXjrz0daRQbxL(GI`9X9*HyhqJ;h&98%A(cR* zbr~45w$@aeKDAKeGxzPMQ@<*|+{Cm|j<=OpmZjD$uJN~OHv3*y#nX-FjTF=&3os5E zj7_+IY>a93a?_il8*!fYeDJRl>g!ag3Hexb-~w&X)?exy28R|R??Ckz7x`>-4pHU^ zfHH$eYvL}JxY_=ldFdLt7??~k7MxjGxlroVJt}0wMNM0Slu%4>L)%1 zUZ?LrdXo-ELt_-IDTfA= zLrPQeA4+3eSv!(bwVL&i(gtApmD;&)#r5~ji*L_HLi-1n6Ak7ICtio5Qw_pNQ3E6I zn&?{?G!A!;;e8{17+H?5;a>M1@bq!a-C_oBC79M>;?HaAiiof5TW8Py8v1wD!$BN$e?L8SM5wBg`u>6K{DxV{dVx`NIe zy{zs=tOsYgwVMQ74;s%n=$O(IyaTfpgR*%wf2&u(F#O4Q8?;5mK6Y>4S+Ot>Ewo4dwS`uR-ibED)V*lT|%j`Wp*;>b~8DzEq8!4K7`9-t^0 z#B5DOx%D}%&qlyi^r#h`2h4jEvbN^^Aq9bV6Bb@E&52A7&E2_cwOQ^SRga29sz^4_)p(mZi)XKAs+F1)X zC`XaA>D8dtYtRgXa_B-3Rt_qR*>y$Ol0J*MFM=MNF}xD z#t`uTx^fS-ABFweNxf0*6Fju#1NRUqnq`JF7BD`>pY5b&M)9Pp@BIj_c z@|2Ey!}_-Yzb`H&3LY!Fmv8oiwRfG--a_^B7OPC);r2?n)OqmsVmhg2&}66cadC&A zD!(@?;}1jx3#mYb)Tk_gli{U1IBD)933?^g7Ik@0gq2X1pr11(fN|B%f%}f{c*{5- zQzq=w;1Fdxiy$0o?t5yu!|LvZrz5@<-4qI-|GEMCSAPc)z&HiPzb=ut@rU66Qk+U2 zJ>3ZGt0>L6!_^P~YNo6|)J%!@XtXlKJ{a0`ujWxgp?>2b#0a4*Co}8XfW7S^hq8#x z)WFkwKZ|r-1l|ct3RLrVM_e9%YvAsmV(mBc&_7;v>HYbNsY3b`yis$?#8uKI@n^(zL{dWAc@%>28e>&fcg`N2oqJ3G?J# zJR&)1qRXR#r!2(@MMC(QAStt~U{$##XOJBR8{(E;zAthY6?k-jBz6aohO3*|2i#0Q zb^RFK{UjEF!{?8~{(k%f4&B>mo zAlhNtXOhs8!WSKo2f0M4Y!42dIw5V>>9hXZ@HK<6e?3! z-*3iPkWx9+_!o~03gXg)Nm;i5wu;YwNV)0JxVLep0LkVtR1x8uK@yW#1@CN}TUTMW zS8@DGm}(x79)#E&_FkB+h%_NS?T!gU=9k>LnGY665CGbTW=&jtBXF?V)1ZOSE4iuz zlIdHIX^zIn(-;~ged7jty$MkhmnX|#tzqgy7_Z{=Osm%rG^w72%P*%4Chm8RM%g{_ z8g{FeuQ7or7~Fr%IAvsvVvZ&_V0qCHwUoK9e#r~uD`UfiYW~L{Pljb1w1vbtoj#?yA@$m;`!)VMd4$e@cc5xiAcJF}h=LABY+ z{iGTT-I?&@gLy3lc|;X{P7>bZ$R@ZWRcxusG}RmEuSYM2gG5k5H`4(wK zt2*Lg^Y~O6e4wW2qlFbf!dgECCVGx!*~>ZndL)2sm%O?}Z zVygWMa5IWv{zR8bObWZY0(WJjZ~`W@vntmo7UVX9PmRniU!F~_BqL0#Tlb#y%pBlz zws&)CG6DwwX?1UO7$Ik0*+<)VVf=XWkYAWx$)0^ID&r4F?XB%0p12pl zojEW;YGt@VP~G2}>;Ww88CMo-a%#!hQQ7H~J#vx$0TUa=$vQ%=&gexUvCaVGXSKXAEp5hPn1KAvq;qR!&meae^#7S zFH(?dLplWZDtK}FL?%#$2R~IQoL0X|>Q@*i1=$yYtv1k=8_Lf|0Z^RbcVQ{Z%qNSN zsVlfvI;z>qKLXhfG&6N}@}dBT$K!(kfhJg%6712}{$ysVSPKdiB(tUQ& zMx8JqQT%%K=EhyGQ6O6Hn(AL$haF1BO(fl#`j7CxS7gi%*fptt+BK0!_}e|2Lj!2{ z>Q~!GfUf_>k=Gc9X9R|^Bf*1H;8Tl$9&!fLl^~rWU3$u)UFG6S#V%KmqrdkWwDt%E zv^q9gIiiM+O}kovtk(mR5dJ(mtpGjeE$m?gfmMT+VE%gD#-`RjykP#B0tM7kR?QqI zBUNLlaq3)3ZM+^qNy27@u7jXEhJVDH_CNQ9Fm+pHRP%6S%!F z>7nnsO3i_h$nq^CO=+n08%zd`kIuK>9!dl;K#)i6^eh&^r z7xNFye;@*IH;hsJA~uaXB_4xEWNk(tr*8ZzHWHGKGLifQ5^Yh1)EM{RuT8xTsnx{U+SIo&rB75QBd8RwWZWv3x_ls zj&faK*FZiv>2oEGrG|mvJz|@piM~>5TnltnODqZfEckA=r@NZnvScT(8Lv_E3@D3dWQ>n$H%%m zUO>k|eSrGvuKkFqPk>x=FPho&)@jeoP2;i{pamYBqFZGRuJ;BS!rLYH?U^Ax)O0^O zl><(p31!Ds%oBm6<>qj;Yw7Yi_4tEROoP-#O5U4;`=3Z&o65G{)}zfDYK8dCd%v2( z$iy>bwh^sbWsk1^1Hqolh8^MWS^DT~ZXcinmR~e*U%CuAT3JiMU71v0u-oPr1l@EL zu+?YkbRa7oM<2i2N%{*;2Qg29-q%(TNSm*3FKKu}jjl-zo{MDh(M_i(#J(TGH1s0@ zn~*au>_rK*F<=^S<0=KD-}g=?dU|LL)PGH@tY*5VVCbtVGm|$ZyN#!?qg~J(c|L65 zSvypR@=n_(`6oJXZw_4qFjc_6Xa@`GqVR1MzWf%Ds7g@XnX(9|$MI)`=M~X2yG>%~ z^OURu>X&8ovmjO*ARmqnA57g%|3n^i{)0;@-MIv_z5@oJbo~mn9S|D~ia%a1fe(&9 zJK)rE4^UDz=0dPPJ#mfA^cn4i(bJ=qZv#&_lpZ$w###aX;q(Xo;TwH~-voDS8Fk|T z^@XHr=1wTF?rC9E`vGV_76xV&%@3^&s|I_4Y%6V% zpi{Jr$mD=Tp|I`(Pm%8%ug}F|V4oBopi`evv$HFC6vo1eZsn9W0bn9w6s;xQ6HcH4 z(uq6^0N3S%5xD?2m%od-R{%x(_HT-|%yXZnGjZwq7(NG@qWH`|fs2149dH}h0ycz# znDS1AQ)c%2XX==4^uFVd+Qz~d3}Ctry>WJ{<}KPN$l%;nPJ#eRxnx%ZL+l%9CpQKI zIw8kkMjqXk#s{+Qy}ZFy&;#p$wP<^Jo1_;G!C9~eE92pVjz6NjZ4a2dqd7)HBxd-d zMjK-v6^pi?$1*anAF`utH)lyzA5W>Wn5UiD3*1*rc9qru7x?0$pQclgoifOExay@6 zeucEfdeZhk5Xsf{g=||K@F77C;aMP+Rh7iu2&U5d-qCCL;;EF&o{$}X!10AQL}0z2 z7vec`eqp3*fh=@uec(60Xd@=@Oe0BR3ctaAM*{Y-?s)L~z1>?dBx92zBY11<37qWXcWpp9fvln)ov1R`fk(zxJRB~_2Kb!msk7QI-w!;h&=Zx z!{X&$6UPBf>x#n8oVXI|q4|0NR(TLz*h$&9PnqtC<+-vkc@c|VDe=0S1=3=q%e+~J z{4N6qnqUMoUhYG@Rt%?%kkk6UK7(f-Z*leo$rw|eh3}+ z-A6LepO@fOJ&zYBJAe(90D!oUH%w5n%jE6kLTR2+T6LHcd~8NX^EKsq_OIl)nRx_z z>Q5w2>6m7`^m~fTTBGUdc8wWz#;aeKBa;C!6~xH$*81!vb?HItCzQp%yP>rk!tJdu*A2 z-KgXV2@B?JSHIz$HwBB*GA0#cjdcSecEZy!DZ6_SRk^VC6j$M>m9PhOaE70b(PDwt zE7T**g?Osfv+v=(0}=ulyVgfp!%u-=&sl(1G%Wo%K$^-14j#CE;>6ldz{4(n*il`^ z0z(_Ze~9dK_J><5hz6zJSaCjlGnG%IAMk0usa>p_TRnCyP56L+o2?g^x1~eHBj0Rg z3C#&h$y2jS=#9$fniD7N%^9FkY%B7v6*K9Mm~XEdl~SY@^fuzzIue1V(Dh;3pilrc z<+K7V_}J3~`V=XsP2G#^slYG1+8-^BLoZo%2;>5#M zZfI&BUfm@sl41&sv>;v*Dqn+$#{^%=p>D=8((z2Huc~%TJpF{N$YTl!7oXIT>DXa7 zYoD^x^wx`WC7t;~ptVen^_e~&pY9B4yLIKIG(46?c6-8V=fUND&>^2zTls2aka;-u zAV3ae?Odonm0mUOs{u$++Ho(jT~O+`>V=*|T0pUXCYAUHEy~dQHu@;LM2e;p0q{OfiVx94LH}qcecpoDh67VL5oV|MP(1bOBG-2XzjmHsb1Ja zu_3kGR5fky4&S+ebHVTJn~&m*FKdB!4P(0j1|?08sP!wuc2@ zR*r4F^xinLTMFTXGnD9RO|YxzReca#98;F07E_jDP+~7;ooH`W0W_AxsR?dX5&Px( zsePaFL{O;nt>rIv?ANy7r>MELMDBs?`8vaO>Mc>WvTfx4@)cX<&~L)=D}mhhmO6)S903L;p!c%h9-4@} z`jA?$0;BfvUy|fHypeWaRb!DI?ZM2Jx->jVUmHcQYeX@D1xw%Jt9sw@zAx&vnasa> zGwnh9RZZxIswrpbR|gF4+;n`ejbBXSy8O6u730yHM;j2(E)A80xh-k?lZak{6stRR z=vpGwf6Rs@$H6jwb9~y!wzH$+^7b982Yh&I?4hejGTOU>1=8&NHpUwXQ6{)HgRG6Q zm#$;a?}-N(3^+$FEqx{*ON_oN-bUcC&#U1S0XQ@VAIxpOMa-nfqn$9JQ44>3-iB|% zI{+sTw<3}dvsNKddG#;s3*78u`3GjNaAA<5mw)BJJAI?I%Goz9x5Qq8wz8I}Sq9cX zGkOVeXso&&B56vnU1h<%3*<(Sp^>MCV>QDmQqjEXfxMYo`#&T@@5%0>ZxXQOF@Mik zKRk8#$T(*9UpwgJX|j-f|z)iEh) z|IiplPQ8i&LR>lw1n!8z?f@n%ulp5&oywxgM8iB7n~g%QAy(Gr@q;qS?N^zu+3pXr z;&TD(Q5mLK1rh?wup0PD#Ef!p+M;5@UaX>7fYhp9)v)tw+$nLdvpI0c#^=44%Ykvr zTXM@fb*`m)d}Hya|5&FG>PJU`7hH{za`BDkJJ9uMWwh&?m_-$j$?E}^SEVHDHon;> zuLihx=^f{c8BF1t#EmCYP7 z7z1=pw<>|Lq$vx@JL}Zy3w5*+%ji3bsL)XX1fiPy#VG0ARF{3+WG-x79Qp`;akoyj7_c zy;hy59M%q3;W+DU=Ud}0sj0W)^|S=73HfFMsy?oL&WO8D*Id}ZL(ck8*VX}Ianq+z zufaB0s}WewC4r=wUrjPJz6>$R0DxFB@UZ(cqrtYTOoA{J{ZJ`0O2$Gb&u2}Gquw>U z#6=Q%Zq!~X6Zbwf-avL^!Pr0Epe@>E0a_Mu&bYJt)fZQ{wI(_>=_YyA1t{xr+cwb! zEt$9dDjzKuMN;&>`t(dk9` z7k^fCjkGsk+q-mYtC2O+@z)59xbQLRO^@rD!@oz)|GQlsPXdlqtB{0!g>6)RrXMg# zx_}^>LJ>Ye^@Zge%vT!2_wU}8Hg9>iDPbWNkt4sJ-j98og0zKpZ@H>zpkyk2HjJ;( zuT=C%OqOF^Bmyf_4Gq-(rfKJlw2bIpsZJ*v6M^wk#{pm{R}7B@hKtSIO8j0t0h&W@ z@0t!vy-xHaflRn>45i6YSLh&Qj02_j&@rOsy3C5Hz|O|}pw~4z0x)Pt#e({Nn!w>pBI@ENoS>nxlvgw8)t6L6ME~UujZ6n!;qVyOiJ7cvb z)Ic7q_o&?i_wN#Ia1!9jvwVRG6_# zFO0Ts_u*R@(kpW~2T1Atzz=r;KJG5ioNQZ)qMD%amoDP241=zdj@|H@#IqEVJg!GO zXT`nT^ZVNa!Y=z|vsqDLt@ZyL`XjP`aa?;m@w7-SZXc4Piu1&KX2?N~7S{qZRT*tj zX$c(Fh*ZSUz5UXu@4q``17iZQu# z`_W+Iw;@N6&66Hx1JzRcq)%Z$TV)3qCvI6))Px|_%^{6R+vY@M%_sCkyPu)KPCUc3 zwI2JB#%Qx92r?7gxf2c)aXsiq0Dgj9sD% zd2UjZD$K~UUfZopAQLrv9A>3SfJ!}( z*;Z?6s(#IuK>VTzcp$wgF&^-o!3t-iau|h(lnXrd9WbfUsBk67xOzr+X5|dkLhVuV ziS*F&&Qwgv_|8Dv4=A$V#w9krzmZsRA241UI`0+EuL>WZuJqEVU2ZmpnDE3U z0{){o77}K77x=P-hzQlTb0xEu0SV8SwNxF`_8>@a?tvWel>|gG$)~E{!nP`Ijy*6O z(fU|Ywba^g@Er3(HnI*Ex-*-y;;*)CLy4u(`4@G-A`DMFT|?J+q7Bu?>FEa@VK$Ce ziYHSiHQ5kJc81V&NF(rK`wU@x-5u2~r#wkjw8LOXiTpda$-In|H>fztgXX>q!$!%& z>cFNvtYo0K5#ahS1Ee#d!AgZBkosuk$jCvkOqH>jYx`2R4|x(*>NHk+h+|&I9cehV zF=+1bAMNzd(%wrNm3Tc4Obq7tdM=MO5f5kW{ZK2wto4YvwaUt81@PE{V(-D+DLns~ z(Uew0$}26$?9i%Oy&$|r*P`br^|B6vF0xt1JhJ`}bKLE42Z z7~kv&l3FO_bb5PRRno<8Py=zu{|p1~-r0%_rv8me5e^Q-<@3g*UL%p%8r+WP;4LW3 zrddaDSQ2HeGCs+UAbco`utgfQ9SHli8u9NdsnH|kw_EAuS)9VYm?LnaYt*XxL-1<= z%)o{CCZO_Xy+&XG0xC-$Qt|;7x_1hj8oO>d02j(#k8xM&s}*>!)-rp5vwQthSj=4@?K3r@3$RqJhbEfAE$#L)v&UWA0%nZS;fLhq= zbQ+8x{qXamIo_1lT)E z*Oe0^QLb$xtf@MX?Q27`hIuyW-XjqXJQhXfsV_JOrlX=gJ3W&iV^^g{)Z2aQ2&$~o zpj?O6_|evHRlPEEpIR>#quKw-E&K-iMU+OGZjm|c6lCc;JcIIy z`mN_@j@WZG`ktPxi2Vll4fDGH5$&BqejP-91U49gfZwh_z4KHo+r}9E2HC5D z6d2|qSKmNdH4u?3R9PSGSQSYpF)>LNs|yjr_owbE0e)u1VoIpr`=Sd_tFIXGcIG!b zv06AAt=$V2#PkHDU29%ox>GF6qC?6fW@C|5a4BFoq+8W@S}9^?{kwbjDS?Du72IO++qrdxV-QqxVqWa1O~g`))43`G z$M$Q081J1fr|?4u4)k`#R&B9TYspDs7D2FidoAC%{G3aN)~`eh`>U*Sjng$?yc$w7 z?JXI3h8p4VEe2K7GJ|e&Z*$O~gk=N>o3A3LHd^{T_|h0$#eS+* zT!z$F(=63CwO;XTgr3Qhd-c*qc@))xefu}c)xv~L#;qf)}B@=t} z)S2Dc|MR^+zbx_cTHWalojcTk*`6wtpw;(-4sP#*M8_{e2PyEvTC+OYsFQmg|4ECx?2oj zxV!!Z-v@f81}q(wF6t<(T@A&>IyXN{6-yMDNHKGBI|b?zsyaXF7IGpqRb$+X0}gp9d7moQEhsp$*I0l@y&MNMFL#y}hmzhGKZd>KFCcK!p3i_>^(C_Y#@vIv;N2giv8c!c0ekh^Cci>-)dn^5 ztw_@>&qV3+MEFksRQ?&BxKIJBogZz+&(PNLD-{NX6z^}+m>?2c0O`@5LquQg#qH=Y zb$crt0^eR|PiIc}Gi+_oMyI+h6v#k60Xpu^>hCT(qFp#%x9s-h0o?2Sr)*P7QE*)p zgnhO5n_vW5-RLRwhb#n7uTO*-pZ>HRUaj1OY!{y-vV|TKqdwG(%1Pc0b(waqTH_JM zN1?@BH6y7xx0OShyGL+9?ukUJ8n!^6Wt8||=pk+cGEb%abkUHL{fEaPcistqX=&n~vvZw)Am98T>muTk!czWQ_Ny7=0gD;$ zxh_OWv*)-^iL_4}`r0qSCV)K&=K$sM!!YFK>ltm%6>B)D5LS^iOKHmQ3TEv!Ro}!T z;!jQL82%WZRc8E>7cFAo8+Ss4zW9QRl=n!U=vQojgF>!aA;s5{w$tYsnr$D$#Y@=y z@X$b7zzP~o5s?gMFSQ|*UkLHV0s|uD17kCpK1+X8{?ob>bL?-bEvd{G1_Q3e zuLO>IE8_KMzmhtHGP=D{XVec~4?Gz8&fMP>=fBvS4_!Fve@>m|xKU_+u>x>T+ukrh z`^TX3Cz`aOQ)03HOd(ixf3C_%WYAV@i@_<*Fx{M6c|yF_)>!qYd7}Vt z9P9fVjghIVc|m2_-e>uhzZ!L77gHP>D_9Ks!!4iMq*5Hf0?JtXYd8_8NQ+M)+LPt& zff-k(bh@!(+@5Z`L9qX0J?hQ90$J~cT7n_}sQIMiZVz-;hxD$t1-oUkZW`WHSx3$6Q&qlQ$ij5_*O=cA7s?3>T?0pn(@Kg>FIhvD;v8PjmxL7-vpxROl@A zrGox4{l-z`+P~I?|53`v=&cSltyaID^t)79sZ->!0USCc85CD<`SvaTHTf8e>wemn zeF0I2t0sn@DxA6}bXPm}q==l0dDXKh$AavJrHJiu#PDnm0|#Ifsu82&Q>|>d-D5q+ zpXptiR+!}F=UYgD3}{_zvrT&Iohi-0Ow5$F1gd64YQCsp>*e`)JBWBJLt=l#JO6}K z=k8J>V&u0ma}Hq?IoYh7gY=_u(ySTs*_~&>sXL;H}S=l=_s>N83kd)$MSb~+E z4kPIeC@`Xa7DjV^wLb_$ZLRI=k2V2LQ2jc&>Gnp}y+p`Z?LnwXya9Cd(!bNuUz`vH z6OTM6Nn%#H!_(~Xj#LGF3+USHvP&j{ZQ29U_tiK2L$cq}r8(-=^0a(i;jk|eH00cA zDSH%pMVhgXXi5Dv%V;1w#|x4782_4@6YD?Fy)hWDn398J8BpVBni;e2nF%<@W%AZH z3*R%NnV8y)Y{G?cxEFid<{exD)3Kq2WvaxW~ zsELc6uTVnawG1E`kpWIlN~=>5I?J#LWJ54>K#U~*vrvGsdHa+c*W0PmnNWP%KE#}B z_lHvN241iw|B`SEbAUx&_M-PA`Lk71mU*^hk%m^Ufkyw~Lbp$<`xGOcJ@!Y3#A+%y zD);@+Q*zHmv8x=@tgsruBDp&aoNC@t;U79I0?P@d%2X)>;8vs9C0!45uRQ1})8&pL zb^qbpGbRZKYct;$^*SlVpM47_Q%)9Cw!{Z@9B{OQbR-zUlqAF;1>vm*)1$)c(6>^#+l;as6G>_omgt3UqNDE z(+}4@q(+~yBO05-uDI&VdnrQ!A6?LNil$*`dRhh5=6qIw-n#=SnZS16kGc3u+#y4j z1I&_2)xQ(gz^-f%%2$|wcep@|-)f9Fc9I(VY!@gv8AykdQ^7{aHhZ^S-+csUeTOTn zAg3ffi0vrLx}m~@Zai7;`B}@MJ2-gxWDnfm#FO$FT@;_uGxZx`7F=~=Ur_iF%r&Nm z$eC&xYim9!GH*-k0}!ypH>hPzLss#~;9I)K%11jfmt*#s=h4OE)0rzfEPiZ1&+aqV zcSA8UnQI5lSju&j%Exprops=d|itk~^GAtE$yI(FLef$P&LEgW+fucM0D~F&=+q0;c;p}i1stA9lPXuaDT{O4A=h8Izl8E|^1l}RH ztn$?rxMsurr298>D56i!c8F-WvlwMq{PR&9BybwHGAZn4{wI9X%yUTqS8=SUI&_}2 z;yeF6eQ;Edd|8{y2Cw-+n7df5?49_pwc0dQF`S4LE&3}MuN*~+{lhhBOcHj;nH01tW(h19u90Wp>^=5&;_K{}55G)J1@$MAH@{a$tlN9J{jnkFb+50}n`s)h- zA0(71g5T}pCKFmc1d2Mv^bAF=zy?lN=s=drt$+}inpzD6X`_K5J2z?MmSclqz+`cL zFXOmHTS_@tfcyOcnuM1(I}wMXe}!>z#?_PYU+Ulo=;dC_^MY@B8?EY1YDI;*Z1Zy1 zqEpHcLD=Sao_|&$0a~&6gNOUVjx_Y!P}2{@wN|*gJ~2Oaw|(df<+}ICy3+mluF>6^ z>UIviS7fZ>pj+GSs>+5rH6Kmww%gMn=x%*QStIMS>aRi-cqT?)qN{bThqww73%-do z><*DBlN;66WWEQgn6Tv7MpYGv5!s@54uthyTm>Z3VvX zFxhruXLb3C5pX|ph8*%4@g_>e$vDsGpJH5>5`?~L4@mhgmi*DwGMs0K=ni;(U+aTJ zH+aj#Et~I?9pd^r;kXBe;c(-vp~BvnscLJ}->SpN33X)XccTHg0Q_}4j_e(0)c2!p zEx&LB$Kh;!YmL(G^eZ8 zzU@R#*>#-X?_JGHhT_7uKH)cQ1{Cg&b{fHd%mv`&Io|JOghyLPu6SPYKd!_V{WXL~ z6GwYbqI{iHnyStN@)#QT_H;F*ho}PRiD;$D&|^NkH4HNIpk@5^z3ruijn0yu*Y@8B z8qrrxGFvpZeV*A0&!T)Kpv-D3uG-8xum)`_b4NPOmaHW^0diUMz28yybgfh-`#WE1 zXhxnCi5Ww!Jxg~1b|Eeop=g)vZQW1bRV%GkaDiPE31Qrgxwl=>j%B@KRg2d`?A!1> z7p5k^$h`x`fkxk@t4{)F8t2sd(S8xW;8FKw8-h1ZvqcrBPWy^#^sm=o$wiS4OuwWg zxtHw7CH$0-ys8zfXeEeApYs|7Ls*X-*dbhZ(WXlUau>todBv3skF-GxAU_53|G-x! zC>l`N1ma|I6eJnrwaib;e2yAHm@&kNyk`XRI#pQ|9=GY_MokQIDdcZ@+vL?G_h=gi zN;&)+lxUeZRZgfr+o^QVdcl)j3!O2(?Eu&Zdk>!oSXFtLy`q-}e7r9}#aqJP@Vw&G z|3!?RoS4BM8fhIpJw*#`&&?m74=rlm17PD)k6_8wD}%}}8$?o9LTV*Nc*U>lP4L8c z3YWhK?wT$JBcZ&^$4@G&gQl;GTCR{Up!0;QYk^`_e84lz+&61yidpC$eIdi~>BhTq zrdflWr$}GH@=YqEt;cG3Z$C_aKu3a`!2;gy8@%=`;+c80jcIHYG7>yKJYHuQNL6oG zaHs!q#ueL}F-iH3qP88eF)?zSKiVlTJBrphgVrgJ6IfyTZ_VL7?B(R8TEja<6M-$% z)a)5ppw`(3a%+XXUwP7WM5+r+-vI{`Spu=uu=tmC$_;ItDi5XdLah$q3=11zE&ca5 z&ssQJg5+(Uumg zQ9W7_-XND?(@Hvj%h&iGbyDsD=L3S{b-(^cD+LUQik-m|_x)}#dDee+n92bN7UjIN zrYJGP)JhX7>E?e7CXC`t4VwDol8t*r(oq6fE^DDOo?ZM~%m)&BEP_bkP zE9MN%=+^9`!}e8^?S>Bu0|@iFyK%w_l-ATe9HI%X z!C&EK!oZ$CdLgZ4YQ*?z@>g&1yH%XAnaqx4*!6Nv>8vV&g`l5&l5Xj=m*3BHKw^-`l;XC*C@5d2S&po zRLzT4+)NiA-Oy!JpOd|x?G3!Z&Je_kD%#~Mu}$O(bV*gI)$igNUQI2-h$!SI>wmE= zt^Sj3IioL_bxt{8(vI{owC8|*Uhl3fJ82jCQoMZ(u}E z4$M{z-o=jnR`cSN5&Mbw!7@)LCVyb%v%D6lmtpjzkw5 z<|lx--6vO(c{Lpw zI{S9ps<#FT$X$j zp8cwyMa_x9Tk-Zfu~8eJ0IJ!>pJt_sbxGV#a!22wbmTIKDDBUg#oGH{3cxKEOsd>j zTYSewmh;hRB0YA8Ru#QN-vJAY9%%X>LtNk14O%xtgB#^i8G+4^I>Vtn;fkDdgEss& z8Vqn#!G#iggfs<7!s`{RJ40{U1MKZA87;#Z_3Sk}Xx9Kl45W$=R(E=aJ%$|5avKTm zI>YjkdWdeJvVe)S8q_Q@=DCqkaNv_PHf8-%PkgbrEoH3Zy!tJC zu@pep?fMyjv#u9ORpzvIxfH=!Hkz=Thi&*5%2~_^_?v*{Dwg`E z!;3KjCGdPpf6%a~Y2gANo@eIH#^+f%>As5gx1LzYzC@JkYjYQI?w@i?&+i$bs&XHp zs2a2Wmx31GAU=>Tj(N%uhCzNk+`mdC$q?CbqM(9lUp~60{tr*hUmA^vM%*O6ub$fQ zeeb{!)H3r?o!b`3uKNB`Tyqz(KHY}ZWEgv49KPQ;d^=%AjGgh>{g?N03UT4I@JxoB z=)njzTqjae=-hyR=eNs`hc7@Ejzz`Ww*gm=zU!K2MNpj6mKFAk!A$NbuLisA`fGB2 ze0alxTe2)ZY=h?LFNH8HJ>?o`*}2AbjB zu5B&YK~~I}d$4|GcQJ47_veYTpV!_*)mc*4qdY}j+A~bNo}F2dTPev_^?gd;CU?#; zk9p`&Nme{CmT*3pV<)ZyqXq$VZ(fwy zLSU!j{QK4i(06*k?lel9tk|rxwD|xUBWW1|T3Rb63&Y}v{F?DC!dCW(!IAd|+EYuC zpFS2L;WalEaBQIyzg_>3`;w&%@ZShKwj&8YEqvf!_~Z)vSV+`A!~y)Lj(Wk`rfPuX zd*XvoO_le~Tsp_K_}C%m>PqAM=M&!60I4v{7oF?q**H=8X*fxHg~K`urD0JEA1aAl z35|*`GM2drSxQR~cz!m0|MTMgyjV!nyBlliMg^Y%DFpb={Tm!j>k*U7mdmk8K9UFA zf3LL;O_eT72l)LrYx&Vz`JXr1W&D00lM?p|x#s;6z)?w;}N%Izb&E&4j7hnLT7Hvtm! zt3)jAGNz*FnSfOv^^T?oH)tGWYv^YiW{(Br`u@EE-eLR2F%NltHlyyr_8r12(&41- zQGfq@Aa0*IxFhrM>kSU*25B^vM(4)M{AJ>mvP`0X463Mqu@D zd%eH}mK~=>N zHa$VVOzUP7)V+E_Jw8-Z83kjx=h+!L2Ob!ESP%Xccrg& zP%i5pWQ3}t^sA~Z|G@oLE(4Q0%U7!vk<+^YPB7pF(gwpQ^_qb(ukHO=j;o79Mo7;6 zuh$o&1%i@}-PLxur^A{TwERV6F2&qdSQC9?=v%s`J(`h;m=_}6&I{2}2v}6+VCaNv zIwqhRP)t0PGXt0n&UDAxZmXgl-9kAO;VO1u@D47+B)0R<%o4Luyh`;{q^Xl}zSo)+ zZ{>a8`5^?hss&z72)~Wd6f0j9f;3@X@S2MY2_JZ>?ClGjI9(gc@WaDI;X%C?hXlUS zp5g?!q4~7GxXkr(J5R5*gHB?o^7}kzPC`EU*NZCOPC0w>H=3?S!f5AVqen#rqo@BI-^Z;TwpepK4!3FBKv^_xVRW?a@L(N&O z86CZ|Nx8ab^cnON$4)JZd^T^l3^v+J8oRl{%q)`m)1MK=I)PU*Y!w1H0>~X5XFBfe z6o~vig28G)rge`-#-z|r`z&dZ-tu4LixV;}k_4P-8(@KI)xd_kUqRcY!B@0i3RR*> zKNTbnv7UcZBj3O69{A3PSuSZQSWqD^)%BC?&Ge}}J(lUlpv*kx2Sw}yH&u178DG?J z>ADm15%yl6@em8g9f zFf1NFvxKjo-SmaDN>pn?T)v$v5#)1R<*&B-PFNk0iIu?J^b_DIU3zm1+e%zQz zXQV=mR}K+NDc-%1`&3YVH@=#ZpifOuMz_g+unpVA%dwNW{5_U4bL(G&-o%y;HBl`p1B_jn=_+B$I8d5Un$dG84@Z zpErbj4qFr-eVs5PoAPY53Kb_(v059Ut*}(!;5qxc??lCk)fAU1aZ_)7^A)Kzd2#J& z46fdOu~la?c%jW*$!n(X2X=keg&`5j9pc@>LfM}GrO-`a5!xO|nbuB32!{}NONZir z`zg=YQq+2}eHz;L%@`2VYO37xsqA=}fu04~C7W$_RecFFuuMWQ5SJ0xo;uIvPMWULz2VPX z$veK$0QvYb%K(I|gTrxhhzHC#Bq<6TSy=w4Nwf(+tFB?+>SPO}l1H*f` zhjq=*1xG)@!xgy?S6vp0VOD2lcFJZ&uPazwj2cgUcl^=z*c?aGNgb|z{6rVV^>iZJ z=lYCpv6a*$n4W^W(jyo3GHR=5<0tLc*i~Yt&=~0`$?XOn$fI@SgK-Uj_iCM+ebeo^7WkS@8{VV%II|P2H$l4Y}xpP3;m+3dfpTsb#bJI*&tU!c3m&zh6!o*=}r zcJs4B-EZ};=&0}26CW`-pNn_n-J$OE%bB)jGk3Yf>g&*xnj08IK@F?FB5s+~+bPtX zWi&Q0do(D3la{i7g&4rF4W1b0>}m;X3$B<+;ZCl?|1iO<(N3h?L^Y%-CRU}5&`?mL* zO%}Sg$(nc-7OuuPD*4o_4HW>>7sI9PQBv6gC%&+Mg7U)pO#IB58KWoN=0wrWqTWJb zS21z4lJl7rlzX-;Z6#g0VYURXzQ4~#&Mb8J6*|!LK-mJqyEGNNQE=Nwfu%h+NmGdz z37Uw+>em{nH5l3ZWf@^*%CI+>!DW)fN;Qo-zDQ~juCujQc|*G*x68S>)w?WLb)4Zo zs+FZ<4gcmK`~Es%aH#t7kAsZ-w_F_X?TAO0Z-g!^isD{*W<%BIT& z=}2Gmd=BX=(v7qL?J_Gry7>jTz_B%s~&osaE3INK(4CaYI4D-@jmi z^UQ1-gr&`~=0kbAFRUgfojN~RDm9v!$j(RV^V&$ZZvXIu1c;L}oa4576*H+jBQ9rh zimpTIA40-{ly6OXpB@fcTI+vRIV8V2D7#JF==2(a$I0ynFF|R^JO#U){?QfvWy>Y- zkq@$Y(>E3f{g|V;ztZj5Z-@LCA7}i#nEh|^l`c6_^n}Wtx@WuqDHa(n2GJB8jLJL$~PeUit(5DdG4Jq0%HEKb|HI{H6 zbWh}5g^oS<^j!!cM=`fF-+w+AFtGSV9I0n9T`76(S)OeCc_T>(1 z%H6hYV@@qSpXxDxc`k0Cr`S_ddxv2d@KL)%FpBGqBS6sM0uqFJL4U4LogA^>FH2$ruOaL+Z0s208L>^MgV}rqTS> z_?@R~dv_OfwY|J%v=;_Cg&1+etU~!TZxUI52<5jkK7vBGF6KA%uLTk09NCv(=*T~dIYyI)1P<>)FW=Q>4gYyrNXYoU7(sOEF+E->yu!rURZZIU zH_jWgQNftjF!aVydq<`Cy=T=6ptlcXk-d%oGxMR}7ESkhuy)!7xF&e7I3XS;i>38? zG_3d9V+f`r&SCE>9PjU$Mk2f4*sg7kk!A%-i|od8L+MZgIrQq97bAv0>a@(jv|@Zm zj`wf|Cv43~4g1D<%54ohj|rqv?f_`WE*o zte46O%GS;;BGwvN>dwyYoTILZ?uw#P_9C%|&&OY#bgZTb= znE7X%as2o7Grj)JKHKo6gMarHV6Zzr4^cVD7FPlX6s_K1jQqRHh#`Ch)kHF(q7IEY%E`r~(0 z^Z>=$>iz?WoCHjN3-f&Yag}`-%^UUnQ!f0c5ea zS5fJb^r%&N8|L7~X^{+BBEkavrzjz&D%3AX6tb+U^Y}e0TECw_d~4w@Z-A7xII$we z?wJOu>pG{1bLh_a;#e6TKh_zY54J$#VIcj%qoCKiSy~vZ`s7&Kt{g6CsQC_0kXZf^ zJ?5&lRLQ2E8?9YqZ+1bmhUw^cSsL_fm|t*<+eo?;Ci_hVly&;4MKH$g*O>PiGU~1J z6ZNySsEJt?&S$@azZ-=;sKj7$0-kPD7@lm)RVjIZ^Hb;iPhyX9OH)#}diRc;k~SG6 zV!)HXa5xJZ=_@IJWs_52C<*y*LrFOEPmbR4S5HsS;`FXN^ew-LlxxRSf%7!a*AG2J zX6>c+t~jo)Js%m}(;Iy$t;L>r=J=svWb71=8iAu>qpt-iuC(}3=mBpqJLS0__0m;` z2T|ksUd^AM_M}U-d&D{8UdxwN!i)RGgzApocF_#s>U51oJvai6=YAJ+ZOrEHDqc4j zDzi_r7GG|&S6Yi|5HG&rW%VK`xMkx}@Y8#(-Tt10N#d0GSG>xdB@Q`4^m=)}yAwPf z@^dt*-?qxGPww`DZ1%g0A9RIM7QR|WmtWw6H6U8aAF`t716-V8*@?MmdNy)Yt|;1C#sJDy&g^h2M|fh12KC;KX-@yl-q^N7sYE| z%5|3$e9_JW_TEnpb1_`XIcSgF9v`YM`ERYogU7#E+Gr^?eqB3qdSl>#U+f=mVnTk1 zaG8wiGZg_iHuD_QXTxpF0oDkoYUX>+y&PuY0rf3@4}C5xWWW+=|z_N$RAU zKKe`rUKC2ZThB*vQ%FPGipO##)!WF&R)k;@!|3A|=fJhG|~Gh9^L4R#-iW_VADhut6PKxBuLBQZO>E@z4}+wdI}qbglZt6z04Q|je7 zkft$yj3Vx3Nh#EiiCdcD!liR~3LF1^;KFB>VM;CK$Qzi6rcAs&7_&hK67Pr(cs&tH z0v8SApDOt0%1Vt9U0*@i&mWaRU+I*!jLB-1TmD!dkwcdX723;_o+jY*)}L{YO?aiQ zPQelxoxh~ge0V2wf}fVRZ~Fru2Cwxm5!&)L{srvq0FFR_`uGkZdGExEnQVYB8%7aP zuGvSAU$sAk(9Uk~QY6+tU5?wi>#?#z6rwNX!A7>>$Kn+SR&vC&Cz|LqLeV_RoPS;; z2)Q3X+U_`frcoC6)@%C2d!NvOZ!OuU{KyWgh@xHO!pD9T`q-kn)gqaN)0`A7l&H)= z`zvdh9j4}?v%Y5iv;Q*y30sX8e#5V2=gXfWKpIUzfxUe~f-5$!`OCk(0Ge;)Ga$!~ z=1-zc9p07?mH0Ktvk(TnVC{0e&hz@UxY8Y$VIFo7lamjfcD%Lcc`CMhZ&nk&bA9rdEXq8 zKBr1)vUgLWw>6P&Eq+PS|1&&+RKl_-jZcwdX~})r{*o(%IK{`ev(1rzLk+K)%G6B0|#gpcbQRUX2DS(DK5&#Lc)vfzhIy#`-4 zk>?@?*fD-bSv@|Pnwo_yN`vw{`Hf{!9PdP;49vj6%vU~R4a=Qz$~Yz#5}lFhyw7<{ z%aV9O+uOX}dhd!Cw?N$o4x@En?j7rc5UrHO9j;-Wq(7tv6Uor zYdQaTqj}L~Xgs2w$JDK_R5;O7FkV0zr#pO)pvc4F26H?OZ4N5Cv5B$rQA9Q7^xfug z`)H2ZH`+&OZt7P@`o)-yz}^}u;_kS1|Fj7uhK$Wdiuuh9l(B@ZU5VSn6z%SznwCjA zHGbDwvzJH@0K!y4`BUjA{Luv>mZ!X8%i!zQc>0T~>snr;XR@j_)pD436ug)d==Ex*2%c~%4TJbqQ=Dt-@otNE0je14BYEdF*WQ}hq)zsl` z>!OL|a(6V$`y+?nCI8P`r&HrVJJn23CX}tD2H7kNYbMqf zdQIb@Ri&7sGp&1Wy2G2@jehjunb|1U=^-zKBCa>0jXGJ+6yp6Jnz!|5w* zLRnYxpF>9-p<}s5PAlGmv83ooEsuf?KEWhJF{Q`QvhoiLKL*PrmUEpbm3u_>Eq~vX z{l|FG_~7kQYp)ri2!0a$O;z-M?4dJ^fdx#f+{p(`Bh%(?+_*#$e zU1lNVzG(k5!^BF6$-?L;U9(S-pRZG_go$IU#CzGCbFd6t4Ue&676;G)Uz)pCRz={p ziwWCG25BVKG_PbVCCgpwQp9An?VD=na>A(ZF;DC^=jdxLGG=gs(xO>mtv_azb;z$V zMzxK`?bdq*%JMf!iT52cYKDZ;HKdc zyD6uCS5*z-5I~klS0e}9wJoObC9wiaHzmsFeevufYf2tFTlZFTZBfZE!NKpT8&tn+ zS!KRr9Knk@qvU$xAakF>vQpVI|2wle{4S>7dT5WjthOmaVSk8_JkRXW4uTbqZ zYeKBX%HMC(G6!BDTUN(H-do1}II_}zdW`j9;op(`Tl!Bd4wuK&Z>@U- zvRI1Cdw6DGM6@7(k2?7}LywrW8@G<>mu>lJP7YFRBZQ(Z-QbRg3^|@tK-=U-h!x#h z?$4dn9GVMB9~7snzcYz^CQZFhV@ZTQS*YZDViFIFVa&lteDu`f3hKvCTp_o!bd2=VgoY;@bu2E>0?<=_k;ASq~*`RSF z6?E8VnYu1IkFX4C#{v?{#oV0LUXj*Xr75^xT+)-)*R1%MNQrC;svw(tq;1a5vXIAU z_Mq7yemoDWYw%Lqq}$@pq7^Jb{kK03qM&B2HE+B+NbhXo z_fYxd+xRq(d7m#6=S=tAJBP!Et;^d2NUcPC0X;l^(u+kfdZ@jzZ3~~Yod6D-hveuq zzOy}hH{qOj<%`Cj8%>LhrFiSY(4Vcmb$7ix3@0B&H3V*egzT*<_89Ng@yu)Io4I?5 zwq#+BO{BlRA0h81x{`l;0CGJb;4S!?{Y)jXPy0%her{c6ZR6+cOL3vBsB@8wn6b^J z4g>KEqWa794Q^faW@eYVRceb8du#0vaA+8Me6Ek@b6kbj^P}<{sOxJq z@|oV4QMF!(|2NvFeRL&s07VTP@ZS(!gyM-upaUffF>>q1>sCXLC zIv5=$Lt%$@6?+8*A(Kq`o}aY{q(#` zeDSJXYIT$zX_M@rJ<==11U$6TGb&XL2Z9U{H zhla(_V~#yjqv=#g4(9jnU7xUsfw`_cdqFPyuvdMlrrm1vEMcA|#7?0K>B02-4U^mR zI>s~w&@p)VIuo)h)|&^uMp@j~Ci@NU1S}y=v~w$4XOYN}M4?xBp(s><;K!@kr#V$Y zjSKwepbg7A;t@d>E?=#N?-MiOmU`OuF#Pe>gM$UYEy5C7zL?iC8xUYS&bKYSP?4Pe zMd!i%S@$V*-+B$xxAt={L&z`Z3ZIcjO4$7bp_Cv)|M}~4L*a}T`%l$dWNj_i=6!pj zxjXG!*4L2z#@c^=DUCW-vF~_~ekpGw$S-7OZ3zX>a++24j*#oEsXmo445aPwVT(}( z=W(7PA6Hdvj#n#{(mQMNd4qP^_1`$_GFH09N|{+_NWUM5RN66E`i->9DL0xEi@d5J z_@WoZa=eYq(<*ZDWO>UO>SMrym#*xJ;=4v@vd(I>1q3;F}k zCS63YqrfZnQJLkZi`$uYDtf}IlQV=!hIze}aUWE)d^`GdR%d9LWWNlKsjw$TxdL3H zeKGFhHB|kH0OYpZ>j8M`0jRO0Ebhgxe@Hp=p9?{}+3`i(s_$Y- zZp+^McUDY;DyV$G3pn}@xVx4gp>2|R!|zXt-yiv^-Y{I;#%JT*&oaI9pT~JB@#@g# zCA{7$ql|k6ery=uS&9qYvo(}s&Y|kzb+yL=*OSp=;(|*SzbzM7UDUv(yGM$6C{DER z9fHI8eYkpIzshZyf!A$(_c*((b|%3I$iXEKi|S=*{+yY

q)nuxPRJ-?qZtIdr47 zYSQx?qZn`N3(+^IiRv)dMU)Am!A7|LTY~((o#!5#OI#5VRH5ZJTii$_Xpg1SW2G2S9U8pYp`CYG*uFppurS~A%fwpc3#&hx&Q7@Kv2u3th5b-5E6}z0( zBtkxV(v%D>9{=&4Gzuxi*0CDe+CO6UqSL?ZOR9b&oGbkG@1W_b!EuKgPKG19>b<#L ziYD~P7CE*ha2`Z9w!ve(eUW?`SYs*7?C50C&b(TkVZ)Znu^{B9&Ps{}I}hBu$4ONB zO;U?yab~cPo73SU!o(_+XV~Az2alJihi`M~(2PLpJFvTpat+BPnaIAgA^ld&dK`MDc^oV+E8+7UdB4M{J zvr5r(51iJ2=(KumbXzcb_)6!bZ$nG-|%LtL#<$5A@RS)$x#I3$y9z!?t}cXd9g*I0#N6P{KkkNP`2k{E zUH?hH`6{|Br7Zd%EePoHBx!ojYv0H#JD`52ls<(6$`h@X`@ReabkI9brcmDCHY0jz zU)?2#_tsCuAR2G9O?s<@aX3oepEoSXu$;>`;ULUDn5&e;w$g!4Sk8CuqykF)minIsMQXpezM3i2#exaal+m>$y;J8%L@b^{8|JP1eZa!E<_?pA{oN<2G%$D^Y=yu$TUwk5U+Tf^eeNBc0G}fdw2p`vScrM{KB55M9%duHY&-;*TN4b)!NoViqAsNjvn?n zq2Y}{82O|*6yGp}aiC<{>-j?Mo&FP@7RUjlpd(?k?-B36+BcLuU#qgBvue3`nZ6?7 zUmwpiEp_C6u8jXs^uiHw&#=L3w$Pmk7ZB|}yY=KlRWxYq--#?wN! zUf!I%jXg%GD4;ugug(@yz(iIwvh^)9F-&cKX(MmF+#H$6m_lNk{qwd~!wwpjUU_8{ zTnt(uj(NNmg;S4Vy~mn8gp65|nJVE@ejk`>Eh%Gvgg5Ne7SgUdnSy7ANJUPg*Pi1j2B|SX$q=Y7g#0MT;^8N|404_`Yqyp>VL@x#mGNLDV#&c5v3WvU zW7R7!kiHtx)I%C)8umuSRQl=H^!{|L zPlDxJR^etZv?R#|GeUkUH}U0;y^m^5#U#zwPpu|m%n)o&u#3kk^EZtHh*g;m6lRxq zB6USb((K{M8>dqobD*nE=M1?B2>k^2u=F> zUB2q6Ru$=>7wd)PcV9TGY0X@u)`==WtTiSGlq|G9N6Eabw%s*REr-&K<`Ya3YXPDW z$I)5SdqxcvP@rC%WUi>nl^IpuQB$Go5m$CTzu|*rsz73tz)*ro(EP9EGSS7?D)&Dn z9f+CoU$40^&p)r}U|@~A%eY7tG@YzJ8+VT&n|q6{UC>l(7rD2j#6^|5u;qKY1(?q62Hwpqw=4CE zmPV%eNX;N$n#3-e;7lk@7qu|zK{Kv36+}dBDz-~UllI!!zA8rT%BbjmR9)zUCH5;3 z3Z1uxhaM#r?!BrtA->;`7=7$Sbz8=(H4?l*+2cX0_(d5!imYDO?SPe_y#||?2fsPt zJ$4A`RfN=;hG%}Qe8+r_UewK!gy5uh_+l-f$)j(SzU205JydZD7)xqeDHPx-UOHvXW0y4L=Z-8Nb92#cJ$1-_2i(~ltC z|HapFlh37fjeqt@0GVsnXek0>vn}ehrooMMHpPW0dw1d1jG^fUf=&v_AF&sZi0@T{ z2qemDq3c3Vh9Ef?)TYgg99+k+V}EMmWT1)r9Z+qH#4W#w`P#W{r+>ZD3DGX98qWTd zH1B4i2)#;OsKKtn4Kn6C}N`{ay1+3;-5U(KA-pP17QX~q&{&?{?6fvrvqRGPJ zE{~>+*7sG(J4-#hYVa+_=Mjz?Q5A(NzDSD1uG8ND&330N@K1VIE4B-gY{4i71b{y{ zE>${z=ol2gI4KB)WOD_ztE1~p1LDt+W%W}fWyOk1@1$i99bal(_~In_-2*>zkPLe`v>TxCF~O^Mgv&IpHaz6TA^%58a>0EW7zS2@Q7f9A_(W!)e-`r+F3 zoEx|Ju$Fu)jmz~8*CSK^j*y7m+-jjP*p7Z4H-nWZpd6q0v(v!P>MHMcIe z*`mKG0-id0_QX$#+Y?CK!5`N3ProeNW3;xV;JVLRm4c#3bwmeJKzm<6L>%Ki-AU%r zWMOE#^OAG78O(FAv<;gDFk6CCQN&gPLuCc6%FF2rfAIM0R7VjsE?9p zNQr}3m>#@l6b;6BWkGCGY#wX4L;6tEkj)u?rP5x;!LyiiBI{oao?enUK%Erwk4>)Y zpudxJ2mf*PEeAZ%IeI{R-Ta`&C*C>#&{ehlCme`?$gik)2=T4i?%?BA=C7(Z)VLi&(jo zqB^v6D-o+~pyDV{cT>ApM9&pm6RO%$jw|82l=c*nWJl*2M*Sk%9E^WRl9jq&oh;0C z7%1Jj4dAM0da{uC=IM!GtBEW-GKYlBVe=T?1nm};E{qAInM&<#CAsSM1st#I!kz4n z8Ig7iCwh>U(D`jUBsd)g{@&LBXOY zD5_iGBx*h^17!}ocD~AO=~}4jitkcInLR#hlQQh@((H7FmlP{$NR&CTro6rh`BBI> zv$*+7P5a@Z7a0Mtp!w{lOsh^tx=Q`0DS(xvWb*kR_D|aFn@^o#+2pKC0Y7J@TAM)j z1QEI_!QEvmmJdu@;E-)t$j~;`HKUPJ7UyhuCRV1vS-|E16m7^T`u0cT|HG^P`87oi}+wi&-crrHwU0|a%=!fem)t;zv z7w6;ZvSUq(hV}jj=8gJ>Gq#1=m@*Ht#KV~!2^zl( zW9=L*1NEQO@21q_T7#<@U2_~YB;&^poA4e*tyx6Qb0>TuiWjNrO(3?Pthwq~-70H( z32Al4Dox2{EXS_$>#mH9=8I?1=XG{{tq-w&w_7eVkXnVz_j0OATRk|U+Vz?nrx=5dqBS- zELX{MBrMZ(14Z8ui1KN4n|{kyt!m#IKQfW`?rVs2dyE{ zNJxUx#Tv*|g|OYHB!8KVLZxWya<-A%d{-D7-;@CUXp=oU40vBG-|M2(>_^1)a)&EJ zO=W1DiGs+rrM3>8e)-`#5+5Cw?!%GBu-iyBO1f0gnMvg#T~M!K9QD%d2Zq7H7pJ1$@^SWWgN9%j@o(l?Gzn*%TQ=aFaTD0ujMj=5o4?^jV_R zk5*6w!rr{Ay&((@NqNpFYlT%Q-9BUD?z3rQCXGG{I|MhG$-@SR>h;58>iJ27f*LBA zJzR3<#+ey7-~(5kmRI}d;pC^y8;@mgt|Dml+3$Y9lSW|6Vd;hNq$4qUGASmiXVHk(w_XcfNpcNWE#3a;*m7?CrQ>mgRRujV@u{k=`kg6a{b6Ie}k5VD2qDzzHR zl1?vlyS^7y>g}EvPa}&*5J%L5v1KB;pA*08?=uV^%<~gdv!%_c|4$%pJ8@Zj$-sn# zODo1P@Z2Hn{moT;hWXl(cJH=dqskd?9E@J`N`oKLcKRl3yf7W+tcwV^Z;_p5wGxV% zOt@@s>y*}{`eT2&K!J2JjfO9l5sN{;89R|uHbmO3mXCn1bn7JAlmRS=?LH!2(!x6O z&i!>Q^QpIG*hXQ{u7o-kV>rp%KDi!>!TH~ZaaZYfGQCIM=_EyXNiGr@FlCx>~rBzF@(pS%bKqEYN3wpz6IJqj|J~mC9zEgYgb3$rHXga z%W<<0!aN?cW=zFCJnDtn`E)R3KV8gEO5T=$i`PFL`S&rm;u1Iy&bch2LSad|eE!{l z;flvSAiAxzO4VMc+Qq12oxnyKC85U~5iDW>Ru^@)RK3r3%e|GleuZ3dc^0WpH}PN!#ae^j?#c-h|Uppqi_gZ%E==c9?eN!g193rkG+7k0r( z$p;GvX+qi9Tf!@~EAx7otNV2JaBmE~is$#R-Z#%mFaFn$nuvM70da-#!)j|;>)r)k zAJ|1U`yMJL5Rw&6T! zI$9$4_E?Q29nbhN)EC0$oXyYjEOO%-}DM+L> zTp9!zAoI$6-b943#vzZFlVl6<+VD`(i0}1+i_pC7-yy8?^!CBakrE)AV)Kxw4fcsH zmDleG_G5GC1&0HOwY+GrPI6G{A;Nv%eE;Q=c8&YD(oehBoUVYhNJXFH%lPXT^Xa!c zK%q#cH!lNQr5;naRFLGo%*qUu5WFBR)HJ(e-%H{2zy|JYZ1~whTYAL(4^k1m3qBUK zrF)kn_H$Yd+*t3fd1+B^V@nH860^G-5=T17%*wipB(5>=I-^t$z!)I&p`5JGiV7zYZDopq~q>6jY78f^2_T4R0iyj z7!@kU6J~tAbZq6jVqkZ>NZAu9I&m0iu#(lLJnGI5+`?rUon9tIRr$ zqCUNoTal`fvv9X5*s~Wo^<|sY!TP~it6|T-9fD84iHB}lhuH9yEEX|8pg#u+W=dt5 zc(8Q4HWwsUJRMc7-f|K2a>r8InF@sJJ$k+rL}hT;b59&Y&liWoyzaxL3`@C9qj8nR zxFl4BD5ovM^RzWD1)GGg*gLKxfw*JZTl%5AQ-1VWVp#)pa-zgV*n944ZB_AXjRfG| zAyF!baD+M71nK*Phrxfjpy;^9N99Jq{O@utU(y9 zYZH>76}b-rmE!j{tn+#OQBk7CI?3pwH}^}rlX&gTe&5-KkJJ~!8fC&G|7O!oRpmQc zvh6>Ixi7Wh{ZL1v*EHBvXbZGt(KYv1$(P^gMq+iXt+Io`%)z1s9hgd!2X;j-ePc`6 z^M@New%}0JrdQQYQ*~JsoMG-0S`xgPOTnm>jUT0dGVZiit(J-w_GSX1NW9>;Nx@dT zUFMJfam_X3o7pk#*BoRuq1J}^9K`=<5UlT1lEDvcnlr`*>U^+FvyC(s1@WWxeS$%i ztxluc6FWNNF%cOqHe#W&_&fPOgX+d)j;X*r&L`+dioM!gEJgb}s$PqXC6PTb@b8me0-lRd-?oo z87^#s4HkPSZje}npalKFcKh&*-6|^BQ&X8J?(&toU~P`V3F(iNU2vDB5z_Igt5g2U z|6v@UXV*0zr(i8#zo^D2ktRmTH7{`YS4Y>C6z!jzGEBXGAocp@65O zsHhf;QUNZ(dv>Q){P$szJ{xJ*CF2l=DOLGV48mR{$`_IlAS=o!SQ8EVv3eSUQ7qS= z=j8avO9rIvg1#12U0QnAPQQVl7L~3(XQL=sfO7dQE^7v z({`>Y_y#Wr>YqeL3Pi})V{E4+CgdWo!R0xG{MFXOs%v_f9Q#td z&pmG|ow0>SU|G!ei3F;7E_0k_P@>p4b(vgc>7%tYblvvGE>r5Y{# z&8a_agFDdIz%`JTqgoC#$VZ)Zc*S>L@af3BqTUsn%xVPl!I6hE-5$xa_2YATbqvMO zk{45nnl$4DqqS^>8hsymMQQi_nI4~*_!Zyu)b`t za94lvq6UzfzbO>3*$IUM-hE2T-}`v;{_}oEc zDDYu)L0L^^OKxkBdYxLASQr^;s`qqH`mNN1xRp0(n*b=JAeRwq9jF&5iE?sTl*4_Q@{RGPL;Z`wFIj1ZQI5x*2W?84E6aB7OK47x-L1hyR z;heFb5Q?7=rjA#N%?s&`=9tKG>VzAhVfto65@u(*tUx-LQ)rnswS-p|707?VW76N zmY!k;xw|@zH1q16YG0KvkA)@f05YjG1oV={Y1yi3tgfjxud`hvxmk(+*sD2|5G``y z477_ZtGfPf>v!BW93fn!nPJ@Lh<=z9%d4Xh;=j;^&woSthQttYSY* z$sWB$roT%>HJpNuTopgg2oF(5=xT8NE{D@VlomjRgMBYPN}{kKDTY_~{YmK0oUob9 zzPo3i9A2-adDexQ>q4H5zWs-zlr)&-enfmvQ`~P@cB_u_flQ{pcub()4*!fE4<9tV z&+hNRb0TqyOt$Z6X_@l;x7_izocvL2PyH@!?2(?EWDO&J2v#^&%WoO8X=wMRv`IsWq@{NvoMfAN=x2V=DReXX{@on{Fc_H6I^66@0K?U+lmoIIYySQV}ERPv= zz!x8XaJR-Cc5+;|_`-nrtK8=-czjHu^3xC_kA~o+iwhMk`_puA$z`!rj*MnHBx}w! zdHOzJ0M1Tq=M0%|1Oq|q*&Q|q;kfaAFYvE7QnQM12p3anv5fmggp@QYXUC__!7u3M zVZUnEoj#F&QEoRA?-;&`l3=(!w|vgkc*1+FCd;-Apy75g#j|huFflAc({jNmAEs(> zJNwFL2Sg(vdLlLe-$wLpA>R=!tG$eAOnIXNsC-u$$@_60dcKo6+*Q-PgR7I4#qV$n z?Ychu4I$%h5lZ4d?@hN8Wnb(35Tvc9lr+1Zzr!?hO7t4-aUzzczX|UaA{lg91U{Ax zBHccz<|y7WrLRRpyjuCJ1_tED-ui)8KPi0bPYOTd-xR(cw9X~fp1Sd3a}l&*ALM0O zV=WT|hD~k70t))EC{JCV?>l-LF7qDf>pwFQn+^SF5V%hAcNzS8q7Daw6f!4#a)xXW z_?k1?(C;4N8~}^gTtMfyW|($3bdB+Nu!c8!g$iZt)+7s3Gn0-lLlplI><&u{tmCpJ zpZ|=TRO;+<2ZrY~xJRXxY+D)mycs+B%cra+b1+Mn3CTGJOs`C7`2lbre?D?o$ggO` zolvYLu*Y(vlADrNjtx26|N9~;b5K0AG2U)WcmRDd;Be!T^S0xm0)kr1x4-bQJ~S@m z`CSei|A6ys!>L@EmV)^oz3heqSudoqB-aPh(($kXEig|#%@(=suYTgh7YL#zFH)m{7u_u*??MaAwP!hsN%m zJ`GwFJ;Zc3O{DqTtZN)0Aj>dXG5NOpcM$TB@pH;3Y#_}z7>x>_kkW~Uzvjd>~^2P*`1{y~9O97%sPFot*7n)P(5+|uwcHO`-IF%+-0 zwov_3-Eh=&I$zkOQB;0EQ8k3L_iV@aH9XgPiV?n@ROkb)+uW#_8yu;`!O0&cUK*Wh zJ+aVD`JP*Ez-x~^lu}FQ{mw62on~rc?S~-+h7mFA=I;O#Dj`<5koWj0BfG>>U9cCE zD;rN)ICuRD!4-hb0k1%e?aNy%dTlpE>f*&YxQsVnZ*|4-iw*5C;hA$;W7`ISd?*1+cYbVT zQ8UF@sH~39&fcO|c-I()bE}kF8carqCtZZ(+c;uZFkUEN3nAkqoQUP(k&>qq{Uv9# zK$6?czhN=qMyAdiZ${bf|JrcYxxKZdn6p=ktdp{EYwTl!EO&QFlPYo$Cf=-QGrSVN z_lZ~-%{Mp21Ff{vY9eWUsV%`g!0iM9k55HDW3M4li@w?s3AJ}HxaNt5Ux}YdlEm7O zC6WOos_cF+7WIGeCrZ9FKTHr55z|R_O6dE88_h1?-~p*)CH<(mR*2^leyW~#?`@@8 zB^=ut;XRL2hl=aLWvv7y;bnV;dq~K$HXu53`D3P4Hn>u5DKvg*zH$od*W+-Vf z@^pfl*S~-5^Cpz<1Bo9ATDQ-h{%!JMv~~vVIqFhrfJCsm+DEb`bF{PxZ9EIk({0P% z;ZzSLEp_spT@*DlUVDa5r17jcZd~UtFhBAB_6GpPQ?uVmBOvyccEB>(AFYa~bR>j6 zZD3i%03NGr$dwEk5zNgMLy|lk17E(MN2sXHI1#0a{Oe{www_W_Ift6*2FP9P&8=%W zpZ@VY>R$M*ySa()Vkp8az_xU3^QzJ$xu{YC1Z<}mYu{6ogIVi=rW>lUO%{~hhy5*H z!KSOlE_K-H+vFSTm5{@mzr7jgjv@vSa9n|To;sTpngR-sq_MByaftzOE+a}UJ9Q*R z?-a@K*G{tZ*2k6u;^3p#C737RIp+(raI-381Jn$RTzx*fZ>=9i87S~yU9P~pc1w#g{vx_=(QEgw+s1Ry#H&KYHFzG`Z?zjEx~3@7ELEiw-1#*ie+tc4+@DH0 zPIU-?hmz%IGRwHr59f-g*iM~4oYV?xx9I4bsY#Q^Vt>KbpLD8g$RNHh4OmJExBsz2 zz3ys>eO+BmUdHD)!VI{x;7V{Ne_yzs%rbW?7mRfndD5b>Pvg%E$|CgnFC;0py1RGX;-86Ncck?K{-d$O~D8y|Gr=>86pcpR^ywitWYTeJt1S z>J|pvjCZz7u&1UahqhH9;1EpIx!+-$_+73Y!D?OE_5E2TSY(m|Z!&Zhn5XakGZoNc z8i)KK9U$srs86A&qs&y~7^lBoGf2-Y+?wLOX`~3xF83h=>sr`D(j_gy%;xblR2`vN zxaCb7d3$EBu*V63x&^J}Uq^12lGj)Y(TnGUFN)E=`@kNUg)MAa0Y-iY3}iFDtOT>HdsjrQ&b=$_wio^Tn%&Mi{0w8=`b= zhY|`7IRoE-u4>bUGVC;Kep_7&S!>D1#*b*^2Kj2;Q@^O(sPIwy;+gNhQW8nWKR5nO z1T-xG9TZQP3L7CT?NS+j55MJ^xE_15J9e`}QYlx;-2EvtGkt^LRr>2M7m#yn*N)HJ zoz8tP8t5QS`RwcI2N=A0#$XI;;zjZ3y_6=GQuHGFGNw*&qdvK4(7B`g&oY}F{7uM+ za==+fmu}e4E}Oj%lc}3sHexOj0~2c0wZq;C7DE?&K%sgfrcTs}B!ARpGB&vUM920P zpQrcVgsczif_Oo};uj5w4ex<~ewguQoc)j{)3|ih7iA?#;K=%=YoWP!3F3t=OJ*0J zJWLBPa;bg30{Vx`J;97IH&Vsk+>NxV2EDz8auuN#cfqNF*WoB;$JaNZR@Nm^gKMcdTt)k z%3t!?r{C&X@Sd>B%zZEG1saQ9OU|K6>cq23)~1sluzltkvba8F7;@L7krih5{ebY> zn*oE#@h%6Gzs}k&7r=EDvmWii%kk>Zk{JkhUIy4nle^MSprZxG)OXji<54>ym3Icw zPg7JMw6_L(PG8%rE=B59wB~*~))jj!rCf-j><9_dDOvP2V2yM)N|MNvFpxITZpszv zNgkH69=$a!;`PVBoeHlm8=;n9{wL;d&;Nl-GRxXNfc@0%lHj5W0euc(JjSmjfJb^P zh4!ld4ING3SgjMO$9biIH_-c^xfW{EFiGb2P4%Bppj|OH^wo>L zPQ_~O*+t`bC3CWv;$ah>ot*Q1UMF-613R3j7gnp(VTB;fomTvp+vs*CxBPW_(7C^jSz*rKDnjgKG~LUWqY82 zwXc=uU%jM?i#IFW^fOclL;34k^zq#1Wx)LtQgA;TcDX-mgkDyTuqwYHHc)?_hCK0E zscno83l%87we6|U)NL96Ouz@+Ne8^OqsnwrcVnH)hzNP3L{YFFgcA-ZsmyJL6H@;S zC+rciIAAmWRM%77`5Ck6NO2>65o|G4@4>3af9=D_2$$A%mQ!A$7JgKv%09w=>3qsB z1hQI7W(-RoD?@#S3;2e4@}bN(sbr7As?>;eYlG%4YOcDEMb`z$xJWZ6M4Hfz;5p1` zkT;YHm>BI3tdaBYuG|fyg)2p0ZOnMB(TUNrb`5Ryz=2#cG_#owMfUj4j2#oq#J%$N z)b;H>tfc90?!9v18lA?tAC~o<(W|%`TlO4TtKISnzUj=w31w;mI~yMCv)7%z`SEFAO|iHaj9$letY+)@hq6C8zYFwiX& zi;dSTq$$O%AFcH1N54sawCfv$V#q=y);%AJyu!^pwvc{tGu^NY(sR}cIiIh~LCa~I z%n4+|_YyQlJBS)rxCM8fnFMyXDjM{fkhs>$$$Dwob|xHBdN1gKYS{xAcm;CCX5QUu zf^6e6{-#fQMnzh6JbvYDY`b&w^pUyhm$5%B4nh>l69vCj@MqCZVMK+zUxb;fa>|PY zulj|($tHSkEaZ4nK`Um4W&fBnHhEWF98t+aC&O3r2+kmxJ%Wb2;SS2p0$ylI>fH@)F&iMydaLY%Lp&9cVX_ zId?Wi5@MSZM0vDP&kc0i5Ojt2w!rm%EXN%TbSdiQE@X*MJ}DS_0A%(ajk4pPTA*L5 z1oi$ol6?5Bdw2b{9Tjp+`iZUEon~Ivnqa_vXd(eg=;@jqVcnt=^VScYIL}m#bbp5> zdO+ukp#qb_r#Cy{vbjF@}sWO3xoETG%CwYFtPkkTU@d+VY2b^-idu~Ok)r(%OOic z;ixtYG&vCgXcQ+>O~n5n%cI%1*R9)Xvt&&SG(h;5%f1&Ja*2oZj0(5JMO~TTzpO>R zPZw39H9ag{K1K4Ct;n}8bU74-kGvD!S#A=95a|7;>!0~cSx2WcrAW%URA~4pWU(~} zxp!nzsPm=w8~L7J5`KSVCotL}-}czT1Apc=d1Ye6Db2?B>>OP0{W2$?wjzXCu3^Xq z`v=23)4U(tddu4G{lLMz=P!df@SGUGH9eeJOFRAqC0in>-?9(H#%NC6aS#4YU{bff zExOEcrEeUmxS;C&piNA3n&dK4DnBvy;Tl7{(Cw%nrat|ZhZLsq;+|2p`AC9lRo;JH z+`~ocx71%W=>7ADY#(w?^Duk;!NHJ2b$b;S&&F!4gX+TWvftXZ?F=qVdVRjeT9SyW zx$CNxOeP}~oZM>k;MQF~3w!+a6Af$IAmZtyvpf9rCp41fi@&A9K@nQxC5o7b02$=h&wA#2Vlg7BIjp*lSd9~ee!Q`x zZ!cM*9aa4AE`U3`1T9{Nd7dV$XQf*6ECA;Nm4ehoxNJt6N4{MRd=s}@uMqFb8fx8 zNFid85|p{T^?P)5(Ho>MLU>^2#~yrnB^6f1QNu^!Oo6z~uYo-h61R`Sw9h~<>IHnM zMkkG)k*B7H&m6LuMNoy1LC1rjNxqd%_oXg!j_%?5SR}IpditsAb_a<)w=#=wP}K0o7kx)hjnH{53Rd);`&Iz!3ER?!upli-qz1QU z+}p^$m$kZ9m4s%i3vuLg1~ryA*!kj;lWh)5JPBL4(yv$qN6aGg3g-Yn>;N=LRF4imfEn=1zEeH{1WsQ3djaf-x9 zDUKKg@vSw^d}TTf3tHCSrx!P3hdbnv$L@S?DQT$Xa0e6sv0wT4_|L^GlNX1G4%f&rWrpSm)^dJVkXrNNwzsF7X32`USDI z+}H+XFL4jWXo_xeT+FCcA{a7_7Y@acj2CLooo=yF0>&AB8fL)r#k%!4KXOWEeieyf zh7-Lbx|HCR_<&Y!pi<828rj8&yFot!I{;r+XWyije)n~ztvpwfIm;6WXKX9 zA44BGQF2P)aF}JCLep-5P)SV3z8FCv^t+?)iNe3iQHXY>HY)6ulgZ`Q?yd4w)sl8^ zafga+nV4xJCto3yQYR`&&KuVFz5~+qk+Pt0T_zUMrT$@7MSDPKhegUD2*=*e)mgUO!wuI%E-V zxkY%(yr=Hi0AnPgvL8zn5o#>H>sE4iDB?NlQD=|H{Ca#a1OemlV$wGb_W8qMLv`!(@dIGV*NXn#>33RgnR>oIdumtu zxvyDHE?X0ccEP(o#XPhI!i>>Bg_%!}WaBq<6V{ShD4_-~0RjlF|5=qtwDRh>wfQyP zcy2W@WN_Cf_u#Q#U2%~YA#DnVYN;@8_z@DqLuvIe6T@O1Ibm~`luGec+rR;6kwLH=tMomQ51CdAQ_<-p_CV@ zKUxDzUonzI5CwDHK(pYq02nj3QK*KEAgc>~_qY(&=Y>V*>|k91P#Jqsz)~~DLmwTN?K&)U; zp^NOofcdHj-u+U#{q!T%z<*qkx47-g(qSPwH>NMX-mVz};z?j9h9i2*PF8=xEPZ7jq3naU=egJNVZ1)eFRSBd3%`Zr7ot1YBO1t3fsieh=4Ma9U`*Seiub&0`i_~~!tcfmDT?d6!O+ZbicA$-DQdwR98Brb(RxG@dX@LD@}jys2JKI~`pyc0 z?xJZ*HrdGVGQ6c!yxK3YWz$EA@WoD1)G_J=!ID~!iI8i*r)z&0Wr~2&vum(H_Uh59 zN!GStq;fzFR}eA|+$6D zrd%^PQAVALRVFCICMM0ixF2Xj}Qh+ z%G)epv~ER|{J%3+9@6qqw3gD%{)(_=rf0=^W-l^qB1~d4&@GRT5+>){hId9ag4PZV zK8V#BuYs=ku^C2F*jl{Se`mBTJzk1XnUpGFcd3sK=MHqY%69u;B_;_rG`JHA;u;#P zG%0Q{mS_{PCW{)%E6P9PZ7O zoG&HM3_?(VRmPZqm4sn1QgS&yLwCyr1`$H@aVO8cWuoU_S%r-z*DXQU@crMN*Ypix zv!Ua&OY-gV`l{C=|>#3O8mYu5T@SJhV0DM$F&z zeT9$PytglOH9>auN*h)>lojlRf-)|9h~$?0v^x8DYY)>ljDkFT1C^drzO+V|f7t$p ze8xY>2!j1qt$rscCA0Ul^9TSNzjc7V?PRD09Dc$BJX0vjt-%~UsQFhRI5k|Moe>WP zGcm*z%aB2@^)r~bww84r{?I(PPka~6Tl|On1yBU0-6*uB5Iwp(R^HRo(%I8{Ir|S(WDOL#47zGkY$`ou)#&0*cmz%TA)fLuQQp2G1GOM~ z(0E_SLiigi?UDbD)uM453&f;=v|>qQU2ghnlErIwi6i-`j?c`CQFRs6!$yTe`|oJq z;U#q%Is+*`ttYTf=p#EGcC;C;$(9^ie06-~(>RyA_j2A7H&ecaYSX{H&4)$4Jo29` zua^^6g#>yh$@K|I0+P|%^V@MHKZTJdw*zx3bB5;g10Gc5+oj~zzLy2PP#os1o^#J_ z*k~6NpqU=+g?R)B>TEy|O#&JWf2&gor3$hAynawKjyMbxF_Wo+re!>y=DzI1JX`-K4$JrEz zY3*pTssGt^5tBQ_CniJh>Mqu=wb!YYNk$6#D_s_t34g-@<6KPTa?R2jUMa?bx-aw3 z3MMi4`()VSbQlO6Bji6#vIuYoB+5`0B`$DFMdbZuv#;zGAv|Q`^?1p~ zrEznQE|aaK$A6E3i*G-eCCFKsVN*L9=T2Z89u9zV*c3 zhvHUe?va~ts`dgYG|cVCBNNEDbA)Ik>I6H8=9gXTfXN~5(i*bWdc zO$O?JbmXu^s?7ll55$VH&p^QHETy|pWtn3|Ltp*;~o z+(%V5`(0%*`+TqOpZ9;u&OQpsq{scVRpL^nMZ!dyru6z^KLn-*ENzX!8CvWbYIuyE z-(HFv_gA1SL}qrK5^^FSiJA&>$30di4g)&AwX1J3>N4PuI<_|!FRnQxtc9|Su@eKd zOWkk_s$i$EnGNih%DOT;;SEFqdYz=&zBZW&c6Hj!qOxazy3?AX4*{q5vorNas{;dSdqjw+sU74cx>8yCY@8sOAE&@XJR_THb|vCOIFAL+<*IswWqlGsv!f zI}1bS5oI~ldn}Z^@Y8T%Z0;lwe8}^#f}3=HVaF?JV-iQj>FBo)>b@me_~OLv(nX9> z|N40FeZz>MtGwO?~Lx{b0{N#O9nFs!|eY~`qq!4n57wB7!GMSge}G`L{GSR0jc z^Kx{tg1hUR#gb)f&iwqDHax|-Xlurp3#YBXg(rdprTY!1iWO`#7%M7?PBOB}X0XsV^=qW^Q2WWGCA?b3tAeJS3PY9^Z5z;fo@ z{1I#!ngSVI!dZ}Y&QBSNO-!l@OBnjj`%CVj?nQprH5Mbk-j%}HqB#)Q%{A|u7Sz52L zZfZ2^dj0XtZm!Cu(i>@i1;*~)s(`-hDMYGg!_RSui2LBh}|uUf$l9z z{onLQ4v51OE}|!WU9{j=Kd6k26{k#$G16i04}H>}-7D=nJ)|^ODoOcRbP@uJJi##w zS!jor{YUadP}98b@@lBb5dG*0p_+U&5ZBsMx5}9o}|xM zZ3@A6`Z&Q0i)yBUeLo(uN(t1sJz*+CUKyO_I_VQko3T5UlR6!>s1-?=#*a8M4T=>Skd6zD#e=@5ttAw#5#PpI1mh3`eyoD^Rp9sf;`tjE_ zQ0bOiKXzOOZS5SWf2_6-3Bp=Rkzhh){7Zk4t5&kENmrTB(S{@`^9P|>2!q%6sj-X~ zIM4SHv74bG!;)zQz<*I^)72H67nr&a>Z;|K*9uG(WZqLACLqoSPkm5WQ*oX9>+S4`+;5U;t7ROWhrvXpE!ot5p}ZY#VouJ|S_CEalZOrS` zgKW-c`rooP^|;oHju6#mjTyP9oRFTWG4hqb*yLbqoy41;T!bBeFrORnjCf_YPQ~CA-0G7nkaQS+-+an-^l{%}mYR?L^ORqFC z-dc7F7ys-ZvDNW2wvaL;^sINBO)jkQ{xNUX=JLv10QNSy6^}>vfbnHPxqT>W9r*AQ zJBA(HqJ0&5n)Q%PLXzTTQ0eJ|6pshI!SZn(n>XQNwRb^G?*G|~WwODm7wxIPEJoAv z9L|5vxMeEy`l|Me#EDp{3$x4G&ox(eIq|G^vO|T%+gmGyiro;;AG*aI$-Z3dW&6AW z$u=q#8mpu_Dg|x`m3b?^3-IKYl+h_c>}~5qPs_|v5^XX4W4DOW5i1TKXc20$hK_A8 z@Kw6K2n378XY)2_gToo9zHh$YC4X<&e6MAoCKOiqOIpAS`6A(VOC;s@|Btjck80{{ z`-NMr@+c}*WKe;$waO!-2nYxytyZa`P^%DxKoE+^Ob9a}si2}vsZt0-ASy-56hy`_ zMaIaK2nYcg0tqBQfDl5+KuEq#-|wvT`n>D=&RXZJ`!CkoEJ*gg?|ogr>7qaRZU;)z zu_4*o?XV!tk3=z-wUUb=GC-g5owkXc+jb6ApYwjS@C0krbq4#B@3vyOW#1n`^oW8e zlRtJTrG9_q$X?H{zuI@?d&~D(XYQo_`ZWJ--~5;l#mRyBw$$JZqKp5HZe;H<*i&Eo zEQ8$Vr*3B92j~AZ9dkC&Rr~q7yUE{vaq;Mn34nNI_U`F>KcG-5cN8mI=5mjam3S&? z>R_|ds(VE2O3SE15kMH({v8>`o7Ocld_JrvFFgEl7h>cg?(~2}2MKYxBLf>plTR^Y z_ipE_0*=6M)ZZwIIz4*SY4e<)zyVFsw2(!sz68cI4`k}Sl%4!Vg}r0L}I2<{1*gwCq9p?qvA-AM^@VY|P*{O6nMFSvKc^ zb=S8>t3R#{W{hZMTMODQ5J!~U2J~q-o1ugxp^H9FHZyaV-_b?W)Yme(BkhcHp6m~q z9UQ6pNu^Wx{xKKDX|>u5*boe&f~7;>)t6gfpJiBT$*5gX@ZT{ZFpLShM+oy3NsPN7 zQ-r5nHR~;yg_`oLai_3r0eyxjv{#)o{&Z@#=?pv04>lR_VAOkmNBKs_viTRwkx8) zx|8yC_C62bqxOSR1Lr$u;(D)5CBp6-4#`ihI&w7*;#8<04 zZo{mQLSd3~5LRjQe4kBse+vIsH-7Ot6z@D;>ufOg^2}sP>+c%zEq{f!Y{9GtMzFZQ z@-e^^sYP1T>@%d_wws_GYvetSANEE{?Zr;=60Ojzj|o;+PqcE{aOShMOyW&p{j9G; z(S+az|Ec|@_~YpM&dq?qKhrrs)vrGg@}7!jHw|KZ;LY<{ZZ)3bie|12a8rR?lP21u z6z+kvj^JS%&QWr2)kB_?+86QNX_S6(fZ+->cdi$S2x8C6dO7$K`H@!6<*0q2^m4(v zt?F)$jmXENyS95I{slL88VYMFGRBsq-l%S~KVKeRyS$I`kX$df~-) zYqg(*0ufx!5o+>SX!m>&|q>qx>a`!;`kl^28h@SL2~ zW78eFj(Q4>G)f}%4B@6>t(<~BzuC1W_H%TKF$Cgm+y5MPEH9!AKO$0rbwSgUGmxfN z>{;bXk6oOwIuwbnu+~y1Xn_8TwAY}3GTx`3A4Gj6d8(>QjionDNBGH3_#A42MI8DY zVeA3nWn5|Kb!>hcdi119{A$m3=9T%0$E*v6tuiEggc+CajBztUy0s@2k}NCdX~@Ub z8(Ret>zY%&5GRGYML=zLfPApfjvyYwwQk(j8eXrUljTC!f79(RV!7|twFiD}{{D9J z_Qy8KhB-xuI{rz`0Z*zZN`r6%Gb))IOMfD1^ND>jluAXF;KPy8?Hp?jTuka9RrpTj zP~6v&Ecq56&-CZRFtZuGNcgHObwq<_l>Qamj#K&6F<#1Ko;k6hi|kXX~FIe-K`CEPu3rPj4)i@}mo&U^{_TkQFhCb@gV zbZ?-~Y>l{cYKXx6x^jIJH3Vht&Xvx6e;OWqj3rC0=+5C~J0Bpw+3?|9&3kF@Xe}5gxA9F92%gGL)E!K<0ML)u`*kFPRzqkEn zDth$x0o!tvf9OJG{$^Kg|J2H>an`+5nm(nm$6&#RzWXA~Tl&@vIDA44xu~-Xg-OB& zlz+R&QF@-)g4uQiGZC>Ud4^8_zLGPm2M^#$RrN}1#VqN&#Wy=ACv9EhG3f$Pi21qQ z`G&QWtV2(%`rTvXFXjQpm(IUqzEb+P)nEU)ArF=9%1c@%t4T4;Z;)Enk%8O0J^%&3 zzpzaO9U1}1RTmHR5T4lA#r{%>x_-4v_GRjr)&$G3OD~??xPqT)IxqMG3%2Z@;hPq` zMT%{2h;6Tj9I~CRt13aY@NQ(@0)zWLREG9Wtk<(2>hP1XmAMwc2Q#ZM#)nAbBJ%=f zVVv9~+mrGWp_@Rv`*-y(Buuz3C-LmCbK_*;_Y2Sl=lzyy4DU|23z;DKb4h~(mK@YC zblW~9@X;B1h4}@wk?mXLCV9uBKPUH^s7;&}UCjlCn{o9Na)m%Kw z^?gzP!U#s`2{a3zJcx7hZZ`dNY?yLkuTGU!9p%TS_6@I!=7k!6v!Zl&QVe0D@KvP0gX9Yj4D}WTRcNh=uVl_LrFsMTGa6BHE&| zQA4*1RnqwmH3Lw*)q~8DoBxJr(cw?HwZ%QF$bma{^$Y*fSUNJ5k&8Zqa5N}@#Qgf3 z<)PYLEg`)xPwOy0-*bh#`t-h5zDG9J{NzJaF;p7W0a6x6cBFHSfZiX9kaeW+zx$xj z?ZkkI!tujr4ukwB_qS^{blV>nFD3pFkl6Q0Tt8pGG07N;JP^DbBU-_4i^d{a+10AH59@n)f|oRurf(i6p9LI_D5AKlj}%wstRoVMJKy)< z*S1hkoIU}kN+}lHoa!fOyTNbs;o6WvvUbj7i_2(bH&Q&eVfE69A2Cfz4<7t3c4P*1 zG9k9@Z&&*`-A0kVV4NH8_YkcTb?II0maL_Ca8*E})Gz#ukMsU=+XAlFv!H!%&qjy! zr@!BQzRtiNxSXZ04v{tJAn<#?$E#AU_gg$NM%XH935n=Ag&oz}eKNh% zAgK<8Y*rkw5pL=b^U)Qbzd)s1WvB8M3voOr`7&}UL%Mtx>NyNIE}#q=aB&ab4#S!T zSl0#gZj)=cho>;W90`cBS+^A^<||s&<4zq5ymLj}NRmYn+4tP}_bBBGUbV>d+dwSO zwE`>%?&4?Iu}E4C)H}Z_^n6ozq^ymen^USL1kC8(TYS^HcSU_Cgi<(oYAB3mJXwc)wt5uf z0K3od8oTsT52+VYy~v}hb&fpQ>&bxWp0kPG*W+!)Y7R_i&8x2N#ZWK zG|@s9mcjI6OyGej$2`5-{QP{uHb;l?%AIqe^>Wjeo%LV)7xGO0=hkw55PctQ4^!B@ z7GjwfK3o<6T9qgvAB#Z&at>%kE4QhYTOwXl)SskayD~KfByWzsoa#(p$qSqdQr@wZ-}kAf+(B5)^m=u2fIjb#6E2zaeA?e zN?N}NmLA0C)2fD$H+U(IFr=4<*k|M+KU;c7SI`w;PWQiS6+dl@VaUD zHQH7tdS2BoxA7d@TNDGi$jwHr&EG<5@$=s|SLW~xRvGamo|U^kYhBX=dr7`OQ6*1U zR`up%C6h$k8X9teVimAXUK&@@aDU+)uEmU)!fMA=rIIk+!R{JbV9LDQw}WrZl2(b8 zpR*X-Q;Z6Yz{(v!W(3;0uC}tKF0Vjrrz|J}VVpkxwK}n5D%z^J3pLPE|8F8L*#m?` z+rcg@`P5wc`yC$i_R`PR-`o91NAIfkB#FVpj$tVg9?I2eaFCn_IL9(0^Dvw!G-oL- z1jX{bXxG&5W_*08c%QBD`j?Lo4WkFid#xUa9K`eYfODNZyq*ghx^s*{6&ky5jh~rD zvz#16KJjTI;XMD;MHXD?mKMB^4f9}VWjtnn3c5<&e-c)C17Wi&_;Hveo^tjHFTlMZj#xMj{FQ$uIW9a3HBqNdXU-nR)IG& z2FBVCD9PFmKW>g&gKvGJ>%`4GP%22T9)N#L$RmG$yJ^4zc+A2ybjB~r-Q@*y!=jJO zQ#n&FS#H9KJ$6dXf!&-cK^U2-JiOi^iq535LbJxs$noMK)Qn*JkCX zIyni-9WZU2dav6Jk@yFgUCr9`u7is8{i)iVzJT+ZpVu`>zdndQyYm>3zm==}v!4O1 z`L_tcfCbla01A??CBdKUX~1Y&$*;gFE(`uuaRPMS>_d`P?$-RttnHa%15^zxDcc|( z>l<`d9KRgTG}JeUIj2Hyuwuu~#Affus2HXAfY3} zopWSjBZ_bJqwlhS2NW-l-F3sZTR+`#48abJ=@vuziK!@UVhi@`$0& zx?o{cTX0$iR7z1txs^j7iVmIxC36d7F>OFwVZ$yZhYb>uD`2`&_$s6^E_an@h?qJ` zI3?cGt@BPZ5c)v2yCJ{VGi`tBXDiVCLG-(kSK}BhIwRShb6Lkld1YiL1!v^hNjqnd z_??n-2wIRw)?$L5a$i3EKK3lV`W56w6PEMd8MdBd46h`iyJK{`7OYi3nt@%q&Ueh7 zS~0v=mGqUnD=2aCW`dUADoUb_lPEBYfCO)c)G6w$HCUt%2EVx_X}gPCn{9Z+8{I0+ z$VHi9S^7b)mZB;4rwIA0mGf}pkM76;^AIpFy3NBad4=a&@hxdfU_Z%I1=VTnW@TOI zp)(Wwy4>=+0oy3l$lG1N2&3}6ZoL08gPHXX;z1!A9^;>)Y z)M!$RVysMwx0l+sa(o=b?@hXtEGUhU_8O^fynq6KL%BmZ56aPRZ%ODy$j0#cf;Ok~ zNNrY(Tdr+uz#u(_gQIk9S>heRcWV)sd?4^bp zteyXuTNL?AgGzkzl&gA;s=zFY~6 z2Lf+LDK!iC)wKs-?b&eo+gewhD%4$@E}hJzSxs!j<)X19IWkNr*2yc(G})R>DI0Cl zJ!}0wzjCYR%%f|=LL@^VWaq}D#-XqeXpxI3Q?mJ$`Y1mNFlc|# z`=-oNnZplR|4F9UxNL|o3sUc=BXdd7#K{5+Mj0jBw+?wWhs6@2rtWTgTz^wy`Rhyr z!~jvF2Qe9U*1B$NbbZ9kBHATXrvqmw%GyR!Y~{D*I&?wdN%*RDdUPL-n}MjPl9NYV zCw;(-1O0;y;o-_@*@0z3FT+D z6I5DH)ln+FwsOkY5nszriR>K4orB^XGS5fc=j&5ppik+%0gCrTzwdJpfiEU$@ z_heTWWknHwTvoL+sGv8a@ zI{sJAyRnyz=ows^#_z3~)^owrb3>N|w^_SWSnEj#y*zExX(k(-u~R5o%6V`B!u-mx zq1Z}&Ks}O-p!=kcbG)Ta)BTla*Yukn!u?nRDKuu1V>Js!gdR(T zMgwh6zs|P*Anf#yza#T9It0&m!wWR{L4n4EjVHtK+(fJT=vxSm z1h&RYVz8V|P)ZU3Exx9l^B1Gt8O`~dHrW=dMKBn1o~%M{-A~~8K}}GTyS+E`^!vY; z1LK$CWN-x+vwhv*MZA3z)w>GDQywG=gvu9dqjfGcNq~HQQ=I#u^xs4$9K)JAu0g^6 z-+Dg!@rB0j#K&fXkz9oI?X(uwK@AtOia*DokRU}?YCs>NUw}$-!qD7CZt|z`*?Dee zaq2dJt1081702{2-6WxT>>TA~;Y4y`z<9DQ!TG&#l>pJ9FPTlm6AxNKDI=d|K`$fX zF0?L*vwSUBckkVPr?^Y~UFH4fo&DeM>eQa>LE4VVH4xiH4K*y;4-*|KkY;JWFSr`e zYLq$iqAAuoDM~Etl>}>+fBY~0^EA*kJR{{L&O{s+dB`r?dBT`HbU7oNQ_QRVGATdt zOKw)P8d>AgZXK4@d9E|QU{$L%Ab~=O*0bvlm}I_K)RH0%8s)ZEs*_({P304XkC290 z`rqi2(|yLrgoh1d`JT(?$=^rjk?)=S@G&jAfd2TcapLLk3U*$S);_b*L8iWkP9x3k z1+VE}-yE3T*kG?A9YDtOiMT5v9tFG0>62TYgIDM#Et;~Rz|jh`Y)5^zp!}>Y+yWz; zu-OD!E7^Smd?hx3--V=FV!PI-Bm*v%N)vg=M?HdNe%V%jhi(YFUUrOrTqKV1$b2kl zQ|8E%p^}-6CFtGvZe67|;}%_Z76P-?ELE&lRt4Klj;w+96Om8#FSiR)G-m4B8 z|9cfH!RRY>i|6)>Rn~h3XOI0iI%tO)vixIzXUB5Xqdy{ZxYq@{gQUnIW7Mp2S)m=4 zxWo1njT#qTxt)BVJ|MjK4cOD5XP@uVrF{+MX_#a}OzNy@R;G$=pqf&i_i?BVC59m& zF}6JC3XRL`gRZt}cT?%fSo9+#L8=Dvj`bF&e@mXwGlF+T1&;6*ouef)(S*rP&3ZFE z2)={|YAC-ct^N0EP_-vf3*a1d6zOzjwlv_d;VS}QSga%i^HOT#4%o62BdqR@x;_?( z>*B+pGJJI|w5ua2l3goXd%gT4-&RGG?38M=A-bi=BGSGUnd;I_Sb}VcuSXw)>8n6f z=AyJ$M}pLFl}ziprTXxwD!yVYNhfZ(iW777Z*^Mj55z(@01mxlz! z%QsqT#hD|BB;KCx$M;P#m0Cw4ZP)hasJj-zdR)`M6`1_z}=mh ziv5=^=HLEz+nlUsU-W3^aT3%Kfhms7KKdTiab_=^9~W)uWM~u8>gcsr9QJk6|6=)K zJkfZ>PCpDZGgrVn=)Z3VS48g0WhbnfXF_MC(50C|0 z=ZsmdtR?V=h#R~n=ae1#lfR)bH(Xkp(r$Up`l)6MU+DJk*RpFTuKUEl1#GPZgZNv`7pcrROj12DE@urbCMR=lMnZIzLJO@ zEmN4%illGI(j_RlQQ8Y_ecQ8@6j+cGRvX1dj5jbFSv~k)$HMC;08h5^Sh(va zu_=1Bp^IQzsSYJQHLQ5la7&AQ+8*BAK`qgW37)$hm^aFViZX?6lc@n|rsUon9@KS4 zua&80Cog?jU7#TB@$7QR)h#8hx8V-ZB$!zH}H#S$JAna}gTZh+s?YOuH?O)hjA zX=o?0Z<7JuPf*_jMU=*U3#HoPREz|J`ERM0?6pL`X{3gJ@6<@55;}A&@qIDOzeUUX zNq(gh)do)CfMf6(TNfHHTQ~VRIjkga7P>vGs2Th_ut*;d#CU~|h+Zo+6fQ7~3zZ5q z0ZxmAlsyZ&kF1?sWflPdOd9)RS$as0z~Qf3^P3)7F$+pQ{{tx94HT1qEhWB#r*Iv+ zBW7rBu}^2Tqb6T=S**lL?k&e|!B5g4X?-U^N5$X#0r|$VZppXR+tozYK7`AknE96@ zL$b<3uiZdA=`-@1(S@I}Gk# zg0-Hlr3RtQFzMOyT%Iz=)j-3u`aY3$XH1dq>g*QLTb}Twr8grKH^sd1E!n z(tG)kw*uaC6}>Fg@%ll2D(Ay8g5w$HU0_zCr(g%pU z&9f~onIS|K_u0k1p-H>^wSAWuR-ta{2C-vDFhC|Rm^0v4Z-M}JHN~keCu(?GI@}eoBT2<)A8V;?b_kihAdK(yII_1DnDl4 z#Uf`Ln_i`Vh75{LdRdtzY(d4a!6hKRQx`qr0C^o-9Q6W47s-_z1vz zLIiB+jg?)A74nB04;o5Uc7@`=vi&^TQ#JB>OzSl2U9EwnOzT$FHP!qe&R2}uoFvpn zo5@}*f&XWI2hXpacQ+Qfz^_ZYG0%+;DaEhzO|OyL&xG_ba#dqH^}((F(`$51xEbyn zW%h}t^(i+0ySLRlNs|^Zv}B%>VH0SKYl}pzT0a3x+*9KI+Dl0tcT3aHWGlCc&*>xwx+V8YgG9|AB0w%T{IiwBmAom|6iQoZAHaV-)pL^ z+>V@%D4lH`hWA28$GPHB+Xn%6#7_7fPOz+I?vk%RapvtI`583Z|xR`5O&46|0@gNW_f49D&Y@trvS-pps>j^udWnv&tR(bvQzAqS!2^{eDk)pzJ7mdNhiqa{6WQ#w1ZaHd&e*FBxckv?H_6| zkv;`pE{3x(=2jb0PHe_kkcEIfFq7%A_$ZzI+QiCM6ts5R)!mS7}`t00Y1B2}w zQFS?m1Ka0{lP~qFCIWE#?d|?P&5gGN{!tLDjw;w{Ge%LTQhc`kZIT=v2&%3~v1gT9 zanV6LM2p#NOjQr+32DT%@_b73*H9IXmbAaG!Yg$#(YKs5$OwmG{(S+XOSH%jZlcjG z&MCy|D;s2E^$+AT)Aa!?rI`t#oD%=}Mq6&$Rdrv^d;A2bOJ6G9xi$Y87{RTmCr)p? zwy2mE6o|BJx#iX1BUfA1HE2MZicNo;c(P38NTwq)6u>&eCXv7gh&o^*`5>~C>-j1Z zBozoYEl1fkCx!fW!RyfjxMaO0;X%efa5h>kLnR)|g69sK$2J}-w(&QlI)rn$TGzWp z8-sl!Jq3}bF>s2SAnBF{3rxN0B{@~Yva~7|z!(l{q&=?dcG6M=qn{{wB3rGHi$#|! z&FMkH*&B=X>?}$8$$z*=Mq@D`;xL>_%{RsM^G#x0krf;I@c$wT+hlnA>#cg}7zomT zah1vf!b0Qaw+PaYmk>XFNylY_6YN`%7F_|(6*&AGmF_y+afs2EoR`tLh+YOrq}yly;b zRq#D-VU_NZ7Ogh%qk$sV9JyU8elE))_*$ybqSIzSRGzhEXtkatwUv1tb4%M%p#j~= zdV{gR_BER8fv-37r9PwF=g15pDCS%H6Zp%bFhIM7u|*FGE093sN<(@;6;SECS6{KQ zi<&@Ei&y>hrb{nj?XJUweufbKnF&@#u@eTXui|ZXtX^C}@KyD6!b!X9h_Jh~z_?a0SKX#$p5!qia1;{_LWlPYCd4meoN%Fa{?Ay6Ur4)> z8cRw1V&gIO^V7Bd@*d`o0&I8M5{j>^!g?%R(*{xLL;PJIbeXhv%(=bfn{&*&4A269 z->N*pqj6^8&a>9tgSuG=Lvq0F?KAF{3#Q%o!02&xipj>{U4sc`q7blu(Q1*P3K%qW zA+ZD7#b74(o#$R4WLqu(rzgt)dipi;`qfJ2%t>&j1*K6W6(A`%0yMu3rs$l_K*2(2g+v~5G^ zr}0bp=Vd{bU~IB6!IdYsWp8VKzdf3QduGMzbnZKtva2Znr8WJ}#0aP;t>>9yVO@qKf4(u_hFJoQM zC3?i!B#63gWq@VFKUrAEBIm9mC;L9Xkq>TvqhnB+%7s51QyitgG{^;6h5aThBTLK5 zfHB+QLR*HwHVSA(RP2Z}HH$w$8xIy9z|+Lk`*J8>^5OTav7uW?Lif7r@R;N{&97fg zdp#w^F$-<3#EEu5oSSBmRI*@Wsh2D$`Hm1|oHru;rHV6aS)duuVdcGD=q-H)kHQ6g-#Vq=3Y0@GAvz~VvZ|+@NyZ&r@#|W-mIF?`dz($L`4C})(FR%`f0$h zJ^@3MSbj=V^sPN!a)$UA)Wn)%Kx=+0yD+0vZ*~HxjVs}q8nC|L4pAJUHS8?pjx@%D z8Zw~2HTawWKJQ(|KX2up1at91E6{|QN!>$e@q~-t&l-k2Rz?wgpv?-&{ypo>MwL6d z+50DjGqfr+{EBQ>U|Jf6664^W_AfoCxvyl6Hi$Rp+-OxF-7bLKkMrLhOl|ITQdP1+ z$y|1p`1tULh(myGs!Oz0xqfejBzY8YHz%dWmfRg0i<)&Es2%+Ekd!${Y0N@>e3@)L zy5*TqV8!SpBNeV+WByIFV_wv6)HSd0^N*5#4EFP@3C}(`%GqO=1s48`9z4w420h_A zb_q9t*%2+$wIoP$tavsF3Q~wEP{6if_Kt_8a#+YtUK^rxOiUYBHPHzAK!OmbpBa=2 z<5)V=$LaN5xnaVC*yE|^_0E2_W&rB=lC8z|(+1$69zCR4Y_Q7R^MbIw>Q)d^a`lpJ{c|qN=4E=yc zcw;Ju{e`i+dAD_8e&uSPM4J3#iWu{R>VVfO^|=al&ixu-l1H0J~bK$8BFBsNNIC?rt1fo8o9VF_v@ za+25@#owLFn>fda$vh;bc5q-qeRQ{2^9G74%HC@0O+aw@9-sk~@tpv@>AqPL`ateX zwyJkMQk+iPPR6P%-v%1eZN#ByefYI!-pMM#=@BbgMw<20bej=ZS^mOwB^CNGZciplTxA7iCzb`WFLVp) z%;He=SJ>Cs7Kjr>TmaQ-fi4_G2*sbyYOCx-yY=kC`xs(%pnr9jp$0jCDKGMPCGEe# z*`c8Jm%wWZjZLg`+t345Sw$X#XFKP0@DKpx;ItZq+>D;+k~X+9rK(BKHua?pGqUO%g`;lR z?u0RAAT99niY0I5f}=Gxb3(w56KV?jBLT!7Wq=0gLFVuc zS(+}kPJ==J4x^ceKUuu8}M&nw-+T_wA!UThOXw-X!CZu_;z)&POI8}A(5VR$E{TT}oP zgP?uULQ#xX3Rjw^Q8uHEAbRh1JRcOh@X~j+SwOX` zW!ZQfYV@!n@Sp#(T4m1gcSz4?a^m_~I)rQ_3cN~~;PGwQqJ>ZC2(mPJ&=tjW+2J|M z&fY?;|Hf@h7S@WWC5JkJ*UJ0x=#vh+)437F{C@^Vx9tXP zz6Zksw``M)-3iJuHtDn~V30Ux6VN3^0&0W53JO%^lM*6R<1R%pLY6|gQ<;d{ef2eE zs1$cj3+fg!H@UtBU=2SyH1ALJFy6cOAo_f@&@!IGEQ_8&QIVXlG~z)V`Je3DHe3@R zaZuZN+tygvnY1$Sltg+&uf8SLE9TZR*8>J+Lk+UZTD(2nMSE)fK>C|ZA}YyU5pa@1 z>lRM1T&DnqV%ZMmR6GL6zOBK!`5<;~!-jIIN1WbHCqmL$2!A3`>0Ug`Frj>|PQ6t2 zgUtc-H=VV8GTWrgxv?s5uEy_R;m2ELJ8(O;`|v@?VN&bRdwSd-A{XJeKRg$^f&M)1 z7p3uw9yq2bY)<8jmAfHg8%Pa)DO0KrO`>{830^S3NOuTRD%#{fh{gQh)Bx#NQ|7CrfPd>w^eZ zZ6X=q&>K6WTx`Ly%GOgsCc^K&4LMX?Y>`AjN~6z!n$2Pb>sp>I>}jQx^Ns0?T{9ux z)xkw=C|47L?~Z(RE($Cj0cMejT(rn*M|X6?B;EyV*M_ZNT5CL^(t@-9(zG615Fq5N z4N{LAVgPfJExG_&G>ckmCy|*>V9R1xz{(gxbqY)mxz+?#UKEL)(6dEXk*$)r0|eE@s?~0(SfBhUjRd_n<1s|{QtlK73PW^} zuKb`9@N$X=F)8<65P5mBUHxvRpa`9RU3OU3ihnayq=LnZk-?$1Zi}01bM5!ax%-CO zYh`yT%?tW8(i`8k)z!=^B?`B~3buNNnbsi_U_skGZNTox67YL>H-&6_V5x^Bq;n+u8o+| zA&0ufFI)n-b~QOT*H4D^EtSEyOC!VW?d=9-f&~Q%mb-Ok#Otu^C)fqo^=iao+z0>C zOsXCE%<3iIVM10=kAd+oq^{L78Q>)>IKbvk;Skew0D0jRsd(W*Q63gXaVJ zU5mBJx^R8R(NgiT49Y?u4((Vd*pJr(^FYy~q@1y$Ftzr{({ zmlw#Y?$_C+RH^rsO|b#cZ8Hjn*%qRngjaOPBn(r^p2VIl_=`OsdB@;=&Js5lS!kBb z;GC}CJ3CtZ9aSB?R#aLk84#B1O%;SBJHn1H4X-tws)MJz4!6;5%v9OY4*VBGncS45 zN-?zASSZATX+*&^!tlt%@=h7!b>-b=?7KlPN9ERpmGD>Vd6aSV;}IXVszB zF9_XLRrmeJdP`i&z{x__q7v3Uxu8Mr1*^1jk0NkivyjvsCNfH!v0ffsY(H!f{~x4Q zNYnn#O9j-+fCvhrO@FzqHf>6?sYZYKx7@~BeEfsfm)B}S2@ zYD(AZ?)MOcTJ{D3tf=K3$00eaM0nQvNd~#SM__wQ^4#~oe2Kjqz9z^O7 z0{oop`Q|JL4dfsc{844!y>O3;kEw0AQ)WJ$rC??Nqe5gm;>0)V)QGMaPF#Ax&GrE= z$%Xm?rE)|FppLxNWV4D6zT3$mGn--pz;m3Im7{QLD}8u>7Nn z?k|>>1wwdpBo(Z9^iDSJ5Nw!8t?(samy)buIm5A=us zAd|&)r9aqAZo45mVt;Oto(;h#F`}AT+T>%(KIE@SXrC0+$nL25z9G-wMoLvQt)EE) z*w&?L9mWRnYa97I@TwByXi~%S^DF4}r}hqBnI7Gi;JFfXZuG^s#pX1xx zJKA-NyXQ(#Gu4kWB2102JvaHH&Y@S5*fyKa4X+QTK+`V0uMW4wPW{bz`AC5O1>a!i zXfB^j8Dg%2E_Eeqq1kj*W2Xp`)gh`e5R%=U_+O+Blg_;oFxvqSrI*nB&Z`RCkVX zce~_v0m>MtiEN5X5GhzVYR69~K|O)0r+aNwzxGKR))$1%Pa>iUl03&OD4_ zi+tSLUJ*PuOjWmy3lfC7Am&(i($SBU$C&tqr)AEI&aK+v+b6 zY^6$Fc36@#a6-z^hW{|4L17{@&O(J`r|?#V%hz#)Ckh4#i%V>^1iA=yS`k5Ddb+-w zWc51P7o{VzybsOxFyMHmI&jJGTe*Pq{t;_?KSzrv66;)IkX8exZgq1IA;h^#fT^ao zY37%Z5`ecOq)Ullh!O#Xv$=FellM~;bEC>L4motOhB`X>U2Nr5`zC_K{+IQP4pK`t zs~PJMLTpcrgKt38=?BB6ku=*ffZq++=>#i?Et{X549@mdY$_x2-!{?A+Xj4zWrfy4 z+YeQSQIr;2)y+Qxo17r0d@W9!e+I0D{s4e54GfK6F%YAbi&i!296S+wFQ(6JI!xxy zi=``$sU#@Af6gy{aZ7~?Hr9ES&x(Ijp%f#Y$@-+u5J*sK8O1xCWHkLN)~A^#cljZG zc1kHa-s4$y-V0Ea7cvkqc?;fMQ-ORk1oH#inoeud_u3r*e1(Z62A^`UfU*&(9eS)| ztjb<`OBONhHHeB=%o@|qWB1e|nWsEQ2+uMqOBomF_tt0DTV^W7$E)hXLKyebb&GG)8Q?6ug?qtCH*N#1kHsG&TO z%=9hC4o+J@BJ(j^Ao?GCT+vMi5^?}9vbUQZ z8RlnWZfqGGhw@rDrzP39V8mdgj5%4L~5i0nG4_@ZU#~=jYnSU@46`l_s<>E9ZT*Hp|MP zN|en)$DT{AT1xb{IXuh%d&^^`u;vE`wDfLX(*R?$uHOB)a)58#tB<%<;=Plnqqyi; z+4uGLvjxwJEpQ&YHa3x!nP5TgP-VkpADaEApnknZ*59N?anwoUgw0&=-QgYGP_){= z9Mb_>Q6j58pPfvo8i_W-+QhMsSYHA?-CPE2#0k;e>~cW~-bst`Tna@}0Y7tG+LINM zuTr>_h(lf&K-enK?C+)kZ%spZtmsuk{WZY)_?~^`x?Hb-|38UJQ(p%do`f7!z66}8 z?h7ri3*9!DA2jxV_=w-%tD|AQFmUWZCqrF(1x$8Gr>+VxnzIm9Woq%Dr!)eYlnBCw-mvIr6<$3MhI0-hSCoMM&i`JDS^y3FufgC3jPa?}Ku=Z1%y~Qo9o`l{Nse%~ zG8K|-WyLkJuJC?9=Eyz61oqNh{36FeXJSO`aJo;BU;KqO#?sXBU_o|*nz5B0yu&Gm zY;SLFA9)HD?DSg0YvWG+KL;S)|C<2hfrd;nx}C7pABs@ED}c)XFz5i#)^rtfBjkj$ zxL|&c>nP(&`)Uf@+~K?{ssL~~U>=7RYfKcFN7E=Zm|)+rlG+~*%me18x9NGW7FDk3 z8}R?MlK#4j%5=Gu8gqP>?q@4QJ6lu==E7Io&RVvpZ&ey_130&9s;*L8zU(SF=(ej? z;Dr;Ez6UohTcB3o)bvSCOanB`N4}Re0BGf00M4rC?gPM(tcD&`h#sS1L%Ob0ql9Az zTwczcjV0%2-K^Ik0jaa{{ER1;Jz_)dskSjps1LpPP!AnkJh*G z`7<}uCHBc;J89?%ljfv#7uMU_3lI6g)owoE>aT_->eMn|?W|&>HpfR9wN@zsb2*)Z zo*i;UhOK5U*ivj{v;{rA37Oc>ypy4Jvjk}@vrX#k$Z~PvUjD7UqCj3__e0i z8zE-IFkiy!)yX3)On!@$f5%NQb(;JGl>#uoxZI+Z0`B$mMjs%VJG#v1YrDb5(Sd8zrSa%2FGGQ9A3LHUaYD2?3sdmt;nCQpLuniW06}J%SIt4Z8zoFSaQY{4mBCKbUBhE zoF`+bG>g=gOAYUJ9%~%ggW>fZ>U&4T$dVRY=MdG)BACp9x&E!DGkj6fpMTxqo>z?;Lgo@v2%G!$s44Ur&gf+RC&W;T9cL400GQ?V6HB|HfeUJG05M7Q@fU8`W24@_xKG0 z9GSX?W#(vsNgZ0?R6}8{$ zy4T~=TD3J+s5Nm8=Dh9iNe$51&x0FRifS~H&Xq)z@yuh@QC-N3RMYN^)n*{dIQH&i zI1yq+JaSNp`~N4*$P)9u1CJ}iJJnxg&X-1&{he2l zHdi@yt3J~aR6q9W;CO;{7)es&oOo$7#n(j0JjfyO_vTWgzE)NCFos~^q@wjw3=EcHGB-?@|UQ&)8 zYFPz)Puz$7Gyk{_V(J18d=apAL^J zn%UrM)l0Rs#faup#av zJQI21CF@Jew)wxCy~yQ&+PoLSUHJ`8aI%{H4mcI3oCapOm&R7sok50z&mWp5opmIT z5(BCiA8^$dGa5G!3b7?mwOeLWU)24PEP_(ZCh{i<-u3{-^t2%^p( z_>&%!UGbZV_Ia_;4*=RQY=ta60QSDniZxy8M2pdWqBlCboapjZTV;t=_BH#k%AgWK z&D9j`e0|Aulb?S|kcS<_dR;HADb(PVz4eomdNj5I{73{HF7Qub=>;zJ%55v&9xcsH zw3cCo38Rv(wE-S;={=DDr1a5bu{-8dF7i}K@6YMr;}M6ix+re6%eDg~P`fj^)_ZF^ zBSEYW_nbTO_(E(DU<$J`9Ri65N-@__;`nyYQZ_$nZgmECtj6azFwryzeGXdl_B<`b zIoz#+6Jx2qpnkvXDNm4KhL5n#GXq4e+=dzBpZ(z-s52LmC-MSD6Q=#70qwHKNxB|v zp2#?UPKCej2y{&zS89b^SD$kEYoX^rhIc7m$Z~$sAN?bTX_NQ&kSjSu|IRU4HK&baEGP27}hei*@Hyz9xpKolS+Spch*`d^?$aBDjRja9iEi? zit1Fo8*}T}5&nJgwKvSRF({k|_FUbs3wkjOq^sO6127D(#7ftdljlhbws%Pk*j&owznsD0OJM>lLtm;C!8Us>$7^}Y*6`v zsT=EYkglSY=Cc8)gAFwYy?Ta5&op8-BdUf1mbk_WrKbuD=aPsxhQvW&iJ-xN*?t4& zkZJYQDQNI}%HgbxcDPIJE#GLan!2_TCBN#5^_V-#9Et%+Gw9jc@A>+<06WYwGGa+J zII>igPV?4;=9DlQp&E@#1)phLEKxQbukZf8Pv~PqMH9Jc zUa~j-m=6P%%#i(1sFKJ@{Cu!NpO6Ol1T1J(SPDQ8sJzy(o;t@*Kh30IfpXdt#y#Iz zatq6<8D+Z_Q)p61V%6lOCi>!?_A&@we~=5erzVVY8P=Q#)6xMo zne0jcwEbNvRcNeC>MO>>Efl&pNRyNms%Ei()MDL@2Xf{gd)MoiD(QekHS53&X2gn@ zPdIfHgBeTNdT@nJB0xqmpLB$pD!719X@VRkg+zL=FIYlR2gn8^GOw(CP)vDrAUkg0 zL9q>{*q56rbLvgxSU`JK(6Omp^Dykv6P2%8 z1A${=lCCVsMvEW0_=Y!Op;0ePQX9PuR(}nMU9r3(NWZ#tw{_JL>Pr$PNNjMBk2y-= z4xbRa;ibtxLN1(l5w5m$-Thz8TC!YiXAkqJ2K1O*0C;8U{fb7q&~?(1161|Ofb)9I zBEZ7l7Up4=$>U03J5w8Lt(biTZIDwnztwz;U{N%4Bcvm>A~)G-M0A7TvSL!5JSLNv z$}ae!GDa(iq9;_FhB7qHD#DovGq`Lq_nr}N*Qj_=Y{c9xUnI}Jap4?Rp`Hv@eB@#= z#m>Yle%2J^hCl(po~-jcWJ$S?z2xDEiYhOST{!79X0h3^!N|z&Nm5k+sV7rD85>np zgF}n{R6#pd_q7+s_JzQu<4z@N>_`zYSuxo>H1xRtzf@7rS^!^Y5ol-qnXd1fjjpsL0})n|#IR4uSi`=Ob^&VWHJ?{==waCes==OCD0*fd)e1zx z7;+oun*5}H^KM1F^*JpQVF};vQ6tz-bH7a-AeumG)gMA#iZkb&4V>Bu2ks5)`N&VV zI>&xOX}SiG)ISps{Dl%lo7C8H!6WA3FsBfBT`%?3x1mqV5O~x%*b!g^gm!=7!2d?LN)3$xb9r&gXq zCqLuLux+cS3l5M+$fDCl&TU)px85+pWXcE#-!UzGikt7AYHvkflV@X14-8B><{Kuk z(%Ng&H_0xtaTNW0QO}Iwpo7#VX|pxo_zT`YcS-$)kz!FUPgfF zU_Wf>gtV*OISpI(6*YccOPvIkv+DUG>vq++C-B=1OZaB75zdoC-Yhm3ze-r{uECXM zkZGkrXfOra(PgP`T1qx$4Vv&#hU`&Ei#%}xm;M2Yh{UBZO{k?}(e}-C_!YR8ntCKN-7au2<3Ks5C9fZkRdjhzbA*qcQ+!5ZH z1NU%FskwB0Q($HaUAJ*9w#*wJ#aDa5naPs(Mf{%9`GrO)l#yf;cJUP60m~!+ns|IZ zV*&ZdS(EcljJs)SEUo*M4<>iCoe*Fx_rKXiKk}WOvw7)@^zIjG;fTm=F)iS{G88Vd`n6eH}!ME~anm;$S*b*`0vNJQt*Uvs; z$h@!2GVl!Gg)3z`5DwC)cf`Thf#LgK_(-T?CCYgju6RDG%n08E7|(RD?)3>5REeT* z>=Il4(}8<0s%n^E%p(}^?q!Ovq^|*;yuQO%2d@-s1CE^su^XmfEs5{>KmX+Xa*u+N zc!^!46`~5jvExbwZ+LI-SMJBRjN7OeoPdX}ExLmYt~KBmQ1n*cx>|9C@in73=jwG> zD{T7I3Yc7E000}zZ7y2B`4Z4YtL?_Na%I_A`n)YvY|CO`{A_Cf zWTm9B453O#fOm#&1~veeG%fty4nV2-PAzTkI^ZbA9g(zT%4SpAb|G#86YXC;8{r1)0vz7QSh%(9<|qe&9KvJKqjnN~HjbV50NrFdfg{ zaNp8@Ar!*d22cr&>z?oht#tS$NSlseoDPs(VaJ){4_eQJl`lR$l)3hMi;A3a7|(-u zhf62;uvJmpw<21kH{T^fAAzy(KteCbPr(U#w00UeMf*D2Pnq-a(VXyRJ-O9}5GP=C1ih zB)watWFh8F%d;i@mWI*ys5> zUo;kSH(K@yhg|UoH}zD2S33s5>Ms`$puqo7K<%1;cFOfA4QxH7$mFxeF$Vyd#nQ;q13_FE& z7JCy&w|xF6Cs$Y!c2pBzwBikwAn)2)kf{-X|wozp|J50 z>*|0Z?@&y2%6U?b4U`TN@2PkwgX?~QN?T8f`bZlqOJt1?NhW>5g+i~D+@F^%KuTX; z$@}>%YDk<7XM!nPi2urMXqkd=t*+l~)t_u_a)MJer8Eeis@nskMdwE^Y|eNO6613F zHTO}|pFgGpomRCZWm{}e7E;h{>qDP@-M%b{voq*4H;34=n#TOYj8VOq4?jkdK6?(wJ6#WE9sJ`vE zGIgCEWkD5IH~3uqW1Yboq7&BDf7N5Y;(W2DZ7U8yH}!*80Kk+<{@WBfXYlattLF+P z114^oLDc%h*!1d&qv6IRwlr{fip~-N+3Z{-KL09N9BW{i%>j5MLe_3WYIL7pT;Y2w zdiq|~n;cAP0UqDDyFXsnB2eY;vWDKaq%^tjozBYKsQKL_8=|TDOOSn#xHx6H-4rtE zKkW^jU#=XdN4m4C-VFDU^LP{DhJDnPadT3$tlj2nZepNmZ+U+-?enM!KfdJr)?7kB zoyKl!WR>7ce0M~y_RVxQ$HrW}Hj z#zI*wAGO)1w#~Iho2%-&&RyrjLa1CV7Ytxu?Y|Lo;vj7c(a2z}3K#W!$|mE= zMW@?%w)tUBm2$yWw`6fXZ&;wmHK<44KwXJwey+5DX1#r!t5UMx*zh)F+N1)DJZlnp zeJBTToJ_O6E&pK0qoFM+z!AEjecF~^gin4$-xLF-5_a;{jV@Liv zJC^Xj6A+DmwgMnNpgUa6obMvG?G)t#o9;3ZeZq#qTGx?f9rh!z5T*z_2ZbaTCVs35If!Wmk`S^IQ=?PNXc7I>)&~k$mB?UzyUyLB+Zu40q=YZUr9e^ zXt8ptWu?t*fWqVd5kbb@j0mLUj62P|Em1DFZ;8pRPDf z47AQdR%1Sx#J2+`-@M_;<%Tr_ger@9a6M{*X7`@#~9$g4vZ{$USze=^ba zRF#)IbP+;iMZ*BeCZKjltMi)&LeG$e7r5dOV1|HK>%Wbrh%7AWP4Z zK}N)NLE#-lbi)Te7oJ6+9qTxvZ^(?XrWN4rMQvL5CDm*$I4q(=579(g!IF0OxExw7lcFZWeL zDTggq(`x#hrVv}|xL!$0ICvehK00j5d*#Wgo`1D>_21UwpsKH$6Vk3Cao^Jjl8K*p zs=N{E?o4k0`N2(D#|woq)HB7EzVt*_lf9U%3Dq4fHxjZawYT8h0leQlO)T|xL7vC! zn;T*n=8@wznzywX97uSd*&bYq#Gkpk29YEvCw^cH4yx#hCcc@IG`45>m7ft&LWke@1=$meAe z0E_1O7}6>L%J#%H2D1lYb#0hm_NrCTNDU}FZ5>S#HrB{pnrwSp7f!|R7IT_Du6y4?nQWL2 zwNZnERMFq(bm&Nohi}YjU++0?Obkn!tKFK}z6C);v`nD-+HfR<{x~&F%>Uzc@dX8A z&Tm&a5Igfj$+L-980H3CYS{I?r!Al>e~(UR1zq=T?%OruvXhsi1F!%3o%Rpw6;!&KpRzB$xoQpSo zb+KK46{rAFfV>F58tVLaN^a4Sil6?A1@Ql(>h_U+zsVdfT?2N(Kme=n@(OU!1WwW$ zfD5tp$enxWOqLY3V{!{$+B{w?P-adpf*LeuCdPsIiKa?X{?7m^oc_NOKn;IIZO8mi zS>Bq=LDc6u01rIEy{?0&Fw~wdT^2$6YK+{+UWOD*IzM#-HGmBO_fi9v$o!%4i4EH=j>J>GUVU`${cYyqX8Q|}tZl_gTduA(S3-&yb|v8F;ex$l^OqIH9EPPADb)R9p1Tg}*mjvBqV)YXX2@!& z|A2{^56$&2c&!iNVghT64zK zDa-viaIFs*VXY;7EtoRk-eL|WOQha>j0(?|I_%^f7XiV+YEbU5$bSWJWSoXt0`!!I zW)T+%u7PxwJYn3yIheiw5&T{wU8ldB-u40lUxq|?%#`G&Yn?a(jC8Bia>Sav7bw1z zuK=9}N*NFzhvh$U{#xohu6uVb;WjL!rg{ELq2rnhR`Tf!vDdI7-tpe$4L=?E{^lR4 zR;R8>Z@Hx*?<7oYpFal*2|aY8Kzf$!k)NdJgc^+PesOW;Y<7OwmFgYUDEMGa&w$5$ zkNACuukZM#{F99>21m@S^nHGrB6b>o?N}gQV@f2DweX9xs~<$GO!VE@r8XI@lBWi` zmuBOe$5cxgrbu41tdCG#x^`?=Dn~yA$j}|)18Mf|&j#P_>jWZqwEdFugWcYW+gHIV1nq;(&O9BK7Zc4b8s z^dWk$j%;VmoHK-iroAALM}T}VB>Mqpql#Y_c!eS=fyp$Aveq=t?nP|df1{!N7#;be z89gaZYgOiI+M3;IK3A2AhA&|UD6-1mTSKOrx~?vXwI8~Y2IpOiKJntLKJOEAL>Wtu=R!ov55DxAnnssiS(LAPrh8DanjhZJ z9)E*qDc{(tbHM5OhnIi7h?sKvT5FPb^VtYM3)cy(|29_ApqOLd55yV*C7+>!&XrI> z;_s{ePxwa3Z?@#&ChTI0V_WumZxKB@y19N5eVhbv{DH`4-Mg50UU0ZSrZ?F7xVRQS z8EYIl`OlKXomLz_3$GPg&`->I~N=5M43zi~H*2XsIir;}tJY>kg`w;s4X zATP7nfi?`Vb||l)kw4A3Y44 zA9xur4PcrNv5vTG#={6XDXb$zfd3?^zs0M(tkW(p%IJN1RMy_8Dk@0hW=B%Hy)H*N zAV5)LB4<=TI2v$@3$cN5-yMFdbtE{juGi40daf9jWwr$57MLG6GBxH}TZuc=9r(A(OQ-ft4ojyJb&Fg;B+FOKyrd z*z$Dn&@L5s!F1@etG`(P&-eP{n=ZThjZT|<{MN_=g)ORdIksWMEW2kb ziH-EbTQEOaOncOnb|#wtYRlQG{c|?$j7P_`0w;_bjBwBMs=9BAA?M?{*Qp_{%Djg5 zLW={nm=m;(dpL&@qibmB{FNe|b>SHd_-p~;Ij`Z|$h-Oi?dqn~#gDw++!c`{TXNA6 z0BwNnd@i#?O}rB)G%pxB9o#z!rD%ciL+*fiIpxDCLf)%v?fxsznogBjo^dTGCO=Ko~^k_xyAV8FyoLcGwMCapi zSDiJq`dsDuJzdf;TQz8s%5pN{jolwXcUS~O{l)|z;4f`Q&z!Aek2jCPSNf(VnjgH) z(k4RJ(UiTt~UzH5ky z^rME_M6$p|pXZY5me{UVU6PoYs$S0wi-0b`*&ye;rO#XL1OL0^fIkn4k8kao-G2=J zA0K5Sr>~Eg#r;0E1=X-{aPhdE36MAK^_)cM#b9w8rnrF-ji1MTbtA{6+KSU2T-7vg zgch~N%x-m`B(*ghZ?VWs6i$DcQ`S4ADyoPYa_g0S!YueJ>?LUc zph1hhj4pXI;H@HBaV#77G0Fx|*4xQiq7>dsdQL>mJ>v`4|3<}>(Nm0)33O~TpekHT zpPc}Sm?qx{dM))4HtJ5p-$x7#`LDLmU2?envENAkk8nQdbAmlBv-tT)JYJY~WNtb= zi`^q4nBjGn1IH+v%`~;WJIxXN?>Y}<82es5-GBX@)<0hy?Y~~L0c>$oQ&FQq!P_}c zbe?7<;ecUGui-V5H1oD_Wq!DN&+4T|x~z+fSn7U{5{{NxaU+PJ|3Y^m%n~x~A^np# zx+wsCOC=ISL#z`+owM8risA=eKLDA94R!FFh}>POks>+TSu3dAb< zD~l@v^18vyH7{cl=7iGA1m5zsp}EN4hR0Vs2YUPfdyq)?sr(a`Lj?q37)y|Bv1rl1 zS#qqb$n<&o=aOZgi!}BA&&VXi%k#IM@w?5eyA1MuB9d*>W3EVUDSuQ#!qUwq3HZgX zazR^Ts4+bWke?aodP4__`5x`6^q3FNNPCo&tLbKkLtPs7;ATkgbCnV-e|heXk11}S z4%?JOh;_>MsoG9Qo{T4OF}++X2t7*M2H~c?@yZLU?DVI{CEQ}R3>pX2U^!J16DCFP z&Xq>QRbs))^7Q`?yi^ z11Oti_m9OtRlx3hc<;jkBHGuh;~-`q{?5 z(pZ`pZ=JX)`T^;$WUd*G_Zcizbt)~DSI_>j2dsoW$4AU1P6DT<-bU5rCxH^Bvu)5| zxgrfHVB-=cu-C90x9VQ5-X;HQLD-=}@>)!Aw^QBX&1*abnbYXu=g>fLJ?Lc|2PAbP zFW>Cx*)=B0hEiL#tkZ%JK^sdXjDNy_K`VjlFyN_zbQ#pb-TLtFfby&_mQRpNO%dDF zztvkSO$amOSF(1!N%g(Xyj?efzC5;N<`A`Raw~LT5P!tOf`Tf=kf_T=c4XZk2a-?y z{!Ind1pV8!UbLe7A)dG>TbL|})+F);zUM8x9lK%>wA>m2mH#Po@Fgu%w>mpe&|$6N zQgpq*v*K-9b8K{q$-%c~Jf0I*RqFQ~Eza{>-&S{16w2M-Dv_x8l$+FFVN@hUT2T_T z&U#u7vME9s`~Lev`&_2eeBw5~T3K*(G#-`v;;3w$DBk(@JzBlTYetb3`4+(x)e-NoUZA3rw(FN&)o{u;eA8U*|0HQj@G#4?TqUdS5 z)6>eB+)Jz!MJK~HTb9gp0vXp-Z9Xm*ckg?-Beul>?U9f?)CDFirsd{H zna8;; zAhguMsD$2%F)8p!k<LC7sL^As2}l-<5!!0ZP8Il_7RxldoBDDs3ubFSNFF__1N zI>f&Bt{1$z%jVWxqU{6@ki1Y~9DwQh!G~Xu@q*)~Yn0H1*(MwIQM@rFLnNxp--<2UnDU3u8`@`Dk}>Y;_#>y^=nl$gzH zW5<72*w+RKH7)T)w7JQ{Mhjl8bXHCb^4IG-W25AS_qer7T?ITN|GxF4@e2dR~#Np zWF+|8Jr&w_l?I<)c64E3xZs0H*wpp_#Dva7>uZRk}BqV#C2sWZd$c2J5h%=BTEc zUIBNZg3D|k_hcsfX-pz=e4wL?>sVjATj)J5*hr>##qWK0m+eCnyh0Tdx_T7;t7qZG zR4sXfXWYx_b@^+gk{48G2ty^TrA272wy}N~eREn!7s#qCVh`EXFV_6mwfN&zsQ|Af z*d(aSO94_$Ie$)+nv7tV?=kY*q7LBZyV&w~l!8!aq~~0z4?;xmwi}ojK<(`dy!AIyEy*Qy zY*iyh*;E=d{CFdpa+r62(iz3X43JH)Ry&T3Gqde;&uX?)>jP9f-!;+lwAP+v{Q1m_ zJ$dQ|DTr;{c-92OmSXKE7Xm8=Lb;){ePm51kOcK0ep##LQn&dSy=DY?=ChAVaHMS*czf^1e#BwbXUH2#xQ8PCOh zAwBje0KXghH4^9_{uGfhR@N1N!)(h+Ng*iCmu)vXO24r*=5H`pdts?&hcJEuUY)gj z9c26(NwjXA_hkdK$_}jrXq+$CBLAe6_h8BVpNjSr*QS9iESJ>Rdz^VwCy~FYYqyV+ zB^Lk(yq2d&7x%;5Ye{Ums%G(RX4e=_wbSczE?D#BCXY%4rwb`bKZCcYA?9i zIMm#g$RD48zw|khTuw?jd1608C(0POZ z>RRb#l1n;rdLO=giE1)^ZVsCIF;r|6SA3aNjiePFyf^BRZXk5E6aJ+! z*`f*~fJ@d_X!TE>W;q4z+_ZvrdCZw`cX^MXDz*eU!$L$@t_BLztr~vSV>MM?YARGx z%=q1ff_c%R&=I1cfqCI7wEC&;#W7O@Q;51Gs@O=G;6LMIpC4KGZtfy+YPJc1nq#d2 z)ydUUa|_mA$_qNYhIF{A(U$MF|3fp>C43loCXV5)JM}`N$?gWKp(D1xqDOR~Og-2N z5JnVNQkkF1l?Bn?0l{K8tr3)47}VJKY8zFMz%^iU^zTzPK^-Q=msj~m-oN_rMqC*+ zou-b6Gq~*LIg}!-eg5q|RgBggb5qq(vY>-}-7o~R3W z?8!fO{lH=fH+k6zN}0L|^s4-s?WHkCN1T2@Y{d7n=I5ui)3yf8nmY6Hv?d~lL=jl; zSkVjI#aNva!6SOWG+@YP&W)5(gB1*@=J>RSJ7FiPqe_^5|&cX%1tI@ z4W?LY^@<-Z^0+hFKgm0P7{YoXy{M^$&JHEQ_)-(YKGB>A1mGHwVDEvqCpUu7oO_;| zS?rh~Zh?-$m3D?dPEvR4jTD|(&(W7Lmcd$tx8(>+kiCD6H||%ijCLIsSTg_iV#iZo z`Bn1m*q4U+1FlNH zjinjAhEz=fYIPYE@Bh$(ULR?V#}C#4bva8wRl;pZLnPW(6ZxLhj6k{kV>GJj^84u_ zVfWzQPGRK7#&>q@jMr0h+44N|iqC-$FjX^6ozeb5lE(XPCAi*P5^|CXfV&VlE52~( zi*26EM6L{sLv>|RwW5y;ckr@9hlkK9uFkTg>dQ|N?1i9fkAga?XSQ+ycJ25)BvJP^ zP^8Ldd&jLP($Ri|{gT)-{S_rJk663L#~bp~|B5I_CO?v31dM{z>2_>w$FAw!!g!|R zcEvTFjw7&adL-&jbUp>jv+!ShfpNa5X>)KO;qPUW`l@37e&62 z$zB+N)^y=hF>sk!Ayc!%c^{FxHbMOh?2gQvb58Dq^B#;aT$5 z>F_d9BLCpPdyQ&;ns*m1zOaT)cDd(sYs5cNEB*Xr!rk@+GC)xh%5XQ=xyjB7viKBQ zWC1f?Y1{E8#kL@G--)=37m4#SN1PS&xEli8@Tmtq4D716E5h=HBG!FzSB+x{WhYSV zW%p%FPw&oN((=KHRa zC~d|-bX;o*2y#?IG;C|U6t>QqrzRhjk&efQEi7yar6kBQ^v!_ev<{8q;MenG{liN6tA491)BWI9ODCTWC+;WOTXZ>jEe`qOD>#ze2DWJMQH~KT#WjCMvfh zb{6}*C?U6VCci}MbjrV;y1S0a9lt0WN^GsdNh+KE$UH1YfmD}`ZFw=4s-nQsE%5Z5 zqBn7I4vSc$$i+ACrH24Hkzex0IY6|u5{T)(iT!Q~F)&qZAkL)U6^WV@?l$)Z5=t#=vxuoh8Z&b42B!8ksYXxw9{N8bZmIqgEpDm2rlXxM)s zdOzJr#RN_yos8SYs(z72dZtaWNiPQVRZLLyI4Q)ChFxO1(FmS{KlU;!79 zB}P^jRfO%+Ifq?hzKR=21E;vmW+Qg`|7~LSihsQZ#jrcIh5`EQ=X;lvkMMC7z&yKA z`DrJDFztp=cl@y2kQ~;W1yl8=jcj*qzkX4A>!j|uz2dG4T!0}-lpnZ-znFGkkd`yK zV=v;4v2G#R4aX;7(@j58!G~o@tyK=hM%P5fcC6Z? ztGPo!tXUJ84xGpeRaPs34kMgo0)V(2))$_M|K&ox1diBVtB(8)cn#+OWNpw`mGBc- zu3Jb^=%x1IwJU^Mwok#mhARgkl^MXkoeV4OQ+FA$uXDWZ(_5w9tEoq;LtW!$r-}2f zGokKY=ofu^!=B_HWMqzLLfZ>fKhqgZ&5yI?HH*(>+Yzu_@iZE8D`<-noQd2I+w6kQ zpX|^o=D%B3)!_fUMuC#3ilz0s?*_p1an;(y?jIV5x- z4V{rbO@KlN`TJlPIznF2u2=zLU0Ed0;cqc7^lDa5OIm-92AFsec@m78I8D z%%vb!tDWaXa;;!a?)0zQgvJSq&%V_|_QP8hM?_B^)dzk1Lp#vk8t#sAmaIOU#sr7u zU|bw{j~GAK=ifStj^B5o{_%u6FAZ$67r%r4%H{ zhJ287@l{J)#%OW$d8Vu!A-#2xJ%(i#i7*c658DafyHuMf>rF1*&Gd3l0HN835M_NA zq^@ggd4lRom?4Z8ixOj^`Pt;dopcj3g|PC^o=+r<=*iJ#5^(&0E|o;YMr*JB(dwNz zsWy4$diYC;6W!-)Zus8iwo`c18e3GZM0?1Z{nUPT+C<#4EBu|p=|cmMjN_;9y!Mr# zLg56nxdwcwz0($GhEFAV6X6Rt?SFX$$TP-wHp;^9i24681&D0FK|BGqG(6re z><>+^I7m@T*q%6va9@6uV|6=BQxgetui6n~guC=}s}{N>a>(w63{;k(-?tn?=3ui& z-8frj3WL; z7JKCe#gU&9lS4I3oXm4Ma#GhVXSG)FDZJ*Jai~ zn8M@UpPF2z=y4A#Mx7%U_ls5gO39(bFp9_lQyoP3OafQ^R|71`BBpa}U?Gr7KEM>A zuN(wZL_0X39BHWvULRGzW-Itoh8B4J7CNo{lj`1Y*B5`=fG{dzY*7|L`~hk)?)$E9 zh+Y&Bj_pjxgaZezg(R=5Pju>obOARy1X`0SjRnq_ZMTFsBw$r@S@I)YpFUaB;_*ps z3n;1v*g0vKj`gr~DHJl&^I4`%X>6~S&BcgD1&CQ9D%=8mb4T$?o7PchE=1$|y?n+1 zZ?yn&26UOoV{q=kXE(3Nr=^rVH74ghX%|P|GQqUW=BEX3<)rIadR%Yu5)G)rYlvwO z2V$wpX7k0k{ZAKjxGZB$cr!b0yUV$RW90Hp8BPE4pd4_Dn7R5**w0bc^E`o?QB$?{ zj&R7a`}(^?=;EV>0Kgh01C9hKYkt6`jlY-fv`2nwxMXV{ghfJ)yb<&yUiP9I)eN~v zGd@bKp9`zJij#euNo8xvHqP{{HNR`q{cSNNyl(-0_|El4Z(L;hvHN5hM1*=?etIa5 zDaw1myH}aN(6Ez&9xnNkNXe=*23lm7^{Gbh3)Q2~PcTi%KCm2dCpkf;bXq7;-Ux7u#aT50$bz=kVcpqZJCi<0MQvTe}{)(Q=u; zu8aE-M&?}a7RIR$1r09LP^|dQ(KMf`k`b(l?oM*qD^JloU>H+ORxrn6FBAU~wvVUn zgVt;n4_F2s3>)^L?zGf6)~)rZ-ahyK4GaV2Ape<_t`GZ|mB!h{&uQLi8WpuBIRekt zQkgy%*{*7nW7u2_b=lF`iZAZgvw5B^_Cj%!kmIIO`8x&$D(bZi;#WdU=4U?b7)v3ua-~KotURk)-7d0T;O-PQO zYnJ1Rd-Qj;a(~3#i?ww7V2z z63asJ5J$%zcXppw%6SMvu}(YKfhYD~B+4AVcgf&K(|qkZ2hG$-Aeo+*sTaDRWaXf4 zzUNw;eEPu^qSWN86Hlc@gWkz`?;D>G$ z2aiwsM)`vvCp4^Px#5QSIoZcKdeB{w1iF@aU6thUgUfCSRHSAW6lwWsDP_-n^booOGbK>N&G+;7v>bbvS)iz3^c~v<+f|d}uRaifh8q3Sqp?SlyWiM1fvY{i{ zx^!p!0NLcM7h!ImVjE+}@wZ)jCb{LTLG-r)3SG9|HXsB{}*d-9*}gtxBZ_PPdR1jH06@H%uI_X&27vC1*~bxnXzQb z+)+w1OUsR1K-9|2(v)dY(-bN*#tmF@O(7S=om^3KMFo`-5m7+I-^cFz{@rKJ^XK#Y zTd4R2`My8z>$+aoBQK3TOQq_!%bDpex0+Gb$X$y zojQIoA7Iv{%g=leOe(-df%YO07Ww`8GeN8q)5mLfOsaCac@v|xI@;X!sLRjFJnJJa zCNpFN6<`Exd(K<*Q5E7OKp6s4hb3Z zX2~t7Zhy?Tn^v~_-AWi-UZELg(JfB(uJ>mDg&k)4`(DX=|v+Z@jB7k&zc!%`EWYw zWpMmgW9_$3#BBhoG>nFM-~{ze1REQ5LBifTAPDN zo#2wxPPzX=turlgcLDBv;P09-?ann<8}iKdL(PEdEuixXaMPo&Hadcr=QTEh?x89O zrzb=q(Uu4Qnu9~{)-v4@a2zcWJGO4`y_6JEN1T{jUY52T>Rt6t|95}F#BViU~U#!?6++(Pmay3t#7vqan!L?>Q25p6zSbT_P<=qHCD~E)*4UfJyHF&^cqIBbIS5OdbL557A#(N ze2?Ea^<29s1_#4^4k3qP);@`Ibl|r|GNK5wNuFklzIl^>G6n`C>i$U9qtD+ie~h8=V5-h(RjXU5ZP3b@N(t0U znCCWg+8gY3#bVJ2W=dOHy>NA6c}$eRdF560F*;2U7Zbe!rzasjujdNW_e*RUVJ{z( z+k1J#cYXiO1_<;H$4F)1_M0hz!F?5vpVXbvb&g()(}!u(ad;6pHur2;(xBOB&1t=+ zAYv&sT(onasP{HCCi=qq6J`62Cc7ge+n)!#QcJ)xJ~K{BCrUMhaRdLAuU<+#M}mnq z^VNXV-%)=x1ytYqIMiACth))jslj?r&_athRtW;F`FBN2iB5Q?a}2Vw!DuTp+W(11 zC$Iu~=;~%g5J9M(+(}XgZj-XSl9`>>%VyuietkrgAsXL3@Sx#el&@moHiLdhBX*%| z-pS4eh*-olo@x@wa;|KcSE~tB_6QKEUQh1Z{iYmQ6gjXZeM&jor6#ci0meG2D`?!E zX(TnqpX|)1=4+HZj%Dgbz;w`AF_o&FVUd(L3>-^?LeOGOVO6;Yz0`McaU=j6jjt@w z*84`E_VJ(B9J+mCiyda?8X{`(kcGCYynBuEu)T*wa8TdlocVtz}b@c>-dPT#_ zNevx-{gsCt?Fn|-6u2~Re9O|NT6{;HN2-_VXCf^%)5MR0gawfQ31OEwTyOrMAGy?F zL^Mm}s~ltXUcNY@`RpC%F@^n0Z2s7VZR{-`j22&`LWTK6I!A_hOqR`IjwQxu{Kx(E zk?ws`-pyH&8b@Zzu@+r6<&Q-PfSU-Rg$@*RUFfoYI$8f8ISKfa&B>X=jXcHcnr>@P z3D#!La@A!r^!nu#iVx;2%NGDE&k%E{RU#lTqd;ed`=$HUX&cffOq_nx!dm=d&^Lx|^SLK@#T1SBiYEp;r;v z{D~3zfuo8<>->l;{vvFl2o=$`T7xCE{B|-%&*_K{PNYGq!7MpudFi)xg8931GRm~; zW7viTOB@wbt~yy~(CHyFra|h?2}3(~w?=&S@(gXL#5q&SZQI1Ba}UG9S}T`ZEB$9D zP|C9$C*>IrI(lAC%+hvdK;Kl^;=xd z!3mNH9@p{l`4sJRXyHLj0hW;`>HCVHAxcy_a)N#}} zZ+6Dgdg~1{C(`s!)J#_1;h2GY=xc-~ce%f(8PyAnjd>5gMo^L`GRc(8gz=Ta6sarG^X z=dPzO_KbK zEF?w!wKi4hwcI2ndi8UV*_dET{HNeZ+N&GKe%O$f54_jTe)s5VX5te*6w20{0fmk1 z1u1C4jU@Of{$(P1mXp022Z4OL)aPiN?3HZkz3$fEv2Kl6>kCO)o2b9$)&EbPhC?n7 zB2NqC=4>+3pO8wyz2O~aItJr8T8Yw2_hLaUm*>-LI3S#NGa_#;>?d@MwjSDU9?6_U z@A?2_W6M7{0%qOwz?y4<`2y-#RK1E!nR9Kv zwLK2sPazQw1>Wbs*3YzEYS|wJCjIrskYGhcWSd-{@lr~@ezMBk@&3La-Ao8^qhmWy zJ$^Pd(T3Cc^ner8b|c_C`nK~~PD)sITf$UL;a(WdmC)#-O2W6_;fKI@VGnX{-{@}> z>Y?4eRBjM{BS40yA6OWSmvz-^>g{w}O;sXC&ZzY6x;$8|=49` z_N+8R&DpXpVe{2E)mTLQ ze&Y;E4QD33I(tL{7N<|G8~GOyU>%u*Zzt2thNzIrtq#=dQeo9{%t{>(F2F`@8p_5r zX^Zi7fbnxlP_JCszOJ@E+EHFE(Y$NZF`2CUX5m%&-%e5nSY^)X6C2vp*i`!bfpo9b z-rfHYZg~;m1;8@&UFd(v40bKA?FdZS^F-h**YTlbHP1DpBg9QeS;t;Zq0JZFnyeM| z5Ixxhv`kj?@_i?{Ay?wbHr)9|EMA__$o7o7L$dT(LlPzc8?!Ctzo^*xCM9}7Y@OlM z?D@+4ZFV>b@;ze`%%z^TN77m8x4oyXiIS!!P{;tG-#Y^Ry9~wE6^j!$gs$wqSo*}F zwhjlEnq@;4nK~;Z(*j1scEpG2jOZwnZZwxm^j5|1 zSpj|ya9*W6(NTzrUY@WZ1$f}8y!CH^X%C6;Sfp%gF0X&o_}zFaK~)3JEj7NuoB$1s z`zshOS%~7E{VCypdl*%6(J(2TyBk=5QOc-hosT-1K_%AzV!sv#iXw;Q*EYLBPVM^| z=b_l)r)iSqzwy*VtfzqrOo(K#1|MOaHUrt~yKY>16ZvlbT&yOos?O4Iyyu`70A%k3 zfb5v0DPhMdibdj-5Yw9X&=~=YJeMMpJ7@E%0|Jjs=d)w$YRn>GGpjxfWs?rtZq*j=It<4HNa%RQ76O)%2js>nNxh9JGbz9D?sk5A4Dk2g4su z2`vZ^@Cy$)2rY=!BG-b@CSkpWrbg_P>T}|;9~-VlBKg14t;~j;Ej>1m&+8YUOQ~Ke z$Sm4OjUFPBYv8{D{P3BBNrt@W8Z|rgt;LZlcWR(ewuB8+!Lzfba*R^ejFTS(1Xz0JYqDy~-=*JHn-&jt_-j`tITSgHe zyPVwjYw?_9PDjQ&;(%ZsmE6X{Gyinl5zX37^{-gW7|--m{AzmD*F@O%DhU)XskaAg zQ8M5aWa_oc4ar(Eq5-1vO~CR^3x}|yzo+PDO^JTj(0wI(3SBv6it9cojL@>ZSgLk* z-D$=k=DkrA?nn8yM|z~JUyY;9isZYut8V=-q5Adztx%1m98^$-qd@;&n8zS>b`fkt z*!5VQOe#(5=z@|9Tump-#Zu&T+wIz$Q-6N+?WCj!;Px`bK7vc%RUwP z8dZcCc6KPo(E`5c+7(N7l8Zp&!?2u+bTG8gzIy7SV=O?s%=zXYs(X9XPJ-1%_^G+e z`XW>jC@!YZtMwJT1lId&UHOQ9mCe*r=EC!iBUbEbR>Xw^BI?dpw06GJH(4!YR{4YW zzuWi?hE$taziBeXvA=xW2tpYEGmkAfdK$Q=ey?T8eS~+VteElD=y8wUm(_y50>i5& zTdf{qRTpk@3#`O*anNHtS9aFEQ~$qAEq-b~<~L)biKyvERihe(PCE&p4W#=|fR<^y zX2uH7_T(`->mE@H16qTG^}aVagZZb`F}fkyR8$ZpOOz{!>@4_d>vQv_JeH1*=z8mF zAq1|6?e7YBVlon44bd{7%`m^}oA=Y#&BWYFfdj%XDKLTC@;JemL zZ!9|{iQCyNqOhB*$o~9+6KZ`v4hO+^0c||tlP|Yb&hInXj+_j|L&jD4^9uaYW6GZxGmEo{gnua@i71u}>EbAw)9 zmQh&tBlKjpDZNrv($#9250z+;@D)Ah&!kr^Z#DV3^Q$);n{8Rl5wM*u(_^m657)kR z^T|~jkNPVZx>fH6cjB4PgLcC=_9)4u1Mmpw6Zk7t3ns1;C=WUV?~B5pz{MYay%IkW z`5_>(w!yiigAVfkZLC8b|iO2cIH2iPoQion}5PPEVe!Ie& zs+qp!%3Mv&KSg>MNeF(;@vMoJiwv6tdW#Hs#R~X#^?tSl?2Y7#?(1ixJpH}j|g!6kM zy+s|CzH5G;`Qxwe?WpUTaS3?&J+!miAYn^yTii!R#Zfi)GLB=wf}(`--+FakLMNV+ z6RxQ+(Gie2MsK=3=)4iMMZ{W1-P@aUrY^0U78F6lc>GlK1w7;EazvlYCU<{SW7UoD zrGC=Amg0*}MO4TcAZZgbU1?v6D% zRjA7R!)H<|=lxIvRPO$|m78`FCr|Ii44;C`iyr(4iu|xnl;AK9 z+C+9O*m88Y7wr=B_6S}`YvzSl2iT~S0qlz@NPOxUthe#=0I7nTb@VB^&M#uW>!o9P zZ!$QMV{0cqh?-V7A9P|<*;yxnQ*`yDC<*uvz8Hl~Ze6bEtCT-AQq0cw=ZE$y2m{&- z?C9jWzPj2-pCWR7Z>h(u4$Y_Bd8bS?Vr?N1=tG8H6+p^=0xO#|N^tW3umI>P5wEWd z_&Ffo4a5sHZX8{wS7z-7=rk8CMwC*DS>NYLjH% zBJsSHU|BS6!C8tNxJ_kNgx#WSc!lqsz1Y22y*6DkT@0mEhvF7bfR{Y3YWc0426Bp@ zd`&+l2};hno&*BMa}cK8D7>PiFF&#KxMs`W&1U(!_fLxG-<5B;q53DgwgnlDeO0Te z%v~MD@r$e!L$+&vvHWUQG=+HlLvrHQ)!id~7gLp{AX4pV;zK+RO})I{S~FVO<)7U3 zS=#q_E25^9QdF(R^rKC=(?k|;QXOmAjsvY2iE;E~L6*opAnXj~W2U1~0Irt3yCwq( z^T2_^U|>M{^e=sU#iEC-!3D}oru2hsUSIyv$xr-N)vn5f*^uCv0~}^PxpQiio8BDY z9yttKZK};jb{WIFD|x5oyJB)bgLt&v+Afp-cPVP8u=}?K>(U}K(Ds1Ft-c$NcG3BB z&5?(bp#)I$T>Pk>f0$}lp0Ry2VHatbu3-f-g^|WLSkQa!dM7ngxDzdB-4=WLFVcub zw(zvg47I1x+G0T@CDlB$Qlfs0X-M(zV>s73oA_in8i`;gM=+64K+Hw4^W++KLR5e% zy@BiM^pTH?=JdR$N~*VFiYX7$Xy2?4?fV`QdGQ(l+Fg$+*-y872V?A)SMF7L{Z2>_ z0%0Tg@4`lK=E8BEXXw2}>!Bzr+{t(>jO~fDY&RALG|=~fzjR`x;EM<3#2pjq^26@u2w>h9 zi#H9!-T#yP(yAm1q*uA+my7c7)O$RXRluDb18$%ls161crLE!litT<0Tq6YX8UKS0 zIEL$EryuPXz6ItXbc}Sx{6J!SF3rO}eL<&C1tPfciN1OVi9|42&V$g#FO9)?CsWLq z*mOId=@k6}Jb|w4CA9{sOuNVcl_Y?_33^d0(J+`}*aVH;(jEgzCCr;D2Am^@6hzcY+#k8FC6 z6xJuZvIFNpF)~f|C6v8R>TYa{Zbf>~RGU2p<$(%XNDtSeX#ug9m zA-M-;QzN|sy8I|CqnNI>5%y$=)GM8M|Mq8LeHBpf$+6gXFiKgL4nnJPN&I?6b9Y5% zgGk5xNHxr*RL~Qc4J*I-WzxE9W1&lHuz=b-#_0Wo?k-K z8{M&R%7!@wgFJ<{Bj}B;fjV*dae3w<(`)H*x_o@oUm%|O2^-w_xF}e!x3)$Qyu<3@ z1T3OvaqhSE7FLd?PjrTbCH3g!2f{}~yXz@MM=fICR(3qk%=!4y!i?f1K69ojaZ27M z2>B46bXtACmA9Rw;cfFbbmonj`!3}XMMG2P{O0NLPGf3ajcn=x{V7Xh={1q$tNG0+ z(a-Q3G+ECd8WkmV#P8l_>D^^z+F#*!5u-J-JgrLJq&ob{3#N+4V7o2Mr)l}pGQI0 zrdsn$mgaJehHBT;x9cJB5K1G)@~6m12Ucl*w{~3?#1VV5z6A0ACOS>33hwD{QCQ>T zWdMN9pQ&ot4VNH0bOd(8*09)`+q2~y+dYtVSk=0*=9I5ywvK+b{!=QsE7q72^yYgc z2@QhBQNqz@@pmQ(&Lv$vGZz>;Ky6eGGHJhCO1T;+q3$g`x-VFjmHv4f( z<@m-8ym@L2oLUpIKds1}WzMA?@g73BN#>vIv#F#tKWwdjBz+n_5R5Oc+)Lthf!QpT zeLM>85&Kv)cz?VA3WVizpY>wdW4KHZp#F5VPR~K64RmKqZ+UN2S7A4*A34y5VFwCz z9fdCD@N;@8#YVNN-Plv@%?r|AuFy+_F|D3{+=v?1H`jd+&RiKl!P7L1(0IRz!ukB21})rpCQH&$LUsE{1t32fXQ>emYsJ^G|%vmW~macIzNmzklsf z0FG`PlhoUQ6#vqxVaxVer~#VI+sP`Bgic>au|>oJ*{%WeE?sdHer72c-w$wQ>E(D; zf-8fiRb0B6+c5QVvWKveFP5&fj09Y+rOvrMs)d*^dv|Lnd?xV-is>#hmGPg?R)U#2 z?Rb1=Nm-nHyh$7}HHfw}Y|9J!;AcVGNTCnopo!zff|_sx&|A9x=+Lb%GEIs5GiP%cKEAINpllB8xg zQr|w1DqO-~T+2xpZ1CQbD1pT|_gKQLH3VJ9s|EX#j?P~0^1S8fxIeCVGAL?jniqWP zD=_l9WVXer6HXMSDqAtn>woSzNR3o^0!5HGXJ*PYqU_|~18jHOt{i3V@_DyQ+=;TS zmf`Cbpu$)XZ%s7d4myvOfbs33G3k*gV zce(U|KlA=Yy#nAWD!t{SkBivXq&;_CF6C#Y1k8|cdgd$vW_P{Ivqw5wL%;W~Hj13! zOM#xTZ6waQCq$yg9h@vnfd64UKgXqVr1H1(?Ilhfq6L>hL$1!MQ6ZBCe~n=Wsw%{g1`v}sK5%Ymcpi9-QR zt82;R?Xl(C=HlwSlMmNru7n!n%VQhPtI-)QBOA4bsFasy>0N@E53O1pxJ|=L((k+% zfGr875(H67sy27N;vb_j0+vIs{*f-d-&vzhCfhVboLvOI;r^D$PO&1CV^k0)>U>%K zX|FYeU0>tHdKK~9c5R4-5cJraX5)5h)JYVAg5GEE175c;j)?sp?TX=^0pJQAf9bzt z)OEV`7s6&Y3Em~U9FReGNdYpv$!6hkG9%g5>;q8(T^5KtPITspKu z-N4p2NSl5tJO*Nhli@ef zG&KK*s*!`|^s1;Tc53AH>?&vK?7nE($i~Uj*Gv9p6A6C&<=z_0i8ZBcSevX{4;|hM zu>DMz&434T6D&aAs2g9avpT(dv+--v2YOFtlbZW@SndP8iZ-Lu(Lg)Zdv?9ftIHfXfN6y$$x!jYL$M#j zj^2Ph6T@JEI!Bt%Ujp!0XQ8f#6h6A0s-;6bhW@-x(qYLDK7bNWXxviisAqYI4Y)sYi;e;4iQEB!8v{rAGT<($PgpDqdOR09}> zcDnc?rOhp4S|IX!%o1Xys;xT~Ji<*4m7;&sYtHaA$(4H2s{|m%+Y)ROR1z|s&`!qQ z#t1mW%N9Q{JT)xj+mcfGVNhVn3YNamCa zesSnduKx8DKRpmfh;nwFTf6#2QNC%I#h;4viFREog^zYbj6GGWYycGnZ#iyCs1z5> zC3@NlNxZW1&BGNHv_{v#N%ZUK_aC09fSc`6lebyU445D$zR0^P1WeO|q-}SIh*(5Z zS1)hF+AKE7Zn6G97acvSO)sTJulk;IWcDH1k2jD5nzt0KBzY@us{e?7q_iEaFr`n~ z(55z$yl!GzcOF7GTj^_OV)mbB5a;FnhX(D+HPglx4oA&YA12jxRH1rBa_r#&4lq{+ zqm&=Ax7exjLsnb;o?9BFfV>!n_SOO|(nDv#KD_7RDRbEQ|9-5YE>%SpQLO_UzKg|x z)iG1>6#>tnMmGIKsygEC8tUNyEcyzsUPrF=QFPsu9KcR{ck}#auVJLD=mh{yBp(wK z(u!WX_cc}&JK;_I-ld%#?O>xc*PaJ}2uKG@0u`k>Q=oQ^t`c>E*pQu%7T$+4qnC{B zk?MBlGnON49U@O%Ul-)0{oZOoBpsurF>ZK}7HCpye3cRKyT`vjrAXF7Lr9$-dcADx zr^J05gAoT}j20hBetzdODVXaiaKFs5<{w#)j<{ENPoZce9JcmKAKb35KOKs~GM?a5_aJo?hCOEpRpPf%+%wq7hw`C;n-Ch;(JQeoY*v4_TdN#Vca>=`c^ z(yY|(D-7*(4AhLVcMO>?b!I*;@HYfD3|=LEGD>H@22>LXb(2g}wuS?sNJfAjs}Rb8 zf0wS>K-%RZ-ZH;yOm&7uu&?QlVqx_A(r>M0`dwGYq^zk|Bu1Ou3A%4T9+E?1upnTc zxJs$wB-R07OK;RBlV=rdBYupY41K*qJ4~UwTjoyx9fdOSPY~^U#%GT!E};M<=P=Za z-Lsid%-NJgJAu(;=QxPWin=0Q4hgJ3oV|ZOjJuXQf`Bv;zC=Q#Pa$?_^euL_c z0xrfskyH*GXZuSu=9>Q3^8)eTlZ7697#NP@kt8-8YjkLJkxjoZraL9DL>>ys?wy!a?8LN^akYL^1I z*2A1gn22ulHT^rb(}8?4>v_b(KmWs^l2EA>a#b|{$C_109fFb^7*^KEET_j~I~-m0YMN7J2e;oK0gfT^eE_>e%3_3RMr z{p}x+S=jdNWFwI-NMe&U2CCt7CJX-3IAts5leP8w&{Wh}b}mx2v(o7pFeE)99V19H zaKoVV%GB1DcuY{Ik!1Z*dtV6WqkFuP@{x*LX)l4$K7H!6hxtzKVA%3S($!XuefQc6 zMb__&MkZnJKfOxY8h#-zbFrAyZoonTm<4=H#OQvZ5w4r9xNDmXOL@Ucw2wApx-sj# z79jq#1QYnh+yf*S2DkuGik5HDaqfd*H)R$g@?K`tJ-*I-IzN$pCVLlqYO~SN<>q)e zpkq>x%JVQ$Z7|y~hwQ@aspVTvUNjL*+17)1i+RUWtiPM%Iy2+gJJn`BVWD4g)fqK^ z>ja^SJ8g)Nv{|#n?;jf^IC&wk+|r!=qREo2{+CiCR6~x)iCc`4Olzreve{dh9nkBh z!09z-O|VYck5o14_-4Gklq8*Ya*T6#^{ytXM=mNEyW!7uH>LaD!aR&Y;J-JSi4;I3 z*W7c9Z^7=Z6@Wmte_D$$F)cN@F}I9Dlg*ETIlrREr?k6r z?zIX!yz8p)LxxPCIg*vRfAIHoF9wquY#a?yAID64SUc$`vSLtV=C~zKW*qB4U;e>Z z-pI+ZBc%qaE5-g{znx3_S2=6X|a3F^66*@ zT%{s+o2Cxti108%a(yxiWj^;Mx^8q4KU;1Lro!cVYLrqG5`|0?4qsi4P2z9Y=FW*` z9$>;R|NB6g^#T3_6Rh@&L=pQbv1WjnsK{2A|L5ccr$CggoE}xA3*7ka| zZ!eN|?L47>XXa{(nrgw;={1!3PKK6bqPVSn70bO0`($_n()+($P*T1{s^u)CSPAg6g99V?n^e{W+8kEF$&aCwCBr2r5q^C`& zfgbd~6>&D0a`wnaJzJmX6d;2~6s}g_@?noBQl#%X8`-^SezS)~#RUL&*2~pwN}m@K zkCD^nKd6=LzLCcZSk5eh08e(+xptcMSk!xEyJ#j-+VfXrQ6!RpxI2`pX2lNqoaNJH zJ*dfX)c9PDpTDfQ0B2RMx~H7otC!lZCBOc1nWr^^fG(CciSBzOh*N2}J9W-@O}-GqdANBWgoXNclABy)f7*oZji z*P=x56}L743BX;!b@fk-V-bz+QFUk>O!Eb5;k94N=Fh=6j@o_sxSv5fkNrugn;!i( zi)7xP1=m!gH;BCp$?-1@ma4n<=#Smcb-_CCZ?km={A{LVBaW} zluo#7N!q4tm{Uu3Tg664;7(9R-$?=qyH|j@3EOJRdj@=Q6Wv!9V2qo$TcM1wYZv5U zTnX7{aZ)87xd0JWkx{0A4W_8-8E%in{h^WlFfa5XJHMASk;fb{RapWmXf2 z-k=!D>+I2q94cD0b{)04>tBVKo53+osL~zt77?}H2xdge8d$Jlq_TwDbd7YcJlwmc zWe=P7-Mrxk|Go+eZrOa-#3BxaT~y4UOd}rLya&SNYxIpZD~9G&ok%%$QF(kRiwEPq z{Px36WvlN>M{Z3#aWwXpbkv&}2!{0;1#u6h1Tq*sOZ^xQjuRn$4k=)?;Qct6?lE4gmWkUphGogJ1L z1oudqGw(6DjsBT{#5Xm}U9-2tdKSDiX!E%a6-F%V(*2WpqQ^^8V9*IXQvH)s?kHDN z6>)=RQmh!6j|y%WUxC~f-5jGAo}l%sVOM&}BgAEI{CTumQr5mazI?lFDoY0k=!w!j z^nNwikY_UmFR)XLOv-neMEaZSPo`WPOn7*3EZ@#6eBoAa&%zw^%l~$KrX2QSggV!T z3LZhek42$x78b1bNx9o@&X?nIuM}uXpthEFmH9U18${OT@AU?EeoU&acp)u(;8ozV za#-}N(GTI@eM8t<#-`Yx8F3y@VX`toi=&#hlb+|LeAr0ao%Eu60WMgH6Gii6L_Q@L z`|WPP#@Ff08=6|fm4qk#$TI^~X-A(VTaXML4U)suDahYw?GhVGg-*p@vIn>a2MOFCw6WfBq z49id=6w?3Rz-~tYgjTp!hr^$h_;GWL;(x~+AaH-xYp4+@cb@$K?-~A0${~V|lpoSARj8E(<;F%}=KqSTSEc@I8C=TQ)vD z6COi3)pfHCUQ?=^yo6(e@pKht)U42MK)}B_9`I?NC#&;v@-ZCeH&$Og z7yGobT~-&!MGg?+mMk{UVi;RlH(^YZ3L<0TrfPj+lt>oyyz^aGUVPXyZ|y$ilPIY7 zl3fC3M0316!;w^7$b_YkM2V~SKtX2mRVZ`a>+B40dBVg-JIt>$Smw+cH3#$4T~GMp zf3l5XN5CbqOb55&dY?%!Y6KgrXn0J5NhIGjcha0!rFQ!Ne5jPDdAiY@-!ewjYnGis z;RI4>$hEhUHqSljL>S%J1YS*f6d;xaG{IdaJfG;^)T z(>G3^jmoX30Y(ucVJh*a#Xr@a-){1ao@F`2$#KUN85{CTuM!X;ZlOz{|GnjwX~7RW zCy8^&#VKQ)_f_hc#GyI@2O@;4?%(3nv)s^wHZ zY61DIQP0aoytIh#O78H0gTzu8`EA7HntK-2otP88P|$Geh8v`>MX`+|wxkXWeX_rMbb=h5$JdHOoXGs5OhX?vkDp>SGo(O2W5{K*h@cov>Hg9=hrdtL%As6-}0Km#d)uu{q@ zN9@#y>FdCAQsYS&z4USIlz>b55Ex);q>Jl^TcRjSVt(u@GdJppF0oN9!tz7?_J|WG zoV%ys4EuY7*hJHZ_rNZHmz=<=zKyD^#Q)u1N7KC@m)X95(Uc>*9sR)3OnT-au+vUf zNWQC$Sbwi3f1mJb%jg-&;=b*y!wVQ*Bz}?_aStwB|KnbCli{JlDHs_av|POWz2X~6 z!kqX|{w*;C-oh2%A(hS(9z`8Ya7sq$Q?4hWXR^|x*&%2Mm4u-vQ4(4sFYR5l3}V0y zYNwv=+uQXB-M=LVMRnj-&gUr8d@J#FiHro*gaI|wLP#VH*MO)!6weXw*(Fe@KYr;wS@0~5TBrYT%NXM(^SlVf!)1r;ssXH|i=0sX|-Bd|AMy!?W-eOkShtIEQeTEMb)?Z*8MoanE}G$?km>XVcgn;JVDnRCs1`{4dTJQC(ilK3I6i zSwfvz-5Kio7!g5&rRf}FTC$*KA4fui7d%QO|F(+m7`Y8Ox&b~9MIm#eH^|p#6W(m* z&tv7AT;Y|?WK2+$LPUyXz1d6OJF)dX0^@)Q?0J7>2Wlv5&3$UkOF}DAYZ^3I*~6E& z1qtI10yub_Zc&mmL*(kESyvp>Icitw=V?2YuK+o2ut(}?b?xkaO1vj(nUQR-lKx|A zKx90=7J-%&TBZi|w}b#V`o;Kb$-82b0FT(@7EvOn?Oyg ziY$xn?$hs!_;@R@5mW4O9?}&cHarvXaM5GLS*LSAv0IbQ_Q)lK6I8a|xSnfw1gQMm z5Fa~M@lN{Dyj_@ur*sw4`oGEiC2@UrrXFl+D74wjhTz(~!hN?CF{(75XCUndPjTJp zGr%w{jckfYKh)J6RPCrt;94I~|BH5@PxV7K_2yVXmgc<@aN3QFCxmU=l=*Q{Bkk2O zE8Whu^9hi;i<6h?TT^yK_Whz6*tMJ4;6s!)89lE~5!M)=mALX;5Scx_!Fts?=&!8w zFHW@L3VXt0W^B;X+JUTyoij@<@~l-X!$1($eISiJ)O!M10jOiN>w1f$SI$_*n%zMs zwxdVC?kaa>$3N;zuZTsM5D}Vsh4`)J*HbLgJGBTiD58zC!vBae?^DyiyRM&=0O>F$ z?0xJ(img>#_|GpucL?kA=AqM8x@qS+X}h%Fc8OTVLU_=RF+0=!=ieNU+m|Z7zV0?^ zb}K%?Q?eG+JgB*n6n(HOW|P~=x@1Gk!pDUQ<1x?*>s%&zy^OZ z(dZ=V1w5rK!V6a?hQR{(IX~xJfd+oQ#-Zz4QK1!Yg5b`}fi|e8>6Pq<&36LUSl3*b z1Nvh0*}enh;Xd&9^3L@rFSL$**knCl19qK}YY;i;BV7Fm)%3jCJ){O(eDAV+uw^$g zyRq?={aH?FkfvmDZ?hM9DCh>ruXPSS`l_^`g{2HvoWv<{S^LFy-Yj(DB%n#R^Dty z6C&x-=XB}W&ARLHa_CWZ^4C@>uFk)z7VP^5FcMau?}!|vTGCb?m9G)MTdn&M&1gw> z1@G&Bfxq8k$@Ih}mx%{z*XpS+KAp(@%>gFJ>k(?X7K$FUhSrNw{TTH)8*jJ$8Y%NN z$D;owfJVAX;7I_#t4=;`M2<`%K~svr6j=RXF-xE{Y=IN}Hj(_o{bx&Y+2y z@e<9;`COfEQq}gVNM~4`vbnRLtwxv^3heA{nR!3hL=<_cWf!75-A*PUO^wg;Tx7}* zuxIg=eQ)mZ@bGDJp=9wgF9j8Qm!Br%H$GQF{JC5-$$8_beIexX=hC2}eRqiCt zR`YAZ8T((>8%~TibxEr`m~f9ZW8_s-o>;G2vRKk}?qT`GRI+9vrlm4;FCP<9 zwTFs3Pn@KA2V->bzR}5)uQZH@@=1nUBbpkR)^_GpWQtdD;-*5DNVZp=teLLd3eC3X z9}d&4SbLVQG7i z3^rP-t@os>?}alXg2Kn?AW9x(UhIBd!C8E8$)oxq8sp3>(^XtwG37wwO7U!XxH_R9CLbxOP|2C7ck7m$l;xNqBn@LBU~oeF;nj z*0v7SY?07grtG$ReSPCooyrGazpyv#(Z^LcD@|ta90+`Te8*t(Vc&03>Xo#nI2wdU zsEp9ZCFJvtzn%T*hY`yl2W+330muV`_`k!G~XueLz!JhX&rIpIYIj;--V53(Vz0xX9BPe)|e!(#dvo5z4;*i zvggI;L8hwAG#>`|ho#xHpu2=O=TxgQs8wyc-@E;BsbFNelia*-Veoc|l8O);E zn?EDIH+jZ4&D`+P*}&+?9#@NM5W)vYxh+U~p+P2zB#YWqq7d4RvuBBFmZ_|STc}>_ z;>*j6<@>~5&TGt=`bV8nc|g=1zraOz|H525KgFB3eA;>&Afr1H!x`j5JMl~`t)JZH zSETW#&4`ERo+D!1Ym_;~AC@6&a8K^+r4LVhon_8=|3%bCXpPq>xrMiQd+o@aV?2k$Dtir|ZzgjQ~ zOS|kGe_3+XbWDL3)cB;!u5KqBL-|9I(Op0J5a|D$ihiBTxV~sLq~L$&fMiMGD55tz zV~(jX{=7{MhVSgpWSB3;GwtlFJ=xzCdFk_3gR!&$s2?h2ju-XByzbfFDEao2<8{Lf z&~S4Ap{7UYQ{FiQv#Yg5S)!v&bAY%pHop2}_nSY7PDQCFd)KN|#dxpTa}hNE35?!Y zmhU}1dc%jx{7&%&U4*MZfC#HxULMIZJ*$B~f_3AzSxOKd%~dIDR}Fc1Mqj9xrAD-l z5>g8vyol3K)q2~y`W9!oT$+kdK{#XQ+ssuWsVDIXrBrE7do4+g4TABiO>&4>vA7 zrTV}7q`W@ylX4nj?1_$!Hzc4)l#!rQL9YI%lKzo2SehcyLu(7n80H+c1KLAWcd^0zbm-3+)#6z zNN)IsiZ9^e?4z%B+hG2}vMlR#fot@G1y8gCBh*H?ULP1Z(|1{@%WkuI!=p~Bw4dp? zlg)ow<1-o&m}-y^CLfZ_UMkbz<>OUy@C9k&{K%ayu2=3P6urf$78b5G{N|D*KQvtX zxY401azJ{DBAdAHl4@#y>7S&aH8*WEDXOS5<=C05JD)HR-=OOc3?qQ3A?^{He zoMwl#!M{yFbm%7Kkawarhs4T5E>qtttL@9R&~P>VGcF-)2g22RXin7{xg++|`~Us4 zxUYL(#R6BRXoV=4kS_if(QNE2$o{Xld<4WyQ%3snQR$SeVoE@teU-G_-1YojVH)C_ zKN}593$|$3PHm0dIB6a=qhH)|iF|f+A)q|Hue${{59imUJaMMHMA}YTG+VlZ`Yz3} zHLf;pTGzg)G-bCY7=fAC^AWUAfQj#f&A8iZySoKEfmf*kP%?!<_HyG*wEIh|&wsqI z5-^=k3>vsgpcL{-DI$vjOZOPAO$zNv|LF9`S0;ZU(O+v<&jn&UFS@`@vUsMi+e9@n zGrcD*WiD0DfyPW0dZfdpkb%8uHMCB$k#;CoCf&Fu?U?N$RrzI;uvt_|kpg}LGM1A- z-l~Vd4rPflCLguC0&lpdBxAp)%mp6WCC%W8-XYaO2Mg;0I?kk0cuTd5EjHn;M>6O} z2@1bMN?vOM-ww)K;Y40YoYtyAVz1{{UYIH(TUs=$eC89SCH&Q6iw zSLPch44-J)XGj|pszygXk=BBzFe4f&k#QM-me?(0FgZfCRwR^@dOy+f8(FpT>V?t96T zSL<~3ue@=I`@q~9AKM`RWzU<(4R40|mM)u4QZc4|gBfcCqui0;e&j)JYywFbKOaRD zufldq6q zytfry;!|qD&1jsOI=rOcrSJrAcEpR?6FlR?8V~8A@Pu=nxk>Ii3MVrC_Sb}$31rx=`@1?}f&VQYw$-+_+P(7Efc-UL1J8PW`9BmAon*HFgS%^j)gG!7x{JF)g%lU4}=GUJkfR2807j(q&N3C zrnk_3cKY)+R6k}vZM)m~3D9p~&yh|0-+DT6U9swbv~1rM3q46+bLINX>lD<+NFq-K zm?1)!-nkux`pKTfbM>>O?&I01VB8UU$-Hlm034Op>`c=J!EQv%{c28Sl-ewoYM3x& za1gHO0Z#>Pi!TfAF5tMeN-jc6zbBPtEjxtczk4n1<3~^AUvUy2H+)m|wp|chEG-h- z<0T2sNk?2*!HE|gh0pn&M>vvq56Ys>eujXC8CS=s~{T73q1qWSfRUzeZB8_UWx%p4$K!?U4}uZtf9$% zT|(mgMhqdbNPS9&F6b6b-%zX|4v<=+OjjlAQRNg}aqSp_W&KgSR*GWJy$hv7aT+Ch z`JA)lfZqouUEBLB9_SlxztiTU#D`qWP+nG|ImZ*+RhJ?F=RX-5^cADk**Cw!!xN;$ z(yvLaa8*iJjLWg7NHh9=Hu*TrwyCxDUYF4uPX0+ko-R9&9ZE&6r*B+D6^BHCs@sxC ze$57kruX)vyts!-jo> zCclO;%z2zoNg0j=w$kxjPf%oqLuJ_-c!%Oyyw{BQy>;x1BzexIobAP9|IgJ|^s9f- z-{eTcghY#kGKbFGxj0rs8VARGrr17HHTAiyZ%o{I9_mggE#6` zqAJwKHm&*JT{-W#60wA;QfLkgdl3k*>d;g=VS8Z@(G^}cnFJye9s_k=b2g(}D%s1a zO55Wyfq|v+`!*0fIED6bLl|pP8>rM%f(QP}du9~eiSNYCPDTuu z&9~d(TQ%q8KjpHYR<S%gbedaKhbJa}`8j&fhr|Rn`zu{Q1cmqwd z^--AH*J4fuwrHz=o;tp+NlQ}Z9&w!`>-r0!fWWqTtm_{9N;KZ-mJQB9qvp(j; zqi+R1;Vg&u2D5^ma8lW`h1;1G$8G;xQtZARSbOh%Vx7hQ?8=3hOt!rq>|08;Z5_~T z5hQ$~mhWVSx}zu<3#(g-5r7*|W8A#asJR|r3*PrV=UbrOE?-_SE(}<6rXgF@0@82e6WBtO$oMQC??XA1Z3g5+>ILy-4aApR{ah zO7&y(8t5EUB9AA*&IPn5gnQ!xSu3}GIDW6hbP7G{+@-?pv%${jb7*`w>$L%+pB9>W zH=9(4pkoN5CjzvG`lBxlab9boi`IzETdrpQ^X{we11~StcZ4B<-D|6jhNP{PctcfP z>G#L1xQ}Xr`~0oTW*_;Ik(oA-qk|9qivIRsl=D6#@-OZ@=3O3~`_6Jq=orS$_oVAo z6$X>0q)*B6xY!U_vZks_Wsr`|pf`OU^Sf!xuV#;QMJST9R-3o{CBN~a{4F&_4FpzR z9Hueu8P#6xK0&*vAJQ@?DPCbYb2;hJAnffrx>r{)ddW3<)B@@|$E=MVx?=?m+H}C* z(Z6u8Sh|j1fwE3Jysa_CM$R4b96qz0kOz0)lj}pb9!Hp1dE;<;W;q|EhPFgVEMsqn z9;%~L^iCI+gWzG@m*$982_z2M_gd+qPPh+;izajwX%SaiU)1qtUO$k5RJHA;JUr^@ zaU1(iVK5BK`5klV?l_t|e8BOqBQbT(@k68QrB70|^Y+_9-I+gx0$x0O!x1x4b0|H17)P%3yEz(OC=M)x_hptruVCAV(0+$#`CnE4Qehe1&Qy zk87yEWG0HV!Tt2<12|mpeRHUCC6bNcX(LTwWE}73yCGu};=>P;7doYS-}_nO#)YPw zobT6vD-G=g2>d6rh=-Z<9_ZsgXJvft?3ARCnU9uanDx1gmnz48vCOe#$9$D?)afoi^fbe z2RvrK_*XlM_g(x7ah7d$UD*;Q%;#*eyY>thvLb%jam3_o~69+kF#hNzpInfCM+v&mV5S7$=4fM9H`9?vMQ} zE5IvP+C>d(I8o|Y>z9Y2MVY;UFu@7Kc>f8{%XEroN%dPzLIT@lAq$ZK#<7)wy?~;k+gT4-JhvPo=M`M)eF-AT;OFo|t?!Fw) z4PpuVBA@U@TbH4TWIg~n0sJl6Q^>+E!iL=;obZird8+FTq^&~5rde_5Zx`xw+-_cUYbo7}(d1cw&uXTQwY9Kegr+>a;CkuT^1oOB zF{xXU+J7m?m?+n+$M%DsMiaa@#NED=!%eaK`)!~G-Ui6hrwomgQ29)E_Kq2TXKRYM zwF~Sn+NF5KD}hb<<(=vr7qfjD*JD#9v~Rfj+ZWixcNoJhdIrSsfF0qS`$YM2uI!Dw z0%CT`7XqLolS!u0HJxs5DYcO-PsI6rjakAPQc>=QkfTEiqA_pNnNm5K<- zbb`;|`95))cfH;u+R6+Da*`o(leWFB7=SavX3ZdJyNQxg*GXz`JLA24j+Fe3b5!*% z{@0qdSkaa8!5!(Hpx?TgvtwR<)$erwe;7}38~Q*2SxzeS1sOZ@#F%#3Du0g80!^6*d|cdbM;{I4tn{mT=$Km&05)+~62kGqV^bUE#5MDDASrcQ z9E0b?0CM*Eg*)*#hcvy%8Vtes>NW4_vIO?1@#ckRyN~r<{m=5OEv~$t_zC6-AfnAH zc^zn~f{=nH?r&R7lO0{xakiq_Y=Cu9_Nr32t0AhU{cM6e#7{!P#)$SrSM8a!jVq@$ zAM(zzH6!H#4RycS>z^$GlV{0mDpg<1qc^8ZWi0-4Mb?&azVc4`I+!%x1vm)*koj!) zoA&!X-T>zur>TBQ>?Y{VR_13Ra0qWZnMftBr)|PApXUkO$ByqJfmW;8j%1{wbk#7ViC!vck^VA zGAx_F)r+6+bVhv`Qlad$@#7W%K>I+w5N7^biBB7DvDQUt%plVzyHDxTGJ8E?{DO|i zn=ps89{lN9%y_46dT4}&g(W74D#4WGiLjD5mZV5u2fqSKz|-9lfLgNhjyT~sEr1uQ zN190DS2RVMW=d3uqIL51Q`E?a@@dFDT5a+2Cr-vm)Ho{L&rt_O+iR12fpj+$cKJcx zgQtU)z!eVn3ZFW1M^pU&5+auGE4u15Q|6yWjn-S=!@ID9k%afdP;YBCa9s-3gb^&XXUG>C zIT_73>E-Vex}V+Z4%l|9nF|A#YrRT!VYoL;>oQJGS~|c*GayZ@CCU?D)%Y~1&Oc0` zuS}SJOEE5KbQr@*0(RmJ@j)R=X4siTpkg)5Z{2&rWK5b0E@`-P`z8x8i~uqA6pRE= zDi?`%{C+|c&~6^aQ600l=K`f_cPj}%V|dmzf~>b7@}a-ef__6;0kde?W(ubY#GHSX zokEz=Ma5pT9SpA(bzdd7flb>SYm6RwqD4kh=bE(xKpyDytL8yH_oK8Y`uTbQ}d-v*O>xbU}2 zx<_Iws6|mZC>7TeN((Kmdk}&RB$UP>Rtw@#XFEjl#rfX>K`!nf>YR-d7=ao!0}CUT zRUiu)*blOE8N_dW5u6og)nt3aPdL1@vopH+FI%fvz)V2y$+#eFVutfp{`V~00L}sv zc1vT9p40uxrs2aYr>xiUYp&tAfiW4d9F|`{z1Jp|V@p$Y+k{CRggw}7NptEq{*}sq zR6ROJPe94KE>sa&QyRn??*YWghP0{;9$B-ULL-HU@|0%OfYFt}c>wu58^^d-J3AeB znS^j-x&LX}2n~K|2K}RT?dX3^8}wb%1`053=mVw=%wj#__`VB^4VZ)7r|KHUKoj4& zG3{R^&(&UE=D1PUo(s{d2zzuH(;Nq8pF|cm!cObnD+Mw)y-p9tpQK|=|MY86L#A)W zdC}g}!&j&H0(OlcL)m*YigY$BNQ}oE+`cNspG}X5pTZA=t+m5zGyeQ;hx4fmb3eQP z&t0;UFJi3t!8yW6>xI4gzUa*Tro*b>6~VrzE9?ty64Z>pEv>$o_u$Lu z*1}+zef3<;s|9XPZ6^H)i;sh4P3qM1ds}}lu!P*n^IL6i%=Hwz#XvF;Zq%d7&JT`T zL;KLy;MI;)`4LnNGY#-tjNtjW8pu06di+xtklc-Nn{) zDPWuBB&`}qgy^h>&g_Txrc=w-#ofmkzC#V-ay&U;ACbtbbYh)1WyDZ1#hYjN56`D1 z&{?wnj%3g|zT`%%7srBAPo)PHDuMo8MdjoN=Y4l@@#>hAS?RH)!weZd!Dwu5^0rO2 z&jf&>lFeUndEb@vFNw%h_;3VO>^(*#nW28GkAc;GReGs&z6r2KolUlW2`Am^Gn)2` zTdE=rBz|)2U)$86!FK2`8nQlW156F*lOx2^WsFI!oFZd)9Fa)-tkQv*M)jPFvpmw$j<U3 z#R-^y9%AoV-FeShpnPQiOrNvbq&xe|a=gTGO2uZ2tir*sZ2qBrW~O=;)5?h5=(cM( zBx^7pEACu<;5vap=7z2BF^hVwzr9VR7HJ2l4EE4=+!a`SIq<}qQ<gfzj;*tQx`M~jrh<=XZshoD>2#5r=eLFjd)C<24DrVAk>LuQ|+{; z?T-lq3Aw~(L-|8=CNaxJrB#>QVuLQ4 znGBJOyLpuF(@iTD57l(bTDh_rA3O1_A?Q>VPh!N%8|{oE`Duo?2T06E@s~t+0>?75 zRpqjhawz7YS$${?y_Osr88+K^`R#Dm)AN(DncE-{+6s3qdDxKXu znYVRffX?lkhh zE{WYU(Xa>IsHqeDlW;PHsQ3o_Ovf~K+60}hk_a+?gV!#-84DvNLr_mg*Mq1|UY~QZ zoFDiFft1KWTh1!};Smj{dS~(c7D8+Je4ucX=$1(oNs?0(d2PI*(9cu%Twn!e8Z14A zyB<}h$niz+G@g&u{^uiUxg{lu8qA6*hu|mBgwL1%7-aOQj4rN!%eTs!C3o-jFvQc7 zgqg>vd@(*KEgF_3NafVNitP3tGN~JMc8jf?x!Q$Yz>oo#!-*rZ<5pHd3G9wdR5}oB z0GxrfkL$RXoi@X7!(*psLQ97&Q|{Y9U_PBowd7kHYI}B4m%NG#7Dirnn#z7M-`YJQ z^gN>WsIpc2VMS>iKoV25Cd&7l(bC~k0XAd4zMAI{V|Dw(;06zv5E4YxLj00yBU8Rk zz?I(TVPk>2!0mc13eWM~qLtSh*js}W{R0>b>#X-m`D|dO1%G<$j%rvEtOuP0t=4ibOUk-y%9cCf4Rw;pzc2kr-vfr&{L(&Vhjxf?UFi{mGNtXCNL4psNABvtCYUS=%C zSv|3LcST5omrm^ivb53_jhv>{5vB`Xt(#26pDo8)`+Hq~7-wjCE+C$2c!`4Sv8$_D znh-b9hFc^3&hqz0oBS!0PZ$U=%eVZ^ss8w#YuUcjeYrf4?9KvUlJEdb56a+q69x2+UlZeDz}L!vjReau50Tl z60EvX$sHRCHoY^viuE}{vytOC~DAYk^C z*O?#9$AX;K{3KWU(|(QP*z?N!o$e^Y7PE?{nXG zv2kPIC z17PN3>gNF3Er&tVF2Y;y;4q4W^EXAa0nHQg#?<3s{uZwOIy=*ov@Y#fn2cILAjh>v zD2>+`YwsvL-j~8iIDG)lG@M!;O%gg>ueY%e@#59Np<~6~=;xtJGTw(%z4pzX zY$-FJKc5ev)|89Q1yR7I%E3q~uB)lp124KpH-s!0um!F$zdHMq=(@u94T1jhb89uo zfuK?5(wX9{F3NFydB%IbUuAuPp7zh4epyCl#B7hTGU;AATiL!2s44(ZVTX3HP#|)@ zu+%)}s0xP{P^<00HqL@o*JT4|@KDvb=K-D+Xa;uy6}N37Rvt}6ZdWJ=XZ$;8y2(My zU)=rsMxJ%y*PwN}oDCelhX=l%V_`<%(hhMHQiSFaa7br2vEuxwbf)zmU8nM$FiR@& zS`oFgKw|AOZc4+<&r34N5jaK@{d9Mc&$2Fyqa!pl0jjHC_ekwT*Z7gd)Oq#?Q^H>U zh95dbHnN!PYlZW$Qy07eCTRtbc(5nuY7y>~&R<*#HNd6l`IAdwc<=BMTTI@&U)iLhwOa*E&cOX2@>CYto- z7=&(>8(O14BR-b}px9f>btvs{HEW}TMAQgLt&DEs#u*a!0Pjowu?q6!Yk9W(8n6t@ z0}bulX?o{GxU`LFPS0C*!bEB;O{Uf?^nkHAsWJT27Urits!ly5MgJ9TEI zT(7^wEaf*r#zmLkM4=foqh)q{yM4Wgxu0sV+Mz5C*}W zLcVk+Dluf%oa2Tyuy{|1t#(4n>#y-3# zeciX&6NQ@dgvQy{KEOv&65w!BqLUG{kLxpQ=i3#IhM-nAcE)2kGo&ye+F^x$z&Yl3 zB215EKZw@R=nC|puCU?1gy|~ad zXqK`93%+D02`=VLe>rugpSgXUvU&mQ;#=P*m46RCND&Yqk08Ubz1L0nVwV;h=7d9e*0kavI|Y_oXMapwb~DU)=a``Cqe zdaF2|?m6aMqUa6WSNwd|&78bJk%(-(1)+Vqbsb!G&^9E17*xZ3L6p_McE|JI$)g)J zz-AMesr^RecE~J6_Sn9JS5!NOkK?QUC~^u-OK!DPuAd+;S*_0eo|wo1|H>(}c9PHd z&m6YdrBSF8z9!Y*2r)3j2j)m{*9+X53$1}0Tpuz%4gXgb=y_asL` zMvwlTqc()r%JoqsV)?X9}MIxZRXc zRq4bU2F?#bKPR5ngNA=kJFIp1I+-q=@oagaD^X{E%Q0E8dG5Gzqpkd}3iJBnS3rr0 zR(oCB{t@JKD2aV&_?IN}xKqoM*oh?oQ-&V*+kUc}Lg^{I@}CBOhUTeXIO}oM%ET$S zA8UA8M*PX2UI|Ddqc+~d7aEA`&xR~nYrNmQ6VX#(C|mGrYV=f`1^wbgX!iG8RaL~( zz5j0OKfIkq?avSn7)e1v?NHlu{Fy3CyyRKx(AB3D&RPesG&A`P{D?Az9(g@*hCZLE znrpA9w|Up8`b@^8%CZJ>ecu=jDyX+jjiO&^fFi#g^TkYiEo$Qxa>xg>--0@P6b4d; z;=*e0B4+}-EWi0N*Brmr5**rK?lXIH0`+bT-2X8N_(@QDP4zEBow)2pjTA)lE|Wi& z{|omsqBeKx-n(r5Qu1U=|39QScdoQfU4re+wei5(U$@s0fTcc7R4ZaBZDIZ9 zz0K^&mXtg(SYk1SSXHf;qt75nb^W_CMVNeE0RE*$Ivyv8gMS^rjJR;h*Pa{mgrCN% zW$L9H7X%b2EWNy~D(75_k9vhryI6wBmu6YUE;-wiZeFn?-Qlfs*C4p2y)KI&MFDU0 z@r5hH@wl#2^o#L_?;@cRR=_ECK9JF)w$=ApZ~BeK*uDDYd*l)DvKx(IkVGlon)Jn5 zEg;9P-6LK+7XKUqFRe%^($M$K51=7uQaB&KpP8%NkDgnW+qC{jmDUI$_k#X*$kapt zHtj67{j04Wd!%U+do+jl!bw{SY?qm_w)Q(9 z$#AE66$Csbs22Z2mUZ1P8}S$1;s}(-+(*#$6!{fNTe@sZ>)qCSMnaP zUm1C+(a72I637M^R+Hy}W9D;|({t==DEr&jfEc>`9uRZ_3>$xfSwb8aLq?1MKgv=S zUVU>L;Y6?AWTpWti9ziuKf$C5lLDPEC8kIub(@royLXA|w{qinQ(iFfi!1fbs~2D7 zF9T{05I$sD8%t0}6ayf%q?hL=uvhkIRdo$g#24IWYu03W52A8ZCt}tF?h3~5`Xk6T z2V+xii%gCazu;oKb!l0W4*xj2(-^WgWM(AEury6JADF^Xu1A{;71jsL+O&dsir=KHB z#1Xerfr|?^q)8RYS_{SHChSAtu9~;?>re&5_*>U!em~LGX(wtZwGXIgMeUm}>pf1U zhISgg0{Usm3x361Vah%{z2M4|4GO+w7@xhcU8LxwAPy&I{?ML*&`B>b?f4SC@$e`6 zSD3!NQKIO%E6*2b32-|G`FP?_Si<+ndSMH3M41?|}R0&8zAarW3%0pw}C! zT%%6E0yvj(_=&GeZT`^!)0@BM^K7z98aEjBM3}rgLk$%?apa!QKJ&K|bNc;v_iH}a z@&iB_QG!dO=y z3E2`c_g($)8|5s6Yujb%RZEOtkgJ zxc-4?<*Z9lo$=jPGgW@RB*XcNQRJ&+5usYOD&&yb5-}6|Td)@t*hnkhAGo&P2P#UZ znr1ccOa-2dTI-Er$Y3CEs55IJhu0(Ns5*hMXE*VNY?CrEgxkP$x@QmkUV4?ql;j!v z9+CB@nbNj}8-!c@9n{ zF`0m`>b)?T!<3_bos{D3v2o#ivD^yE#B9kn8b;rI27{N1VD5{Wq?c5?d45(}d?)0F zvc<)!)(RHA`7XNS(OA~ls?wVQyjH)?1+0^o-IIL1S1N`gmkRaRg&UD`+zkV3n@GVM zWoB*$70RN)hq?IMK~Ew}_D)GN;RydCQ0&=97R3_Qp=S@0g)ABUt0#`_77ST{hbS8nS0J<1U(H z+qDPlT1!80*2~5KZRn81LtJFkwT0uxD;q#nosZ%0J9+!h^Jejc}~d z=nyLlz0fa+MtabjfS4tbVQOX2dmEUY$zqJ;%kv4Lxfgd#`Pe!Nk;JZas%g~fMj23?9;JY6?el;Qe{aCg;YNxiHq|6yfAM2l%%Robry{ysUN{d{SI&&KnG zzRQn<$Al^Jk;K0%$!U%3D+Fa*5%75Gp^zydW;N_LRSJyQO8u#o2j@XgcbGNHfLs|D ziU&{7mfaOjcjjEv^*>ftEX%+C2jylYR1%rvWp8!k4)+=F-e>yTSGG8l{wn6FO`277 zv9R5$e5EY&0&+N=Al|h;ta+|#75h%&=2Fx1PEM&Frvs5>KI`eU(7`}&gOmJ+5=#kx z;Q6H@stTixoKWansXK6b){GyFE-~|TVIYYl>uiCoOCmTo2Ixc9A@Ze*^5)tt3ecDK zc_j%^N>CkOlvsDNSx5JHz{>`67%fI94s+UO-uytrO?hDmmi0J2dbn*e9U6U*9!Dsc z%2FYgiFPq|G+MI4XgD;25tjJgSVhFOboRZ*sl+0r6_v)OnQI}{_r!*#cZ06#YY?fI zs4to-anF)+GmwL1FJ)Z>ATfLg7qv^||70XXO{O@QRS8VNOkGV+&DWI5m6({?h*C*b zIPETMV@f@QEzQ&=P&4tNJN3v7Ic^yFQMGcxE@x-hy3gn5Re86h*|L9i`*FdBvZ)GC zUnO$PT}}sGY3$azQf9pSC~3q=b56-d1AKVHyPl1UeM-%Qvnp0FJ@Pf*E;JwoCnfb9 zS*u{#pI<=w3YvA2_0CBQ;+9^_O7$Wq?w2}tR?Q79(50f>YEN-wlLI%jP~oB9bwFU#xN*9{IMS?)8oX~5&zhDLivvX7 z1^z?F6-gFj0#7?h;8gUu5qC?HCH+b2|0UAP5Z_u-&;KQc65>L}%zDN*z8;pQssf31 zWB4Y(EjJ+V5jJrFMClLPI{AYmCw;X5C>BU#9ZAZ=Z|+3`YGZ$}2sv2R|4JVO*p=x^ z0!5TYgRAjCDFq>i!e44V*IeTMMS68@TJ~Rf#nE$o0AAsuuBD!x_GgrGO4;Hmx&N z6%Tbfp5G#vt~AEFg6VF}Vuzzvy86lI&OllV{nO0JbWxS-EA6}HFPkYRYp5P^Kf7K; z0Hzg(Ba)*>B)gtk$7+GJ+zOQ}e1x9M6#GC~+wQZ`!X{NETp0M5g3aaVwMgV_gZLdR zNFD5E)TzD%`Aw8hoG~KIyj12F+YooH5M<^1y<0cz8w%Fm``KIjl&pU~EV1iIjr&v6 zkq>N@TaLdf$nnjv!L4eij_oAh9hJ~F{|0a?A?!EGTQ?_)|2cKHZC&tK!YpL-^Ol^F zkv1WjaHL07eJ|jQc#=r!*#PB^I>OODxRnX9srw?ZK4rsWqJ}KArzEyPt}7+-?s#83 zlmjY(9%IhyeqC+U2X}@*3ooLs8O3CqJ#|V_?W7g5akt&=xCKe0Wl~RNSm-R_-obmc zs!UpZGtQ4y>D#sSMrjphK?(}pX-}TYF6no!BYYGng-c?jXO zb<4tr?Q?y+mhBQQDKdBRR7)JN#S5%2r$R@02zuPq|F|Q1LTIla@%#5&@EgXYh1n%Z zD0DoGkKiFl7JxIta%p&t)%~qCEf~((0Ng0AXB_p-p7@5iSVB0zH3NY3wFX3~D0V;1 zxf*e7x=V1K);i>HAyxln_FAmTUkhC2d-R+2TK3A1z3gE>7M{?*P-kZaQ}0Gn6ICM| z*yedUz(|MhE@3F`;=Ql_Yp%C5ytp%GRa|(}5~gW4!!I>ew*kq!*|bpD`85qI_KDNo z_HGxk<9Mj1)ZZj&cQW7EZS$DCm@;4Ci}s;Bj-dJ6Z=G=eNfy~fm0utC zIEv&ET#{KM#V)3>b5h9&mU-#GgONDN(TrD5bwxV%kA=OAo_tAmxa^!FI9pc+W!x*8 z6yAL5QGYD~bHnhCOM1P$Jy7>SJ#W^ImoU-#a&*A$Amxs})b{Ot*)TdZK8oKhfKI1k zau5UElI(rsLwZpu`+u&rky`6qr=&P4T`4OA@?q%=q^ux*$F5?vz@1K;@0hi#k>~ z`*cbyRdIwBs=%LRQ0fJxP(9e zH)Z$6rFB~CD!a9OmNw-CNoY-apnSiUs8aLU+o}FL!@CoWDZ(&=nrE}8ufG0vXNdp# zzRV-`g~EWeW56NUz7bww@Uk;UrX4_F_q7fcH--E-_N^2(6X4f~fqB}c1^|HnoT)+! z)NL{N6d|n$_tJf+cg4p}A3W+umS;LUOr{@+r&lSjTez6rY5UcAOgi`+@Vlnj+{rUv z?Dt7#i-8T!b})Xaif=k#G;&vGDM!bS))ybt6n3KSl^|w+!JKX0Roiu{ab@KjF$hEQ zcye+WO_lb{fmDldaRSDQ^MlO0G7-(@tY%?=_IrQx6EA+YocBPcT`O*2UH8S)3i=C_ z24U%-cLISzyqZPh^-oHE<`uhaVUQ{2=~Zv97j)sStoBE%zkp*qSCzl@(%Tf@QBsH# zm@J$92jfn`ifF?Mmli)s_iS8crA`gxc-EkwV?bg-WJF*e#)R$(1MyELowO^K{!|i@ z(nX+_3vzovr89QGmL#q{B=8_@|KdI-wj>fslLM~|8JHFtcCw5cGeOoT;aX#!YzbzM z6&$mRwx-!tIjwMuTu1@P7JG{^`Tw-H3T&V zDD=OlKbHN6zX8EVy5N4km^#_nY@T#?=u2d|9)I8QrzdnFhAF&n^jw~@I)hzb(A3mCGq7Nf$+4Jh42MZIjF?4};y^@ZCzuKS-RSFO z=SABz#?2RZ5v#{~_uLNph5g1nR+3wAiK0&i4Xc!eIXy3laGu1kUl*_IGQndcZa^4f z3J2;WmxFE7&%S;p_wKkqzww6{9~ruM6ebUh=hAR4j5HoDG(g=Pu!E-}t%Q$e))z-9 zhvioPi-M?DVpPo>k{K~dV;r~o=&<>f`K}CLnyI-c`l3#X(9V75RJ>l$v++@iynUEC z2r&m@&kta%a`xkgKYcZs^~gb)XJ}fBMRE-q5J_}gX=BH*-F&ivp(`M>X*z-7izATH zqGD$HFoJSGxkdHj{+VR&4iQeAAob?o3@erwQWjPw9KyM%PWkp)6~sJ;dC^AMlp2Z# zybW=$RqCB>I1oMJ2S~MEadMKbdHFWu+EMRv1H50^ynnEJzUFtrv*mNd zro+?-OVdx^PKYUo-*vavgW-OL2bg;>&lbH_8ceSQd&DBM<(clos#}lYrqZm=Gr{gL zi&xEDXZjwvSV;DTK?m6aI>w@;1{{hH?I!GM3kZPCG2JHpO`&fHI;GkqBL z`&cW=TVGU5eO?Ypg&I?99^XOor0a|pAO7VlBijHHK*#qT!f9VOIzc0(Rzvd}HEn|F(0tpOXQRVR{RP(tF1aChH#>6niu zx9U*0`xu2)k(0WxVQ{Crb|$VwP-h6sdYnVg@ZlDCMd4 zxf43RNs>2O&wQ|FYV{T{F99~Q^*KBarb(0m@)*z4&K-9x`F>1(xE(ni;O;Zv8;iS< z)>Ty4mtPpj;y~;9<3>)3;~uVFR`$R+VZjr~*IvcIir#VxS%6sB{lwjxUU-RCNLICU z?@xyqT6rrHlP*w?EK>}S2-IwQfJuTr*^3N<{Oxs!KCrEwS(zidyy+MaHi5@%|K75p zFialmPvCM@W&&k_ee3`@SRMSudiHL-3R~F(~JKGxI~{wq$pbWj>?8n#%eo zNq1L^jBVfa7e@iahnHzv_8v!CeKM;%hUoyLU=Dy3tk0a{3yOw;Q|vsjb@f8hQLOmI zBoM{1Vj^P}>yk94Z*~;~FGIhwzP<9;w&fQ!($$wM`mMCCbl|`&kPOM0k#Nzx4Jx*z zd+g>GJp%aVGuG?wii56r<72xMPLgYH0BTH-=U9IyG>;}(*oY#C(JVo=T2VO@OERS% zjaAMDVz|K%oUH@=^4DT!f>WaAQ5)@GNidZsgFyij$7bmnTlZROm%Qn?Y~%#v=5{Ga zO|wGD89ow$t<8M0*i0lUAtkmp*B-k%J*C z@$f>Zydi4wICe*AQo#Khys&-$2}O2DLoTsj8Fe8w<~kpEfag6vj!({o=vu}^L3J$R{Tyze*p^C(4c}XETyw zE5`kyx#<;Fj1%!nGu%m2s9uJ1+HoaXXrUA0l6 z$aG~!mE;BVieeE1ikTHqq)&*9IH-3V%PvGs>TV9qA z2AN7S<#S)~-mklfw1QUtTu3R=bkk3Rb&@j6fnLy8vjB;E*Wfdh%__`E zVZW|l6q@ZQ_n;4HE4N!oEYLOLGvj-Lcj>=)VBFQzBKx6wm|JU%9t=bp3ZL)9#}0K5 zo^shK^bpMz9c{>{%in8=%$w-iP{LBBo|MTaOky+=2n{??z3`otZ`pcBG^tTcFs<9w zKLEhG_44Wv-$>$y#{K^}9(E#D*~U*{W*h@Fgn+Q;zajm-b`|`m6|(%(HK*3qsn!>g zEYyFbipiaA#m?;R=GD$wmQr2>I3wvu+?Z8=X^S)AbM-%VgJ$|IsdeQ_m4}ruPxTUCV2q6 zZYs;Q$3PHLY2eJY|BtyhjcW2-|9{(BWm^=g6i~!uD_f~DiHH)&&|L>=QK(X8NE8H= zhztQC5RxhaYJ^mgQAiXDC{qLk858CRfkeijB6A23B#;0}AcX&ocJJT+|KhB3UYxVm z@dYnj&tg4fxS#vJuFv)P5;!#Z-Ap|QKH@ihCV0(9oXQ?1YTA++rE_*I9GezyATN=- zpT28YIO3{h+age;QFg6mpk7UE^dyVNdtcbc(H8&G-%BA2z?cR0Xrfe)m2rb#2I!9> zZy~opffbwNOc%Lai#osJwXXU z%yDA8eyg#CF;jMkAEafep@>`&%y<)NtId)I!n0y(Izva{)V#IY?^TMnC`O$hz53a{w@|}sB&yM>#h|xrSq?-`YwO?PT>>lDg%nhG_ zZ&(!S4uHei2QcU$kO7I5Q-<|hjfrl=gl^hqvMu*^&I#AWgUMT*c?BCznT^6@R7rc& z*G;hRxh}k&%hy4v{P#Tlva;dDgEs-64#UWE$Vv_6HM_|7In31>=BhcO`hamNt$N~- zO$bXqD!YzCw7#9QjEnQ==9bJgb;3|~mxK30B2VqLsq<}U_j`6az_YLZqQre!Q>wN0 zw!?X5QA%wD6P!eYGkIfO8ph7x$p`#sj==0N*W>00NQEaLL%p?2&A>HFN$RfG3a*%Lrf4m@`B@CjF4ZgdOL-`&F3 zAojmyrar6hq4^Y*X;S>SL(t+-pd*&HsgWgOtj;;reew^eSpvhcbVUPH(SWH@t_Y!5 zr)DkG>*4vL zq`RmxJE4mp;);#?PZWwQ60@^i`qi_VioEc}Q=8cEtHE;<4Q&^jQZ}c^^Nn0U3{W_Y z+Ileqdn90P9Nz~Hu$|?R44+R%E9IPP3AA!aM}E!mh{YBk_x`1UCHSx;%2*JICeZSn zgiB%_fe%AN(bE&A-B{?7Xn_=H|!|u zt+J8z;laSB?O{MnViLu^xvlS&tp1<06ITia6Ta7z#+&}(48+fKBebeK%B#D+Xn98Pd08RNw91&19z(V07*7``f!fm%>rWOFzW>>xplBs=Ia`@OataI}Qz9w4I}zA=7-np{NCs)opZ^)KE1s)mH85FFJxMAN6pk0* z>2UkvXEB_NP{zw*yX``=XR3_+TWwkhz5z1w-$g7Z|MLN(IMT5e4J>@Je}*u` zyEj#MXR1O!9(FX61`-O?<@f12I^D^3h3Q&B6;Ebzjc-unBfLFqh-7tRY$D4Mk)I*F zDjd_sTSw)FPi7vaUQNSiR?Q&gE6_*Fboco{E+8i z$P@cUCUoR5#<2+1Oh_vhuSPE?L|igUsC~uPh}PpIuNe22PZWfO-WbV$?~dW*#hqlv zJ!{QqF7;)H8BKPkH@^d^VWRfLgM)FN>pAg^h#*k539fCMQ|6=l@JBYS-JL#_VYEcm z^wox>2NqN{EE*~v?4xvsw#-^P6a;G$yO|rJ7vXNfg5VW|cQhz;fnX5qO2KZ05(9Gc z>GSgrVGM$2;Ss|bPToOP>m?5@h1P2)UzF=$27SKRgc$~z&rFQ`-BhMUi>TqK2L(8?_r@WT8s{L0QX#8>mRC?X|3v&lc)%a!CF%G?MsVE?- zFLFpib=nvRp)i*E-G(6)AJ`6jU03i_yv6Fn^kn8fcIeLfh5xt!1n2j_VV?pp%*LGWlZ&w?^qPJ@z%rQv0cDt;1L(FhEj@SwY zNh)m&R~ob8mNKwLFU%4pu1JA3>i@>zu)Gbxu{d!g_c-r#Fk%b9W4%LfojK0Pn7hDp z$8~B(-Z5L6Zaeo=lp4ql7lm5b7`fK?74jo#1mpCyj6yFM6et*?w8;sDYMiY`GxrOC zo2-+->SCLs1LPxNd>bBjGeUGCrC^3bCkQGrm)l^rNWp(Z3)?~?E+^3gM|kgl~Nd_fI#p%I7qUGGr zJgKejeeRlu{!CoRb$O3AD!>cK01z=&Z^QOPa-!xzEruQB5Ebpm^kL{hm)BlT5{;31 z-v>JbH2-&d9T%qsUFJ-@?PPRL@jz5d-I|KQho-Y&Jp+liGwn{Phf~ahYtNVo4XEP+ z;(hSqzwB)&O}WpH^r$k&ZXI6w=tNU}go5;yPC8w>^kwLF-oJX&LW4ZrVu=J{k;1>e z(GX?YGaU6%h?YK2l|VlRvyDVi8(a$OVb7itwV^*go{0$H*W$hvTb3h&^9|I`IAZ73 z=k6^xrHCkE%AGX{?h>)n7E++AnsMC$pk|VRJ*@DL60j}c2^3m1VsF<4DyUK>xmAxe zJ={VpKHDR_Z}33uTK9fS(0reO8>RcM+oL_qNa{vd>d9h&sosvU(0Ksx&X3CQ0v*KS zteek^Blad9=K?r6_)8oGa&?9?8$$Em1}% zApiqY{BAv`E{7iT@suht@2lgp#waGC_>qq>z3ZsR`U{XCMFW>sQ`{3F&J=Da>sNMB zEM*<~KqwNQED9(-%lmw%b(^hst$0Sl{pNXrBkdKk*?@vMov8_T%`m}(C+CeqNJNyufI%ds-4)4B6E zQ}~2qyxA(M36YiXg36J)*vUs#^_I}{i)-#}4NbuJ;?|Gv zt3`)xr@a`1RftFJB}lZMNycizLON)buf^R#8E0Uhuyp>@RGd_6ZkbyD=l%8l2?gm- zB~G#;b>e*V`X?3S{4J&i*R6JJqrX5$gLDXea?qj=TYRE7L%OTBP@qC0`HC6gwUm|q zK@_Kt1P$TbcW63nZHQrGpPXAQkMoX&oexA5Eq}`<5Ft`zk9Nf0ljKfkFci!DV4tShqU@vSMYxV`XFZF)(^Ft+S2O( z{vCbyD|wDOg%9#_33I2n8^m{5zXqkVv2NBveqvZuc;oFLG+T7JjKM0lMqVFI&k^>%tV%co#)z`cZ?h}$bLQUz;%WcHYs}@B9Y^xE7U%U*FWK*KQmwhC)>^ft z6~BADWR-*PRe-{Bfbi~rX6-Kl3h|P%IS{>EoA^@4qB?qQ#)0InM)U%sZ?}7OOd<*6V-H^(|JoE!|v%uNQQ3eftyas;>e#+osOB>c+O^3 zbyeG&ZMUuMLZp=&8Mh{@Z>*7G--YMNFIrn9GSW9ei-ou-)2TaQB)g}d-f9Sc;iqo4 zu`O|I5%wJ~T+#fLY>fA5Xl%M&P?M1sqhAm+ckn%k2E33MV_h7#Il9wbT#9tE(Lnag zlPI~1uQIHS1o|V(o43JTxDM4D&!Yk=*PQ2Zvb^>viiaqc_12lBPl)l$A#W4?7wTe7 zo@f(Z@9rUw!eVukT@#W-{9q%N`c@JF_9LqJzpjl-0V-pXh2ew|uORokU}qNyT(>9_ zNN4b|IU*j5WXEMv>;r|AfHwTz66TL2QvvcamT%y7F7=7wjRX&kbMZLGg2E%**tz+ zQs*c)G7^_smKO7JYz&#N>n|G=`VlRBsuKq_aA8j{L^+?5pn4?o^%0#E01vcS-rXKi z@835H{ffRV^;$yfws*yRhwy7Fqq|lPy$*5Q2p6ealb}ZoiZV7CAb}E&*L?L7FEFMP zPT{Zag9}6!e4eo&yXuq|Z!P<8mLMfVz4{UY+~SeNFx^29qjans>+@Aj$oglag3Tm& zdp3PU%xy$Soul|&_*uKN1gNfbXCc0=7t}$<(rjSrR`?;q~3Yr^>I_4pIh9=r8fu5#9-b#of&d(6SG06-HjSI%eE4mmF!6drFp zDhO!Q+>)7}J2-;XUe;bsD*E1G?jeI@Nhhe?FTiO!lHVV6UH=X${EjNA%1_f3>LiI2 zjvn$~&A1m93f%iNit=M)dHMJ^ZF8j=TzK~aqj@T_s71xiW#y7tEc`t>FBd$2UJx!D zATFo$A4F<*MuPZEudf%c19?U9ic{5goTMFA4Y1V`j=x-!8B-(%lV|kcAv0b|e}9J8 zT-SZz2<71Fb^~k9S{os-n7?ZVL9RG5C$&I>6bmE7<w{b&eI0{3Nr^w zO=jb#M{eMB?&()qOrK^cso7UYID=+GQB(!aanpo(kQ9y73E4{1>p0O>MZ> zl0Yqw^-7lksy2(YfN~VVkvOvI`rF$z92^BPchkA$(n}%)jJQlyCGZTO3D`u9p>o}5 zt%3Y4xuwMg5kMIlDlKrXsyeOiQuJ$&X_c*i6Z-ELk0E|>Ia8$~A7;Ed|Hg^Hsx+}p z0FyJHae|hFwopF}e4Mt-Ib}XWTI3U4i2WT&=xY`lv2IHSH#Y&VmSlYQ%`afsa4R4N zV<^oF`2)8p%|ZLn$JVd7|A8kCdMm9LxU1{a8>6hl%#Drv9_WY^^1NnkVWHKS{iH|` zZnnIVY`L4Iru6Y8*tIJ6D(b|;d*!nZoU(uccN%%LZCQ(1);O|y4o6t1w*Z+u&js+Z z{GrAxY9;eVNY|;IWU`4+l4z}A0FKuOwTxGqZ@iG7OB00?j*JEUh9e`x{qB$6dUo7* zLzs~Ns_KI-W97#aYoylYG5IauCoEhibPtJ$d9)>%k&?PqXik{idB&zB84L8_D|AgJ zci{Kw2DpvIC4!@16%X{4i8OgHx4)Z)D_Bf@9Tx-%=T?aXRlnO4HVg>7Ie8kbB*_?Y zWu3GIu^w8ZF+x68QdqY~kk@#^22TYelUIr$>`(}3E)&YN7m z^y9UQNB=sjzkT1alX3q#A74cN^u3DD{v&_B?>~0y)VZ-->b{1N?=4e*i0y6scAw49 zzm)E!^(>L3%1WXhQFW4B!|6nH^c;QzehXd7&XP5uHtx0>YFT8Na+RN z?gmWRJQYWiUoq>1F|bvl>UL}YW#=A!N&=QgIOY%+7hh#TnE~Ikhp5*h-tWzgC2c_z4f{4q(i1^ zjo8j$P7tcer%G=;0f(v>rD*KZKVm!L68;VUww&EwAu^`$_I7__uIoYNZ=~zX0qe_B zkDKqjQwE8vpHM-dgg0%*!F!RJKl~^P80syrbGA>2n6RLtqnS|^+)2s!Qls!+R;v70 zr95u_(e)1DM$C_~qWnEuXV1 zR*XC*uYSp{@cBEtBGRaOu_GL39u->^u3^iVLkb#vpP)o|u2o&@RW$9LbpKwXnUdC8 zQ>JGTwc$@}r+TZA%u$_XW&o#m$~z7NCr^t$CGjRaa8p1YNFOF^ zl{H|zKX4Hl$yAA3rA14zSr0`b{E}PY@Z`U_6;2e#0?Nh(7=P{#ZLbyiyHn>3d|I_o zO>a*Wl&@Tfwj-d|#Wl+4qF z&K!Z?z^e5_kda2j*k=Kb!cT1K9jS88*LAVOuRKF~n-ZE3>_U>E*|OpoO0K8CAXiJ0 zUothmE4*d49fv(j(ev^{c!)(2#vq#zL${~~Bam6z6EQPM! z!cdf-LRz7~n1E4bDdYJeYdb?-O6G@g8@=(wrq-&rH<4Azr`7kA6gxHDP3&t9CH8VW z=L5Z?@KC~+3wtomixb)R;&EG>zBxHqdZ}cGP;&hUKS6xA=Oe#obBK#(Ojir;op^^) zN-}AM{v_GpJ!+Eh%a+`=yQ>*4%c(;Ef` z_-6w{g*CJ=WMQ-`kubZx*xT%*78N~kHxzN%uhJDc(>I1@1ZJq}UO(@KKjJ)`B7xh{ zbcXRYD;?4CmPotpEh>Nl|eXhJ~KeMTZL=yW7N`h(1&*N|weE^n&c|+K(;08sKcY(-+vOe|a4S5rDrGUAT30)mvDGP#A*eM@x ze(;ClyU6IpOKA=PAU&hWvcP+2s{z3a3W|X% z_V7$(g6m69JAPLlE!dplSI*a!#z+|@u@GQQW*3e($B3M{C3Z6$Cr(Lo>BBsC|Fb6z z{EA9H2u5HQ6Mlr5v`{rhVX`RceSWEv-f+$E^Q}-17w+kg_vls~>__w`AV(pu$}sFn zipgevS!awlo)ql7;@Re_%Xe+K;(rSL^~a^w&HPNjIhkxG$P zEEwBJrKs>telwhOa(zu~jw-0o2E})ibWXuFXqC9#VCld!nvpgq2IZvemN?5ZBqqu0 zq*M!jF>X>=GUO(+pmTrkA(#1NJa_By+;VL6a+;IHkqZVws3|0Sy7oCxcI0T_I%W`l z45`+^V30Pkd|&Z-8Lj`DOn@M3lTY`oo`IJa`gXLWWhb+S+~jXSe#L-+*rR5$>7MI| zmmR+jRjEUZ@R|Npo|?@(GG~x5Uhjx<9*aF{jS3^@^0I zJ&=4*@-HxdyB1`ep(%G*QeYOJubNz$czgRp>24KdS@<@{dCwygZjQR6SY5u$rRnV2 zRhMnRs#8v#`h$#klf7Fw@9l;FC{UZl;$N|vajs-w<`P(3C0o;BwzE6Dj=eisXppO| z4AGbC`~w5~=wGaA1hh?Q!p173p0p#)EG0?Rn8njQv4^2gwzH$DLK9dSn~pYb0Cb3$ zTf>d4_r@8ODbHV2nrjonYdXH-8CepEvc<(+wb%~%d_(#2)?DxLZKgMZ#tjqvJ2knU zXFrn(5Tve8YgQLlj}p}ik7zHeU+z%N^Tr}to@q0LvU4sUOVXh7-3KQ}j+h-E^9zcn zeJacOnD1RT4afq{syvB2$!hlyM}>uGFg&dDbHjp zMzU?Tg|#6Yj_%P(+q`ELKTGWWgHG6>DVCOE0BCHUjeTRyf`LEMSr$EY?`H3Q`a3^j z{J1||1DiI@ZS#{uN$=i+&tJhAN z)8))z#pH=~3_q)ic-D7e3qAG31s4caWzTR%OsMW)DpXNthK9cDH(^?uaPFEd;&PVH zAxNA%2+7I?_YY=xR<-S9Q;-KLfZx@WmA#9x+Ka7-8;=-Df$I#o(o+K#a`<&`mopaM zWS`H3n=U1TC14)#U347_z8NO9f2Xy&z`B+eKAF-h0Sx^!I#MOKZLM!{;!qzrV=@go5ZLyOdcu^g3t?y-!dIDQERrI@b(Tf`4 z)6hE9*o`p3l4On(ejaTyR+;b?Sg88thuz#Ks?%l=#7Yg%w>eC5oZOFkErAG zUeKWDr-{uwRYe02D8^t`#*eTlxIPi>#Jz6Zm)T^Pa5~!uOeODGeHIs!Z6V3&at*xm zLcX~3;EH*IK+oFJ6>f5*g6D<1cGmi@c*Q%gc_3Y0sXEGA zSImVmS4Bw_Z+StUZKkC-7WkX=*(ib3%z~kX!R5g)TQ>K9YmVn%Bo(hIE!Oc9=d99 z!sw$ny5@soBW%J&x&IZAO1pLkVHR@pZZ84;fH?7;Eux@^&oOJfpI3fIT}AnbT5zMl zH@xd8`M2Jwtu*)ou}FG~3{(Vlb(wnS7vA6vhb8yjY@Capzi#KCxC?2Ut>_k%r}}S( z%&t&6ZlBKcZUFOO5gIm|3WeS?hCAo z0WL2~U9WaMaW;S13)hZnDLRchrk8BFR+sm3{^dgqxvMRF@s8@>MupuQMuo*>2Q+w8 zyCOg{gLQ>yV;?@V=nHu@6>|UudO;g)al;baU>?%fObzBD1?Zb=Z(T+Htn$I}l^^j` zcb~mZ5;I7Z4ohyYW38AWpJUXX{Sj;&TeLJyO00T$&FKR87>Oa z;@fY9?`4f|D9$odN`FQub=4f*46ucsR#5EVB@idRY#{@`ru`((bi^>0dF*lSW0in} zxNFucvLt5IaFled+zvz_k{E+6;xYPaHGMU0Bkg;1sWu`Jp!bu4PP54$tXOMzlWaS- zD=ko@&Ppi8AY$$6LV81(0nvS=%(Z!Er04-Rqj%(TCVlYH(1lILh!+}O)8lnm$+KHA z(aDAe{g0*9V|N!KMBBPAKeIMO0Ac^R^B?4#lXRahhrJ+q!aj2sU@=_F<&J%Iz9LPS zn|ag?yi3QiLsK+yit1#KfT|sNF6=MiH`U5(>wQj`sCOl$%dY4gF-M`XB|BS8n{I-gX{gb4|kJ!m@p zzCUXd95-ngMYQ`8IJaHN^!Ja38d=J#f95g8t`kmOH$O8B2S5WO1KRoW%W@DNoAFcC zRb^~xlJqfadt8VO^TOnc#zwvw^+#=oAq-d%n00H*A4n^*h4GaG?g0r4oxgqf&DJ1N za;NO)ZAuGf9q%6VpxVk(6Sh0DnU}@$B>5S!xsTAwl`txA!GS{H`m-aGHQXa;2JnyU?Q)+W~rvrjX;vkyjcUgc=`k`<07^e*eF0W##$-O-*zi=KHM zWbJ@SzZY|wj8eVY#5;{^ao@n>s{<2$^PI+0mvw}pId>oKPayC?rnIW!a5@Qne*x?BX7HYJ7&9^41 z?!hkRcWNy_xIu4YH=!NL;hLY;({OixoxrX=H#0dtbH#KZ{buXJ;J+6<>=_{fpY#Ij z^Yf*KllnuYd`vW?4n#-VMvZCE08rhQXw7E+)3ShaKhcl8bom%M z7#Fw1J7zgDeoj&N!Yg}={A$B#kI^@my=;TX0DrwtSn|YUxK--Rr0isuh3R{p$3|Pz zGSq$UZ-&x{#K|@GL5#9ymyMo%n|^^zwd8)qB_5oySI4RYwbhk=WLK`hdi5FDbPw zKcIEqF!JZ<+A)ua3R#IZLSUFaAC_i=a8;a3WQ_TQ^4+l7N@HExvlh`irl==MR8jz4 zeeL5wsfxg=39?SFqlb)FrHqHeAE53N+)g9(2|=~6*vdh_Nm!%Oko=))Kbot7XCK{Z9F8TMmki`*j995UPx4#@ptp9W7e-8Hjw$?RkB4S4-W*8NbwqO_6fn7A1A z*jmreqy~`Um$grD%^BGq!%>&j4v^d}q|o8NOA3Lvs2g8&T1pq`FL<%lUv9FGM|m^` zAoY-MwQn~q_Ht5Y>aeF$2oXbHw_^;Mgh`Vp*jGwn;p8)P{Y+r3yl zwk^BXv7qAT>!?*l2}KWET}R*rGh3ZdMl%IhmpTm5Dx%7Cb>Kd;>d%Gn_rsi9s@d)s z<)H$KAM7Ha7txF|&$$~ok=gXrwYu7X=B;C)7Nr?>MRNlks9%V=G(MOmGw*!E?0rN% z;yU2)is>t=nNUR595v7y`Ztwy{6y4XYh8Y;J33k;)NI>8I;amz^GCfP$U$dN!N1(F zQD*LKutv%cX!*ZV5WLP;qn$D?KMpXmXnd>vVeCRQ^Ufxx3XoNW4dwl$KUo@{2V;8( zv_Xsad`n3pt+M-?XS!AbB<-@h2jU(oRG zP)}lAuDhyKXJ3DvZ1NT2g3sE+4e#1|l+bN>1$VP6!#*J(WWsyNr)_6~bw~8Q<6~Ra z73m-&IuJEuZeSR-pHf>{G8r-An!3$Sjp2Fi={Vl6)RgYd{n^P`UToIa-V*2% zm@ia21qgQTaT??M-?i;S@~S@it1;@iZoRJk0t>rKnSVfq?M?K{`}JFGyUYx!se+~ zi^&%?OG-qzpgj&;rf#dt!lTRAjKO`ce7^6<=zH>A*1D$0$FK_*YeNW1EvS2QII`ar z_g#UCLZ@G{l5#RdXmV=lZKj~wqPT|h^>i^#0g~7yZQd2Ww&7=me(j-dguor+a_0hb z%>)&~%d0@wXS=<)kk|G6-5YINf_VOJi7DNpzy6Bj!21kpz_r`tR9EDa=!|3G^->*1 zA#ZxSQ@@bIR=iO;iEO1hK|xf6Q(0sGvl*+oCSAw`hZ%YZ5+ zyigDF_xc{Z@vd97KPT0|7k3!N1tDBxSB9XgCD7FcYiQJ>2?k6s@JLN32u*e=7zVWD z@>+ZXMs4sr9n&)?`oY-|I>&I;J5JYk7x!kya4An+@S~7!#d)YJ=#YD5(&Xk0X%lEv zO@AUgwo2RwwaZ?TTIRAplomsS-YGyNgL^z}`c$Fkv79_U+|LyCHP7zSU_{*{z!OxV z<&!hz5K~e01&zWZPaKS&{sSEUJc?Bhw@?kVJ17RmP;T%AIq$T7L&rcN3bt~62_r1` zLn!*4=Ra1==NmOtCrhe1!)?z3;-Np5?KA7+q}JZK<53F2AzC-WA!amSHr)N z&#g_Jn;X4@pl`I_Y<;XcdEzn4nq3Jsq%=izDZIQZOh_9WIWm~qB+WN$?C{^z3@sJY z4rzCim=jAjUx8!Y+R>cU78BL`OSy0M=(*3d`;x2uqEQ^tQ#2|9v7qyqd!K%S-zFET z6DaY2BMOT5G>w_MWXQmC8_0(ORbw%r6x4&JL>8}JB6hvJ(e(p#`wY5?bvtN}9L-jw zYvElGSzjoH^7_l%rkMosqeT@^8`N{j1%nBub?}6#8xn1hNU?HVl0SsszPxjGYq2Nd zuJq3j=pr@Jo;pL%T$q;GshY5#~go*sm`GIP+E%x*32A2I2c-6o>lR931LhB3oO{kZG67^5UK3=7C7~( z_|dkRTQ{_&HjD|I;5ms!G zC~=GO+)gcoOx>1L2REbR3fw26ajIL41ku^KyWr+65f-to?Avi7XF8a7*N!?eV1aFB z?SdQ^w>3$e8K^t=2;nyxp2oy_JwK$qaDOTAK_E^Q01lC#SrDK7b0t%-6kV;%T?Te@ zZ|7Ni|F0t4E$R@hNuGCLwGX+v#r{Qp!N^vN!n0kuK%f7J$QCf9TIXC2RL zzuDnD40dqW-wpbsl^;l5FYNP{aj#+G((<(Wm)5{>Aaf2kda~dqbC#re7HLIt?@kvP zz4MyAK>my{6m1|3l6zke2BQsx;q_;P!Tdi615q|)!g)WVTG1*^JDT}`HhQz|nUOIO z3!%%25s}buX)ckgWhSgdvg@Unz21nt%CN426jbH~`J=aNq`b`z>8$iz%s>|B5YA4) z)*rq7RWcAgRImSOXJyVo@F7m5pyQznoFM;@=k`t2Y6FFnl~b(UX2|y)qdI5_ft?3@ z1-uSh=s-1jrJ@SyA32DNZ{drQK-&(wnc7iyt% zgIc(pP;hwXwlNgNzV&CF~L!AHn3TMXSs8Q!XUec ze?wAhgRoh@d&%yGUToEXNeT8MdC-s}+ig6Vxbtz=FF`YUPf>WO$9-0ilWkY^3fLaV59-;ND;L+!|ujCk49g{bFT6Q?-*A8{PnS1 z6r95qT{u8601Ha z$T%o3tA@kF=>E#QTBmQ$ZR0)YeYqpMwm)mF@W*Mh2;ADmV7=X;cLg=l*ewc?Y#w%oWkf|GTpWX6UBLyG~Ijt|MIs|6pR&lyz7jQ^3 z`=-MHp%B;gM=l1YmLIpXi3U<%WctL%cHh%T`I<9t5%$-M^kgwo^msP>wnk{?3<8dk zblr|C8bz2CiVln)W;IobN5_2?Z!XN5jr&%no`k9eHMi`_D1^+%G=)77@a>!8vcpki zmn-;Fh>br31SRZ0NY0F=jd~{RZg%Nb-)m7s9csdhBV~buS!av;pxc(+<(0`jpdP9R z5~0+i+}Rx|ce1#!vuxj|#k$C~D{U|g{@5Fhg8s5Q^rbtLgJwV46~|E$++-8(AEY~j z8hgwN01Y4n792+y>!Kd(Iw;4?-|*1bJ9D)e9{O(E$%F`SAeC{P)EHv1H~xn(?8B5# z9#g97>IJ%?{P`r`hl!yO&|^6tQlEXAnp$nR@x~~&Y2&VXdgyyPkYV8ic@F@+Ce4N@ zzqE+dx;CEv7{^vT22bGc(=kX8yB%2Y|2)iY3=LX6$>%&O;9-pX*AD!p}6pNYHolunee?wxcnn`PXyIU-605mFroExVpA#bt?XzG*tr84Y?;s ztI_MVAydJz@Epm{nKkm-?^1-n4H*a*IxKmc66R%rZ~tj`u8!qXZA6W@)`ipjgs6cG zTrbuk*}eF*ByMP{rgcv2jp@5RzUu1W$fbsLJ`mMbp*HvBN!G#GC3(Z-(n9$1D42R#JXLqX+J z_dL7>v{9>_+g+q)g_8NvbE}8X0s(3(URH>U04oBf+b!Iu^{}>+W44_mncz8j z#|A=9E?jMF+Ghs_UB5FaHVK~ie*_T({=@dE`w`Ry$gtBHd5hShL%VbR-)VN3uOcek zkF9qBsjkVIyZoEC>M15)MO}${pv?UjEpF&f=UP}>HGO3S_iLnYp4o1}>o8+wdJyKW z{_4^=N@Yo+l(mTjoo%tI+*hJAVRyb=j8GJw|c{ketjrzuz=XUEOM-3CQxS zOYXW4WrqmlcmNRqSoh;(%9ZUt!Lu<+HD42FKhCW<%`I>(G(}SdQW2-(a|i@QKcqXW z&p59f%1yBIXCCL=hJ3!S;;dye#RC@6pr+`eDryUqpl#fhcP05DJ-=_$-^*+>OY*PP_-8F`#XMBC! zuhEH-XJUCN6Ix#8thl$j;h=nlWUxh+VLyuxJR7?qo7xrUlG^#}o)r063l)ggId-G= z7GODWAV($j1S=2s5YNOxcGGm6oqkWK7SCB3OIkvS6NhsXM3xUlbqhZr&jkeK~JS0+kU}mD2nCHsN_)GTY48f^u^#cZRrAMkviX%H#5&-a=suPNkN_o z=Ct-U z2F=+O2PMiPjjN}!c!VV<(h`c;W`h=sc$ex%7Y;s_;{xvPw(g!#Aw|9QQJk~TN0~|Y zlJ5w%FhxsjEZpiO|2ZJ6CKL}wdDmNSQHoh3T_E#~;oY)>(RzWpIT_hrLu(2AnB^k8 zr&c)-4Noso!&HD+1+B~nC++;4gPxbm7Vq9nh^`1QG*^2rS>&otme+LB z>z3c!?=I1^UjK(T2{;aPDKM3gyA6MW{Oa#EZM1kiEP_lf*au<%o9LiW{7<3-_LIgr zcI$4>!Le2s-4E#o)RsronXhR?1SsV{IGxQq16h55UwrI)>rVvOMjRQNP$H_cmNuj8RfS3`iEd)hWI9CN04=!$grVKI? za?NSV+vS7KCs7esB)9KLx_e-M&Jrq!Bkb7 z__C{=sY}0eV6v&5O&+CoFFRt-fMzpL96-%S42F9Gwql~9p3#=BcTVYuyMok!=0QvO z&xowO6r0w<+V|Y6(@AoEB*^ucnxeI8x)VkGUd@$7JK{%<{0yJM;KOqH5r4S zdKO1q%r7X87_}N&NKgkr1k+v|Vc#>>**W~cDd`i2THhw#1$Ga$#%im=INmY3OK0bO z=Jyx%?6xtyNBhoAL;gsy(h_Q=^KzQk}J!eRi0Q>$j7lUdv-K#>v949G{|7)|WN6;Gf9PRwQ%6Y($ZPKL z5b(!cbE}a;Lh$Ta?N0Xkhm4+-JISHwsO|BQfrGhu3wgWy-FJHyCgmGDyAbLZogf%< z=?iZ{$Wa?$x%#uo2^w+PArTxKUm#!aht?j$R&!k5+pTaKC~LK^agXD&Yfb2<8RLT~ z$zEN{y4AoP`eLEZnoS|RoS8Q3jd&DhsAH~b9jX{mM-+}9W%iTdx}x1t5r?2_C)rSK z&eFKf-|K+g_}0h6hcHg>Nm+2ECtkOov~|%r?L6k?#AG| z5gG3KT_;-Pdpx%0<(xPvF1_D&TJ^^MVp{!=y5Lh1_i1UI?ofwZGcRFR;Ll$lKlr1MB*IZ%5}Eh87+fA`>!Hi#mJ= ztg~i4614dP;i+MHzW>tO7D@0!Li@C5mGM(yStomZAe843W_drfb@5w9U)jIj#R=N( zZGw{3l4~U|`U*iQ20>u8i$<@Q)#D6?&0id{#$0=tLi(OeEw-^;S!`WiyknxO4#s_x zfYzXBvlfFpICkO5cmbo}I3g?QV3dO}bGNSh^gAeaR83| z8I(J&FdpRDEtic8s++|E*7{)OarrElvQm%f)+m&M`W4NS)hC{xG?c6`Mk*_UFTIH5 z_=+v7saUy-I`53Su48%vcIkPaD`Dx`>v2E1D<##J7JV_e2Qc(c+1F91};T5nASx6VzT^M zW`KD@PmYVzgQ>&k>%9*i`06FmMAS{c4rJ#=swcz&PkZ$~HMZ_5&|j*muNKgo6!B#$@m!*Is(d?1}!aTpIU>5*trmwBUV*#%gqo zU2Sic0pI{K?=B3i<;9ayO?rFPy#E6NY#b%8Dwn)9XoeKgAxhKAu%`!1j^!`VhJY~N z#Bg~NU-cH`FtigC%1`6!cC7BfZOt2yENuUCmzC@T^JUP@3{}BjWqtcwZ@W3Lfw=pZ+IqP~j;PsaO&j{en^pB)n~ z+Z9bthK%G@Do_oF)(#vFqp~R27lWb3{)>Z7w(3i7+mH1A&I(Hq@TG<#jfMR3nGEZR zzOlQ~R3!DJe*ayd>zn^yw7qFqlh+=;+iI2FqEbbO10=0fsWOR(j7i#BWm^P9Dl zr(6PW-n?1sx1Q&|Zz!5r8NnM`(pExmfX}lhZ&+8n9MzOlP8}2cjvjp7`<8dIp!SjX z?rXh|Q}TD;eQmt8hlp<}EXaUfcUHpLVlviePbTwweT2X6q;Tnyp2nP<$|a56YABiq zXkf$mx`=N#D_PD|3x=_3DFuz3+HV^~?!Tt;QcC~=`egt&QYMh|F#QQP;! z+tE8Ui{mTiC6q(IoBP_=?(dKuO=0{w_;MdrH?lq$k)gynt2%C2e_kS;)L%qqi5=I{ zaQMQf^4gA@8TZKix_F&}cDurJSw6!7@WDwvd0pqw1GI~K$rq5UtQW4uFkHxLQ=75l zw9`4C63%5OWB>AYU%==He;!je`{lz!2>4^Yz2wPe6A14dvZ(lLH57zS z1KR?kp}#wF%c>E|a>aq?%we3ZXvE73eLW5wPgQ&EWnrZucX|k=7fppjhq1Tkx{68e zp)Xr0k0!qji}1meM@MdEB+WOSQ5SE3Fj_&kIV#jGb96bkHj%ga9J0&0p%| zU8sGsw$)|y>+zK`{6H$?Xi&+aTNWm)kfp!Hg(p$f7`^VntP>#)$^u32B!>yBlzuRb zs}%zr+9^m+eS-@JEC$*81ect6ho$XFWkmtwiV^0c50|Sa$D`lO=BF%XTL?|P7kKwwUuV9e{piZB$x%sY2gmz$Lo^bl^j>wtfu zD*DN!cbV-z7jYT9wf1a>uAYA$%v5@^kl%~B)n>M{c53KAJaNMPG6ED&auOr#c>&Yk zM*our(3|~7~ zK^-cZnEaM%(Avo8SSawvhk3tXw7Fq7S{Pb3QZ6HWFnsd}OtoV6SHz+DC+u}}_7GKf z_7CL@(HCYq`70AeS_osUqmtQB9gb+=_2WW}9?I~nr|=POerh|9D7)r0tcM9zI0zDN zI`Wj(U{i$Y*%K7)cq_08&vG^ed%}KBDlLf`SRvU4_tN$c_r48Y;9VWiS6sge52!uC zl8IH>-E_25C43#XI&vPzqX+!V7$7!T`b zeq75~e{coDptt(3)SVay=?JRm2G)uZkl7W@n0k+F{;Syw?rv#+bN(scltT$T$nBky zhd_*wjkcbRFsmmYGB>F>MEFTr>A+EgEAVwRdSS=+BH>5(&Y(GBt` zGctns={vDZ5No257t=h>(znd9e}Vz0E&m3Gg~6?P=5x_BR;E(B+og!=JuB+GDh@GX zWtfg%vr0le+KREOmkw^_o8n8Su{N#JuG&Wa!*3oMTp-&VmDMRO3#^m$j&LfB)sV0r zFW&0frrAU;Zll*6a~ei*l4$ys^yIjf_Hc)h#>3obM?wKVHQLy5A;$DBqwY7mBg=E< zD%>Y}0AElr@=fu^f?!=`^iB009pwCehIoNw9OAI{Blwp+leF{$M4@MzdrTsIDH-}W z!#>f>svea+GuIxb#~F5Aw(33vfXPzC8OnT<&)|HX&xYhXiBNkqaVX!xLXW7WK)Uv% z2|BPsnO7{UqnKN*7TpjNODGdQcOevBt7LvsKeVmt%;#(X4kVO)kjk|%j2QYLsBX+!?$1`?5JcqYZ1)sE9ob- zQQw5Wt%aC6L&1k%jlFLbQ_Zcd)wx`^>aW#`q_ql;E$Foqs>?!KZnnh&&DC4}pn0Ax z>Y9icK2x_Kag{gIDXy(|_tB#Gm2HC!vP2tdEJi4H9BYopQ?_C`@afW=6oS7z#5)L( zQHS*)_MG)S(;hk@_WxXU+KjLotqG3+=iOH0>mhNqeoH28=y*PEm2_~^Kj`p3I{^?i z&j4Qw-OQ`ck&e)8apeqdY#sh4#7QbgJ5cS64le4qXl zxq2e|!aimJPT3F~8(TgUT=@YdU-QJ4K2gMymD4Zm=R9=zzT98VA3xiMXtAH1(g|}t zpW_uJB$cvEnOVb;{u^Dvd!>@03enc~v7d+5Sk-w&dB(R3aQU90 z@I!n@j{4rfSpd>!*>H=i(^bX-&8i-(AhK(TB6Jv~RIhngLWHxTY%!?8zVyuc_#KM{0~b*7l69xe>M4Xcp%p9+$%peAK^tTT*Cc zp^W67-<$4c3h{5Trw-xVk|%oIBI;xxJWis*=Z?#hu#QRN%LX4-tmCPjVNDz`Wtr4D zD00Rk4Vx}t?sr-knsu6CZ!b$@?Ab%Kpu|r1nOD0ZVdIw%dgXJ6-nkrePg;51nqRU! zcb~FSY-y2XHl39){3#(&R_j;1+n}`RjQ2DaG34V&45o0LDAMJ73gg~?@q&E(JXGV- z;&6V`9t+s+$>Q~8A6xsi{a7NQ>@ry{0VMBZc5#Z=2Z{%ZKBW>uwA@YaGOLbm&eS^= z8&CZ=JG}8#XVgOuWR38g3j657KIw+|y&7j$r8rIHRkGrJPi+P>af0rxd3606TKM$L zW_IW4=|>xJ7xi23M8zCp+ZUe`gB`*vh635cft1eBHFD)VDJ#l*v+2yr+8>m409UcU z|A`)vQ?lure9pUfo>kUP&?m67c%}jSHDZtAoF;+ z zJ1x%TL~twcT-_yO4$HCfUXKgs7&rWf{rsww$IfU{fn%Rn!Y@vbZ$VeO9z;d&QXegy z=v8#7EVhKo6AV{6yw3%wvcl16po&Vz{cpBnq9athKL|f#f)Z9T?1T3XPCb#?iws#d zBFc?tG3&SH{#JKlh3!S1(-z-R%T{W}>@m_TJEXzvY;}wU&wy=yI{L%scUk2Js_3xUm zf*4i#PJuRF=0`*4hzR;!NJHrzd}|e>Fp3%0nCqKqN3s74AY} zyv(ii{Ytd*>0iiEoTysDUY9d5qI*_7LGBiMrA+%sCOVVgrNE$f1It;T?@1W+Zbv>w zFE?J>zIFAHJ{zqsuCYIx91uQaq#b6h6Y?RJc6qs|haRFUrx0_e#Zyu5Pk z|NO^CCCg*qsA)US8Un$>bO$z8XKZ^-5oSRNERJtR^+7BbUYHu)YB^w%G;At*x2!O) zy`MS#pUPpr>HU?ONqHJ;OEZ1zC#=d0=$Jm2Y~rvu*2iFG`0c9en~f`nqjJFMMiP;TBvpr#VH@1(`NpSZ@ z^lnDHo^@n&6tm=po0=^ae#XKF9GASkorDN|tyz>XxGR8Nj0OqJ`ZX}gtp0uL*9f&D zq}j%lLzR2E8F_u|x}JqkPl4oc{ljj+NU)^`XvH(870u;PcRQf1iw-y3Gqc9DH(K3X zIa!Nk`8t(dFAI*094_4M;>}hejPgll7RZ^o?`s0d;|iH?NUaMm+Pss}vITk@8`HJw z6sOSsW;6vhkFmvtl$hHsFq^#H|=8N9) zdy}9c?{ZsBgA^p3m~GT+5$dg>Id`99-`?0NIUC9e7kw0QftfRB^D=*{9gSKaAw{%mxbk^V z$l z4R%_r7e~>{t^H4g*Um){&(fj-v>z#QN2nk?hB+;iCGpc_aZTy)l2 zGhav>ux($%wE61UUIRvjcb|+3`xfMYR~?5NTq~Vr_6e|Iq4&vdx$6kDJzWpog&kW_ zLoTIOz4|#WgZ|sT%X#YhoCGKLYj}TUooW8fWmLXImF@2@$DVtDD?YpVVnxhi zdpHmU+gk(QqzFgs1~^g94x_mo!=07)eX@D+F+KfI@!HS(Kn?l8X#EX8*9;}y%EwnG z@9|N_yCZlIm!1K7?o1@SU0|c5EZr=9dBXhTdRQI1=7jMCxVwWK+}=5+D7g#w>|2br z+6x8VzWo4$IQd?$xo2>e=NwR?MZqkmUUCksJ%OCbrS*}c{7ns|+o*zxAKRkkvV9oA z>3N8`BvDzn%M7=sJ4a`yR;35nCVVRSt?cTPN-lcyu=X~s z!1IW%90`|)JfsPKY*3Dy%+Y?b70q0)WA-x(rOAI&S zYh13%YLWX-z@Y8xu8f}~?Bx)wOtfpwoXsE9Th6JGaXs&mPZ@;ZcrL*og>6$z$+P6z zX=dHVqVE=!O&X2pc_=V2z>RUod3vNxHn6O*0N6@>Wn z3v=p=W;@Ijk8%z?-1V^1GpD9g{(5t76lVV)v zMO5M|pX=|hP`vM(5fJb(7v0sSYRe4u=6k+_4XchfdrgR6>fh{D9L-X&trjoOUP7$x zW|XAfk+;&h)lyA7t?#S_6Z-h;pbUF;8L}{D1aqN2J+H_;gez((0bl3;r%%BWrZe&QA6f}WD0P8#;-;(h zcRURO^6XCd9=0g?dkPmg%&WkmB2)^aAyaX^0Fo<>Sa|@_oiCm-(jShi6t#X7*S@%7 z7uS098`J!Gab&$Qm>%UZz9Op*dv|iFq83WXhQ?iH@d6VA$G5SBiGwe_6i%?jB+vQr zigGKrx#6aPvzZFnNou_CG2W!f3Bhm-L#AR%k{m`hWA}x#Gpxq7Oaq>t52v-&bklYP z0OaY?>0~m&YjVo0>f3<)vD=WJ2&kRWjpn;TLfb$81^ z$Z;o^j1{RDha)`0!)IKklb1_3G4M%EBYCf9=Wx99+CEKrgCG_eJZWZ`J=)pL&ow`f zh^ck*SueZs8#U}D__#~yE#Z|~=FBvF+s7!DvAKBI*<4&ksmVw{XL2HBELeTLEN_UO z3C=NYNsDEo}6qj=UD3RQmGDzmr`^KKuZV0LXA$aT8Z(5P0(jz%$r+?9jyj^I9ZNp&$OogGmo2h45 zM`6Enw>LcOpXhH~{@F6yi>xFFR<2Aw6|?jnm*Eru|69kF%V7#Po9RYuO6Pw$(X<1L2Gkv z3&xS@uFkM}uduSl7v~pB`$>+3I2A@Z3!T&s4p`@}x6?}G7M>A%%u1uJ$Txat%a$Aa zov@OY0abDu_4?hiGGbqr-H^`AR2N3@>!ylpkYVqdAJA;MAl3`#`s!^7SStOd2_#=o zhmdTO0B1m77*!4JMb*Cj+o{JBkZCBusb+zhI{0RODQ2I#<6x+5oEhw9yU4Krf_k2( z5!HOuLsCY(-uTBzL54uB$NLI!qvWseH~CV-YN{XdFWHS;DiIplc=7g1>IJiKew4>P z++b~CZBjtfMT!rcCfU!^dvh@&pL6V-4^|Tq-qB1R{s5ZSxnOF*!Lnyz;nYD{yMF;_ z3Y+k$$&vFP+Wx7OZ-2T)l$Sq&bVz~T`{pZ~eut+su-Uv65r;}%AP_@4YIZ(pCUV0kJuBk_Qbt)W)v-=odZ34Hb5)Es5fW|!H5 z;1W@GIj^t;J(-8fuyOC|RojDP0Z)T`=`R^udpI2vr4ch~YoMpPNb_Hcygg@(kS-S& z6I+|S1oAW$tyo6VYPT0(rMh!6i(U)-1p8E1K&xCB^)V62pmMt|`wlJ-lRU=cY65#4 zBc!2l!5kIW;`CvqwO5_yoeI;~`en{paziKFIcDiB#Ma;zv8<+RvKQI^I$9GUZYN;D z$3nTz-p*CST?K~LXp@!xf7lQTyp7~g8z0io&Ju{gZr~0dDv|#1Epe8BC>G2e4*PL8 zO!C4)KNfdyl^&QGsQ|^(n)dHT$ttY|dzCEZV_A*)-%9jw*U*TOrUBV`Drg;W&CdLD zjC2Z+DN>L*rud@gTNkh@YcVr~=ZEVH#+1a_AaSy?9V6OclP*zKoa%*65dq=7rW6VP z#3`=to#Pov^{MxdLl!46K4D3ESG_Wr^T}#GKa9xpg{7hd*9}~_!U%~h7Kj`PJkX3i z*ngCJh)k_&@Ju2-6{vDHJY01_grLgR>Ru*Z$8t4+xmt#<#qmFY3vF8ux z;piH7w2GF)XOsyeDkz~#+1&nuvvYZlysn7}_bj}!JPk477L{`XPzlN=$S)(qvLPG8 zYO1p_*P#1S+P_DY%5{^4d{Y6f52m5Ao@_NPdaZJ3zG+QcTo1WDx+AIZ1?{tla-i8&eBE}`b62&fB%PQxh z5M$~$wOE2$odfSVoNcNgN88h~UR<0k3PQo%7ph+CU5eTGjgvdoA6<7n^=DlLwhs-f zAInjt?{NhUp*K*LmZd~HwqF`>1$t`U4RvfG?>^WaKqQotljs>pN5+Lt_-Rqs1J`LVqp!AioA9ox zv^(urKF@z?6r4_*7u*Oc9;-k2PFA`e<4cju>k1e-`|l1$8|3&Fl#jKGj_I@Ci;N{B#AD}T z(AE1#^~|S3E|W&`Q}Ic8{5r+~610os?6dvLt*7Q@b1@-cn@EZYTYGTvoMP4Su

M zWO}UA8W0mh@SOW{(2!W2uj_ypoKm^@;5|lKsT^+oMsY#S`9pFtn~Ez>Zok=zkrAs` zMPc}-R;c01Hz!GhYKS&C?zAR2Jm92Gd>(X09YvjM;5o+Tg^oec!J<9)=bF zC>}74hUvBpY{YeA#1nHrUk+ccK!x#fkEoJ4rBYE^5UG@}viWlc>D|;+kj7Dnk#KGJ zn0A}B9;+1QpLKWIJLLmLI~!K_2ms3q}il4Pf?p6+(={c<{CuiZW#^gK(=L6C* z!+FDa{PjnT?-RtPPMa6{Yzu3HFGFZTD{c%K)W);Ts?J|Q?Fr4ty;waQ{=512xpoT` zugg3pI5E7d)3ZE%k{Ly(=Vfa!Zl(qgri1?RdlWIl`SCAY)1!^Uf|d&L1Hbbs4M^%k zp;BXHGks7kI@N<>Kx8py?yJ|(MiO~~c2G5AHt(|1nS$O?c!+sqza13tOx8BkUrZum zrgdC;2xCNenb_J&SNyv4jJ)h}n1-Ep3T(ZbDeI=L>LhluoF)HC&SHm8|63AcFX61> zZSoEKB_u=tm)VO*l3@kL{WhBT+k|XS2{UxySMoUxjtaJA`7z)!>LY@BMuIvXJEf2E z#o+1zl#N_#Ev%^D&a5^4#O-r)r_M@ayL>ySzKUlwHBfk|7O0&%UKHPZ8?< zcy%IZ9V^~s(^+z1740gjW`Hocb0hO4c3krhhgyd#HnHH{kECB(*eGd8jT3~eQ9#mk zf>SU0W;iVFkDx6<@}LX2G3~eX9`6$yDw40we|YmV!qLy#&M@FZip|(m9!Nf->g>lE z;5gft{l?Q47wWEOQR#nT+bcY$6!iM%ecbBKo3CX7#qQT!keCYW*9N59g&BS&Z0$xx zHjAR|&^&B26l@;s*3k9-B_e2T+E7&2lRw~Dw*&$%4{q~Wu7D7*uphZ*W~Pj?A5wvh z0TA=K^snn~o$%3*DV%=_3mZJ^4z&_Q#thN5NKG8e;D0E`Y>OpXf==|Z#qnwupAw|@DO`PDel6E|UBM2?(+Mgb3*NWWlruTMIi3?=gSW+w2WUmSh@?hp;RZ z5Wsh{HpW4SN_;nGd^gS5g$>aRfnfKKT!inhCHeMtQHD$TjJmp?y%0hW?Y?) z_xur85sr*XmwZP@rkkYGMN=D5!XsmE(%l+{G*t%KIxfq>lW*x8g@pntRF@R`d65Uk;oxeMT2gBfLR#Z-qUs=-8GdqKDu?cVOS;c2d=Ai!U?upwe@ zRjoi@%Ci+I&X*ag9J3)pT;XQP-Eg;$qOx2vy&1hy2SvmE5A0B;<*5 zkpSnt;LzGl?O|=c&f3L~XgC5_G<)5{wU`0G5Ma4OxczC$PYeQU_yf*1=L$?JnE3m* zHX}WIcs~-%woiHZ0sbtj+Lc7I4Dv~5b1fh=q4&J6>F`Qz{r9b4Y{-%{GEGuLw4uBg z;p=}#&Rx_;?5=Bbks|+KTLpp2rlJ+E>w+@nLSL*2hj;>+Cv*}_u!G(Yuc+1W_ z8qWN$&Y(E{V)y?;XONhStoW=mczum@{o1z9;7K{lekZFIWJSX{&_m!}fD(dQwrBpP z8lW(AHo|H6&C;2O?p;NbOf5Z17Wk%T0FY|3>n5KNA&c%zp2bOyGR19S=J{Zz*8RZ1 zu405ZZyK`mch{I&9OtBhaxCXh#>*4i1;k0tg!frM4AFm$>8*Z`Lgu;T6E`?L^t23j ztyc3SLGPcuvNY{O{>NaMNkIt10Qg#kb z?xY!Rgw14dOD3#KNAExLqp>61rCjWnEEU*b=Ud5iE$dVUM98xe!&7T1jb2svj1B;t8INIIefpi* z;bsuVaQ|}+{nqIxHDxIgSyk5xT@sXv}2Y$n0#PRZyBu$_2}+Noo4fXSo{l8KwYUZQqX%V zlO)A0o78GR*mv?0Al{Jg8+P$5T!b~KZtVj>Px-+l^2@bo!kNaj;2 z*G~gN@8!#Nh{na6m@J6?j32iQ3bO#G(kyy9r!*CW_{Ttgi9eTm^Xkq~v=clGJ&gT} z=Czo*7pmOzEVbn^sL7ZFKO6w(`bS;rN1b6EFCXMbJdj0YI1qfDKY%L$It-u`WLzp@Pa@69c>qOr2_KM2KUS{D_$hHM=9 za2sFjcZ|s$2-VMwsgLn2k4+zZE^yGhoP9xir9)&dUAwN@9IH>EPn+U62_`?rlyl2w z_>Q-cg-RRk1Yy+&&b2M#uAFne=MvC#KF7;%Q^hujlp|N)_?&(g$#2-HU@8@}2qcXy zD~zSDhBO27#qqV8F2V^CriW5|rTA#Uvo~%H?vwu_SXtN_`J|r6$e%Ip4R#qkgBW?5 zS9y)L+*!8vqMH7^`}{tQo@cuhxX$bncz5?#>ivNmv(0KGzS{2mTX{2vqG69A`EKRi z(4n$0fI{T_n7nw&$OoiV$dcu2B$kmfoUVF=LKzIn{~Y}>&9eI2`Cy1OR(5N6`Xk%F zbyv|aA@MNE0pExdWd@H+R#vQ3wp>95PzO6YI=+@*0McIdI{I~wmmiH<6Ae_xZ<%uR z=L;w8=ZPQ`TFSuzMp)*(dRs#n9d6@_9MN4L9o;yU18-}k6c-~P&9rx!T)j!mW>Ys` zm4)Nox5_+3%YVx_eLYKw(q<;_;(l|2R$}J&HtX@VI~~6$$|qAkSreXaTNAnn`+_vF z%hO7}{;ZEPJEW}`30oI@(rJiZ?iyL~eoCW~j94t$^@eMtHHY>}K z{zTT^5jgif?eKj7saudK7utHnJAM?DNpSc{bXr-h=tCw9JDgfNn)C1pcJiDsLuHMmx9rmywnHqO{agU{aGwJ4`-IHYu;vCa- zt&r5aaWq`XVM1seiWWmXpYo+LKc!6Q`dq7(TH`J-2u7?H@LuKKT03;gcnAi(Zy!T>s&_;+H8`{`GzA z7p=9ZNq^tAinYy5L8d=716>eqDXPm!E%o8?r4-*-eL6m)bg4Q_Ap4cNewBrt(|_J^ z|9fUh*OR-Tue=vW#Zm@yI=u^&vpY37xEX7rhhw$eCqKeE++}9=vme3sA3uUfQ@tzk z{nx_9OPEYUM&b-)s&loUfr_Z3ypN-VjTQ8FdXGIzVJ)X_*uVdqi0<+2-nF|xIX<*} z0>g_{^Rf+@PPX?-3__&!eMbm#VW*V7HMyHh$X>qD{5nZ6z|quO6PuqNH*<9C+8vRw z$kdr!T?GRN_Q|`MsrUtEA91;%nc-aEpt2Jcf_wLTG)Sv=Ug(ckNamnbF>UM=JjDP= zjZ%xLOknZLd~r|YU^alNmbi&w=;4=LAfU-A`Sud81l_}JHv!BEZu<-xRPss>|X{nlZY@lsZ9hCm6( z+XwAe{r8xQ<*# z#aMt~TfK;iMV){NwvU?`FyR}sIoi*{-HlTgzuxVEn58r_EN=~s5hau-x@*3sct<*E z@%;R~4g&1Sjb*VK(p$iy^9O3xr8R4qaLFu|2;lz1s0a6VDw{*|JYGJ0{qP#)?P3XR zHPT!`GrU&a$gst4$dRL`V06o--|D&iL0(+O48;B_#vyaU!GfyC4Qq;yHb$G)e^qG!0UQ3 z181z>&0n8CPtTz1b+w|!*NYvT^sEzFgPk>aDa87RI+}XA@^=fP=i`HzRoB3;%a7*w zHhXEsUy~?bl-O!;C372<5c}m8`xSff zlc<}M4K>}={;BdnJ!Y8`LeSK0DBRI(YH!$*Y68jP8V1~O|36~~&p@Sd55nGkc+Tgt z)t-M8oZGj<4-HEG>rVdP^5RDI2#t-itrA%4;z>SjIt&H;Ye<8_cCmT|Sf%7l$^R6w z(RS2#8vJED=oTuc}u?E_<72qYDyg_-b;DLYrZv?M(ZYY&q9&u;r#F`Z7`(x z==2O_1W6X*A~cQT5hc|(-R5$fW5|wZBWn2M-1q6|*{3|WhR*72ckzltr>Ba(w0+7Z zL5U%8MN7KwbsI|G+XP7*SDQ)CG?r@B5lPV1Ug_=L*ytDx2AeC%y@DJr+vFIFqn{p7; z-*o5YCS3Le*zShrnKscZcxZ@EmjbCaKVU$~nr;Y-66n;)qlZj!8c`|0gE&0Z(*w}XMi*)@-jrv#Hm;;ciwa0O6 zQ*4+1khx$o0qc^PwcjqC`)l>W*@W?&DVF1E{hz($z!cIE0oeIIm~#*}H8j74Y!o@r zBvrPpv+uK}Y<6;uKLZS|0e}JhGr&Mlca9U|q{U0%ydZ^`ixcrZFV5@av)bNRm@lJjiBZ2i3Uh59>Ti}$p{v8%?v{izj$#MY)`5GPDgTbHJ)L_X|SSAz} z%9MT5O49u1=3I9qBoOBiVe|b7^>m}BBmFzb8Or<#9*_E=e$90`Wca%_7FF~m6YTp; zD`fuc6e7z1J=%ehCw3*{ypj;WiJI&jud(k#(uJ%+8&i@7w}Fl&q@uqD@QO&w@~)F{ zP!e?5SdOW?3RLd0$BK4;*^qA4nw=w`100|nR?XQS*X{ak1M;Wwulf=xB8}@NuN~9I z6Y9PgEkXP=69V2@n;@~)twd%Ni`q8@njbtDb}c23u31Q6mY_o~?Nkj>$#Iw3IJpN; z{+;LGh?{wPT4kql-Rrv$XvVGNwS$(<;^k24*K)U%!fqFk9g-FzhPtVLaWQ;toZ)bf z@Ffx3vQY20uz;+>A`iK?eX**BmL}h-?<|ZRrMGqQ;zvpF6Qx_fbxB@{*?iS) zDoz4I+Dq76u>heA*0v?a06DdvAdbk&HaPh4t-&|!cW*iZ1TyeWKV7>J1AmHK^Nm2Z zvAhK#%hX*2B?o0A_k12HKx-d%63qCUfFyR-t=D#&fuIE#2#5b+Ak0)uLH{2Ngwp?E zAh6~8ou+1IWU-$Z2uNX^D5YbDaO;v?I_cY``wF=4NVhE`<}7eV#nWLrWQ%*MyjR10 zLgFedq|zSN3=%D5oL^rvq-Wzvj*3dr2W12&40lta`?A0}kv>w>vidCqDataqdkN-d zMC=kE#O7zCeuhBTeiZkuIB49K>U)xp>q_-ZdHq;iAyQJdfuX#jEUQTOxOaZQ`(we9fH~v8FGA$?h^sukLDaoj> zcO_K`pv^PI)X688Rafml-!MN0e}@MMRO^uNF{s@R?fU76M^Eu*d#r2cRCys(CH}6z zk+}JRTu7_ZOuZs%ht$lPrnAseQv04&Gx+rCwn5>${~8q5kqT?Sg+=mgCB<7KQ5!+1 z2-yN`Zj<$=GhTDq-uh$sGNyd$uY@3GmlC3N^8N|kB;qn-^?92LiDJ(= zeSRsmxN0BSbJB#6k)Px!`Ze6pfb8Py}PJZJ!&Tu)| z@0`oN@n%|*!=Kp~tq!&;!iGYv-nDmB*T1X4ygCU5;)XC+f8Ve35{2i6CF@3r((4>0 z&i>V}ssa^^0F~rrf9dtPIOV#>ufH4;zRh3+3!Main*o}>UxVMCPa*}l=075Zwf~9~ z>H~WtPC`|HqKWvixoy`k-m8>%80H}`)O3QGUCLgB>7*tSC9cf8gAp-=#?{;xto<9`$i zxeIv0XN7{NDq}?hTBQsW3Zne22erv6Js<8D@AQz<7O6f;_|ki74cU^hWqgOqekJj3 z$+wDS9%im?>owAm%lCnk1vqaaCNF@gPx|7ks(RhIUCz1{exmUK_WFU{rr4=Q=GKK; zVYcD+LNtW3AeHU6BB&J%v2NM8;CXZx`@%RB93K@;cfJACP;y6l{NY|#;2ii}JdIwL z!NV^_K@X80r`^)v9TKI=eaycP4brT9!jr;LBU<>S$R1Z$b#=p=J&yx^dQvs_Yv@l_ z!-F$nM)c(jb6vJ_aY}Y~#_!TVM{vv^{$^utKAtR(lMMt{YdWryE z7ai%jd#d@v7!8O8phjzBBdM=i`M+_-LA1f6@l2%qolc;abv#5jAs()EmGoG{sY>dc zRe#MKsHl>f*?*05P>AJ()`OM@q}(oZXX5J_idU|JwSV^t52+ zDJHUh_~_b&^*;%!>jqGynNZg2@tC7RagzQ>-GLfx_=8LM_=L{Na3qjN(#CJ-?sN{l zs@~QoN1PhM-M9`+Ftkp6c3q*NM=d3A_gv9?wIm|C6O#RU5yyGKD4Bg54}c4~ma!je zMx0w0`yL0db2Pdt)VoE6=jtUh=|N>i;lKWDo^&BIZN*itBId%;813S-Yz+YBmUP1so?a_H1)0=jcsJb;EADdZmMdjGbf zX!&=PF)YI;+d1J5@uWw9ONLKlvo>2d2Q;3mkVmxe#IH?_TeJ|B$A>=sXLD@g;RJ5M zVX&-R`BTx%fK$nw&&9;FQ#cvDdv~Wv=-B>AjTH_T}V{?tD8(~pM%M3x* zXR#;^54NU~szWP~sWrw_Tg)sQAu{o3fIVXF-Xc{{gaw?J#`zHS`bQSYto|2h_imL1nLfMX%?vtywUI2OE1Pf(q2 znyb^3Bz3N?S%iQp2)yCjW)k9M)KBUi6-N~DN3GPmg_4ruz%q$L^ECe7{+hE-k>8lp zlgb%`gp~1?RB|n68hxMnt3ZV2ucq3Kn@u~2G>#IgVFZsidKyEz=#Bgif6v=fL$^S= z+Hh9%S+U?IDI84utXSZ9;}z1;t3KUH|D#w?RNW+oxBoWn^hvS6{ayD%(%n}6nDu`Z z3*Mg<3x%4c4dl~xDl$cHI)|!Vuy3WtllDb@WXolCaNawziY@vP!b_0K)iAZwK!5fD%naazI;B|F&`P8{er?SJWBVye6Jqy)~1?t;?u?rEL+I z=_F}-aWcyM_h;n}ME3EqIS&V!4<_?8ozec=| zga+Qm(H{oZ61dOE0X{(o%|}+B64zT+y;1EnA8Y2X!c7hd_MtPB^cImENg}*%#W*9B z{Y^RctEL=;&_&a@q?)~vrG0yTCAqLG7`o1>I*v$New^&5+Rw5}BVw5PVPMLSYId7} zQqkkoaJToJ*um#Es^*q!Z)}%%;PZ>5S6S70M+L{PV@&6#PU}?}al^+TzK@ecT{2hS z5VX;a!bu}D>Z^3h4}se`si7*0$N38Qby@F0by{6C?&AdSXaD>=xef**zoysY5z_V8 zF0*~+6z?d{ty4tKSaP=e$57nl$}j4IMr*qTihDc??|R*{@hR=YsfP^KYG7FHTT;O4 z^E<7gjCDVbxQQJVpTGUm%bAX7%e7t3v~qDgeWUKK!wOZ2v#EAub9;f1{Bd6kY>Pp? zQh%r-8Fjb0OimhX9qJ%k65R>^a(25Z2P25XNSmuUTQqe9|M3<=CTnXx`W1G(A;gAn ztj}8tVmI#D^h(A>d`K^jST~ti&(aLr9!kJhHr#xldw`!0m4E2i8hjblqKEtoa6$oQ zJcBvaPcSwH&-D1}0CNb=u&;rxe>2p@Kg!xQ&u;X)edFu0DuS9*wYj8_jgKMY9S010 zXNV5j^w^L1_yt!>^-k8gOlM@ormVxz4KLlcT6pZZUMGhyd^|J?Nm#4~vfvA=p@Vep z_@j-RgQ`vvvkvlVp0n@J+w8-_*P)2Kz$o}zcKDz=IxIYy2)0AZ9&e=&(8Dfbyk?J` z0=ZX@e$B0+d^=Eqb~CWvf^Hs(*Jx_KDqx9NuV6vTss9&qZywe3xwrl9)~(c{(3T3Q zKz8d^s!SrH3>j*zvRjnYQszKJ1XM%_ks&06Dk2I>suYkZsUo5b34;t_NMwu*Nd$y2 zNq_)hCLx3jB;mbjpZ%QuK4-17*1OhOXPy5PvtmeoxqtV4eXr|tA&C#q>@O{{vYi7j zd&cZ!&G;utC!$idO}XWFwC-x?rW+%mS2qZ*xSlzA#1GCf3QlDajSM(>j?ssx=FG1( zAIZ!{%s7$#bWKxq@9Sbto`+OYC-a%Fk<@JAr@x}^J->>hn8&Z6WeuA;1J6Ew(*-81#@zJwd*RC zV;*~oX>%j~tSLKwE|WOtzY@Q>v68x(A%6|{k!@kgX)}F^*Qz(ghWxR$LR-hWPy;#cU^YzC3Gu&Yj=AwED9|h`(j|jaXnShnNBR7Tevrj3?>;2N=3-h0AB44qhv~lA$|pf+775*2Nl$1#igqyA6K|6@O1wGv-l_c8^2^0mJM)sGw8nm} zq;mO!gf2s_(7Tu(K02OoCIJfM*YLo`)U#bdjPS{{B&P>#TpJy9kvCU^h6SV^s{Qq9 zztPn5rrivlD6r8bthT~0+HX1-Zn$c{-k^+G1SOw)s%;B}`0Vl6C+_j9;pO%;JKmcZ zi-0X|f>S%hBUcz|EdFyvAZ%?9PPTnUOCCwFQXK8ldY3*$yT_LjU4M66X^?D8GWTh! zWi*n$^V$*egRdqKGSN{)l*?9+XQCE=Q&qw>Yk_L)Y1ep$d~yTBB2R`vPsAItVh< z>#44z87739Qa`dx@u4tNI107^XH1Q6MnDJNN8<|=w~E;`hVq(kC_HZ4NOd_k=3A_f z6Sw(5WU*%II4NVYA-3wEszhi_sPUtzY=N&Fbf}@5WkhGfaUc9SKksI$*OipM$=gp; zm!uuJ1Af)VkMS{X@oRZb96DBGNmyrQhg?NWcoQf)!36RJB6g^b2sHooVcgWQYJ-(d zex&YfVb+v~_5&YT^xP6bimLROGzn^=l)w*}x57(FAw9u)pnDI17Ol|lGViqWZwUoq zFZICXFtM?#e({#PH(PKUR5=*&g{{$y2;3&t7zpm@td*+8U@EUM%z3MeA)ORdg?!%{ zGI#5#gwFV_Z9tX&bjENEk%HYrsoPkthkRyg4rIoz ziBfLdGM2CWEeSf+cR_IeCsxb;KM3y9+q7)Sot}LvHe9YAWGXS%CWsB@Z;)vT3lcUv zBRqs7(@X>#0kzY?3_(LXci)1Y$~JD|mkh>Wi8JG*bAhuCgSGb7cG|~QUeSE7KI)LN z=d`yu?PecTa~NHprFZCGBoPkJeyN`|vIa zzP8;r)TCw(OsS^mYsec2>KXZc8W%>=o4c|z%|L07ZZql{gMKtGp3~NKX3Srh9{0Ba zia7VKeq>uwFx;+Yw)Vw5hh3LNGi2~$;n`za4O^s%SLV>`1-|09P5B-(uF=pZC|B}6 zc_$z$z}- zaQ;nLk+^+)K;1+-KWxdbZ*VfHN34@RILZgR@Kfa*0iX>YNnSsDQXh^#YqGH6bmL(n zDUup7M%h<+F`XtKuS`sea?|Q7I?SI8P7TNdIusl;qaeP^@4Vo1Y3QW65qo?XcL>-3 zM0kCR>+MHqBR6l4rbJcI;YER9A5{V$fol9^$?{LEnZrg7jb&4T9Y73K`V;1+8zUO& zagw1o?%D5A_0t|I{p!w*bKvrj+WDm+&5a2|wybZKA159fu&|lOUq#^ZTL-yvs_%}K77kWQFZ35U5&Ly(!zAcQxT#n?uSr_J~(=7pt zPLB2b?)z*V`B8qie4G4~Yy6xM%iAOKT)7|nj}&=og5J_D6^Dy{2wc)q?|j4Lu4 zJ*W={zb7vKTK8=?#$*ClpMCJ(9EC_l$GF|#Hw+wet` zu64}>{Kt8ELOft9p+c!9-dEfkJNy$7?|kl`wp0f1l|H@8Hk`S1=n~7dYxD?JzQ

xzne7vo1 z;Rm*2YGBZoFw>8)`AqlUOWiF>G}sDIHa>YUEhl zP2Wn^Q;7Ru0cv74`i&ocsmf!k(7}VS3~+GSR0p0@^{n%Ef+EQ)Br4MKMw>@Gy1VM; zAz;LSM-Kg%R)@`yi{7z^jm*61I%p{>A+0o|*TBpi987l0(<4z`(SF)#60A*C5Zl52 ztOt%=kYg2eFcVZ2Q-gie=;fT^h@zJ0g$Dch!~c7mLtAN?+wx-xvgVMX;;&ucXrJR} z@qEPBv8ujW_4lLHy21_PM+}Yb1V43z)OLTB%g{(^OmzxcHEAZOyhMwi&_>Jm>&DHV zE+z$uPwtM_TRnLUqgn$6nPfh7NA2hxcLPxNC}wEX_l;0QZ9RX$mU|!F$#5 zvy4UJ;Ta*%wvoL#u9<;jChg+!cU1ZN@umw8DApJ8`Z_SPMbtwL0LqLA9JMG}t!G#v zt5|ZKxjNR6m5?9SR(Qhqg2`pO-}!x^;ow`BXP4#v{cN z>*j#1@(sFmdb21jeVY|AjGA0*WTf<{{q!`y$o=Y+5n;7abFpmgpMIBmtYn8>ey1qk zI>A>9KI{EKk_Kpu1HxSNJA-@kFJu;Z=ST&z^0`)J^AXZO##C&mH7p;Rs9pnU&9H83ihrbE!NIHJ-L0%@UqwYFS&|@ z_;6CjVpc#q_~a$RCx{an@(Gxjj@Adlx*-l@%YQCX(3dduDm=oQ*D1ciqy_kRNX#Gmz@3 zFu`1>1gIFvIGKgBxLyuiv=?#$WsuaiVr;Pr7QU>^&QT_DOQ~6&l zzyT_j6%M3hQ$lKof1B?x3Eum@=rxc*7j@w71-6Zeg{JQGhN69OMcy;`(H1;APK-rd z>c0c3B&yCAFbrIB^%26#PYEUSA+g%rZqMn}qHAlfu4N&+bHh6VdLBojW9+8xPjEmJ ziu6n>bii7E@qS=O6L?P`=H=%0F`&#M;b2DNQJ36}sK49{cyK^?t`I!ySP-lWm&HL& zyl?q+>xlNHVDMuP!5xJZW3=gu`bhi-keh2-w?a7HwFsRn$~ zWBEyiJ51oXpaOV@fb&TpT z&tjS-X_BTxi0%uXgqeeJJvaTFbH;8M*FQ(k9J!m+?>1cs$hOrX2-Spc{0WyQ6rP*# z;~U5)U4iG-0xTEViqDE58eLq!`NPc;$%KF5-f9%$MkW?8_2Ai@uHp9)e%bb{l2RgB zHr5$z8P_57%UT)65(hqBfz3HTBqnEyCZy)sVwq!4z@^W|6)+rKm&CR1pAlO{(p)I%VOhudTd$B2+}EE*1BYu zcYO2P?u`;)+o=KC;U*#XPD}u*N>&9?H9=Itm|j)o2)i!@YPD7o`}s_wA^N9?i|Kv) zRORu|L+yYu4U3P_K_X|C^2iI`o-&0O^4Ba!KSXW+~}w1Hjk61=F=jI@aJ@P zUm6ymQ zmk~N>B$sv?BqhdwjyB~;b(xq+)gAZ(>hHdhCh;d-a_zjRSobWFOZ8e#rG-gcYvu~3 z;J%AnaYSlnHEY!e)^z*TYrMTMIG6iJb{TjVZK6ItvD{i{^_hI=XD$r3BY{0UWtNhv zoYZC+$%}BlIE(2!Y(jsAxiGka`^P?YIk{`FWV&3wc2JiYh~;)W6$aWsa)s&n@#|pp zXv3=VHsY?d0v#b_**JU&nLrs(McKOF@ryiA0=D&i*dV+%Ow{?g;j?we^{eu5SGlY2A?V$*Q z{~OIf+d?z+{|A}@>mk;CBe+w$;5+CSYT3O#56UMWr@$pp>IuZ>=;kOlR48%!qel+k zM)xK=B7z7r2dL>8!Tqkqy?}DS5aC?JJ&(8%I`FEDJuWFGvz8MrujFa7-M%E`7JEVQ zPbBe0|Fb^{4P-!QDF5D&*meOVFoF_lukhqyZ_@(gK-%QDsRI5d*iVpV+4vH}91?d6b8uQL?p|Ue4TNO7~Rh^(L@-tIzWV1>I%E~RwRZuHy z{SRb7YIxx4XBJ>Y0d^!+s`2k;Al|3<+WhrYMyP$PPxjK?yHcCW?nwd-PvSqoY({o=*H{ zz{9PP1ZnZx+@s7RHxQ7?l?NjjhpU?MCo;U?p9-^^y((K8j-4-fuCVfrS4(S{QwObZ zu9#j_*e=b?XA`eg>~AC6rYek8Y_bA|e?B_M6wB$OWQ4}EU(iQs$?o?cs$xU$|6h;> zA^nZp3B=~H_6_{Qz2mgG!+G{whz9@EQ9W~;TRzv~4%uDl{F(Kspz*Dc{;ueHTXgPm zQUYfFLpRm zyt_Wt2Hv<8PldBx|1QyJXY~1Nojo4jQ`3;PXN3!o)8LKe&ausz0E9pZ*y?y_{Ilah z@b8X?imi?Z9|s$|+QAZZTXTewsI1vF4Lr_Ubh4-CLtl!<=--HjZeUM!Vu$@VqJd>a zX@F!#Tzsirf3pdl4Dd=|uF!Oh21$x3qJXRh1eeEnmtD-EuR=9CIdbJa{ec0e;7O<5 z+9koJYzr+DcW6-h|7>~)-fDWlGj7IiH9Zsur|=j4qv=7oC&W#4z9629ap3QLKeu9| zt);s#O18=)ABrpJncvCe6&6` zxcG(&tWn*Ry`yN-2s(8Hqjah}$!dr{Ohn?*MlBuSB<*jtd&3nO+nYwTf^$`{x{tq} zH~0G^5O+GCYJ?M2gpX<^70i@Jc!SZl7GHaPr!zaiGhlP@zMA#L#vS90nxXxC-6%E$ zF?G3E$mD$pyK1+Ck4C<=hahBH+LV}w=}{?2#GG}4DiXZ&u!A z&Ehz=BA?nLE8f7&a1h~g#|#-3M^vm`FmGnvPnrWWs&hhp4@utrcsXn&q`I_6H?%MY z$%Q16qLz_kc=>ht_z?z{C+|HQwtMBMrxJtmDo)or$>d2ciA(YM;(c&<%J`_AFPVu zndnuPE+HW?@O-X7v1rw1Pr{`K?4WrtutmzpsAAspxaCp08C>3^ON47?96m?u$9}ER zssD@;&nPsba1kE8grKzkYto@#bjNDeY3Yc!H<-l0Tvm5+E_WWs>RRbPR=o#L`_!f; z9;+(xVlVEKuSGJhxs6$`W=`e`vDOLmltEbJJpg48&h5c1-rF9i{_?K4FMX?O&PQ+}(-q+KVF&Kg!Reb1;Mtz~YGmZn@}`0TJG_|A_iXrtISfCGOO)ilvS2=zso&ODGD~ zrYK77B$?f}-De)t%(p-dNRQvbejt3G0$iEj=YGSB$50qw{^IVjJomj4l#URwgr4E- zl)zbMB;`>ycS@QsDrUGbt14gL^s%A!J86v#6P@K(JT}Vj=mr_&kO2Ik5kBk2brb&y zYXC%FiLui|MZ;a)yPB!Y;R2}gU(ttI!M|1pZ5D$xyv$qBm!QaXK2I-l(Hym@x*4al zl0X4I$j1Sv^0V)cW(SnUnq+VvU^8%uW_Zm6L^Dx1wlO9nI>4)^395t@oNvjOrthT} zEDR=Liv+^qS@Ky`Bkn6W@tlJSjoSm^d5s)O-WJuMT+qMIIk1gXjMUiZq#(iBalk;gA$v}-=yqeXjreJsZ%f?Plk=fE|fAM;D`ND-;W)Qc_cFcNqg<(DvLN8T%KbrhV9$3t+2!j zfz5^lE_~IYl%U0;UNzm><|Fhj; z2DCfiPlQBtr&r%xy`IHin6_1Z6a7afJSs3}n@!$vgWtRd=Zdht_cgz2LC3qB(`K-h zKNm8+P5LJdeTMx!ke8Ht!HiXM8f`mKkIkpG^#%LkAdiAS(5^%0iO|%ioDxq~i4<5H z(yQ+KR7#bW6Myjgp0;3&dkS`oeChdr6YdmNKYnpySNGy%W{C&%eBG?zT^{MAY|HI`8AMrNc z>c*ym^L6H3`R17s%EJ-N$a*sk*V5^$jWJO0F<_B8V;;V0s0rK*PjC1#}?VW=AtNC^beaDBqxCW%mxB{Ntm zIR*C#pTDJh*T@|QGW>Q^Cx@nGStRP0N7x4=k7u6y$~=3p+Z4^7QXNzuyXyxY8PwUf zbBCHneMO?4;N6$hot=|Q0TX`t)V+>J#lg%h={*n;)F{n`D}pzmne_r1HG701p9{VX2lI_UukLGC^Z zJO^v(er{pXubA5L20H4?c-2AH3Tuub8|>$*@s%9ouF+l8hx%$fO1KoEf@yj+;{$72 zDNDu&s>Vt##tz`=RvdB^Dv;O~3Ni(37D6Mo8qB;ikL61JPWs|p(&Y6^&*2MDm*@FS zet*lV#K&!W672nK+DMkUmQEy{-u(2mjw25l$*R-!uy?1rF0lX3vw)ftj!ppsN8QGF zxhPivug%z=QX0NSJL*R56@f#bR=$xL@0B#@_JY2NKA1fwPvdT4!*@G$^$Cjz-P#k8ZVGRbp1g|2Jh9D zDnm2d79_G7gRBR+(rc-^o@}gY=B!&L#raR5`nzn`UlchG#I1d(o+s1R`3qQL3fJg; z&js?9li#OqyyejjBK3#9g=8~O^UyfF10xy}a^sAKdVM>iEo4@c3(sTBrG44+4qlue zByZ1~cGb{bPmYGSWXX*NZ6R41q&AWx@5wFPmn#)Ve0ghi+|yRHw6w-6n+>&Z5I<^e zN9jF}G(X~Q%YIpG73W@7;Z)v0Q+~5P9m%zl_Ovuh{y*^}z!QX~1k~%BOF(>lWYylW zI%mU)oW`k2!L5KAIA7B^Pw4##{;!Z3QPxzAy!ZXJ{*(RcjjLpJ*_EV~3%JnuKgE68+%TP&{h*eDm-PD<5!`{9O%3 zSAuo0>sOg!j0(3j$V?{{1OckCH6BR(a39=|NNjre{?^Gr+QOOKf(F)9APgbja7>f6 z3F6)lBKVoWpA>(2Doz{&iR40wv(pG&=~U$3igU|SCE4?h{Vm55Ic13G(i5N1G4px)Zf&!f>D?( ztxRh&H?|a4&~zI)3Y@W%%gr9T2%WXJc@Mb9NhC`ImMJHu(poo0U&&u)&{&ASQ9dcw zn>7V?*S0@IDInqL0E5>)5I1Chc5?sOQ~OFD6uuxVpV@8pu-mC-s~xTvqiy7K?kme{{ewWyULgS1%W8+Ctq~kfY) zNa7te&Km|_m-5bxJy)^6`_dvJXLcOaS-$(6gAUQ6q*oLe?_VZZGBG;n{uVv(M#G=e<#Z4A=#D-ci!#F!ARayQXjlxY_zS6ozR0 zeEUE!v`FpqE=u=jsj1e#Fd=SLwyGZu7$ctw>9&LVz_lP_fUTd;Wd2TfOo;T_9#)kP z>S$>!(ttDEI4k|WZ{ry#o=DA+=(f;iyoZss`uyPUxL605QvG;W-{=)(mY39@1}YyU zc<}`hUP(WTm@XE4%`Lw;;osC@=_Q)Izx?y^7bxx1+@fV{-UBlZLd}V0NYcb6QMasi z?%s&ZJI-S>|M|-$d+NUDM(W>hu(!9DZVWqaJwGgFh2XZT5h_ouw>2I^2w=?N)E6KVuIn;n(orLd-;F#P0X~4@qDW>$Dt?hQfm4iSX1%?&ByOr*5;qR?ZWjzl zg@l;Y14#uL0n>Oos!I%O2Ex+6w+ur-Tb$9=d1s8-V0ek9wPFGutObCj0K3lu6wA{w zwk`Zx_4){3md97*t)zSz_U1@sjO6DMgTT^HJsK}2BqkZFuI|?zeW)&mcnHKbn+^53 zKp%(+v?Q-U%Q_?knIYu*mQlB{Jz)F)xoJUpML!m~nFs^ffUa*942>VEqWo66*wAh<9EcnI2?Z5mAz5loV2jo`&1MI*0A4)<0gUw(4 z4-w~WunqJb@vlG%*SVGv2467BB!&RaLr73w&JU3{n~uD2q8{cKHSyb?(K8k*IT(9= zDX1c^1qsUqRdOa)R5lxg+SBs1`gd&?)j^5hJ?$*&!<8K6mk?e=+a3?pz4$NTdraAd z@u${FA^uOwW_^n0BFy1P(hBPz7lbEszT6(;dGpreOzBXBZ~1(dF2}-w`l=2K2Gu4l z9w7hTxA8`@ug>#mdSX)PYcmu3n6*yAe5zJjNT=&IG$_p|Fm(V!Jvc7HM4)}L<``e> zmuBT#A^@3^#5DXjNS&PW*3`fgT;DIionRS3p4f7?zZ<<}cU80cjV7TM_Q%dTsCN9m z0Cjlozha8p@%_bqk)Z^?G5!Pj4`5bJ*%He)bsr6AAGPYfai+s|`i?l=x)qFK(t)Vh zthp3cvFBOmL-h#1{u*hpvgpO=AY$vs%&i|ErpSK6Xq!Q874;wk%oF8u-Plu}yq5%F z&3vavHZC<8JzYe;;%0li!JU2DB`R~8F!Lx?cJM4e!~#Cp+3Q5{AztvM+uh;>XRiQ> zDE>3}9*-Qfo~f~&`%TN9gM0Mb)xe9&!7vL4dWno@i(Tu z@NrGma=2@OtJrMR(*AW@+X`D?iy#*?l5TTLoHwwjRMX6=Hy2-Z#kz=l&(I18{QLsg zn`x7^7t6zXCtQ95%3**Bc0B>28W#%UmVe1TPN5#>v8wJpFXqVJinZpqynlLPu_g61 zJ#b><`cx~%g7t@1bLczqZuFdXFYdj0j_Nv6#^blJ>TU}gXoPE? z!ds=+QoG>L)jfRc<&?C5o3R-t72aN_%L5|vhQA-1(18yegbL$|vy2w@rR$inbxtzEoFfJEm-qOqx)($ZFLls)}`7!KmqDj{oN&-XPp|RC0QQ(9>e&5Ah^u#M+w!8?_CG|6R0cz0A`vpl>3z9S^Ju^;r;vs!Y z<)5I3tS!*PBqskw+BCITZ^qSPan0Id@;YKf_4P9OUn8G8sV91!cd3eAC@+{_#j2>R zbDp#b8w0@gH_~_Ex~ojc`(RI!R9~36w0UrZkMzqovS`B>%#}7i1+T`&n9VUd4Z=|m z-;jqdMBT}7hawBFEQ&pFx?UbS5T3XHsb0rYB$?yJ2bTB2V|d}{NDJQ7;1=V-Yy~hLkbv<}V=@+^I#*uwRA@K7K7$)< zF^RI&d?mk(@+F=!<$@FBPTxqKQyzH&79ZFBnpHSZHokwlQK8d)dEB0HO1F0Ms=uUR z@q#l2s(R?XX>xuA6jTgBNp_-g>VfzhO~tQ$M(J5EYviR3F{5`nY^;j|P$>H6dziwp@$CT6la6Ljt9lbah^J<8Gc0)R5Juw!jOKZ6V*JZ36}2S$md}k>~fx zQze9AWIET|;#|51N70=RWxc+s+v@*x4zrH0>+Wg!!?df!m2dYI5e#m+YECjf`^94_ z54vStmM8hE4Wjc`F^j{tvK!6_3!60{C>i(dR0a(<%cuCs*@^l}C*iZd@ZkY0nj2hE`oCc1fU&Yqdn z<+|u#0}Ofvu!&nqG`e@C-42FGe&uk@g7>rj1%b-MlFM_LdC+C8CWIY(VPF$LLi^A9 z^v9}SHkmFYZ$etj|2iZG$gCys>HhYM4#}F&2l2Ux)N>_z_h=DiBXh zYpD+BJc@tfm1hM4p@1_T5uWKznbVn~`a2vvHTpHgT)z#O*%y8Of9a4?J zopQ^ta1e|e{a-m&V*$OOj_khg*Gh*GRvv1ih7Za zQ{5UZb}Cn5!v*DaCIF9t=RL_f;>(@JO+1QTeC%~B-a|*N+r?9r43x{eot4k#8Zu5a zesGBTf!Xc0OIN!+`0MCN5i7g0ev%=6$ZLzA-gqSsT(JI= zzpymm6EL|JgQcSh(jp++HO8uGB=fVY zRzQyUvEqpNJHYu#}o&!5hGlJVdd&C9u_6&GuJ-RLY z!?U6J`#QCw3D9g{{;TF~gX`xdpGIEu#DKWp+S~Q7IqS)*I}3{!ZUW!iR+SmUB%l_+^Ql*4k_b!frE8s?UOp75so+9^DbERCT= z6HCXop=xI3nu)%?01?$%*rLUAbU6yk34V(q2ky5duxw&$YQ;*(K$r-=ODiugk zXWn7TwrkJB|GX;rF<`$LG72Q>P$R`k`__Jwmokg!9Tji%-t2{fQ|DoEqIK88R47u3SV=X*l%im5VmaJu*N=@VkO{ zshgTRl?Sz!k|T8(qAPFfX#4D@&CpNAvRxi%y-_&)0M9e${jesY&l4PQnk@tW;(9XF zZmn%yi7RDgX3UpV4T~z$gPeKzUMs=GC13vk4>=9qa>A}uN5z&uvV`%^Uuu@3aj5Yk ztnGueX;*X}l(yr_)SH>H+kI$T0=KKsUF;TSF;O)xK>pCxXHZ;6khg-8yP1|Q*1P#R zTrGCMUQVY#(*EBhGXU>&=o|nuFirs~1MA)W2;V?zF`G1^6d1~UZ~7PITe{d?$gq`J%<|Dq8fR0$ov39v`r| zX4o@XJ_)x!3PqTHH|o1gg3L@k0bk(e^4si4p*utJDh;q1s?vGSmVx0f&g%M%4BaIk0;>Md-= z(WD>d_~rrTA&F3f->MYAZOMxMTz~lnRhDv zjT(|NEh^ug&LDsD<|}xKlzin;T4emyFyX&kq2RxhHB63u;cm7NS|O2P2|-O9GtPn8 zoe^^;5f8d=pD7G(>fLVQN{Vj)sAn-;J%@}x4CjHXp31c+r95v% z?2R01G~@0u_gwqE{}OZVe91n~YveA*lAz};mU_hO1uMuF8DHty~;C*VI;}>CCC_gcVhb&J}}}0-Nfc) z29Ri$ye9JcRtqLgo!DS7-2O4JWjlG>sE;bq<55)5_Y7_m4CO{znsqjXsg{R})1_CTOCF?~n_UB?AK_U~kx% z)oESX6aSUYQX~fd-WvLSoV$Y5zVhRyO(k;%IGirz+Q}cWV9S`z882?^0OWf=D^0^k zq8GpJd1%1T?J}Bpb5SdPOQ@dpD%%|Wjf>sBV6Tw133XZN5M3iP+=OQlnAX3!oI+mR zgZA!p)#GGJ($RhUjgOD_ra4$=z(rry%$(i^$TME<)Wa*0ZF>dM0-Jv&C7P74ftb@# zi%_AXZez;g`g8j_R49C+8ql*^6^G;YzAVFRAKN43EA2> zbazSyH#cMw_aSmXc_pCdUBC&8XDm?KtlTKo2_051jvOv*D|b9=Ki?d4zFc40#OLd-Us~jA1PQE9 z@s&fRY6o2WgDn-5B6uC&a7fOz+ca-H#E;j!kIi81Z1g731kNWV=^^Zw-c=}Mq`dpP zU76(83a^%sA)5TkOOItOh)H7^Jyl;pW@j5=3oP=WJ~Ogd+(UThTxEA*+SI2a!9SHd z^PtS>3?I(U{NbpcG|zzrax}zG+ZhJQ4_Tb=t1MWGl>Xxd1mvh!>=oYQCwo+CZ)n_1 zy6kh@fV#6if0-pPobOJK?Dj^4M4-HKYHfXJD_`g+VaC_G&za*r86j0O1y+q^oFzpT zzh!1$qjzOs0}E^Pdg9m2{;$WrPhti`D!x#-Bj&qP*bZ*HstbHE(CA+Xyx*-p(6eUd zz4RK)Qxx~jy39pp=d85QhKeygAei(EK7NH=!SgrZdZTm9%X38%`4jy-Q_6hZ$Hr(1 zo-yhC-5hPGsK2--hQqU4!*Y*2G!P)^xvk{|1UA?_^>6 z!t9SNQs2tygy4(^*d>(fE@qK5VzxQV*p=g)W@G~>mrePUNqq8KQoEL#B83pf%v>;AcZqsw@o>axp|BTQJOej)vWau zA~#pJB-}oLf(ip(3gwv}%^*3<+Ts`c?FmA#(wD8eC7jMhzt=)LRx;Z)Kst+2jYg9Z z3LF-mD6Ncfe``3%MTwn9sEmm;UTyOH{jn#fZgPn@7q5%&a-Rr$$&)7{huY1=&ZI$7Fa za$9#sU6{2~WTB@mzZkOqYH5^T@DdWWX~V}~rU;PPB+~1AxtYDyn?# zQ2~>C#&`HVZ>@tMjD>KyiYv{gWWjVS34Jw|qb?aq&J%#SXMTMb!^gdDgn8T9tg9@?svug_9?wc7GZs<^}e#Kh{hF+SAo<21;cT zJ@EKr5TnSpS=SJD2jka}A$`7>&g5A-Yk+VO|9uMteC{K+z-04RyXQk%0e_AjMa3Hw)?jMt-*eajLHAp12Q|0^;;~zJt=wCtzG6b;c1VM=bW4^kI!+s zhX8SS(cmL#-KC=-qqkoRSSN-+;)aFUJZ_Vs*ptS({j^=|0kk0!W5oS~q+h`OKlDem zZ4C|FW{%8Wrr*GPq5dxSTf0*3iRka--OpajkYz!ipxvGK$-!JIIob;-*agB!O41eu zY5_0}jQ&k)Sn#}4dM*0`M1{?RZreWrat|~3k*pSu5r1cYGVbZ5Ov@ov_}Sj z2o}Qzvw97fgPL-x*uW%Rs|zqs$2S>vC61Hp;{h=-=#(t!bODfAI;JVL5{@I}b2M=s zD`Re|nR1m7vB?%^QPKBb`x#2V?(DS24L!&Qo4|yQmBoPlWAq!@G@~Nk zC=EhNeZu>yB%;}Y6H+8|*X`OhY1Je>+PF6YQbrEmF+^w>7naNfOnbfZ?>`_*G8>un zuoVXKBS#H58^Y{`Uqde4{BAUZdV;@!emWuf+`=@n3ODLPhT+$L%=_2TRMcF^D~RTI z&lq7Y)XcUdHXNlr?Q9sk7Bcks`VTP~*(h#31=ILMfa(n1oRGe5JQU}?kF`s@XtuQD zo}jQu-vl6Mrz`fMBM<|Ydrjhlx_8BDjVcE9M z!U&_dLin5xsy)W<%gOH%pZ%DSE`I+zxACQa!6U`2J9tWz(#|h(m8y&MJjw|HUcUj^ zp!98UsrwjxNGAAIw>_j2m$&Z(ujdM=0C|0X;;{SfVkp4s(?X9eZJ1>2ojKkleLbvq z{mA4s|C2pUfaG9j^>31cDMwPB8ngJunhzEWqN`D}nP8n_)OT7DZCyh>ws|rekt&>8 z00l@ZB)#p3H94?`<#A)$ZGMqWTm9ZZuibMZU`Kqs*6P?dCL7TrgR};xjrwSDK*%Eh z@z6Ek>bi3IL&@Lyq3vsv0OC-@7lCr`Zb#sT}!tT4n2dWxR9MPiG zc=cJ!okHVoDARJ*|FQ1~r`W@%nHy^YBCOI*bV4LUVn?KP8N8^<5c!O{o3IB=(hQg< zeF{iXB<&rc*9)91vEKNd@R4p=Y(FGU_z1h43o0?x|7nUynj`sDQ_=kqsf|%4^ao3A z^{dezwkfY3QuKc;7*PAhI-+5`#q`=FK#ZnNW3Bb*jRL~>Hi#j`C2EGa1?&|(lhAVS zr3ni`>P=zi4_7xD5(}2%L_O}KlfMF(!x-wGWf{jHHy|;4VXC}nqmw`jL|_}2fhhvy zwrPap#c|IL`8n(EiuB^T)%6>Zv5ZxPCl-cQ7$ra)^WCAb;=^>83O#B`0T4m##_`_Ilwqw9_Uz&H>nA8eBp!*?p8kovvQ~G z&D~(uv3n(!S5N$kVWGZ?NmtO~yJ`qsP6tX)e#YE6Z}p_1>DLRsjHBLD<(<1VLFhq9 z$@(YYbfNJR4f@A}Vc7l!aSQe~Wpn0HIa8~3{4x-_rS=pPk@1Qx;d-KEbRQz*ivY>> zsY>5rJ(C#H^v3Q7*V}Oqg)ajd##Wnz0bh=Rq6}VfgdfEv8UM9QYD&J9Lm#VRR?;2W zj56&(9!>=akF93u$VpT!bicYns-MpMyVV2!k-V0vCm-#;l=|pNY_*%Oy?ih8pVZ@c zsAy>2uE?TETX2$hXNBIPyt2LyY!ZV9_)>}7iT>_PUx0$R?LZF3&u6~A{pVD{fT+o&O_M)e`I=BxQCF%^ zG&NPnPC;RuWc+PqL>vX=Sz7c+w>v~_WS8miyth8~eTd%DCr$_cicIBkCC`!3i zoNT>SGmvsa`AGVww@jC)O5ilXF1W7mspv5f@=gL{d!crEqf-LdX>URGEf#eLKhLrjc+&p2ngVc%HZGMXJ2|2AwN;86BiXM_Ci zY-F*Nl6B>xk*TAZxkZRb?TL&nDFf2AytlHuWlKqpcdxc1N1$`} zBV7i3wHKp2z1N#rvvCtuKy4J^RaUYP9xo4{#|#7PRe+a=zH(2wT6&3G2r{G8;Yj8_ z*qRjglZ}repg;;DG^LCK2c!XRvGfqHk|yS_BPBV~K1o51F(Wg&+WS%kL5v8w!RzwH zUjXMI&7WYIZwyklU<5W$;o);k%JoY{h84;wkn+9vw9Uf6=|M9oFV%mY+eFcB^Ekog10 zKzP|{yA(cpz<#MmEVC5-T?Y4DLmBi^M`i@(_+^*vZ7$svM#H;qU<(c!BC~tffNVO8A|vZGaln2kcRMSI3P5Y=y|Vuri|?n7r$>Z=kCtP z+<9qPdqDn;W>NNyi~^XtwWjvueN)(FAMloN1tmQ7bfOS~Jun+T;pqo6l_^YhRD%KD zTvv4P^3H9vh`yO(5}e;^`%<#IU2{EEne$3SUjv|i`7#h zfokveM$sFnCK~?wF4GmEIJGe6fc3j@F{I%$Lc`s~u-q<_FYas4`*XyA#^YqwHxQ<# z3Nnn354l~SmLZTvNV;yq%TCP|U|?!!3N11}Q+J{r(RXb*YxqLlQ@z;uUh{{4wAAWG z@$!p3Kq~1VmR$Bu>)~Ka5l?Kmc#sxfu*&$61u2x0ObpzJ|6UhZ^+&C=b+J%Cq3k;nSZ6rCzlPJ}8|-4B zm5~nSpQ)l24G5!y1|n_4r{5M{&x=Z%7*9LEsp;9DDf0k@$voO4Zvh^PBpsT5U5XAQ zJ0oloe8jx^B1Jv_tf9s9-F!R4G3eDY0e!!usEw+`HGG7IMLXs2uVE2EMMS?Vs%6Z0 zX5gMxv_Ly>>@J{jNeD048dijT^Plf7tN4`v)(J(ZnM@xeRvxo@*ITd1=^*$=f`(R_ zKHD)+9J@Qm8M&25&(2gsxP7r5{X2gXeDQM=$kDu>h^^uQH^8b_nl3zTdvEJ;9 zV;oJ3&xZnxnt{8wFdlh);o!F|zQ3ue1gik5K6(Q24606a;+Z|plx5tk;*Z6PUP)PT zsu8)whl-qiIWnPG-u4vItLL56+xa?^%{>1spNd|)h)4m@5tt6TxtUAzv|@rlgV?K^ zpkghaID&mPe_WCXJgm|DTXJULDrozNy3hJ|1JAJw@BK&CH3!nB+7mcxw%(p0Kqs!Zy4s|0rkf!Nns+A_E$7#?sSB_Ov%+ z{_eO|Tz#P6vS(D3Grddi3B@cflPvD4BLg@OZG+jq?%rbuIMhC7sL_)%tcX*NRE@ZV zm_8Y&jT$0ZV<_hwu>8d^9sDB&Y)~3o-QLH z@zk2q)LMmLvrK@s$2{SaLXJjw58rf1&mdjn0W;)VrUa72H-XvCVjvk-|EXjii-Je@ zDeMj7`zmxRX&D`#+VvIAR0(AfN6hIT=$+Ush}N$75!|>uPpmm0jq0~nISG6~?TKmg z9TBm^1KjDEp3OB2nX?%@GWb!QJUoNCdY*lKUDPPNPwn0QZS@i)l4Tp2ov~-&9+{n= zlp2H4I}R={YBmAYkQ?^|%!P^o1jb$21Q=Gt?k+Tq6d5 zOE^6_dyW?|J%H*;ZdBjCDUb;{>Yl(wB_VtU(Q>la)@jJtU?Rf9@Gt4cAw$02Mv3_W zZ5I081x01;bTiOwUq#!qG&&G{p1l#PL|VKNn|hM-@pnCbJG$ZwXm;TA6G;x=8VrI4 z8srIQx@N5rCQeGt)Aue0rYCQwsQV1Z>G7{dB;Hn4WB^rT@n8hV2-vb)6?zfr8c?#& zTI+?3(}(^EYxF&^CqNV=D;fZqvI?irGxeeFh1%3@4~hZhsxPL|CAvXtn$gRrq$hJd zznLBYV026SS90cyz5dl#`^%kG3owNXcWATlTKuE)rV_aKur0dWC2+0x(92euS5COt=vC44g!p^(BpXsyggNxQ92 z8eb%M*X*Ea)jFPHHP0Ng5AQp1q8_U_EG?HNo9f>E12)YiJ_8XYt>gs(EXF z^!E7lg+G4JzY!E>L~}2hec%2NM}J|Z71!_z-h8ikYWAxG+KLngpvxF*KT!38gA{%) zD~hVMYBTc`7f9&EsacL>7Y=)Nt*S|Ir8Krv2PkBBv-M#QK=ck|K-k^her!rH`62mi5d8)75L9%+igPp>H*3&%7|^!hBuve6;1+DviA0A_ zdm&{S>Yh2aPwEZe&DHCR_;(aW)jo~k@opKedfQ{XD1-Jx_4pqJjJjKU!dH+(rMR0v z8dpg^P{J&iH0$Z6qqWJ(&}Eaq%sSpj(-@2X7nIJ4ZP4+xNrp6$GN%=m=Q{xnEcxIz#3<0g4GRfLVfxQD0LnzLC7iqj*& zs?nn03^d^B3d$ha7@#xS*^AywJC2oNP9Chqii-c$Mh=sbLJadFK~*eKsO;*gaN0Z{2hK zU%^pV+>Q`uIPw42L1!w7bthf=XG9-FbtP(TQR;(~a3tM^6+aefU=;*)V^m{k5;Y zX0wUN**7J>$m~F%eM_iot)l}dV5X5EeKD_1+LbVzP2JRS0T&XoM}AN@a9-+YVzzc- z;gM5R(F}*NJ>EojatD)jIn~&3CHaDx0x1iw9t#P0qg9hwQkUh)iP}zCW5lC_wlsVc z24=N>RPPTlSlRgr1LNrjSB+$qDQ^d2cJ9kf`<)Krc$QO`IlxFR%bo{YGBHAcP?c?u z>2ZLU$XIKt^*`nO_`nznMjKHu9Y=NtU|v?$PMUoWj5~KrrPsD*wp68OxW>fH)+ws) za>B;Xaa3~WrzU)fvXfxRA&%yvV8prt+P;>Bi33i3`Nd{fXZodm&cx}HA>@3zFb8)C z)h~ppls%lekK6ctH`CG@Iy?NGJ?^FzV1mHvoYBiU6!Bn!^t=gGXO1?^%#f`wsJVYr z517-}1JU3zUD6c<8pn()aWOkVl2pOD#-)>HI}aL$|D>zKH;P>sx_p682hsm^(G{ie zXj$lm-5)H(tXT)rZe}$8xh~w{o!*M8?4A173yqlduiBYr@A3!R$lnyv+Re3aEPH%k zv*MC3KP+eKo?8Qf2*(BX`J%n5cH;|(YMp4CrH9Q?N8IUagGHX3KFZ2kvwb`=U$OBl zzKp8A`AU46B5N%X}XtD%1o6F~VFKumBfURpZ=&l41?ewq`ky)2dcDLROm7Q0cM`-lm^ zx1t#N*S5&&R}TuLbf-~d;RMOTzgdrUlV|TSsD81)i794h-+-L#c49nL}oMaRf_8Dv+vmNy#6Rr;wh>k>mT-wT;k0Rf2kf(yomCi zeb0CkcX|~UW~>KrAyokBY_yq+%0HNiu&1}3Ts!6k^uG%E$I{?66)@wOec>ZR$e#OfP;TzL_c#(I%)n_C*z=(m3p=YK6SLfd%Xy`5nlIFc> zuOz0+V)dnBy?l^tx%YySTGjc8 zM-Lqvh97}qz7hz#DE*7-LEN@R6Y<*vG{=(@T_yd4;wEIi0-%K8tgSMqQ-vW>US&Sij<2pb>-SB>q{?oT`~^1k8z@B@>eADs!~mw;pUea!raCVsfA4x zp#V&***1srOa0$ZB~RYHimfO_rX8@}amCk|LCK*WMV-m0%~2(A8ClBtY*a*j!f|>= zi>#iJmhA+N?oE0`KWbw`plBSc7r|1H6~F))gw(x-8`9$oTTi{4dm3g&VdXOxBX4T) z66>nZ)ZFJ>K55Ic8yC(MI%7b+uSH$y$+We22(AEHI6oMsz8MSK%7J{f5`{<(f17+a z&|2%@xqNkAxMzkKX4oVh>Y+aBbt+~3l_#B(0mp-RM&5CB(E8itRI`3$yCfh}LrTjL zpioUDN5dsHmu$)%EXH_BglKf6`S=1^!{8T4zm1Gp#6kWjTO57hF zTGLnt{;OmEZrVkil}!HgQ@@8=+!^aVC<4#D!C=zm9IHJ!v!!4g5(e2J2xJ7$JgQ%r zDwQ!ICs1luK|1pH>v15os1l7s z`GgD*;Q+!Ymq?PF(r;R6TK$1|RlWB(?~OSexNR`9Hv%Y2G3+dRGJEd430ZEd47K_r=?KDfFuA_-W zbm-un15j~dNq@Y$6GVx}>HWRLYg*4LH5;h=KMxy3sP`5L4m^|0MCS5Q2Hk(fKF`|p zpZ`Qm$)=y0sTJ+c^h`CTQN-LiNl{2LvQFrKN{F1&H@Nf5e3$xt|@%US{0T zYjJeN9JN>Jd82CNqP+Zb#I6=plG#}6jeU%|yXG>0TFozV?zAqstEwa`v*H0T$*kE1 zin)ed6V3pz{YSyP=r(X<4$_SQAc)lVzbm_?1*vuEYzOA=k4%DQoD_vM`>x^de$nn1 zRnG1?V}9sO*e|T${+3x_77J9hbuVyFUs7UXZoxqe;E>^YnP%#<=VGJ%kV zBN+%;@EM&@*A6$6fJ*KyH;an8uBqF4jbn&^O$3!ezBJ%mrjFsZUX$JK2YgUOR~L69 zOg8xDxF}w=k!ff2s9 zr#Lh8CHZIgPe1n|n`@RfLO+Bo{+aK~t!xC~6s4X^cK|p=I#_NH*mt{x<<_xzI%&p42fSSZ>;FQ@%%=ozX zwkfv0DM0s+i^J}bpCI4PP5p?U-UJ4PuB%ORlaXmue8%byCyyq_H!Hp|kof#iZ z6YHkzmJ_c=zCtHZwFloc_C*XLDv)JVu3!Ba$fBmayZ_G`?800uXT~>%r94K=>nG)=^~9iI!u(fH4l_NC{tkH zNZvFk6Pvi;lc(IkUL|?$t?PiCQwS#xZ z2lGpcvKHGgjEq096Qd5U$yshdz)E5CtV8*z!@o{n-Z^shNVd?YuVOXMA?2ue&K1@g zp{Sw=K7#6>kDiQKbB-E7ff4<`(;u2G`DW^;`$qwH$GF@7=TQ$DFMcqz@7(hi_J5%i z=6dqome|do{tKn>DL(*+;`M%hMSRJ|J9r5H7HWi->z7>`=p;h|JCt?<6lQ7VzCiUs2+&*M zR(!ES^bC)twS`#l{B^_8?ubOgmi7oy8t0s`hEdKBE^>gZd5GZQ4qavv7^KGqw zvV1*e^e?u}P&FZnUGGvm~<7id&W`ow#Pr4reBx-u_j`CDQ5*>=8N2UOgi$|O8-5l2!>x~0DCznf@#M*5BHf?bEBxERb%e%Rpl?W7jIyP#p3 zwzay|DoWV%!~uq1Y2JRvjri@9W{s+M$`+`M%-H!ulLH5DOO$1_l${bmvS3Klm;fLt zP}^j}k&O=N)f4?M+s}0(Xis>K&o-kKZB)=%)2^-(qZ03`E#1DT^*Vx>sxXe5wbo|6WuKz3VJN zrIuk~O#{H@=Xi4Mog;DDk^mD9_DCLME_!??5!vtJ3-OeBklDu*j>_lCm#xHI$vBZs zkWE6&vxkaKC5K7I=ZR6X&Bg$U!gVb_ILA^~1gPraLrcYc?8gr|yF6K5g8G(U|IE+< zahK4{*$b*|p55neS(X5DtZ|d*w6IjLb2Grf{!>BJB4!V8ZzT$&hD#)RN{4V<14R|R z)ibz}wTQp0$q(I{S1cbbj~?8we2ZEK9IFQ zKLy;$Cfvcd`&o-u?L!E2@@(HcGAj6ZaZ6qK`uU>6Wd(Ny_g)@#I?$N4lEVOL@UEvY zCn8t#gp7D`eW?%p(ex$3Wvbt9Zb3)xe1yc`Fv4P9LKZn?D00CCT@#U0I~_#)HV5Cb z&6$6%=PB>m+xch%8Htau`tOo^ ztYi`e1>neK9i!MoS;%`%Rh!YN#2dq@Kd(*PxP{CULeod2P1T>09krO(WBcR?_~w9) zT1A`R{*#tjr4hC3(~T3n$ZTMzmQ+PUjLF|o?^8M^`hO!v7zmQ{5+h2ha2c#5tL=8H?K@QG*vf5B<`~l)(qdnP zZQyUO&9o2SaD#m#j!hg=1UN&8ITm;AZIYoZQ{*e2Ak%LEM`W^zaa}D?kd==lL z{#$IcJb%v`n3CnH;DDe-vNo*!a7tRsUr+tl6z>_kHOEOaw_800W1}r2gGL0B?5qoZ z()%GU){e51irX1cB^kFeG;kyb z9qzZ3`RU%Tbyh#-y|q^IH-aV@s`cHkTQ!+_-8#Yj_rfP`U&I$XPxZ>oJg8%c&?WE4 zg(pxxL1VGwv9<|N@1kl?-10SiVkp58Nd8}u=Bu1LL+DuJg;yTs20`;VPVIn&2ZkBo z+%v84t6hI_KzFPSs}efh7%_eaJaM`?N=ep%(B%$aJw3Pr4*YAGK_?f!@1&Lh*eUbh6@D}XkJO18f*)O+piarvB<${Fsrx(e{BwnQ7- z@En_4xY-UI0Wv6@MCvzVmj9_h?g{tV*Z!X$1MB?A z^-W%{4bjisiJ@!5p`2Ck+cQ>-+8UdReX}hH-n%M?Y}rRI0-9bt0Q$bhGd1UzgI2sf zc*w>BH~~tP10HUO#MTV2?oTkV7oMFv!L}@PQWGF59@O*jw@np zD~o@aERI~i^Qyk=yA$A``3WZXX}?lHSHS%&LJ}rSZ$lI*b9P$GWWNL^nxW;uoo_I~ z8p^Tkj6uzUa?=Z*kZ%ls7&kJq4?Y#Lb_mQrrY&x8u?ONSeF>DDsL~ndP;E;j(4aK8 z%G_Zy{>On2ivFJ$C`FUOocK zK7fb_<8&QSb2LlbrYsz#9h zbi{_x@YFsgG?MynVX#>$=QOgoJv)Ona?wTdEII?i?yI+6CRQ310agwC z=Trx2;!bzi(`VqVq6v*Hbt@kb7!_jXk=XmYB!}njCd_+WSpLkO5JlEgHah>b=1Hig zpD$3y&0)+-mBWi)3Ath9Arv_YQRtRDsET3J?IU^*hM{VW&_GSdN(4cK)|n&kC{gTl z8hWJ4D1;s-=uP(Gk2hcf^AdYFH^-B&cmy^aI+uSCjI;)!vGLYTjE^N`@!*R?C^G-t z4U)@bMKe6BEng`Ek&;HLS|6R2-fJRMUs_PwJ@+|QFjKvrGu1{nG+B9tUG@yI1x{fl z6juo0F$4;CeHvtet#*yre_%HNNvJm~$`jajRC9qp#8+eKA=MEUw)U!SDX#TS8ix1) z-%Q~DSp;F;BsGbL8s`5kZ}kN%V%7p6sbs~ELfAZFV}=XVDOy|Wh&f-hY%WIt$JDKJ zD$G5zj>w#6E7y;s*P81RQCiZ$U;E@)Y00R0jbYRgsMlI6P)9Ml_u6W{ix3{-2(3YGTA6xhAr>-EFqpFKoKl|3fPe4~f{S9kN3BxR!9+acxj1Vf#FZ(T z&*!1Motf8L6b>lpr<*w=L?kl25z(iyo2?6HoL z?h#q3_DsEpVvD+YfS3EljWn-6oSM?n%^rXmod62+K;H~vG*B#t0R(URIPNf5-z1^@dD4}Z&iGU%`0$ptDz{oF?6|0t}$*S!Zv8HhB=v%t$af%mk0(s+M;@NgQJrB@U zt!Nz3;N zTETSd2<6v_h%##IRC?oJ!Nrj!!y!I zm-olGlj6MOo%cy7|8LrFOngRU0ZsPbeF>)t@f7NLV^CBb@Ye;~nu^>TxkHfgLv8ez&@dhs07Yp01B!THXmdn+-+A$>_gGv)#1XhNw^Em(#iMBf^A_dFT0i2y1pm0s ze#y4_k)qT1r^V1PB>m9tBe?=2cd{#cYMU#-&ONi<<%cE6L-0eUF+(j=J&S+0cVBmG z_mOqzUd9|Kkxx^kx3*gIx@T20Ml`nSJ}YdTT2*EIn$oVh#js0Zf*D^kzGS56(;nHt z59qTv&o~;Fpoby{8p?bMj-wYG>}83l)GPr=8ZT`yO3+3zp7)YD9q|HZVuhV(z^SjI z?}3he#pget+!%Jf9=RIFD1>bN@ZIkC1b3ded6hxXvb>+uR{-`zE~kQolajXfHYps+ zD&cRZ+fUreXmAd{KoG~X6PxZ7dw6|_e*;P-KTM(L<)<^7YiFO?xX)HN&NV*jPf)FS z&&YZj9TRE{m-pQnLmSfP}AMS>C(fe)_ex&h%o)QwM^3*b;xL;Q?Q0(1@v}ZvNy3uX%e_ zrN`ieAHeW^4jjpc{k)37M#Jm0wHX<7gATei%;XOLsvP^Igl;m^QFH%uDQ&ua>~94i z-yqy+FDhiVHg@KyfDy>td#)xM-|!5Am+2Lyv{?`R;$qFUVs?ANRi^VLY|vcAfQGd_ z>d`ZlFX`$J0TcnoYY_Fw>SjVcpLj#2EynzVv;P~J4_3r=dsOs2p+RH)1IJ$B|g}Jy>hs@?kzsK120uy`#&GQ8rWs< zqXC^&XLdKvtc=gU3xereWVJ_?KEvvb+@Xo9qmDG z90aOaxw1epP^`?rane<|wH-In#azY`(f_daMw+emj z8q-$}R}tIJ#LuI77HySzU1AFvEUWD=z-yq6^T$wLnMk7fhjj;Xf^Ad`YvWJr>hqJJ ztb>OLZp`a6PWtA;#{-TQ>&a)R&Lp#Xb3Ga|u#Hr5R6H#H-0_xz;o2nUh<#F7Ah@f6 zzPaR-cHCs9FU#B*hlt}`ph^E68IJ_Ggdjb9%WC~VK{9Xtr_J?q_{RLBNE_m2&rCD| zPEDcUg1(}B0mgsrn$zGsKi}?aIA(bY?18viTF3w-N4#kUmUd>*T-l0sGyySZt&g73 z$`%fuPI!4EmAIReid%d4N>b2-UZ7X_4eNud@B6^k%R?_QasJhZKwbgxnm>|aQ#rz} zXM`tGG8H{Om1wnU#!e>~J-QdC^eT(X`MBDR7}MYk&~Kj0oR)EhVRA@>>;BVI_68` zD;uldBmY*{w*V3XpZ#uUQ!l-5@K6(P7si%?fqw5@kg^8rJ#L^Oy}WUrIpUC)wLTE* zkWKaJ#`MXbN|l$Sv#qV|$3k2HK(%fsF1M`%+VpPZx|p)nK(X8f#v2+{09wqyGxjdS z{4-iG1#&-3_o`lGE=fN!H#&E6M|}d5RoD3| zr?QLn?A%@KGK)yz`0il5B4tpZQb-lb2brm2&lU6lvzEQd)FvP~z9jI>%#gY!%*1kc znyL-^QJn)%7^`fvEaKXUEfh_n9cx728Q@P zNb|FJ?7QnKBA;PrR>TADZ$LnX5Y~1*N9YT7q{t)(brcT!Lz@qGxe7(h4@A&_+ z0IJSt?RqzL?$K{&ifQw>DD-s4Rd6L~0F!8RJjK z7_i*f@?}0qJqP>ge)B?=8hLi%EEi?wjJ-!Yc@l|nm)_MGfYny(`d4@?LLG5S;AXzxazZ}ZR@c#6#jQM~HXN4TbabT-3Qos*XPHGY~jS&X$A|8hQzR1uq zYW@kA%=j$4iGYb8~YO=mxJvO=Gknr3Kc-E%()jF2BywCWtpsv1DI zbS7(%8u6Vno4wZ_$nXw^GS2p&?y~KJ*U}ek1D@>ny|?Ro8NinUKhNJE-t@f7#Zz%# zENpqK{jNUlgtL3++-i=YYv{Vqw#@(;gyku-*!8o{c#}D?ODp!)u58;+-H{V$9y^>G zYghq}b?k6*r%bl`nlq@xJns{pu20ic2NJ}`J@4!TAnv3=(fSe7{vLc4rTsPTgi%pF z&zPvelx}>dbqL#6z{?WF->m7)oge?}4Wnw|&F1>)*KX<`fba=eTF)?O9?Qv^RFy26 zdUv%Kf9jIfbmm-wdJZio<)>cHpkA8Ov$HdjKTUJEbs$9ygFm*I`f#}_;fAM;*++>h z%GO91H%!dTRQK(^Y!BK5a1X${1utIS$318V$TijSM9n*`-Pot*i=BC=&T#47hoFHF zBAm{j@7VMkmR0DkEu5zaTP4nvT z$mGtCS$^xH#e=vK-Rg->n8^IIGph|@G2Kmlw3M-j-h2b}m^R)3!JaD5nKCqxkq0oR z?y|^W6I|Ul^3#b~(@7T@=LnGAHTbx$6`=hEppb@EtdM?p1u(3C5UsTT{)Wnz za(Eh-0x*mo1^aP~hu+4wXusDNeRCmXpv{7{U-+FFcJIw~dtnOG<4>gUrQ01hnKM{v zcGw9KCkv=W+X0Y7t25iEng0SGG=W@vCfH!H#nXeL2ig55`24`qu$95YPACvZfyi@i z02y@DgI#Hl)rGRn+K{bU&zNlvm|4~LxGSu!&(7oNGX+IEG$1hC`NLGk-|?c17X72z z15RL=w-fgHKy@|1t;ZCN3g#do-8YZ;;>%I z8CiV~@}KbDkc5N3lsc=xp#fe#K)B!Fq_GRSu)nGwR+K!ydFR988|v5cs(zxD<)goG zs86kq2W}E1LyG9X*832wXi@#vT7a{tA`cn35r!cMxfIrgDpqZTx;DI8KHVJO$@I(6+K&WoI(3~q<3BwmOeh@8xE?910vVn_C8spNT_ z8mRHHL(5#sj$c)e4YD;dwDn%^Yr3nVExAMy4x$4)tq(MDOTPyhx6;jp`}L?FfqE2= zVGN9R^(enc=0XgL8+-XrzMexIwsO`S0hS1^5`ZrXX(;W(?}PRBase0f1Hn2%xHH$) z{Z#c8SN7rkc`)vg_fBsd>?AN50VW(IJQvEnbR9PWVfeR}@RrGny>0J25b`MofDZ4Q z8fLSs`=fBJNtzw`2h}6ub)KXe^}FHbc{k=t)Y|#jz8G1l2DJ~Mody;jjMH;`BU9Bz$;ffy8k?Zkx&H8viy@ac$r6hYfp>bOU~Te{y@OZzH$dMd( z$lm0mRxE34HBaYG5P1Ap@);BU;byXKm~nEM=ouI}a>*NHE4ytvixjI_4gFoVUWqGJ z7TU_PL*MF-%}U8r?EimJ116!QtYPUt)T-@!RL=Gfk-1|WSLGKcJ3pkrj)shc61EHo zVfQLdB2q1MXgsv_D^1Vowlgg~L`xBbXr?9ErZw=m7DHr~4}$j=-r;1V&# z{P!fFJaI?t9u@ik8TKeI`M*Ex@e8wqH*a;LewzETCn-fW)9vs3KDae@^f3V1aAK=& z@-b?AdD~i%(Iwk1B^5F^6a)45EqxAiQ4EI8-1yeaNfpQh^k#2nMhISJt0FE=Gt!CyQ8qMM&phFS1%xJ3x zY+fdrV#P5x5lf$w7JVx|yZ+H1wuIVJT&+ES?}5}iY9bH}Yq<#%8kd)RdL@_3UAKAm zc+?JR6~{92o%yAG1*9IhoS&fZB!+QJDrto8JXZkAJ2ITB2YZ&Dr#hyw4uthbk92>AI|~4?G~I9J4ppE zYbWVFzUibsfVpKOcf(u9H1fA^En79ejigY_ss2h|>w^Hhg)tV7zrUTQmXoow4HaN% zyD2M`?-GYzN-;XYlN9p zi(}4+f^HVYw{%;Lj*RZ7+WEk>!Mdecf6Zq;qRjKs-W`{AyqjTW%lLnjCZ-uy<9MN{ z7lId+cu3xP8mjm2Me!9h?Jv2_bT8bee?xFeiAyq>Jp{};trK^M*8NyGFbn0e_UT#b zR^^SA^;62J8dKe_%u~U@S0=xCtrb*~v%%y6bv$vrWG6C(;Rb{YG}x(d9NoR0lb0-f z>y+JCi(`MUn=FvOJ^ZAeIic%W)pkc$l$hL@s~4Fbvi0)|#f7cfRTH+4+nHrUfr<4L z-@XB>r_<>)D31(}e<84#yDx-62F@HPOwY3$BlaSZs*3{Twq-n$L#lSVr(tz-Bg!`PHGStpiIBw z(?GIFv!kLX4JjP#4xCfeiJ1+}^zlK6GY_P>c*STDgi$uCh>qb|51q}A(+9z~Y&|hy zp$~MxxqUZ)H5Ijr8WB=~ea~^!m82cw|2xtvK$6r>@2uwQlLrN^VlrFTt4X5(?T8GVT|Qax-fe1=`6G0xk`I2WMd~^_2{B=a}3AU!#!AdJ+AUW$paW@VUxUKPGYl8m_7*K1Bi|HSlZEGBwXmyzbZQvh5;MPg9D>3m3o!mxwAsOk$qL6JTD zh!$Y@Ne>ly5g3^6-FlRbvIu@^3Oz_fFrz23&fv)6i{So1Qdg4G(1EK! z+wxT~D}j+ii2}kC)@96#v3*;J&owg>eW%9}hKcCW0tu)=`RN6($dD!6H16)=2T zvOnGyG7hl!u$PiaDZ+^cO4{=$-n)1D?41Wt__Z1bODSOo*bU%npHy9>4B0y;7 z=KPjoN?-@Z4%Q}?Qk3H^YJ zyw}JekCQI*tKG0S4;{_ZyvLJGV=u*j0baQSj|%_5%2C${>&v|wI1u~~zhPwQ&OiJH zuCq`Y_E&P@|GsJ&J2KUSz)4?gUESw5G!Fy(2CTt8zkwCdVP@Ph^v{r)hOf39d84R^ zm$SDk*xPMy_{Bqes?r{!y|jpMSHjcX`uJX z!n-DTC#9&L>Q(X!tceCkEP`9xDf92WE`p5CkKQ^N_;AKc=S*je;gshyx9pIHz2S$c zeaHxJ5ERFZRt9I!Kw12J#wK0o$#uN}t!UO7&}9Iy4LeyAk3|V9oZi`~Up=N!+JSBO zACVv2xqAcbFkWsX?eD%lmP4NC1+i(p0J6iT6LoLrmYW$-U*76FYa;s`FG-B{dk%j6jQ%Y#`YlFD4{9#Y2AX5+wM^+t z3E;Ho!tvOmr@mPg#1s;}GRyCQ`6XzE|rlX!d)k<7Ag~33R4PTIk-Feri2g95i!kZ}6y!VDH z{SkLBa`LsJd;TX_P!C5lI-t~~rq+`39>KEE|^8TSVpa^!ocdk0> z1o*9HX6l+gGmVNPMjR$$CjOh&Xm_$}Vuk9P5p#|Ix#2O(J=1^-UKSqjQm@?~wumYJ zBIGPm#-D#f%|pUd0pU)r^*+FKuQbeetg1zx-6A*bb?4&m9E-hh%nl9C(b%~*U(q@x zx4E}W0>dov@-(2=xQRA}Tk#mY1d`8+m{~!LfRYr#U@W;o6S9}R=DZvU9O&$TSiyh( zKVk(JChpq38C~qX(kqx-Ji#MEMTzBGz2G%#rK*z|l8(GfQkpmIu4;dZ{gMBNw>OPy z@?87Aceh)pMWKj*A||a=sWOQQ5=cU=RoWs@i_Ak5MCKs`1VRW^1O$Xst$+{`6#;2*fycR6Nd0p3e9>?$a{k5`A zjTP0-y``&nXG}b8`J{@_53>jkax`RB3FhV%cRpoIXAyFJN+8<$g(Bhe@!pqsbNc4z z{QcCpQ+!_GZG&yI+aszILhO}tdW%_Iy}A2UqKLhn=uxo#>xmP9n{12Y8Ay8g*O zOBtuf#7?1x1^d_pQS^*&4Ul$IcXl@Uy9;|~6~f-0WcODoWntjbQ{~6xf5G(8zdsv# zbacf5Y}sQd043NPdpB(#kwg0Sz%1|3xSG2?B>+623q3kbhq=(j3hWI_jZG=#yog_@ zaDrl(A>DOLMwZ$9c(ZfRs<$5f49WnpxR7Be~gNjDxm! z0i}}jC<(JDo%-pzuO;{W z8;LNgoMd{sLR;q07pwyJFCqlT2vIAOcAQc+dMA~M%4!Q%s_3%8>{fkz9R@v5Lj)#Ny z&M|ldf*o*ezx%-zb z$1p9(UN5_G#f-^08}pcqg3-mSjk%JPra<l;AVLU# zmvgyy$ZvZYd#jx4vsLl?IFB6z`VhQMt*;8cpfM`C3a1du8ON9rnHx7QEry$}Li97L zf{)<`j)vZuTyOC4Zc&thCS4=Ow0*_hd>!up$FtmPxeZ-lE_9O9VVyne^_x;%Vqaqm z+06Fq{}V_VU^#}+A|l$Q(Zg+`^K-mqQNG^xGF~zhzrN77df3{ZLP@`t>g2H!=Kbgb z&Fs=UU{2ykfl5@fK01eQ23r*?@e)0$<8lp`qCt=y`|}L_k!))?XJn&PM^QrqY=)tBo3bmQ!rZr3yHqoX7p7I z-LjBwvveTxbduhCoQ!?%sIOZPRubf_N_AVlkd_Q@<6Im3Cv?+JJqmqvuc2;Ci@Mzq z(DUl*MCsglo)LP+WZ1p%S-nUZqm3Euur4%w^GdNImqz(Zl9IvxXU+0?GAU9Q6`c-x zQ$VO-);-C2HljNu*iuTUy0mwDiU9%U}(y zcBBR~q(}sqiH_=Z{iVvbD$kQIXTiM+{17DZw|;!V*z8Zbp$W8&Crl^1>bLtDzQ3ob zi?LFHqlyLPxNxqFe)7M%#BYL1emo}HzS0LuVc zPO99ICC|4F*wEp^QG>M`pEir~BRI+I{g_f%Ukx1px-&A|*E zWW}3qs&;;V^Y5l^Zx^C~8a84n36}nr+?$^d#5i_I{>=%#o$sBZn&PW|Q2^N)tj%~U z3vx_YG7O5W9yV@z@3-`ApVP!hlDkt>TZ8@Y)&|qolz4@BQmNPKSciL-ehO*!UHCis0GRfMFZbnTC2Y`S(2a^9S2{m4$$d?Er!mzI7Qy`wo@X7u<&GfNLB(Jc z%R2A?Dm3aPdB{&ZueQ<;;w}uLbhlgwe=_k=v(%Rt-zgs7PC75jz=eg7Y7V z?|=0JTaJpVEpOLlL(}lj6^xbGmtOsh0B~p(f1PGX<#K(RJ0+|CuJmtZ?VNY<>6n#+ zZr%(HnFGE6Fq#%S@KUB0fipT5eK;$^SD3%&KQQf7BA*$0eoqHCloa*rVGQM?; z7BMfyc6b_m==M3c*CuIdiN72*JN*|etu3D6o(1Fx=&a&XM46)-PFL;tr0$iJwmjrU zPZpurNHW)ChTOmyt~AwA-KHn(9vg+Tx!~O@Xk(aT4y~3z!sK@nZKC7#e(EKNnDXdBGv<)2B0Awx_1Ud7vAaC3*a_BJ!z z?LS;EEvoCyv+uMZ+#RhA`ulNu1AjTf^4+qbU2jfk{&NRxBCO5eW}g$l{*}H zuQ$Em=e{@>Oz~;ApgWUv>`C$-AZjnXm@1h0fchO{<1d!ibHpkpsvFFJ>~<%fLI26q zJba-4UUr2WGL4V!b-H4o{I&}066nH({U#J6!pqYgQ;0jst023=qv`kKIzAWDWb7H; zZY1U)MH~YOElq6sqD3v8?!Y*FuWG9X+hzT1YBbR2LYOv;07D6x;x%Jtlkn<3OSNH!riQv%2J@ir-^QLodiHmQ5B{`I z8^f)(!uQ=(|8MZf=++7U)f+2Dr9H;Q9569qkV0z;7)Q_GBDLZ$RM4^Z+LRb!%@F5_QIRTaF$%C7QzUimDb%b&Ovv?Bi=z8m0a8 z`OP_r`|hmpF!yg=272dX-t?d%ojmHvy*Z3~D5~Mt`6>~_H{$5H1hMfGGep}7yCgHb zzhxs;x1_k}sQn5=M1m8FX^wc?mI_UT%XMb$OX@Zbqf0_Xu%FYqpqv+$1&=__ zZQRw40nbXS;zM|f_LwUQiKei4IaWc(m^J1&O8G;s{f5xKo7_@9l_9g$Fz;gUM%B00 z5Ecafe0E8IOyGw4)E~_wObTYYu%>&{#J)y&<%LMI<9PlUJ#L%-xx!Nux7~b!=GoBW z5%mXZ>=~FnWr}@wa&f~~nD#>spJGHl2rLnwHi%9MH~0PB+)(~~|DDgRC#?G1leXk^ ztEWF)AWM7Pp&-}>a+Z0e426<++@Y6jgVW(E5tFcRvNiyg)+j#pD!9D#7gMS(H`2Kx z7u@E+)kD$Fbu7A!;CBi!I9eA0p~V@SzoB{@oxzCX0Tg~Y3dUs3hMN{S4^ny^0(-J8 z5d1T4X+16qB;Nt6LIoA1C`ZLbI6+zX3CyvXx`V1jeWh3f-}m_k>GnOe_eQifrP09^ zTP&?XB5$a?tm|QN|Gx2;!6>0*H)Ls~ben=>Yeh?+n(NNU{Qx`GuJmfYb&fZet>_-p zC~95ST&T9&8+KJ9BnYL_v5l=D`A1yq6uH@EeWPn-ptjy`4QF9UCmFNg)M)6q`j51X zxfkyF`>aHc(O$P^UY_cH1ZzV8Q%^XxN_OGg$4m~}t$MZ60PG3JtBaDj;{@-1=qzYH zUSWs5-|>H4+UsO-37?j--lnc~d)-}c$|(>+QB<9qu7q4PyWW#je&?m8{C0INxbi?%$jh19;>!vZxI=PQ z(y5*4JBT)7h`W`dl4$nMK1gMn8F^M5>=t#=XKO?$JS3d~N|%L| zC4t++fl;sE%&q>F$c-OLcO8HlApooiMV)vB=yJp`Y_oq{H5_|4#YP>K+T{AD^@M2J zr!pR@UrgW0hH_gcU*{bSXWY@5BPJ2zL>-;4Z*-ds3tO|e6>e7g@hZlcVQF(M5>~kW zP*(!Pc#f+_K*+`KL}CzN&-7xp59*-J3mJt$2a%*HUgM>I_zNjN}90$z)Fz%1#sgVAw%jV zrC{7`NWR3BB`Tj%Sex|~Z#C)9ke^hmf}H{Bs&2KHRQmx%h#=?{b=VaSX9tf4A=op3 zBB&m`qkG%{uDbo05a-i|70ld_J1+843>F@t^cZSPL11B zAV@Mt-gef$HWWDq7L6g)SDlRK=3mq-1xSl+cxknR&A>8ahL<~z8GI*J5hBT~mxpBQ z3uQz@e(U_DD>qNN7MPLnr8hJ)V~V^z)d`=KnFeh0u;RQL+~B|Tx?e_fUgW4sj^!%H z=sm_!5>NwcU=N&ZR`UaX{tWO{wSk9%C)HUu9dsvN@%2>cRvT##PrB|bBS))w^}`od zy#TvlPv-ppKp?ZuFnBz zyjNAFcfl?EMW6^g6XtT0=GZ?<*F?RcRS{B+tp_Xn-6#BA3rfA6D;5Il@^th!PRida zR)NnDWB4l3mgSf95YQWBxbHvBokbnDqd#9nk-kx#6@mwK1JKD4XP8^u)Qq?wk&BFBV#3ALzxmgB0+DfSDlW(}+UOR_d0XcUEyukw)?PXvO_Nm8$%(4gh(mb+U= zF@>AcN8CYy+SV#)60rTUSDZ0Y5Uv7OAptDGt{fl@DI3R5CwZtrFe#h2{^zA>{D|8Z z)yos-_y*K$7iQG$zF$G9a@mwRL$?0=j(1g~7SxkMEDc-(*X+y}EB40UjNSk^4YOBR zz%~QfVZz@C%J+9D=QdlW3c~`oBv zn5jwhH7)4Aq}xXrUToV(S^TN!!VBM4EuTv(*3IBaIpeDI?&xVG^;FgS@0mi$d2t8Nm z_J|pg=7cqW~%3w736=Ap_g-_KlFHzsL-;!+C8U4cWk2bw{R5~NNL z!GgdixHziqkh^)ZefjOYUi_;!J6LH0j&NmacV`_XX;Q!oD2t|F*Y7Ex06{K%Y~{}m zJugstV0rRjTa=~qFe|2U>P5945|!P)Bc*~fWYnG3D4`T65TML75nFQGf(qI0F|d;_ zIEs;~k({nB@^!QkJ)nE;J!CR(f?v37SX`C!878JZYIxf6PKNh@RoSk3nnP5Ln)J8K zO7H}#G`)S36d=liAh2&I(D)|@K2JO0l+wgWNxH^!M`)Vh;H1G6cY^*Tj)0H5Ou!ms zq7gE5_Z7r4zO{l=Se~Yb(;Ma`wmiZG+pm!$=B^^8Ih8pr)St^^3x*!j)j*<+5FpLj zXLJCl)R(0cF;}8b_7)F@BD}pUcY({NB`NAXN3d`|VlG_0@En9dwBQt{Rs;YcUi!U$wH}1*IJbtw7l$^U%j`pnQe)$l!<4AtPXDN3TV6C}*!4V#vq{=n z%_DzIdzhN}DHjP2iC`Sw?4})^&8y+ES&`#JO@A8rVHo-uPDJoXx>+{pUH0FVx5BVX5-+4t zW@>ES>`XO(Y9XGkPPJ`_vAO09)_5fbg1JRh)!(x>Mz)(msXyok^rVw%U`>Q=x0Tg1 zzo)2XX?EkR9BAELS4Ck`>@qN69N+6?HO{mqC=u#dDJFOkK-Qw)&V~N?F-hs@k=YC_ zS(yT(ql7cXmo0ZdeTj9nX+wWjzs&&9?qmBtw@J2epQG@r7|%PV(QX?=FE8pHBUAhi z+-_ihcE%ItK)k3)simw^n_}Ms+=(F`tPZz%6H4XqW2mnL_epzq?a!$ekmV*7Hlq)QFyf$={AJ{cJ2z-{LxRN7t@9`bMZci z(w)L82)+O%X&ziOLlO(gkHj@1p9;qe1dhUBW#{9|NRP}5hMa7>D}0^L9cxsHiOIz} zpFhd0@xmUA;(A1~i9O7R^c~MAV4u9!U`x4m9s(QYr%y`eyV{?$z2(;rXS_ZwvXHt$ ziy-EE|NlldJJ-cTULcmU#wvr*qS zQmpo>O5n)QIUgVjz72GkS@<7d%f@p7ZBpQzIop}(FHMzz*+=UOx%($)*dYf^-@ z6$TZO;#flN>g!ytPwlOb&rZc9*QWI1!pqcVHy=sUMKxO;gb1?rfV;#s%|J2xS`s0} ziJSe)6vn{i-0V+CV;vqYsI^4D&)Luou7W`?+e;4yjU4sVJ+8mm4(8_&EvCM}v3MKn z;k|r_Eq+&C+3Ast_c#?{mse~cIXYz)Gd`=PO}a6P{31gFtu`Qom^sU}%F+Zd&J zpGvGOOJ9nAeSB+Z`SEs=S?9*lq!(ZgV(r@Id8BDUwmS}g5ASNE``(0lsWm~W9$k_B zdA%d-J$KGrm1nedDs<*fYVF8d^ZFt4T=RoedcGnikr6ELh*b>pw#tK#JG+6m*kJt9 z@ct0Q>#Jdz(C?!kp`4e0t^2L|-28=ys#c@>{02|ycGm)N=VHA!<>=8BMD49K`;dGt zX6rh^faaW}R9X>1kwFZ|Rpy#cM6|x%e`O+ag$NGJZvB1>XJjoaW5tl^4}by7LDrgM zg=&I?8q1!1&*9@3L1dAre`#ie8bQH0FY2&cT696zLzCUVzW`?7W+`-(-#M+)o8!z6 zP3d;LDF-oReNuu00>$-lQ_Jh)=uvg~8dqH-VdO?=y^mC#3^A-2aO~Q@A{S6EY}a5r za8cSjU^TeF85&Nj&^ADiz!y}b-#LNV>Rq!JZcA;S@YA<7$km0x_Ctf;=%J(?c5wNS zk3Y85w6=LKo7 zC4!MYnI(7W(n+R}^i0pCkR?bPj8*de-tyq_(w-CMfe;f7aJHO?hPRk%fyGe#scmI9 zryde!Ygk>MPdL)GS5qn*XQkm6(sVaxRU0MiU3yEtAO?61r4?4VAoqhoNbvNVrUW^Y zFAg76XA4Uc4^i*kMvP>7#dZMTVK_4Fvtnc_`^fRlJQsU~H7&<)%SJ{T#Zw-Utt1av z+r7Hz7jYN!lay1Qv~`H>CHCC#9!Bc_oq5m~cDD)l#lk@yu!*QA^E}HHq}o5HzIWE( zB_M4dO*U9X9Z9(UjCi)%)UH1=WyDt3Ev?VR#K}rUq*mA;IuTC@4d|sy4E$8qNo6<{ zQHDM<)2Xc8KHCsT)d3=i4N1YRX|6QYq`G%hX^%BmGiSpA{LNT>_{yx1*DI}?iEJ40 zEzlhS+*4P`d3@aXcX5@~k|I2u%UdXFP{m?t)+ zPxpBi_W67=H~!A~tad*Xiy7#MWA%1EcW^f$l+6PPG~tvou~Ff0RuV(ZdE+4p%mEHZg3m5+EOdRv5zW*VY3gmb(Gc^QBBJ)n29p9xcby z{L0ccV1_q0tI-nPV|8uz5S2gGhjP6G#Jwp>Oxd-&>ZVJrU3VkrN`=z#hyW8i0u-N8 zu@eSS&cowR>dmt1ZS`i2hL3>vS}Cb^uuG!VHdM#Msv}ED8Mpf1RL%;(lyc1@hO-_+ zMk9IgW1FBzeQkGw`9R4Mtm#bb{2s$5g;RW z!cGNR=?Dz8BT$})cxY_0KDi1!bA5C5y#LhTG#uVH@a~sBX=~~T2=N8ZRWi<^T!nx& z=MKixb|OG+r}aYoKv|uG(zbYbABq=WzdkoM=et#7R9iec`f9UVdPs?dK@4G&jnOH^vy0|>(A8hHIT}#s?%LB) z?pbMVf5r2MBQSV9IuCFs=^-4MifK8k!uH-0ho#3NDJ`n#i6V%yyLRv8mj6afP6^O; zKfUnj!<6dwohMs6!A;Kei%iHmXn4PhhhXPJPYHDNu>DC>d-HPelIN>R%1BK`&V$3O zH?6YgB9!9#=1ba&MtyF2dSSI40y|C+Q zf^Yqfrq4yZx_W$;M#sf z3mKMSrTPg7_N3jqbxTIym9Lim;{R-Prp)p|af45Ah3XuT60Q=3jx`6Fi8ttxYZV_( zK{0(4@qU>iwG`a@Y4^{M+$|}BN9*?3=b^}qPv4}3y0pz-=r*Zjm|2IvpLv>uUcsb7 zoVFm38BbDW8k$g`r->k@l0;6`BW<||Yr-}Uka=*N*oN1pFNmd?nU`9a5o`-m_AWsA z_bRG#2Sp7D>BB_uO%7g})MmUhlShhdqt4m;oadJ=Q5fhGE30hS!m}{E)gWB-&$-FgzodN{Iep8`#CyOa&BDfb|Djys(JTM#twaC$FyYSV{Y)W0 zidw#VVL2VsTS2d>RVZ?(SUZY&yt_+F7Zp|z`aac0))8{u`WQs#6fN4z6!+-^F$(go z^yV*O422|Hy?EEkPoAJNZ|SO!{emw&%dPG*QvxiEybJx+Rj>$Bm30Z~*}B8RV+GDB zO)ba(-1f5p4{ej6zNH_w@U;dhy9R2tdMR@3T&W(-apyU1U<>SPBkxXJ+|7|(*@Q87 zx0$=7YVVz#57Nwi$iRbT>T@S=2E(a>OO20Gx5u~4;`$Vm^D*AA=v0vz_e+L6w`FlI z;sMzd|G5M@a+U_Mg@r%w-Q*t)PJETrE51lJ+2Vf2`P@Qq4TyYUDgkT&oGG!2AXA06 zRoLKJoXLt~FzFkw&mo_BMuIg15iG88VFW=OE@p$FIGXbPj|flf;gq8`PjBIdwmCC-gac zAn}D;W~neE#=(?iuknJ`erQB- zu&eCyk@)&**(NjoH`=~Np`hbOG76sS@PRba?Vv*|9U27nvF%27Cb@jExutKkQ4v`i zksPt>Slu&#>)WxbeSsQ!>-O(Nikkl5mcgF+2w(6>(*av zdM7ih`iL}Kn9T%J$&z*9SGtuEn5B1)@5}jdRPrM(j0v_c)e9` z5}L@edXf?fNzwa9R22NxTBQVF+T3+Ke;qFX2cHepMD5R^^FMMPh?5+VveGX<&uDLX z?52u5Yw+RG_EV;-@->k9unqC6$Bmw~l!?KeQhKwG5i~l>q4Cod4lI`)sh9F9MZ4C1 z@c?tS&UOvVpal*7*$WGKv<@aHT&yvYm1Bt>>afL**=Ns`8B&t3v;YzkGw}ts*7?$K z=)5G$Og-i1Ex9?AbCC=q1k9gQgDuCvVPVwWV>k~!iP zQ~TQ=+-H*QK_r7&_$^NG{P9d_2Jag}4v8}-?EK8&xPHt|DU?67gdL8KMG5UG!9^R0 zP$SpuculiiK|=T0Yp$ZDXJjX(q8i*{$0s@44C{T=pchdUyMCmE z%r|!VD`j)O1%a&oRg?F$Nf%Au9Onw>A|}jCUju(oDR;f`t2S%y`8u41jLddNka;|vD<*&vR6+d_PWZKtZiQ5Emz;(X{_UPKGUQ~1@Wd^BB9*IsW4{L zdf+nLL-*0tH%93gMJ-Yk?ZLWz+ZUQTVC-e2*))ninzy%VXcXl>If4#@uEg8uhrN77 zjx-3T|JKLs*78#>FdFo6VB||k6dZO9Gm0KOmC7Cb&eW~nYv`}I_2&jN+-mwlLDJA6 z^zpn|PIbUj-ona|+57qEKWGEo0*#%INHwxQUOUA+CPp{v*Sl|XhmNE3_YHGb@_)g% zzV2t0>y~KLW~Zm-GVZwCavJu%o5FQO8a$6@HropQji{+AWa zZLT)|!96R(nmqAnGA^bV>n&U;XfBb_#%A9;4k7xP`F^FTiwkcEZT`Zk7jcPUr>C(= z4i%{d<9(=ypq7=^6&;=s%o@sQ?SZ;;;cSt5y59vP{Q?OVl|0)P6Qk!OEI6vp4!Qn0 zR)CQ)urma^iFxRDKQsyvkWQ|hf1M=Xww}BY{g`L|qg5N2g#N_GIkcZjD-3Y>czj0D z+@%DWMmO$sAMJ+7_<3ZJMN=`{>F=+hbP7cREf6k|bwwUo)AgVz7~-zeTvsf@1U%%Y zllbBbeUSon^|tw%*iZ<*?LMRuA}y_f)383ZnfRz-Gu0^|Vo4T1Ejtz6a_G|hnUJY} z-GTk2QG7`m*JkjjQ*-ZVY&5dP`3o%<-QXF40HZe1IyG1_=cM9HV8JNn>WBOaY*W@HpH>{bBClgx`%hZ| z*e-YIkSObo5$@Rh@&HE|xgCV78DYmg;f0=!mZj>IFM66aF|H76NBZ3mz(6tV{MlCF zlivc?V$lQcT*yGnQ@L7D;;JAP(>QxZMpnBrmM(;#9I4mdD;LZoW&y1tqdgX{qau-qz9YL0bFug|*dbw@CY7;FjodceyoPEq3OZ1QZi= z5w~)#G6R zX0Cxz@oc1mP4APVYIPMXRJ7@t9mB@&NQS0`d3|E`OY9;X$;5>|e7k-M((uZlN*CK_ zmZokyHkh5leI)kd#MoHyn?kc#=xXa>n52fpNF}iZm=ov@4}AN1)u~cts7tWD_j}2_ z)o70_CBp{QWfJeIo^-9d`Leko6 z%Vm}lO;y*V<_h#RJAw$@5wm*%71$1g3x?d8 zqJT$y%X`GEyk7Cumj$?yp+h0t=o92*Y{VA2D7xtdqucrHVBqlN83WqO7qCR%-=YI7 zxY?bK>D~Wv0UVx)5Y}QUTxd~@n{Xbd{#+}7F`Q|(Fm}PWg&_tXp))P_O`9F;MmN9G zbHXZSs2kk)rVrOR?ECua_2KRQvA!p{;jK7bCM#n-u0+it@I)3qYj!~Ho+DcAvc;d- zksWFa`;#o`4{|`m<*x3bl483ycw-TBQ5Lc2rX0U7&fpxmtoYOtUTQ7=EAMneIdkyt zvVAZFL!Hfz*~s2YW^0WcE?sWv)JNr=gDC`>s#rKA58-Ldc{|)*n9MUt+MT@FgcXh3 zjmNBrF^HVZdEuRnuj)jnUd=vDGc|b2nEewq^kwO=>w8Jj#{5mVPxJon3E1*8a+z{` zdg10^s*Q8Z7Pb;E2J*%HEmE#v4g`34-H}fOTW5 zXXqpMS))M;IVqDBxf2zJyV#9k$^F3G_$v?2-rZx&r<9n@I)1#@gU6o+@3jBLec~z^ zd+4UUSw%FJVmmQehKV-rdz)2FvR*{7=vItyh~ZVS$4mWty!p6@9=l7u;$v@xCc9qnoO=`J z>g;ENaZcQOPsdf19 z_@_UjziudqTMf2goR&@5DB5vEhuhE8TPCHkR!gBsX9qs50t05=X%r22idPHNWwWMa zH@hKa=^+Ib&XIuQc%gy-6M2{pTdu=*GgIl<`Qrt~7;F&e))EHzMB_fizyJ%MPR@P9 zjKZvHR%e7?BXD7~F?qCEcSovPBU7yCua*Zy2)FG_3$ijfu7R0&oJ-$&wa-V@opQaY ztd5y@E@K7GnfTzS62S|4#e50Rn`a%yZ+7mjty~*LqSB@9@ zDmqCrQ4b@m_FfzDM9n3|R7vno7T!Xa3pNs4Gio0zUN)&-{HXq_pP`--(qQXq-FJX2zHpk`_Ts`vrFguvHFb9GVW!E) zAQ#5Vcw1_0Y~GevbkI9euw`vc-s8>)^t&$+VsL5bMTk7 zldKM_QAK?FTNMq8KE0{ts+GQ=xYMx%rV2g8ee&#T_VchpR)PuLmrV+m*9plj6vc){ z1>5rvxCm_IuUF2WaTVs|7{O+6MkpbyA~p<(H0TE-M-lSNg)7pDYX()1J!Jbjk1kb;>8+IxbKD*_gQ)@C}!%n=F{M;$`|Hx zh(g|Bv>-|n#V1(&N-?x{3AX+j6A)D8k;Xr;iXZYaC!4Doqa5SA^Qs%Bxc3hHXI%5WrRXvmcDu~ z`f*B1Vp1COI2M;CLr#*;Gx*XW&n#ZPNK%j4K)xaPmOfZn7wFj4C{IaOTucELY}tMj zBhW!g{c>{B<(^TDCa85C8=botQC?dgeW;wXJH{^m^JS-+`l@Z6`YfT=!s;qLYRFUXN@MRTPN zG2xZdWyPQ$1j~&eP__m;a6@k4E`%C|MpcclG0#k1Zp4JPX_+XbW@(WyFL8IYkE)dF zPa>GgBTEOq9a<+PKp%Q++cVyr=28B;MS=n>5`|VIgZrn7BRDrV$O1fS|IwJ5iyaO_{y5ySy5>8_{NT* zx=+WNM1!}EoLpBM->AV;82J^~#nV7Q)kq7SGUV}vX1th8Yp8Z*)wSRT*QV7%Mled9 zaksBFy&HR7v@K7m8@GnL;5&<|rmzdDAlb-Fw_){D%Z8oDZ98&c@q;zAj+P}n6#qRW zb)2nmaleYw4SV0%Z{vz2Fpm9t)0y^;h~Ng&bZu;WtU_Ehpm_MmaBVoZTA|pZ$xTaL ztaV+v;36DkJvM#+KQ7f{ikiKQ?w-g;IpNIesGH5iXIt#{nq7&??gvnwn1U<1nL=re zP&4XL`NBSjuQ$wYht|1D*EPo=!F_i`{*6sj^KxLLa*@EdFlb!=WG@P|(YJ4ar- zZiK6ni!R^y?~}!ay=OrZjua%r2JZ>KH9uIiA&9I<*vq*~aBupPHSumGB@`M}Ra8&2 zG0$#u@*Jn=AhB~dej|d4tn%>_f|;N9nR4GOMD%Jso>gm@P%9O^JI>O7Bt5h`WFeAV z*_gKhot07fmpMs4Xc2atwGf9^8RcTFzgZ0(z-lm=L?Dt#<=m|Q^dFIg_U1sBN#%;d zQ`CZ8sVl|C5`n)UzsG7o1_7(_46qs&|7JDb)lNI!JN~~}4G#6}!I9K|vl@E^3)A@j z&T5dQtz00Jc=vCa1Rd9w`?pNO5742;^b?mrUY0 z*;=9KjMI?mY9ScQPozgJW1@5QWGAKIwcy+xfLc5CYM#&e@}i%DncnLSItmkvpavDq z;4a>DUtKqA3mjUh7QG{rxmjEuB|POhJtG)Sk2K=9@v_OA9U|v$Zt-Wt*LiW{id6Tr z;KNSwZHwB*3?~@kIIc8IYb=JTPr^K=l}BHbbSGo{Md#&1_VxmjE?`{8EvX}tt_pca}`ksyF4>^-lCyiOw{$HfOj^m}r?8~J!s z?O@1@XV&VVS`eB7ybkd;eIktwWf{a`g#L&$#0(Qg%sN;0Um-RY&G-!l92m;+H(>fX32Td!olSj{LT=+c?H|H0#S{6 z>;0K6d9s`rEObe8I2=>?qVArn0<6$yebEzN0A1|>X{zKhjPR3aClVKQj3q2&EZV6Z z1OY@KQ)0qj@@|Ir1Hry~4Lfeg-L?+P2^9lfDdbWQq225~?!u0l^jkzIgd9;EeLMGf zFFaHpq-LPJFS>p>n+5VIm;>}aXZ3R{7f_|cf5a=N8TY-?O;v~YV&t!TMB4MC|COdM zz|=3sq?dpnh{#LlcHYK7k^vlYH4_HkiwEi3iw7BgvgWH`u3()pjdlDiKYR>rP{JFX zis-wKc5RnTL~$WUqifKls?ZmK4g1h7TZ`Z9{-|zRU(r$X%T})!&y1BTRjqH>OVyYM zl2r)o#w79b!gn_mHL_*0)Ws?SF1Pvu=?fC|}Xh6*&fF!T9zU2pnS{cJ?xJAQwtd$qJR@Ibg8dc_5ts0VPN8ZK6uG}CS>&TOBbdEgt(u4G5X5lxB#x2nH4!|VO< zFL=}8&0J*Z6mmUSW6PB;m|PQd^)}U}itHP?{eAiz4O~gKO7Ad4DUDQukr|tPUwx~? zJu>usUPYQta!;7E4K#|Yh*|!t@ep~NvY}R_>72wzyyBK_51Q#YF(|>Xc2^+1XkX)u zuT)L$Tg=y#4*i2QyzTE}f->MPJqHU9v_jcY{Ys_4(mwW_P#K&jRze-dN+RfyQwe)C z#)c}VAo_ud)eCYWb63l6LNwCClvby{vrK8qKJB|dP1IT{NcThvyY3dd*9Vv@A%~^U z33tUJ4NX^bg@X|e1e;nL=-!Dmq6kK=K~f|zKE}H$j*+A37LkQG!3Y$_ejCq+pIc{3b#z`l^ zju2#8MzgLcAXZZ(EUDgJk`X^4lS2;Bj=5x#6M6%4TdVJ~r6D12}5k{?TG<&)#}_PFB&~V)b>6Jf{dG$!)0werIWAZIA7^r%P!zA5ftEW>wnnnuP+P z6Kize`;_;=2MZ;Vk;hpV%=VeYYx!}c&Qxe~Ii7X~8D<3SRZR9@CtxvBK?w$X!a-_o@(M4fv1%nOD8~FI|zDkL7LW z9$X?0d1s$v*?FZqUq!ya7?&htM8pdNfCVZqvQ~vKy?6hd6W`B%|TFSQ| zsm`~!MZekNkU($(gpvTbVj)5L=qkOYwPb#-X12BO*v?8T2rX+1sMx!?H@>0jr0^$y zot`+gUGDYSLKrC|1Sjn^QYVEp5sH9%3&jrsg^)0-UN^vHWb~{{+m^-4<`4P7i8{E? z&38*sqhH-<1E<3!mkP5bhv(LQqd*<;Kfk=>$43ptU|$Co20cD|EugiTW=wOZUb5K> zQRoW8Yf-{;UTnUV*c84?uzh}|1!H5{dMC_`>Ro)C^&K0t1oy`qArn8(f}~8-1J~^- z1?L)OBPSm#-!+YK91PM4P6VROF1~oA+r|;&R_s!gmso@J4LPwsMkD~d>L6~1BD} z-pf=w$BfOnn7GI0y9HHMtWJ-$zKJ+XGH(11$=g~1BiZ1yC3rhT!HiIc)pjj{7QuY& zI#uBiGL#yx6k3n;9UYKuI>D>?%f~YR+kz(s^_nHVa~lr}`&n?BoHBJCi zT=~eT$=8>9nMdF3o|cdLsXO-ks&p% zJXgapL}|PIcp#iATfg4$UCzB-`PkIH)0R(|^E6%}?L)Hb1Lhz>t=@lW8mv(M2vUD0dY_M>gSARAaj;rd+TrrDq zMN#8uZ!Q?T-H!@)(+P+za`VgrYanp@%hYhpUMY~eDw;Cd`BfO~!izPQ_S=+cBh5A6PmQOT&6TjK$`ep5%nt#80LZ(%IiDmzn`xb?stv38c5y6w~l z?IYlNrP4BI5MROGfOV`Z^j%uBF(fA?df((SjW28`o;G$(Q|GOycLA$Gpab@59cVtv zP+9P)ch+s?wsO{O${6JK_k9`n*1y5$X;Do=+=&Uel}0Fh+`xruAEQFiMQH~{O&QSDl4 zR==WStdV~UC4>p?F4p=Rg)1p1#QjGg{?&8A#I3(_XprcCu|nVETn-d4`geF=0`1Qh zL^rI|pFZfmd(F3bp8_hX0*gL~n-TW^?l-RgdZ>T}E?8$cV%pg-F)r|Y?xj2$q_O$8 zsxI;3lNfrv9rR#oMvs~HCNI=E9v&58xiObz`g_<{SF&=KD;Tbk-nbj{Z9tgPff5Wx zOu%<@k-0h8Mclh-OH$}R*Eg1*g_+YKnJYP+e-KXTnxkN{%*gJez`$tHMg*ogb-R?y zCukp(WT5Kxq}Y8j{OZGMHht*lgug%dTGExIqeo|Tw45QZ zYk<7FU|XXe6CX7p>GmXU+UnuMz;ckz7~!>l*a&|r_c^y_$Lzyrumb?;B~3||B)F6# zVM{Q3Rw;h;dRX*&{JnsT&8u)W=5}}Rb@V@LH?Nffe&Of6MuORc{}+D2p^qHp0tkju zG9Vb}FT0uw{C1?UIHKFU8wSzKl{ZBJzf>W&K2C&~TIp}OOXO9Yo4pA`XOSxu*m=F6 z`}In)9sQHxPB^l(C5*&qqH(Yp{IHjo4`~a3gw&|ER=Krw)_sAuNFih#<%s*#l@%QBYEgh(bt2 zRLU9_S;CUYW{@QjSptXz5|RKx0t83`B+NJVzJJes&-2WjIcH|hocYIdIHffW;kv%p z=kt2M-dKUrA_iV&v6y5~z<0qHUyX0A_VUF=NdhwXkekUE1>RiBlbq@=Yy?O&h z^NV6vs!fL#VFc2E7zejd-}q>A_Kl+>;Py_!DQ1$Al7rez5fIn4yG4S+Ts5ugW@l;_ zB^r7HUR!}UpS;t$JQP1Wve(FivF+$~(N26>m+u`=fc+n;h~>V8R%!@?YZLW#@FS%0 zpVGGZjy;oWXYk()D|^5aI-9Bhf4)Q|ETo6PL1|P1>l;AZe=I>&*rF7tJ-AoH4KcHq9_*!rw(osExL&GgPvva8-~%O@B7tYR00<>x$v zQv5V%)NXs~7)G>cI3Xy>Q=n^C$Kxy%0r^-*>c3T4R98RG096*!{-UY1E>LArGc8qB zSs4CZWr6!tW#QwIzfd#o2dXTv{q2@QzkgO)R4!NJVhgXrAAYK`FmAl4tOivUnV`y| z1XNiVtEwzctEw#QezU;+v&y1#KqMRiQkhdom*weS!C0uR2jqwDex4tRDCM6YIf;aj zqm<&CTSRPuTE5kU3QM60jOt7v2apsJ_Ebgvm z`CZWg2O^#76evUSMSaSC6sWa$*fVln<`Mc`8r|?3LG|I7TRXEx=vme*$`**D8FtF< z+jO3)_}q^(cgtqYBCHpK%`Zv)B`MVu+n2RHT}R6-;YOqnc%d$`PGy*bnUEE(m?Mn~ ze;+l8MvY_6ojHmF3JPrPO?njNrHTIP2joF#Z##?Oz^%orYsJpj?&!_SsT*!`D#k9F zf(0^}^jw=0*5_mbBp@OBRZJmR?q(j0N)ZhxRT3BNIJa#ax zt=+32uWljY563I?ma2;C@IIoWMzj7LSa1X@gBL-P8vUn|aHr3h3I_e^$yzuukkXvEBB&kRfo;5qfV5?RP}M{0 z3&Osuh%94#fN$#Sziw)ihEqEI97g9mwcqs`#%jT- z0W_Yz1rw5sska1o@8mN#;sEE3p?QxUJ%d&=+sVxvkU!?Zf3S})X8d?4P>#V*f0az$ zFURx>FO<1vgCo>A5B&I~8WzejEzNyY_Lwr#9-8nvPP^lrk*NG`w;Mu_T-Q2Ya|PJi zCtrdkx1`p)k459TB?xMrQ+e}XF}+aBj-M6a>iPERtO9+HA?tB zZ0?mB8nO8HC{l-vjTGfXjml{%sX^|m$)9^SzS#&~O}HWY%DBZU1DY$@fOO{{gq6xw zQ^fDYsL^a9Ry9FbfO6SrW;ZanI`_?w@SrsH5m@FH=s^P> z;(Mu&2cd59*M6gto27xdEZS2R{(SvST)Y=X537rnjpRp9w)@!v4SnYq`A4>1wU>qN zQ~q+5`<#)FP*_Tp-=XkN`+gm+nsc&{?zLRmx$PDeP>gdF81w z!@ZDv+9Y8wRvb&twgl=qbV1MPHwnb5rCqlEFVi;UUqj&++9u2`Sj9D2e z_GZh+Jg}Cbf7?AAKiNG*Z!v1{Vn$99{ZbWnT(f5Z7awYf6oNUVWLaCWIs1+@F-H%% zi-BUCQ}j+qVnPz^vexedOme8Fjp3JV_fPTuB^~Fr-=J4drWz*za9V}i4UtV6=fxFN6#pOrbFxV7e4 z75W{jrV1_-jYq0=7xzq?@Z4}h&GfkCIw<=cF{NH`{_M-K_B!m+F(Oepxc+2l}E3s|Zdm2b3Z2u*dh?I={z}b2uFI$jh>c681&9H4Bj~iFKqn3ZC#K;%}+MxJoLa!=d8v6szPSFI93YvP;6h@ zC8D5YJa+$?v^XrF9BfBX7MV-#xPfemzauNIV-SjCCkcla(?v-)S@_c9XqeRf@GhV< zX6b{O^XTx3i3=?F5mx`Sa>_R0+ceFO4YHHPQ}@82O1outmpGPP9~=WjYKhA!rlqn< zRc(@ZNNy%sJMpcSrMxcMI{XZdUiN`Cc#}SZMVNeIW!K;>3Vf-V*vM~Pkwm_p;2;aW zL#Y&@OXv3qZKVo7up~#dL(w#eHQCWUdMoI;z~y|v)cki|fs-e+>1h$ZrYbjie)uV~ z5%joI?&|yh#X;OI08YP6_{eRv<25@$GaNH@r=uIu?; z6{_$C4VGQ{7XYQL<3G1?>p^?}MeAf^4@w660j}9kq2dq(TNYb$jo1$;V2>}*I*4Ig zPv&NXc#ZEx4jT~*^NH!fvwMBQJ&6IYTGAFK9UIO$loC#)lH)!nXi0R9Ms6>;#hitj zG=d9PIIUj|HuD3@Hteb`L*ab3%^h#MsP?ed{h(mrn9l>0#aJ9X_v0b)eOAxw3SGgw z4Jc-nRFvm2^|qxzm3VYnBP>#0I|?{&&xU<~5m>fpo#l0;w|75qazV>J-rY(`w!L2U-+pdChdp{TENe#R1)DRC{Rf_{+mi-pT-{d z#T^vc%topqmI{ys)>6;c4)FkAr1-@NCx|>HuNg~&JTU6sKKS~qB$KhQ9s^lF4$*se zRua-0n}A5mbh7D2fu~b6?^I5$cS;;lZ3EEDb^LJ~_FUar0H0(Vi zRVR#?`>afu20)jx4P1aAdS$$>oqd{=^qvUUSXY_`_0Km!vT=*g6YMqID&Pneb3mKE z)OFs1d6N)qjW%b8uAOY`($m<=pRhtZB*j!0T^xa+F(V#9h^IHRCo4vdB`&0s@sE|z z<&=hknq+!-4D~Sg!ecVGWEA;8~K0=l1!K!rpg1ziBuS(Oy)Y z2K&S=Bn))ou7)>Qv*KTd8s@7H;1=$jcK;VD5iFf{TX3p(+g-cQ#_93WV(6swz{F%a z6_9GB$LX%=G1bhE^7jkRHcQXU&|mhT_YYWLjalrTk65Q7Hx2l&1Zc)1ztc3owxL_e zdqxUF4!|{$KDT{vp19?_4yW=jIKB32TkwL3{Ng$8^xIGxUNETRFTB|xfzz?{!l|qx zJib(Z|2;_E-S}$d&$k9ege!aH_bfK+Sn%S_$?)Iqz{c!MdZav>Sa zFvP-OF=z)Z^7**#3#0=z4J#n7B38|^@^8J-dxm{Eu_K+LX0-W0mmb2dJf_l@_4oK{ zBlFKsv&+bs^}!hpp}MeZ2*3U-x{q_UHil5NFq)VV1*Xbg3gS;1_}M#+-x9j@TPrta zs>(0AExY6J{QMJwf0bY4x7D6=_34Z+lE@@j6oAf+!%iejXG+UXen?C1tt$j%MS{3D zo>E>y7D;1s+&a%|m)_G|io*zlDwT$bFA=rSr6%vV!0*^1oinW1{nECuAVF~|6*!SO z;yD0DRSc+Tl{Hl|f%bxRkgz@vNTzJBC8%)zB{g=J;?G|Lyow@zr8j@s;=Bg=TP-mG zqk8^NY6*75g>s#=6`dC;PXAI%{O`Z@pK6J;KFa=oswGY-r{8PGZ%kcp9lTx}hW9I8 zwBbgdg~%_$IX2@;msfyRq6U-1y8zQ>L8w|+sGcgY2`o^8g}j&FWu$p+fVHt>_wV3S zXFDatr}1I9@q>?iaCf7tO&6N6%NES*c+V9oH{mrO7X)2rqcg;hS38wKqm%(V;MqXQ ziQkew%DeKT%!D@un4=RThnYM_1nkOdAP2~Wv%jX3?$J}kNSjBKxhTv-B3>AX_;IW= z;8$z{^M0o9`JM4wQWqu`4pZRUUnICUArTx#Vq!>4jGPHxfd>Khd&{7 z54ZZ(?AlKfa}uP955$4+%)wB zD=MB*@K9@^2m@vk2T9+pS85pH=Pa6$JFr_~_XR&?B>qf%mxzX>5W-yzHcd(1@{Yh? zRJ`+BPW)z~mX#^-t5gHng0f25CcT{GR*K|gCLK!p|FNxIf5o*KR1xw2>;rYs)R5XZ4U+@SWdAJ6^=N{XSmEA{wA_vWKrum0w ziypFBQ1M2LHcv*f*s5OF^=5AxD!BEqJq`oCgMgEcSYT< z!XL1*bH!|(zRSaok_>UKid(Xx_iM*ajC>KD;>q=f^Tqusb~dXtE!hRw|4n3J>2ng}tVEo~|FE0kXz|Kd=~g_&01pc2g<)=< zD@jfTq>Ud>dpubTvUt)~z1X#wX4%cx+3D_0RKE%5eBEqFC_%c_q5l!Zl=AzJJoGUVic~BG7rV|6!EBCEGW6t zo&zjo!w}{d+fffGT>M2%qyDc@$p&{UKC6e3^m#nd+nEx_;btc_+WRkTOdeK6vg?fh zl;jOFJG1;Z;a;3@BD++rFZOiao9ihs!`J9AeQ;&_M-Q!vBi!*68*bjvun+g$SCP!0 z+=;q+TVk$I90Xk-QoE#XPVs=0=%P9*58;>T(}5r!0UQuFNQ`AiqsA*9^bY>cxQ{UJ zUGK9)IysTrf8~=V&}w(xr8NZ~@%_X~GFrj_-psw#&rXh}Gt7|CfGVvVhinz-Tx(v3w z^o1VG$J3t??Hyo*daa!c6^2Du!S=xV>OEW4A-JsV=g&~dc$^%cP+B~n>eHk)=y2GQVK5qmOOR%OukTIyo z>+j_+s0r5_B{^dJQM_{Sz31XnJw+}e%NI=lMz5{izAQPLZDV=>^9TTI$usw^7=nv@ z?Be9OY*P*IkLIUfl5i6A zIcUBP0{O8t)K*smSGMGxuQ}c3m6vI8c*6NdNw>@Q#P(n`B+mDo4HHsrzRJ(vYX-k) zmx&&KK9%hASN@2qX(glX~i0+xmKwlJOBxrvYPL7NH%&u;I@gLfvwfhOE2WdZ4MD zvyBuGO?Je@ex4~ew$49LdXG?2TMwVwE2*V~ej7|QN?VU~Y2!^v_SnRq`oY%KVDh(K zNs6TuhH3lJi0FR6A8G`Fb~mN>Vv>E@m&~GNX-g`^V@M;ZyYUj9)Y5VZ5f=UFbv)K) z?ce$GZRi$g+mD_&gS2hI0oRhn(VyO16bh`$VwvCHI&Q+!F^Oc(WwOAwI^z0pZOj_l z=Q7=pL66*EJ|E?CmZM|Sg?z-0T$p$hh*-E!SZkCan=KMPf^ooZRW~1f=T7sVT-9+$}tFI$s<#OO8*LXr+?KsFt3>?_T0Z(Gjtt4dH~BLcP~|A!0$Vc-6EJCic6b} zYUx|zfdpY#>3v{1SsJ;mtu2DIEr<{Di%9!ufmAV`z;mp8_nk&$-*P~jAW~`^eAh8b zr+58VDeDkt9&HI&RaFHC&(i$n#fR43r@E(35xeaDc6S=0vnB-7X{COpvpYsb&Z2K_ zb;r^?4`hI4HAS_ouJRsr)J*4j;@*!Ctp)mkN_AoE6$F;35Z81$$;75`3bPhu*61{{ zFaMF$&1>I&@5d;7>u*v25bcb;0xZD7aXa$h5!aU<6gENVCJHN=@k?N$x*M_mM!Q1Y z6wYw!@{Ytp4I#=aLz-}6E-g2tSO}V}0dLy979^l0;Mr5lJ5V{;#c|Mc6*v#{f#9qc zM)!K2%d%q&iJ}*EW-SQeNJK{I!1<-5^A_Owt^Y|d^Rk0hw&mjOZg~L|R?O2W8aQU* zB5Y4~ynLycHNLG#woA>qIul1+EiNy-c}ZJMTQqD8cwpR)qJd{Sq0uhF8UQJv<{_yh z27pvZCLxno%Z2M&twzZ;@ zhVQ;jQtR9sK-9%aI}vH~Na_ed%CDqDEyRF_R{3eaVO^6Au!}SuI5`b2?cVOMHSd1q3yC z_%_McWZq&SUNarqbu(nX=jTjnt*oMW8*w2&5@f}6)<2XrPhZA;zxa}h$UE3<&o%yF zjxOHm?|r@a;G^$OJLno7I#QGMlx%H{PV-5#ZEVi)9YaG8tX92aitg_TY<7;A)TBvI zZ*iXo0|mb`*7@p+^B~PiOrboI8Y6I0D=al>XJ3BJFOF4>2{-3=MiZ!%hS!j@<5N2E zS0C)&^_UFJFt@%qWE}dKlWj*&4&+bfWk{ookYcRt;U&{q>*{&;RTO;X(ky(RKw)?3 znVyg^W?(!EK}54d!StAYF{rhv_?i`VtnL!(^9D0}Z80?Ag$w^Jj_B=#oGW7v4UpZ` z6d7=knbqS&z7JyXPDzf=bF`C<;%3TqJW(W(6%*&U+y{kT@w5m$Z+N$J8znpq2Nu_3 zUN|#p9t>ZMn?P-i&WKDsominmz^8IjQW@Wz8F+za)ar%}^;~~3H&<4g>oRK}11v0e zL3|`g7>AOL_U^#CT^Nh&3Z(ukJL}X1okb7si}aV@#c`@NTM4@bNXTjVY8XuZx$B=6 zJZL3WBp!WdyX+gfBNK*jy_hc+fP&c(fIIpucC+y_lUyifdH?HO%V*%rAusp9=H~j* zMS6@^dWJ^(+o}zW-5L+8z9F&1+7Cl=WJ&k<#Nxnz#B@tU5r$$21&r%b(*@Av)mlOK zWJI+0W(uF7M&-s4`3L%@rko!+kpcZKng@mF+Y|Lsk41E2hxxGmvD28FcA!^}>yGo} z#3#+vEmrQ{8T#!1RobE7Xp<*?o|R{Cd$#~Z;MqLoC+=k2jO@j5!0IKe;bq-rL$a^3 z0jwQ5=UK%eD@{ggO^Fbj?)C4=F#Z@9m8#)oYM@**QF4Md!x3b@Wa|AlRRb6@OIB9q z1Ic8Q>W(n2^D0||kl@q4_m=q~b}xQ*PSP*$dlkzJwB_*j8^N!#{@{k?#DE59gfj%Kb4v_xGlcy zU0bsKSuXWZEve*cTy%h!)xgq?%j0eUUCtr^;Td-9g8OhvQqxKuQ5ZJ;QpS8gkZ*Kl zU_QZZr`STG9b0NRsJGIT))#JuaIT|yPM_4irKCeCj6=;mbp}^tz}rPLy?7EoVO~?D!Qd*JNSh=|3^BPzjJAekG)W(UuBOeHH#)XzMBtT5uI_5AMs9zD zZZoP*G)`kcc8U<;AYrcvZA}<&vq+dn(uJhB1QR8Sg6Mm&ebnL$Ib`B{6Kt5P)TeG$ zJ()gd6Zah6GY7|Ep&#{<8ht2t>=^NUJw*M>QO)IFS6fy8MDDvj_}q8hHtHgH(!_bn zta-FA9oYnN-W-#GCN{CYmb6QYrCi(T_NS@ONpt&YfxaB*tfu|eA>z^GXl*s;0c-1I z3v#Z@>-%|Wq#qb2Q9pRwM}i$DHvU+uAa)q0{0yPH?pET2(syzQ`{W%+QPZyfe1^Bt zAfWxLqYoir0ubtk=+byP#)PG{1pE}07TBZtkcgYqFx?Vu*09Y~3pTS!y9=Wg?_-6< z8BCP-^%7wSs$zIVGq&%3f9`b;)(U0L)KKJ9>O{}iVgxRN<|ZRVm}^^mASr$U7x>gV z6J_8U+w==A;FX@a1h1I28<0CzoscZv4@_Yx+ciwENuC$y(RZ5kY%B6wpmSx$`f%Dn zhv9|FJ@_{J>8EM~a@YE-RPo3cy(xFz^LjN`GPD$EYLIu|j?6lj74Y{;`+!D1;rHFb z&lmatG`l|dP*$sZ^{??I_KmYf7r+ov9gPD{=dFMpq5@ZhIQFrax)(bV5N#kwfW!1A z4t2kgL4cP5YD=*Ym_ln;(~9t_@6AeQMCEizF`at$YW1Wb&jRD3qiUz&ZEkqJTOM~} zXVtTDnqZf^swe}Hbf9spxzxMUzRG_$leZ1vlR6(cAWV~BXpzTWv9Mo2rtB7AJD-5n z<;tpAi5w@apM46fVw`uNZ3{BQrlhnkDZQ;f~R7*EG7LxB*y9Ax#?XeOP? z{X%iLBDgfQK`)^MtT3|U7aH5+UO>dA8dZrPy8`Y zV%z2#+Z3x;zuAXLi=dbq|LTCJYUb>((**k{*}Q*TZNUpKf%^?*O;-GFpjYtrFUO^u zhrmPnL@Yj_tI9vszChX!Hi)XvzRIM3j|D!cyFKEpeJ>0Z-W%e6Z+{j3(Ph32|@sXpdH6!H4r`C+S!(Bc( z&`+%yfSjHha{gCqMn=>XzF)%4H>%c*?%IKdHp;+I?<~LYQ)`B?sx@QZM@W&a(|@&Q zh#aj%=Nw}fvU$US6!@~V6|0Ie zD7KA;IHUf$F~@Z1NZ}spm8RcJgz;L3*r39lnW1fj6y^)ywCR-#aGiX1USPXD11jrV zq|W_Q+0gh;WdoQ%l?EZT?MDtE^%BAx zxnKLWeI@?u;H-7}b@s;RN0U-JIa>xEH`;vus>wqp^6>s!&j6l5M>jAxciW;sV4_hE zkn}5%@rE(Xecvy8AtUlwW!avAW)@a5kafpyAYz|UnyA9>|5Vo?etq>QOnp8h63pzs zF-Q@Q91yCnjLUAT` zladSaXJSUrE=o0R&|>&@oQ*dGZI*RS&iaF4~c zR7Bn4HSnwc^prW(C`(Y_gFpy5e&EepbkC3+UA7)#?tFx6p=exXw z-!g|5Uvo5u|&7 zlKb6XuEzs2wt*G@db;7OM3dl0iO}t%irFZm)R0mo%UH^_6E{fIROckLTApSaAnFi3 zaFZ=D_?j`_U0`fcGn28b&MD!}Q1JIa)ecD9jA}kMp&&+V)hfDz7)=Bx#=h#ANQu7L*?_N`5Pi=gpJbz|mK)JsgLgT8N*Zst zwMc~086!BoPhB`1XO)foQ6~x#KM^gc5iE*CpNoc5u758s|3JDb!3#nD&QXvhQm;q6 zUsK`ui20W>PCjV6F9Zk!v8{OiYy978hJj~^1AG{JS$0I`9~UogZM;RvL^L_!h0OUz zCWPcO#qfbAe!+@$*PqjV8rA=YXX(`N#H(}keypjMwkeT)c|M$oSZ+x+6)9>XnU_n) zWf2!=bb@4gfj~u)_>z4;XKqQ81tBl}n7OneAsD41;@BZz)#<7o@8jg>pv??inhaaX zab!Tb-6f~?55eA^NUz!+1%nbkvh&TIWAh@k80&cYgaE9G7FF2>A6P_bwqWEZI&f!u zpoeMZ6kb?pg(`e%sVH=7JVG8#=jF@NGRSexT~$4K=7)F(L$+?qIRqY=nL7e3v`gZK+D~}Df=rz2+{0h_z ztigSIx|%sN8R9lD#PAt7y886K^r9+T$Dr(zN~je?q;P$yg>`^#G*`LD9Fiox{jUW( z(GT3=`GUR^sfJ^}rNeM$5o4D}r?t15L0(?m1)Bo1EpJab>D$KbeRUiXY4IVbh03?Nj zLoHQpD?4IqtUuq~CAx#KtdT#xSNJSDuHz9=FJE8fURc=?@*rK5*TWT(Ugfnkv}xFQ zf08|%vS4>TB8Dt|1|$yK9UunaaOUJVuWO{Gxc2?5?men?&rW`?rpy!NU*8=!fqPkA ze3N?hRXXmYV#ObQc=2sv{V+j@kWx($peqp}K;=kUsmEfbVY5QwyUZJgc9D18OcTzO zrSLj`Y|xg1Cum`<7)I!1Eydy3P4+0DRR~qT=R8`z(6k*u>K$-C#BK77 zt58z}Y70lV*NqhcAytoK1GiG|?;nURf^DBEyKucOKz=Dpr!kUgN2pem(7I zJ%V?_5n<}7Pg4sYu?4|*{gBXpG`s)O$C=DEfX9h%V|~DlgNSUPPtVNZeB!IGEDL|G zOTc&2W+5gfA`u%OP?qUmEh8~9BL$`pDd@J?mZcj>D2uM1Cwp*1#pBc&G)N_zvXit4 zZgod!t1n}~YH(jL$;j!9O%JdBT-wo@!QwYr1sgJAX7@{)#EjpPJRjwqIxDDH6qe7l z1bV#@#=80e&6E2uDHDMUumnMB_#Ujk`{*3j+;T3|=!?0J-S7FY2b4nM zB*HCj;!%fvO`C~D(e(&2DMQk5p#RI)A}D9x(G5x{J&560yCb4w-`KL5(C%?G)pLu7 zti+mMd+<(=mBbSs-PhaDX3qkisI7CrS`^y%k4#}J(6reVtuVp-U`)@g zmfb%b^dw#W*_*&L1l8G~&0gJ>vVq{{($?e^hrb$oNYb+eenCdIaJKhu=WoL0!Ga%( zD!U`B6u-hYN1j^yCT{PeTTbx-9n-(wr8R%(=EX7P9YzyR^oj#bUmUUMV)rZ;@i3Xu zI)O#qohP#od)KjuE5)g`#p?2IOTV~og}drSy5=;fh-hL&R;N5hSfTXKbl44fyZn0(t2#^2#+ zc>2uplM|)l_*xX4Kn3xNo1ll!5w^g6YgN8i6fvR~a;!7(QUc{r0~K;mI7iI0o@&Q; z!v!?i#JFkXmo1`Ni;vXR#KrF|V&2@Tbxk;F#Qt^z9egB?+OVQ%-yLNCq1hmD2>>i$GrpDpN+G!1f*+AwBU%0_p7gBz=L@*aiBn1=D{f>9D-j&F} z^U3TEY%T2V{Ro8ZLRPv7dpbRS1G{2Bjfab8XEov5EMp*GU`3J`Wc)K!jVb zDI_o|i0^LT7#$zV^971*Rqe)=$PlrdI>QN9hNhXZSvTVplkn?Jt4V^^@(b-@!RKQb zbp+ab=TTn2Tqxg5Z_C$SnEb&3lnkfb(~^ZgyH3WvTWk>2@BDB;SlR6x(E>{|wjv#p zDscw=-ZKN=mHF7q?;L{qBHu=R-uS}_!v>xk0&h#3{qO#UVhWuL{g=OC!0kp!`1CoH zZ7k)2ueNvehX5nsZ-CE#3b9)|MKo0vi{JdfVROOG8e&};d~?J5iqHp{l)q;d!cfdM z!-qr)hkXhTAZ4-)l6uI^$s_#TQiI?zWw7s>F=TjfuQ_pqu}OQ&67KABO-3@I8_yjA zA3RS_KayV>E8bu_AOfBc8#t_Pp=(Yt9i}7%EK_8XL{DH5OIi#;{c`} z^35zEoeVj6+=5CIOyEQGfAk%c`}^O^qa*hvxc;y)2d!9xiTj3D#S>|)Vbj|Hf4I2> z83}+-R7B9EKVhP|F6_@t-1!C~nxrrRE(VnxZMZA^7879v%pPMaHQ+%R(Xds&8z9fe zK14oh9GpczJRIW(K_Qce54Srb^t_Q@*>tU+`aTwnu|6pI7K!o@)deDzO)Ws* zt{)hYYJSUz*Fq2QzypR=3>Hs2vVT>$3Jwz4R>q&K4*a$GcrefGetcirCfwaejZwZW zT8H&l{vY8Gt0?V?m_~RIs{naoHUr{p?Tq^4=pX%Cac#Uo#aF+604|?H%G-@s0ZzSq z?B(cBsGU;lsCz_5(uUIH4R*fIn|{iKLfhs+TwT~61>8n_81gCB>usKAr!$7oBzc4< z)RV&+p&|%h6PdD9$35^P8S+r!M~ZojN+|s}Rc7&SX57tsyi#4T3x$7qYtH`{&4ht& zobaL{^a>O0W*p&x($DH$-@%d0g&Q?O@v#?3P(uyVy9_J8Y-*rz>5rDeNJ@gBX5|P0 z1_LK~J3R}yn9k71v@~SJmLxoHy2fho131HnTNHho*5d7|E0mfb+$b`_biYdZaCH9r zTs-*MRZ)A65xZ z+p~F5ua8n6(LOtf=v?EZ$^vI=d1;*ZaZRjjXf9%dtnCZXYD@q1K~l1gxz8AI4G(@% zIcH<{hxB25i#c$$fOSlY<80@L@cY+c45k03z*P#&}WJFnpR+Te$W!I~We!r|_I@ku-bVsEf z1;AOl^0yK&&wJ<@E80POuE8l0h4B3L4-lN0+sPGxlL);Db<8V76%Qw_O!802CeP~v zmO@w#9n=lUR!Hmi)7ZP`d#-%6477hg8j5uxhjkPB4315LZ%&SYa9qM)oG| zMyz6&tldzxx}3P5Sw5=;1kdVHEI<5iW29mE-H+Wh{E&K$K1b9-(T3M0tMB_FX#vb3 z(=e&kn2$&2>QfW%_r<+crba>h!i3wsn!1L%#F^ap!Sx?o^O1@v)sJ2uz)>f$TlA&z zf8Ci)F|wHa(?fte;zf5nYrIpiffMw45%}(oZaHnv(h;|Xo3mJ(J{=rIX2a3qwVJ1E?|HT3 zX4PSPPA6KoMzpM5FKn;pC}#8Hx!cLIA=A=Y?rxPrmV$}scOvXcv(dhJ^_>5ldIhNj zTcoLO2AgS?=D07T?8=D9rHCp_VzxAgukcZLmNz8M#?!|d-peXeCM`1ir`K$f9Sg@P)M;?qRWGDmA7yZQHT$bs8Al;fGP2nHqK<-joS{9&gn z=aWcN8{IF*cEtc(dyA#`4bD)b{@(G*{CtS*kl{ewH8oBNPp~q{oN5bvWg<8X%_q5r zFq@33nD)3EqE$hoLs)@Lrna_SKD&VQz+SId(AN%abBD^_yBrjTH?sGd2cFv>J(zMD z1=gJ)MX9cx8vNP`XFG9%I@W45#hx$Z6aCh#Yh>uwFH?#F017zY&ra5@KaMR6i ztaq5)>UI&NJ+~p`=qP71O=2=r*JU%n5=uXmw*F0_!VRJ~eOAIrscI~X=v@PY1WFtj zBye`ECofx35*4DvK;a9h-tFSmg!_NA?8_{7GQUuCM5`W_Ne6ZRpSn+;)RFx$~ZE9!(Ex{*?r`v9LmUYBw8R{w%iWdv+ zN3`!XPrQ1q?J(hyS+dGEjfzX^c5__a1Ab-Z%R5k0n_57=77@_a3+ylobeW6&_H_Q& zVk$K72GSRJ9z4r~rYmoC*}KPtJ9&g=9CwGt7KN4o=dwL(>5kVF^|?n|!8dkMC7#+j zg(uR=Z|Raf-Lil`dNn8REWW1iMVb%~2OP9)?xHXalL(5O{xa1%ESs3ze0p@%`3iGx z#TXWw#K7MW#cP7~fv~DB7%)EW{-BuiABxv8BU0D? zKl*Q*ye+EA&584#jp>WaKaY!iD67p@EVNFK6k-|^l@IUynW943$ncLkCK%FZ{vujS1RLMmnc0?&&*}PQMY>=$){(@rQgQZRb_#` zKA&mA92#W|y^iDWemar3n_*4BO)-i_^3F|~@S@#E4ocIboYp-+zQSof`6H?g=^MKe zl^~2#4m*Od6~)yD)0*%UIDbi==`=QUsi9w1)w?w~- zj#a1ZWk&Fv=X)$WBr9t~*q)q%BPA(f4138I?`>?|^z>9v+xT{O*AJUm)Z0_nzl=Yh zdH@zg1D^w#Sx+bLvLr8Mx5Y^A5p9=~i>)L3p_EK{8d;Q=ZEc-jeGo@OYjmfew%DQT z(V*!3v5#xId$`MrcVm}FI)q3nk-=fm*c-^2J<-Cv0{vo*(_2J%Jb&5hFHWx{!9L)6 zh}WCd!|pDG-oP|@gU~O*(<=T{62wxRvGbAV*>I-GAqI227dzmmm~hW3i5|$d%SV8x z31Hv+kpv}@KCrSTLtYxnoRJe?hp>mkMYZ)rbQ>nex_H@Bo6lLeQ%*5`fNSI+9; zedcm!)C7vB8vHYmi@Dlxm-thEkq#0-jmk3<7CMT_`+jqob2C&NfzxuRE`1YQ*8FtJ zl6~#}3BLm@Y;tnC*67%$Hw5x}cR$)@nkEay8C+fr?_lkk zjAO}4kKP?^hmvXSUOIY&B-vj}`o@shprzj4CulDsVNVz+5d`=Ya=^M#`|`g0+*)b< z7g`Ok-qblP=^KW~{hL~<=M42gTs=&O7g~y!$#jsogHqDGDJCsfJ2?hO9{>tBce5qx zE`y)mlAI?`P;YDxzX<16#Qbo=V(iBkfbIVzAh~UoZ+JK~*1GYQWP&g^UVA*H+)g%Jr zCk?WvFSJ5SMb^*&S(9=fy#*VlZs{t#FLnh#5|~@-dgAiv#=&aQzTSH6Q`OJnzIRVJ zSzUh7$9VUR4-Y$E!yvnBEPYSvZGCqAn$cTWp_<2cxlgWr;ql?}lXtmwKYt-vwoqM`3#vEyPDIXKCv(P_m(fAx3J?=4sm(A}Cu)vuj^8kOPdl_A`4^?~ zhcy&e)>P|dp6J)W-ycF1%+`yQ%bRF3nzS)ZWj;$W!cz3kMOaRbO@Inwm|<@YRk$ya zFP>%BCDyN=%dw)_i{zE{SelKovMy1ilv^JPXW9zF5s3?ReKvU=m-p*C1$XpOz{SN? z>SW6H@kAHoai56rZ3hcS9z6EU0gW5v2&>>cJ)2g-q-yKf^VN6oAX>~jOk&JEfj*=Ok+4`0}GV%=JF>EP0bOI?3Lmjt#m zzOTyq~SUVoShLsBHcKBxn-NWQR)d&Qrj28)u+*c*V12{cnBFz-6(pJVf4En@fXb$;RqVR_9-Qn>4(B>z+W`pdU+lPD*_EH^k>y` zi+7#O2>a}F_GQYurnZ}hnYmTWYHBCj;%afguNwcQaazO{go~h}bydsO+^(g1{aiq(*5L zf)!b2{7`1&61Odtd;nsSUwq5qqPMKo*ZLLLZ={2~Y$@)%BpFb+vy2>WB;mdxn~0Vw zJ&}h^7Gjz%SJKuU?8aB0Y+`Q>;~@Fg?5~mCuRSYui-A{Ru^`_im4XShWyFs+1~YT* zN6IJmiEP8h?FM|ZBUZpMNV5R=V7D%o3Hhf@Xh{Bw8ob*E230${bg*G|$79b%Kkj6U zQ$t&_RY1>ToohBEY~^v$25n7FjN$J7hy+%C@bl9iAYsdpHwRuE-SLs$4A90J)i@C zlT3!bd!FEA%pj6uM(L}4U*GB;US&=dyjyaa)iVrZq%Hm_Uk(2&5kp(?dpW>`6Z($# z#_SIYsE?Qd(YStyq3&JjF*A1x8MoTixJPke$aJcD`fy^tQWYi&TC=DD2@WACdU7q@ zPnFcF1j+6zun3y`_Cpbcp5U`&cRKcSgYLphX+0u`kFRemy=wYAA80L1CFA!7i#IX? ze*<^_gTVeSay{4>{5riTK;SY94U~@rnv$q}-;)A;X@NC(TUSkdX+bSpgUwB+m{q|u zefsoX$9G%(t+V(W;`q=yKnUnL1pCQ&bQ7y>KIfZt`!J#)TY%gy>b0+YVAIXZbEWN3 zezoeT^4`?bmILX_HCn)!{Cm6JO~!=iJHfHngtuN-_<=UnJ|E~Gp;aWLXsIRc7Fn~- zEgI#@K~{?m76zmQUSnceGOg$^`(W9uP!ghcr9npB@{feh-_uJzRc|~*;2G!8mi%~! zzbzIgfW;!2jGg_tE{2&~izxhFkU4W17hg?Pho1{fS;o31wte$(f5cw}&_@YX<;8)% zLHx;>GeJM+4)Gi{XTDNEubg(Yww~0a`(^l)>FtjX4K66yiD$9otD%#Gh*<4D$1^cy zt-gRRwM*#p+h0oHROAhhz4e-HRP}CjL)h88qRg)3yxN5ew>vA;Xa3AmJvO0AuJr7z znrm`&50iJjvGatIlZM#U0lyI3oEjmWaMn_~92dzu+7sKKAq{=cHJXq1Um8VijJz<%s^V`ev3_Eh61W%zx3;=zUP z`Gob|PDjC&?za6|%jDDFo7l5E51pT2=q(;? zb3OUk6(21v18$eFSfp8Rkyx50oO(RmFNi}!_#^KZNg zC=IuGbH4LUA+O?S6N;<5`g_`UPNS(?o3Nz08zz|BoFfP`1CU>~FrhyKCNb~^D(;`I z^C~6Yn*XcdOGM0cuMsXU%42SBLp{xVYy{oK>$tZ?I96mBn6AFmv)w`M3{!~7;B0!P zH=V~Ck@t03AJibr3(nxO5`FuR?_l-MPv5&r$nG!B~ zBZnGas@qfQkr+C(ZBt5=xaL5LSgQ?{#JA#Ft?8FA*|T6j^F;0_vLLhu5?WUnF|tC^ zo{&tgZdCm_$wy_2-hAhL;--ToSKW~{ugYiceY~sY%$4?GP?k}^k#!Mi(?V}8Nu%eL5U(!nzO7;$h7>4_;{^_&pnS_tupx!{Q zh%Qwbf@uslil40C)pAH1K6P;Ch%S7&mcFPUtwJS;$0ZJ#HYy` ztDT&imN{Q)ZjEsI1tRyj{-QbCnSL=YF5Ym=-fi`(yy*>8Zw39NljZc!iIwWq9q+FD z`uFC6NYGw_XOxG;vyeaz9@%wn49`XwRl%4Gsw*zW-a%*Ft9qyn4K0^eu9zPb0m3bn z0;B&SB z^74B!NzGTD{an7QtHDKh`7}vW_lIeJ9Z{!k?-cmrzAw%+Tm5CKiR#Ny{oY>%?aW-nD`TWtByk%7f9rfUh=7 zVL4O4>tWnrhe4=l}@Y_a~xl18Qq$Odv>(DGH|6=?3IVP-a+79ZV#N6YJ%P zYch~|Ty1zgp;a7lMtWy7>O7HNYKpE2yAIx3R^o1b^kmayN^r-iG}v3iB+bofmZiq5 z6^-DZmp6y6D%qXo_uN+swbgs98*qmH9@9a6lS(pIK8juX`45ZsFrg;Rs^>c10S)-ee@ zzb1|&ZS(*Wn=bbY+{7+f{5*fVwxEH^F)%l7Z~TJ;YjpA3hdWY~3j-yD{e({g-~D zy&4&bATJX>={LAw0Dvopvv7#L&`)zS20K7tJE8(UatY` z8Z1wY3w$1UoQ_xs9?uZO zoUf#nn36u$6P${KY}|?*e@CV80Y6#r96@k8NL(9*^hVzi0|ZO9U;gO{h>*GLDS@%u zK7lOIXZ{JYcpJivgwG)j=EqzIf@h0P+O+C?bvcyzl@%{5OHc}8<<&uSa!}QEX{QYu z9yLUm{hW*S>5y&CV+Id6mC!p6#CTE}Z`9XH~5-Q?i)I7pbIrU6}K zu-N^!;>G*}=&X)Yzf0Fio8uRx32DX^*FK}9 z`q3X*!no5LjBY$Iq1f7i2rhUiFhfF=8yttt3><@>Sia5EpRc2K-^f~iBfK2osfC^T z%|tlFlJ(H9Pd;`{U)d*JCoVIpW?y|UQmkv|b(NKAm8a?CD`SrTV7E5i$s%9vK`Eg{ zrxBwy&z8qx`myW$vlLmS+Na(o(vYxd<-oRH|AxU{HjEn3eR;yr6bi=(ql<@Kx*o@M zQ6iWx=+4?A#A7Yy+na6M5dg=BKT2o0hn&1Nh9z3vbwOh`^ZKqvI(5P3Q2PkXgZDPN z*Mw>Eh;v^ajrN9+Oj7!)X|%iLQ~W?CSm%lENwc@$!8XmhX8B?-`MYEBu;?q_ zqpvu|s8fy-uuVQslq<)^6$e|D0eBvP7Gr87jp=#tda-@*c9C_ToAX~K%6P`lF6BsTEuy-l+ zn9FG#_vkMKqGRQ5wpVrygJ$h&&*)UORo$=dV$5R|9gl?&Xf|8oz4AKsW8h5ta?H4e zVHb4lR^E2$mbtI)5Z`$4igDu?)3t5QW~o%{`e)h0_pN1ePiO4BBR*GO{_uu{K%JEJ zfyB0$wdcH*R>>eXq`e^7He=6Kbdg&eDkwc$>eGA@@;WBa2_`-4X4Dexe*fJpQ994) z=g?&A%DBuDz++HtZGVJL+&(?)7uqO)lc`4vLAVU zyH~>R-uu7{OcA`Bkq{A{_R`!(mI>t>3G6_m^lR^y*Ewyqjc%6ncnJs0YG1`2S$%Tj z+OILd(v`rsBDtxd%}PJL&;=4?=}it}bqLa+*I z#s7k~$UL!*wxC%@Umf@x)vU6}6k>TbC1`|iin7sG;BLWR7qr+efKD5APY5-XCwU2@ zUDNg(z{{fAmowizGqG*9W-GfiNoUf$JOF|m_o=p+SB0Jb$ZJB-{|ht6rvGT>fc>AC zIgtO}%%S>Z=BO&~_*XLr@-H)o_nH6B%)!@YWZ@0+Cm_p_$^=q#y?MwT5vhsj<(%CP zrnLPUcdAK?L5K+Ev5dXV2YmepZ^it5++%sef&WFa@qg~)NcdO2g}LKu5OYj~%Fva8 zPGjP+d2XxZBZe}7c(+SQ+R4)L0w~_)Y7S7eyq5{0hSVeO%!P;bH^TaSOzceT2P{tb zkABYF3Db7ij((l=;rB#a%ES6OsIU>YTEt;1S4)VfZofkd%&^WPG3~=juV0C?oJo4W zydtA4oy~dc{3wTUu8x^=H`Z8KJ`YyzYYKasolz>4H*OWl6c`^PNV+j3-9CrXD5Rj; zGbYLyL7l6f2J;bI^npM(Ipk>mJnH_|o>lwNfR`YIc z64Z3_)RPIMrKcJcT$2`mOM4+7JiXeRNiX!$1E|1KY{1LFu@fbJx+zizq%)@L27{al6;wm|c<6usvt_&F>MZ^_(t7HSfCGM@Rj2T$LhvH)(5cluut zJqbBo)w^ajwh=h)3AO{r0f*8X>D3i^5EC~3Zr4g%S8_+_SX}UVz2!`K?=8OiKC`+1 zhg~FH_}xI7SMx=00_*Jh=R)+OW%}!(!u%15Zxo zy+L(vh>PDmUe^O=L~C^g{0cDTE9zP}fUG$sGcAal=3#fF-B~!A|6IK4>;HGKu`A5RZ=OGm7OGN-w z1>`(1kCzlO4If#g%0g;?K4&^^023OF;&!l>34g&LFoba90oZ~s4dMo4lPBGGEI#Ly z>Tv?*;d{CKxj>)LE;|QBBiX->ZkyC$5`S^+QJ|k76@3M7H=3F=Gs*}|VKscsmvp=joEwTpjK3)O zSV&V8$8;O(=r|I(%v&7UDlw2F0TGH{Av);L=wUH9nqZd43hyv95dLN#MAx{KW#^AS zYx%TB`M?DZR#f%430j@aRbR345|Z7PdXvg^)yZ3 zI$Xr%>B>-3Zxdy2CDpAacK>>?BXhP3tDPkMzEwD9zuYX(lO3*-UNXdkRY3j0A7c8(Ag21w1ov4it>p07Ow_hy7ERPsO($kO*#H}j2_E2Zd_e)LKf_!#15U(5>=pW%=_ zU!F+Q`W3S|d?8!tamYy5FP5TyhynwOSaA=Sf-5TgNY&rH3Lvg!j2wPxyviIC>&@I} z4IT}5KR_d1E~X*+kvCys@kvtPI&q4ze!VYUp@(EqoKtqBmAgi_gd6#^KQS$2TcVmV zy1tggGyvL^>Ywi9A3nxN;W~!g<(}7uwY^Ws{W0KYi>>d*2<+(L+}Hck6e-@koRgik zgA{204ZlM7D=AmZ8(d}g@@a0)MfKCyZgWLjn1_m$k96{;O#+B>wQj{!!B<>Svix!Z zt-yrWJ1ukT51-wx|4U0~%jlo^M(If%k>;63$GFk`ez3fS<*~9gSG4P9@@WRgG$X+w zMP@IsMOK$apS7H}XH+~ZY9pYT9EafMGvM<(rfwSF*@HaevLmY0U=h`+WP~Z7-+0AZ zW_svacHS%RPrv9>1B$o%U1&SfqAGCekZ@#33U_(EI`2a0iY9c-?pZOekD>JhQlNw` z#fjz7vM$q86U67MlW%;4B}Nt0bS^*eV3dqCMwnh)(n$)|ZCa9dHN~40?q-rH>o5_v znz9VDM%)occD2-oAOv&&D;$)sTQMX7t?@fIW{k^TKz>l;$%I*k>-t|eF# zYf#V~a`Q3$Os5}`zm6Oqr~GNJKmC?=*6`eZFh zsoE@b9oXxHpz)ni_g8}j_Cwf(+{6gT>L1l%2ONE`4(u5b<@WB`NRnDbf8iUS*BOUU zN2SH)b+TL6Z9drR!=*O#2}PQ-MRal_UfcI-u6xkg%Bmd^C7$WFb?4Hj-J)K$O$;>y zPjfDnEh#i8E?=^J=%lx+|Ia{NgBwVAQUOctSO4!9UNet%iRXKI#2M%Om=N*crJ&-XaGn#?*nKqkfYBHaSpqoted|3#y4tJ8cX|E!; zcjo$tBU0ME&T1LG;`Qpni=?K0K=uA43)2tLt~zaQD{)Xp0LU(cX0%jZ)S`M^|8pu( z(>9xSIn99VmmqFEcL`0*;sq|kgryiMLHZv1`Lnz(AROHuVeLM9U)gv!e!D@}p6xG; zGe<|Y4u9XhP8fNd7~!+D9suc(z~EOdBBO0bt=KTkVJOx6eDiTFL*Z6kvaKbJuVrKN zJy-J2z)kwQxYXc%PTypebQn5@8sUFhpJT4_PsR)%T%G=^&Md{^=ls4SE4d!s=`E)) z#4VHeCC>mYAuY0&Z-_DoovR?VxD#4F07}m4cRwgT@7>gKZ`KV*1!R*uU`~01{Sw8r zK?aK90*{yzM%bCR+_~SxJ-F3tY#0jt(gBIem}_1@+Qm#b+qW7OgE8lZrN4h@m#N?1 zV9M0QSS&Fso4$X5F9G%QBI%$Fxs8Dkk@YQ~5pNw`4Vi8rNUx_M zuF*}pY#h|-!eAb$Y06ku&|u_R=OzcN`aPsUiw$Me*m&!~5p%px&>!9h<`97)7U?C9 zLLmN#-*H5w!Zn=D9RI#P(_Q^FCn4H-9Y)zn#5xXS1iutq_BYJSV3ar78bO@|cV1r_f)qT1PDe}`E@O%)I6-Pv(Oy8K9`l=ueHO>CPGEu9O& z>qRea4%?QDH^&XB&)hyz-}gLhJ@Lk=gA%5{hn7s=mz|9Q@cQ$~fH;xW)C8g{S57V7 z0#Ym6hnHHF5TlX=n&r8Rco?gSZBXcSdFc?~BOrL-LI-eR!u{Czh?w?xh8n^ynT(z( z9ZM%qbW0vy0Whpij5^U{&7u_}-9Ms9>_`BQ5e2r$v&DyznG+W!X5DL@>q!qC5DjI{ zKFbPG{y1v;DB?SJlQRF5`!8AWiiL9fnx^H170F;VsZa3~urvsoM8+HZ)sOWNYuAxs z@+xEQUnC7SZ5EI;`pi!;)=?Wbyq3t)Mvl`j!5y&?0oa%jZAR}6b3A_7JaNq|LxM#^7l)Vlwo7aZwkD|A} zU4GH*BG}0?V7CG#P;9_+Z!pzCW+pT=2{K+pgFUENz3%*Zc%$`u2lOl6eNEJr7XG&; z!F`1RK3SDBlRvmbMR{<3{U=xB1R?6-D`}kxK^&A~VRmR9At(om`F~`{c${=G1DbdY+7q710@Qy$Lz@n+yV-&;W==>agWCf$Du6TqOvbzl#B7jrpNoL< zW2vIC8_qI3<~Q*@h=4re%gdQJ!0Ky#%77x#x~)r?BnS~bkMJjfaaE4$Iz<|fxP&$} z1KV;`{j&~rut;dK7dE0_XY%0Q&D|rViwQScOiVTtSkbkvc?qE}d3S8Rb|r=UuAxn{ z_@afHytXCs6rp5b(aig^NHcX0BJ7CBSWq{%eBI&DW%AH)Dkre`onikr?TE37B zMbT{L_Qf|s$cn%g&NzBCXl)d4-JO=}9!1TPdXkHzJ=sWC%e}r#$!K-36rodo+V@H$K&l?KKgr?^k1YOfOzH{bjC<#hn`4?;QO$4n#b3 zSgeYY%F+tyalPyE`3TH774(B{cv(_*0Fp@_q7B;0*28`I4><(RZ3$j;Exd z=D3TcFxbhQ^)TR9mgW5I22D*y;Mi|Rv!a{}(~ntrPl24Oo(W?|-EYf;hghG9oO>yp zJ@Is5_jeobM74jN?vQd?UnKu`0SiTg8*8(aeV5PiS4uxELTO1dA_;;X22>2^M=1MM z>qS~iU>s5aY6Sh>0KVn)t2XMMkl=K+vg26DVK>0jR0&=)Ux3+Du@EZ!On9e@0wWw@ z)-|E7$aC>UyvIj4s`4>Yaa9`Cs~&FX69itO9&s=hYf7lOBp|n_btW7HexXPxO$opl z?wRKbd{S<<2x_N)ZvuG=#q*8$N1Xjg%a<>vV`IG4evGj0949h%7*hU%p03J2G>V5E z%5n30*M}u|ZCKn(>rkvfS4gMS4W)#mZhYyLE0nO$(5e^vYys9IDT~ND=iP*Dy+p zA{SCPH|<%wE#^+n_t) z_Zzvv3)!})zny0{y9nv2DtI&O`Iu0)Sm|mm-E}eLcJ7z%1M$M}Q?||7AoT|0u#vV= zgKo9Fru!}I$}4mOyU}x|S0A>k6TlWc)>L#X;_hi(Etaq=TiO!=v9u~lY0zx(*JDm3^-fjUxkn{(HjUJuut35=2=Yf?E2*!XkaOkE?IrfVO7Zt@ArHmqu zZAaJap>1%JJ|tbI4W?GDNQpDEdsJQj3dF!goFYtb;__Y+VSldtC_fakLU< z^xI~%O~;0KlDRe_h+co)uU8EUvZNp3k6mMS?5ovC)K;bTPHgLXmj3za;?2a$C*|_E z3pTfbI%8=3ZlANe?H~W06y#LTs_8I)zAincT(Ob|wJMpsGAFtY?O^^7l_1Oil@f&c zpOhd>$TakSuLMEhwBsCva8-QfJ{a+qpI{%|JU z{5`mhXbn}7DVpw{0~(rIZdgtvI-?`r#=mSkgz-rAnEJvP;N-RgFN$QmAQP5`@A5(d zfqbBO#67^26%Uy~od!Oq1s|A`HI&Q8O&zbX0b(T%gO(=!#l3K|6jq|o+mx6pTcc}j z5N0>VA~3Z-)?gCiSKHYnLzYhSDT%58L^?V{W6ppT=a`nhIYqT#v9^G&m9*|s9K<$6 zEKJ|-eND4}+yL|<4;dc^4VfmQRYQdErT0vtSg&UCFC2y`X=npCHTh-a^M7FhM63-+ zE$W2~4!dU=y7U~Ub2_Q^AV=S_zIC+XYRgSBo!yYbf_x*P>N&`_J76|?Oz)eEv5psQ z?=-fK$nml12)G)O1_h~8#q+d=yw3b%XooAG?Yl}&#h-A8gd<{3hwQuk>h(Lj5JM}# ztof?^x%c^{RPZW_C;x zfJMNfI2qEhSW&U=FKmI)LM^Ma&h{0@eI#*@wW|hFc0wLDxf4i1I^hG4_>=p)KC|z& zpir;%Z;SVm)ACI=uguTN!?|Tj z_7yZS1v{TVg&lK#vUkWcu~HeV04q)C)>S>lX)_Ry@PTmk?CB;9^pk8<3xDli`AR2% zA0UcBrbbnUQi)k4JzP^CZFO;(w89~+tevyzjQEG>xzpJet2b@oQG|)m<)2hf8mMp3 z%b_(;k>YT+PK;j|{mu7xgP0&&qi9mR@I&dW%9^a(%AeCV{VE5-(v? znso73Cb9my+;3UJU>j$Jyvl3gvtRQGDOR&uH6TH0{!Q`=aUcQvk8b#3jE#l4t<4cxNS$mzt6o)8uS(Z`*C~w}BDgr(bQ?SP z#&2oD(S?2Z7MBi94}du;_&<#BX=g+=dqK#th?nZ%f%Bs;?If#MR|x7` zk;(=`S;`WSwgjtn02jmN73ep+2-qutlOSh@R!yX70qFPI^ysrH^RKcG#hgFno)jf| z>ZK5^VwlZSr8_$~(!jbHa0;2V#)L)BWXM*eV{5DV(8=Lwrt}yzLyk8ITRXg?-i~xT z-Wh#4X>fXF7gf{~8xEVpR^}oqPn)ZE3;*^iddNqTfi+&aN_bTT*pBFg^4O8!UFDtK z?DNj|!#5KaJofK%mprtedlS*!j-ka)c`Az!IhG$tcKc;$CjC$}I@`gV@1-8e^s!M* z&bFtI^dhpFR72Q$zff&=Orb|VIhe0yQs3xa4LU}Ja9lz(97~+Dl~ZX_tQiN3wu>G~ z=j31J5PC{M^)0 ztagi6Q?ywU%g|W|P?XhJ;`mRI@HTuA0WPs{w_$MNL=< ze=RZ?E$}f-6a5DCP{>G>aFp#ikcGJ%;9c2~mF1{&>IFU7B1xSTN8?`xT?_v`B zBk7IYy;)ZX?i^i%V>Yc4%77E?iJZ~m#k2;1oIkz#>_;Rig`~A*(wewM|4gk~idvJd z3GG2;(OHAl_U3r1#oteENfk$RT5t1Kd?3yv?$^)JZk#s&w~pCkNE5K~t^?ZX{++xS zr27MQ37AWLEYrlT$#;$~AC56^jtiJSTo8V)^tiJmfo<0&lY`xN@^-}Q+`Z8PkLlNa zwf#_o!Og-^U>{^}UjKc-@_mjVjjt~P6Xm7N&4MDvQ4fi4taZhJkRa^rpPk6xbO+{! zS+)+96y#Z_8hmw~RlI14O2j{erkdetnmkjCvM)6LSj#tiaivg_w3oh6Vz~R zv+IH)X*4?UmM9;iNmE%_6iyR&C z)av24!cyV5icR)mFJPa!C5od7QJE zO8ws5$)+!2GRKRzoE|JoKgCa~9C5FJ>c(nNtq*Iytu5CdZ-D*<#mM&>hu`6r&U@AU z!IpX99C`1q2I2jxJMtUgQoZF2!shwDtE&z_=Fz8N`V=9t@eBLxoBm=e#t%-Cx|?htbJHm>!AV^2CN8^P)|NDnri*7c$4t~)_?Ptb<4+Q8CF zi)ZpUuY=a+JihJ2+Ma=>>8Mm34S!XgD++!#C~|mV?yzM z;c&5>9;c(Dg%TEKD%7`9t?veE(Wf8o0QyEh!_;8NBhekj(J&X3p!#0SNt=#`eOqk0 z(vjEZRt)pse_T9f9wda7TSOkU+CcqO>p$bri;2DunS?4Dl_?{CRoO67|h!d?Us%Jrq zbwW-OUkr{Iw8?N^_Lcdy6EQwnFpu#)*(WxVkhzB8R z!nmHWj&1p9Z-PS&Q`P8`rgn)0_TWG|xpQ^Qc9n0NhD_e}AiiII_PXjAMy(HC6pX?y z?&32W#Pq64yrwC+L->$RXiHbW1r6xtn$OcMv`@p1R{iaD*mrm;C4I4$cg}6~r6UtH z(^*aWU^u^W`T@d=O$#CuNP}6kbHyBnn7#g9p~HEjp;O=(c%!7vARgfF@QOaoFG z;vG$P7cHwPTwb4M^!05fpgPx*X&iDJ?=;w%PC8%|A4C2Ck1(ol_W>R|WJ{mma{CS0 zDayzR$-4}G`9cmM81p8Vw3z*)MZ$eeab=ngG{tHj>tsL;4eDw!^}UiHQWQ{yb!mS= zF`WNEPq~-;6N+KuTI>Fz)Wotjq?}CU=27KfYW}L`S%G`|myFuwA_Vcn>ib5^xRkOOw28{Jt_OuWz+4Inv1LqirF7Y!Gxhr4aPbo5 zt!Qnpa-;C~c4%a5N1dPV|OdE2Db>m=Bsj}rRm{!-F z6|BhNH$T6Q?Zool3ydfZDSj6bsJw^Lj-E~_#6&zGB9CU9LYb8aq%8&_#7v~v`*<@& zsi`f?1p4N^EGe9y5pbAkjZR2US?2O%+jo$KJ`Csc5wAnfBT|q)6H8->@oB2&12s=m ztQ_J+XDWENK3$WWlMx2t(SR4K?pvF7cJng(n$_Z-#|G7&Obl-VJhfBp;!W`xnw*kd z*G?KjZiP&@myFqJrK1kBE7X3pb)tr0*v`HLcZ24q4I4l`w3M26#K)6u&saDN{YC;` zuAG(+6Qj&buNFF!m#rFPAQsR(=8yG}QZ)EgNfN;FL|CroNAchz?jcEriaZR#dnDJz zmeZ!Ru4i(=^P`_bwbO!iW4X)3r-w`Mjz5N7k(bY)Z0G_0wVIddH?uFza<)U0i?SY$ z)^ui!)bgT>3dGStW%>@⪻H)5o^+EW7Da3SJ6t&>jZ`TYOJv9VjUb*13#ZWrD5MW z#3;(G=%N}CDrT<)JSuv~p-BS@YQ#03x|@Sgzc#6!Axo~TP35HT8q0Ch#nC?i&qB*-@rah- zU6)(|9VHO7eCi)DPu_^Bw|i4_dUjx*Ik=V-NA6U>9ma;aF8BWv3@jQGQs0iA7}^I+4I zwcwAby5oWE6N^GJjj@<(v@*2UsY58|btHF0)(XcR^+mSoJrQGPKXEK-Iqh3~KmHB% zRmee`4jtqNg4D`Q?ZkJ^(xMMlt={ZN*>a*f5oh<>@p-|~`pY$XCgh)u15OBlPtg}- z))3JMVe~NZP;>Y-9;b^baZN-a;p9V1ViOvl@1^nu>TnZgY)ko7z|t2Z;Y1CsQs}0>kzWw zwMFN(#Q^2=G!^LO_5mFJcR{_Gw2=teK(NT23%u-A~8AD9?w8RVDY%x9mU`kD?GdA3mKIEKBgH?JU!m ziSDoEp#jOm zUM-YseP|fDVEUsTNYvIu_8XN1x;m9ati1#uj=A{Xe;8jWrVTvg{25*DcHa8Usj>;i zdM|# z5toMyf4{>*hkpw{2uu9PUH93m7m&7`@NX2<QG zB!G&1_FqlE$)_tto zTQoJ%x# znyUEab61I>xY{V*`Rc1n!w_!1o>clBNIMaKbo_?6|2b3bt5Kx(ymr&SJN3ic^&fPnoO=b*ZHp=k05%EuE^JWL5(Sceb46f6Xwyf@82S2k2 z`W>v#w`%kip6pUIrw#5QDBG1qG=gK99vkN7AJjRuC-*2D3AWh_tKmE-{p?sRrL(3lS^gTk$Y|H55n)kPvZ@n}wa{ z+sd58sg$dxbAY1g4wL0JY1VCRS9EA{%IGJ#9zs{kiLsi95ef?6MHZ|9UZm=%nY>Xq z7z08L_%{ljLW}OCU4n{c$-rQFMKfj(SUq)m2+Meg(&#=o$h*Wz^gC#H;OA85yVooG z>$lo;inX;(o)>9v_Ft&_>P@tfQ)`hrh`ZkMrV*}z5cSf^MdF%mwSG)Ykr5nA(`ZFaDQA|>i>4DA6z@WM^i~{%Jb9Fxbg1Erjc^V z)aH)6dJcrjsuU|6Y$E-e#kxQOXZMNFaf&l~`~|S493{NNC2!HLd!?KT>MlIg<&awG ztpE|)7>FoyB;M*_-><`}k6&o|jb8B0!)+#45MGX+_l_cKiGuSh6EL>!NP;?n2FnDv z3_WvJcYG6^zW|{WY0DeO>|6N@ZDUP6YFj|;hm{&(-ov-$=!bz|O?E7LEIi4m+4GE! zp>18JUsLn~FrW`VIa%Zm{U$BbGnR0%Cy;gXJIO@ zBWq;wnL{i3K)osRrUFb18ueEP)(dzyUyGW1H)sOmW|&Qr5WD&oz078B$^HRJlY((` zWIb4Le*~2qn36gxe1lt=p<1kSB{Zr?F>?j_P*ja#DAs$YX!AFu6! zGu+z%M&bzIQA{PZPC8gyg%|IyR(*ZR#*1AVa^f_=gB^V25}MLCWIwQ1gp~6a?*ZkY z5QlK`E4O+M>wM-uo!Vr#u|8en@D;ol_-gVvRR&?VS@E$Ofg{2JX&bHc-Y@mb zUb_*?<=(kWo41-KqL}_v_ib((DU9H^zc7puw{l3nSX z%1`!k?5kMvabtFaf1H$fy4L#jNtc{n>i3`-TVcI$`7C7f75}_RwW&IK-1e3c0b!JS zhN|0?U_Z1g;%R93*yyBm-m2dz+T^cNUUEk+du7m|8M$N=j4a z({O;bO2Wc#${sLO)eKeojXodLg_!PAgP1dKgnzS0!VbHKOa$vcYZz&xt5|e!13@32 z3yuee2t4&uTcaHo<~4#M8rt=(C|O*;4Kg-Yir{h`Ar6L~h6Wx>-X+`7RRduusz#S% zM}*zR%-EjI68QBpxHjV2oSQS17Cp>2%FF9~{8L}BF0_PaM|xlk32uW7?9Ea=@gvh@ z0>R=~`Q3&+4iuOo?aTN$aa7A2K;(v?adffQ;;lVGh_c~p4I{14W?&7mZ`3GzaEv?H z!ST_IJ}9#?Av@1i9$CI+6mcQq^0_?EHNBXYfV#Kk)64J1qLPiMkd-DA^THj`on_83 zL8o4(E#wKP7n&Rg8`YcPAcP-D@fT+~LM`TTP=I zKjyGFUhg%o4%}wQfAYQl+71=$j+JD4pZBuF;0d^+^}UbR4pcZNW%ADGJJy4L*A87- zbyM5=hFlW&r%((Kh9VuR9j8;e+0TZ}pTd4Lq6v0_&>3I!kDyE;l z>3?!O&Qc&bX;#Ca#$O0XV*e7YJ2g{E4?=8ZYGS}d?q*aXHg3CPZrvLcGwk=ZH7Ij*&?R<|67PXiW zyL+UJ_Z647uj?~M!!7h5pgHTG;CbZ34u+Lg^^#l)@dbHVSvy2z-&g|nH^5~1} z^Kw5vgP8<6qJERAg4W(05iL1x4E7eH6`pt|vD&ygXUB9P+`7(!V2ccdcAwY26U7G6 zcsYX5HQUq{+?JWSth}WYN;4X*KF(U!p=Ba9#Rlsmn!1QvQ}2h5QI{*L^jS;FxA>B$ z&#t`A8~F;VjR*idiAO9uECkWA^PGb+uCJ^(llQ9@H=;K0fOzmNTm5xv0EkLtVTz*@ z(ZywXAKP8a^9v#6Ct_mGjkykiO-n%xpmF^shJgRAcX^iva-J=Yvy(fZ4Y7|0o^>6j zDLQto%E@c;5&4fd4`V3FY&duEd0v+_Z=_8cfp7RyxO;HL^sC;T1Qtm*FuXPAds)T+b&hh%w=yT~|ZiGj<&6UgqUMGu|{~ zqQcgQ^piY&{n^t-UNo4@VM)H5eXDn9L@$`&I(%r2>lM5*MO&R>ty5TYqWFZxcJ%5( z1#+o`ymI-R^q%%degfu6+m)#QkMI$#K_m4+aeajY`3=?YHT`EaF!Q^5JG3C2t-!<9 z({$k3h7$uTr%I)bb~p&TE$~|ogp|tB9gm*81mw7}0a#rGvm%at#DP}#CraRXggvDJ z$L(|n_kIgVCOyuAawlMzR?5NyWeD!nG6LnU_c4L3^n^-bomKFEBS#qg-$#x(KiXp5 zWADRmNz{ib0O4ab6HsdGjo@ofnW70F_`OvQZW{iQ-9r4cGd->#h5CaI_KoY+OTVSd zZf?YcHIBCP>?6A(wVBgX-9E9(zN(W3{lNHIJ4GK7Q9yp44gO#6^vRPO&P^$6DkaV=)7@k_)tD*l=I_BQI5j?Rdy z4|CkbU!L+@@Cb@B<8?8n58gXj)+_Zg`-PDrjcd2|IV{9g*FmfsF8E%-Q8H}jOD50V zv#0sAf2{>>K9NQ0El&L!Ab#$fO7Va9a63j}V)=Zky7{T|wV9tz$pI0USLUWL0)x}n zjbJ+s562QFmiwQbc-8xq9-f1UjZN%S_WO7YY|t@hSaGsE|)-3-Zn^#^4ojU_RPW}9SDt%SuPg9E3Y=#aVJIt~J@x$$>B;GO3H7yePJ*h<&NYV_g4SRgt#gB>! zeVDgzdDWxchNYq+>+2x(%EEfwM-_K%ReX=VM3_qiUR92BY-3eoIS3ms%5o`+SZff75CvzIE$0SwBm zqKNOwxCDE;9$Ve%W5cd`Y%YqY9?|)ISv7hWGDg?;~lWSA2YSt)5&o z_nn%^q@U7;$m;U8K#klWjKfcMe?xr3P1kWBP+?{%eLhVRm%nr&b!crBYDo0PNv@0o z)Nb6PcI9XFFHIyAK2uboCMt^JnI#2fPc?<*xJBC)^L#!;k~Z)(?W)n`oVKBR_EZWh zMdYFnRugtPw&EU6#BGwOxWW$#?ORBfsJh4cCcw(u0+Bry;O!IE?Or@`Zp8s-_cwr$ zc*RJi1m`&T7QIM`^?rYvf~~U<;(emTdFj|$DjRorxtqB2nGb5nk%ZrCcw`w|2 zVcQ`JPy|K^f9u-PrQ4+=7zA_c6^-<|0Q6v9#M(2%bEp?Hx+*Z+P_8z?{>0vv-j>F~ zmKtnHXT2kK$VW_I2Y1L|cHO!lJCqAy1~;*AA@A5eOFNnDxcQob{M7dFc`rp0^ikn6k%D4N zeC$ApZvQ&32>?Nlroa?@kCzuBx>1-QeyYniTo{ZFi4S*VA$^uEb3t>Lc=`7Lerk2_Vx)3zS2QPXj5?=_wQdUJ{RtUF*ML4y}gPCygKwgLb$hJ zz=fWke!`;OHM2G;PxE3=TgCy+8)vdfUpgZM^x_QdL-eniZ(&`;#chT1%d#s^HgIJi zZZhiP;@D$>?{{GgkMOYNTyH&_vSv^L(%8-B547lk=lwjq z5xV*j!=un)qF@a7wkc0v5SHKOb0m0Pa&Xr#!-oRt>#Knv=`IRkG$%`>*Zut$=r-e( z2T3_9RwfY4&n0J$@4C1>E+0rDwmb$Yi~GuXFOP*PD(5{X?~>yOX+I85*6FgI&_#hZ zYH-T8&kx`FGRI)V6mw9q{SLg&e@q-uwpa9asKdKXc7+_)EuQ*4Cs0tzny7IrL{Fd5 z5)D&n3dGf}(}n%sttvuF>=DR(sX<5Hd&z$(4cY%m8sg)O{eO{$nEWLTDW-aR0dtqb z;(Bs1Q5?mxpJOVg3vFz=_~&mqf-`N@kPozHA&BVXNI1Dqy`|8g;N(ijZf6URvH2-a ztiLBq*cgQn22$8%wBX046j7j`wWhPhPW})q5B3Qyp;cf043fUr5_f5&P?L{3#b<-Abs78N3H# z{KKRFPj_b?mUO;9`e|x%&RA08 zrkpgFq{%Techl4o$Q5%VQz1)5K}E$K5s>YEsB?bjoZs`i_qqSx+rRld^59qeEU)+L zl?UWB<-pS(rBwW7WAw>R{ zF__qJL9L?CePSiJW3Sp0W4w*vP*0Kr?n@VMes}R2lHXT6_iZ4NBzabON5D9cZ*?XI zFLfKi=pGLoRcDW4QD)p|skaf{3vW4&OJ}i9hr)JHcN{G0%)ohuY86OhVFSOtqJflOa&g7&1B1R^F2rZk{E0 zFh$eD*a$6u?Xq2<3%=5b*#rgn-0@+D_*Q@|Hc7w@C|EmE{(cqDcX*u(ZpLDc=7K@W z1LYe5aPjtzd04(~%su{6^{vEPko5W~PYb{C-`Z|;5orEUV{5L};>=p){Y=1LLK}Tk z^9-51zm5`s z=1vLQ>;#ZaW)B-K%L|u1r-H$`u(X>hy&WvNT{i@ljEC)Dr)=+@Prelsd1HIx^A)Cy zMMVEJcFNz|I-d-ZTJa=K;>=BGn8Y(&_Fz;A(hf83h|une6rJh5*Sr$ zs;<-Cud5qXaSIjHx(@7v1IrIq0Tt1}w?gWIW)AJ5Y0O?0827{e7H9tL^x=&xlemTP zN~iIp=bIpz==a8HLA~}+BwmhjYcHRaet9OC{5hr5~Ip z$*9P)Z`7f+?1B^qIGpAZSElb<+0*e8GZ5WS<7MSvn3CA<)q*aYfVYbh4`kpbuOOdF zA&-!r(%~$=SL`GVeTU;`@gir@wLkpnt=(LnF#HDp0jw2#gcR=bsTnr>F$F6a%e$-p z_FE08eJ2*(AAY8UZRF&AEhu%(c=#sjxgs3{Rl(~h-Z$8H#vAZM4|&yrlGH0NrEFM5@6Tv zoT%8r;+sHCxb~SaSlDcud^*?rf(5ntrysplOX``eiHWz6@3LSzmpH*URF>xoP~I=v zB92WKOcH3@Rh-jn?*b3mc!D!Dmy;8-0G@|Ss65(MeC(TkWHM)wcGt$>Kv9_VT;iORM>tTY!O6lW^zFh82*bNYIbT2KLBj?KD`{dMMo&9LOQP|qLfOQ zqnfNDlK^;pEEa4kVlGa^E{ipQ2NS3#fTGS~g(4!PM4#=228ihgLGN6xL<=w0$_3P7YpA6*pxJ+Gw?)3_($?|5KQyGJx!m42 z4q@-}Dr%f&U*=m{7Ab5g-0?|7G+wm&+5zvN=B7pT??vF5y}VtCXXY`o?qETJeiS(K z$6woni5`t7LQMS}@&#zw(S!}8D0*|tomUX76+v%$J8lRQESYMIpLIiz?Q7?-%_}UE zjwJN8(GG56(i9X)2!SCktara^ns2ALsvFuhJ-l1*uDx{SY?r zgZ@p-{(y+R7g`6wnbt^D@AXhjJ76fd`C5woQEYn7$QpD*N}YI;|Om z5)Oh(lwWZBgCkpZ%AF?Sr68UspKyK9Xu)@H*@1|;8fACEv}Zu*?_4i zXa>E&qdlj3cGo{cm<#%6lLhYNw51q$v*wdCNdEX~+4)lXL*}!=e%93|&6LzELbH)6%sZKyRRMwDBETzRN^0y@~cCK}bm{qV%L z>cx6>Dz0w*OM?ru>Mh?w%hXVA2c==HV5b3oT`QCX-iW5n8?zaFuK-w?s&~hs-u0|n zY`34FWz6Jcp;h(=xM?kx)IQOt7VROI9wF;S=P=j9AONKWThbxU<2QiM|0t4c zzn=(`WwpJ)iAYTM;uahk#hdu-WuHgb!FdGm8f|;Mt^FJ_@lgvN;w>TXb^T3q&HeS? zg1x7iBk|5-#Ti{z>8yK4WN;~eF!Z1_!iyIx`N)bJR64bSlc_NIyt2PamF00AoJlcp z6N&iOLiICRTTLHbwkDTLqp=KGZm-G1-2mJ6G2#g<<`bypi%_1#IowC7E)pJ(SFG}G z)t4Kx4zgPb>5I&>U34%re1dYdD!m2!tLBLd#VI{6b45*QD-VbF&n*>rO2MKssD3{x z*PWWRp7Znw_8qHu{|}z$TEojW?I{{435W!E!EU$zcU2Q7b|fUuuRth2$qd%(HDY@~ zQiE5_7a<(re??thayj5x5Wp_6sW^@V^9-UpXHYEHWGXW_tV}e^YFTVLO15 z@w~@K1vuj@Tlq#iI4L~t0=WM`;mE;p{9F=99>h-5*jpDFpnuIIt^856)MsqB0cJjY zv=fiWqK7CU?Cdp~u$?>ikfvJ_+igoi4b52bAJ}8eNzh{vzDt$qSaE;4c(gLHwb}=m z%oMV`CH{3h%`e@jLUB2ffFe|sPssSS90}>whvyDS=ah;82rse?hJ|AUrN#o=xApI2*@3r7SMsfyVESuzm}E^<#0sac7xj4I3X3vtxeGq9BX#vNy@QDkDiBo# zEOTqQ`DN4g`T(=b( z52k2cyP2QXrr_oP6?D44K_u~rE~!6r!hEr|`82w9A4!x{xbQW@eDyuxD|%ZZ5LFq~ zmtJ8ip!8Y>2R#I2FQnWU>NDiNv6}U==&*TPxi_Sj)bjJ9EOkupAj^aPCSo2W<#NT6 z?pT?q+=8i|R|sz?pA8p-xcKl0$oa59VLV(R=I4IAmTO2CNbaiv04t#{a@O1Gsp^1< zZ7Fx6-@uy7odR#K`>}BTBhA43?xpX#JxE;i4y0c+fnG~scnp4()5qPR2hWB?-md9XK(JFGQ2}u`P<_Lh_X=9$s&uu64N-llw@?? z;e~R@uYi9YTy@N~o|mC_ajFFCwt7qmlEx6z>H56LUKQYx62lvDpo8VH5OH9R@@om( z{#`gcF4?dPaw9kA&df#IhSeHz?Xu<}{i#QYoYgtmgf2hRvHyyySKG`6)!X?GUhU>e z{t%~QXa8GTGRh!njU5Z~C$KkR< zv)GvmxcCi7Vi>;ydR%+XIKV?P-` zQMlQdd8^bnF8!w`r^xZgvc>L}eakN=p3d0*H)(`kd&8*{=G5!y@%_hbW>hDvsu|yn z#1{4j)gb+j7sQMOtRCv-asGdhMN~xphAQu(g5l{3YUDC|aCvFc5Gh|Kf}^MGx~NWX z2=wsTsV5EJ@65~7Dpj!u=Vj}iwxUu0_WE?mrJtt=J#QxK!?w)AHs|jZjg1M6b@yIU zU%V^`o4#NayO~hRp4d^Kxs+cKmR>^m^j^Oe=%QO+ZwvMuU+FNP_0=Q&6P-YE@2?5K z{J%O!bbn02hn4>Uwv?@C>h7QiyaLZ0u-R0sGg;a;J&GZdy5X?-5{%$kyg*SGf%r4i z$5XpPc(};*{_N>ne?Rc;y`;m(_MZ2>^zHF&ZQG7qRQtPn!rP5I|Jr}*B}KytjcGL#+##k6nWchel4% zZxxo;GS?}=W#mN)_l(}cs|xVI28_39et;aBO30eLJAM>U!e3g5Ua9uIr-sTSk<+rr zO_IN+61a1FNgWBuHDba^Th+X*(6}H92^%+G>9@DRGu`6%$sbtUW*{pDmWr!YA%ult zeXNc)N$c82_Xh2Sm+GXQ6V*poF7t^v_XFIxpp>h{T2k%GUJ4xE}P zvh!L?Wx5YAMkWC?`1gh;0lqP-O-D7M`c}!b4`XQS{ww3fx6(YA>Q8Q$v=v~kjCN_J z$6ik;yKJPknFn;uv|?9|eQ+5H`Ti+KHn4XTJ3(6WhF6-cCd?Ouylv^#Sn|MKQ>{`C zI=l~rwMN-LbHm3>LpxGpbO@^_TB>iCR=ls6+7jtOzy8KpNjYizzdR)eiM)r*Akt)Iv+(!G3IV{q$1tJU8U$Qv$c(H$vVG-dYneZhFcdx$Q(clT{U9?u!7 z>kw#?zdYW-cJ{V*-wGc)YY~{4B2Cr&Pf>->%72L}S^^E@zxYDq=Oc&qpZ=eu6%|lv zGC!4PvNUoBM#F+Asutal6fvHoHQ8&@}B@j3t@vRP1% z346XsA|)_9$A&|0|3D;ktz+!c$=8&=3M}W9+v;au#njtuO3sCZK^3bf6(N0Tf}XV1 z75dYH0wopOyLDH<#h3bi4+p%e*#UDc37l~M`{JRP9|2z9h9khpz|*j^_RaPpQXxD{bxUp=kVM~p=tf2Z2tQnED zN5SmJTAXke{~azAUN284VVC{?#=Qme-@KC(m$r+`{RY!>F)tORw=``| zhn;=w=n^X0&S^N}Wz%Nk#|}vt4$kDcPEGdz>g-;Dfl~nZwqT6yU(r5%5oZ-6*;lM? z`ckrR>rf_a^~V&m(VQH%AT`H&83dnPIY#BNZ=arjq7iJv!~C} zJ&8l;lSwZnD}6)E=#kQkPnaoP^>@buvD|!C^Ee3a*$%c**7Ep3;6zFOZ5sEme6Bu+WWl|Z##ufiB~zaj4sS!4 z63zYyPXb5FH2%umS5#-wV8 zo4eGmE!7(F&!Q~-Nbl`Ex3bUD{A`?|wxF3AAa{96wD|W@|V@oK!!oIDGdP`(8 z^;c~}GDTL?5I0#b-I=^-EkwL6R4LuNLeAuR8?1-CwjkCAF6a`*-~JwswGFxBPuZK8 z{`9ku!fZ%GDWq5%yscSgiF=93h~5s-Z|4RJ&0APN?I$c?RhHfqA z=o0OzllCe|Mhe_k4awM+=sn?Vj33v_UGCeRc;6|FD8H9RSbCN%C~U+}w^dylFxIU( zuYBJ_Ea`;HHJf$M1t4l~CdYy2qvLM+ZDDBxei+-v;+3E~xAGT_wo1=MNq@I%aJ-H1 zl)su>HUbZeg25onyeoXw1;vSKSBxwmnaD5J{UHd^SiEK_=KJ^!*)E$|Wo-F@eVR@i zOC_zZx5#VGd@QO`yh_>Ze<6=F5|a$qUL=W4EXtuDU1$@jJX(ER$dxhlI1`058B1yt zzWWx6>9GU(QcofI1zTqVZsR{oujNBF_FOJU-4EVuB^WfOO`69#ri2md8s@+TuWZp; zMb$l1OW;QzXtS%EvS-M25bfiUX07L~e5u{{H-au1MEjCc8XCFXJr@Wm-aluiHRMeF zI&78oSx8Z8xZRlQ;Fz`WDW3wVsQ4(IqdB~ z0|{~+I?Vxx$hI$~jjctRbJgs9H*&s@5&mxVPF3S!=2tFPYM%CZ>zws5ONojr!}9(m zq`+1KA;q84!st%djM1Us01Kt3-WIz&x?hHIP%a-#cpk#>)&~`?4;~~&BssdeCCHvw z<0oI=<9n=H1#g`No`L+1`&1RY@{mulnh1@H6s&y=Mw-SST+HyLhwvTZ*wRf=5l^1K zT;0^hECxKD3iZ5&8hHK159g`O>je)a>2C<@k13_b z;$DwZV*%VppqMwD=c!1wUjHd7&*P$=JKsXTN{7ZdTbGI2cx7X@YtRFhn?BV$OmSNI zfx?eB@zfJruVT$#RMHaJwVIAvOU;+}LZum+ zvZ#m?2%_xcL(OX!m5&FCd(f{@F%_Fc=g2HZk=|yoo!vA#i9$kts4L`ciTQ|&T^tu# zZ9&E;zJZV^Z>Otl1i2f@6IH# zbf(KDU1C@-T_UkD414Kr@Ae+w>8Re?4r@A>+8uePiJw6o?aP=Z-PveZl zef9cHx9dlPiZybqyiG8BvKDf2V}RO#0~f`g9@eifG@y+c8@QougoU{7CTw-74f}07 zBjj$KWtM)yh+>6;pq1BN! zK!afEzXTK`-y7Nt?PID~{fHo0BM}HEW>xFk9N5lZy7$aQG2alDg-tFAIn&9DIxDw| zFWa-Crpu}ZZUUsJUXsIHckNY?HD_ID&12`Q)U`iObIfY6oK*HY#CI}Wk8Mol!x7i* zNN<06p6G;?g#5*;W#{;w5Iu#On=1!R;i1zsE9IBh$9|4>oa|zPXvZRmb}(GKkJzkz z2fprv_1L)>5beO288Vy;+KHc{9chqqT69_clLr}?Qf+f{EN_GUi!2cBh=$Q*=;O*2 z?drzNdN0ehvScSS66SSX^ns68h7CvsX%|eo3peKH;h?hx4`<#UEHjmy>T*85)S7L! zT!iRMw4~o>4fF@EJlun2hLNRZ4-8^yw!U)b0~Ov4VeJ$y7)3^$_9S+(W`n}Y8bqOw zieS;71cJWV!wnSXrAU zR+_QGGiQD?3OP+M-|dWuS>9m)(a4+9nMjUFYhukSB^1YVZPtSGNIm<;>TWg6{oAVl% zKC&(uE8KEc2*+K-TgjXiD--S)hMD<(cOpwQLu+jblase7ncQc=cY{X`^f$IU z)2p*v)y{6&AOx+GawbuayX?$r83q+REz zE?K_LLwd>$ME#S@3!`!CGewHpFJz8au{v?}9iiJSX_{^uyB&5)tK#!+jtq@;r}DvP zf8JLo-qgocsz29b5=Y`ftYH?M^(y)LpFS59*X$c#Ir&Gi6vm5o3oR|{*&xy}m(0v@ zunyQp)bJkIk^cU?V5VqWE+RZAbh0QEthr~6(5+rNRTTVF>R;pHSX)XwsB>IR#_205 zikg2=6gmG+Q9K28j;E-6tLwYVqbANvpyKKC*PwwZP)TRyomwSDaUsV=iXL$T6veQT zqHr;rLQ6f2!f>A`3M}V*C`_BGanP_UqXbYCWT_RXbG#72c|yd9PzNXTpbqlhp)&%+hfd{yyCo;7`PVw(#2XqXWRNT_NSQ zZ`P9G3Ix9T_Nx&X6Y7DydkNK;DXH`}ntD@ZXijvh0lQ+QP9nhRlTPC9qG&pyt-W!| zWJJTP{~tPu?feP!|Dco5eM7>1)=3bYS5TIoLEn%}(&TPYQbJT9(&V%>H0Vbj20%#;xwwk@E&-dsRC9Zban|-=@Gz^=VmyTGEl+ z9CCKVkHiFRiOu3W7*cH8w;=M=USx?IMfpGN>qW(#sIj5AbEKD?Pb?%)+3>~7g7L14 zEy7)0Oy6Ekqb-B4Ps4U5lnizFt6}1$c%G*Jx<3EgjE6yw;z7UNdA&7CyDrvUyZM)| zHLiGW#Rhk`Ne^9exFFq3$VIdDa#$L(S5Ko7;OEP=$Q}NX`5ryZiTE4|%gch@Xt=17 z$4zeV>9n`zqY_9n7pvULjEiKVi&5wOclBe{`7d#6@x@P8y;^v6A+^JxPuUI^=+?61 z&TCa#sX9lAC2AsE{j=KEl=bczd@}gRf1LJYF}V8(ouA{c)#kM^eeb}PaX&S=j;R&L zuCe`|oD#0bdd7nftULUH?H7EY$YW<4oVp@pTbLR2$lCYCa|&=Squ?Y!5cSbuBaZ51 zZpMNjj^HiyYXS1x0PNtsvV)Q#3EzOjWK4&0FI14Y4-;7#Dj)p{X-Tq3lS#|hF+sh< zk+NO+L#bxEq0&?r(>1S_Xx-Sl+D6(k&S8bj2!HPtn(U06z0q<{*dUpxny54{kLtcY zH1&c6GqdT5uRo-CAYJ^w|w;S21jlRdZr+271})JEbE4ib$1}ET$~>t6BAu7Q0}`R~g%dZCv{S7+@ke z(zz2(!2XFC;U)t5;&lQABgDMdVImZ z!4Fe?Pr*0%5BMQ{faK*7?eT6C^WC$Ez5W1x=zX5Sf3T6$nDj{!VI{vZdAmWb&M#aM z5u$3oc{bf+i7-tO_pFHK!})9Z+951H=>TdLH)xD=~$jY3^~ zkMzyKg~-}_`_}PkM7M#oqe~-B$8h<}4w-}QaT3}ulUdk3hyqkD$*AB=U znqB*ITSDONWi9dmBfHH4VMh-4F<3ukRF0f7pjt;@25#bYWCc5}xRE??B(DbjxVaYY z(nvIdF9djb6mE^0xG0DwSmI)id83;bEZ%AqwSRR`|Kl@t+gdWfX(^oQ^=W(J1ALa$ zim-;{mDJ^jSW$#G^J!|uL`+RNY0@{9d`-V9=}HfCg}JanFpwb){4JCx&-u{n-V?ia zbod~+O~6HAR}TgD*!kG=``iE%4l)ko=bGNEZHXK>RF`Pf-TDe#VTi#faEUZc;MY@x z%8mH?q(#Ed&SvkE5{PMHn6qoNPOpI`M?HkUX>)!lZJ!Uf10wm)qkcaX(Fvsu`gjoK6QwpS8#-O!WUaCao+eG$ ze{o8NL^x3s2a}v@%2$UL-!v8fukWX0$ypBQS11vN3T1rqi_yAPNI(xhh%F7j_)!A2 zSLk%!VwI>3v=Rgw8D;!#Z4?Y3H9o#$&8hbb`#wx9Z^UiyBuUeQTP zBTlIB?G%)!i8)^Qf8zB!1j#G3o(6=4KZ*#mpJ_9P(4rv%8Pm-rZiKMssHYm_U^NpG zVuU~akH@=V%h9PTJ5^>2cX3F=mRbh1FUD=jc>>TNEYbd{*G8a`3O1JE71NHFXPFAL zUmxVy{JCF$2QezpKZaliN+T!XS~F{r#rRI@F4zPttQ9@Sn#Ym^*IpllI{QMTUlIS_ z=-<&t$BI#bhXzwb!J-~TsogK7zs4zIE`fT@7{>Hv8C#^1JR+MdzU-|mBO6kkkU{kS z?fzdc6sQRAd{)U=1kGqzRCq~lSDy`*Pn&KoXN=U1+MT`;+JD33KfVU1rN_{?oscsc z5Vbpcs2O9jX<#_v<)_V1h!#Qz7Vz9Z6?y>0Wn2`fWbwHlg~|UPZ%#|Vg$^TWVVz*c z9+~LvpON5r2|+!olP=x7OAWb6ORX?PYz`NgxPJBjCHmj*e;(;ijD5i9_cEq7A}y2H zxu$fED2n1uAXq*DJBC*WckFnF?K^&h=&FZRYZ5L0@e+(^=&)-X@iureL!U$Ua!NVn z&>-CC7zEFWFuaytyd0OYTdcPyeyEnr9cCr*@9b4mhh*QjpnYwWYL*e>V6a?fBs~)A zgbF`DWd9p7rpc(Y61id9S7@f9AMsz0zk?3L##C@?sJLpZYCB$9I)<FfP>OUu9J(9*oD$=xNE53jRkCVBR+5Hemu$D4ejAQ~6AP!YTG z1Nkzy1zX@hHs2)BA9IZddMMYO38Spl3Q7DZ=bVoTVuZk9 zNH;fDL>7sQ@~bk>UW%F|(Gkb_5BN)GM91sxi}k*R{gFx|(>SJ^ga-8-q%^$m{S@PO zrK=sbYT39^VFV>X|5|q&8am#mb-7%HUFes(3ug5nWEMC-Q=EVZvaj@w)|2zo6)VL2 znTiJAEf!Vi|0WI^Mu-YLU^|R434DD)Vc$T$T54J92kK*i3U5=x36tn)zBw@(vur{$ z;v~KQqpH6VH)@EyCoB(15UzuBF1`l#Dos&)5KNw}Hx$Yin|7F8`)0#zuFVl`tB!mmYCM+0mKfB>Xw|V-^z?PP=FVQSF9<3=lq8D1vhnX{d#J!Kt-2sDV(yG{a9X6% zpZ4#CzM@0zJR?)Oc@ev5MP*a)8{;D}*VNRn;})X-di!)63<}{3wWtNYbo_&T9;k($ z8!YfAKEmrD`!A|Zm5r```C`-OBB~XHo9yzxhvsD+g!@5n3>)6Vmm3jYQq-D+@dWIs zqC;Q++3#-FsTe!E&9QI-4N9RfC`sr2->;(~6ll}YowSi;NObwSO$O+<``9CSa;QC) z2e>nP71>26+~iE+?xG=?we!EUITZi}rROlr5NW zsy1%&e_0p&4TSrXh$La>=X(Q+b*8(Pls2#1P|-&NTrS<*4KJkRht0a!m32{_wjtKq zr5OBwCE#;^f6SU{#@0B>_`r3Wy!o5-`Iz!3(1WKFVy}?nqdSSkLPmCev~=&QO#g=v=kL3#9_pDCAu_w8ySDdm~%!s*kf6gSd2{&xe>5dIKu z{}NVDttd|Hv585iL-|5XHb~!N+6RZ!uwGj7O(9z)2Mn)LV~z<9?9qwgAHj^(M3i_v zKi~0>l^{GoSqT7ozJJvGVY~Bg`njXGfXi z`A2gl-Cml!|Ju@YGITsG)mOsg^JrsKGi-_%^abi{&K!i{@Hd^U#5|N>O=NB%-=AcN zU@O7-CSv}vq@VxXfx`oa#G}-5C0M+$%|~-?v`IcGcq9es z)Lgr)@l;1M1j&J@i)rV|Op-Fe(qcpx`H`d;7vsSivr(@7E?)bw2n_dMg+@&derd2H zDzA&W7L(+}z5V?flYp;o4s7={*4OT`g=>bqo8#S`Wo?R~uSe1Yoq=@ehi{dmn$l+} zE@&(hRaE84u(%-@^6lk+w;ahRMh10^wLy7#aD(xxR z?#Ow9K>`vCf_z4dbI$Jyg&6IBQZHH;42m~q%p=iJtdgpRZ0$~lhDGAVFd4@XRoZ^C zPdm8ZSJa&5g~mcWTv+d>SYKpa)PH!p!@4oKvy6pEfTkb5IEz$$HO*c?A|buZy4iPN zgv6)AQwPY6bL-_*&K(>X1;;;9Zs1lrV$C6T$6P)Dt5Yz)iqE=Va0>b8WPdf+LPYnN z#`%>07CwTANhQWYNnBj~OTs4seTa~l@2SVYJ!BpkY~P)0J96s?x^@Q&&5?U&xqOla zYbaIElKE0k^ihBU_rkfc)M!SB`mH#v8FqGx>!=>5TtuUFzByd?ScGA95ubHoQnc#z z$O^7$8yyx1iWG)4=ZQk`CFwuAF7I_0HjMh8 zLr?n}%c9?s)JyD@Fk6U}fN7jnB^xK6ROH${)78P8>Kgkw-^$LqV(YQey&wClmG4d+ zL*(C<5c9O>RS(Bxib5?&{DSghzFPJq@!2ONa5vd%8yU?a%39C8T4OS_Pf4-_IjabG z!qhcmPU1sNhSM;Y%M~6Vqo6l7r|X@cyPT^kC33HBdHE6lpfYGaz^|7Iu8&e`#2;LQ z&6Y$>Aa<{EUCRU^rY3;H*3hLY{^)GB}Nx<^urG_*COdzmF? zhED2_eUK>LHV75d*~;UTP?7~i;4K42(~1a&{GW8>718aW7^mZ)uc9F-vh(LTZCTu( zg&(|T-Xd0xr^#9PG+JVCk!9TKOCuE}VEHJ`-+<1Fhxc-RYfyfxgjQ0q*2Zvw=3SVW zRlD!HN#3&xQjsRt^-)S#lrr5Kv$V3fel}UVKDXQE4Ib=p|I{0>3W{d$zEqL;m9rfo zy>Jfvn1J`CQ5P=qL+~#-M-#I3#`3BCjV#+L4mpf%H$fAdjHWQ~i9G7kKNZXW3WPgd zSaBl3)gltBvP<2|pmHNkMYICnmQJxI*fd3FFEfn8s{sV3X7w`1JM6mH%v`kUTS5xz zdcmYBX?(2en$OK1KTf9a`f`FD0cGilmNtyzr!LYi(s`vZTuxaH+t*BOJsFUt2_JSjVTZwBhmkk=?8+J~nm;BY`-)|P8$NW_pGUs`xYAtR@|V0sO$aiA zPO0J#&Wd6RuWF1|W}>E`uQvD3Dt6x>Ob3WRlHWBOPjslYTu9c%yheR$AG8qV5BJ1T zhsoiNT|ZDxsy(=E-T8Dpw}%OxYAeZO`}4aj0Cb;Jl$CqjV=@FMmlW@Xc||5svWEDl z-W)OV_!9K)$KjTksX*OWM*~)$+T3QiPqdqy~E@)W}C(!R4!IZ~%w4041`N z6Hb3Jp1)K91!y|r5zXb^I2Se^4F`1I%R8cYj5My9eJMh<2siu|T~d*aUXjCT0THkL z@zp>_B^!))%u*?qdm5oSu_TV6B@Fs`Dk*Cr%C{OyDq;ISzHbQ8TdPlnw- zs&0}fem*;#6SM6}Wvb67O4UNo$`h;DM@!K($E{}Xt)ETL8 z74!pyV5JNhvig4j@f$3QH}_PrXaP zvAQk!;?^xh9d~xHAsV5RF`m}-F!7&xX*=l+VE9sfRT~r03@NpM)7K*uhEK(0_HujG zR_Bkr^`j8E$sv81`tr#>mIeDvB4_jd;Gwg#bL0A%b8WHAhM`vXs-bybim}3G^my^} z2Pt}?qRgK6JZW%wukQdF+K(kQiH=voZSqHnV-!KhBjmgRF>o$%4ZLmBe{=;&MZrzV zB4SFVZ!nr67H>Q^q$=jK>A9Rz3wzHcM{N$lfJv2L=Mo>lB*Suhk|eZ7GpbFY6rCN+ zjxyOMMU9U>Mw~UeZ;6t9(jT@mA%*NGaW{Y-}-VbyUN_~?JLYQJMWO3Who z#C~RCy?IQ}w@=Py}`~n5Ut`ki7ZQhQOn{jCRq1yWKFg(>ZyY5VBco3`BsxE<`QVOFGK?kCqx_@4L?= zILR<1GmpkLx+?41V?2D^5=T|m_# zXg-Y7H@omG@^M2<*2kHV;l?$k1k!$BQrs4(@jva)KqPyu_dbJb6w zz#D_J_0(z0cB;n5nCCTX*np>(-vsxOiArB)*w>vZ#$leCT38Qcv0h1*5+vy@^q9ru{%>X&Z~Xy$pliZl0v@TH7$msvjkWi8Dn_Ekczu;$tmBi8I63M~ZZrz+&%*RaaS%*orTpM%YRhV^3QkIl~kn{Ssbalt5%vwu%K_|)KztmPZ?p(Wgz?$>u)Sxvjj0K^}q zy$iU)Ihv~w)YvQZg)%zQ-vDNXqn7oVS^8{@u-bAjoPtNedZHr7_9Q5b3lVVT8ubA8 zNpnq2eim8mhz0s+raGqT_dBwmLAp12jFlQ*IuQL)SuAsLJ^!hf-(;|q!4n}7H4k#% z?+^QnW#VJ52h#$iMFYV_Pyc-RpJtAL0v&H@k|hXli36M6^zC>JV(=2hXOXXgR(Ep* zCzX)J4^LdyM>kgY`ovn>C~Q^kM<6BBg@f|-LIiKJzIM`jY~`{xTu|?pWKO9iE*1@H z@33fiyQjMSgRs}IEYQrYxm03=Sqj$0<7%8w z9q`t8`8_Q+`ZpVVrG`>!uTt`FZ&eVAtby`ngkcwy|LQiY`p-;ovsD1ZV6y7CH${jq z*444(YmUwiyO`70PwL89eI5E$^AnmT->&!X!Ay7N+s`U1D}St=9e>J}kB-AE%z1D3 zvej0DY^^xVCZ}F~tJ@FKc>}1`>HHw1?Vb*Qh7<^nlY+1{O8G6?=opfo+;>xG{l(&{ z_oVcKb)sEYJYx5<+%_gf+>y}u)3H-WAcNZFW?%?FL7CQoJkY>W%O6N36Kt<2Bo)q3@LHHL-tA5hw zE@HD*FNzzb5LwlVgze*FM}#QA`*PQCZ*WjXMMpbF`2IKyzsa|0>uzw+!jsZd5_N?! z!w%m(bTn=Cn9umi8W?#5R@%Tt^e;2d!6}4|1}M-zCoypX?GOZSdS% z;u&p-JnTv=lir$bUbZ;<$j0=70YZt|?JR<72LqwuQmUN%4c@fZuP5LfJ@S3!PFP>N zKv7^(9GyGXc#*olAz}Yf!ZaTyU1D|~st%xk*+|{0ov448uo~3T*rL7N-G&vPCwZe3 zXP*plkCO_1_y7W$(Gq-(rN=gk+-r+e@9{dt6-4$ee+}*ed$I6;rW=by{qSx!&2GUe z>*Ml((49gP!#spu1ksbF?$zXA>en__veFfZ&w_2ZN{ET zm^60FuGtv&r&-+AscL!c_C@(@Daqb0e(o3`e}eO7{jx8)C0(|v5{k4^;i^}XX`imm zG`id0>Uv~w>BfyqkjHFZ8rET(gBL$Q8GZEmnOaZ+V|vP}rYX?&mXhWXV_w>0UF%}~u;=PKLM9mACKeYmI zu-FWq?C?b;F&gcYC=VRJ`Ra?;gfn)>pvBws0BpQU)Z8`h{wLo-o26gkObJnd63Ee6 zy;6p)RpPrwz;X#EEa?wK$cb~PbD$?PYK{GqR5(RU`c~EP%wvEZRbcD@fMWdNSpCD56eo} z*Oan8>T~0yBe@=8u^Bd0^^F<(`Q*f1dd*`uU1y#g`QjXJxY9no)b^RIv)=`6--eH^ zPF5O(Jk5eY4h!@yMDx6ZSihG_Ac~HcO#!PeQRcmMdOtL$N;xVuYI@$@lMAF4O<^%j zt4Pj5ybjhTyz1)6ZoL5t*^EX6wX=Q0 zW6d?&5743pK(O4xtMk?0LRry!-dI$aw1-~z>h&p#6xHmAplTfIk=PpV*uC4nqUL^& zV2oE}&dlvpX3H+F5*vd|eLfAq?NMv+PgVaf)*7e`zm!j>AS@Y0?RKl3$ZjB~gzBVp zLBzZ_IalNU4CiIpN>QJa?pK3WkwhKWF-)&Juu3bVTkQY@gGqotl#}cyt1O$BfEvTb zs`}m};O#30*$B&_9Fcor9UW)sq>hs5g}ls7QbTJ$iaPv~xh)5A5mu${KO(={Yp#9p zq_$HNtfcVaRGU2#r+tM2g6u|lgWo^^ST^?qF6fFeqZk&K{Oti!=D~Y-+4zF5s$UO6 z1zU?87dp1CQVF^gur+sw5??_$VaMd5(saDa)AU}JW}Zq9Pjk#2m3o&)4DW9kdzT-+ zMO+FlCk+q(A^)6z#a`eC=V-vudt9njcjUA)`%Sei<bH&Wu+)s7H(*no=WtfF=v&Ul5 zt+wg+_|!ZEe2rPAXSce#LS%14=A*!l*EQK{QT!I*0>OYSOEb2USEHhbtjUR2?IZ(J zsWIiMc~7G2Gh&@<)>pOqf-_Vw-vP6^+`3BD(KzH%!Mbv2tDgn3d_*Rl(@|#@0y@^3_ zRWGfNSG}UZ;h-5=9jg4QRqqnxRDVXla++xKv(5%}Ur8aiZ%1Qc91RxXs7!rF$gE0d zrIQKtfewY51#gnGS*z8$KuF%+I>CkIb> zMMRn{4Aq(NWwBypX~_W94nK*>3~KDLp7d_W?HOa{w15979~z+5ueSfFZ^jdpRi3V-|jF5r8)Q)eJHkxspJse7$nsQ$&<(VINDgK9Gz(Az}= znbmEQJ^n`o&o84^`h`R7%0DZmL&tM#U=d0h^-T?)@Xc*{W{sxBT?ZQ1yu{TLaXm+# zVXfo(yc9S6kQsXswzOixWVjyCVFM?%Jb!W+p5_LfV0@}XD1ThGrICtC?-zE1ns16I z?Jc+WNABPw_C)Sh42m@`tL8bCK)DB#+^`+N3>oJT0WE z#v*QW@6V#!W9BmesXyjsV1ZQK^_j_0j5o^Tk-fR@w-{0W=%eo@hn&xqsn~NzB$@lY zmtz8<=Ai@20WVa!vD&VJHs+2qYd+TRz8fpeACt$N`G6AX{=P3qN?}UtVIZcUy&zqs zd7sLV)-h~%eWFOWOu#(Zv4a;yY~KTx0Ap!=U#^gDxyPGJJu7+3=(4d zvhRL?b&rp76<__3sO4<3(pz9r(OaJJ<4#ZR0@ft|=He z8O*?j^DLOflBk@j!HTWd?@nj71lV>22Ee~r7kN_IOpwJ!Z3Lsh*$Km z_^NV6IL^SMNf*m&qnYJTBJ=gUiSAWAMg{@!BP%{U;kJFh&qswT#(Pw&&^P(8!B=7M z)0|k~-WZ8{^6o5!1VyGq`g_1+OB}uuWBuk?^bG0mLX~gUxJuf;@+hG6l0FU}rR{Kw zWp}B--$-9CsKA-wd+^r3)hcgG62-HmB;J+~R5vLdTasqFZ7L-l+Lmf*>tw<@PL@G*abFugKN&B#Z8+- z>5J-2sLE$QRLGl=>Ygh5bh15mM4dsiU;Qx&BZb| zF0)9TA!xe%3bT#Uw`osxn0v`$%kTWe{U9(M(9fuYUH!e*Kv{S|lxEECL*&&q(?>cWWb$~fkk|J#9Wz1Dq&brS}^T6I&2zAZVekMok5@%{WOU$td&7#zP$0O*v z7GqSR&%?={C1QPz+*1`k^u#%*7>WCs-707G*kusa)9$seLsL+<_l&yv z8vwSG{V^E=Vph536|dbD%V?sG9#`3wzJ!_@<*!c-4GkHOnJIJ;8$AwLd^qtqwhbk_ zNk064vRkd?9?)0q3ZaxXns@F;5%dSYep+okW+s2^DG@pl-D0@1aWDTWPfmWuw(g5g zPWhF7B`mPB*2g+eR&(Mp7r%bp*GXGIAfuUDzi^13e^+0_N6th!qp1 z?|Zn+kEKNcur~Ht>eK(%K&~9MNZ2lqndN-MVSQYxadz+0D+U#-4GzE3Qks0@*7HI- z$!Baa(y4l{Kz<0I^1}?eHgyk~+p9aURS_3w|Hg7Jbu8%WqqLtTcS9=8G&K4_iFAqf zy%!zl%{k8iVCZD=kh1H$j36#uQ5n0K6h_uZbcR^h!5987)n!byG7 zM|kjo?GQ}JgXVK@|1P-z{_wbMYIQZA8R@xozm#-mX$MNXk+X)vgqrhWXRMg!>$66; z4MF4e;8OSZ{1R`iQN8#jr6kq(s8oRgqq!ISovK5g*X)5zoc4&_YG~1i6veRye6kC7 zWIxZi&uuh;>FISahO_^=xOnzu)WDwoBw?*e<}BFRRn&NJUPeI+hvnh)h%;W6S=S%^8mFjSmgaf5ubZa@`B3IG0gxw17gFd&N9Vbcn zLk#`*nY|UJU8MpZ+Yby5$Twe(tXR3bj=0Om&e1R~K)HR*=-I0Zep6GG5lHvXa(Lgl2$k8 zAaR_==P95YyO8sF?w8`Z^ja0=+klQ@XpiSu<**MpTP2jRt2KzpZ|bxzswH^7yox~w zNDBoa2mL>K>lV;kANt&>EPm4yv*sD^{7|KAeM=6H&5i%KH&vuD$j!x9P9bR0=g0Sy zsa)kG`mUe6)k7J@TOZL`k!I=3a^;}9FKYnHGwTg6jZXkSJ2U**M`gc%LA!z=gjAi%p0AA*xj$sr z$H1c|$S1}KyTQ5H=)By^s&zz^sB&=#kL|DY$vmZr&AyCtZLrU+u2tJ7Ihl5W2oFOX zm7T=5Q1>qWS|MT^oFg^K0zX*2tj68bWQ^Qtwz-?!YDbYog5bH6`tduYNGMPM{TcwD zx|ss_R6Z6;ZHcw)RQ-D-XzvU)kgX~lt+P#zi!*B^TcA~AK`*gRV1+8BPU&mW_~7LA zPMu_)Yp$>}~CDz?=D*&D4A}LqxcH6uG9CGLDvE5kLC+uDKhGnK_{l zEcpBS*w*na~ImG?25I*flqM z={w>`RNfZYR4+rD)P2&59q!Un0il{%nu?I}ca`!Fh72Fq;$NUV4o0e1Y7lS9@UTKL zsc=cz^4&haMGREbHD&;>kYDT9C`C~XN=gVz@=vdWWRC`SyLyCGjrYO#jVZpdJ2~%J z6%mf|v`kFPpX1mKoHR8x_ms)km}P(<(={cZL-hP@UYf7hS}=_-zdnsQUy+#8ML6GV zUEhrGL1e=xP*h)Uz9A?*WZ6_5zUIXd$SoBF#|EoaqlL6xm zGD>pEc3J7qDB!(UNU~V?$_L~6%Zi-N1)_Mt-QdKJ*;~*w6{|28q*$X`{d3_A?#2 z>+U+N@d~3@w8u=JV7hP*%X{9N%ub0MVp^o+wU%o;gMbAz84rH3_bFZIIR+=7D~Y|paN6wQhvwd%ZOuq;Coze1Weiuq=* zwxi?&0Bk=89$U+ci>}&Yt12Zt`X-h%$5T#{t?^26Qkhx$rTYuRx+fZ7nDmsM0C|lg zALBXXcV9#J+Fx+bZ1MZ^#}dSoo=TpgjP-MKC*n8*Taz)|dgIMvV27nOB9>$`Y$^g# zIv0+*q6KM2L{L5qHAyg^^scp=Nwh=;CyL*Ykix3Nq7?SnHrVh^c?77#5VTm@@MT>f z{3=2J=DwjRkD!FMC-m;!JyoEd39psLooMX&BME#NkuQ%T zSW&YciN7>N_*cjc`N zv$s%9H@Ly|R~khA5@2$B_&~80_ww@6HywRlK@{*76sk(o@b4w9)%o@;XGplvfI(3? zsq%{_s;u*2C}+kRip_|4A8i-tUptBbZ2QK6eR5pBv9|HDszRyz>3iW)t%mY7Nn5PD zBFLyf(1SD94{#IxI%->3`9rf>^=IOQmU$v-Io%cSh)Ze<@7l*@25lDPrLJ+9u4uue zYmFS+NpLB+Ew)QgvRtfuIvWVD1XOxxNtv#2&Y@>WMTotbYh7s~MDp{eR}3G;fJ{1L zsu!kjt*pLQMUj&)`4qfw>f4+4O#_PS=oe}}1((;ByOa4H=N;YIy=hX+KefIFF}ALh zX_nnh=oGjvA((mVI-m#gE|r!nzxd%RA~o4FibWHhtIG6!B~thXi_QUpTU&y3C>*N+ zg<@y-hdQt}UAXPE-|(A9F)&jiEE&4Bd(RWwSAdLC_)~J zMj|W7`T4Pk832hT!{_)%?tXx=mR$R{=YjsaVLGKvfWI(P-s(_ZZItWEhYBl}6)^fa z)hW?m6a@V(0WL5SN!xZdjj;Dud6q!OY>Uuxy3^Z_Y+sg-B}^I9Ju+ zT=k0NK|{nJ0H5WJm8_0ftDay{uTExltrvuR}1#ecDjgWjKcS{B$>`atAzLrh`k5mOH0{$5&)#QtK?i? zl`n4h{@X}5KV@P!llLNtaGSDK}R%R=lJN6Z5y}5UF?WXtNmUuV%T&r&-A^Qd%C2+;TRm`arSyXQYUTw z1HsUB5pmR{uK%VYxGeS;5JGgz9XT5($B|o=|Z!njxwN$5M zvH%6__mz2O7f~BuOn}mk*PoxLCUG(|=Z^wGZRx~NH!PM{EwYWCHmFm6!>(B|w3jHN zIv*yU^BAV}EKy@v|63WEG%WF6E4n_>9E6nPzDJ0t-BmT#bAHRg>>JZ1>S^8ky0r?_ zFNYn2gB?=J>RO{u_0P%}=&~8CFo1fH=+75>>le!*AV+s?(v11Qh_r_eB&P*ix(mS;7WilNR>F{qVeFW3xSqlJ;7u-aq_W0@E!{$_L zlqiY=rgJFxm}J&jQxzeM_a}yFR}r0Yh!{s+v1Yg8enX}_JqKYA6T|R|&t?O1qra%r z{rro?;Ofy8E_c>p-AcVHhYG&Xf-m^jzD%-xx?ro=@Yx~PSXoZ1S)>m2^-)yXMRe_ z;9b|0An(Q08TMtK8xWDjmX^}VSqLH3A zW7*-<9zB=iqO(0kO+dsBLlb`m`tu!h*KBJR#UwA+c*dwz-JFr`TvNR(Kl0Wd+|cvy z1$?YJ*HbhT{iIxxv)RQLWj~3DLq8{YPV$#Sro`@-K4WCPFbYJ3MOe9p-`Xo-h?BE( zq{5v<;P5f05E;!xI$u~?&R@S*ZXz9gus#;4)w(eQOf_?O)WSz^8e?&Oq@t$fbsr>} zW($s@N9+xVQDLS7rNYr;D4*+(Qn7q|f6>G`*ey)B)?dJzeeTto7U$u$6kyG(-ffis zYg0MMzELcyReaoq6TO^zX`h;Jw+EvbRj~TyL!xg=^ZX*@ z+t2(3yIo_3nxl;6=u^zJ^>fa1{0G+LZj|^POgs1S47l`Osp>GS1lBD-JK)Z6kB=ks z!)hZ$k5@6{`SrU1fI)K2OeYh?bi_9%^N35VhL#$EzgsClr?Ra>JY56JVsgXLwxOyK z90upR#wKd-L#v!^n0Hn2Vh1Z6!V0oGdKklk?@(%&Qk- zYg-oy^~*YOz92$H7#kH~r>y*2e?*w+SYnY&aZq%38e{2=ZVS;&$}*^OhuRZ|+_sbZ zAZ7In5$*#ris;Voh%oL*p>6v8w|?z7_@$QO8?> zR2zUOmM$@=X~}QZ7+%&baLomGe$%}%CMG6af!`ww_&xZBUIYqtMAEd*rYM}1cI;M? zi%ZTte0ZNziy}#*l@++BLLP#y;?dEP8qY5Ytcfl?q8w&H9d&w-u;jdtwe!gf!S1=0 zdn-$QX~wz=34 zbkySdf^D&}^wT+uv=ErnGXUnLnlDjQ$}lSeaDf37>eIfbn70TJDEq`WFrB)eR+`_i!kV@ABwvk&}pdE8=}VtsCnAE8(X3p^Y`$hDqdswnL&cK+RI zW7`BeZ0oAQe%Bl71de&=`1x{o3{efinhH}=lYeq2<7MnL)|`|-yGN{n)a-!jg} z2&y8p_2;7nnt5KuH6dP5n*V2>#bVcbX2PE6-HNTBd=FA%JLT31Sej$NtT>N`hDPou z;P|*=aqv;UaKxE0{z<>r4=lUNr!}50Z|G@pfs}~#zQp|NVhCb|Ka9DA7IXZv@U(auxb*8Z65Ss?qsF8RDuV_j^OeQuT6it zc(aEUgR8PP1{W!N|750~mrB}OeeRttK6YRVL^-|Pf&W%i%jeB1xTE2vaWvnU6l>5At zxTI6Qc!Q}Ea89d44_XxFT2WKqe(=`2q{yTH*COex4)}6_D|)X2zhtJx=SS|&u*_N_ z054#iwG7=jA08g|P7>sVy@Bn4o$s^vkGpjR0nD=%$Rzs~0gbH!$&-r~>u=-bLNn~T zH01#R!+PC=gB;J|2483!Z-=2!0uyLB;fN$S$uG`>LWzc4NVRL0?`P!*bm!yyEoM|F zuZRkrimVz=BVCdit?Pq8qvAdGbD0bTFC>QjCcVKev1$&(2JSJl8zb{2CBu9ISfBK( zIzjeU>^F*(y4vGX=2+-ihf$D^-cXL1yHcXWkD+bsz0Z3lRm>SP1I+}<=gn3slOJBDr#rIh4R<*Y3xpWZ;nmjBoHDy z^o95a3!cY`;A5yWIDl&v44}&$xBfYO^yyR|B@L%=<$4BRyne6JOu6F zO@Yu__&$Fw^h}H24ci8IX=;J-d^(Bab$dQgNO{Jtl$xv)n6Ohc9!4jMrwe1qMo<>y zR?A$m!VVYJUq9mmV#86bQ25C!GuX+SuV(V0Lc(q9S)mu!$gDM*Ne#t1GB7FO?yx5q z`E|vV_BOh!NeRuPB<6|9)PqYOciY@UoX9hJH$<6gFXNI9Pl1aE#CWN#Lw}EXF@;_V zI`DU}{~S(*{xzH$scKsT48EtIqTvN>{(C8tZhH=`K%sJc1?VtKf2df~ZGQ=-sWEK! zI*>b{60;pGo{$8t@#^rXP=O#r+DOkRw|0#8jYnls;p%ga+8#)GZFR`XTPSotJ4p5&CM<|e;wCt(b{BFckPqG!9qlg~I()CnVnDmT zzJ6{%cB8Qxd+3QB;hOPi>|7e-BUEij%E{MDKbP^5ucU2nrv=z`$3rup@K-rQVCPp_ z4JG=ry=DnnqIg!udZE77W;a&e@3TK3%OiSzw2n+DX`^W(`0VraZbepzjSnoMH0|8xLFZ<K#DFAjgN}|8)G%ew= zHfv4QRc7Eu&>)XbYPl5U+~MQW69E2B)g2FvXsy*3O#XHOAz!?xk)+MQ`Zm|v`h74* zv21|i!^ZGjQf9S`qLQ<2>(FRdDqa0#K*v<#Ud{B72uoQY;b_1ql3oeJ>^Q*A<<$I!Pfw=2?qq;LdR<9VqI7(dZoM;WX} zZ&eb4ODoFQR%4<$7TQU?oQkVvC-4V1HNh>Zcu3Vv*YiT{qKYbNyB6XsCZERssd6=P z3Ja91v#_h9X^9mh|G9^6PS^(s{bR7f%)5QUdm)v*g6nlch?A#dom=uDH+L5(CccIba!8z+IoQ&cOlnl+t*+t{SD7F*Oh`0_RNZOYH|D$NdbKORK@kZtiD z(bi?xOwKIWA1K5+mPpS;neKR4Q4V2nRSZaG6krH%2b@+UhT5G0{>$LEE{GMlUUpwS z_QSAN@7sx@gUm;%`v$KQnLXW66_WdqG-q?F6(wxf_$!>m0`i z{D;%d=4rkstHw`sD9FWWpP{ZX9i;L4fl_K!6Oo_WBfG~Sef4@K3la`r$Dy7Cn(5DC zY`)fH&w^?vwlAfJ6F6KSuP{{%sGaq)4s2#Pm~Gt4O|m=bB*_UqDab?Gw|vELzn3sJ zy4eLz4cMps;cdxy2T@lb1 z+JAR)uwF*Z_4pI6#yRmO^8!t?o1FS43p5%giR53XvI+Y(n

lfk)MO4qiMUJjH~la?pZ|^FK?H)B#-s&XTy7`NwA$JnZa_JGImwObmE1pD#v{ zRERJtV`Zahwl`NO>Tu}<%)2AS!iGz?ZT>!lHPZZ2~>as7Tg&8ujhlW zD+-%fcEK=5iP?<+ZyZHP7eU2cpOQW73ps^_)kx?_XvA%2}S>RrWNvTq$aazp2T+J zd&h~*>g(ERtD@T-3C<6L0^RBq=9mj=Q;=;+1P^!`CxrF?Zqufwwxz9@=VMcp*K*BP z_ai28Tv)>fo+gQVxj);699p*=NMRyW32YCOa0SkzkEFPcs>ie00!Du)dPs4k4RrrnBzx;7v?(_`**4pW=XrqG7W5;t3((!9G4h=n#F`b@m0LV zG0MfhGIy;n_6^hRvQ#Hc_3l%X=}H zTn2NF*Enh*Ia*l~)Iv^+e;(?36lH5AudxY}Xe5_0-{zS~#q)L)pi zY?n1&AUL-+99P^BcT0<=a(3d@OSk7=x*3n)#l~+Eb5xP^%1UP9K)IFXzN{4|D)b1uNq}BCLfv#r zKuqu;k9xj=i(HE0?5-a{4%LSBP0EFtNF5*7*vR*Ifb&KW(YF2zjNsjpOliD*Hj!?Q zLg-m;eT7V}3P;-`C*x}82Zf+a8_!=*28d(R8K!b15S0q8KHlHFWyYix8LHf&nj$=8 zzZOm!GbJxA5=Pw8*48!xaDEX&2xEZ|HsdllPeDPX;C_TAAd@&Y<#!EpcIvgt2CUv? zC!dervuncM3bEsx4-~=NT8`OM^cwf%;kz{;I=jfYkdixkyf6G%iPf9Cb|@y8DiSs8 zST9bPCl``xJ>zy3T@(TWyR+nv8)7CPvb(XcK)sfzoem4Qhc`JhlZI7Y*LN?b0{)Nid@hl%WFl(p$wY+7@Y^MW4gW)V zVoQaa?%z@*?^fXSWybI$>Fb7_Pk5?sT4191TxM-{7Um)Yk=QoPev@$BGajQpZmWaN7ys0uFNkb^zSaajNxfV$TD?Dp$P!5Cpb zGq-6Eg`1or+?6_T`CwRA70)1K{yWx6wUJTN zwsKjK2YK@qiL(w&TLs0Q{9i<4*e}B)R*&-k?G?ULeBfnWEUs#=ZgO8>CpGdtAEH`0N${V%3dNjG@J%0?8@%dg_GG?Bwd#Uy^K!#M zmG}l$i=t)44~V!rAEa{aZHyZg+{bZDjYFpJF9fim|3&G*NMgVqAhy1&0CXmuIsp!w zY?Mu3_9!gq$gOs7qlf=6n-ZPDV-)baLxw=L`r+0OZx<>jaL*aYV?hv0Pe^0)^UKl%uzYjV&x zn5Aizrv?dT{h*%3BHFit0CT zqE>GO+rmnIvdbd=8$*GDY<`pKFW6y~%BgL7V)Q zHJJMO-HZUTzP@-U&0xw)TA@2{WKzsR*<|~Ado@RZvb^*JV&pao0OaR2fFO&4PXt*8 z41*jEjauKtT;fXO;H8azgIYH!I{0vo=e)-FrftW-dxyP0zgOPt=N)>5?xjW>tq_EL z9}XvA&W|$wpd|2AbVB$6`n>H=N}~9`xswRSC)40KNf)v=q!2wNZi;<4#` zbu)2ZRNVIDEjF1Mu*J<+(4VJ?f);=Sfn0VD*^USA53Ajgv4wVNCMNyF9(%k1X&7xi z1^S|@ww^q!%ObN0X=Z|6_J#6jN}*E{Pq zy(?bDB`o-KX?a)XciDNZWIbj@$L?(QJvpudkT%O#K)uC*Y2sw_uWzo2PE>`RLxKl4 z)d1$&t*);^hmrFDx$?3+dhf?W0vseoT?qaE)zN?~Tr>Dak#2Enq2V)tpupPD<;0Py zRic?Nz;+8G)Vk*bIYj%;gZSeYZJje%|!Sd+|wnN&>*-&YoSJBH=4>fo$Zj*)G z)fMIT$xagp5RZjCq2puLXox#+HB|OWLZQ~EChv`scY5O$EdIzWjUq@>9{h4Mg*tPr z1{nyk64t2q5t*MLhJ?sv0Kvhj=X$s zRXhx^&I|r5ieOms69t3LI$Pt12V3PqgfyMqXW~Vg!Y`K=Jqc&m!J0ZSHGn${va&O* zOKSZrKHN`5fAXK;g%05QqZ4b4ane z(1%2=5~6+jJJzD$SoSuj1B#id*W!FwTpAQD%tsb-RU6VUMs7P)YYz-#Zj%gPeylMw zp<1=Ib;m?UR$(} zCnVEFR2zUpYRO$KEqUWvilig0>1O=kq(6kL+8kmT9g z6L@Hfw%qLO!mVy+npQL9uh=d?Df?;(IrumD_p5g1OBq@i>|-!w5y^&V^xwKJel{MkGfqk4_8Ni5vG#+r)jj0CuaiRJfYKR|j*HYuZc5%RNEQGa03crTd2%&Q`qd zdAy|B-Q^mF{xd>vEL&3m11qn00RU(}arKE@Z?>MKIYm(1o^A}wx3;e>B@roD;N)gZ z)JgxwCT##+<1o0)iryTruk?R7kXZXHOr0Hx9Xs60*F^VC*ar1CbMt9{-o?Res)SwZr{!DG)Km(glLkp=l`_`U?iJOVRq_g9{4tgg>G9rTDb81{s^*T2&tH~@6kUhC$n2ji+cDA;OCrPywHA0)POX+-nD-l3}wamlthL__A6&4p9 z(eDMdTNGSgR_szRFLc-EcZro481f=U07(a0-;biDy6}H>2)p;j@@S1<-x)lfK?;t# zrvZ|*`1s})7E^HGuXovTEvT-0@ zjrV&TWc;3JZkXnl_OefATD5FdaMcSKq+zRrA&-!2X)hHbHTjwCPsaacGoPqQreyTR zFHnUP@@f-z*3*vjB<4qI_6S=;wWHdf{yPB%20NZ@P+qH{J;xF~OaiGN(}b<%srHUwyl?_xNfh z#Hw#&!t8$`E2KqDOFH`w-Ln#-jh$w%u-V&~zf?H*t_76*g}Hk<*6v+1h=-gdfMrqS zr<`zc@K9)EaE$~6MulPimg%vd$IvEvz^Erg~V7wO1g(Ep_c65uN1^C3kOep;u zMu-$o8EFf8=0Q$T%_k^WsVgP*Po04ccHoe6n*YXI@qhSR`#-p*=M}lgCJ(;R@4IpPBmABQbGplZz7@-k@g~9f0RwD)z-OyChx0=+w5@n= zjH*f|fCQ6M;N6J~C-O%0KMeM$d4{jrI}%Ei??2MNuXxwE!niee)2g)TXIlnYM8OE! z;%{sP<|S53o^DIgK2|%9Z}MEci@&hs%ADTh{mxfIxBWl8rlh)h83@@UivYCWD;T?% zB84i2E93uFr69v=jO~lq^mBCdkgjl;$9+?DSMe}e>NL}iut#+1EF_NmVC!_x*1Q1{)-xsM>lm@xWE?Tf%bxKw^ z;U~+SzOff+KU~IkY|QosO}ZV~cLVR!4L>N(`n{IQ2a6;;|2$;a=vuiX^7xIu6Zs=b zW#_nN&(eu&W2I zPGtcM5IMfkD}o2^6UjTEjT=g;-}$SiRjj+BW+?gUGku7ko!7-CI99~q<%yUv=!3(g zRsj5zj7;Z0AAo{}M^GjB?J33}sQ$aTyPM1BdY4Pypd-Q?5HC-sgWFaDDE62}Kw&6r zHwFwD-mK6HT6}x&Xj;`icxgfe5u=S#lmFNt$WF_13hUqtyQbC^12yt_rpxfTNCv?u zOQytUu-{F}a&uN@f3Z7KO_>pS>s@DTPWzTHbW$=qKWn`K^gYBjaep3QXMb^$0^(;k zQrK8aY6;nmy^&oqI!rEyKWo)D?a%Fxgx7Vv|7KZELBXKeaqq~rC(I0rMu-~7@MmU#NMI`RLO zIGtasg*1i+6-j*2RLjXAcUH>9BsAxv&tIC>%DrEQnG1rB&~)Y8UOy|v06Kly=I)1v;8ldrP;g?qyXu}2HH}7u!P`@M6y?eum?_AH(93!uDY2H~>OziQbYmsGtw!!IzEszxG zO*W5N>PnU4Gcpf=H?yFhn7W<(WmSmB~rm$qCq*1^(fZ=^Skw<`v2}g!RhBZqY6?UjJ` zPO@>gcTr=PWQH9%bEM+2eiZu+QSrP%i#01hgI|_MVH@%`i+%PNLP55_IUqFo&(Sbz zr@_GuvyN~9%)7Wj%_*BJymqb$hQx!gq)+)Qjvf-SHf=gVP~nJ~>Al_4#G~!3KDzfO z`Y*pTo(_AJ({5T6CIZ5@&8CaGM(=Kgf=>cEjNTEd1le1((VE)cf&1%F)FP-`D<;$a z)2Ub-h)e>wJ5MywB0b6Fvqx<#pZlO(p{hA@ZAm&mE{*q}yN3Fa!v>jYvzZH6$m--* zDD;FQbZqr`MrP78j6G%vSc^>+?$0Oc+pe(?w&T6LsMO=D_Y1ko1d^dP6^_d_P3H$Aw)W9~IitSm z?DK^T*;b@0){@YL!0aQ8fl?prt#xfBmgg0+SlfgpeXY74G3Il&uK#4VRoU|CZBUm^ z!8H^GIgj%i=D|=xj9>h{B_J|~j=4SWvjg|06?UpVioQ1~5^Z|D$RpOmk;e&yS73<3 z-!2CPXU&)}r;5nWZar)nSfd2iPr}rn$%WEDms zY$5hCnq?1|Fqsc5$CAuh#Afj%ZZiB;u2Ua*k39s=c9TF*h*b}7`X?eglt|$Y zF30URv-HYaSNK(*7CCgryGZ~xr*692L7QRrkByTp7cRy{P7AO2OO z^i}Uc-KxsqbBO)M@|x*2tEEVjng+{+;~{Q&i+hBc`1T~r>J=;i)oun7&UHsy+TAmBRx9y;4m;j5(&@$%A{O|C6@bDBe9%?6Z|2IU6l2kkkuN2R3 zadA-?@>$JvcZQ6e`88hj?aYGFQ#PV~s@`i%b)$E$8a3pKHd%cs`QbApLMp@ob04nb z&&G7E-0zM{N#Rp!H@-)odg|Ns$()MJ727H_#2nJY*mP0l-sAKuC|>i+%*-03U-GBJ zc#{>wiTyGE1Qupw=u=V}Jg7hPn7N&6zhUS8gIi}yd}FsxyZ?3dOzq6;oczv)u}7*@ ztMmNlWP4P59{wE&jJ|~H?)UP|D=y)6>JYY!KBJ|n5A{3s^Wri+8D?=63K|(I$lOe& zjkWbHAq$Wfktj5BgeK8ie@4f|QlDg3FU-OcWWR=Af5V*6PnO8)!2>r#V~s13 zgc+=yVWsyJ<0+VZVwC%M{>a&d*{NKCpJ|`#4c^r%_Lu4PK{N*p_WTQq={vUi9FryA4r#_!S%^F|DRq5ot@v5q*k95SyIer-a%?m zr0B)uhQNS$>Ri||fFy0z}zg)dA@MP__NXz}~!x-C)Ej_ADJE6C`7HNGon(gl~7B&pTSe6te?Di$5d_W{W$~ppa-i9k-fdW4PdLeC7-0tM&}=2({2uX z;tvI~C*(PmupvYO#Mn&+jMe**J@ER;C(|KcQ9O4rMP>*wUK5{HudJhqy#M-+9R?j6 znhF;i`JssP8oa$W9DH_1IGi19uzHzkRX?6xsqhHX*fo3BYm4_z3R%?gbkU*#u?@kx zj&mAim6Ly{|9f1qKb9O-sxN}i_=J;;#M<8KzOt@Kw2^(=>~QkIV%lNvyR|5ZgFiv4 z68q~LOAUA6Z75LU6ti06=3TVMvM5u+JKr`!AO>KPvpXu=gK(PX$HfMYg*)7WTW zU|>*6(V9UeF;^1V9vP(FPl>)`X3`P|zoWXwA#>ieJ~NuD_;SEKOx-=Om%LqkR*XEz z>&odbs|RtzQXOI)gc@bJpM+?R<2vkttDF1rwxdGaQI0}AiV|8l@%y ziZyX>=zY=hW|VAY%EjVI;jm1@tYT9zMl9oV)!&qP3AOI)QyjB|V|sDoA$_dv`IN5N z9}W{6Wjw1aS<9=svw@SLa9ct#G_i6Mw>OcyRQHf_QRXQJm%{cqkL#W`x8_f?_x)*3PL7tq!0ZyG z&HCV2A6E6X#;{Z3Mv?NT66r+mTT7XvqpegLWg>AxXZ~GR$;k}+Q338yWL14Man?2( zeTIy?PZEk=Q^&N4g|fDaExakc8pk^PgQIZQvjVvpi6odQl$~pj;A+9hUNoJ|PJBYb z$Rvsro`jMVtP4Iq4#_MWQ%rcHT&MEhT&GfhZWJ$=+@hs-k_pYJ0_o5!hQ(&xg1BCuItie)}gsa<12T5O= zS`?@6kunaQ3+SMy5zy}i3>P5ziSqJtiDVGH^2E-OA-5D#<9{NNUE(A~GxTJ13Y(8k zhlPc$$%kL!O*d1`f{XDkI`ba$ZMVh!{f}L3k=AMdSNsfA#vtv+a40v9(m0 zWz5C_Y41U^xogYnx8|Q^bu!y~xowAOdhmcv7-`DmGv6p9NoebF-#{>mr$v*Op)4Y5 zjZUoFj;d!fyT0B#sfnO26NC9Vv{k=VC!wiZ^Kt3S5Y$wf(v2L!NujsbOwePt!3vr9rq{=JMMOKI*bzERnWb<+p=l=ba{ZJFtL@bEvM(+ z?`DZ~k1^VE3;O}R%!S$wEkm29z4c7Vi(=%t`!sB6S9A_;yLty>>?v*k)&P)UW!%GK z652b1k-fS3yVe;L2Fa0Vfi+b4?QA$K&mf-0}2tsl$YulbpQsil4RF4Z5)tCPj zEIWA`FpK=%obdB=XKrK>of&^MU2#|(g66nhuLtwE;%}CvzD^H0*w?oUU-b7UQkJ^a zHV&G&Wb*PV&mSKG9jc6PCl?fNO0ew4aT1GJ+7<;y1RsC z!X08pnK*t?sWvT}u}_{Ad+%CxuJ6lgv*P)>%DgC6|t{EH74cu}^ajv`TIu0Ay(;_+#2wR)nqdq?vf2vZXwe3I~ z+7!Y%bi85RiMu~O!C0Fc59DU0-}lg-_L-I1w{snW>FCxW=*Dzb?G8Zg-{1<)u?It5 zuj~N*FGtlr&2uv&&QJ}=!^gl+F3Gz7wEXwKyu?Ym!$xdol}&y+8(!fkGn7_u)ujKq z>QI(PFZF$IhzXS9}gV{Fg5}JoxgfVmX}4`X+C^ z)r{y(1cwi51SO;1+Ac7uXGc#~&ed;L6%qdk-($BznX zNduzpj~mW9lQ{aA)2rf?xi_fyLKn42WHaxZV$GFSG+nE^kb4%kz*^7yO?vwGUp;(3 z!O$pL__#P-Ym(K-ZLehrHK^Rq&(B|-pP!Gxy4`Ap#iqgM2T1=7_?#s~aLqesvKU~a zbkC+Cl^{{Kht@1yY?9Ld_3INkRx$%;V1|YQ6g0wy?faGT5;`J;yW6Q{drY2ASRU;{ zB3oSdbn=4Ju5I=)*+1R>?kJNC%}?#H>_G;ZBYu4Qf0EveBO2UZ<7-jRm=t$V=t;35#cveA%pD zQe)5}cNpOgQ@m?_4F?;=GHKw=#W6fQY@(e!%iW>w5Zf)sW!-L^9l+DBlu5AukmX`T z@%dY7cvByj8tm)u zK4P%?$eD9iLN10HEeBcWN!hT+p}{BN5uXut3uT(|kFDbBY|X)1@pL9$pYg4kw;mtz z7!0y-ZMRJgzRCrK+K11uHDH~Hv~k_<48OmwY<^NpJ18yxTRWrYjq3KnFRL;F_dCS~ zm{jl0=7Trl?sOj35=40d~*TH8b~IU0N|~J#6%5>GapH*;Zhv*(a^Z_-cWPOIrPOl8tT5a30#O zZX)hi^kRy}nd+}nWJ|b2K}W<5?N_KI`H4R?C2wz$^_!=))hXVa^&eYZSXkg0(7Sn< zU7RYB3T3y}*u)})-2+CX_n8Q;uIX4fbnA3%rq<1**rxIsz$=DTYasp#%KcQ}Z&t!C za#`08H)~h2QYx+)3j9I}LdkD9GS+yriLHz6*LY}oPWV2skGTlG|c{4hi6 z=gbI+Tqd&-A1_u`qrI6coP=wby5tqylZi_7y`RIQiJfhD@TCWbGIM_#(ZkeLid&yF zD9h{kac#`wOHCB(Jky8cv2awX@6~_-^jLM9VZydH=Vt#Z_fQIn?8r9)R^jzq=!ntV z`uf|3=%53=3or8~mLDNsaZmoZo-j#br3@i(K>(2K>})jPt_w2_N#BX#)VShaxNu+ zYk{%xG8G#P+RN4DAzVYJAmArB_9SyLgeCR;trbhJb*b6DP)e_kh1lU|mK=83U+(9x zy#4ib00$rczcc*(Lc(~v`AklWPuL$L&fS-&p1j|7FSw0`6(4L_Vd8Z`MO2;xg`|3@ zXO*Uu`v6Yi{Ktsvga?jCJ#<3WdM7pJ&aPW){=o5*D&V@e43#dP9`Y)|km>w%iMKHeI*@SP1{Bbo=ECWE^|_T;q17cAQ{rHE z$9i!iyR!lR30i|xvcpWC%q5D+y0l{p<_?`f7V$b%Z%go2EwESavXW+D_Jegf<#~B| zT=c=imoo4AVXM0h?>lF%5NoQ!p6Lzu9X5(rgT5ITJs?=%^ zp@$B;Qa9kpNfJY~SkBth@=0mHWo-V12zantyQIw+i>T{TTGD-2L;A!sgTm}hY zP9FYgmN3cKDiu6?_N;iroqwLDm{4F-YmFY5%8+fu+&zW@JXItK-;z#!KReXQ=Dg0r zzH5!2cEO&e9`HqN_M`~{m%9Z?UV=}+?8<6u zT>>ex4b6WaO;M7NE3CR&|8dwGhtOBwik&35c-L*lRuee&og%NkPwN+YdIW}Q|P&urnwUb#^i;s_$=Dwj#4d@*Rzqd^RmGPpR8l1g?Sw- zanuyAhx(#=u5WytD(R_fqZOCf2`WkC;a%rhUW5{obMfctp+Mw3r(Po!4jyg_0f!f}9upaLaj zWMmxE(uKm(jy^oP9>w_VcHU#tIOF)A1_zQ;rd(3al_P{5oTk}{Q!DDUdJQmQ`sjJ} z7s2YNQm_WgV!-nV;~^8_Feao44YbUPVhY! zMF));=;&;GS{y3X&41oAEf(Yjf8h_RRs$2+az_J0%*#(DFmG#v7x8L%*kCvPBN9q! z=TJLaE2i&ZQs=%`Ixk(Bit+5nE!HhP%;N^9l@YH7%TN6GH=8RN8uzciOiV-${WvnJv5C{Bwp{eGX~dB zZcc#V=hE&B039;(+!B@_0`SL$_t*OdtBx0d2FD>Tk0H1zl%)S1CqAJU&{%D~Q78cj z=T8+RV~=X?!~iIY8I${FVeWxFv;(ARN6+|F607@5mP|7BXa}Bv#ow%brx>@K z5T6s>GQvJWFXI4(^~h5D>QuXYfs~`e-Me>V0myj_Qoe&te_L3$2a14{88E4c{yK}f zF;d%S=M5aIPUzJx6=hoOv#_j;N7t1u!HpF@CMKy7T<)?1_dfurM#^24i7t!@=b~&; zj_8AY^a`JdjnXpR90{-|aC;z{M{2h@4Gs0k$JB3?C;{*xQLTLApWCBTGs<{Xk6}hn z;w5;zTwk6*(6dCDMwEuDo!vNZ*oWRfUfFmUduim?y=l`G$CVK85nn3}38M?15Nw{x z($0T|tBNN$j>6%eWZzFs(V~0Ni&ypUhSnKptR8AToyDo7f&TW5hU{14&{Wn$u(4?a z1b^B27-TWU9b?syCvuSwk)xNDNz!Ahfy$`3`t?BGuIG+)#(nrcckuc7`4_>`xLq93 zpfSf1U_9vMLdY*HPJMQSBO-+gCQ~8OD?u(^jBbUmdo_0_naIr`^ro%Owyx6o{lvkj zot+(hAdk{0L8Dg8T|G-LVqaQb0?Tt*GF=4W)AC(jV2Y(fKjq63b@)mU=$HCt4+uA09# zx~lahVuVZfrx~@d#oH;WNbTUaI_nwBFxj#Vd^5@r& z0lU<#=`VYI=>tS~C_lIj!xmkdU<+V=l=ye5$0+rh+z0sMZp@$O9>MevS zzUL=+Toa%4zrKzHB@|IKt+4)(f%B{gNwk+*$+yf{3C5mB@JsVR8#X0Zwq z;3(5`2I~^0m2IT?o0Cs3Wz{Hn9fH?6T-|9{={Cx;+TPx-{Pzs>M))r4d?t}k-r&vc z_@q9QIvq(+&c7x8!K!-yqB@9>(^*hNXb4! z64DN!7(>j#!xc@J2+n1a(^+HkvTXnZgf#g2>e)}<5D1XAn+w-{bgl-}%>JRy4y7~! z(iv}uD(GcPZwZxqq-BeQZGN2V6t_XnVWKo`Ke1TiheY?I7{viG%I?PYhy~5_{e?nd zf%3hA&=ja0(5}B%dCQ<3Y%j0ZoWSuu1T5gt|G0LzPkQY~AKjf1`%?QgCMKr9`B3XE z;iHb%kN(=j?~NrFuH4`se%Vr88OZRxu)X%t_*x|JJZ(QXkzFA~V&!u=+$`1n_%6K% zw#7kby8X{(%U8d@=V@eOm<^rM+M%e5 zJ~&EO*Y5PBL%M1Y0SUF?R+Kp0y!5(9jIp1_tM~Ayx(u92IuuefGy$XJ@8;%a7kX8U z-sbvUYz4IjR;(iL=091=_*G=)Ac6Sv^2BqfPlb^BRI*VG#Yhs@mgZq`&f@h!-lp32 z!^BVBmSvF!P&)9a3%*su4h$R^jZXPw_}_>mN63Q=q(AikhbvevpvRU}_97Ey46T75 z?R@k-$n2=+k}fVT`etSm8Ne+J*L87(pMF>L=SYxKiR{+D2x1E@Qm+(LD_i(`sV_OS z23=tazER_);cS)IE6#DnWB5U?mjyz-9Fv1EJ@<-LBj_1J@bK^_e?ScHah>XPJj#+! z71H5{gNlmE54f;r(}t?&;ox@5{z`B_H|OrPN!f7WjnXIu*)U;#M6Hl0>B}vZ_%Qx8 zOyr&LGa-q-G;CU-BysqTv;XPreyz!&&BR~g1#c+Lz2azn=A3Be> zaz13IrS+e>{8;&i;&>ScMZB>e*+ zd`wtqXlMnPBThuZjPQ#*(yz#&`%eEoGQ7lm#Ptg%@7ejwnwaIBs-m>F$e0T4FBCgF zyAmZO<>rF8rSa@YrYxd5sOzqy`Jva z5uQS(PiJ{X>sy+;;R37Tft?q`4059GKLRNZvfjS^Ww&+nC`GC?USYDn;LY$ek_4i} z1@!$_UA!xXxFOjGzux&lC~s6qrHh0xTq5y1ZpGc);JMc%D5WBRVq0EoUT=IZ9T z>SU-}ySf~%-_^EBcAg9F3mjv5@r?J{oTl)BfI17DJ{8~PwZ9Zv%Qbj2OA}vRN_bk7 zJk|Fb+Jm;;ANY(dgjKh9K_#~RlKH|DPnbezSiNeA^wyG=C{Af?_6~iQeX^c`0yv!Icw9WnN#!&n8~W-~CS9&*SOi9MI#O$KwLAnzq{*HyAU@ z^w|xG+yH{0dV2DEPnN(s2!!G7=PWib1z&aAEq(I)=h?bEpWAZ`0?&IBRDpdcJg!@a z9^yHZGg&vQpj-x+@u-BISq(9gCT?z3G~#$Sb?zV*zz~&`fOTwdYfCDBNdz*Q>sRW~ zVb9vj_+88LMzuo7Ra&NKwO}DwP?v;SStxJ?k+jYj1|1buV#ineo|oQ4vZe_%GYadq ztsKDv{rxFLyhZiJ34i>-+*U7uHt9_RNt>VKFFa>vgrUj$y^?Cgro5Hh4So6Usp6a` zN0G-B#ZT&$h;B))0`|79XF0yEJ>C>SvGBNY=+XWjOTUnNSR|wH70##R(dawRvWXoy z-t+z?W>KU5^OK3|=GM56j~}!6_RHR`SJ&=-2n9bshlfYy6l?}Op$JcbgO3s3VMGFS zw7quqMxzRD6w3q(op5$~pZY#K+Y0Ibiv!#u+_T?x9~cdOt|Crk^ut}*m*StXmP%1xwvAbLnT z3x!#yBjrBS4;_YrnxlrH-`w6FEj%fnwyti%1Lht7=T<$x#Cog0jEMElJD7zHSJYhb zVt$wr319d=i6mLamj%^ANcHFGX{FZ9bzB1%Wz)2GSym^k@i7bHkWGLG7Z%if%leB!AhYpboP_Mj}ludWj=`;bA9x(?`?@>b}g5%}9oTHkSIpc&g48~3bRr~#>uc3okgaJ?;wcz?(G}q0!_vz>@>HMNU;WWX zBGWLvVevWiq73LQOIdk%R$8E;@R|YP-qw?@BNWFs!B>~aC9;`Bw%}8`+^BZPOXPln%Q|nGnuOQk@)W$ z=DSQ?ROi!it$5wGbYNiMVOib)9jQ{kUDj5m)VHj-pa~qQ!Y&SIp(yVRZsXIt@Ie87AuGfm%X-Mi^A%uBEVGc z4z~T-ZkEYmG!3BIk1t)(j%7<>lUjci`gLa%Ud&4WpW7NwU#smk10UI#i3w3^8s(R3uuiua)Qyac(iORPm8k6c>-ebHD7U|w-?O?Dv{Vxau+#OW z;(#4#S}%Os(43X>Y@|0#BDv5z=W376?BY6y z;yRmMeIMuzQ*3zGNZrg^q#J^c3`m`n7G_eko#6zD2uq>C>TAL>VTmC9U!oCS%&2#XLRp47v7v*!srYvN#i*uMxD-(IOF2pix3D{WA^Kt|AZEA!(_Bd11=PSLQ{fv2eo_ zj#)b4^}sr=s3X-ti#9IYHpPV4*%n7B-$=FkbJd0uiN)o+MWrdPU*&064KOp;+uGVxtEnFm&d_g+ zX!aISd2n_x?L4_$sdR>VWVJ6OWWl%F7vSIijkqeygqHF2c#K|!EX?;K=3U6mIg%dC zt2$oVymp`{W}n*I*da5BIg4|lVQR&QjkNe_KSVCK#L z!OSO6k%34mTIG|%R-~{plgj^1NB}n{7-o*$Jc@s?Na6n{@K$HafXe2wRwn}5!_LDt z44&?SuW^)%WszKLPNU;d;8~?~Z&s~N9PDy!1592}0IXjAB}rgG6@7nc?e8~#Lh@Gb zeQcUtO-BzY-|}LwI@T4qOJ*%dVtj?q)la0u=W{6kX4Uzam->c`O+yZZ$Lf& zB%HwH`4nGBg|~lM625s+zFX-cc_P|m$HGlJ(uhsUIbnouJGl_AhtT@|%$1D~dkpxP z2FJf8kSN}hOxYBqP_pII%jkuo6+|)RCmtTCZ z6-ogG0%+YPALfuDi+C40=C1B%Dn|Un@(Q*Ue@4u=fLHvD8BT!gL$(6Gb$v?6_$~{N z_*_=3iH$@HsKEh*ApIp5BK*_}$^h!p|A(vh4y5{j-^cM%NV1Bo9D9>8LK$()%(63z zGO{v~Jt{M#jF5FuM##>th>&q4GbEd&?Cp0y5B2{1zWww1r(Wlr=kxKn$8}%Vbz5hB zgEUpu-n=RK1jj69I}4)JV!*l=-jHkE>vRL8b;J&fc>)kDioy~Sv0Rh1h?U@R;PPd4nnnZrgQ1YaCj2%a4|*_z%r0tBgDU|Yke3{);%rmm`Q`oHt&t( zUg;|XK7)}Gq|AAYxXEul^>4NDZ;LN}gLlS3pOD`bRmWak+$^KQ&g+h^y8^#1G)^stg4-YQ9G&SrYTTu8n{rQtpohq63|R ztP(+zxZ_9(Y#;Lxn|=DL9!}+z(`EKjLsi)7W}1jhx6dKCvmnhTo0;7yNc;=V#jG4W zkBeU$G4i96uy0yz?{hTF4u^y`lP&>`a+3=6>ol0+3kibYpPBdEcY%YBnnIZn89{MA zg&7d~@tp4|dQsaRJT&VrA3qOeWHcA<;XEW!-uWEM?J2t$rS!sDTk5+VwLmNLF*q96 z2o%DOuC|Ur$o{TIVEfv5qFdZ@aXsO|&}65mXM)e?`92Ud=EnHCJ2*HDtjvDV2XLkw z`}b;~QE}Y1lo-7fjQmh_yKyFT5w?KzL106NE(LoZ;F)XzK|w)(ng6;Ev(-J_A6jE0 zKPy97yrbzK8n@#Y@tXo}CoyjPp%3Ga#q;sZ(K3Ci8{fuO)u2j!bvMl+zo206E6`|s zUygrfoqN;>i2^hdMTFX~&W4|G`%J085k!Luk$i{~vnZbl0NmpT?06Kr!@0#)B_3>r zspuXao?1v*7|~2|k3m-Oq`4zVR&xZdg|y~E3A?_z7uR~bf@{mdBK6zG!$z%T0b7rW zXeHH^kNY&6(sx^9c+65SdMq($bG-o~j4bLsp(M3}fT{>4cGJ#BL1+lpgFGuIAF3U=-Zdzl9b5qvrG>cR>DVcan+Ws7zYxl!tvToK z$Kjo@6HuL8IP%*zLH*^mx$~o`aWY~F-HL@~&_G^Ac0I;p^7o`6|5uY9J2tX*m^T!t zVEUn9h`_G&0}FxKZt41#Itaa|?JI@VMQ)2Jq}Uof|gJ~Zgz}YJ4vgh+s>JTT9uEN zH;m}`>F*U$n%ZvWIM|Jof}5ZJ^FWb>l3HfLKy*voUL;gd9X*(z4zuyCBoqpLO5LQA-=A8&1BjnROx^!gRIPa(w3xEzknF}J z*VCvu6gNPq#xhjSt-aaf4ikc}w%3#@il2?~A1EAUi3p&cceI1C*-WylN=Z*J*Y#rN zw;4+IsSYcO0T9rCGeA<=y@y8VTfYV188x?5{?0@jZQJ;>Z%Z<#{4xD7eOp|X`mX5F z(Mi>6nEl;|LOjT$PSVoWPf7;^qYaOsg%v@|ufyRb#c&3}{UyQ7Vd&^3oGr8H2Ysui zIZ0_Jkrv}OM*s$csiRNYlVw*GVWgv{lxvXFr=hc5zvte_jm6Z}#9TNM@R&>?;Nj?d$DP}0JJ-IhVBYMzf(3?uO^g({(pp0{<6h~G#nzO zlcFplR4f1pCk_Ljr5g;jVmXF1TM-pGUO)!*ec%wg+epZk&R`|(o`i2Gj?Zbdw7&XY z3hu;5=r!x)1z*Pu3_7;0Pjp=-!Fbh1=2Y)^#jLde+U~6p2EaE}(!= zJ2ZW)C6?7>I)DCFLC}^gh5Ep$44f!7nK~P)ppqiAJ?q8kJ$o#sqggO1bflb(GBeq# z5htAHVfW`wyu1NMdr<#CmmN-Ai@sO#*>Sy9anthV3^{<{h-AqVwBDUF{eQTUUAy&f zC1ErUPTnzuLeqQ%+A13@*WtNd5Ko27b@4 zv87_4ZVqb2Vbh@!{~}nU*AJDSj`}-CvfXRTY2L`&HKbB_b*$mPa}4r5j%`K~u4M|H z_NL9CXTO(7h?P=RQ`^ril7|l)8gc1I5Z&)Y1kph*{ilG&0|P|KZi7#^Y@MdJ-s>ad zLU`)^gs>b`%hn=%uFf7~yuJ<_H=~=D7W7X7_J*^Kdewzv1i=GNb5~6>|rWeyChz zUd(Yk#FilH8*nnH)U0qZ4S%1it0M0wa5HJ@K_%gJO2D(9QnpO&Rl~X`2EFUG`y0C3 zPpvoCJob(uc{#+N@MB5YR?g?9AIIw(Z5HAu*PShc2(_1mY(2gQ5H&$3@fDb7QwU=e znItVz$kDIn@f}Ws#o5^!m+V^DVWX3l;da~pz9|wc$i%|4T&}^(Xe6@ zmfcY!vxH@Dwg_{f_e6v8etvoqvqczOA!UhLyC?{-QPz zVBPJsIZfsytbCzMZ;Zz?`!U}3>>HdWJPKrD;xHmq{Vn*{p#G}lfD*JtD_i?af%qs;0o1@rDTandB!>$S$(tTU270lcj*|D^sPMpOc>#5=0DM)hk1zOWG%JF) z%)%bE#)TVd!Di3kjmf?v!og2ZyQN%{Dy*@}6`Rg()t3Gehj|R2O-oNNP9LWEV2M=s zpelLDZe?r)FSm)3!K{Zy%|$7Ea5>N#dzO9=4y}#?TnzMg9DJ@1~U1*P%JJH zlPiU2tV}k0d7AN%@^}U5hbLhtfrFD$cp~xKMWWXXwf5DIu;#rd3jvaKWq|-CsQ=Ux z9$7Ng6O?Dd313}3?5s+Tl=*nT2uzXuY6Ov+xd?9VJ8ySnydbOcX}~63vcJKB3mNvm zVzC3V3yTON&xG9_y9pq>3_8nv#WzFFI8w}rh`BP8WFU*y`$r8+v&F42=voCNxI9&X zCy-FeLkdrT7e6#qUNBxW-~o}93c*CdzJvuHmgz8zIyY2R=T3&Vb$vK7P1>8_{_cvj-XJx6fOeJ&E0*2qk$@(OL%(gdMO%;-aF%&*J0bf%tDVnv?MSA4bhga!^1paO4tWpG4luN&lvA!mqY# zK8W~u_w{1QJ8>801Z6S(VT(;(+c2X7P5qdorIDH_+-$6-GvrRkriF? zdZ>nVY+L2DeX4)UCfPv~Ml6jVL7RLD`ar7c(V^h8)%(WzFYLXf@8201C~5RMgKK7g zr~n3ezndL_^z48f0HMZai_6A&O2<|~CFy}8Rf-&RVbwbI!4Q7A0PuVg6Z-4 zfZ9XtV`Ln@QDby-X54gNBta*D^XiskR;urhP%gn#ptkb;y^HRM>RqFu&xVlCh&!`I zd~3Vb6vxTLBlv^x=P&ylztbBm4CS?ejLhh)s-FTSX6*7$I=ND7@B7c-U3R%Z*R}S7 zt{%zS%7D_;{dA}_H^J`mhDh^{YJ_lv*#7Ja1vJ!;l$10NY51fl6s~SGD`4SweIvOL zEptXrz$9=A98ye>k9>Q2TJ zdO7R+D2JJ_I|ML*+1yAsCFbcbwgYy5_IZR?j7|4b0CbRsQ2tiYZKDDN^gh$Wi@xh- zhma_Wn@}>GN_0P2u`oaRKz<=scU@~P_<%b|!At<{xCgx$ho&4p(bufKkmbi(zZAlo zh=eQQn>EYgX|J6A{s(4+C<#J#cAA{bYD@8!9m&0}XG;smNHC7pOl82IAoH1w)&Hga z@Y)cvNi?|b`C^1*01RA!vdh|)fU>2OiEeUuE7no|E1V^QuTMx;w^0{&?n2lCph_uj zYHE^424&6Xfxp^G!l(F*?@`6@@XWZuMMJpw6f-fh8n2Wt9Htl;itvg1@+R>tXP`Wl zeFrQxNx%NCP{wB8f;M9D>Xr{ETkGp!X>e~$OiceKj%!MAz&3-}J6J6XgQTEG+Tj$j z62nv5HjI@uvU;aq9pF>XNt9PUV@rNGxwtGFr)$lG@V9-YVKDAVVG|R6_U!hoYFn`g zj)4-&4uw1G>{DpLyY9eLplx*=q&jPo&l>lCOPmr$;2B5lJiYw6!T~YIzP4}gY`(l4 z7Ke$<(Z5$x5}&KJd5$vlxEluD5D2ylHqp{YPaUmI**K^VniXa739|kMXDzD_9L7m! zZK;LJl%AY1R@p(g2eRuVzh|?yUtfUTsmfH)(75RK7!4Sz@D{)NSUO9z-X_g0=bE(M zj2K9%VXuuMhMGsw!3Edi({KO%8uW*_NOe1(j)>(fh^arNNkf33ON)~CeY`|Y@4JIc z>M5)V!U)J_J)A5%Q!eEX9#;yNyqV2QB>nN$4nV3q?;YVJL= zSd+PNqrIzjCW68%6{gJ0UO$UIKnLopGkcXwJ@FbcHyW%wcte_i9!j2aM!G5});!Ry z!8lH)1rLb4-{9bZPfi4FmW^ULFzJ)X`z-ON}lv^D#4m+nlq#x{U3uwJ2r zSHC^w()K(60N!5?>(#(32z+b8f364q1F%%MQH6&(zrM|Q=+VlNf8WF$n+}XH7PkzU zlRPX#-IihlI-dcX>TF^_98eI3OU;`@=MNL$_efsn`r6hpzckU4{6-V)clqW_w}D`G z^$rm`p0_pZ(US4*1WmTjDV;&$3gD;2MJk7>hX4`G0;`v*?5v;bcj;Zk`9CD>9^Vw)@`eJYRP#Oh#AQ9{hI!-8##KQA(8)}xrG z)Q;~a^~EEKhim}FZ`a1uxFltMYq7hatwGI>_9FRvnAlcB( z{PbPz@>doLZvxNCqF;Z++Z>`-SMNrQJaHst50ai-Eh;D|D4e^SQFpzQ0mkGNos#pf z>;HmLRg}ntiyNzKX?_2jxRvpG=M!m~RW!7Z9y<_$YM7{XX9W z^ap?`QY1R=IoDtSKL*APL@OTsM9<486-cTn7))=gVD#qZnPrnrabvQrcz`~D!>qIQ z6s99#10_~|7NFe!2Yt{Zn4umzyjvJ%U8k7nX%q!6!%>YZ7?|2ddh&q-Q6OXoO%m>7 zB9_=R#JLpcqg8}mzn6od*VCBkle&dADrePc5lw-yr1ap)U*qJ#6F!Q>dBm^>o?k?6x9TEphEyOHH z%h1s98_3#!;$rm}vCg`$BS6;3W2zw>G`m+zghNn(2Sr8Q*;PsYNzr{>oJX>g)u1pA z1%#Tt0|@(7lUS~n{$?!r65FjD!lteqK(BBk)DAxy5t42Q((7KaCSzu|q{6Ru%Qb2* z=b4YJBBlKkh5uQs%=tJO)Rsj)$IEp~0$t*YrxN+AN)w$#uXr4)cZri??vKz0xSD}^ z6+{e~UI84B+M4i-S9+M~PoMN$mrOB!2E6D`l| ze{kSx5jypELo=m5%{^tp)d1BQsQD_&W0sHyjiS&e5Oc`(M8y;!l5R3A=CeEvPwsRl zrG2m$2kfT1PRel}j^sF!K>zp=-~luM(INjyepjI{?{W!ht9++g{+=g4j+D9B(>EFX z^-X8>O1IkLWr|Zg@ad>=z-R3k2_Q)J#@;{fYfy6pX*n6(`ow>m3UTa!GWz1wlGgCj8%8mgbA~1AXtC=WgW>9 zz~H_1+CU;|PzHaX`FvY@>(67MDfKJ2b0sZ>%<6W|MKF7=f^&@TS-`qRJq~elPDJPk zwiuBeNL&CS=@yLUQ6aaxnMvGmR7+L@Sj)+O$IkBJ{Zeb~ZR_b%idQEDk=2vx@yO3mCT~T!76g^JIFHJJ^%O7 zp(tA{1_pf+pdHH7i@C)7<@_x9qbm5HQz)|_s#%Lp#Lwwt7>#HJ|IHr0Fe-t>52T7% zF!91Sb@@l+|22wsqTfAl@=7l$T3mGm+Rcqp@r8V=M5iM%m<6sDY`iiAZUz zB!lVrECN`8)cWZ@LGP^*)CI5s3b44XEeU&gh0ql38#0u5NWlQWiTa#=F+vycJTY(| zGd4mx)_GyBr37Ymt^N;e=(4pPXTR8LYYYbiM(6NBp)D{r9SeM;;SwuGEXIM=4kqs=l*Dds1V|`Yf!US_ zd$o$_ZuRHIz-;xj72$!$27%TlCc`5C|2_QXGTFY)2N61>}V}ZGgc^`l&7ImrOg*^@s^HhZbGKFf~n>dpW z0$_8FD*30EN7HQm;-Z$nYMCvry8TbdAblQZc7-SzY7VG3sH=!nJ@^3$rhI`I@e=zm zJcUrd93r%*uO9$zcmbAFUFW&IAdzsu8m(3bduGsg4mL_ zK2{LEtqC+5x^?V_?1N7*wF-iB_qB>m%#2ylfjkHS6TN6`inDHCO0v6|RSp$Xc9FsY z-P9T59%;hv2%aT>}Drv(Z=JH18Z7?7)^ zJUmIuy{oEDxKux#>gOBmQd5uPMasUU#EtzCdS)X+&pdVP5kk)dK=jJCe0m)cn!QzJ z?I12G*Bwwg`6Xx-2s-YM$>PrXJ>04w%B4v3wTOVOc7u$(mkcV(FYX*$7 z@2x@VxN_QGR+Z$?Q$u-i&z=e$_57?YHobh|%G-%Z8c{0)u%gC5pT%yHym(xVh4L;@EQ$HdTx zz%eoGSxJZW!zum}F=XEf5dv>c@1+FcJq1paV}9RVs=AY+BG1mz`u#zann!_xVSb&f z=AmpMKt2LJQHxJ}3~1)u6kE2(8hCBf39-o|tY3BOuFR&!MkD|oDjwR((t*P=9$CbJ z$PH0*5mXVx8HQpx-3SeH?C>bSJg}YViLth}_8Y_)!_$=MuJl}sCc_<(p9NVUGFy;P zF3lb-VBbT=Nr9**8{wx%WKpsRD^tLIUvNA7^Wy&K`lseRj{9{&aY%V^RX3G6CNAzw z9qibk0Spk4Y~TfGAg^M&6qlq-Ey`Cb5`2?g3=x(MJf0l|a}euh(eTiN!fW06?EV#y zRV9@yaHal1Mwa5p$kNB>_X&bpR@9$2*JNt+%e8189{qK7$t9q%OB@-K6$ ze?a7pi_SNCh9X9!si*|zUgd=dQT(P2VDzhe09D(&BEY~UjXnAeUQB<&(7$g^bSLoj zQ}!5a)a+BCC_~_vf#O@uIapJD1B26vU@Z0ntnEY<4jLJ-AVHav$*%t(#`GFICQdg@ z%lKU2<`c4%cZzuo|W8YE-SHLX&4NI5nmica*dZ#2F-h?d^?Q z$TU8}f56k_ho-v;vFjp0z&O83pZcFm{%`liHzmx3M1=0|nt)YGWD{wX4puEbf?jma zZv?#5WabaaN)$87AcV74I4v3=(sny3$~9^6IUNt~i6JmAbP>pchmSbtLxpffaMaLj zz-Lhi-};FeJMn+Sr%3s#AkL4Q{zhtC^;`pP;kS=y^*>Y_vr6*# zkz(1B;{MC03j1oxNShaQ=0I6n)F<9YIh_Om>W=G1Qt|qkNf8;QL2fHSV8poczv?mZ zO{sG6y*_-Q4@tlJMI9^$LXex(GrX!jzPBP2kjVhn&Q0#~)rMmBdk&dM%0`Z*iYz5& z021yk=z{FJ*KT-~C%iIZ#`4}S&6c?ns1JEF7vZID9n+E~^i%;7%&o0i{adGMKeGGd5h6U1~-dh`{Y0AbP$3dd=X~K)6(AeXAwJmqeY_1Q##}!VqnYQ8sKz< z03Y?P%?VGCO7QYKq`MB@MT8`Q-NV?2TGR^arz4Dh)$i{G!U!q~_@sScG*fYNYh{+< zaGVW65{>k>+eM*i4kbYrDk>`J=zdo|7Y*Em0w!582w|;`zYu!!H0hOr4a}HT%D1u^ z?3=zg#nNm|A(Vq04BsfwK2DTQ_)tT@RW+LCk53->S}85zU@{>iDBQzpB*m{5$DhD0 z>>90r?E?{?kClhV=KB*|(a2MV(u3--yB+Tmczk>>h;2J%*(}auy&hpdb1E(Xjw+6?pe;^T&hq^{oJ*I9Zoiga zF{d^@*LHmKFe0)$$B}f6#}?8y&d7-0d1X{F>ddZ5yWoEOA#n{az=0Zi+zxUJ5=`QC zp8q2(2zv1^ZU$aKlxK?&&yV#qUFd?zS%vS~PK?2v`fcEVf0Bg+PIn)h<9rrTsG~IX zKWUHzH5=wHEuR<|rn)p#Bi#qMH56W*m&AHI|6gGPOno%pg@)aAe&f^3ANUe-tn%>j z2TK9%IY$r1HvaFlNoF?n%Av5N!JwnULLa~pIu4&Hoc4q;;2I!bwy6R#V6nz89$UAP z_LJ82*DWgf)bQ0L$dh&Yt6NUGx?iKFJCe7r9b#X20l)qaSFo*ECHADs)sbB)1lxrt zkD@qEFoz$_cBAzE_S(XB4HlCt=OymxZhvSN`Hwoi&Vo-8%+)3ke&P}~_}540*$}FF z!R?2HSosm^9+NsVU<*#KI-k1_s~ycQf@xL7VFLj_SrKVt>mxZrB!{P(qnJlE*MB%Q zbV;NhG_eRTf2P6AMqa)F|3D#JgwA*Pr4sk^Ka7`*$(+U|NOdFB=2vn?O2*?ULKvWm z+$^q+9b>kXqf{7uQaG)Ae76wlS0A6<1S*C4QMiY-@vyYThZu8r+l7SASf`SiK{`yvJEwwmJ!G1BOkd))T^lP_ZBvo>$QkZ0h zUNlAI3rwEEvt3zr4N=O-tA_JWIa7eLC6m5$+^F<(2qoKA-jH|2(lq;F)%Jv>f7t=j zQ`X!w{9MeG;xSeU69W_9LcH#)qlEbZ-Bx;xQiXx(c*(0kbLKj_@E5 zXP;CM&|dHB?Y)Pf;q^Wp64N{R6_0)c9|%GsOzc24@Mro^H83>cgTv|J+dW3%_-N{H zdtRRbtIP7q>FMCqs9!T$UV2sQp)~CwGGx3YfMighEpD<<0(=cm;fjQx_C58Rs>;d* zL@{}8!TXA@zrn~-`sZZ4S)INRWBxR_A}2$K`i)`!B2L02o3>6^6-HI|B0t&+riBP$ z(-|>>R9RG;h{wGP#O6@TEAt9IL&REuR;S{01`8JRzUIY!vVe#13e*wk^<6!3|MO}& ziUamlS9jyocU%()v1COTVSVc?(Ms_jmfHIl56pRbB@R--yCS5Ob`#zB5Fs-hFAu=e zPj|blrNfIadzK_7Hg*zhT&EFdu(T>H!eU4{ncEI(mLR@cHVWZKm$!b168=EO_bDPR zqy)kUq;hRZ|5kj{g`a(y6_fqL#Y4beS(DsMUi5xdTv@q!qE`8uda~r|2;#)EemK4- zW{>oLsAKh_bd6a1&UeFWpK-)M;t3|9yBjUY;tJ>@fZHAZf1Db;^b+UA%Cq%PuX@Bf z0bN!Z58w1THC`+~%XbjTdxip0Y7>u30B?SE35$_WjhMUx-Q)l)C*1uBk<=Hewimjd z>DJ+HXKZkf7&>B@AHq8jo)&{j;nQ=11oeq#1l@)c^2vZe?B%_`+Fy4Xfw@N(o!4(; z))9}NS#|jNwS_`uYLpNN{u+s;@r!kI=nOQohm_w>_MJ%&4inKE1|PsdfV1K?pn%Uf z6jjKgeE+dDs~%xr13mbviHUl}=7tG@^TFI64@WYy0Tq>YX*T*%P-+4^`i;OJl7v(+ zw-mwGYB^T|E_}5*gy2g-6w-Km(=)5F%dBy!vaW8A2@uP5Ywwg*Xx#RaVXPEbH!U}TEeKWU12R2rCgC=5Aqe)n}U%b0~T(+qp9gg0Ir7?OlU9aU^^%e zf2e`tca9iC!$D7p7{wd2KW_3kp|kjKgMbY_0aq|_5%xS_HGU=-i*sv8i4SJNzjkN) z2o{s<#0FBH%P6j^ysDR2o)9CW58hGc7XHL@;*_`8xjW5xN9m{(QvXajvMvIAFZ6ZG z!A*Q~5;4FG2Ge2V+UcT$5$GQ-glkFYlhz870zj8oUJdO4hlTg+%shji<0n}6hRclJ z1jm*>4TIMTewpK-$X32b9!Ku+)WeUa-(Di6o;u z|E@xV%`e+?Lvnw|5i`BchKMu)cgKKeO9Nb@Y@_5SNC(`v^}nE95WXh?Zw zQE^RAPg)eNXsjp6|E?&kDF9|e@7GRB1$*O&x7UYDC>5w(Bt9W24HyI=vXI5nIU|Pq zz*{4L#hyx`q4S!3(rNmFoJ$t!D7Reu&RY+)gQ2bgUmykSN=-ozFFuseM(Z0%w<_THs*xDNQjFAauOr1NS0-K{sLTDVeoJaJxY5EM{62m$PBcDF?& z8yLbNVtHnhZAP8HH%5soZRFG>%p+_{Nsc9xM{ouvp0=$owZ>*lzte_)J`5-K<seA_;x9o^ApHp>6?|)ap7#7bYkn}2M@ceqAi6ZYXz~^0PxJiZ3M7Fr8$85QRejfBnrH8)nNU06ls{RY#z-cNN z*|N}i-CcZ3Bu5gN>D{C-$7G$>QV#S-hGao{ocxhRyLbXa6Z2oG52rJUNh?}3{1#D15>e6j^Z9-9|64w(#3KoF{iY4vKH>CFBA28xL z4j}fm8!XMSf#r|eqI|Vr^Lpj2<-F6n2Y9NULem+G{I_>D`=%n*_eYX!LQ=8P^zbBT zd|aY_DjIf4GhXCRrB$UE&H-;b&s%xbJKmzXg-oDuAZHJerv8gLd?zIU1ChuJFeiNd z-0)f(_@47pDEQn>a6(8vpzTvlgOa*5Jv|-WsXKp}d2hp7x5!=zfRBQbL)V5bGFYhQ zU8T*T5g@xrqI}^+x>;Xa(3*67%#L%R>TU?ga@R{6ScOZC+^W^c*SbLyE(7}v`r7ETF*isz@>98Y3-8W;jCbATz?u0XZ!;KDUhz3n>jB$8>tRS4?)%c^ zxvnq`H?C}9$MIjOD{o@5?Sn6;GpZL@cJkuJG{`THjP?(r;EOw3HOe3`2Zf{68?XJ- z;fQ^UKRLA1TfZ^ib)1o;rOY81_m#b3!a{K2iSx#bpVA~4riUF$XFM{I>0*WLxh!gg zYFLUW;zquB9vFA3ZmEv68a`TN*Wt||e;qteQ}PWFe#4Px2ILowiv`qg0}E`r zz^(g@$ol1GGNh{oTjLsYqV26QA96%1`Z|?Aw*A+b=C0G0qQu=w!p>I~5?6tbt7kGv z3uVOuGBd3Z)#wN?n2ts~UjT+@fvna}N-Z-Sn7uFrzLfTRAPz*d^T)Xb1v}Itnq$By z21&BYegwem>K_4Hq`72Q9vPW^#Ki*Ay~2!Q>Yg8M&)M_HESat^!3c5YyHo0^aPKl+ z!0V@-E*v3sKUPgvkJ&6mfU}N0=#FKuma0*6;nT(=%ecWSUO*33S8yIT(G|Qh!Yr#K zLrZJ+%OaMSbEF+&Tf;EEjR*k&_dV`%q?KP~Mu(RxU=$jn(6Z&)Put#f2+o3Wx?ZUJY`Tdn*b5dgg3hVn-xcNI zI+)|S$G}JTRCQR*)}@NWCAO`a$=c~2J9sIUc>m^Sur-IysVIk)@H*jh>y{%A+E-Z3 zDPwZ6!ItZv0x!sYv{>4v7kylDXZS`m%2poF8WjGHL-q1$Q|*UK|6>aV1lc z==SK2gti{SlHQjAmXz>35s!4>QLxox_Oj!da`z1PYPAE#Fu3t4V85H3zqm&6M9Z2o zy`oi`gY*YzMK>?OIN8O>-2mWn3Ddxt+Qd_L=YcTo*mtE-fJuY(0N^5!lZ|-gl+nr- z5>(wzPIoTzdhOJM4MtKzuNMywj-xAD);|AcyTT~KYhXn$tgi`wsU6i#VFbqZjvA`D zzF>@wu!<9gMk2|pZ-3rQP=9?g^JA5{x5=6>2_~sFGS7ja6pkT_VIMYk?{JK?<)nQHE~?Py-|4UzH4_?v+~xa2Wfkrf8^P*X)0M8<+MR0`)hr;* z1}dTUWZZs#YZ|}Kg?itm_iPkZZAc>`+~Y91c&ktCxX(8YoeF58HM{#-B4~t5EnA)z zs-3*_JTchi;81b}xFQxOMy{d2VU@cUS7)yzN`Wr@A)lIEeDI?uZpqQSGIQGChpoi@zMTszT(W}-2|f@_hR=? zf!sf3SnKrxmDSspHU@Bv9$u0NcD=K(Zfi~n3}d6#TNDUzH*({tY%a=H!^jml9`{}_ zB73R!My6q9eZHcQk=%90uEfTJ08c^8gjA2vRl6>No8#BT^RTk&tqr&hlXV zoq&P=S>V)bI-ne6&HaJ-!-V24j^GDyh~|{7ORy=s)MlVWv1zj2!qoOLl9c-2RkqL} zhOan(%g*lFM@V`lCd;i%YpsVp@eiG_CAAsNKEhNU~Fl<^bMoOfyFf7rLdx&prP!# zO(~|EEDcXjv}#UzVCzf$Agw;*Gul*mH2(480N(Ys{Slxy^1y=JyF$pQbmmB*_W^1H zcGQ`G84p>?iLgAL8hWz{iANcr#?$Rg5vV!yB1EkP&u}9|7D3nbGK3r)9T#Kz2gXyz zoujR_nTNTq2fWjQ{^P`>Gkv#X{0X&Rbh>;6rQ^v&I#X}USo0D-`iEH!Jrom9Y0u~W16QuTVZ{U zGLq%H8GMPoT5*Zlgol?IIQLH(y2;{SKE0J0zYiSN=gz?2tX_3$e|Fll83sD! z9+QXYL7*H;m%`2T)iDfb46MUzm=ZNnjWB)fiGEr&-;eu(@Gia!5o|r7(=DA52BzsX z>x)J`7fUTFx}IK|9xke{X=VU(!)t&bYNCTjixp*W&YaZkWjBs4Qw^?Q-InY}ZNDYN zY7}A^=;;f(KhTTcA#NfUs^3{^u3dU^a0%aYnhT)|j{N%A(*48Y*qty;2V&le=CezG5dsCy>aO?|!s@ z&c23`bBE4Q9ozO*LoM2*jW}<=U_vYn#0n~f_?h>Wl`mgTWdZ*2>sriAv~}C#D-G`WEe2Qi3slN09l#9BExTP7517+{DaLJA3FRwHUdwxr8nT%BqmmU-s z&W~l`G8x{z`$s!sZ$?|enqT-~oxW@KrS)epiD%;t7o6;uIhn}7P2gQl+_P}3u7rwY zI``CQ{4k1vsf%Wpd9(I<;0(3tp17D;$NbNqcD&$NWeRsA4!lrnO*ao4WOFKIT8`Y1 zCvS-pLyljPuruv^@FSF(>!=(4d-D-?#J?Mf5|;k5z{gj>Vw$PZ)5exFIT*A6GZde1 zDNm9F++dY${BSlP^Z8Xo&P*`#>Xx4%=^O#|+V5>#pC)z%)3>%U9u?)ew>d47-Ixa+ z|Er&%8sVEU9Ms=vZJV zd4}f2Mf=PUbW{@wr9i99Nmv;p>-}8c>D$LIC>Y9b>221^-@8Y#tGTfgvo^o#ye(BI zcJcSS|GtRuFFBA!Y&6`8H(4WVXY%alV?Ka&!7Mx{FuSbL)Enrm76REPX%+2naHv&$ zj4d79IZalCh(~{o7f-jeW(Lu*=Sm_Q>&Y~@?*&vsE1L_N9Gx(qdGV`d&RpGAj3DOq@-BV+GIv z24Ts7A9(+x>*(w2v)x#+WY4J%`WK|$bER4BaQp1= zi;rEUp+yfDm33?p=j31MOI2=fmVi#>5|T8d+-B}PJ?$AvU#Tm0>0N}6NnJe@yB4PQ z)(#GWHja+_uk}t}zu>pG6Lf@>=I7GiB>phozjlSaLhujONoHwBN;VMk_R$}o6nk`> z;ct*+;W!IcVb-whQ~1)h0I!JPW237J{p~!qK7{U!I>$vw2?7xEV47p9%!~NbMm*<* zSDK4w_kP=InR+Yfx2ti5*#7F;1T*>la#L5nJ}CY1piW`_vCY9SmBNfrnNWH4imRyX2CS zF1PTCb6K{W7|%O_lGq=Pai^=k-Mm84Dv`dNm2e(Do%hh0*= z4D!DE|BR@wLvnmy>&`Y;+1OR&{BG)m&tiz=xs_JGTvovKw^B{f_P~}4I^)CuL`+Fo zb6R-=tbdhimJT6+F)ni<(U$xxA?aMf?RT(`vh^|ru5>gA|NYTp9OlfIS0fE7@AMVi zV@h@MIkMo@Gk3rKJ&nmRA$+5w0p`>&VqDv0pj_k#G0hKKjE`WTBno=fEqH1fJrK_x z(o_>>XKU*T4E>~+8p&IiNH8+Xt?~!+jfc;W+Rdv)1uW`rAdQ|7A0GqI_S@fVI_EbFGSXM&_`kSj&kQh#^5?$GOY*SSx&DUux0}9gQX;3gMpPtfvU-K$|<4WIW~w z`sX^$GY(I6H;2Al^|Yc)?+xlyqgYsL&6(*^tE#S+DU2obySF(Rzu2Qi)XA+=ct-{I z5dpuc-oQ{TIW&z#cxB>^hZkk{8;`APW3{`bpoB+au#+kQl$&v<-0s~w)2GyZKQnuk z)>S(y(Edl?pad54s_|14#V1L8$=`-bXI>xU2-0}gTwc7B^?s=)s-imPrb{q90!O%h zj>z@%mC-l;kFRZgObKZv0$!k=2!gyM^?qgO;_w@f(DaXx`mitj<=GCaL<(g!b1*lH zg&`HvU`fl@)SI(r&&%|G!{mIh9{jKY-Rh@f(CNN5KVixN)k$8jdT~VY()Y5o_-69C zpBYpaFVU)WJ8im7EAMV>r$>f=h?fJM0A zz*)~Eec=FA7Z7!2`f2J|5#A z)TIw-0Mk`i)x_fItg&Rt(zA84W%@sXByZs6{iZ_cxZd|TS|Aeo;F0r|3kd_$+oLP@ z`UyMkaD?nBEl%u94}p+lLz&(ARow?&0i#muY4DC*|5vg*2P3_$Kn3k7T9!G}+YlAe z;rHC!(BMPeJjh#8DIXg5w_tUWBm}ac`veT`rLP+qc|tt+!lGnKY#9$=;K1ZU-XMF3 z;1hWoCeOG+MkybwkuHvkmS1rw`sJ#coE)3V!R<;Ia_?Jy&D9;^cT zhHzH&b|eq%m?!eRJ}xJcK+*j78Dvsr7ZgOo*x-!rD9e=e8>5to8LfFU_SB(Zqaf_7 zrxT0>2^^r|7UH~C>6%6Ogh(8$in#G+k#xgUb#=8DSyG=j##^hS z)=#h$Y^8A#YLHOG)prFi{M9;!l#w-kSw4j+7EaY3Ir=Ou^)@+EN8R-kNPMO?My;P5>1ajNG zuF-!d1ofTxEpg<;vcf~_I`}fdW!5Sxq3sRrhmZ$+p`!}2r04bOV1dl`YoT;swD*WJ z22J!Z@(L2Fq~$D+EPv8tm2<7UxFI!=Rh&kOAO?(#NcqjseTKnN!JmLPVDSU{nm3z@OMUI!hbI zTJyccP1JKrD+XpCR=N0Z0$PoKgPof2oFXETOlR5*?+rbL!vddG#kLg9mZZe`M~ zG8XG{bma)ds|tPNd%wOJ=Ee6`uTbz9*WCYu@bhX%{}$|c_(Iy?%^UF;bK%A5#KQ5A zDZG-eQ+Z91Obm}0{|0M{)BFMYWI!gO@^rBPcRHW4*2S$cM43QXW@i{6I$k-)ynX+a0Nu?yUsaNVT)k%2&8U zG-+|9-t~<#@>8FTgM3RnxDkD)e+1}xVOgi;dMI!HdkN+wGi-NCVOD##cK#Zi38?N|71QHC5rzOudp zH&svht}Kf9cxr44NUp@2_Q7g(3pApWXuet0f6GXBk0DW}$K{CU-wFnw_yR$T5aYcU zc4AT1BJ=`G=Wk!hY3ux3!9voAm4&So3j(6Uxml!pFPeFW4nrcwsjDE+kmJc9v2t)3t6VblsMi##c=De zMtkuTDI;-4YAiubz$t8wR?ajB(dh9c84g|FL%3Yl{4618(potp?{OQ6ysT5IA-_4v zE>vvk^K`;xzU}N|-?OEaM+tVJo?S?dE_8aPAb!H zm@L$HommC(*B#S3@5*-3*2B;<6A!s-PVhICg8ifiC@vsp<*gRq>@*TPKsn&h0)hgL zf8wxRF$^XjMZ*9&9ih7Xr9(jS^$9K5jM^10Te!*Rx%(j$mT#e6u)VtXsbf9a<$=qL zqw7EfY(1%ARKPo?U2}y$FdY0C79Q?pDI9(RcR`&?vnAw9trZZ4b%XGC*UZY6E-Pcv`;vZxgR^b+g~pJVfs@cFehU$}2ZjKSXs4hu)Jg117N zjNG-(=cWx)r}BkWG1jqBiT-?lljy@3e;U`%9Bek)zR%Eo`wKtuMkHRt zw2!-*rxaj00;)wbT`r#cRQ)A>G1CZ8|26Lj`K1-Dk6@>|f7zw#tB}E)?{%BY)Adt- zYZ&mo$6bnPR)uFrw8iawJ6=dwus>d+`tc8Xl|@+)f(A0YR6|kQ%WM1Ys*LBA~;;b29*8? z!d@unO!bw=rn@6Ti-Q1gJVEvc$GD}$ua6CDH0i>(T4R=;K7IP(8QldWVIGvUbey0e ze3-k3L0{cIOLs5y2g?%|XeL+31maIuX*q!Ze3H-1i1~F-BU%$S;T3mN+Qn~`B?f*! z9kDl6X_KKNkpf(PBk*r6iAS(YsSI*dA! zxqC7HUsG2e59IW!zhw_9BXoOkC0LvgQ>lUJj) zwM(^_@mg0P&xbNZxy$V+GGnXx=}2R?fHhegO*=gTfIJmZ1@2A zlM{`5J8WR86SBSszj_52>((UvVHbUt9Fy16H5#H@K5S2OwEs}cp%ZD}VcU2{KU$GA zK>$!FO3WaxT?JTj%iAe`WNH|BBI5$UtFOg_TAzAiLwYZME|a;8=6Abk1((ZL5S*av z*XBfe;BJNP=wz9n=Y?%NdDBhOaGMpivtq*6 zDu6s<{RSPzx;&~7mHp{hCYn<*0v4(4Y*gAf#Kx!4}H3Qvv-M}^b;;YB~3W^ zsjnW{zn*myv1av+KV7w)fEDjHkg;cTN6y?7*A2Gt7oTm{*nE+=aAz=sf$96+b*Gr} zeWt}ia`Ca&(MDA+P4}~gpKdN9jj1)_fyx|;()(TnYdZb}AUzJ(c3jvZ|ECl(pn?oB zgqX~24svYO7bJ6+y#{fRZ?1q}+lrtzuQC{;s!uHCh+FuUrWH2JZgA!dm7 z%(kFk9uHRY(Bg%VPnIsg77IQ$lw^MXagBr7_%XZ-w8~2pSq_l%#lW33l|B-Vtm6+o zksiT@{uvse}$q8)zvp(?_mt@?YQH|kJ}fOL|h7e zs6-`}X+GHO%_YQ}*W3`oUHe%k?Hiw{$( zuW)8O#J)g_wD57QU;ceKt)RdyhMO=z54M`WxAO(CVj~?VbRMTmIK{n#f5#F5S@1@; zQW~t-9mTy9ZwXsRK;JT~tExrDnRg$)00|TTl4&0kD%H04zx$C^U{*=}3-28~y`TBS z_duyS?D1ksZ(mI_qklRt#iVQO=}OBA0pcf;7Wo2eal5>jLZL(xanvvTznMhTjw*;5;M@bK#$NM3fDczL}vt&-I-}uaEw;-%~)h-#uN4oua z;?Q^jvYIO`cZklKn7YsQ=i;X@7_Zv`<*=E(l5O;x8Q9x`SiJ9~P~+GnyRy z)24h524vdO`yNDUSY&B_Ol=t1p5#4TavSc!d`|!U_w(8Hw&@VC5Dm=f5DNC=p*G{P zQfuEH&BHkN)G{}=Uu^|l?TGdfxc9D866K=>$@q>k2<=Kr-GUt!G2y?u&-1$sbaSXB zHmEe$*UQ7fqAwP&r_*Dl%r5~VFsvURzw+1*W-xs=xF*%6W1{8}$D?HZ*k*ic^zKTf zfP93CxF)PKJ~%M2`^r$OyUBYAs}5c7L}M5aUwy&xO(CyaW0@4R9PZUQ`NmamDo2j!Ml2`FNs1ysU4Au{g(SQ-Qg|D>iUyvsFwc-p)?R;S@W0 z7H*wmElLy<)|pGf@z9lYeD3xum>p}lV(6qrqex+`v!Oy06tZ>>TMVC!{en0*p{7-a zOuoh`$yB^_(jC66Fn&g)C3dgniCrvhJM9BQ%SPhAm2_kuvM{u3{YvrPIdNCT2GArn zWG{YtmF9xnp?rN2g`+T4ZlDbh4~P6m#%@t?@Jr%mVEN$cRUBoC+)G+6k?VxPl<|1l z^k_G8{CG~dh}sUBEJ;(fktX3~4ab}WIz#XMqNQ3DADCRZ{UGE=R(UNI?l^Z}qvU5t z&wE7vp?a!qv+i6jm+)Q^qod3D>ib zp2^ad=Nsp%c^{?@WrHbfY7}OmeE;OwQfIKBKpTzr?2!M7_n_*Zot7N9V4TPD2XThw zwdG2MA3Vj>{xzu99FLE!`l&6xHaRk}UWd(Dd=W5Rg>0_|<}2q9i3eC{R`K31=g7e#LYy)f# z(u7kDD?xW3PP!oOF@fj=>07N&pE1^oSVS{hORj8q!SlE!x=u#mWM)%;cw1YW8cb@{ zYKOkqKqeY+)`c&g`+Z}JXk_Y*q=~0V)FT1?LV1UMx_5R+HllUH1qkv$@W>#6*z>nX zI4F*AOu4e0I*?oR?(NU&J6=xK5rK4>wOd-6rIAZHw`FZ$J@^$)HSV4UaPPMnG~>$p z0*BdPhWbVajxBlyw2s-0c~xH%WB7t9*4tMGi(OeXDt$-XlkTdZTTP%5CsbrI+-$+A z*u1pt;Y!<^f8>?wOs)p#RlN7`C||O=pJJUZ%l1zuP-2{$QL_i~sM&U*R3nAPd_ z6~6eC|0NS{P_Crgq$153&9jkFMJ`OAC0R1U@|-!#dSlIP&W0a-;3!0MgGwQ+Z7Ba> z>s6oYqJvF{n!tpoXiM5|QAG`c>XMi2$4`pN;f|r$;5UOukm9QJu)sa zP_Om0F)`%K%6hHBX;6xK4V zALxO}y^({TEdy`dcb@|HGE+Rb5!952rw*?xUv0i%l~yU)1QJzsXGL%%yA1Cw@1Xca z;nUh5v%d zH6E_0ZKA}1(=!v{>k=kHO!|xj)n2@MVie@9*}APx1OIf~!f6_&or8H)KLw7^?xZL*>c`Qy~^w82c%S+K;gtxRUb-r)PsH-U#K1AR5+ZUFG3%y>K z9rOQ94(FC>Re^1qg_^pRg!YSnWgHUL9tR_dvqR&Pw*=FhdL=T~3l{ag92sWax{3?H zy_Y=7R4Yl{dx~!tc>CMEP8YCrs}97e6@B_FKNo1?mGAsS$Dd=vCKW>rmv;R`eu2*P z<-{i%fzxAlg?5z6dVk~QBCtD)4a=OJfK>v&v5y|*jogGWuA_|vW8@MTG#D65l<5YX zxt%~hKLZ0g`H0RTvpkSbN()VVKLAEGFt+F9THM48=&cI$;2}|%^|pi*A#4}5n%gRD zI$b)LUu_RvL+NGrS98~m*W1O=M4Z_fB1r!aw;1Ku>rliORZ{8~1zN22(35b<$%u(*K z5!^`{cXI^X!l^MnO-)Kl%HQ|xHuLt!%yHfRLk&F=t0}qxWeR6|F!n$-?U^_SCf!|4 zujT3wkntiz%9DR{);cO@J>v%&+@11xcsP7{beEdtv!Rc8Y+Hizav9>p#PXa?^v^lN ziXEh}7g=95qcH;|XMEr?S|_LRfzdq+Buf>zJF!X8zklR#m2nng1_e)s<=!%CIsvHZ zXCHv6AC{N<-6HcZE@d$c3$G1I@HCh{(+4@l4Kv$U7_Z2>*0u?+6dIYb`5TH+Mep19 zJB646LO_4)m}~eGC8oucj7Z0trDgcUBe{2LvdqS5$=z-vHL+5HpW@Tb{usNv(i{Hb zyl#f0yVH{;?X@z~?F6GR39z4jjAU~<*3W+Z-*{z!A7N(5$^WJ9LiQy~wEn+p?k+sNn1pTG2C%9D*Zc+~x zwp!=C6)*Q~IUm1}_)ppvg=DpRkAjB7SKy+L>r$Q;6>%S;M=Eosu9mG|itFq)ZbRN9 zzr@5ZbH|G~D0Aju2Qru2*{;X_%lBbs;H&A)AI;C7J-pd;o?G9XA}jY}WgMU)gHo+#IFma&xf&?&aEJ#Zwtc7SC|cCQ4gRYie(fNd z34D5*TUtCpEh-i^wQSRK#jt>g9>!=~2*2hef)zu3V%ECh;9hk4TuF+*sV|ta_^J>n zys}hP?r>lIaKqmffL8cD@tJZDUYUu|CxCEO?SpsF?gBSW9?;UwD4cG{-}VH(-b3UYm-#@ux7w~B9_{3Adq z7i&OIMd~4FgzbW+rzzSDUMGG^}qgx+% z%sLtu5cjf1xL$u1LiN!@C5hClo#PhT@own6VomSXLKPi##%ZeN25PBRgie6b(^dj_%Qs^KY% z8;ll9-IU?HfAe)4j6AHlRhneaN9S9f$5zyHYjTget4wOba{H*uN8xjY_ZnDXP+hpS zV_$+CWun2_>u+z4=K3Q(F=8T*W)yepiJHm-J(G}Dz^1wO;U-K(uA}91CwmZWuMIXl z_q=Tk=yfQUpg9>j!$=Xy@KJTvGV7a12#efG$ zw!1C+5}R4`rio3DWC+Q;vi?|G+rIY_N0VkAfcwMmv!y<(0~5IL1{(KK`6UvW$rff$ zS^gzg0ZUCqAPlg~Mj(u)VKO#{d-8)J%j7L?em^-$cE&}~JBl`NmQhRSv#eTUs$|el ze6apZabr42Q9Ts{&mciuYe}0N(4kLg#_Hvm=gm2*MKr{bM`;JDX{1la1{yEQ`Dx@sWo06gL zv<=R~t8M=%9O_J zzO}K0GPCviA`{C?$=%>qmsNmMDxub_pL<#RdKBMcD;nYzmIT_D4MRgig6Qz+k8r*) z3fUO=ajj_Ei}nuhKf#*I(j@#60DKsi5T;-c&FUc+{2;cAODdGXUwvJLXV&5>9K|R zalRwr`2(r7k>QXyg505K-zArUGS)=%KqBI-NRr9r`mWTiwu+OXnN-)wF!1AIh=#AN zzNr3;>bWmgG(!|vNJ)y5NUq2@=;8^Y0tHkM7X-drfSyAfVH>Zo?@pJ4NBm(;xn#t6 zDVf|krU=2GxTt5Svh;g=X$(%r_^AK$w@ApN4=L=@S1^uZV#kVMLN+eE>(*TT3rHBm zT$uz&1wxfR{f>=$A{Xx?5Ej(P#Pkr&Q$UwHG+_}tnfbFlW^aYt+_e3F;LyL6kc+c0 z{DA;#wQ%o5E{E{)N*};H5f48YthVSZC}|6fXQO91z|RR}?e2=691+JTa-0UxNj1z1PMK;pp9?qn%BE5*A^(&?C*5%jhZ}8xc2rq%BB?}M{Ycaww$Mfx!RLr3 zoLYq7R{p`0ytIHDMQD*Vgb*$YF@5GE4Lrh^&2)tiscP6PD7zZZ3k-F==QucYkCl-m zCXd0H1@ud^e-?i!Um!ZMRNi{!(a)`v$`S|jItW+?ds#yE$@WpmBccw!DcbtNQ=}vL|P|xd(8g5s4ls^KeFOxYz^*wK}d|=l2_8Z-C%mNCXSRK z({#eAUrGa!l{=BM+R6$Z{Wf*CL|5i?EjcY;VdrkwA$l+SWP8EA22~2Q(SYdFnzGH8==(TBSN`93IAD*ZY2RJ} z{OPVt{)>KDj5$iy{HA;$KL7h(1R+~pG%%$NZ*6Ofym-ynn5=0lNCiv9T0(}<52gtS zr=W=Ay>(UP7%4*!8>R-!rl6goL9Ls|Qxdt4WzhtK)Fy&SQ!r)BTfQYE$y;H`+)C0Z~G+hG_=4(DU(3cF7$z{67eN1=j%7CJx0}6gRGx-#b zJXfpw?g6Otq+FTUjaEiY$QdL|+T+OGaD77+5MCVV((Ck@GYPU<^tpiH{am***j0?v z!23iPHxu(I>1+AxKO}B0 zW@C{8#x0ZpJjauu+Thu4`+H6*j;o4tOfcexPG)OY2VdBMPc{cE6pk?5W_tjah=Z4| d2NwKT+K}cPuO6$__M8F!JAyr`ldE+);D5%cB?15d literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/illustration_training_lead_01.png b/selfdrive/assets/offroad/illustration_training_lead_01.png new file mode 100644 index 0000000000000000000000000000000000000000..12f3f6bae8ccc2b565d99da98df17dedc6c9a889 GIT binary patch literal 1515 zcmVPx)rAb6VRCodHn|){-br{Egzst3qFY{&d1)VSJnoHJoV_ll06sJ@fqB2Cr6h&ny zDu^JWsNi44KNbB$+&?NRqD*v5=Z44-94ZWxYc^zE*Zk7eS=Z@s;-)Qaa(9oezN*a0h{W z+eB#g?DQUr*Co#HZA)aoE*%TfaiAfKLu)!9uN}Y!v9vri{ts`Kdz8*21LbXMI}+HQ zEHWFeM!AreE>tfb0hnGW&b@ zT>!Yn4kObZ{p|SoWg9riA{}`Jfj#O30Qr%>6JIZV0(IjXPAOXq&UOMY$GSLYAOYLj zmK3|Z1ZO9<<6`V2v0^LK_80^02Lybv75hpy2zr8X`Bo)9n5ksv*H|DR|C)(jKdC_q zZ*(i%E1aKLBJ<=;v7s^dVmgad^PW69+H=vA2D{w_OfX;t#ijVp(75MSQ^{-X9P`Dl**7fuqYr~_d_12( zx5jx$dPM0O`oyhxcH-0ovdFCNVY>buUS%zI#8zXAPaIP$6uMoB9mTm2e?PuMK9*^} zS=Y1_&Z=GGZ>fwPzE6c@Ik_q}c-+t2zV_r(109#@y1u6tfC(z)rTnC0K|%)Tlg^Ci zcil;oT@yF5B*Pjpw;t`q?`1+ zoygT2U#>rT7f$-@MX~2CL~&cVSMd;tj+057!(Bt)xRt{-$Rg9RhH3c&2>3F$#MLSe zLOILi<{l+BaKsG_uC$9WHF6bb1-gRk9xy?rI;bA1D-e)jpriR;V6+gW)eS+xi2?W&sdxZ5{lO!is#s^Q@sl`@LriCJT(0Ah_&Y}ZMP^oUJ z-|m7L%aF1E^2w8@Kg1T1u=6c0I9sfrI1mr3wONLYKbiY*Ma~0O121Gd;y^sC)@bS5 z$fY9>;-6!7SPi;Z?C?)P4}}xiPv@(5UdSV=(ybY6KlY;~^95UM;|On3mRN6VT;SWE z@}G*3bE&mA0-H)B;A_i=SllBB@DI*f65-_G(Q+ip_GDTBVz4|dL}>snM-R^vAL3ML z!OR6An+s7U^0+t;)>nw%7@8pf>(3xB;x==tXy=0MBAbrB#=v;7$gZ(#g#edck0gd( zDm6V1ayAuxj4|W=Qp3ivRRYrEk>t<^#ny8mAIm7WX*&NFe{ckEAxg38An)UX894-- zR>j2k=VZ=67V6qIF!HnzW%;?m#?~nTews_o-AerMFhwvM^|0D?IY53-1F%!5rGBuS zcoJ6=GQj;I1I~ViEuy{Dv~gSo0pv+si7&?`t#9LG$1_!gYq(Y*fRp{({{xVPKz6cJ RzqSAX002ovPDHLkV1j+wJJkP)00001b5ch_0Itp) z=>Px+z)3_wRCodHU0ZAvRTw^Jrj?6#@UBSQ-L@zKcCS>BivbhBpd^BziD-j~8Xxsl zc~f6CDi5M!G)g1ksyskUKnd=pi-j0vdod9a444*_cFXR}@&C773t>CV&dfP;W_Ng* z-I;U#|Np*kX3m*2Us*!x=-<&<^KVWD!h3LAN3e-fFJLo~NaN7p;5I_o3f$uNdcj^d zBI^U}eZtt{lCZEXeXkRh>q6vIF!CB>?8Qqp#qYTP(tWl1nbs<>GOkP@vO*{NE=H~# zngG165M^bwuk)L7`&!)Aw8$XvERC{5aGSnB^OV1PaqHPLG#!jSr!#GfDAE7FbaqH zFfZnpQAnejJSB2>C~?DZv9KEmztsp7uVa`O^J5*na`1@j8IjrQ)oMR0Yz3lc@*u)& zOw3=Z1L`r`$L)5WDRlYp#CPGI`Hb6yjph%XJl#L#qyAHSC8@`-3{OnFV9D|&K=Gj= z5_b;13`?Jz+(~UdtMnqLn`29KP1_4saf5kSf?85qR8)0YESKIdD5Iq`Qj45!iMFtU z_9MJiy2%nc0iA%r0otg}jUCS%7m&_U3TY=^KhJENq8If&G7F51V|`dB)@w-t0iC22 z8IA83^7(CWiw+6kz2)#i@!@g7#uVhpBajLPMFwRML@|iuAfKZ*O^oc}wc8}RUyxU15a%W3;cCm;? zcyb+Y(A?uw@^3=}ofkQtJ<2_oi3CzyF~=TE+^!V}7~yL`U?d%IARfeJLIdtiTo?Jb zMT;g54i$EQ9rj-CXay!fJctYN2~1ltmFps(`Tg8xcvPBOu{y8s1Y9M2F5_@jsV{+H*$F3b_1^BD~`V$yMMcjxVd8kQ|!M{xN7tW#)zEvbZ*>WNNQ67Zd zMTK3-sZiu?cvN~)Hqu?G2Y4v)AtG#v>*-!@lEJGCUf*0*^|s@?fFnV*+m_{u~DC=)^1C6kV$8`nMpmd`5VO ziQ^Uy4f~3+Jl37r=Tr{IM9wrvW`O_rFuYZg)(GzuX}sfrC<97^(iY8i{^~?7M{d{2 z8S$yQ#-umGJ3*L;71NIF%>s#wpFT~-*eByzSnKBu4+en5Y*m85tKXLvY7}nb>b@2B|%fO72 zM{|?m|NFecY;eVxoC<_rfLp-F(n9eIGh_h9==OMD7S=Py{#_<=s;PAW(aApF2tP)U z*FK?PA6^+Pjdve8Sg!qlkw=a2DR|I!#Eno+;BUn<0EYd)!LT1M8}>^g!|x2=2){FY z7#2M47hjT}kqZNq{sO-X-3Gr4eNI6`H~fAu7~y?^xsdHvP|y=~MSay3`HAnrYSucp kYVq@OWgz(Hss5?|0k-D_JWVmbJOBUy07*qoM6N<$f|;$^RR910 literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/indicator_wifi_0.png b/selfdrive/assets/offroad/indicator_wifi_0.png new file mode 100644 index 0000000000000000000000000000000000000000..9cf9762ad3d8f3e20fcc8fb9256c958bee6933ba GIT binary patch literal 3038 zcmV<43nBE0P)Px=m`OxIRCodHor#j$HVlTlY0~>nkN1DNcG`4vAI-J>KZW$jvSd>fKvA?X!?CTE zDG>ODlk(nt))3v@-Q8$8_rv%+yx!9*$K&hpJ)iG-k5Wwb0 z%0{7IXgtt}O6L{Dm!cz3=%Vj5-U=K5W>d5Y5J>4L_e%{F&nwEWl{zqpx&Igf1z@R~ zssur})4!JFqT;#Bw@QGZ1B71R)Ch`dK+sb>%KvJs8c*OGK)lj;U5o2j6$DqL_$h2u z0f<#VAmwwXf2Yy%9Y3Y`spD_-hnE_-jG~!GF%U@cT=&m1To04$zQ zbL^BR0RZq!H*&ffCnxr5Lz(6-MHo0nYiDVI2g(O)d zfk2DK_hbH(&ewTfgt8f(;E4503-{0C7Y|N*05BrruBC zrxfAeserK+Ytm$uVy4t}f~+GLN^Y0Cm7ED24|D*5m;#mD{iSk$d=(usqWY^Q$-ead z3M?)KrtYTeKp-YCQNL=G@c%GC-MgB|Ui?%+(gPL&D_kNFC+@;3e56tW5PsM2Hc3SI zpby`_(-{d!C#0B^5e(P(HqYrx_BEZipGYdozDx{=F()n0u6e z6okx>f!V1NW-R?;^%%p_a4aJeLC5#J^0`PAQr9^lWGCLSpq^dY`+&g1JkKgyo~%CO zfP{r|acK2R^22Fsh;^1i`57`~@scQhn=K%}^?$$2ieJ31U;5SWaky8M-}W=pF;cJ?HK0CP!jxWqMJwg3P? za3Ki+{)n6z7NE7}le@MnaqHD>>$v2AwWFNB#3~S@Q9SBQsNQ#_O(w=7%&lUvaFp-j z`?X;BLFoiZH7Z_gjgl)Mf>p>Z>`|NfC*H6}=2H_RWPp%L_(W>b<^`X?3#P9`&YZg5 z-17iLERLDR5t0+x9X*~SU7leS7xuSwcBs>wd{L7kbSAw-hhoE}6I1`LYr_xMNBK)k zUFs#*I1hJ$FE&e=B{zcLlwu!X1OP`j?Fk5wiY7$~>>ipTYW-||X41tJl+QI8OX8Bn zycC=OMNm04aifx9O4%P5a00$j5FiLmN|6Ge(T;_%eV-K)TbXtOEHSnd%(DNVddw00B1< zEzU^`InI3+1o0%xS1|}dBLS+<7LQc7baRV!0tAyd!3+cv2*U8(rq)+1il^LKT=9J-`tP-VEMF|HmFRnL1Dx~$ z`aGq+w*&#*N6!?HMZ0w3QiYXzo&W&|sEK$7#oeZmRKBLpv-D|}bM^Vf^wF^57deWW z`#uwM-iuF4w6_AoQ@zHgT4>y%BHO(*zk&Hn-@TU={zeu#RRRKr&h+ zK9C);x#V6Q%Vo^+dqGY#(Q?yhtR#B_COd<3_%#Iq7uEu4VS@I#RHRNmmnpCFB_~`b z>2!`&AU&jTWJ2a3fGaJK#ijZ`%o?@vA{{gMtBEA5xxE#BaDo`ajJ!a=yzEoFgmMBK zwmq-n`=x+x{klHpbu|(nq?E|(QeaJxOvYhKE+BwIEewB0?O>{ZK=4P;+(iLF!3dY@ zlLf^AUyT0R;emlw0+5ts8GzKh{H!@oNc;i-fG|~P!u(?~&E?e>#0g_d4}^tLMH~Ww z$e-Nblyp6cRahTh5vJAp07UFbxczog04@RJ(3RpUi37|5pn1)N#9X5k7RI6g0(TjY zLz^`}G(Yo_m2izq=2WLFCKM6N)&Rm>FwqZTw*Zg@0$aGl+RsH^=;^4Qr7Er4%UDamyI8r1H)!O5KJVg z=TzY2rQkX90tTXYEQ7h5n8V1NbE^k|l#gE=3zp`rv-G*dJg)l!Ef-WZ2m}E9eMqLFubUT=}K&k^lF#j~6i2hq4vIr`pCfmWRg;Es= z1OW1Uic2*Ie@k?LMR3jebC|0J1i=EZAHi~?OO8yuzf&C$h`ei|_!Mm|{CM#}np+js z1cFvwz)<1$Wc8}Db~Q0W@Z?F%Pgjr}o~j;c8^>^o3~q?nY4ol}R#jE32?W&Ot+!~C zp3#Ek`Gn-HSRpgF{Nq(Lsli>vn_3DZGgLs2RG^PExzN#6Eeb8 z5wk2!Td_h%zZ|B|t5a1VKpGM{6~Y{gfN4khZgqR{1{iX83&Wqu6GNKElxhS4Jh3Aw zwMC3?kIF~T?j$h48~uzq!7KpSi$$s0k&yAhDK!Jk{pkPoNxfF?dEybUlI{(60gX*r zU2UMxWObGxGAAJuv;u^wpe$~=DsuNnzJ{;jlgG@?<^D8~uvFDjwID!Z5-{c#*DwS^ zRo%J3C*|(p_BM70Khg23scH})ISClS5}C(6iUfYi=^k^GAn^%M$!q{F)``88)%6L) z*G{_xb_whf7?D8r?qG!H>_alyxD*OL1f94U1}P?42BWJm%8aiXY>JPf)I12Jc-BZ7 z7oUAd5ipqtL0y%3eaZsnoYOQ21OSRUq;I)B5(2yCekWlFkY+(309fr dUoHEgKR zoX<^yKmeemOA*JCsQS^7Y>tLSn9VORSO9APAeV=l`_iNKo0MNuAdr$`!NyA&IlsW- z#f#azO@TmC@!k>iKtOBGg|-F)vq#=1ZnF=H3kVdOqNYF~1yS(vtk+lF4a`MmQy>UJ zplfIHBaZ{2(h%bD^X8~I5J*v!d>?6G6|9KL;bW`GYMZAy5Fp^-765{U|Hi6NBe0kY z_Nt>ML4cH{G?WJrmJrs2YGKn2rDj2Z=A}H$_$}`lgp~)qp^X z#m5sLoHOw}C)i{`=p3@H1_TH}3XU~|F(A+;u6}#?Ic4Vlt+{4MiXcK0h;}nOkFXFt gyn0nGpf9KY0aCHP+U?NOy#N3J07*qoM6N<$f}WP27XSbN literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/indicator_wifi_100.png b/selfdrive/assets/offroad/indicator_wifi_100.png new file mode 100644 index 0000000000000000000000000000000000000000..dc9f28fab3917b000318a78c62c11d1969ea26a9 GIT binary patch literal 3270 zcmV;%3_0_OP)Px>fJsC_RCodHoei)SRT;;-a=}y#6#M`UBM?oCv>cNFQ5za&&~Q)!2^lR*%cLxg zGHt5KAwR~!QR>PJVT6N;3VtN$h^V0WF&dSVjv#skB^3ctuDDnruJ($X1s`a(bGUs!f$*|oraCF{j)`><^* zd{BeUY~Kj4!pZ`x8X6k5vz`fQs7EiTY*pqU7znEDB7Ioz1g_;{3Rn%rq|ov|u#Du` z#ImlWE|P#sKbWWvDKM1fanJ~%iIU@AuoRYPNm8t38MFkM1XTI~MC}Y12CDo4P_MEI z!<7(^!F?pfy3ia6CJCr`UAsrYw_!Nw`kpn}fkThL9WalCSRaCesU`sx-;E%YR(zKb zg5t>rCBz~qCd39$sD+6{1lGy;$3|f@)Bm>2(w6r4}G}cJPD}$-Z-LP{e{rOhf^6TL+yoIU>eErhD)EE zB>|PM+qla>4ZSQj@?6$Sscu~==E8L(!}8KEY^_^Q0xJIqjJq1fgLVD39Irz?YA4(V zza|-8w`sq%N}}?0i+2S~g1v1Tnd>TxfV#NVW|%@UyjS*3%nyl^fXY|vUf299;lP-7 zG z!2un&9b2-{S8*qP{E%db+$|kB2}po*DNNU-10Y0E&)doh-sW@ZP_c%G^?5Tv`xu`z z^4PToO8DX^rI!6*KL}Ce=SBE5FN$%-NkE_uMX~N%zZInbhx@9vtd128&OA|AUr7L* z_s0{9UX-VV_#$Xja|nDELXp`RGKp9ibwwK`0Zxxc=}nMk!%vN$=RuXeRN&;hEQ1hY zq+4SpLoq4TD{2&9M-IG+-V2D)f<*dptQ*_~X~|X!z85CIXA(K%`C#nr1((1Q&?P4= zX`de_6D!Yf(1-t`FyOno!DYH$T zQF_`)pS=s^>g;(B1#6U6BZjiwrl>JKKz9R!Sy2z1O__-@C4iOjZWF`sqZ9ib5640O z0!OmcB`9fM|6AxNjz_%0`pfVX{x!4oBKX&rf)v+b77JAJ_t~Y70v-k%@+L|~S~Rkz zD$3ah)T-7k?L+WB_?FcaI0t?N1EIXdUDNt_U!Y$<+DWh(Y{>O{EJ52rko4Mf8#W_K%H&QhNsbeB&e;GL>}be&U=zTD{PSBcVcMW$T6eKlv(_M z?gQa_pkMn(P%ommC?QS<>j{C*yx_e#ukpM)|7k;dI!NB z5aKT$vm(iQ_P!Q&Uw@N_XO9MS4hQKsm1cHSL%FuF!w34){YW3e_qd7d=;7KLTB9?Vby-Lr0Y-aooz80X>T6@1Sx3P{Z?j2q?O6 zpe_wM?W-X%6Lha?MbLFBJO{b#j)2At)UT0P(4)59eE2uq4qt6csd|jO3I?f%@>5>WY?i8}*^ zJNGC%1+?JGpFt0nXo|cuah?Puzr*OhmG}P z=vskh=V~-kE%xH5WKY)9l)qEB+6q?RU}8N9NB~v55((Dm!8f&S zhQg4-@>rJEV~EbSWI11+Ng_12wNq-}5u^#Ao+)4Q0R`zkcr9Vt{AIz!nQ0s$DSyeBWKf@;k~w_@o$V zK+cA|fs*jfju@rJTIDci6o*%^vz1}hD3#-TUwk|p;!Nc$#!`1hZH^53_NlBqjMLo;mpSF&1HS4K5$6)BOUg(GCfQYqkvD;<=(P3?yB5@sHhfnDBymW0}tTK zHroZ_lg^%_Krichj52hF$fYs@1Zo640%^)y6n-V7`D(w)&}9EJ0UryRMH`Z+bw3q! zUC+f;1PJg~U@3$w8!=Af9BOdpVk-g!R8Q7S2X!aci>M(P-gv*QO7W?OKn{Xc^-}W{ zb}DH#g4pOYW|=9Az%{^c!1kycD!q$3#57qnSaE)f7}awEroYb9EakJK9vkrf?_k>~ zZuORhXk$=GKmw?BeJ`98Vz3h0q@K}Slfpj<)V)I11I}dlreH z+1SB|=G%uNKf{nLCxGItAKlGb2}wdqg25pL#-S~}IqMzfP=93AA>F>H@#Iqehw>Le zql0TfBZeA1)Jvr_s;D=wY3xCxjXEQ_ip@@RuY+7FBfziYYfw3Q#-`Y!`*ghpLa$BZjl#U9c&CX{+oG{~eK5-#}7%6$L+lo;CuCo=z|n=0egW)f~zmHtfo@ z4uW(m#F4ceq!(`K^zKB^t?`Qm5Jxnzw7(O>vZjK5CNj9Yp`bTl*&#%Xml=^J`QX-0a}|ae7%92`7Z56 zfZ(cgon7lB|#5#yO3?I=#s zM{&ex&>KDuFQAt|tts#{%lVA*ZDN^ARw6*fH^PrW?`JjA)ET75!g8sH2vAv9Sgia~ zRhs#HT0O)ds*RbtJD`%f697#f**j_=4EKMYI|n^jn<)vV>(x?JH6zGX0?0(YOd?Z1 z966P>BxsgX4yBnhL4Ca>!XOx#N&+fKa|dS{_#JnbDRB?XkMkG-PS+a9aq$ORGd#MH z7nL*uB*CH3+R!eWV~IvEUClmD>TZ5~tq4$QUx4+os=WLlbvHYEPf;!V^X--*K;@kb z8ViUkdTDoRuh_E`hFlGmI1b`;AFI1qufNMB3lX3)FNY|yjh#=)g73KxB@v)frx|8} z&Kl!O4$W7y5&Px=$w@>(RCodHoym?IMG%G=+ib?{U@XL$MMzw@vWXW!;)HkxI3gj$9q|B2To4Bi zz8Z1i6?`xto&ZZowphIH9z6VCJ9AWBUDchH6`7UQlOctwySh3nGUBg@$cXHjod>pv z_V)I6G@T=k54+1)+f1k&KN&9}+((_D1K3 z;d9XvD0I`i;yVHdfSDD|0t7NT#(h|f;W=XbQfUDO33nS7C;&^*R3r%8lm4hQ=MB$O zK34(+3qa_2t3*%~1A>O(G5#ZSwRnKs0OE%DW+|a#QV<*g$;HJKQRbaR?ZkX1A&Z>tA9d_>#vkn16MUXp24I#IT{2qK4V~b05EzyjZrB~0|4NP_`1L_ zYBe#+Xac}d34!a+S+m#eDm64fXt*pOkT*n86bNK|jQ+H^uJfbRp5#k_;F7>FxK}Y4 z1Ofm{y{E*3znf(0tApYi_glX1HHzUpj2rc@_i&{m=Hj{Cat83eL&*^?b?(gV;!v*; zJefkDevD1&m8BEiyIm>3Bw5l}z2tNO80cpDCRa%zkyQjvdf! z!r1V_@S5ac*Oy8#=?GBxRyV-l{gf2!71kP66T>xP{3+M`)YOT0#dO^y%SLkE0=@A7 z0gkDNegs~D5ZFn*AkZXmbG4pbbtU1fMNV@?>eJJ47K?yZqAlofz{b14+7jJ$>EsLfZGB903iuU3CKt03|oNK zT27wYMTuL-WLw9j2fQ8S{4rjE9F5}9!iDPfqO{4tc!Z%>C`MrSP#;n2XX`VAjwWY(?g@{{OGe9*aR3ZK<IDHGYEWD=dkQfS$Tj=ngT^M70W=cQO7~Y4=y%Cg$0$a+CAR|zgbD9)R$9n@?6n~9 z7g-)9Ac7HU070cy4Uj-mX-&4&Zr?I12m}CPK2Lwv`?e=NgZE_agk6&F4gvw7^xr82*kaO4@Cqb#D_OmjRLMXf<1;o-KiPk!@fsj$mQK((KAnC0B2y7%l%mec}6a{ zId^1$@k#)ak}M2J&CAakbA==?000Pmg(loT9@AW3O+~B-Hui*@7*)hJ5Xk&l`uGbJ%rC%K6+DS*IJ#?PV6njadU zaaomck4^4Wmy9M1;mg(l!rU;L69A?JjmP3IxR~rn)>xfn^`vwTp7Nv=g_2l_q%2i$ zngZd2B#rXzBzesy0Yg5Y9SCH6o_eZp?GO_(-&EJ&4Orr`@nd#im<rZf2TMgka?Fv{#Uf6$dgJAmbpbyNg&wP z5YRUGA$h%`yj@AckUXU%#-}UD8lI{i%Qnst5@8+)-)T%;jV!9FSP}@R!CP<9W_d;n zmft4?Z^d%?39A!2lCY)69Q}U`C66f;lNd59DW7d=V`~FEW&CiH4&Ue}PBNh*LKQj7 z*kvnTXz4G9>HXwX6bR6Ulum^(#v|a`F@CbTy<`InvAczl&*T?F8po7M1OYO!BPp~+ zOlGyKAkCKz0nXOy<(?G&g6-&i}0F6n(xLZO)8wf>p z=bW6ByW88_*d2UH=ZmJIL4f9@U=&Mc?)NB?_ysTb7$XNsPJqhF2H@hI*h^VlpFna| zsv4*os2b?dK=I+AL+0pHa@nuw%O8qg7Qf^em;I;X(>k6iJ&}`)m4;|QhCd?yMEt8b zgl_4gQ{uOW+^1e!s0L)nx5U4TW9bKd@kF81t72`^fQs)ps;CHar!hMV|`&^^^P%ib?*JX`_B3NR;>Px=>q$gGRCodHoJ-6lMHR>WWDrFVd?7*OLIod062+*fsBxn^648h*NZhzl7n%^z z7*`r&bm2mcG4T;KnFR~*?M6wA(LjP4V}gO8PBa;CV3;Q}z|4I9ewXf#zI|W)sH$6i zZ=d9!?%TJ!>eM;^K2>$9?%jFT2FdR3?heh_SKz$j_-u||FOT(eKkrs>ZqB*a&Vn-~ zc6N4rW+Oxc3{G&i4t)+dACyk_sN++~6e+0mDexrZkT8RiL688a>)Z=~j`yhZbCn4h zQ0@rH~o27u5`R_`A|g?ObEg8bdIFRh6EMI>-^^q)#DBHmJpAFQ@L~< zYbC)JIerm0vLM7-NPzQw(=P&>{KhYG{G#ip`Qjw7%Sbx&NJau2Z(Yv^I)BK0JnBak zr=cgn4J5;f*n`PvB*6Jj=Pm{g^hW7tfm1ww95OuF zubBBy2PXl}H`HGOM(5ABd7rD!Dvm)0yNqBGj08B}Q2zp8=pQAn1&&j^ks(NSvNs8E zzGdim3DCPd${3}Y1th>Ra1t`~noaa_8U(lyB@F#3bM{m>O2q1%%0d#*2t(bA!8#Z{NXO5$Fc%9# zNCru<4ni0`A6*nV=aK-WRrW<-?)O}eA@=V{7fxa{VpW;g)|W~`m|ID?mSXqt2t<$& zQ!?db6!f$CeiJ{b#Qxn3m|L+HhOAV|q^hT|bxDSl+vN^pX9tdZvPS}xl9j&wspkIn zRj!aZs^4nC_Nn(*7;#N7OC+XghQ_g2r5> z-6siRgy&Xi%bC`9xPY;Au3eh2T~+v9XQAu~87M$omGIX_F>E)bCv`~1;{_QUxQFf{ z&PORnyoel9bx7)NH>ZNo232i0%piJmjoJuLQPWG=Tt?f2kZX} z=iAqtD%}?6SMBL}uw+_cPiSjjup|pxd0-SHzzWt8=N9k_?2aW#rFt|h^0R(V1Ve(?#Bma4;e_j(#cSSh> zt1mD6xw;bRx!2YyQPyXIlK=vk>5~BKFqqRJ!=`YlcP}-{=iWlwB!ca8Y$N=fT5O}K z`e5njpd`RZ_WyPPsl+$A{EdREcI8{0r2Zn}In_S z-gIkn$5)l8p3{CKUzuD>vF_muFtZL&)v4)uND{dE7;_3}qob_EH8ob#`yhlQFeegw zP(0Zb(p0ZS_l4}!LY7t4*U;yJmH)_*G~8E}XmgI9rf3gChNB$Ig|T2STt$~4>n$N2 z=YS=MQbi+u^G|?a|IJgBo9qA?9GD)347S6C9mh-|MVt4QVCIj1f#?k-&1@r?`sc4s6`^yq3Nn2RN0B`db0YUnzwi+H2Lo z+Cj22j-V2S1Zqgb?C;DSELuNs@aLMj{abLMe(Sv!Tn(-)@M?~ZS;}df_w3~#ICm=g zAMikd`#Ii&jt_H;D(EW#B*LOZli}Zp8QfmcNT9`vhM7gI6Ty+c1`jIK_f`sgKX?zg z4une9{DZQ75AFiLjG;T_YA^lafU(|{+EqFZ2u=XXjlaXEXqb(X2!?%s4jpXqgYw@% znIA3Sn;u(yBYy$*gJ02>Ao=^M(zMBFU<%r3>OZ&`HAksi07HEM{0^*B9;WgyfIidW zdeg?wt1N)QKLY*+a*`7$^9|q_Xp~qMz`$hSnPof5#h@31?}D>n zC~_Z)UcVh4irh*Jc^&xYP&{ALQ__A3gj}SHZ1IeW$8i3a(ig!QFm$<_2D~aG^UkOe zHBT^8TZ0Q2%&F0jz=s;#K9pMyq38`v_5PHj!da030yw(<8F+h+#_Fk)37?xG!tFiF z3I2FCB!B>B_wEI+3*O3n3N+()BSg3(ACAvYnPGVXz7kOtc zibU4q3ZmZ2BiGTY_?)IM4xVDlLlk}=aE0(7Z~@DWEalE%_dvMza3wGz#j=g-Cy#(p z>K5SbcpEqeLW%SAKZ4JJH`eQ0_L=)H1vi18fJZ?{`TnxHxBfdUZEm2i{EGrU0bIiF zEtGQ}xE|aN`jYek%5cxXD9bE>k$woe$Uz?ZBv`a5V_CJ0zN2i{FMbWW$RQqjO{0po z{U!``KKN}5E1%@vTS2G|Br9D&T}Fm`KvOxzjqg}l@OZ;B7QkSafWJ4e@PpiQ%`;D? zJELC7`t1ff+J$^Lon{+U6NY;wFvKqs!?Gj#wF)|X9QdX$l3UiQ;Lt0_s`kO|-l@u2 zKDauUO^yRy-U9v&>hkrW`ydPbv8u_HuYunH_Z7S;3&m2e`3z%lL7$ zz-WQd0vTH%n^nXVHX=m7mU=!2t^%(p;CAl+7Py<^oviX5<2cHuSOCZG1D^ta0ZrsI zH{A)wJ%XD+0v!1+&}V!4k9q#`O|ZpQwgKn)qmaJ2eu~(A4EVFQQHEpzoc2|{7f?(F z-7q8@Y_+a9>+=DfUoFa=&+pqr<8IXK04Mp2UN?_i5Xo78X6A5hq_WpmY&NOaKo)RE zP%Hwd;x!O$qh1^vwP_?cV51_+0U|+^{|Jbv^U9((iUc^wy@Nkk+3M~$e5L!Nzz6EgF>w*6-+*eFD``?VC z4ABBO@7=()fUa_Y2d@}n+ee)%7Ql%&fiCG|)5TX;iW*OcYyq5k3uq%xaPxbI+~!gD zITpaF-)hJLqsGVP6fs^Jx&?5oza;u;10viu^tO)rFR=gwxDfdFF^l9oOCBG;+7t`m z{mZ~#=dfTu*ZhCst&@#g3~Ay)ob4jhr-56@{CWD%NjdN5xRvsM=leLm4THEK00000 LNkvXXu0mjfBZlYd literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/indicator_wifi_75.png b/selfdrive/assets/offroad/indicator_wifi_75.png new file mode 100644 index 0000000000000000000000000000000000000000..bcbebce85d754c65c43f2f9e5c6f4f6ff6f6b6aa GIT binary patch literal 3186 zcmV-&42|=NP)Px>EJ;K`RCodHoqMbuRTYOVEd{a2qlkctMv4!NC}=>GqF_u+Gyy3H5<YO-onP|HoI7V`?X}lhv-b1Mo$;(1VRUqK2GyCBab|WrgrnzM$Ij3GJ=(?tT|Rqm zKit>ij2Sb$rxwrvLkFC#LubQ7Vaw?rb$nGA7ZeowU$~dxFkprXLlFcxUFRMKb-YKN zpDM%e5TuQ$DOP2*v_}jk{h=BwF&i6^51MB?6_i}u%^Sk+CC$!0^bmUQ45a4*rdJfe2 z!`#NBepEON-2tDes=0_B1UTQGy^c2k9NIO=X92T;!LTECXEIt4;CzR3M?yP#4a!+y z7q@RG81|ME)BWz?L4fm3^+&?y86n+0qdwh{>T z8~Q?DL4fmh`Z2H>=l5myC^s1dTL^~2YZZlqfB;R=GlEuYOts+gH86!i?(#)7V2d76d3^iaHKf(f+G|^WMqy?9nF) z;0H5;S-6Uhxcx4(!U1PW420uh?382=-{`aLZ!n1k@QFiAr{iOHBHg&M$sjNlnFV6O zj)=~;?Qc-P0{F&0L+rJgwWj}AGhL>8ojGZBV0`#JXbli9lD!AW3JN9G6-U%=R(t#A*_qB4CXW7YvH_%r*b?6>gc|K>~-Ay zc*Z9(OcKfgQ^PoEQUwZ4wNGys$sv zoOJLBA9OLjUkfjSsXg(iR0x~7`nzxuw)$tGJEyo9J2|>@jc1%MC%MfI`_t&*aSRh~ zM5t}8LZ`yP$%d&e%=NHUP#wv=f3r z#Sm)e!`(x@u$?d5`mE5>$O7*}2>KX2xwOFH5U>h0Z^niOMQLEeJk$O*0rmyPp=%I$ z1wx&qu+3>l(Dt7)EdNS)6MRv7LDT5-pQ-D0IHz=G$n5E~bEn@l=Y)kLPl}#F;Fk!s zX>g3~sKFEx?1vA?J|B6vz%yZk|2Gpi5)6-(H3qh|Z)YIbJm|Mcf4wwm5O8yFpx{dp z`Zf5@;KGMrpblFMKSMCs`$Oy&1mq56;3N42J!M5^sm$h{VJn-5RN09`ae=M&)<;Wiipw{RP?%J>yC1t=%aE5&LWshZ$Gwy zsjE#yKTW7j$~$7~S6V(wejVn8Y3;403msAc)ZKXopX|JFB{qFfn?vB8Icjx3*9@%f zr|j9V>KVTY4n&93;gfJGe0jpn0Zv3S0JSl-uYkSQ50>)X`a?gUFgTI3gF+<@I1brJ`4x{zRk$ot%Z`9ejc7`;>FT}cVT66+}Zv(P4{K~)yO;FrO_!<1m}ejzOK>#eFxR-bY(@R@KWOc`5H z&UFquoDD)*0D~S0zXP349v0YtB1w&9eNtHt{~2;(q^?O3&Z&? zrO(6At8R#_98QS2Su|NhA0ig5IR^8mZ|+jQr0Bf~U%wvRE@Y_Z?+%kgQb9lf*t_<{ z4sS@#QsotLX7nloVR?B`VI?FJ1O$N7%n!gLKp?mqI~lm&J{5c%Md};? z+S!M0ksne*NfvnYs^T%w zwFg%l%}B9qvmeVhU)@>WWPfx0(a;scrEnt*iSJET z_O$;FOFK7E7XLuN2jFob42qnYa6ViP%Lb`?DCdUItJX3w()VFMSj$ZxhNkx@K(^}_ zcf)?*#?pCF6swz14CTg(dkR?D%_BF!$~LJ|mYHD{%!^%ISo>YnL1Phv9R(lGVc{pZ z=JcS2=M+Y{2J1I-=x7siX-=`tW$hNga3@1kd@q=m?a>bu=x`16N$-X02ddz(7mihJ zgWbK;j{W@M>Rd8&9O&|T*loA)EyM1EB=pC)POf|f{u;Wk;EW^`>reu{=D?fa3U~)x z&~ZugXJdiJ0*wU{wm>qgh*j8#6#a6_xfuF}j~8b2B~WWJ-p}z)R{6GZY)}^q;P_ea zBk*r95BzbAKcQ>(2-YD8aOAnL%=Yvjalfy!YcPx!z445}7v;|93x>f4MRlyz=m01AFMHfPa#&GANSv6-4PTk094VJN!04Wu~Kylf)Ohf5hG-R;d)6#4rA0R2yl>l2XD<$?|v`& zQolDg_f=>C(zOdY55Uk^QeickqRLtT@1Fp>E$#Lj7_MN(+I?KMy3PH)EP&Hq2{-lY z^|t$*ZjSbzqF(wp=L1;)=bZ;#3+NZVw0mH$*b8KaMhs589QHGP>~yiOziUtj3*gM_ zVG-=%; +#include +#include +#include + +#include "common/util.h" +#include "common/utilpp.h" +#include "common/params.h" +#include "common/touch.h" +#include "common/timing.h" +#include "common/swaglog.h" + +#include "ui.hpp" +#include "paint.hpp" + +// Includes for light sensor +#include +#include +#include + +volatile sig_atomic_t do_exit = 0; +static void set_do_exit(int sig) { + do_exit = 1; +} + + +static void* light_sensor_thread(void *args) { + set_thread_name("light_sensor"); + + int err; + UIState *s = (UIState*)args; + s->light_sensor = 0.0; + + struct sensors_poll_device_t* device; + struct sensors_module_t* module; + + hw_get_module(SENSORS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); + sensors_open(&module->common, &device); + + // need to do this + struct sensor_t const* list; + module->get_sensors_list(module, &list); + + int SENSOR_LIGHT = 7; + + err = device->activate(device, SENSOR_LIGHT, 0); + if (err != 0) goto fail; + err = device->activate(device, SENSOR_LIGHT, 1); + if (err != 0) goto fail; + + device->setDelay(device, SENSOR_LIGHT, ms2ns(100)); + + while (!do_exit) { + static const size_t numEvents = 1; + sensors_event_t buffer[numEvents]; + + int n = device->poll(device, buffer, numEvents); + if (n < 0) { + LOG_100("light_sensor_poll failed: %d", n); + } + if (n > 0) { + s->light_sensor = buffer[0].light; + } + } + sensors_close(device); + return NULL; + +fail: + LOGE("LIGHT SENSOR IS MISSING"); + s->light_sensor = 255; + + return NULL; +} + +static void ui_set_brightness(UIState *s, int brightness) { + static int last_brightness = -1; + if (last_brightness != brightness && (s->awake || brightness == 0)) { + if (set_brightness(brightness)) { + last_brightness = brightness; + } + } +} + +int event_processing_enabled = -1; +static void enable_event_processing(bool yes) { + if (event_processing_enabled != 1 && yes) { + system("service call window 18 i32 1"); // enable event processing + event_processing_enabled = 1; + } else if (event_processing_enabled != 0 && !yes) { + system("service call window 18 i32 0"); // disable event processing + event_processing_enabled = 0; + } +} + +static void set_awake(UIState *s, bool awake) { + if (awake) { + // 30 second timeout + s->awake_timeout = 30*UI_FREQ; + } + if (s->awake != awake) { + s->awake = awake; + + // TODO: replace command_awake and command_sleep with direct calls to android + if (awake) { + LOGW("awake normal"); + framebuffer_set_power(s->fb, HWC_POWER_MODE_NORMAL); + enable_event_processing(true); + } else { + LOGW("awake off"); + ui_set_brightness(s, 0); + framebuffer_set_power(s->fb, HWC_POWER_MODE_OFF); + enable_event_processing(false); + } + } +} + +static void handle_vision_touch(UIState *s, int touch_x, int touch_y) { + if (s->started && (touch_x >= s->scene.ui_viz_rx - bdr_s) + && (s->active_app != cereal::UiLayoutState::App::SETTINGS)) { + if (!s->scene.frontview) { + s->scene.uilayout_sidebarcollapsed = !s->scene.uilayout_sidebarcollapsed; + } else { + write_db_value("IsDriverViewEnabled", "0", 1); + } + } +} + +static void handle_sidebar_touch(UIState *s, int touch_x, int touch_y) { + if (!s->scene.uilayout_sidebarcollapsed && touch_x <= sbr_w) { + if (touch_x >= settings_btn_x && touch_x < (settings_btn_x + settings_btn_w) + && touch_y >= settings_btn_y && touch_y < (settings_btn_y + settings_btn_h)) { + s->active_app = cereal::UiLayoutState::App::SETTINGS; + } + else if (touch_x >= home_btn_x && touch_x < (home_btn_x + home_btn_w) + && touch_y >= home_btn_y && touch_y < (home_btn_y + home_btn_h)) { + if (s->started) { + s->active_app = cereal::UiLayoutState::App::NONE; + s->scene.uilayout_sidebarcollapsed = true; + } else { + s->active_app = cereal::UiLayoutState::App::HOME; + } + } + } +} + +static void update_offroad_layout_state(UIState *s) { + static int timeout = 0; + static bool prev_collapsed = false; + static cereal::UiLayoutState::App prev_app = cereal::UiLayoutState::App::NONE; + if (timeout > 0) { + timeout--; + } + if (prev_collapsed != s->scene.uilayout_sidebarcollapsed || prev_app != s->active_app || timeout == 0) { + capnp::MallocMessageBuilder msg; + auto event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto layout = event.initUiLayoutState(); + layout.setActiveApp(s->active_app); + layout.setSidebarCollapsed(s->scene.uilayout_sidebarcollapsed); + s->pm->send("offroadLayout", msg); + LOGD("setting active app to %d with sidebar %d", (int)s->active_app, s->scene.uilayout_sidebarcollapsed); + prev_collapsed = s->scene.uilayout_sidebarcollapsed; + prev_app = s->active_app; + timeout = 2 * UI_FREQ; + } +} + +int main(int argc, char* argv[]) { + int err; + setpriority(PRIO_PROCESS, 0, -14); + + zsys_handler_set(NULL); + signal(SIGINT, (sighandler_t)set_do_exit); + + UIState uistate = {}; + UIState *s = &uistate; + ui_init(s); + set_awake(s, true); + + enable_event_processing(true); + + pthread_t connect_thread_handle; + err = pthread_create(&connect_thread_handle, NULL, + vision_connect_thread, s); + assert(err == 0); + + pthread_t light_sensor_thread_handle; + err = pthread_create(&light_sensor_thread_handle, NULL, + light_sensor_thread, s); + assert(err == 0); + + TouchState touch = {0}; + touch_init(&touch); + s->touch_fd = touch.fd; + + // light sensor scaling params + const bool LEON = util::read_file("/proc/cmdline").find("letv") != std::string::npos; + + float brightness_b, brightness_m; + int result = read_param(&brightness_b, "BRIGHTNESS_B", true); + result += read_param(&brightness_m, "BRIGHTNESS_M", true); + + if(result != 0){ + brightness_b = LEON ? 10.0 : 5.0; + brightness_m = LEON ? 2.6 : 1.3; + write_param_float(brightness_b, "BRIGHTNESS_B", true); + write_param_float(brightness_m, "BRIGHTNESS_M", true); + } + + float smooth_brightness = brightness_b; + + const int MIN_VOLUME = LEON ? 12 : 9; + const int MAX_VOLUME = LEON ? 15 : 12; + assert(s->sound.init(MIN_VOLUME)); + + int draws = 0; + + while (!do_exit) { + bool should_swap = false; + if (!s->started) { + // Delay a while to avoid 9% cpu usage while car is not started and user is keeping touching on the screen. + // Don't hold the lock while sleeping, so that vision_connect_thread have chances to get the lock. + usleep(30 * 1000); + } + pthread_mutex_lock(&s->lock); + double u1 = millis_since_boot(); + + // light sensor is only exposed on EONs + float clipped_brightness = (s->light_sensor*brightness_m) + brightness_b; + if (clipped_brightness > 512) clipped_brightness = 512; + smooth_brightness = clipped_brightness * 0.01 + smooth_brightness * 0.99; + if (smooth_brightness > 255) smooth_brightness = 255; + ui_set_brightness(s, (int)smooth_brightness); + ui_update_sizes(s); + + // poll for touch events + int touch_x = -1, touch_y = -1; + int touched = touch_poll(&touch, &touch_x, &touch_y, 0); + if (touched == 1) { + set_awake(s, true); + handle_sidebar_touch(s, touch_x, touch_y); + handle_vision_touch(s, touch_x, touch_y); + } + + if (!s->started) { + // always process events offroad + check_messages(s); + + if (s->started) { + s->controls_timeout = 5 * UI_FREQ; + } + } else { + set_awake(s, true); + // Car started, fetch a new rgb image from ipc + if (s->vision_connected){ + ui_update(s); + } + + check_messages(s); + + // Visiond process is just stopped, force a redraw to make screen blank again. + if (!s->started) { + s->scene.uilayout_sidebarcollapsed = false; + ui_draw(s); + glFinish(); + should_swap = true; + } + } + + // manage wakefulness + if (s->awake_timeout > 0) { + s->awake_timeout--; + } else { + set_awake(s, false); + } + + // manage hardware disconnect + if (s->hardware_timeout > 0) { + s->hardware_timeout--; + } else { + s->scene.hwType = cereal::HealthData::HwType::UNKNOWN; + } + + // Don't waste resources on drawing in case screen is off + if (s->awake) { + ui_draw(s); + glFinish(); + should_swap = true; + } + + s->sound.setVolume(fmin(MAX_VOLUME, MIN_VOLUME + s->scene.controls_state.getVEgo() / 5)); // up one notch every 5 m/s + + if (s->controls_timeout > 0) { + s->controls_timeout--; + } else if (s->started && !s->scene.frontview) { + if (!s->controls_seen) { + // car is started, but controlsState hasn't been seen at all + s->scene.alert_text1 = "openpilot Unavailable"; + s->scene.alert_text2 = "Waiting for controls to start"; + s->scene.alert_size = cereal::ControlsState::AlertSize::MID; + } else { + // car is started, but controls is lagging or died + LOGE("Controls unresponsive"); + + if (s->scene.alert_text2 != "Controls Unresponsive") { + s->sound.play(AudibleAlert::CHIME_WARNING_REPEAT); + } + + s->scene.alert_text1 = "TAKE CONTROL IMMEDIATELY"; + s->scene.alert_text2 = "Controls Unresponsive"; + s->scene.alert_size = cereal::ControlsState::AlertSize::FULL; + update_status(s, STATUS_ALERT); + } + ui_draw_vision_alert(s, s->scene.alert_size, s->status, s->scene.alert_text1.c_str(), s->scene.alert_text2.c_str()); + } + + read_param_timeout(&s->is_metric, "IsMetric", &s->is_metric_timeout); + read_param_timeout(&s->longitudinal_control, "LongitudinalControl", &s->longitudinal_control_timeout); + read_param_timeout(&s->limit_set_speed, "LimitSetSpeed", &s->limit_set_speed_timeout); + read_param_timeout(&s->speed_lim_off, "SpeedLimitOffset", &s->limit_set_speed_timeout); + int param_read = read_param_timeout(&s->last_athena_ping, "LastAthenaPingTime", &s->last_athena_ping_timeout); + if (param_read != -1) { // Param was updated this loop + if (param_read != 0) { // Failed to read param + s->scene.athenaStatus = NET_DISCONNECTED; + } else if (nanos_since_boot() - s->last_athena_ping < 70e9) { + s->scene.athenaStatus = NET_CONNECTED; + } else { + s->scene.athenaStatus = NET_ERROR; + } + } + update_offroad_layout_state(s); + + pthread_mutex_unlock(&s->lock); + + // the bg thread needs to be scheduled, so the main thread needs time without the lock + // safe to do this outside the lock? + if (should_swap) { + double u2 = millis_since_boot(); + if (u2-u1 > 66) { + // warn on sub 15fps + LOGW("slow frame(%d) time: %.2f", draws, u2-u1); + } + draws++; + framebuffer_swap(s->fb); + } + } + + set_awake(s, true); + + // wake up bg thread to exit + pthread_mutex_lock(&s->lock); + pthread_mutex_unlock(&s->lock); + + // join light_sensor_thread? + err = pthread_join(connect_thread_handle, NULL); + assert(err == 0); + delete s->sm; + delete s->pm; + return 0; +} diff --git a/selfdrive/ui/linux.cc b/selfdrive/ui/linux.cc deleted file mode 100644 index 5b370cc29f..0000000000 --- a/selfdrive/ui/linux.cc +++ /dev/null @@ -1,107 +0,0 @@ -#include -#include -#include -#include -#include - -#include "ui.hpp" - -#ifndef __APPLE__ -#define GLFW_INCLUDE_ES2 -#else -#define GLFW_INCLUDE_GLCOREARB -#endif - -#define GLFW_INCLUDE_GLEXT -#include - -typedef struct FramebufferState FramebufferState; -typedef struct TouchState TouchState; - -extern "C" { - -FramebufferState* framebuffer_init( - const char* name, int32_t layer, int alpha, - int *out_w, int *out_h) { - glfwInit(); - -#ifndef __APPLE__ - glfwWindowHint(GLFW_CLIENT_API, GLFW_OPENGL_ES_API); - glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 3); - glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 0); -#else - glfwWindowHint(GLFW_OPENGL_FORWARD_COMPAT, GL_TRUE); - glfwWindowHint(GLFW_OPENGL_PROFILE, GLFW_OPENGL_CORE_PROFILE); - glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 3); - glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 2); -#endif - glfwWindowHint(GLFW_RESIZABLE, 0); - GLFWwindow* window; - window = glfwCreateWindow(1920, 1080, "ui", NULL, NULL); - if (!window) { - printf("glfwCreateWindow failed\n"); - } - - glfwMakeContextCurrent(window); - glfwSwapInterval(1); - - // clear screen - glClearColor(0.2f, 0.2f, 0.2f, 1.0f); - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - framebuffer_swap((FramebufferState*)window); - - if (out_w) *out_w = 1920; - if (out_h) *out_h = 1080; - - return (FramebufferState*)window; -} - -void framebuffer_set_power(FramebufferState *s, int mode) { -} - -void framebuffer_swap(FramebufferState *s) { - glfwSwapBuffers((GLFWwindow*)s); - glfwPollEvents(); -} - -bool set_brightness(int brightness) { return true; } - -void touch_init(TouchState *s) { - printf("touch_init\n"); -} - -int touch_poll(TouchState *s, int* out_x, int* out_y, int timeout) { - return -1; -} - -int touch_read(TouchState *s, int* out_x, int* out_y) { - return -1; -} - -} - -#include "sound.hpp" - -bool Sound::init(int volume) { return true; } -bool Sound::play(AudibleAlert alert) { printf("play sound: %d\n", (int)alert); return true; } -void Sound::stop() {} -void Sound::setVolume(int volume) {} -Sound::~Sound() {} - -#include "common/visionimg.h" -#include - -GLuint visionimg_to_gl(const VisionImg *img, EGLImageKHR *pkhr, void **pph) { - unsigned int texture; - glGenTextures(1, &texture); - glBindTexture(GL_TEXTURE_2D, texture); - glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, img->width, img->height, 0, GL_RGB, GL_UNSIGNED_BYTE, *pph); - glGenerateMipmap(GL_TEXTURE_2D); - *pkhr = (EGLImageKHR)1; // not NULL - return texture; -} - -void visionimg_destroy_gl(EGLImageKHR khr, void *ph) { - // empty -} - diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 3f6af4e026..f8e3675516 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -2,10 +2,10 @@ #include #include #include +#include #include "common/util.h" #define NANOVG_GLES3_IMPLEMENTATION - #include "nanovg_gl.h" #include "nanovg_gl_utils.h" @@ -13,6 +13,9 @@ extern "C"{ #include "common/glutil.h" } +#include "paint.hpp" +#include "sidebar.hpp" + // TODO: this is also hardcoded in common/transformations/camera.py const mat3 intrinsic_matrix = (mat3){{ 910., 0., 582., @@ -348,7 +351,7 @@ static void ui_draw_world(UIState *s) { return; } - const int inner_height = viz_w*9/16; + const int inner_height = float(viz_w) * vwp_h / vwp_w; const int ui_viz_rx = scene->ui_viz_rx; const int ui_viz_rw = scene->ui_viz_rw; const int ui_viz_ro = scene->ui_viz_ro; @@ -358,10 +361,13 @@ static void ui_draw_world(UIState *s) { nvgTranslate(s->vg, ui_viz_rx+ui_viz_ro, box_y + (box_h-inner_height)/2.0); nvgScale(s->vg, (float)viz_w / s->fb_w, (float)inner_height / s->fb_h); - nvgTranslate(s->vg, 240.0f, 0.0); - nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + + float w = 1440.0f; // Why 1440? + nvgTranslate(s->vg, (vwp_w - w) / 2.0f, 0.0); + + nvgTranslate(s->vg, -w / 2, -1080.0f / 2); nvgScale(s->vg, 2.0, 2.0); - nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + nvgScale(s->vg, w / s->rgb_width, 1080.0f / s->rgb_height); // Draw lane edges and vision/mpc tracks ui_draw_vision_lanes(s); diff --git a/selfdrive/ui/paint.hpp b/selfdrive/ui/paint.hpp new file mode 100644 index 0000000000..e71a2a43ec --- /dev/null +++ b/selfdrive/ui/paint.hpp @@ -0,0 +1,11 @@ +#pragma once +#include "ui.hpp" + + +void ui_draw_vision_alert(UIState *s, cereal::ControlsState::AlertSize va_size, int va_color, + const char* va_text1, const char* va_text2); +void ui_draw(UIState *s); +void ui_draw_image(NVGcontext *vg, float x, float y, float w, float h, int image, float alpha); +void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGcolor color, float r = 0, int width = 0); +void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint &paint, float r = 0); +void ui_nvg_init(UIState *s); diff --git a/selfdrive/ui/qt/settings.cc b/selfdrive/ui/qt/settings.cc new file mode 100644 index 0000000000..2dd19ca806 --- /dev/null +++ b/selfdrive/ui/qt/settings.cc @@ -0,0 +1,140 @@ +#include +#include +#include +#include + +#include "qt/settings.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/params.h" + +ParamsToggle::ParamsToggle(QString param, QString title, QString description, QString icon, QWidget *parent): QFrame(parent) , param(param) { + QHBoxLayout *hlayout = new QHBoxLayout; + QVBoxLayout *vlayout = new QVBoxLayout; + + hlayout->addSpacing(25); + if (icon.length()){ + QPixmap pix(icon); + QLabel *icon = new QLabel(); + icon->setPixmap(pix.scaledToWidth(100, Qt::SmoothTransformation)); + icon->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); + hlayout->addWidget(icon); + } else{ + hlayout->addSpacing(100); + } + hlayout->addSpacing(25); + + checkbox = new QCheckBox(title); + QLabel *label = new QLabel(description); + label->setWordWrap(true); + + vlayout->addWidget(checkbox); + vlayout->addWidget(label); + hlayout->addLayout(vlayout); + + setLayout(hlayout); + + auto p = read_db_bytes(param.toStdString().c_str()); + if (p.size()){ + checkbox->setChecked(p[0] == '1'); + } + + setStyleSheet(R"( + QCheckBox { font-size: 40px } + QLabel { font-size: 20px } + * { + background-color: #114265; + } + )"); + + QObject::connect(checkbox, SIGNAL(stateChanged(int)), this, SLOT(checkboxClicked(int))); +} + +void ParamsToggle::checkboxClicked(int state){ + char value = state ? '1': '0'; + write_db_value(param.toStdString().c_str(), &value, 1); +} + +SettingsWindow::SettingsWindow(QWidget *parent) : QWidget(parent) { + QWidget *container = new QWidget(this); + + QVBoxLayout *settings_list = new QVBoxLayout(); + settings_list->addWidget(new ParamsToggle("OpenpilotEnabledToggle", + "Enable Openpilot", + "Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off.", + "../assets/offroad/icon_openpilot.png" + )); + settings_list->addWidget(new ParamsToggle("LaneChangeEnabled", + "Enable Lane Change Assist", + "Perform assisted lane changes with openpilot by checking your surroundings for safety, activating the turn signal and gently nudging the steering wheel towards your desired lane. openpilot is not capable of checking if a lane change is safe. You must continuously observe your surroundings to use this feature.", + "../assets/offroad/icon_road.png" + )); + settings_list->addWidget(new ParamsToggle("IsLdwEnabled", + "Enable Lane Departure Warnings", + "Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31mph (50kph).", + "../assets/offroad/icon_warning.png" + )); + settings_list->addWidget(new ParamsToggle("RecordFront", + "Record and Upload Driver Camera", + "Upload data from the driver facing camera and help improve the driver monitoring algorithm.", + "../assets/offroad/icon_network.png" + )); + settings_list->addWidget(new ParamsToggle("IsRHD", + "Enable Right-Hand Drive", + "Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat.", + "../assets/offroad/icon_openpilot_mirrored.png" + )); + settings_list->addWidget(new ParamsToggle("IsMetric", + "Use Metric System", + "Display speed in km/h instead of mp/h.", + "../assets/offroad/icon_metric.png" + )); + settings_list->addWidget(new ParamsToggle("CommunityFeaturesToggle", + "Enable Community Features", + "Use features from the open source community that are not maintained or supported by comma.ai and have not been confirmed to meet the standard safety model. These features include community supported cars and community supported hardware. Be extra cautious when using these features", + "../assets/offroad/icon_shell.png" + )); + + settings_list->setSpacing(25); + + container->setLayout(settings_list); + container->setFixedWidth(1650); + + QScrollArea *scrollArea = new QScrollArea; + scrollArea->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + scrollArea->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + scrollArea->setWidget(container); + + QScrollerProperties sp; + sp.setScrollMetric(QScrollerProperties::DecelerationFactor, 2.0); + + QScroller* qs = QScroller::scroller(scrollArea); + qs->setScrollerProperties(sp); + + QHBoxLayout *main_layout = new QHBoxLayout; + main_layout->addSpacing(50); + main_layout->addWidget(scrollArea); + + QPushButton * button = new QPushButton("Close"); + main_layout->addWidget(button); + main_layout->addSpacing(20); + + setLayout(main_layout); + + QScroller::grabGesture(scrollArea, QScroller::LeftMouseButtonGesture); + QObject::connect(button, SIGNAL(clicked()), this, SIGNAL(closeSettings())); + + setStyleSheet(R"( + QPushButton { font-size: 40px } + )"); + +} diff --git a/selfdrive/ui/qt/settings.hpp b/selfdrive/ui/qt/settings.hpp new file mode 100644 index 0000000000..e65e75bc76 --- /dev/null +++ b/selfdrive/ui/qt/settings.hpp @@ -0,0 +1,28 @@ +#pragma once + +#include +#include +#include +#include + +class ParamsToggle : public QFrame { + Q_OBJECT + +private: + QCheckBox *checkbox; + QString param; +public: + explicit ParamsToggle(QString param, QString title, QString description, QString icon, QWidget *parent = 0); +public slots: + void checkboxClicked(int state); +}; + + + +class SettingsWindow : public QWidget { + Q_OBJECT +public: + explicit SettingsWindow(QWidget *parent = 0); +signals: + void closeSettings(); +}; diff --git a/selfdrive/ui/qt/ui.cc b/selfdrive/ui/qt/ui.cc new file mode 100644 index 0000000000..43396b7522 --- /dev/null +++ b/selfdrive/ui/qt/ui.cc @@ -0,0 +1,15 @@ +#include + +#include "window.hpp" + +int main(int argc, char *argv[]) +{ + QApplication a(argc, argv); + + MainWindow w; + + w.setFixedSize(vwp_w, vwp_h); + w.show(); + + return a.exec(); +} diff --git a/selfdrive/ui/qt/wifi.cc b/selfdrive/ui/qt/wifi.cc new file mode 100644 index 0000000000..1d66c2c862 --- /dev/null +++ b/selfdrive/ui/qt/wifi.cc @@ -0,0 +1,69 @@ +#include +#include + +typedef QMap > Connection; +Q_DECLARE_METATYPE(Connection) + +void wifi_stuff(){ + qDBusRegisterMetaType(); + + QString nm_path = "/org/freedesktop/NetworkManager"; + QString nm_settings_path = "/org/freedesktop/NetworkManager/Settings"; + + QString nm_iface = "org.freedesktop.NetworkManager"; + QString props_iface = "org.freedesktop.DBus.Properties"; + QString nm_settings_iface = "org.freedesktop.NetworkManager.Settings"; + + QString nm_service = "org.freedesktop.NetworkManager"; + QString device_service = "org.freedesktop.NetworkManager.Device"; + + QDBusConnection bus = QDBusConnection::systemBus(); + + // Get devices + QDBusInterface nm(nm_service, nm_path, nm_iface, bus); + QDBusMessage response = nm.call("GetDevices"); + QVariant first = response.arguments().at(0); + + const QDBusArgument &args = first.value(); + args.beginArray(); + while (!args.atEnd()) { + QDBusObjectPath path; + args >> path; + + // Get device type + QDBusInterface device_props(nm_service, path.path(), props_iface, bus); + QDBusMessage response = device_props.call("Get", device_service, "DeviceType"); + QVariant first = response.arguments().at(0); + QDBusVariant dbvFirst = first.value(); + QVariant vFirst = dbvFirst.variant(); + uint device_type = vFirst.value(); + qDebug() << path.path() << device_type; + } + args.endArray(); + + + // Add connection + Connection connection; + connection["connection"]["type"] = "802-11-wireless"; + connection["connection"]["uuid"] = QUuid::createUuid().toString().remove('{').remove('}'); + connection["connection"]["id"] = "Connection 1"; + + connection["802-11-wireless"]["ssid"] = QByteArray(""); + connection["802-11-wireless"]["mode"] = "infrastructure"; + + connection["802-11-wireless-security"]["key-mgmt"] = "wpa-psk"; + connection["802-11-wireless-security"]["auth-alg"] = "open"; + connection["802-11-wireless-security"]["psk"] = ""; + + connection["ipv4"]["method"] = "auto"; + connection["ipv6"]["method"] = "ignore"; + + + QDBusInterface nm_settings(nm_service, nm_settings_path, nm_settings_iface, bus); + QDBusReply result = nm_settings.call("AddConnection", QVariant::fromValue(connection)); + if (!result.isValid()) { + qDebug() << result.error().name() << result.error().message(); + } else { + qDebug() << result.value().path(); + } +} diff --git a/selfdrive/ui/qt/window.cc b/selfdrive/ui/qt/window.cc new file mode 100644 index 0000000000..5b47c27dd7 --- /dev/null +++ b/selfdrive/ui/qt/window.cc @@ -0,0 +1,143 @@ +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "window.hpp" +#include "settings.hpp" + +#include "paint.hpp" +#include "sound.hpp" + +volatile sig_atomic_t do_exit = 0; + +MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { + main_layout = new QStackedLayout; + + GLWindow * glWindow = new GLWindow(this); + main_layout->addWidget(glWindow); + + SettingsWindow * settingsWindow = new SettingsWindow(this); + main_layout->addWidget(settingsWindow); + + + main_layout->setMargin(0); + setLayout(main_layout); + QObject::connect(glWindow, SIGNAL(openSettings()), this, SLOT(openSettings())); + QObject::connect(settingsWindow, SIGNAL(closeSettings()), this, SLOT(closeSettings())); + + setStyleSheet(R"( + * { + color: white; + background-color: #072339; + } + )"); +} + +void MainWindow::openSettings(){ + main_layout->setCurrentIndex(1); +} + +void MainWindow::closeSettings(){ + main_layout->setCurrentIndex(0); +} + + + +GLWindow::GLWindow(QWidget *parent) : QOpenGLWidget(parent) { + timer = new QTimer(this); + QObject::connect(timer, SIGNAL(timeout()), this, SLOT(timerUpdate())); +} + +GLWindow::~GLWindow() { + makeCurrent(); + doneCurrent(); +} + +void GLWindow::initializeGL() { + initializeOpenGLFunctions(); + + ui_state = new UIState(); + ui_init(ui_state); + ui_state->fb_w = vwp_w; + ui_state->fb_h = vwp_h; + + int err = pthread_create(&connect_thread_handle, NULL, + vision_connect_thread, ui_state); + assert(err == 0); + + timer->start(50); +} + +void GLWindow::timerUpdate(){ + pthread_mutex_lock(&ui_state->lock); + + ui_update_sizes(ui_state); + + check_messages(ui_state); + if (ui_state->vision_connected){ + ui_update(ui_state); + } + pthread_mutex_unlock(&ui_state->lock); + + update(); +} + +void GLWindow::resizeGL(int w, int h) { + std::cout << "resize " << w << "x" << h << std::endl; +} + +void GLWindow::paintGL() { + pthread_mutex_lock(&ui_state->lock); + ui_draw(ui_state); + pthread_mutex_unlock(&ui_state->lock); +} + +void GLWindow::mousePressEvent(QMouseEvent *e) { + // Settings button click + if (!ui_state->scene.uilayout_sidebarcollapsed && e->x() <= sbr_w) { + if (e->x() >= settings_btn_x && e->x() < (settings_btn_x + settings_btn_w) + && e->y() >= settings_btn_y && e->y() < (settings_btn_y + settings_btn_h)) { + emit openSettings(); + } + } + + // Vision click + if (ui_state->started && (e->x() >= ui_state->scene.ui_viz_rx - bdr_s)){ + ui_state->scene.uilayout_sidebarcollapsed = !ui_state->scene.uilayout_sidebarcollapsed; + } + +} + + +/* HACKS */ +bool Sound::init(int volume) { return true; } +bool Sound::play(AudibleAlert alert) { printf("play sound: %d\n", (int)alert); return true; } +void Sound::stop() {} +void Sound::setVolume(int volume) {} +Sound::~Sound() {} + +GLuint visionimg_to_gl(const VisionImg *img, EGLImageKHR *pkhr, void **pph) { + unsigned int texture; + glGenTextures(1, &texture); + glBindTexture(GL_TEXTURE_2D, texture); + glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, img->width, img->height, 0, GL_RGB, GL_UNSIGNED_BYTE, *pph); + glGenerateMipmap(GL_TEXTURE_2D); + *pkhr = (EGLImageKHR)1; // not NULL + return texture; +} + +void visionimg_destroy_gl(EGLImageKHR khr, void *ph) { + // empty +} + +FramebufferState* framebuffer_init(const char* name, int32_t layer, int alpha, + int *out_w, int *out_h) { + return (FramebufferState*)1; // not null +} diff --git a/selfdrive/ui/qt/window.hpp b/selfdrive/ui/qt/window.hpp new file mode 100644 index 0000000000..9ab47c377b --- /dev/null +++ b/selfdrive/ui/qt/window.hpp @@ -0,0 +1,55 @@ +#pragma once + +#include +#include +#include +#include +#include +#include + +#include "ui/ui.hpp" + +class MainWindow : public QWidget +{ + Q_OBJECT + +public: + explicit MainWindow(QWidget *parent = 0); + +private: + QStackedLayout *main_layout; + +public slots: + void openSettings(); + void closeSettings(); + +}; + + +class GLWindow : public QOpenGLWidget, protected QOpenGLFunctions +{ + Q_OBJECT + +public: + using QOpenGLWidget::QOpenGLWidget; + explicit GLWindow(QWidget *parent = 0); + ~GLWindow(); + +protected: + void mousePressEvent(QMouseEvent *e) override; + void initializeGL() override; + void resizeGL(int w, int h) override; + void paintGL() override; + + +private: + QTimer * timer; + UIState * ui_state; + pthread_t connect_thread_handle; + +public slots: + void timerUpdate(); + +signals: + void openSettings(); +}; diff --git a/selfdrive/ui/sidebar.cc b/selfdrive/ui/sidebar.cc index e8eb894cc9..cc187f449e 100644 --- a/selfdrive/ui/sidebar.cc +++ b/selfdrive/ui/sidebar.cc @@ -2,7 +2,9 @@ #include #include #include -#include "ui.hpp" + +#include "paint.hpp" +#include "sidebar.hpp" static void ui_draw_sidebar_background(UIState *s) { int sbr_x = !s->scene.uilayout_sidebarcollapsed ? 0 : -(sbr_w) + bdr_s * 2; diff --git a/selfdrive/ui/sidebar.hpp b/selfdrive/ui/sidebar.hpp new file mode 100644 index 0000000000..f273e16f8b --- /dev/null +++ b/selfdrive/ui/sidebar.hpp @@ -0,0 +1,4 @@ +#pragma once +#include "ui.hpp" + +void ui_draw_sidebar(UIState *s); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 5eb00a2edb..5269beaab2 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -4,168 +4,25 @@ #include #include #include -#include -#include -#include #include + #include "common/util.h" -#include "common/timing.h" #include "common/swaglog.h" -#include "common/touch.h" #include "common/visionimg.h" -#include "common/params.h" #include "common/utilpp.h" #include "ui.hpp" +#include "paint.hpp" -static void ui_set_brightness(UIState *s, int brightness) { - static int last_brightness = -1; - if (last_brightness != brightness && (s->awake || brightness == 0)) { - if (set_brightness(brightness)) { - last_brightness = brightness; - } - } -} +extern volatile sig_atomic_t do_exit; -int event_processing_enabled = -1; -static void enable_event_processing(bool yes) { - if (event_processing_enabled != 1 && yes) { - system("service call window 18 i32 1"); // enable event processing - event_processing_enabled = 1; - } else if (event_processing_enabled != 0 && !yes) { - system("service call window 18 i32 0"); // disable event processing - event_processing_enabled = 0; - } -} -static void set_awake(UIState *s, bool awake) { -#ifdef QCOM - if (awake) { - // 30 second timeout - s->awake_timeout = 30*UI_FREQ; - } - if (s->awake != awake) { - s->awake = awake; - - // TODO: replace command_awake and command_sleep with direct calls to android - if (awake) { - LOGW("awake normal"); - framebuffer_set_power(s->fb, HWC_POWER_MODE_NORMAL); - enable_event_processing(true); - } else { - LOGW("awake off"); - ui_set_brightness(s, 0); - framebuffer_set_power(s->fb, HWC_POWER_MODE_OFF); - enable_event_processing(false); - } - } -#else - // computer UI doesn't sleep - s->awake = true; -#endif -} - -static void update_offroad_layout_state(UIState *s) { -#ifdef QCOM - static int timeout = 0; - static bool prev_collapsed = false; - static cereal::UiLayoutState::App prev_app = cereal::UiLayoutState::App::NONE; - if (timeout > 0) { - timeout--; - } - if (prev_collapsed != s->scene.uilayout_sidebarcollapsed || prev_app != s->active_app || timeout == 0) { - capnp::MallocMessageBuilder msg; - auto event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto layout = event.initUiLayoutState(); - layout.setActiveApp(s->active_app); - layout.setSidebarCollapsed(s->scene.uilayout_sidebarcollapsed); - s->pm->send("offroadLayout", msg); - LOGD("setting active app to %d with sidebar %d", (int)s->active_app, s->scene.uilayout_sidebarcollapsed); - prev_collapsed = s->scene.uilayout_sidebarcollapsed; - prev_app = s->active_app; - timeout = 2 * UI_FREQ; - } -#endif -} - -static void handle_sidebar_touch(UIState *s, int touch_x, int touch_y) { - if (!s->scene.uilayout_sidebarcollapsed && touch_x <= sbr_w) { - if (touch_x >= settings_btn_x && touch_x < (settings_btn_x + settings_btn_w) - && touch_y >= settings_btn_y && touch_y < (settings_btn_y + settings_btn_h)) { - s->active_app = cereal::UiLayoutState::App::SETTINGS; - } - else if (touch_x >= home_btn_x && touch_x < (home_btn_x + home_btn_w) - && touch_y >= home_btn_y && touch_y < (home_btn_y + home_btn_h)) { - if (s->started) { - s->active_app = cereal::UiLayoutState::App::NONE; - s->scene.uilayout_sidebarcollapsed = true; - } else { - s->active_app = cereal::UiLayoutState::App::HOME; - } - } - } -} - -static void handle_vision_touch(UIState *s, int touch_x, int touch_y) { - if (s->started && (touch_x >= s->scene.ui_viz_rx - bdr_s) - && (s->active_app != cereal::UiLayoutState::App::SETTINGS)) { - if (!s->scene.frontview) { - s->scene.uilayout_sidebarcollapsed = !s->scene.uilayout_sidebarcollapsed; - } else { - write_db_value("IsDriverViewEnabled", "0", 1); - } - } -} - -volatile sig_atomic_t do_exit = 0; -static void set_do_exit(int sig) { - do_exit = 1; -} - -template -static int read_param(T* param, const char *param_name, bool persistent_param = false){ - T param_orig = *param; - char *value; - size_t sz; - - int result = read_db_value(param_name, &value, &sz, persistent_param); - if (result == 0){ - std::string s = std::string(value, sz); // value is not null terminated - free(value); - - // Parse result - std::istringstream iss(s); - iss >> *param; - - // Restore original value if parsing failed - if (iss.fail()) { - *param = param_orig; - result = -1; - } - } - return result; -} - -template -static int read_param_timeout(T* param, const char* param_name, int* timeout, bool persistent_param = false) { - int result = -1; - if (*timeout > 0){ - (*timeout)--; - } else { - *timeout = 2 * UI_FREQ; // 0.5Hz - result = read_param(param, param_name, persistent_param); - } - return result; -} - -static int write_param_float(float param, const char* param_name, bool persistent_param = false) { +int write_param_float(float param, const char* param_name, bool persistent_param) { char s[16]; int size = snprintf(s, sizeof(s), "%f", param); return write_db_value(param_name, s, MIN(size, sizeof(s)), persistent_param); } -static void ui_init(UIState *s) { - +void ui_init(UIState *s) { pthread_mutex_init(&s->lock, NULL); s->sm = new SubMaster({"model", "controlsState", "uiLayoutState", "liveCalibration", "radarState", "thermal", "health", "ubloxGnss", "driverState", "dMonitoringState" @@ -180,12 +37,9 @@ static void ui_init(UIState *s) { s->started = false; s->vision_seen = false; - // init display s->fb = framebuffer_init("ui", 0, true, &s->fb_w, &s->fb_h); assert(s->fb); - set_awake(s, true); - ui_nvg_init(s); } @@ -227,7 +81,7 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, s->limit_set_speed_timeout = UI_FREQ; } -static void update_status(UIState *s, int status) { +void update_status(UIState *s, int status) { if (s->status != status) { s->status = status; } @@ -373,13 +227,21 @@ void handle_message(UIState *s, SubMaster &sm) { } } -static void check_messages(UIState *s) { +void check_messages(UIState *s) { if (s->sm->update(0) > 0){ handle_message(s, *(s->sm)); } } -static void ui_update(UIState *s) { +void ui_update_sizes(UIState *s){ + // resize vision for collapsing sidebar + const bool hasSidebar = !s->scene.uilayout_sidebarcollapsed; + s->scene.ui_viz_rx = hasSidebar ? box_x : (box_x - sbr_w + (bdr_s * 2)); + s->scene.ui_viz_rw = hasSidebar ? box_w : (box_w + sbr_w - (bdr_s * 2)); + s->scene.ui_viz_ro = hasSidebar ? -(sbr_w - 6 * bdr_s) : 0; +} + +void ui_update(UIState *s) { int err; if (s->vision_connect_firstrun) { @@ -573,7 +435,7 @@ static int vision_subscribe(int fd, VisionPacket *rp, VisionStreamType type) { return 1; } -static void* vision_connect_thread(void *args) { +void* vision_connect_thread(void *args) { set_thread_name("vision_connect"); UIState *s = (UIState*)args; @@ -610,261 +472,3 @@ static void* vision_connect_thread(void *args) { } return NULL; } - -#ifdef QCOM - -#include -#include -#include - -static void* light_sensor_thread(void *args) { - int err; - set_thread_name("light_sensor"); - - UIState *s = (UIState*)args; - s->light_sensor = 0.0; - - struct sensors_poll_device_t* device; - struct sensors_module_t* module; - - hw_get_module(SENSORS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); - sensors_open(&module->common, &device); - - // need to do this - struct sensor_t const* list; - module->get_sensors_list(module, &list); - - int SENSOR_LIGHT = 7; - - err = device->activate(device, SENSOR_LIGHT, 0); - if (err != 0) goto fail; - err = device->activate(device, SENSOR_LIGHT, 1); - if (err != 0) goto fail; - - device->setDelay(device, SENSOR_LIGHT, ms2ns(100)); - - while (!do_exit) { - static const size_t numEvents = 1; - sensors_event_t buffer[numEvents]; - - int n = device->poll(device, buffer, numEvents); - if (n < 0) { - LOG_100("light_sensor_poll failed: %d", n); - } - if (n > 0) { - s->light_sensor = buffer[0].light; - } - } - sensors_close(device); - return NULL; - -fail: - LOGE("LIGHT SENSOR IS MISSING"); - s->light_sensor = 255; - return NULL; -} - -#endif - -int main(int argc, char* argv[]) { - int err; - setpriority(PRIO_PROCESS, 0, -14); - - zsys_handler_set(NULL); - signal(SIGINT, (sighandler_t)set_do_exit); - - UIState uistate = {}; - UIState *s = &uistate; - ui_init(s); - - enable_event_processing(true); - - pthread_t connect_thread_handle; - err = pthread_create(&connect_thread_handle, NULL, - vision_connect_thread, s); - assert(err == 0); - -#ifdef QCOM - pthread_t light_sensor_thread_handle; - err = pthread_create(&light_sensor_thread_handle, NULL, - light_sensor_thread, s); - assert(err == 0); -#endif - - TouchState touch = {0}; - touch_init(&touch); - s->touch_fd = touch.fd; - - // light sensor scaling params - const bool LEON = util::read_file("/proc/cmdline").find("letv") != std::string::npos; - - float brightness_b, brightness_m; - int result = read_param(&brightness_b, "BRIGHTNESS_B", true); - result += read_param(&brightness_m, "BRIGHTNESS_M", true); - - if(result != 0){ - brightness_b = LEON ? 10.0 : 5.0; - brightness_m = LEON ? 2.6 : 1.3; - write_param_float(brightness_b, "BRIGHTNESS_B", true); - write_param_float(brightness_m, "BRIGHTNESS_M", true); - } - - float smooth_brightness = brightness_b; - - const int MIN_VOLUME = LEON ? 12 : 9; - const int MAX_VOLUME = LEON ? 15 : 12; - assert(s->sound.init(MIN_VOLUME)); - - int draws = 0; - - while (!do_exit) { - bool should_swap = false; - if (!s->started) { - // Delay a while to avoid 9% cpu usage while car is not started and user is keeping touching on the screen. - // Don't hold the lock while sleeping, so that vision_connect_thread have chances to get the lock. - usleep(30 * 1000); - } - pthread_mutex_lock(&s->lock); - double u1 = millis_since_boot(); - - // light sensor is only exposed on EONs - float clipped_brightness = (s->light_sensor*brightness_m) + brightness_b; - if (clipped_brightness > 512) clipped_brightness = 512; - smooth_brightness = clipped_brightness * 0.01 + smooth_brightness * 0.99; - if (smooth_brightness > 255) smooth_brightness = 255; - ui_set_brightness(s, (int)smooth_brightness); - - // resize vision for collapsing sidebar - const bool hasSidebar = !s->scene.uilayout_sidebarcollapsed; - s->scene.ui_viz_rx = hasSidebar ? box_x : (box_x - sbr_w + (bdr_s * 2)); - s->scene.ui_viz_rw = hasSidebar ? box_w : (box_w + sbr_w - (bdr_s * 2)); - s->scene.ui_viz_ro = hasSidebar ? -(sbr_w - 6 * bdr_s) : 0; - - // poll for touch events - int touch_x = -1, touch_y = -1; - int touched = touch_poll(&touch, &touch_x, &touch_y, 0); - if (touched == 1) { - set_awake(s, true); - handle_sidebar_touch(s, touch_x, touch_y); - handle_vision_touch(s, touch_x, touch_y); - } - - if (!s->started) { - // always process events offroad - check_messages(s); - - if (s->started) { - s->controls_timeout = 5 * UI_FREQ; - } - } else { - set_awake(s, true); - // Car started, fetch a new rgb image from ipc - if (s->vision_connected){ - ui_update(s); - } - - check_messages(s); - - // Visiond process is just stopped, force a redraw to make screen blank again. - if (!s->started) { - s->scene.uilayout_sidebarcollapsed = false; - ui_draw(s); - glFinish(); - should_swap = true; - } - } - - // manage wakefulness - if (s->awake_timeout > 0) { - s->awake_timeout--; - } else { - set_awake(s, false); - } - - // manage hardware disconnect - if (s->hardware_timeout > 0) { - s->hardware_timeout--; - } else { - s->scene.hwType = cereal::HealthData::HwType::UNKNOWN; - } - - // Don't waste resources on drawing in case screen is off - if (s->awake) { - ui_draw(s); - glFinish(); - should_swap = true; - } - - s->sound.setVolume(fmin(MAX_VOLUME, MIN_VOLUME + s->scene.controls_state.getVEgo() / 5)); // up one notch every 5 m/s - - if (s->controls_timeout > 0) { - s->controls_timeout--; - } else if (s->started && !s->scene.frontview) { - if (!s->controls_seen) { - // car is started, but controlsState hasn't been seen at all - s->scene.alert_text1 = "openpilot Unavailable"; - s->scene.alert_text2 = "Waiting for controls to start"; - s->scene.alert_size = cereal::ControlsState::AlertSize::MID; - } else { - // car is started, but controls is lagging or died - LOGE("Controls unresponsive"); - - if (s->scene.alert_text2 != "Controls Unresponsive") { - s->sound.play(AudibleAlert::CHIME_WARNING_REPEAT); - } - - s->scene.alert_text1 = "TAKE CONTROL IMMEDIATELY"; - s->scene.alert_text2 = "Controls Unresponsive"; - s->scene.alert_size = cereal::ControlsState::AlertSize::FULL; - update_status(s, STATUS_ALERT); - } - ui_draw_vision_alert(s, s->scene.alert_size, s->status, s->scene.alert_text1.c_str(), s->scene.alert_text2.c_str()); - } - - read_param_timeout(&s->is_metric, "IsMetric", &s->is_metric_timeout); - read_param_timeout(&s->longitudinal_control, "LongitudinalControl", &s->longitudinal_control_timeout); - read_param_timeout(&s->limit_set_speed, "LimitSetSpeed", &s->limit_set_speed_timeout); - read_param_timeout(&s->speed_lim_off, "SpeedLimitOffset", &s->limit_set_speed_timeout); - int param_read = read_param_timeout(&s->last_athena_ping, "LastAthenaPingTime", &s->last_athena_ping_timeout); - if (param_read != -1) { // Param was updated this loop - if (param_read != 0) { // Failed to read param - s->scene.athenaStatus = NET_DISCONNECTED; - } else if (nanos_since_boot() - s->last_athena_ping < 70e9) { - s->scene.athenaStatus = NET_CONNECTED; - } else { - s->scene.athenaStatus = NET_ERROR; - } - } - update_offroad_layout_state(s); - - pthread_mutex_unlock(&s->lock); - - // the bg thread needs to be scheduled, so the main thread needs time without the lock - // safe to do this outside the lock? - if (should_swap) { - double u2 = millis_since_boot(); - if (u2-u1 > 66) { - // warn on sub 15fps - LOGW("slow frame(%d) time: %.2f", draws, u2-u1); - } - draws++; - framebuffer_swap(s->fb); - } - } - - set_awake(s, true); - - // wake up bg thread to exit - pthread_mutex_lock(&s->lock); - pthread_mutex_unlock(&s->lock); - -#ifdef QCOM - // join light_sensor_thread? -#endif - - err = pthread_join(connect_thread_handle, NULL); - assert(err == 0); - delete s->sm; - delete s->pm; - return 0; -} diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index 2d6d9ddc06..7db7f6f0a8 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -12,7 +12,11 @@ #define nvgCreate nvgCreateGLES3 #endif #include + +#include +#include #include + #include "nanovg.h" #include "common/mat.h" @@ -20,6 +24,7 @@ #include "common/visionimg.h" #include "common/framebuffer.h" #include "common/modeldata.h" +#include "common/params.h" #include "sound.hpp" #define STATUS_STOPPED 0 @@ -48,12 +53,19 @@ //#define SHOW_SPEEDLIMIT 1 //#define DEBUG_TURN +// TODO: Detect dynamically +#ifdef QCOM2 +const int vwp_w = 2160; +#else const int vwp_w = 1920; +#endif + const int vwp_h = 1080; const int nav_w = 640; const int nav_ww= 760; const int sbr_w = 300; const int bdr_s = 30; + const int box_x = sbr_w+bdr_s; const int box_y = bdr_s; const int box_w = vwp_w-sbr_w-(bdr_s*2); @@ -243,12 +255,49 @@ typedef struct UIState { Sound sound; } UIState; -// API -void ui_draw_vision_alert(UIState *s, cereal::ControlsState::AlertSize va_size, int va_color, - const char* va_text1, const char* va_text2); -void ui_draw(UIState *s); -void ui_draw_sidebar(UIState *s); -void ui_draw_image(NVGcontext *vg, float x, float y, float w, float h, int image, float alpha); -void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGcolor color, float r = 0, int width = 0); -void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint &paint, float r = 0); -void ui_nvg_init(UIState *s); + +void ui_init(UIState *s); +void ui_update(UIState *s); +void ui_update_sizes(UIState *s); + +void* vision_connect_thread(void *args); +void check_messages(UIState *s); +void update_status(UIState *s, int status); + + +int write_param_float(float param, const char* param_name, bool persistent_param = false); +template +int read_param(T* param, const char *param_name, bool persistent_param = false){ + T param_orig = *param; + char *value; + size_t sz; + + int result = read_db_value(param_name, &value, &sz, persistent_param); + if (result == 0){ + std::string s = std::string(value, sz); // value is not null terminated + free(value); + + // Parse result + std::istringstream iss(s); + iss >> *param; + + // Restore original value if parsing failed + if (iss.fail()) { + *param = param_orig; + result = -1; + } + } + return result; +} + +template +int read_param_timeout(T* param, const char* param_name, int* timeout, bool persistent_param = false) { + int result = -1; + if (*timeout > 0){ + (*timeout)--; + } else { + *timeout = 2 * UI_FREQ; // 0.5Hz + result = read_param(param, param_name, persistent_param); + } + return result; +} diff --git a/tools/mac_setup.sh b/tools/mac_setup.sh index a795624598..4993004a87 100755 --- a/tools/mac_setup.sh +++ b/tools/mac_setup.sh @@ -20,6 +20,7 @@ brew install capnp \ libtool \ llvm \ pyenv \ + qt5 \ zeromq # Detect shell and pick correct RC file. diff --git a/tools/ubuntu_setup.sh b/tools/ubuntu_setup.sh index 8de9152175..6b36369771 100755 --- a/tools/ubuntu_setup.sh +++ b/tools/ubuntu_setup.sh @@ -41,6 +41,7 @@ sudo apt-get update && sudo apt-get install -y \ opencl-headers \ python-dev \ python-pip \ + qt5-default \ screen \ sudo \ vim \ From b29d9da875271c719ef6edd6d33a51a11c66d227 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 20 Aug 2020 17:18:03 +0200 Subject: [PATCH 645/656] Revert "more init time in cpu test" This reverts commit 03ec6af300d1d051436514b194e430fb54d16c6c. --- selfdrive/test/test_cpu_usage.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_cpu_usage.py b/selfdrive/test/test_cpu_usage.py index 2b76162632..16f205e824 100755 --- a/selfdrive/test/test_cpu_usage.py +++ b/selfdrive/test/test_cpu_usage.py @@ -79,7 +79,7 @@ def test_cpu_usage(): time.sleep(2) # take first sample - time.sleep(30) + time.sleep(5) first_proc = messaging.recv_sock(proc_sock, wait=True) if first_proc is None: raise Exception("\n\nTEST FAILED: progLog recv timed out\n\n") From 93ae459d967a9c7bd07e9345beec6aad71510142 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 20 Aug 2020 17:23:58 +0200 Subject: [PATCH 646/656] Don't build by default --- SConstruct | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/SConstruct b/SConstruct index 948708cb81..c1a9658a5e 100644 --- a/SConstruct +++ b/SConstruct @@ -303,7 +303,6 @@ SConscript(['selfdrive/controls/lib/longitudinal_mpc_model/SConscript']) SConscript(['selfdrive/boardd/SConscript']) SConscript(['selfdrive/proclogd/SConscript']) -SConscript(['selfdrive/ui/SConscript']) SConscript(['selfdrive/loggerd/SConscript']) SConscript(['selfdrive/locationd/SConscript']) @@ -316,3 +315,6 @@ if arch == "aarch64": SConscript(['selfdrive/clocksd/SConscript']) else: SConscript(['tools/lib/index_log/SConscript']) + +if arch != "larch64": + SConscript(['selfdrive/ui/SConscript']) From 53f920bcca43fcf5470e675a18ea04e51edb07a2 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 20 Aug 2020 17:29:29 +0200 Subject: [PATCH 647/656] Fix qt env in SConstruct --- SConstruct | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/SConstruct b/SConstruct index c1a9658a5e..e3765a15c1 100644 --- a/SConstruct +++ b/SConstruct @@ -192,7 +192,7 @@ if arch in ["x86_64", "Darwin", "larch64"]: QT_BASE + "include/QtDBus", ] qt_env["RPATH"] += [QT_BASE + "lib"] - if arch == "Darwin": + elif arch == "Darwin": qt_env['QTDIR'] = "/usr/local/opt/qt" QT_BASE = "/usr/local/opt/qt/" qt_dirs = [ From e03044530cabc8bf8947b42fb394ac02ea69557d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 20 Aug 2020 17:36:02 +0200 Subject: [PATCH 648/656] boardd: return early from usb functions if not connected --- selfdrive/boardd/panda.cc | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 52cf1e0b71..7604bd7371 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -62,7 +62,7 @@ Panda::Panda(){ is_pigeon = (hw_type == cereal::HealthData::HwType::GREY_PANDA) || (hw_type == cereal::HealthData::HwType::BLACK_PANDA) || - (hw_type == cereal::HealthData::HwType::UNO) || + (hw_type == cereal::HealthData::HwType::UNO) || (hw_type == cereal::HealthData::HwType::DOS); has_rtc = (hw_type == cereal::HealthData::HwType::UNO) || (hw_type == cereal::HealthData::HwType::DOS); @@ -105,6 +105,10 @@ int Panda::usb_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigne int err; const uint8_t bmRequestType = LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; + if (!connected){ + return LIBUSB_ERROR_NO_DEVICE; + } + pthread_mutex_lock(&usb_lock); do { err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, NULL, 0, timeout); @@ -134,6 +138,10 @@ int Panda::usb_bulk_write(unsigned char endpoint, unsigned char* data, int lengt int err; int transferred = 0; + if (!connected){ + return 0; + } + pthread_mutex_lock(&usb_lock); do { // Try sending can messages. If the receive buffer on the panda is full it will NAK @@ -156,6 +164,10 @@ int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length int err; int transferred = 0; + if (!connected){ + return 0; + } + pthread_mutex_lock(&usb_lock); do { From 85ba6e0e2f01794a2ddf3534c3fd5a912b574d4e Mon Sep 17 00:00:00 2001 From: Robert Hanna Date: Thu, 20 Aug 2020 12:55:35 -0500 Subject: [PATCH 649/656] Add Lexus RX esp FW (#2050) Add new Ecu.esp FW version to LEXUS_RX_TSS2 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 73b8fb742e..60baf19d05 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1156,6 +1156,7 @@ FW_VERSIONS = { ], (Ecu.esp, 0x7b0, None): [ b'\x01F15260E031\x00\x00\x00\x00\x00\x00', + b'\x01F15260E041\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B48271\x00\x00\x00\x00\x00\x00', From 2410c7e26bbf60dda83792d273f049586c1aa001 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 20 Aug 2020 21:33:32 +0200 Subject: [PATCH 650/656] ui: force GLES context --- selfdrive/ui/qt/ui.cc | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/ui.cc b/selfdrive/ui/qt/ui.cc index 43396b7522..40ade50df0 100644 --- a/selfdrive/ui/qt/ui.cc +++ b/selfdrive/ui/qt/ui.cc @@ -4,10 +4,13 @@ int main(int argc, char *argv[]) { + QSurfaceFormat fmt; + fmt.setRenderableType(QSurfaceFormat::OpenGLES); + QSurfaceFormat::setDefaultFormat(fmt); + QApplication a(argc, argv); MainWindow w; - w.setFixedSize(vwp_w, vwp_h); w.show(); From d7f3690e85b2712cadaa8da2a1d153d5d915393f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 20 Aug 2020 21:37:28 +0200 Subject: [PATCH 651/656] ui: larger font size --- selfdrive/ui/qt/settings.cc | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/selfdrive/ui/qt/settings.cc b/selfdrive/ui/qt/settings.cc index 2dd19ca806..3da1934bc7 100644 --- a/selfdrive/ui/qt/settings.cc +++ b/selfdrive/ui/qt/settings.cc @@ -49,8 +49,8 @@ ParamsToggle::ParamsToggle(QString param, QString title, QString description, QS } setStyleSheet(R"( - QCheckBox { font-size: 40px } - QLabel { font-size: 20px } + QCheckBox { font-size: 70px } + QLabel { font-size: 40px } * { background-color: #114265; } @@ -135,6 +135,9 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QWidget(parent) { setStyleSheet(R"( QPushButton { font-size: 40px } + * { + color: white; + background-color: #072339; + } )"); - } From 1f4e16be3c7bd93ea073cd373583c0a28e9ca98e Mon Sep 17 00:00:00 2001 From: BrettLynch Date: Sat, 22 Aug 2020 04:10:27 +1000 Subject: [PATCH 652/656] Added fingerprint for my 2020 Corolla Hybrid Sx sedan (#2052) Co-authored-by: BrettLynch --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 60baf19d05..afe6bfd510 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -606,6 +606,7 @@ FW_VERSIONS = { b'F152612840\x00\x00\x00\x00\x00\x00', b'F152612A10\x00\x00\x00\x00\x00\x00', b'F152642540\x00\x00\x00\x00\x00\x00', + b'F152612A00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301100\x00\x00\x00\x00', From 732df68d8406d1924b984324ad10af6c13423fec Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 21 Aug 2020 14:55:12 -0700 Subject: [PATCH 653/656] small dmonitoringd cleanup --- selfdrive/monitoring/dmonitoringd.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index 66a1f2d879..6b0d184bfe 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -20,10 +20,10 @@ def dmonitoringd_thread(sm=None, pm=None): if sm is None: sm = messaging.SubMaster(['driverState', 'liveCalibration', 'carState', 'model']) - params = Params() + is_rhd = Params().get("IsRHD") + offroad = Params().get("IsOffroad") == b"1" driver_status = DriverStatus() - is_rhd = params.get("IsRHD") driver_status.is_rhd_region = is_rhd == b"1" driver_status.is_rhd_region_checked = is_rhd is not None @@ -39,7 +39,6 @@ def dmonitoringd_thread(sm=None, pm=None): v_cruise_last = 0 driver_engaged = False - offroad = params.get("IsOffroad") == b"1" # 10Hz <- dmonitoringmodeld while True: @@ -56,7 +55,6 @@ def dmonitoringd_thread(sm=None, pm=None): driver_status.update(Events(), True, sm['carState'].cruiseState.enabled, sm['carState'].standstill) v_cruise_last = v_cruise - # Get model meta if sm.updated['model']: driver_status.set_policy(sm['model']) From 97bb55703e0034099c3c05a48785616f879a1f90 Mon Sep 17 00:00:00 2001 From: cydia2020 <12470297+cydia2020@users.noreply.github.com> Date: Sat, 22 Aug 2020 09:02:30 +1000 Subject: [PATCH 654/656] Prius 2018 Engine FW (#2054) --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index afe6bfd510..e112b8409c 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -750,6 +750,7 @@ FW_VERSIONS = { b'\x02896634784000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347A5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347A8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634765100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x03896634759100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', From 1bfeacdeafc41cc74f46695e32fe7c0722ff11ba Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Fri, 21 Aug 2020 18:17:34 -0500 Subject: [PATCH 655/656] Add 2020 RAV4 LE Hybrid engine f/w (#2058) C0mpl3t3N00b#0074 DongleID bdad50b8a1f9fa8e... https://discord.com/channels/469524606043160576/524592892627517450/746500256178372678 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index e112b8409c..f6d0c184f2 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -949,6 +949,7 @@ FW_VERSIONS = { b'\x018966342X6000\x00\x00\x00\x00', b'\x018966342W8000\x00\x00\x00\x00', b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A14001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [